diff --git a/.github/workflows/test_sitl_periph.yml b/.github/workflows/test_sitl_periph.yml index e538b7aa58700f..06580252dd8029 100644 --- a/.github/workflows/test_sitl_periph.yml +++ b/.github/workflows/test_sitl_periph.yml @@ -185,6 +185,7 @@ jobs: - name: run dronecan dsdlc generator test run: | PATH="/github/home/.local/bin:$PATH" + python -m pip install --upgrade dronecan python modules/DroneCAN/dronecan_dsdlc/dronecan_dsdlc.py -O dsdlc_generated modules/DroneCAN/DSDL/uavcan modules/DroneCAN/DSDL/dronecan modules/DroneCAN/DSDL/com --run-test - name: build sitl_periph_universal diff --git a/AntennaTracker/Log.cpp b/AntennaTracker/Log.cpp index 5a70a09eb44305..48048dc1a17cdc 100644 --- a/AntennaTracker/Log.cpp +++ b/AntennaTracker/Log.cpp @@ -87,15 +87,15 @@ const struct LogStructure Tracker::log_structure[] = { "VPOS", "QLLefff", "TimeUS,Lat,Lng,Alt,VelX,VelY,VelZ", "sddmnnn", "FGGB000", true } }; -void Tracker::Log_Write_Vehicle_Startup_Messages() +uint8_t Tracker::get_num_log_structures() const { - logger.Write_Mode((uint8_t)mode->number(), ModeReason::INITIALISED); - gps.Write_AP_Logger_Log_Startup_messages(); + return ARRAY_SIZE(log_structure); } -void Tracker::log_init(void) +void Tracker::Log_Write_Vehicle_Startup_Messages() { - logger.Init(log_structure, ARRAY_SIZE(log_structure)); + logger.Write_Mode((uint8_t)mode->number(), ModeReason::INITIALISED); + gps.Write_AP_Logger_Log_Startup_messages(); } #endif // HAL_LOGGING_ENABLED diff --git a/AntennaTracker/Parameters.cpp b/AntennaTracker/Parameters.cpp index c21d5dbf4f5d7e..4eb3db11691f5c 100644 --- a/AntennaTracker/Parameters.cpp +++ b/AntennaTracker/Parameters.cpp @@ -566,12 +566,6 @@ const AP_Param::Info Tracker::var_info[] = { // @Path: ../libraries/AP_Vehicle/AP_Vehicle.cpp PARAM_VEHICLE_INFO, -#if HAL_LOGGING_ENABLED - // @Group: LOG - // @Path: ../libraries/AP_Logger/AP_Logger.cpp - GOBJECT(logger, "LOG", AP_Logger), -#endif - #if HAL_NAVEKF2_AVAILABLE // @Group: EK2_ // @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp @@ -590,23 +584,7 @@ const AP_Param::Info Tracker::var_info[] = { void Tracker::load_parameters(void) { - if (!g.format_version.load() || - g.format_version != Parameters::k_format_version) { - - // erase all parameters - hal.console->printf("Firmware change: erasing EEPROM...\n"); - StorageManager::erase(); - AP_Param::erase_all(); - - // save the current format version - g.format_version.set_and_save(Parameters::k_format_version); - hal.console->printf("done.\n"); - } - g.format_version.set_default(Parameters::k_format_version); - - uint32_t before = AP_HAL::micros(); - // Load all auto-loaded EEPROM variables - AP_Param::load_all(); + AP_Vehicle::load_parameters(g.format_version, Parameters::k_format_version); #if AP_STATS_ENABLED // PARAMETER_CONVERSION - Added: Jan-2024 @@ -618,7 +596,10 @@ void Tracker::load_parameters(void) AP_Param::convert_class(g.k_param_scripting_old, &scripting, scripting.var_info, 0, 0, true); #endif - hal.console->printf("load_all took %luus\n", (unsigned long)(AP_HAL::micros() - before)); + // PARAMETER_CONVERSION - Added: Feb-2024 for Tracker-4.6 +#if HAL_LOGGING_ENABLED + AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, 0, true); +#endif #if HAL_HAVE_SAFETY_SWITCH // configure safety switch to allow stopping the motors while armed diff --git a/AntennaTracker/Tracker.cpp b/AntennaTracker/Tracker.cpp index cd4a4eb5777e18..5fd202b1bdf4a6 100644 --- a/AntennaTracker/Tracker.cpp +++ b/AntennaTracker/Tracker.cpp @@ -164,13 +164,6 @@ void Tracker::stats_update(void) const AP_HAL::HAL& hal = AP_HAL::get_HAL(); -Tracker::Tracker(void) -#if HAL_LOGGING_ENABLED - : logger(g.log_bitmask) -#endif -{ -} - Tracker tracker; AP_Vehicle& vehicle = tracker; diff --git a/AntennaTracker/Tracker.h b/AntennaTracker/Tracker.h index 22c7687ef73ea9..8c745fcf41952a 100644 --- a/AntennaTracker/Tracker.h +++ b/AntennaTracker/Tracker.h @@ -64,8 +64,6 @@ class Tracker : public AP_Vehicle { friend class ModeGuided; friend class Mode; - Tracker(void); - void arm_servos(); void disarm_servos(); @@ -74,10 +72,6 @@ class Tracker : public AP_Vehicle { uint32_t start_time_ms = 0; -#if HAL_LOGGING_ENABLED - AP_Logger logger; -#endif - /** antenna control channels */ @@ -160,12 +154,20 @@ class Tracker : public AP_Vehicle { // GCS_Mavlink.cpp void send_nav_controller_output(mavlink_channel_t chan); +#if HAL_LOGGING_ENABLED + // methods for AP_Vehicle: + const AP_Int32 &get_log_bitmask() override { return g.log_bitmask; } + const struct LogStructure *get_log_structures() const override { + return log_structure; + } + uint8_t get_num_log_structures() const override; + // Log.cpp void Log_Write_Attitude(); void Log_Write_Vehicle_Baro(float pressure, float altitude); void Log_Write_Vehicle_Pos(int32_t lat,int32_t lng,int32_t alt, const Vector3f& vel); void Log_Write_Vehicle_Startup_Messages(); - void log_init(void); +#endif // Parameters.cpp void load_parameters(void) override; diff --git a/AntennaTracker/system.cpp b/AntennaTracker/system.cpp index db4438ded4c063..a9c2527fa8843b 100644 --- a/AntennaTracker/system.cpp +++ b/AntennaTracker/system.cpp @@ -24,10 +24,6 @@ void Tracker::init_ardupilot() // try to initialise stream rates in the main loop. gcs().update_send(); -#if HAL_LOGGING_ENABLED - log_init(); -#endif - // initialise compass AP::compass().set_log_bit(MASK_LOG_COMPASS); AP::compass().init(); diff --git a/ArduCopter/AP_Arming.cpp b/ArduCopter/AP_Arming.cpp index 30226a9020bbc5..4167e6a7538524 100644 --- a/ArduCopter/AP_Arming.cpp +++ b/ArduCopter/AP_Arming.cpp @@ -233,12 +233,12 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure) // Inverted flight feature disabled for Heli Single and Dual frames if (copter.g2.frame_class.get() != AP_Motors::MOTOR_FRAME_HELI_QUAD && - rc().find_channel_for_option(RC_Channel::aux_func_t::INVERTED) != nullptr) { + rc().find_channel_for_option(RC_Channel::AUX_FUNC::INVERTED) != nullptr) { check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Inverted flight option not supported"); return false; } // Ensure an Aux Channel is configured for motor interlock - if (rc().find_channel_for_option(RC_Channel::aux_func_t::MOTOR_INTERLOCK) == nullptr) { + if (rc().find_channel_for_option(RC_Channel::AUX_FUNC::MOTOR_INTERLOCK) == nullptr) { check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Motor Interlock not configured"); return false; } diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index 5374c79357765a..dda496b3e0921f 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -820,9 +820,6 @@ bool Copter::get_rate_ef_targets(Vector3f& rate_ef_targets) const */ Copter::Copter(void) : -#if HAL_LOGGING_ENABLED - logger(g.log_bitmask), -#endif flight_modes(&g.flight_mode1), simple_cos_yaw(1.0f), super_simple_cos_yaw(1.0), diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 53576d969bd714..3c922cb14073fd 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -251,10 +251,6 @@ class Copter : public AP_Vehicle { RC_Channel *channel_throttle; RC_Channel *channel_yaw; -#if HAL_LOGGING_ENABLED - AP_Logger logger; -#endif - // flight modes convenience array AP_Int8 *flight_modes; const uint8_t num_flight_modes = 6; @@ -846,6 +842,13 @@ class Copter : public AP_Vehicle { void standby_update(); #if HAL_LOGGING_ENABLED + // methods for AP_Vehicle: + const AP_Int32 &get_log_bitmask() override { return g.log_bitmask; } + const struct LogStructure *get_log_structures() const override { + return log_structure; + } + uint8_t get_num_log_structures() const override; + // Log.cpp void Log_Write_Control_Tuning(); void Log_Write_Attitude(); @@ -866,7 +869,6 @@ class Copter : public AP_Vehicle { void Log_Write_SysID_Setup(uint8_t systemID_axis, float waveform_magnitude, float frequency_start, float frequency_stop, float time_fade_in, float time_const_freq, float time_record, float time_fade_out); void Log_Write_SysID_Data(float waveform_time, float waveform_sample, float waveform_freq, float angle_x, float angle_y, float angle_z, float accel_x, float accel_y, float accel_z); void Log_Write_Vehicle_Startup_Messages(); - void log_init(void); #endif // HAL_LOGGING_ENABLED // mode.cpp diff --git a/ArduCopter/Log.cpp b/ArduCopter/Log.cpp index 4d9e4ef87b01b6..d1d530ca1355e4 100644 --- a/ArduCopter/Log.cpp +++ b/ArduCopter/Log.cpp @@ -560,6 +560,11 @@ const struct LogStructure Copter::log_structure[] = { "GUIA", "QBffffffff", "TimeUS,Type,Roll,Pitch,Yaw,RollRt,PitchRt,YawRt,Thrust,ClimbRt", "s-dddkkk-n", "F-000000-0" , true }, }; +uint8_t Copter::get_num_log_structures() const +{ + return ARRAY_SIZE(log_structure); +} + void Copter::Log_Write_Vehicle_Startup_Messages() { // only 200(?) bytes are guaranteed by AP_Logger @@ -571,9 +576,4 @@ void Copter::Log_Write_Vehicle_Startup_Messages() gps.Write_AP_Logger_Log_Startup_messages(); } -void Copter::log_init(void) -{ - logger.Init(log_structure, ARRAY_SIZE(log_structure)); -} - #endif // HAL_LOGGING_ENABLED diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 35b1780ff9cc1a..35ede3b0516cb6 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -554,12 +554,6 @@ const AP_Param::Info Copter::var_info[] = { GOBJECT(camera_mount, "MNT", AP_Mount), #endif -#if HAL_LOGGING_ENABLED - // @Group: LOG - // @Path: ../libraries/AP_Logger/AP_Logger.cpp - GOBJECT(logger, "LOG", AP_Logger), -#endif - // @Group: BATT // @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp GOBJECT(battery, "BATT", AP_BattMonitor), @@ -1238,6 +1232,7 @@ const AP_Param::GroupInfo ParametersG2::var_info2[] = { // @DisplayName: EKF Failsafe filter cutoff // @Description: EKF Failsafe filter cutoff frequency. EKF variances are filtered using this value to avoid spurious failsafes from transient high variances. A higher value means the failsafe is more likely to trigger. // @Range: 0 10 + // @Units: Hz // @User: Advanced AP_GROUPINFO("FS_EKF_FILT", 8, ParametersG2, fs_ekf_filt_hz, FS_EKF_FILT_DEFAULT), @@ -1344,25 +1339,8 @@ const AP_Param::ConversionInfo conversion_table[] = { void Copter::load_parameters(void) { - hal.util->set_soft_armed(false); - - if (!g.format_version.load() || - g.format_version != Parameters::k_format_version) { - - // erase all parameters - DEV_PRINTF("Firmware change: erasing EEPROM...\n"); - StorageManager::erase(); - AP_Param::erase_all(); + AP_Vehicle::load_parameters(g.format_version, Parameters::k_format_version); - // save the current format version - g.format_version.set_and_save(Parameters::k_format_version); - DEV_PRINTF("done.\n"); - } - g.format_version.set_default(Parameters::k_format_version); - - uint32_t before = micros(); - // Load all auto-loaded EEPROM variables - AP_Param::load_all(); AP_Param::convert_old_parameters(&conversion_table[0], ARRAY_SIZE(conversion_table)); #if AP_LANDINGGEAR_ENABLED @@ -1410,11 +1388,13 @@ void Copter::load_parameters(void) } #endif - hal.console->printf("load_all took %uus\n", (unsigned)(micros() - before)); + // PARAMETER_CONVERSION - Added: Feb-2024 for Copter-4.6 +#if HAL_LOGGING_ENABLED + AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, 0, true); +#endif // setup AP_Param frame type flags AP_Param::set_frame_type_flags(AP_PARAM_FRAME_COPTER); - } // handle conversion of PID gains diff --git a/ArduCopter/RC_Channel.cpp b/ArduCopter/RC_Channel.cpp index b613cb141aee43..dde5eb48e37c7d 100644 --- a/ArduCopter/RC_Channel.cpp +++ b/ArduCopter/RC_Channel.cpp @@ -69,7 +69,7 @@ RC_Channel * RC_Channels_Copter::get_arming_channel(void) const } // init_aux_switch_function - initialize aux functions -void RC_Channel_Copter::init_aux_function(const aux_func_t ch_option, const AuxSwitchPos ch_flag) +void RC_Channel_Copter::init_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch_flag) { // init channel options switch(ch_option) { @@ -156,7 +156,7 @@ void RC_Channel_Copter::do_aux_function_change_mode(const Mode::Number mode, } // do_aux_function - implement the function invoked by auxiliary switches -bool RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos ch_flag) +bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch_flag) { switch(ch_option) { case AUX_FUNC::FLIP: diff --git a/ArduCopter/RC_Channel.h b/ArduCopter/RC_Channel.h index 6d9d9f9426801c..b0ba3ebb1492f8 100644 --- a/ArduCopter/RC_Channel.h +++ b/ArduCopter/RC_Channel.h @@ -11,8 +11,8 @@ class RC_Channel_Copter : public RC_Channel protected: - void init_aux_function(aux_func_t ch_option, AuxSwitchPos) override; - bool do_aux_function(aux_func_t ch_option, AuxSwitchPos) override; + void init_aux_function(AUX_FUNC ch_option, AuxSwitchPos) override; + bool do_aux_function(AUX_FUNC ch_option, AuxSwitchPos) override; private: diff --git a/ArduCopter/ReleaseNotes.txt b/ArduCopter/ReleaseNotes.txt index b80cc28e9fa23b..2c4c7893f7e758 100644 --- a/ArduCopter/ReleaseNotes.txt +++ b/ArduCopter/ReleaseNotes.txt @@ -1,4 +1,32 @@ ArduPilot Copter Release Notes: +------------------------------- + +Copter 4.5.0-beta2 14-February-2024 + +Changes from 4.5.0-beta1: + +1) New Autopilots supported + - YJUAV_A6Ultra + - AnyLeaf H7 + +2) System level changes + - fixed float rounding issue in HAL_Linux millis and micros functions + - fixed loading of defaults.parm parameters for dynamic parameter subtrees + - fixed discrimination between GHST and CRSF protocols + - fixed bug in DroneCAN packet parsing for corrupt packets that could cause a crash + - fixed handling of network sockets in scripting when used after close + - fixed bit timing of CANFD buses + +3) Copter specific changes + - added filter to EKF variances for EKF failsafe + +4) Camera and gimbal enhancements + - wait for non-zero camera version in SIYI driver + +5) Miscellaneous + - do relay parameter conversion for parachute parameters if ever has been used + - broaden acceptance criteria for GPS yaw measurement for moving baseline yaw + ------------------------------------------------------------------ Copter 4.5.0-beta1 30-Jan-2025 Changes from 4.4.4 diff --git a/ArduCopter/ekf_check.cpp b/ArduCopter/ekf_check.cpp index 47d9121be9b742..c05e7a279cc49f 100644 --- a/ArduCopter/ekf_check.cpp +++ b/ArduCopter/ekf_check.cpp @@ -123,7 +123,7 @@ bool Copter::ekf_over_threshold() } uint32_t now_us = AP_HAL::micros(); - float dt = (now_us - last_ekf_check_us) / 1000000.0f; + float dt = (now_us - last_ekf_check_us) * 1e-6f; // always update filtered values as this serves the vibration check as well position_var = pos_variance_filt.apply(position_var, dt); diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index 31b96628245b64..5347a67901039b 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -44,10 +44,6 @@ void Copter::init_ardupilot() osd.init(); #endif -#if HAL_LOGGING_ENABLED - log_init(); -#endif - // update motor interlock state update_using_interlock(); diff --git a/ArduCopter/tuning.cpp b/ArduCopter/tuning.cpp index babc53b9ff2672..c2cea3c72f2c38 100644 --- a/ArduCopter/tuning.cpp +++ b/ArduCopter/tuning.cpp @@ -22,7 +22,7 @@ void Copter::tuning() } // exit immediately if a function is assigned to channel 6 - if ((RC_Channel::aux_func_t)rc6->option.get() != RC_Channel::AUX_FUNC::DO_NOTHING) { + if ((RC_Channel::AUX_FUNC)rc6->option.get() != RC_Channel::AUX_FUNC::DO_NOTHING) { return; } diff --git a/ArduPlane/Attitude.cpp b/ArduPlane/Attitude.cpp index b566d4ca730bf9..0996a50b725ab4 100644 --- a/ArduPlane/Attitude.cpp +++ b/ArduPlane/Attitude.cpp @@ -420,6 +420,7 @@ void Plane::stabilize() } SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, rudder); SRV_Channels::set_output_scaled(SRV_Channel::k_steering, rudder); + SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, plane.nav_scripting.throttle_pct); #endif } else { plane.control_mode->run(); diff --git a/ArduPlane/Log.cpp b/ArduPlane/Log.cpp index 2df80fbbc1415c..7b2249e6243745 100644 --- a/ArduPlane/Log.cpp +++ b/ArduPlane/Log.cpp @@ -483,6 +483,11 @@ const struct LogStructure Plane::log_structure[] = { #endif }; +uint8_t Plane::get_num_log_structures() const +{ + return ARRAY_SIZE(log_structure); +} + void Plane::Log_Write_Vehicle_Startup_Messages() { // only 200(?) bytes are guaranteed by AP_Logger @@ -498,12 +503,4 @@ void Plane::Log_Write_Vehicle_Startup_Messages() gps.Write_AP_Logger_Log_Startup_messages(); } -/* - initialise logging subsystem - */ -void Plane::log_init(void) -{ - logger.Init(log_structure, ARRAY_SIZE(log_structure)); -} - #endif // HAL_LOGGING_ENABLED diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index 639aa73039e6a2..6d3c1d945652fd 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -908,12 +908,6 @@ const AP_Param::Info Plane::var_info[] = { GOBJECT(camera_mount, "MNT", AP_Mount), #endif -#if HAL_LOGGING_ENABLED - // @Group: LOG - // @Path: ../libraries/AP_Logger/AP_Logger.cpp - GOBJECT(logger, "LOG", AP_Logger), -#endif - // @Group: BATT // @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp GOBJECT(battery, "BATT", AP_BattMonitor), @@ -1350,23 +1344,8 @@ static const RCConversionInfo rc_option_conversion[] = { void Plane::load_parameters(void) { - if (!g.format_version.load() || - g.format_version != Parameters::k_format_version) { - - // erase all parameters - hal.console->printf("Firmware change: erasing EEPROM...\n"); - StorageManager::erase(); - AP_Param::erase_all(); + AP_Vehicle::load_parameters(g.format_version, Parameters::k_format_version); - // save the current format version - g.format_version.set_and_save(Parameters::k_format_version); - hal.console->printf("done.\n"); - } - g.format_version.set_default(Parameters::k_format_version); - - uint32_t before = micros(); - // Load all auto-loaded EEPROM variables - AP_Param::load_all(); AP_Param::convert_old_parameters(&conversion_table[0], ARRAY_SIZE(conversion_table)); // setup defaults in SRV_Channels @@ -1579,5 +1558,8 @@ void Plane::load_parameters(void) } #endif - hal.console->printf("load_all took %uus\n", (unsigned)(micros() - before)); + // PARAMETER_CONVERSION - Added: Feb-2024 for Copter-4.6 +#if HAL_LOGGING_ENABLED + AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, 0, true); +#endif } diff --git a/ArduPlane/Plane.cpp b/ArduPlane/Plane.cpp index 07055294b523a0..4be3c0df7c60e8 100644 --- a/ArduPlane/Plane.cpp +++ b/ArduPlane/Plane.cpp @@ -24,9 +24,6 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL(); constructor for main Plane class */ Plane::Plane(void) -#if HAL_LOGGING_ENABLED - : logger(g.log_bitmask) -#endif { // C++11 doesn't allow in-class initialisation of bitfields auto_state.takeoff_complete = true; diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 3769e44a543c5f..3d08a2bca9add5 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -192,10 +192,6 @@ class Plane : public AP_Vehicle { RC_Channel *channel_flap; RC_Channel *channel_airbrake; -#if HAL_LOGGING_ENABLED - AP_Logger logger; -#endif - // scaled roll limit based on pitch int32_t roll_limit_cd; float pitch_limit_min; @@ -886,9 +882,16 @@ class Plane : public AP_Vehicle { int16_t calc_nav_yaw_course(void); int16_t calc_nav_yaw_ground(void); - // Log.cpp - uint32_t last_log_fast_ms; +#if HAL_LOGGING_ENABLED + // methods for AP_Vehicle: + const AP_Int32 &get_log_bitmask() override { return g.log_bitmask; } + const struct LogStructure *get_log_structures() const override { + return log_structure; + } + uint8_t get_num_log_structures() const override; + + // Log.cpp void Log_Write_FullRate(void); void Log_Write_Attitude(void); void Log_Write_Control_Tuning(); @@ -900,6 +903,7 @@ class Plane : public AP_Vehicle { void Log_Write_Vehicle_Startup_Messages(); void Log_Write_AETR(); void log_init(); +#endif // Parameters.cpp void load_parameters(void) override; diff --git a/ArduPlane/RC_Channel.cpp b/ArduPlane/RC_Channel.cpp index cb426ab21f4a28..d61413c3d0f3a4 100644 --- a/ArduPlane/RC_Channel.cpp +++ b/ArduPlane/RC_Channel.cpp @@ -141,7 +141,7 @@ void RC_Channel_Plane::do_aux_function_flare(AuxSwitchPos ch_flag) } -void RC_Channel_Plane::init_aux_function(const RC_Channel::aux_func_t ch_option, +void RC_Channel_Plane::init_aux_function(const RC_Channel::AUX_FUNC ch_option, const RC_Channel::AuxSwitchPos ch_flag) { switch(ch_option) { @@ -212,7 +212,7 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::aux_func_t ch_option, } // do_aux_function - implement the function invoked by auxiliary switches -bool RC_Channel_Plane::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos ch_flag) +bool RC_Channel_Plane::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch_flag) { switch(ch_option) { case AUX_FUNC::INVERTED: diff --git a/ArduPlane/RC_Channel.h b/ArduPlane/RC_Channel.h index 7ecc352c32aa8b..858034478c9bf1 100644 --- a/ArduPlane/RC_Channel.h +++ b/ArduPlane/RC_Channel.h @@ -9,9 +9,9 @@ class RC_Channel_Plane : public RC_Channel protected: - void init_aux_function(aux_func_t ch_option, + void init_aux_function(AUX_FUNC ch_option, AuxSwitchPos ch_flag) override; - bool do_aux_function(aux_func_t ch_option, AuxSwitchPos) override; + bool do_aux_function(AUX_FUNC ch_option, AuxSwitchPos) override; // called when the mode switch changes position: void mode_switch_changed(modeswitch_pos_t new_pos) override; diff --git a/ArduPlane/ReleaseNotes.txt b/ArduPlane/ReleaseNotes.txt index bff21a6845c3db..54e8a90461a1aa 100644 --- a/ArduPlane/ReleaseNotes.txt +++ b/ArduPlane/ReleaseNotes.txt @@ -1,3 +1,31 @@ +Release 4.5.0-beta2 14th February 2024 +-------------------------------------- + +Changes from 4.5.0-beta1: + +1) New Autopilots supported + - YJUAV_A6Ultra + - AnyLeaf H7 + +2) System level changes + - fixed float rounding issue in HAL_Linux millis and micros functions + - fixed loading of defaults.parm parameters for dynamic parameter subtrees + - fixed discrimination between GHST and CRSF protocols + - fixed bug in DroneCAN packet parsing for corrupt packets that could cause a crash + - fixed handling of network sockets in scripting when used after close + - fixed bit timing of CANFD buses + +3) Plane specific changes + - fixed handling of force arming when safety is enabled for VTOL motor state + +4) Camera and gimbal enhancements + - wait for non-zero camera version in SIYI driver + +5) Miscellaneous + - do relay parameter conversion for parachute parameters if ever has been used + - broaden acceptance criteria for GPS yaw measurement for moving baseline yaw + + Release 4.5.0-beta1 30th January 2024 ------------------------------------- diff --git a/ArduPlane/createTags b/ArduPlane/createTags index e13937801d6ecf..df38cc23ca6ade 100755 --- a/ArduPlane/createTags +++ b/ArduPlane/createTags @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash #" Autocompletion enabled vim for arduino pde's ctags -RV --language-force=C++ --c++-kinds=+p --fields=+iaS --extra=+q \ diff --git a/ArduPlane/mode.h b/ArduPlane/mode.h index b7f4732e924fe7..83da193de00590 100644 --- a/ArduPlane/mode.h +++ b/ArduPlane/mode.h @@ -343,6 +343,7 @@ class ModeLoiter : public Mode void navigate() override; bool isHeadingLinedUp(const Location loiterCenterLoc, const Location targetLoc); + bool isHeadingLinedUp_cd(const int32_t bearing_cd, const int32_t heading_cd); bool isHeadingLinedUp_cd(const int32_t bearing_cd); bool allows_throttle_nudging() const override { return true; } diff --git a/ArduPlane/mode_auto.cpp b/ArduPlane/mode_auto.cpp index f1a9f5de5540b2..73753e1fa44ca5 100644 --- a/ArduPlane/mode_auto.cpp +++ b/ArduPlane/mode_auto.cpp @@ -102,7 +102,6 @@ void ModeAuto::update() // NAV_SCRIPTING has a desired roll and pitch rate and desired throttle plane.nav_roll_cd = ahrs.roll_sensor; plane.nav_pitch_cd = ahrs.pitch_sensor; - SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, plane.nav_scripting.throttle_pct); #endif } else { // we are doing normal AUTO flight, the special cases diff --git a/ArduPlane/mode_loiter.cpp b/ArduPlane/mode_loiter.cpp index 05ce3a69568572..b37f3bdcb0311e 100644 --- a/ArduPlane/mode_loiter.cpp +++ b/ArduPlane/mode_loiter.cpp @@ -42,28 +42,71 @@ bool ModeLoiter::isHeadingLinedUp(const Location loiterCenterLoc, const Location // Return true if current heading is aligned to vector to targetLoc. // Tolerance is initially 10 degrees and grows at 10 degrees for each loiter circle completed. - if (loiterCenterLoc.get_distance(targetLoc) < 1.05f * fabsf(plane.loiter.radius)) { - /* Whenever next waypoint is within the loiter radius plus 5%, - maintaining loiter would prevent us from ever pointing toward the next waypoint. - Hence break out of loiter immediately - */ + // Corrected radius for altitude + const float loiter_radius = plane.nav_controller->loiter_radius(fabsf(plane.loiter.radius)); + if (!is_positive(loiter_radius)) { + // Zero is invalid, protect against divide by zero for destination inside loiter radius case return true; } - // Bearing in centi-degrees - const int32_t bearing_cd = plane.current_loc.get_bearing_to(targetLoc); - return isHeadingLinedUp_cd(bearing_cd); + // Calculate relative position of the vehicle relative to loiter center projected onto the closest point of the loiter circle + // This removes error due to radial position as the nav controller attempts to track the circle + const Vector2f projected_pos = loiterCenterLoc.get_distance_NE(plane.current_loc).normalized() * loiter_radius; + + // Target position relative to loiter center + const Vector2f target_pos = loiterCenterLoc.get_distance_NE(targetLoc); + + // Distance between loiter circle and target + const float target_dist = target_pos.length(); + if (!is_positive(target_dist)) { + // Target is coincident with loiter center, no heading will be closer than any other + return true; + } + + // Target bearing in centi-degrees + int32_t target_bearing_cd; + + if (target_dist >= loiter_radius) { + // Destination outside loiter radius, heading will always line up with destination + + // Vector from between projected vehicle position and target postion + const Vector2f pos_to_target = target_pos - projected_pos; + target_bearing_cd = degrees(pos_to_target.angle()) * 100; + + } else { + // Destination is inside loiter, heading will never line up with destination + + // Advance turn point by the angle of a segment with chord "a" + // This results in turning earlier as the target point approaches the center + // If target is on radius angle of 0 and angle of 60 deg if target is on center + const float a = loiter_radius - target_dist; + const float segment_angle = 2.0 * asinf(a / (2.0 * loiter_radius)); + + // Pick the intersection point that will be hit first for the current loiter direction, add 90 deg to get the tangent angle + target_bearing_cd = degrees(wrap_PI(target_pos.angle() + (M_PI_2 - segment_angle) * plane.loiter.direction)) * 100; + + } + + // Ideal heading in centi-degrees, +- 90 to get tangent to loiter circle at closest point + const int32_t current_heading_cd = degrees(wrap_PI(projected_pos.angle() + M_PI_2 * plane.loiter.direction)) * 100; + + return isHeadingLinedUp_cd(target_bearing_cd, current_heading_cd); } -bool ModeLoiter::isHeadingLinedUp_cd(const int32_t bearing_cd) -{ - // Return true if current heading is aligned to bearing_cd. - // Tolerance is initially 10 degrees and grows at 10 degrees for each loiter circle completed. +bool ModeLoiter::isHeadingLinedUp_cd(const int32_t bearing_cd) { // get current heading. const int32_t heading_cd = (wrap_360(degrees(ahrs.groundspeed_vector().angle())))*100; + return isHeadingLinedUp_cd(bearing_cd, heading_cd); +} + + +bool ModeLoiter::isHeadingLinedUp_cd(const int32_t bearing_cd, const int32_t heading_cd) +{ + // Return true if current heading is aligned to bearing_cd. + // Tolerance is initially 10 degrees and grows at 10 degrees for each loiter circle completed. const int32_t heading_err_cd = wrap_180_cd(bearing_cd - heading_cd); /* diff --git a/ArduPlane/mode_takeoff.cpp b/ArduPlane/mode_takeoff.cpp index 2f70bef07115a3..37d0203fcf413f 100644 --- a/ArduPlane/mode_takeoff.cpp +++ b/ArduPlane/mode_takeoff.cpp @@ -134,34 +134,41 @@ void ModeTakeoff::update() // reset the loiter waypoint target to be correct bearing and dist // from starting location in case original yaw used to set it was off due to EKF // reset or compass interference from max throttle + const float altitude_cm = plane.current_loc.alt - start_loc.alt; if (plane.flight_stage == AP_FixedWing::FlightStage::TAKEOFF && - (plane.current_loc.alt - start_loc.alt >= level_alt*100 || + (altitude_cm >= level_alt*100 || start_loc.get_distance(plane.current_loc) >= dist)) { // reset the target loiter waypoint using current yaw which should be close to correct starting heading const float direction = start_loc.get_bearing_to(plane.current_loc) * 0.01; plane.next_WP_loc = start_loc; plane.next_WP_loc.offset_bearing(direction, dist); plane.next_WP_loc.alt += alt*100.0; - plane.set_flight_stage(AP_FixedWing::FlightStage::NORMAL); - -#if AP_FENCE_ENABLED - plane.fence.auto_enable_fence_after_takeoff(); -#endif } if (plane.flight_stage == AP_FixedWing::FlightStage::TAKEOFF) { + //below TAKOFF_LVL_ALT SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 100.0); plane.takeoff_calc_roll(); plane.takeoff_calc_pitch(); } else { - plane.calc_nav_roll(); - plane.calc_nav_pitch(); - plane.calc_throttle(); - //check if in long failsafe, if it is recall long failsafe now to get fs action via events call + if ((altitude_cm >= alt * 100 - 200)) { //within 2m of TKOFF_ALT ,or above and loitering +#if AP_FENCE_ENABLED + plane.fence.auto_enable_fence_after_takeoff(); +#endif + plane.calc_nav_roll(); + plane.calc_nav_pitch(); + plane.calc_throttle(); + } else { // still climbing to TAKEOFF_ALT; may be loitering + plane.calc_throttle(); + plane.takeoff_calc_roll(); + plane.takeoff_calc_pitch(); + } + + //check if in long failsafe due to being in initial TAKEOFF stage; if it is, recall long failsafe now to get fs action via events call if (plane.long_failsafe_pending) { - plane.long_failsafe_pending = false; - plane.failsafe_long_on_event(FAILSAFE_LONG, ModeReason::MODE_TAKEOFF_FAILSAFE); + plane.long_failsafe_pending = false; + plane.failsafe_long_on_event(FAILSAFE_LONG, ModeReason::MODE_TAKEOFF_FAILSAFE); } } } diff --git a/ArduPlane/servos.cpp b/ArduPlane/servos.cpp index c0cab9f9de4f41..da770481600eff 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -547,6 +547,21 @@ float Plane::apply_throttle_limits(float throttle_in) void Plane::set_throttle(void) { + // Update voltage scaling + g2.fwd_batt_cmp.update(); + + if (control_mode->use_battery_compensation()) { + // Apply voltage compensation to throttle output from flight mode + const float throttle = g2.fwd_batt_cmp.apply_throttle(SRV_Channels::get_output_scaled(SRV_Channel::k_throttle)); + SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, throttle); + } + + if (control_mode->use_throttle_limits()) { + // Apply min/max throttle limits + const float limited_throttle = apply_throttle_limits(SRV_Channels::get_output_scaled(SRV_Channel::k_throttle)); + SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, limited_throttle); + } + if (!arming.is_armed_and_safety_off()) { // Always set 0 scaled even if overriding to zero pwm. // This ensures slew limits and other functions using the scaled value pick up in the correct place @@ -559,10 +574,8 @@ void Plane::set_throttle(void) SRV_Channels::set_output_limit(SRV_Channel::k_throttleLeft, SRV_Channel::Limit::ZERO_PWM); SRV_Channels::set_output_limit(SRV_Channel::k_throttleRight, SRV_Channel::Limit::ZERO_PWM); } - return; - } - if (suppress_throttle()) { + } else if (suppress_throttle()) { if (g.throttle_suppress_manual) { // manual pass through of throttle while throttle is suppressed SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, get_throttle_input(true)); @@ -576,29 +589,8 @@ void Plane::set_throttle(void) SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0.0); } - return; } - // Update voltage scaling - g2.fwd_batt_cmp.update(); - -#if AP_SCRIPTING_ENABLED - if (nav_scripting_active()) { - SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, plane.nav_scripting.throttle_pct); - } -#endif - - if (control_mode->use_battery_compensation()) { - // Apply voltage compensation to throttle output from flight mode - const float throttle = g2.fwd_batt_cmp.apply_throttle(SRV_Channels::get_output_scaled(SRV_Channel::k_throttle)); - SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, throttle); - } - - if (control_mode->use_throttle_limits()) { - // Apply min/max throttle limits - const float limited_throttle = apply_throttle_limits(SRV_Channels::get_output_scaled(SRV_Channel::k_throttle)); - SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, limited_throttle); - } } /* diff --git a/ArduPlane/system.cpp b/ArduPlane/system.cpp index 56998c367904db..eab2ecef94084b 100644 --- a/ArduPlane/system.cpp +++ b/ArduPlane/system.cpp @@ -64,10 +64,6 @@ void Plane::init_ardupilot() osd.init(); #endif -#if HAL_LOGGING_ENABLED - log_init(); -#endif - AP::compass().set_log_bit(MASK_LOG_COMPASS); AP::compass().init(); diff --git a/ArduSub/Log.cpp b/ArduSub/Log.cpp index 63d3feb8ff222d..45603f2d3aed1f 100644 --- a/ArduSub/Log.cpp +++ b/ArduSub/Log.cpp @@ -275,6 +275,11 @@ const struct LogStructure Sub::log_structure[] = { "GUIP", "QBffffff", "TimeUS,Type,pX,pY,pZ,vX,vY,vZ", "s-mmmnnn", "F-000000" }, }; +uint8_t Sub::get_num_log_structures() const +{ + return ARRAY_SIZE(log_structure); +} + void Sub::Log_Write_Vehicle_Startup_Messages() { // only 200(?) bytes are guaranteed by AP_Logger @@ -284,9 +289,4 @@ void Sub::Log_Write_Vehicle_Startup_Messages() } -void Sub::log_init() -{ - logger.Init(log_structure, ARRAY_SIZE(log_structure)); -} - #endif // HAL_LOGGING_ENABLED diff --git a/ArduSub/Parameters.cpp b/ArduSub/Parameters.cpp index 168990b01f4c82..58e554f348ef98 100644 --- a/ArduSub/Parameters.cpp +++ b/ArduSub/Parameters.cpp @@ -561,12 +561,6 @@ const AP_Param::Info Sub::var_info[] = { GOBJECT(camera_mount, "MNT", AP_Mount), #endif -#if HAL_LOGGING_ENABLED - // @Group: LOG - // @Path: ../libraries/AP_Logger/AP_Logger.cpp - GOBJECT(logger, "LOG", AP_Logger), -#endif - // @Group: BATT // @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp GOBJECT(battery, "BATT", AP_BattMonitor), @@ -738,26 +732,8 @@ const AP_Param::ConversionInfo conversion_table[] = { void Sub::load_parameters() { - hal.util->set_soft_armed(false); - - if (!g.format_version.load() || - g.format_version != Parameters::k_format_version) { - - // erase all parameters - hal.console->printf("Firmware change: erasing EEPROM...\n"); - StorageManager::erase(); - AP_Param::erase_all(); + AP_Vehicle::load_parameters(g.format_version, Parameters::k_format_version); - // save the current format version - g.format_version.set_and_save(Parameters::k_format_version); - hal.console->println("done."); - } - g.format_version.set_default(Parameters::k_format_version); - - uint32_t before = AP_HAL::micros(); - // Load all auto-loaded EEPROM variables - AP_Param::load_all(); - hal.console->printf("load_all took %uus\n", (unsigned)(AP_HAL::micros() - before)); AP_Param::convert_old_parameters(&conversion_table[0], ARRAY_SIZE(conversion_table)); AP_Param::set_frame_type_flags(AP_PARAM_FRAME_SUB); @@ -814,6 +790,11 @@ void Sub::load_parameters() AP_Param::convert_class(scripting_info.old_key, &scripting, scripting.var_info, scripting_old_index, scripting_old_top_element, false); } #endif + + // PARAMETER_CONVERSION - Added: Feb-2024 +#if HAL_LOGGING_ENABLED + AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, 0, true); +#endif } void Sub::convert_old_parameters() diff --git a/ArduSub/Sub.cpp b/ArduSub/Sub.cpp index 304ed327249e55..877f3bf8c17cae 100644 --- a/ArduSub/Sub.cpp +++ b/ArduSub/Sub.cpp @@ -25,9 +25,6 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL(); */ Sub::Sub() : -#if HAL_LOGGING_ENABLED - logger(g.log_bitmask), -#endif control_mode(Mode::Number::MANUAL), motors(MAIN_LOOP_RATE), auto_mode(Auto_WP), diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index 53de38af092b79..2419e0fc799345 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -146,10 +146,6 @@ class Sub : public AP_Vehicle { RC_Channel *channel_forward; RC_Channel *channel_lateral; -#if HAL_LOGGING_ENABLED - AP_Logger logger; -#endif - AP_LeakDetector leak_detector; struct { @@ -403,6 +399,13 @@ class Sub : public AP_Vehicle { float get_surface_tracking_climb_rate(int16_t target_rate, float current_alt_target, float dt); void rotate_body_frame_to_NE(float &x, float &y); #if HAL_LOGGING_ENABLED + // methods for AP_Vehicle: + const AP_Int32 &get_log_bitmask() override { return g.log_bitmask; } + const struct LogStructure *get_log_structures() const override { + return log_structure; + } + uint8_t get_num_log_structures() const override; + void Log_Write_Control_Tuning(); void Log_Write_Attitude(); void Log_Write_Data(LogDataID id, int32_t value); diff --git a/ArduSub/system.cpp b/ArduSub/system.cpp index f86637c5a143ab..b72b9889c11853 100644 --- a/ArduSub/system.cpp +++ b/ArduSub/system.cpp @@ -52,10 +52,6 @@ void Sub::init_ardupilot() // setup telem slots with serial ports gcs().setup_uarts(); -#if HAL_LOGGING_ENABLED - log_init(); -#endif - // initialise rc channels including setting mode rc().convert_options(RC_Channel::AUX_FUNC::ARMDISARM_UNUSED, RC_Channel::AUX_FUNC::ARMDISARM); rc().init(); diff --git a/Blimp/Blimp.cpp b/Blimp/Blimp.cpp index 3231580eaf619c..05b5c459160e06 100644 --- a/Blimp/Blimp.cpp +++ b/Blimp/Blimp.cpp @@ -286,9 +286,6 @@ void Blimp::rotate_NE_to_BF(Vector2f &vec) */ Blimp::Blimp(void) : -#if HAL_LOGGING_ENABLED - logger(g.log_bitmask), -#endif flight_modes(&g.flight_mode1), control_mode(Mode::Number::MANUAL), rc_throttle_control_in_filter(1.0f), diff --git a/Blimp/Blimp.h b/Blimp/Blimp.h index 9566f9294e1f17..826d92b98c49fe 100644 --- a/Blimp/Blimp.h +++ b/Blimp/Blimp.h @@ -113,10 +113,6 @@ class Blimp : public AP_Vehicle RC_Channel *channel_up; RC_Channel *channel_yaw; -#if HAL_LOGGING_ENABLED - AP_Logger logger; -#endif - // flight modes convenience array AP_Int8 *flight_modes; const uint8_t num_flight_modes = 6; @@ -354,8 +350,14 @@ class Blimp : public AP_Vehicle void landinggear_update(); #if HAL_LOGGING_ENABLED + // methods for AP_Vehicle: + const AP_Int32 &get_log_bitmask() override { return g.log_bitmask; } + const struct LogStructure *get_log_structures() const override { + return log_structure; + } + uint8_t get_num_log_structures() const override; + // Log.cpp - void Log_Write_Performance(); void Log_Write_Attitude(); void Log_Write_PIDs(); void Log_Write_EKF_POS(); @@ -365,11 +367,9 @@ class Blimp : public AP_Vehicle void Log_Write_Data(LogDataID id, uint16_t value); void Log_Write_Data(LogDataID id, float value); void Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, float tune_min, float tune_max); - void Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target); void Log_Write_Vehicle_Startup_Messages(); - void log_init(void); void Write_FINI(float right, float front, float down, float yaw); void Write_FINO(float *amp, float *off); #endif diff --git a/Blimp/Log.cpp b/Blimp/Log.cpp index 7d62fc9d5ebc6b..e7fcea3cfbdc24 100644 --- a/Blimp/Log.cpp +++ b/Blimp/Log.cpp @@ -393,6 +393,12 @@ const struct LogStructure Blimp::log_structure[] = { }, }; +uint8_t Blimp::get_num_log_structures() const +{ + return ARRAY_SIZE(log_structure); + +} + void Blimp::Log_Write_Vehicle_Startup_Messages() { // only 200(?) bytes are guaranteed by AP_Logger @@ -402,9 +408,4 @@ void Blimp::Log_Write_Vehicle_Startup_Messages() gps.Write_AP_Logger_Log_Startup_messages(); } -void Blimp::log_init(void) -{ - logger.Init(log_structure, ARRAY_SIZE(log_structure)); -} - #endif // HAL_LOGGING_ENABLED diff --git a/Blimp/Parameters.cpp b/Blimp/Parameters.cpp index f0641e0cf28229..cbc14fc4101a2f 100644 --- a/Blimp/Parameters.cpp +++ b/Blimp/Parameters.cpp @@ -341,12 +341,6 @@ const AP_Param::Info Blimp::var_info[] = { // @Path: ../libraries/AP_AHRS/AP_AHRS.cpp GOBJECT(ahrs, "AHRS_", AP_AHRS), -#if HAL_LOGGING_ENABLED - // @Group: LOG - // @Path: ../libraries/AP_Logger/AP_Logger.cpp - GOBJECT(logger, "LOG", AP_Logger), -#endif - // @Group: BATT // @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp GOBJECT(battery, "BATT", AP_BattMonitor), @@ -846,25 +840,7 @@ ParametersG2::ParametersG2(void) void Blimp::load_parameters(void) { - hal.util->set_soft_armed(false); - - if (!g.format_version.load() || - g.format_version != Parameters::k_format_version) { - - // erase all parameters - hal.console->printf("Firmware change: erasing EEPROM...\n"); - StorageManager::erase(); - AP_Param::erase_all(); - - // save the current format version - g.format_version.set_and_save(Parameters::k_format_version); - hal.console->printf("done.\n"); - } - g.format_version.set_default(Parameters::k_format_version); - - uint32_t before = micros(); - // Load all auto-loaded EEPROM variables - AP_Param::load_all(); + AP_Vehicle::load_parameters(g.format_version, Parameters::k_format_version); // PARAMETER_CONVERSION - Added: Jan-2024 for Copter-4.6 #if AP_STATS_ENABLED @@ -895,7 +871,10 @@ void Blimp::load_parameters(void) } #endif - hal.console->printf("load_all took %uus\n", (unsigned)(micros() - before)); + // PARAMETER_CONVERSION - Added: Feb-2024 +#if HAL_LOGGING_ENABLED + AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, 0, true); +#endif // setup AP_Param frame type flags AP_Param::set_frame_type_flags(AP_PARAM_FRAME_BLIMP); diff --git a/Blimp/RC_Channel.cpp b/Blimp/RC_Channel.cpp index ba94d82a173df4..8742d3e347953e 100644 --- a/Blimp/RC_Channel.cpp +++ b/Blimp/RC_Channel.cpp @@ -58,7 +58,7 @@ RC_Channel * RC_Channels_Blimp::get_arming_channel(void) const } // init_aux_switch_function - initialize aux functions -void RC_Channel_Blimp::init_aux_function(const aux_func_t ch_option, const AuxSwitchPos ch_flag) +void RC_Channel_Blimp::init_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch_flag) { // init channel options switch (ch_option) { @@ -99,7 +99,7 @@ void RC_Channel_Blimp::do_aux_function_change_mode(const Mode::Number mode, } // do_aux_function - implement the function invoked by auxiliary switches -bool RC_Channel_Blimp::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos ch_flag) +bool RC_Channel_Blimp::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch_flag) { switch (ch_option) { diff --git a/Blimp/RC_Channel.h b/Blimp/RC_Channel.h index ec37259794cb82..4a6e5e0156da12 100644 --- a/Blimp/RC_Channel.h +++ b/Blimp/RC_Channel.h @@ -11,8 +11,8 @@ class RC_Channel_Blimp : public RC_Channel protected: - void init_aux_function(aux_func_t ch_option, AuxSwitchPos) override; - bool do_aux_function(aux_func_t ch_option, AuxSwitchPos) override; + void init_aux_function(AUX_FUNC ch_option, AuxSwitchPos) override; + bool do_aux_function(AUX_FUNC ch_option, AuxSwitchPos) override; private: diff --git a/Blimp/system.cpp b/Blimp/system.cpp index 5bde10d45bb60f..b95b2db9d61581 100644 --- a/Blimp/system.cpp +++ b/Blimp/system.cpp @@ -29,10 +29,6 @@ void Blimp::init_ardupilot() // setup telem slots with serial ports gcs().setup_uarts(); -#if HAL_LOGGING_ENABLED - log_init(); -#endif - init_rc_in(); // sets up rc channels from radio // allocate the motors class diff --git a/Rover/Log.cpp b/Rover/Log.cpp index f102fa95c0ca41..99fd471dccee4d 100644 --- a/Rover/Log.cpp +++ b/Rover/Log.cpp @@ -308,22 +308,9 @@ const LogStructure Rover::log_structure[] = { "GUIP", "QBffffff", "TimeUS,Type,pX,pY,pZ,vX,vY,vZ", "s-mmmnnn", "F-000000" }, }; -void Rover::log_init(void) +uint8_t Rover::get_num_log_structures() const { - logger.Init(log_structure, ARRAY_SIZE(log_structure)); + return ARRAY_SIZE(log_structure); } -#else // LOGGING_ENABLED - -// dummy functions -void Rover::Log_Write_Attitude() {} -void Rover::Log_Write_Depth() {} -void Rover::Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target) {} -void Rover::Log_Write_Nav_Tuning() {} -void Rover::Log_Write_Sail() {} -void Rover::Log_Write_Throttle() {} -void Rover::Log_Write_RC(void) {} -void Rover::Log_Write_Steering() {} -void Rover::Log_Write_Vehicle_Startup_Messages() {} - #endif // LOGGING_ENABLED diff --git a/Rover/Parameters.cpp b/Rover/Parameters.cpp index 1c7ae1a07b2a65..34f393b740a918 100644 --- a/Rover/Parameters.cpp +++ b/Rover/Parameters.cpp @@ -316,12 +316,6 @@ const AP_Param::Info Rover::var_info[] = { // @Path: ../libraries/AP_Arming/AP_Arming.cpp GOBJECT(arming, "ARMING_", AP_Arming), -#if HAL_LOGGING_ENABLED - // @Group: LOG - // @Path: ../libraries/AP_Logger/AP_Logger.cpp - GOBJECT(logger, "LOG", AP_Logger), -#endif - // @Group: BATT // @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp GOBJECT(battery, "BATT", AP_BattMonitor), @@ -817,22 +811,8 @@ const AP_Param::ConversionInfo conversion_table[] = { void Rover::load_parameters(void) { - if (!g.format_version.load() || - g.format_version != Parameters::k_format_version) { - // erase all parameters - hal.console->printf("Firmware change: erasing EEPROM...\n"); - StorageManager::erase(); - AP_Param::erase_all(); - - // save the current format version - g.format_version.set_and_save(Parameters::k_format_version); - hal.console->printf("done.\n"); - } - g.format_version.set_default(Parameters::k_format_version); + AP_Vehicle::load_parameters(g.format_version, Parameters::k_format_version); - const uint32_t before = micros(); - // Load all auto-loaded EEPROM variables - AP_Param::load_all(); AP_Param::convert_old_parameters(&conversion_table[0], ARRAY_SIZE(conversion_table)); AP_Param::set_frame_type_flags(AP_PARAM_FRAME_ROVER); @@ -845,7 +825,6 @@ void Rover::load_parameters(void) } SRV_Channels::upgrade_parameters(); - hal.console->printf("load_all took %uus\n", unsigned(micros() - before)); // convert CH7_OPTION to RC7_OPTION for Rover-3.4 to 3.5 upgrade const AP_Param::ConversionInfo ch7_option_info = { Parameters::k_param_ch7_option, 0, AP_PARAM_INT8, "RC7_OPTION" }; @@ -944,4 +923,9 @@ void Rover::load_parameters(void) } #endif + // PARAMETER_CONVERSION - Added: Feb-2024 for Rover-4.6 +#if HAL_LOGGING_ENABLED + AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, 0, true); +#endif + } diff --git a/Rover/RC_Channel.cpp b/Rover/RC_Channel.cpp index 9a89b66d613764..eba85331194459 100644 --- a/Rover/RC_Channel.cpp +++ b/Rover/RC_Channel.cpp @@ -26,7 +26,7 @@ void RC_Channel_Rover::mode_switch_changed(modeswitch_pos_t new_pos) } // init_aux_switch_function - initialize aux functions -void RC_Channel_Rover::init_aux_function(const aux_func_t ch_option, const AuxSwitchPos ch_flag) +void RC_Channel_Rover::init_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch_flag) { // init channel options switch (ch_option) { @@ -130,7 +130,7 @@ void RC_Channel_Rover::do_aux_function_sailboat_motor_3pos(const AuxSwitchPos ch } } -bool RC_Channel_Rover::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos ch_flag) +bool RC_Channel_Rover::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch_flag) { switch (ch_option) { case AUX_FUNC::DO_NOTHING: diff --git a/Rover/RC_Channel.h b/Rover/RC_Channel.h index d25d714aa261cd..01c83da59b7389 100644 --- a/Rover/RC_Channel.h +++ b/Rover/RC_Channel.h @@ -11,8 +11,8 @@ class RC_Channel_Rover : public RC_Channel protected: - void init_aux_function(aux_func_t ch_option, AuxSwitchPos) override; - bool do_aux_function(aux_func_t ch_option, AuxSwitchPos) override; + void init_aux_function(AUX_FUNC ch_option, AuxSwitchPos) override; + bool do_aux_function(AUX_FUNC ch_option, AuxSwitchPos) override; // called when the mode switch changes position: void mode_switch_changed(modeswitch_pos_t new_pos) override; diff --git a/Rover/Rover.cpp b/Rover/Rover.cpp index 4d8c3e3fd29da9..b956267eef48e6 100644 --- a/Rover/Rover.cpp +++ b/Rover/Rover.cpp @@ -157,9 +157,6 @@ constexpr int8_t Rover::_failsafe_priorities[7]; Rover::Rover(void) : AP_Vehicle(), param_loader(var_info), -#if HAL_LOGGING_ENABLED - logger{g.log_bitmask}, -#endif modes(&g.mode1), control_mode(&mode_initializing) { diff --git a/Rover/Rover.h b/Rover/Rover.h index cbc508cd2c0a84..e12ed2db608b85 100644 --- a/Rover/Rover.h +++ b/Rover/Rover.h @@ -136,10 +136,6 @@ class Rover : public AP_Vehicle { RC_Channel *channel_pitch; RC_Channel *channel_walking_height; -#if HAL_LOGGING_ENABLED - AP_Logger logger; -#endif - // flight modes convenience array AP_Int8 *modes; const uint8_t num_modes = 6; @@ -272,8 +268,6 @@ class Rover : public AP_Vehicle { } cruise_learn_t; cruise_learn_t cruise_learn; -private: - // Rover.cpp #if AP_SCRIPTING_ENABLED bool set_target_location(const Location& target_loc) override; @@ -334,6 +328,14 @@ class Rover : public AP_Vehicle { // GCS_Mavlink.cpp void send_wheel_encoder_distance(mavlink_channel_t chan); +#if HAL_LOGGING_ENABLED + // methods for AP_Vehicle: + const AP_Int32 &get_log_bitmask() override { return g.log_bitmask; } + const struct LogStructure *get_log_structures() const override { + return log_structure; + } + uint8_t get_num_log_structures() const override; + // Log.cpp void Log_Write_Attitude(); void Log_Write_Depth(); @@ -345,7 +347,7 @@ class Rover : public AP_Vehicle { void Log_Write_RC(void); void Log_Write_Vehicle_Startup_Messages(); void Log_Read(uint16_t log_num, uint16_t start_page, uint16_t end_page); - void log_init(void); +#endif // mode.cpp Mode *mode_from_mode_num(enum Mode::Number num); diff --git a/Rover/createTags b/Rover/createTags index e13937801d6ecf..df38cc23ca6ade 100755 --- a/Rover/createTags +++ b/Rover/createTags @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash #" Autocompletion enabled vim for arduino pde's ctags -RV --language-force=C++ --c++-kinds=+p --fields=+iaS --extra=+q \ diff --git a/Rover/mode_guided.cpp b/Rover/mode_guided.cpp index a1d18cf92d006d..96ab7e15651d46 100644 --- a/Rover/mode_guided.cpp +++ b/Rover/mode_guided.cpp @@ -322,7 +322,9 @@ bool ModeGuided::set_desired_location(const Location &destination, Location next // handle guided specific initialisation and logging _guided_mode = SubMode::WP; send_notification = true; +#if HAL_LOGGING_ENABLED rover.Log_Write_GuidedTarget((uint8_t)_guided_mode, Vector3f(destination.lat, destination.lng, 0), Vector3f(g2.wp_nav.get_speed_max(), 0.0f, 0.0f)); +#endif return true; } @@ -338,8 +340,10 @@ void ModeGuided::set_desired_heading_and_speed(float yaw_angle_cd, float target_ _desired_speed = target_speed; have_attitude_target = true; +#if HAL_LOGGING_ENABLED // log new target rover.Log_Write_GuidedTarget((uint8_t)_guided_mode, Vector3f(_desired_yaw_cd, 0.0f, 0.0f), Vector3f(_desired_speed, 0.0f, 0.0f)); +#endif } void ModeGuided::set_desired_heading_delta_and_speed(float yaw_delta_cd, float target_speed) @@ -364,8 +368,10 @@ void ModeGuided::set_desired_turn_rate_and_speed(float turn_rate_cds, float targ _desired_speed = target_speed; have_attitude_target = true; +#if HAL_LOGGING_ENABLED // log new target rover.Log_Write_GuidedTarget((uint8_t)_guided_mode, Vector3f(_desired_yaw_rate_cds, 0.0f, 0.0f), Vector3f(_desired_speed, 0.0f, 0.0f)); +#endif } // set steering and throttle (both in the range -1 to +1) diff --git a/Rover/release-notes.txt b/Rover/release-notes.txt index 5cae4fdfc24358..af59caf5c2df9f 100644 --- a/Rover/release-notes.txt +++ b/Rover/release-notes.txt @@ -1,4 +1,28 @@ Rover Release Notes: +-------------------- + +Rover 4.5.0-beta2 14th February 2024 +Changes from 4.5.0-beta1: + +1) New Autopilots supported + - YJUAV_A6Ultra + - AnyLeaf H7 + +2) System level changes + - fixed float rounding issue in HAL_Linux millis and micros functions + - fixed loading of defaults.parm parameters for dynamic parameter subtrees + - fixed discrimination between GHST and CRSF protocols + - fixed bug in DroneCAN packet parsing for corrupt packets that could cause a crash + - fixed handling of network sockets in scripting when used after close + - fixed bit timing of CANFD buses + +3) Camera and gimbal enhancements + - wait for non-zero camera version in SIYI driver + +4) Miscellaneous + - do relay parameter conversion for parachute parameters if ever has been used + - broaden acceptance criteria for GPS yaw measurement for moving baseline yaw + ------------------------------------------------------------------ Rover 4.5.0-beta1 30-Jan-2025 Changes from 4.4.4 diff --git a/Rover/sensors.cpp b/Rover/sensors.cpp index 9153fd7e348c9e..aa9f7918912275 100644 --- a/Rover/sensors.cpp +++ b/Rover/sensors.cpp @@ -91,5 +91,7 @@ void Rover::update_wheel_encoder() void Rover::read_rangefinders(void) { rangefinder.update(); +#if HAL_LOGGING_ENABLED Log_Write_Depth(); +#endif } diff --git a/Rover/system.cpp b/Rover/system.cpp index 67f0a8ebdfcbb3..35e76c4d472bc7 100644 --- a/Rover/system.cpp +++ b/Rover/system.cpp @@ -44,10 +44,6 @@ void Rover::init_ardupilot() osd.init(); #endif -#if HAL_LOGGING_ENABLED - log_init(); -#endif - // initialise compass AP::compass().set_log_bit(MASK_LOG_COMPASS); AP::compass().init(); diff --git a/Tools/AP_Bootloader/AP_Bootloader.cpp b/Tools/AP_Bootloader/AP_Bootloader.cpp index da268f948f6249..b3b9caa5fdd07f 100644 --- a/Tools/AP_Bootloader/AP_Bootloader.cpp +++ b/Tools/AP_Bootloader/AP_Bootloader.cpp @@ -136,8 +136,9 @@ int main(void) } #endif // AP_CHECK_FIRMWARE_ENABLED #ifndef BOOTLOADER_DEV_LIST - else if (timeout != 0) { - // fast boot for good firmware + else if (timeout == HAL_BOOTLOADER_TIMEOUT) { + // fast boot for good firmware if we haven't been told to stay + // in bootloader try_boot = true; timeout = 1000; } diff --git a/Tools/AP_Periph/AP_Periph.cpp b/Tools/AP_Periph/AP_Periph.cpp index 8a08df7aed9fa6..b663855304b19e 100644 --- a/Tools/AP_Periph/AP_Periph.cpp +++ b/Tools/AP_Periph/AP_Periph.cpp @@ -62,9 +62,6 @@ void loop(void) static uint32_t start_ms; AP_Periph_FW::AP_Periph_FW() -#if HAL_LOGGING_ENABLED - : logger(g.log_bitmask) -#endif { if (_singleton != nullptr) { AP_HAL::panic("AP_Periph_FW must be singleton"); @@ -127,7 +124,7 @@ void AP_Periph_FW::init() #endif #if HAL_LOGGING_ENABLED - logger.Init(log_structure, ARRAY_SIZE(log_structure)); + logger.init(g.log_bitmask, log_structure, ARRAY_SIZE(log_structure)); #endif check_firmware_print(); diff --git a/Tools/AP_Periph/GCS_MAVLink.cpp b/Tools/AP_Periph/GCS_MAVLink.cpp index cb454786ac8dde..a3df4631fef872 100644 --- a/Tools/AP_Periph/GCS_MAVLink.cpp +++ b/Tools/AP_Periph/GCS_MAVLink.cpp @@ -32,8 +32,10 @@ static const ap_message STREAM_EXTENDED_STATUS_msgs[] = { MSG_MCU_STATUS, #endif MSG_MEMINFO, +#if AP_GPS_ENABLED MSG_GPS_RAW, MSG_GPS_RTK, +#endif }; static const ap_message STREAM_POSITION_msgs[] = { diff --git a/Tools/AP_Periph/can.cpp b/Tools/AP_Periph/can.cpp index 1c658463a6e84a..c985403fd282d3 100644 --- a/Tools/AP_Periph/can.cpp +++ b/Tools/AP_Periph/can.cpp @@ -434,7 +434,10 @@ void AP_Periph_FW::handle_allocation_response(CanardInstance* canard_instance, C // Copying the unique ID from the message uavcan_protocol_dynamic_node_id_Allocation msg; - uavcan_protocol_dynamic_node_id_Allocation_decode(transfer, &msg); + if (uavcan_protocol_dynamic_node_id_Allocation_decode(transfer, &msg)) { + // failed decode + return; + } // Obtaining the local unique ID uint8_t my_unique_id[sizeof(msg.unique_id.data)]; diff --git a/Tools/Frame_params/AION_R1_Rover.param b/Tools/Frame_params/AION_R1_Rover.param index 07b0a15d0309b4..e7c8de00a00521 100644 --- a/Tools/Frame_params/AION_R1_Rover.param +++ b/Tools/Frame_params/AION_R1_Rover.param @@ -1,72 +1,46 @@ -#NOTE: AION Robotics Params for Rover V3.2.0 +#NOTE: AION Robotics Params for Rover V4.5.0 (and higher) ACRO_TURN_RATE,120 -#most users will want manual capabilites on boot without the need for a GCS to arm -ARMING_REQUIRE,0 -#MIN 4S SOLO BATTERY -ARMING_VOLT_MIN,13 -ATC_ACCEL_MAX,2.0 -ATC_SPEED_P,0.2 -ATC_SPEED_I,0.2 -ATC_SPEED_D,0.0 -ATC_SPEED_FILT,10 -ATC_STR_ACC_MAX,180 -ATC_STR_ANG_P,2.5 -ATC_STR_RAT_FF,0.2 -ATC_STR_RAT_P,0.0 -ATC_STR_RAT_I,0.1 +ATC_ACCEL_MAX,0.75 +ATC_DECEL_MAX,1.5 +ATC_SPEED_P,0.5 +ATC_SPEED_I,0.5 +ATC_SPEED_D,0.018 +ATC_SPEED_FLTE,10 +ATC_STR_ACC_MAX,120 +ATC_STR_ANG_P,2 +ATC_STR_RAT_FF,0.25 +ATC_STR_RAT_P,0.13 +ATC_STR_RAT_I,0.13 ATC_STR_RAT_D,0.0 -ATC_STR_RAT_FILT,20 +ATC_STR_RAT_FLTD,2 +ATC_STR_RAT_FLTE,10 +ATC_STR_RAT_FLTT,2 ATC_STR_RAT_MAX,120 -#default aux ch to match documentation -AUX_CH,7 -#cube power brick - 4s solo battery - SMBus hardware side not yet supported -BATT_AMP_OFFSET,0 -BATT_AMP_PERVOLT,0.1 -BATT_CAPACITY,5200 -BATT_CURR_PIN,3 -BATT_LOW_TIMER,10 -BATT_LOW_TYPE,0 +ATC_TURN_MAX_G,0.3 BATT_MONITOR,4 -BATT_SERIAL_NUM,-1 -BATT_VOLT_MULT,13.99818 -BATT_VOLT_PIN,2 BRD_PWM_COUNT,2 -#default save waypoint -RC7_OPTION,1 +BRD_SAFETY_DEFLT,0 COMPASS_OFFS_MAX,2000 -#default use only first (hopefully external) compass COMPASS_USE,1 COMPASS_USE2,0 COMPASS_USE3,0 CRUISE_SPEED,1.0 CRUISE_THROTTLE,70 -EK2_YAW_M_NSE,0.7 -FS_CRASH_CHECK,1 -#default modes -MODE_CH,5 -MODE1,0 -MODE2,3 -MODE3,10 -MODE4,12 -NAVL1_PERIOD,6 -NAVL1_DAMPING,0.7 -NAVL1_XTRACK_I,0.02 -PIVOT_TURN_ANGLE,30 -#default telem radio -SERIAL1_BAUD,57 -SERIAL1_PROTOCOL,1 -#default APSync -SERIAL2_BAUD,921 -SERIAL2_PROTOCOL,1 -SERVO1_FUNCTION,74 +FRAME_CLASS,1 +FRAME_TYPE,0 +PSC_POS_P,0.2 +PSC_VEL_FLTD,5 +PSC_VEL_FLTE,5 +PSC_VEL_I,0 +PSC_VEL_P,1 +WP_PIVOT_ANGLE,60 +WP_PIVOT_RATE,60 +SERVO1_FUNCTION,73 SERVO1_MAX,2000 SERVO1_MIN,1000 -SERVO3_FUNCTION,73 +SERVO3_FUNCTION,74 SERVO3_MAX,2000 SERVO3_MIN,1000 -SPEED_TURN_GAIN,50 -ATC_TURN_MAX_G,0.3 -TURN_RADIUS,0.9 WENC_CPR,1120 WENC_PINA,55 WENC_PINB,54 @@ -83,3 +57,5 @@ WENC2_POS_Y,0.16 WENC2_POS_Z,0 WENC_RADIUS,0.0775 WENC2_TYPE,0 +WP_RADIUS,2 +WP_SPEED,1 diff --git a/Tools/Linux_HAL_Essentials/pru/aiopru/start_test b/Tools/Linux_HAL_Essentials/pru/aiopru/start_test index 437e267d03d40e..162ab16d1261ca 100755 --- a/Tools/Linux_HAL_Essentials/pru/aiopru/start_test +++ b/Tools/Linux_HAL_Essentials/pru/aiopru/start_test @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash #make debug #make test if [ ! -L /sys/class/gpio/gpio80 ] || [ ! -e /sys/class/gpio/gpio80 ] ; then diff --git a/Tools/Linux_HAL_Essentials/startup.sh b/Tools/Linux_HAL_Essentials/startup.sh index 82b3847f87fc7b..b5fd5f06071409 100755 --- a/Tools/Linux_HAL_Essentials/startup.sh +++ b/Tools/Linux_HAL_Essentials/startup.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash if [ "`echo $1`" = "load" ]; then echo "Loading Test_Capes..." diff --git a/Tools/Replay/Replay.cpp b/Tools/Replay/Replay.cpp index a55a33a799d1b3..d3dc5339798403 100644 --- a/Tools/Replay/Replay.cpp +++ b/Tools/Replay/Replay.cpp @@ -69,10 +69,6 @@ const AP_Param::Info ReplayVehicle::var_info[] = { // @Path: ../libraries/AP_Compass/AP_Compass.cpp GOBJECT(compass, "COMPASS_", Compass), - // @Group: LOG - // @Path: ../libraries/AP_Logger/AP_Logger.cpp - GOBJECT(logger, "LOG", AP_Logger), - // @Group: EK3_ // @Path: ../libraries/AP_NavEKF3/AP_NavEKF3.cpp GOBJECTN(ekf3, NavEKF3, "EK3_", NavEKF3), @@ -124,7 +120,6 @@ void ReplayVehicle::init_ardupilot(void) // message as a product of Replay), or the format understood in // the current code (if we do emit the message in the normal // places in the EKF, for example) - logger.Init(log_structure, 0); logger.set_force_log_disarmed(true); } diff --git a/Tools/Replay/Replay.h b/Tools/Replay/Replay.h index 623c1a4aa83b55..a153eab6659891 100644 --- a/Tools/Replay/Replay.h +++ b/Tools/Replay/Replay.h @@ -34,7 +34,7 @@ class ReplayVehicle : public AP_Vehicle { public: friend class Replay; - ReplayVehicle() { unused.set(-1); } + ReplayVehicle() { unused_log_bitmask.set(-1); } // HAL::Callbacks implementation. void load_parameters(void) override; void get_scheduler_tasks(const AP_Scheduler::Task *&tasks, @@ -50,16 +50,25 @@ class ReplayVehicle : public AP_Vehicle { AP_FixedWing aparm; - AP_Int32 unused; // logging is magic for Replay; this is unused + AP_Int32 unused_log_bitmask; // logging is magic for Replay; this is unused struct LogStructure log_structure[256] = { }; - AP_Logger logger{unused}; NavEKF2 ekf2; NavEKF3 ekf3; protected: +protected: + + const AP_Int32 &get_log_bitmask() override { return unused_log_bitmask; } + const struct LogStructure *get_log_structures() const override { + return log_structure; + } + uint8_t get_num_log_structures() const override { + return uint8_t(ARRAY_SIZE(log_structure)); + } + void init_ardupilot() override; private: @@ -82,7 +91,7 @@ class Replay : public AP_HAL::HAL::Callbacks { // return true if a user parameter of name is set bool check_user_param(const char *name); - + private: const char *filename; ReplayVehicle &_vehicle; diff --git a/Tools/Replay/plotit.sh b/Tools/Replay/plotit.sh index 59a2fea56f20d4..68bd9f1c7e6bf2 100755 --- a/Tools/Replay/plotit.sh +++ b/Tools/Replay/plotit.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash cmd="plot " echo $# diff --git a/Tools/UDP_Proxy/start_proxies.sh b/Tools/UDP_Proxy/start_proxies.sh index 4763d0cd92182e..3e8ef97671b6b5 100755 --- a/Tools/UDP_Proxy/start_proxies.sh +++ b/Tools/UDP_Proxy/start_proxies.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash # an example script that starts udpproxy for multiple ports under GNU # screen, allowing for unattended operation of the proxy for long # periods diff --git a/Tools/ardupilotwaf/dronecangen.py b/Tools/ardupilotwaf/dronecangen.py index f6e067da3ea237..1ba2a10941e54e 100644 --- a/Tools/ardupilotwaf/dronecangen.py +++ b/Tools/ardupilotwaf/dronecangen.py @@ -9,6 +9,7 @@ import os import os.path from xml.etree import ElementTree as et +import subprocess class dronecangen(Task.Task): """generate uavcan header files""" @@ -21,9 +22,10 @@ def run(self): src = self.env.get_flat('SRC') dsdlc = self.env.get_flat("DC_DSDL_COMPILER") - ret = self.exec_command(['{}'.format(python), - '{}'.format(dsdlc), - '-O{}'.format(out)] + [x.abspath() for x in self.inputs]) + cmd = ['{}'.format(python), + '{}'.format(dsdlc), + '-O{}'.format(out)] + [x.abspath() for x in self.inputs] + ret = self.exec_command(cmd) if ret != 0: # ignore if there was a signal to the interpreter rather # than a real error in the script. Some environments use a @@ -32,6 +34,9 @@ def run(self): Logs.warn('dronecangen crashed with code: {}'.format(ret)) ret = 0 else: + Logs.warn('dronecangen: cmd=%s ' % str(cmd)) + # re-run command with stdout visible to see errors + subprocess.call(cmd) Logs.error('dronecangen returned {} error code'.format(ret)) return ret diff --git a/Tools/autotest/run_in_terminal_window.sh b/Tools/autotest/run_in_terminal_window.sh index 7a83f1c565dacd..ac5c8e792dbcab 100755 --- a/Tools/autotest/run_in_terminal_window.sh +++ b/Tools/autotest/run_in_terminal_window.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash # Try to run a command in an appropriate type of terminal window # depending on whats available diff --git a/Tools/bootloaders/AR-F407SmartBat_bl.bin b/Tools/bootloaders/AR-F407SmartBat_bl.bin index 41d9182f704508..cf7061c74f640f 100755 Binary files a/Tools/bootloaders/AR-F407SmartBat_bl.bin and b/Tools/bootloaders/AR-F407SmartBat_bl.bin differ diff --git a/Tools/bootloaders/AR-F407SmartBat_bl.elf b/Tools/bootloaders/AR-F407SmartBat_bl.elf index 49212ab4543676..f527113d056bcb 100755 Binary files a/Tools/bootloaders/AR-F407SmartBat_bl.elf and b/Tools/bootloaders/AR-F407SmartBat_bl.elf differ diff --git a/Tools/bootloaders/AR-F407SmartBat_bl.hex b/Tools/bootloaders/AR-F407SmartBat_bl.hex index 5f4de701c613b2..5731dadd7704f9 100644 --- a/Tools/bootloaders/AR-F407SmartBat_bl.hex +++ b/Tools/bootloaders/AR-F407SmartBat_bl.hex @@ -1,1361 +1,1309 @@ :020000040800F2 -:1000000000070020F5040008F92B0008952B0008D4 -:10001000D52B0008952B0008B52B0008F704000825 -:10002000F7040008F7040008F7040008413F00083F -:10003000F7040008F7040008F7040008F7040008B4 -:10004000F7040008F7040008F7040008F7040008A4 -:10005000F7040008F7040008414E0008694E000844 -:10006000914E0008B94E0008E14E0008F704000860 -:10007000F7040008F7040008F7040008F704000874 -:10008000F7040008F7040008F7040008112B000823 -:100090003D2B0008692B0008F7040008094F0008F1 -:1000A000F7040008F7040008F7040008F704000844 -:1000B00005500008F7040008F7040008F7040008DA -:1000C000F7040008F7040008F7040008F704000824 -:1000D000F7040008F7040008F7040008F704000814 -:1000E0007D4F0008F7040008F7040008F704000833 -:1000F000F7040008F7040008F7040008F7040008F4 -:10010000F7040008F7040008F7040008F7040008E3 -:10011000F7040008F7040008F7040008F7040008D3 -:10012000F7040008F7040008F7040008F7040008C3 -:10013000F7040008F7040008F7040008F7040008B3 -:10014000F7040008F7040008F7040008F7040008A3 -:10015000F7040008F7040008F7040008F704000893 -:10016000F7040008F7040008F7040008F704000883 -:10017000F7040008F7040008F7040008F704000873 -:10018000F7040008F7040008F7040008F704000863 -:10019000F7040008F7040008F7040008F704000853 -:1001A000F7040008F7040008F7040008F704000843 -:1001B000F7040008F7040008F7040008F704000833 -:1001C000F7040008F7040008F7040008F704000823 -:1001D000F7040008F7040008F7040008F704000813 -:1001E000E51400080000000000000000000000000E -:1001F00053B94AB9002908BF00281CBF4FF0FF318E -:100200004FF0FF3000F074B9ADF1080C6DE904CE89 -:1002100000F006F8DDF804E0DDE9022304B07047E1 -:100220002DE9F047089D04468E46002B4DD18A42A9 -:10023000944669D9B2FA82F252B101FA02F3C2F1DC -:10024000200120FA01F10CFA02FC41EA030E94406D -:100250004FEA1C48210CBEFBF8F61FFA8CF708FB8E -:1002600016E341EA034306FB07F199420AD91CEB66 -:10027000030306F1FF3080F01F81994240F21C8198 -:10028000023E63445B1AA4B2B3FBF8F008FB1033E0 -:1002900044EA034400FB07F7A7420AD91CEB040415 -:1002A00000F1FF3380F00A81A74240F207816444E5 -:1002B000023840EA0640E41B00261DB1D44000236A -:1002C000C5E900433146BDE8F0878B4209D9002DCE -:1002D00000F0EF800026C5E9000130463146BDE858 -:1002E000F087B3FA83F6002E4AD18B4202D38242C2 -:1002F00000F2F980841A61EB030301209E46002D71 -:10030000E0D0C5E9004EDDE702B9FFDEB2FA82F2C5 -:10031000002A40F09280A1EB0C014FEA1C471FFA23 -:100320008CFE0126200CB1FBF7F307FB131140EA0A -:1003300001410EFB03F0884208D91CEB010103F1D7 -:10034000FF3802D2884200F2CB804346091AA4B299 -:10035000B1FBF7F007FB101144EA01440EFB00FE6D -:10036000A64508D91CEB040400F1FF3102D2A645D2 -:1003700000F2BB800846A4EB0E0440EA03409CE771 -:10038000C6F12007B34022FA07FC4CEA030C20FA1E -:1003900007F401FA06F31C43F9404FEA1C4900FA3E -:1003A00006F3B1FBF9F8200C1FFA8CFE09FB1811BB -:1003B00040EA014108FB0EF0884202FA06F20BD92E -:1003C0001CEB010108F1FF3A80F08880884240F27E -:1003D0008580A8F102086144091AA4B2B1FBF9F0C2 -:1003E00009FB101144EA014100FB0EFE8E4508D9BD -:1003F0001CEB010100F1FF346CD28E456AD9023842 -:10040000614440EA0840A0FB0294A1EB0E01A14226 -:10041000C846A64656D353D05DB1B3EB080261EB94 -:100420000E0101FA07F722FA06F3F1401F43C5E96E -:10043000007100263146BDE8F087C2F12003D840A4 -:100440000CFA02FC21FA03F3914001434FEA1C47E6 -:100450001FFA8CFEB3FBF7F007FB10360B0C43EAD8 -:10046000064300FB0EF69E4204FA02F408D91CEB88 -:10047000030300F1FF382FD29E422DD90238634486 -:100480009B1B89B2B3FBF7F607FB163341EA034126 -:1004900006FB0EF38B4208D91CEB010106F1FF3875 -:1004A00016D28B4214D9023E6144C91A46EA00466C -:1004B00038E72E46284605E70646E3E61846F8E6FE -:1004C0004B45A9D2B9EB020864EB0C0E0138A3E747 -:1004D0004646EAE7204694E74046D1E7D0467BE728 -:1004E000023B614432E7304609E76444023842E7A0 -:1004F000704700BF02E000F000F8FEE772B6374830 -:1005000080F30888364880F3098836483649086001 -:1005100040F20000CCF200004EF63471CEF2000141 -:100520000860BFF34F8FBFF36F8F40F20000C0F23F -:10053000F0004EF68851CEF200010860BFF34F8FF5 -:10054000BFF36F8F4FF00000E1EE100A4EF63C71E2 -:10055000CEF200010860062080F31488BFF36F8F8D -:1005600004F05EFA04F048FB4FF055301F491B4A77 -:1005700091423CBF41F8040BFAE71D49184A9142E9 -:100580003CBF41F8040BFAE71A491B4A1B4B9A423D -:100590003EBF51F8040B42F8040BF8E7002018495D -:1005A000184A91423CBF41F8040BFAE704F03CFAC8 -:1005B00004F028FB144C154DAC4203DA54F8041B2C -:1005C0008847F9E700F042F8114C124DAC4203DACB -:1005D00054F8041B8847F9E704F024BA0007002008 -:1005E000002300200000000808ED00E000010020CA -:1005F000000700206854000800230020802300200A -:1006000080230020684D0020E0010008E40100087C -:10061000E4010008E40100082DE9F04F2DED108AF7 -:10062000C1F80CD0C3689D46BDEC108ABDE8F08FC0 -:10063000002383F311882846A047002003F02EFEF4 -:10064000FEE703F091FD00DFFEE70000F8B500F0E3 -:1006500051FF04F079F9064604F0CEF90746A8B92F -:100660002B4B9E422DD001339E422DD026F0FF020F -:10067000284B9A4203D0054641F2883408E0F0B294 -:1006800000F034FE3D4642F2107401E005460024BD -:1006900000F032FE08B10024254601F0D7FAB0B9C7 -:1006A00014B14FF47A74012517B11B4B9E4214D13B -:1006B000002004F055F9ADB900F098FE00F01CFFE1 -:1006C00022E005460024E3E700240125E0E70320BB -:1006D00000F02CF800242546E6E704F085F9002414 -:1006E0002546E5E700F040F8E6E700F0D1FE4FF4DC -:1006F0007A7003F0DBFD002CF7D002F085FA401B86 -:10070000A042F2D900F030F802F07EFA0546F2E796 -:10071000010007B0000008B0263A09B0302383F387 -:100720001188854680F308880847704708B50C4B48 -:100730001870032806D8DFE800F00A06020E02202F -:1007400000F046FF08BD022000F038FFFAE7054B35 -:1007500000225A60F6E7034B00225A60F2E700BF1E -:10076000802300208423002008B501F06FFA03469F -:1007700068B9072B0FD89A0002F1006202F58032A7 -:100780001268B2F1FF3F05D00133DBB2F1E703207D -:10079000FFF7CCFF08BD174B5A68013B9A42F9D9C5 -:1007A000154B9B6803F1006303F580339A42F1D245 -:1007B00004F0ECF804F0FEF8002000F0B9FE02208E -:1007C000FFF7B4FF0D4B1A6C00221A64196E1A66FB -:1007D000196E596C5A64596E5A665B6E72B6054B47 -:1007E0004FF0E022C2F8083D59681868FFF796FFFD -:1007F000D0E700BF000001080023002000380240BD -:10080000094A136899B21B0C49F2690000FB0133D5 -:100810001360064B186882B2000C44F2506101FB71 -:100820000200186080B270471823002014230020B3 -:1008300010B50446FFF7E4FFB0FBF4F304FB13002C -:1008400080B210BD10B40346002202604260826094 -:10085000C260044C07CC186059609A605DF8044B84 -:10086000704700BF107AFF1F70B50E4614461D4634 -:1008700002F070FE60B9022D33D1012C01D00020AE -:1008800030E019A3D3E90023C6E90023012029E0C1 -:10089000282C1FD00CD8012C15D0052C06D114A360 -:1008A000D3E90023C6E9002301201BE0002019E062 -:1008B000302C06D110A3D3E90023C6E90023012080 -:1008C00010E000200EE00EA3D3E90023C6E90023C8 -:1008D000012007E00CA3D3E90023C6E9002301208F -:1008E00000E0002070BD00BF401DA12026812A0B22 -:1008F000F017304A39059E5678F6339F93CACD8D4E -:100900009E6AC421818A46EE26417272DF25D7B7DE -:1009100070B58AB006460D4602F076F904464FF4EB -:10092000C870FFF785FF044404F51674174B1C606C -:10093000EB7E23B9164B00221A700AB070BD05A9D0 -:10094000284600F087FF0028F7D101A8FFF77AFFBB -:100950009DF81640224601A90DF1170004F0E4FBB2 -:1009600048B90F2C0BD80A4B1C70084A1368A3F522 -:1009700016731360E1E7064B00221A70DDE79DF85D -:100980001410304602F0DEFDD7E700BFA033002090 -:100990009D3300202DE9F043ADF5517D80460E4694 -:1009A0000DF5E2790027719740F27512394672A869 -:1009B00000F02CFE0EAC4FF4C4723946204600F015 -:1009C00025FE02F021F92F4BA3FB003080092E4BAE -:1009D000186093E8070084E8070002232374677413 -:1009E0000DF15A00FFF72EFF042384F820306E2308 -:1009F00084F821300DF1180C244D0FCDACE80F0018 -:100A000095E80F00ACE80700ACF800301D2384F82F -:100A100032310DF1180CBCE80F00CDF86B01CDF8A8 -:100A20006F11CDF87321CDF87731BCE80700CDF810 -:100A30007B01CDF87F11CDF883219CF800308DF833 -:100A4000873101224946204600F034FE80B20590ED -:100A5000CDF810900397B37E029306F1190301932A -:100A60000123009305A3D3E90023F17E404602F061 -:100A700027FE0DF5517DBDE8F08300BF9E6AC421BD -:100A8000818A46EED34D62108C2300201452000858 -:100A9000F0B5FDB006460D462B4B1C7A6CBB07A982 -:100AA000284600F01BFF002845D19DF81D70C82F77 -:100AB00041D84FF4A6620021234800F0A7FD032C83 -:100AC0000AD82202204B4FF48A7101FB0433C3F889 -:100AD000E4200134E4B2F2E71B4C3A460DF11E016A -:100AE00004F1090000F07EFDE219002353729DF825 -:100AF0001C3023720BB9EA7E2272812200213AA8AF -:100B000000F084FD5BAC012221463AA800F022FFF0 -:100B100080B20590049400230393AB7E029305F109 -:100B2000190301932823009305A3D3E90023E97E49 -:100B3000304602F0C5FD7DB0F0BD00BFAFF30080D0 -:100B400026417272DF25D7B7A8440020134BB3F8B3 -:100B50002C35834200D9704710B50446002100F0BF -:100B600011FD01340D4BA3F82C450C4BB3F82C05AB -:100B700000F0ECFC88B1094BB3F82C0500F0F8FC50 -:100B800058B9064C0021B4F82C0500F0FBFCB4F871 -:100B90002C350133A4F82C35E7E710BDA84400201C -:100BA0002DE9F041F0B00646274C94F8D8304FF4C8 -:100BB0008A7505FB004585F8DC30002785F8E8706C -:100BC000D82239463AA800F021FD04F10908404630 -:100BD00000F012FDC2B28DF8F020D5F8E4303A935F -:100BE0003B9741460DF1F10000F0FCFC06AD0122FF -:100BF00029463AA800F0D8FE80B20590049501235A -:100C000003930823029304F1D80301933023009344 -:100C10000BA3D3E90023217A0C4802F051FDB8421E -:100C200003DC002070B0BDE8F08101F0EDFF4FF46F -:100C30008A7202FB0646C6F8E0000120F2E700BF18 -:100C400078F6339F93CACD8DA8440020A4330020AA -:100C500038B501F0D9FF0546002408E00532B3EBB2 -:100C6000420F02D3FFF79CFFF8B10134E4B2032C2A -:100C70001BD80E4B93F8D900204400F003004FF42A -:100C80008A7202FB003393F8E830002BEDD1074B5A -:100C900002FB0033D3F8E030002BE3D0EB1A034A19 -:100CA0001268F92ADAD8FA22D8E738BDA844002019 -:100CB000F0B58FB000230A938DF834308DF83530BD -:100CC0000B930C9300242746002C46D101238DF86A -:100CD0000C3000238DF80D3041F2D00204FB02F2FB -:100CE000204955185258966800200021CDE900018E -:100CF0000DF10D0203A92846B0479DF80C604EB3D4 -:100D0000194A536983F48053536100230693079370 -:100D10000893099341F2D00304FB03F3114AD3581B -:100D20005F690DF10E0304AA0AA92846B84707AB6C -:100D30000BAA92E8030083E803009DF834308DF895 -:100D400024300A9B0693DDE9042306A9074802F034 -:100D5000BFFE37460134E4B2B6E7002FB2D10FB080 -:100D6000F0BD00BFD833002000080240A4330020AB -:100D700010B58CB0264802F0EDFB08B10CB010BDE8 -:100D800001F042FF234B1B689842F7D301F03CFF70 -:100D900004464FF4C870FFF74BFD044404F5167485 -:100DA0001C4B1C6000238DF828301B4B1B7813B99B -:100DB00001238DF8283006A8FFF744FD164B19785B -:100DC000C1F11004E4B2062C00D90624224606AB79 -:100DD00019440DF1290000F005FC013404940AAB1C -:100DE0000393182302930D4B01930123009306A351 -:100DF000D3E90023064802F003FC074B00221A70D7 -:100E0000BCE700BFAFF30080401DA12026812A0B64 -:100E1000A4330020A03300209D3300209C33002009 -:100E200010B588B001F0F0FE114BA3FB00239B0925 -:100E30001048036006AC0122214600F0E3FC80B2BA -:100E400004900394182302930B4B019340F2551323 -:100E5000009305A3D3E90023084802F0D1FB08B0B2 -:100E600010BD00BFAFF30080F1C6A7C1D068080F66 -:100E7000D34D62108C230020DC490020A4330020D5 -:100E800010B502460B46094C204602F051FC2046A4 -:100E900002F060FB38B1064B1B7A2BB10322054BE5 -:100EA0005A71FFF7BDFF10BD0222F8E7A4330020FE -:100EB000A84400208C230020012800D0704738B5BA -:100EC0004FF6FF73994200D038BD0025084C002D25 -:100ED00007DB204601F0C2F904F586541034013DC9 -:100EE000F5E7044A0449002004F0CEF8ECE700BF1F -:100EF000D8330020184A0020FD0E000838B50F4CEA -:100F00000F4B9C4219D0A4F58653A3F110040D4A4F -:100F100043F8102C41F25C03E21812793AB9E55813 -:100F20002DB1284600F0A0FE284604F0B3F804F5E1 -:100F30008250083000F098FEE2E738BDA844002057 -:100F4000D833002074520008F0B587B0254802F06D -:100F5000E3FB002839D00446002302938DF81430B7 -:100F60008DF8153003930493027B8DF8142003AAA7 -:100F70004068A16803C2226842F0004202921D4606 -:100F80001C46D5B941F2D00305FB03F3164A9E185F -:100F90009B581F6901F03CFE144A82184FF0000371 -:100FA000009341F1000302A93046B8470028C8BFAA -:100FB00044F001040135EDB2E3E744B90C4B1B7872 -:100FC000072B0BD801330A4A137007B0F0BD054850 -:100FD00002F0A6FB064B00221A70B7E7014802F0A8 -:100FE0009FFBF2E7A4330020D833002040420F00DB -:100FF000DD490020CA7E9B4B1B7A9A4240F031812A -:101000002DE9F04700AF08460024032C0CD8954B7F -:101010004FF48A7202FB043393F8DC20437E9A4239 -:1010200007D00134E4B2F0E7002323B9BD46BDE8A0 -:10103000F0870123F9E74FF48A7104FB01F1E031F5 -:10104000884B19440A3100F0DBFC0028EED1854BB7 -:101050004FF48A7202FB0434012384F8E83001F073 -:10106000D3FDD4F8E030C31A192B05D940F6B832B5 -:10107000934202D9134600E019237A4AD2ED007A4E -:10108000F8EE677A9FED787A27EE877A07EE903A46 -:10109000F8EE677ADFED756A67EEA67A77EE277A63 -:1010A000FCEEE77AC2ED007A3CE013464FF48A7218 -:1010B00002FB0535002385F8E830C5F8E030C54669 -:1010C000684B5B689B0A0133694A1381AEE70020D5 -:1010D00042F8040B013B002BF9DA2246304600F0BF -:1010E00081FA604B5B68002B4BD05E4B93F8D200CB -:1010F00000F02CFA8246002847D05A4BD3F8D4305F -:10110000002B4ED0574BD3F8D430234453454ED800 -:101110005FFA89F23146534B586800F081FA002893 -:101120004CD1C5464F4B93F8D9504FF48A7202FB0D -:10113000053393F8E830002BC2D0E846494A4FF413 -:101140008A7303FB0523D3F8E41053689942ACD1AA -:1011500044494FF48A7305FB03F3CA18B2F8EC4014 -:10116000E21C4FEA9209E03319440E314A4609F174 -:10117000FF3392000732D208A8EBC20295466E46B2 -:10118000A9E7012000F0D4F9AFE70024354B1C7229 -:1011900000F002FA204600F0CBF9354B0B221A8101 -:1011A0008DE7304B93F8D200FFF7D0FCAAE72D4B28 -:1011B00093F8D2000130FFF7C9FCA9E7294B5A6820 -:1011C00022445A60D3F8D4602644C3F8D46093F81C -:1011D000D20000F0BBF986420BD3224B93F8D22009 -:1011E000013283F8D220D3F8D420A2EB0A02C3F84C -:1011F000D420FF2C23D91B4C4FF48A7303FB0545E5 -:10120000002385F8E830C5F8E030D5F8E43003F580 -:101210008063C5F8E43094F8D900FFF7C1FCFFF70C -:1012200093FE94F8D93001335A4203F0030302F0DD -:10123000030258BF534284F8D930C54672E70024F0 -:10124000084B1C7200F0A8F9204600F071F900F07C -:10125000FDFC074A108108B1C546E7E6FFF784FAAE -:10126000FAE77047A84400206666663FCDCCCC3DC7 -:101270008C23002038B505460C4602F06BF950B1BE -:10128000E38A282B1CD014D8012B0FD121462846E5 -:10129000FFF780FB0CE0237E022B09D1E38A012BB0 -:1012A00006D121462846FFF733FB01E0052B0CD081 -:1012B00038BD302BFCD121462846FFF79BFEF7E7CF -:1012C00021462846FFF7E4FBF2E7BFF34F8F0549BD -:1012D000CA6802F4E062044B1343CB60BFF34F8F44 -:1012E00000BFFDE700ED00E00400FA05014B1870B7 -:1012F000704700BF9823002030B585B04FF00053F1 -:101300001A68324B9A420FD003F080FB044678B340 -:101310002F4A136C43F0007313642E4B9A6D2E4BBF -:101320009A4228D0002423E04FF00054607DFFF75C -:10133000DDFF227D294B1A72002309E01902274A9A -:101340004FF48A7000FB0322C2F8E4100133DBB2D1 -:10135000032BF3D94FF00054C92204F116012048A1 -:1013600000F040F9E0220021204600F04FF901246E -:10137000204605B030BD174B1B6E23B37F2B01D920 -:101380000024F5E7174A01AB10685168926807C35B -:10139000032101A800F08AFB0E4B5B6D984201D03F -:1013A0000024E5E70B4B1B6D994201D00024DFE7D9 -:1013B000084D0023AB6595F86000FFF797FFEA6DD5 -:1013C000094B1A60D4E70024D2E700BF9AAD44C5A8 -:1013D00000380240006600405041A0B0A844002000 -:1013E000B1440020586600401023002030B583B07F -:1013F00000F02CFC1D4B188102225A71002474B994 -:1014000041F2D00304FB03F319481A58556801222E -:10141000184909681844A8470134E4B2EFE70023EB -:101420000193154B0093154B4FF480521449154806 -:1014300002F06CF8144B197899B901F0E5FB0446F9 -:101440004FF4C870FFF7F4F9044404F516740F4B19 -:101450001C6003F0D1FA10B1044B0F221A8103B0C3 -:1014600030BD084802F06EF8E7E700BF8C2300208B -:10147000D8330020102300206908000875120008E6 -:101480009C230020A433002098230020A0330020B8 -:1014900008B50CE0114B186001F0BAFBFFF7F0FC47 -:1014A00013E0C82002F002FF0D4B1B7AA3B1FFF737 -:1014B0004BFDFFF7FDFBFFF75BFC01F0A5FB074BC6 -:1014C0001B68C31AB3F57A7FE4D2054B1B7A002B55 -:1014D000E7D0FFF7BDFBE4E708BD00BFD849002017 -:1014E000A844002008B54FF6FF710120FFF7E4FC87 -:1014F00008BD00BF704700BF10B503F0F9F80A4BF4 -:101500001880002406E003F0C9F80444074A136871 -:1015100001331360B4F5803F05D2034B1B88034AA7 -:1015200010688342EFD810BD0C4A0020E04900202B -:1015300008B503F037F908BD08B5920000F1006066 -:1015400000F5803003F02AF908BD00BF08B5064B4E -:101550001B88064A12689B1A834201D8002008BDE6 -:10156000104403F09BF8FAE70C4A0020E049002001 -:1015700008B5034B1B68184403F0BCF808BD00BF56 -:10158000E049002008B5034B1B68184403F0CAF873 -:1015900008BD00BFE049002008B5074B93F8243090 -:1015A0000BB9012008BD0449002381F8243008222A -:1015B000086AFFF7C1FFF5E7E4490020022800D0E0 -:1015C0007047024B4FF080529A61F9E700080240E1 -:1015D000022800D07047024B4FF480529A61F9E71D -:1015E00000080240002304E011F803C000F803C023 -:1015F00001339342F8D370470346002000E00130E6 -:1016000013F9012B002AFAD1704700BF034602E00C -:1016100003F8011B624602F1FF3C002AF8D1704733 -:101620002DE9F843814688461546214B93F824302E -:1016300033B31F4A126A02EB8303834220D0FFF7C1 -:10164000ABFF0346E0B930E0194E96F82400C0F134 -:101650000804AC4228BF2C46E4B2A7003A464146F3 -:1016600006EB8000FFF7BEFFB944B8442D1BEDB276 -:1016700096F824301C44E4B286F82440082C0DD09F -:1016800095B10B4B93F82430002BDDD10848C0F8FE -:1016900020902022FF21FFF7B9FFD5E7FFF77CFF5D -:1016A00003460028ECD100E001231846BDE8F8838A -:1016B000E44900202DE9F84380460E46914640F269 -:1016C000791200213046FFF7A1FF43462022002176 -:1016D000304602F079F908F1040302222021304655 -:1016E00002F072F908F1050303222221304602F0CC -:1016F0006BF908F1060303222521304602F064F954 -:1017000008F1080310222821304602F05DF908F1A3 -:10171000100308223821304602F056F908F111036F -:1017200008224021304602F04FF908F11203082246 -:101730004821304602F048F908F1140320225021D4 -:10174000304602F041F908F118034022702130467A -:1017500002F03AF908F120073B460822B021304652 -:1017600002F032F908F121030822B821304602F0D4 -:101770002BF9C025002408E03B1902330822294632 -:10178000304602F021F9083501340F2CF4D907F165 -:10179000120308222946304602F016F905F1080422 -:1017A0000025BB7C9D420BD205F110033B44033363 -:1017B00008222146304602F007F908340135F0E7E7 -:1017C000B9F1000F10D0002598F832319D4214D2A3 -:1017D00005F598734344033308222146304602F04E -:1017E000F3F808340135EFE708F59973072221462D -:1017F000304602F0E9F80734E5E7E01DC008BDE82F -:10180000F88300BF38B505460C4600212160C4F8B6 -:10181000031003462022204602F0D6F82B1D022298 -:101820002021204602F0D0F86B1D03222221204601 -:1018300002F0CAF8AB1D03222521204602F0C4F8AD -:1018400005F1080310222821204602F0BDF80720E8 -:1018500038BD00BFF0B583B007460E46047F009147 -:1018600000230722194601F0ADFF731C00930023EB -:1018700001220721384601F0A5FF3CB1BB8ADB00FD -:10188000083BDB08B3700825002414E0B31C009368 -:10189000002305220821384601F094FF0D25F3E7C7 -:1018A000331903330093002308222946384601F0F8 -:1018B00089FF08350134B3789C42F1D30735ED0830 -:1018C0003B7F2BB1B88A401B18BF012003B0F0BD8D -:1018D000B88AA8422CBF00200120F7E7F0B583B0FA -:1018E00007460C46057F009100230822194601F0A7 -:1018F00069FF661C3DB1BB8ADB00083BDB086370F7 -:101900000825002413E000960023082211463846DB -:1019100001F058FF1025F4E7331901330093002339 -:1019200008222946384601F04DFF08350134337846 -:101930009C42F1D30735ED083B7F2BB1B88A401BA1 -:1019400018BF012003B0F0BDB88AA8422CBF002008 -:101950000120F7E7F8B506460F461446812200211C -:101960003846FFF753FE334608220021384602F07E -:101970002BF814B10825002410E0731C072208215D -:10198000384602F021F80F25F5E733190233082213 -:101990002946384602F018F80835013473789C421D -:1019A000F3D3E81DC008F8BDF8B506460F46144647 -:1019B000CE2200213846FFF729FE33462822002197 -:1019C000384602F001F8083614B12825002410E04A -:1019D000334608222821384601F0F6FF3025F5E786 -:1019E0003319013308222946384601F0EDFF083546 -:1019F000013433789C42F3D3E81DC008F8BD00BF22 -:101A0000F0B583B007460E46047F009101231022F3 -:101A1000002101F0D7FE3CB1BB8ADB00103BDB08A4 -:101A200073801025002414E0B31C009300230922C6 -:101A30001021384601F0C6FE1925F3E733190433A7 -:101A40000093002308222946384601F0BBFE0835E2 -:101A5000013473889C42F1D30735ED083B7F2BB1ED -:101A6000B88A401B18BF012003B0F0BDB88AA84255 -:101A70002CBF00200120F7E700B58E460AE040F3B6 -:101A8000000C09490CEA010181EA50000133DBB284 -:101A9000072BF4D91346013A23B11EF8013B5840F5 -:101AA0000023F5E75DF804FB2083B8ED30B583B083 -:101AB00004460B464FF0FF30014620E00018494134 -:101AC0000133DBB2072B0BD80029F7DA10EB000C3F -:101AD00041EB010210488CEA000010495140EFE749 -:101AE0000EF1010E5FFA8EFEBEF1030F06D801ABB8 -:101AF00013F80E3081EA03610023E3E72B465D1EF5 -:101B0000ADB22BB154F8043B01934FF0000EEBE75C -:101B1000C043C94303B030BD9336EAA9EBE1F042BC -:101B2000F0B583B01F4B6A4693E8030082E80300D8 -:101B300008231D491D4803F007FB30B30446036921 -:101B4000B3F5702F23D8418B40F26E42914220D1E1 -:101B500000F11807164A024402F110018B421BD310 -:101B60009B1AA3F1100511490020FFF785FF0646D7 -:101B70002A4639460020FFF77FFFA368B3420DD104 -:101B8000E36883420CD1002004E00A2002E00B202D -:101B900000E00C2003B0F0BD1020FBE70D20F9E7BA -:101BA0000D20F7E734520008DCFF0E0000000108AA -:101BB0000800FFF7F0B583B0204B6A4693E80300B6 -:101BC00082E8030008231E491E4803F0BDFA38B31B -:101BD00004460369B3F5702F24D8B0F8661040F2BC -:101BE0006E42914220D100F16407174A024402F18B -:101BF0005C018B421BD39B1AA3F15C0511490020A9 -:101C0000FFF73AFF06462A4639460020FFF734FF21 -:101C1000A368B3420DD1E36883420CD1002004E0F5 -:101C20000A2002E00B2000E00C2003B0F0BD1020E1 -:101C3000FBE70D20F9E70D20F7E700BF4052000851 -:101C400090FF0E00000001080800FFF710B5FFF735 -:101C500067FF044608B9204610BDFFF7ABFF002818 -:101C6000F9D10446F7E700BF10B50446037C0BB179 -:101C7000204610BD006803F04FFAF9E7BFF35B8F11 -:101C8000C368BFF35B8FBFF35B8F8268BFF35B8F6B -:101C90009A4208D94268BFF35B8F8068BFF35B8FBD -:101CA000101A18447047BFF35B8F8068BFF35B8FD7 -:101CB000181A7047BFF35B8F0023C360BFF35B8FBD -:101CC000BFF35B8F8360BFF35B8F70470346406851 -:101CD00000B97047BFF35B8F9A68BFF35B8FBFF3A8 -:101CE0005B8FD968BFF35B8F914209D35868BFF30C -:101CF0005B8FDB68BFF35B8FD21A013A1044E8E7D1 -:101D00000020F4E738B505460C46FFF7B7FFA042C0 -:101D100001D2002038BDBFF35B8FA968BFF35B8F92 -:101D20000C446968B4FBF1F301FB1344BFF35B8F10 -:101D3000AC60BFF35B8F0120ECE700BF70B50446D9 -:101D40000E461546FFF7C2FFA84200D3284608B941 -:101D5000002070BD2368BFF35B8FE268BFF35B8F29 -:101D6000134433606268BFF35B8FE368BFF35B8F3C -:101D7000D11A884207D971602168B1609B1A184452 -:101D8000F0600220E5E770600120E2E738B5054623 -:101D90000C46FFF79BFFA04201D2002038BDBFF3E5 -:101DA0005B8FE968BFF35B8F0C446968B4FBF1F3A8 -:101DB00001FB1344BFF35B8FEC60BFF35B8F01202B -:101DC000ECE700BF2DE9F04385B0814688466946BF -:101DD000FFF7B4FF0746002425460EE004AB03EBF3 -:101DE000C40656F80C2C08EB050156F8100CFFF74A -:101DF000F9FB56F80C3C1D440134A742EEDC2946A1 -:101E00004846FFF7C3FF284605B0BDE8F08300BF92 -:101E1000BFF35B8FC368BFF35B8FBFF35B8F8268D9 -:101E2000BFF35B8F9A4210D94368BFF35B8F826820 -:101E3000BFF35B8F9B1A0B6073B10368BFF35B8FBB -:101E40008068BFF35B8F18447047BFF35B8F826875 -:101E5000BFF35B8F9B1AEEE700207047F0B583B0AD -:101E600007460E461546FFF709FF04460190A842B3 -:101E700000D32C4614B9002003B0F0BD01A93846A8 -:101E8000FFF7C6FF019B6BB1A34200D901943060FC -:101E900001987060A0420DD23B68B360241AF460D0 -:101EA0000220E9E73B68336074600023B360F360AD -:101EB0000120E1E70120DFE72DE9F04184B0884609 -:101EC0006946FFF7CBFF0746002425460EE004AB2A -:101ED00003EBC40656F80C2C56F8101C08EB050052 -:101EE000FFF780FB56F80C3C1D440134A742EEDCA2 -:101EF000284604B0BDE8F08138B50546FFF7DCFFA1 -:101F0000044601462846FFF7FDFE204638BD00BFC7 -:101F100010B5026854681A46A04710BD01207047EA -:101F20000020704700207047704700BF00207047B6 -:101F30000E20704700F5805090F8C800C0F34000B4 -:101F4000704700BF00F5805090F9C900704700BF8E -:101F5000F0B583B0BDF820500C6814F0005F40F07D -:101F60008C800C7B082C00F28B80302484F3118849 -:101F700062B64469A66816F0806F0FD1A66816F0A5 -:101F8000006F6DD1A66816F0805F02D04FF0020E90 -:101F900006E0002080F3118862B65FE04FF0000E8B -:101FA000F4460E68002E5EDB76050EF1180E4FEA41 -:101FB0000E1E44F80E600E6816F0804F06D00CF12D -:101FC00018063601A75947F00207A7510F7B0CF1FD -:101FD00018064FEA061E04EB061677608E6804EBBF -:101FE0000C17C7F88C614E68C7F8886154F80E600A -:101FF00046F0010644F80E6041F2680E0EEB4C14F8 -:10200000044400EB4C16764432607360D1F800E073 -:102010004F688E68C4F808E0E76026618E89A68262 -:102020000CF1840C00EB4C1C9CF8044065F300049C -:102030008CF80440C5F34006E4B266F341048CF822 -:102040000440E4B26FF3C3048CF80440002484F32A -:10205000118862B6009500F00FFE012003B0F0BDBC -:102060004FF0010E9CE7F60046F004060EF1180E44 -:102070004FEA0E1E44F80E609DE74FF0FF30EDE78B -:102080004FF0FF30EAE700BF08B5302383F3118833 -:1020900062B600F58050C06DFFF70CFE002383F39D -:1020A000118862B608BD00BF70B504460D4641F206 -:1020B0005C068059FFF70AFE1F2801D8002070BD7A -:1020C00020222946A059FFF77DFE202814BF0020BA -:1020D0000120F4E72DE9F04188B006460D46174689 -:1020E0009846302383F3118862B600220023CDE99D -:1020F00000230024ADF8084003948DF818408DF8B3 -:1021000019400494059441F25C040059FFF7B6FDB0 -:102110001F2807D8002078B980F3118862B608B06C -:10212000BDE8F081202269463059FFF7E5FE2028FE -:1021300014BF00200120EEE703AB07CB28606960E5 -:10214000AA601B88AB81DDE90023C7E90023BDF845 -:102150000830A8F80030002383F3118862B64346A4 -:102160003A462946304600F05FFDD8E710B5374BB8 -:1021700003600023436083600246354C42F8184BED -:10218000836113735373C36103629FED2E7B80EDF4 -:102190000A7B0386436380F8403080F841308363D4 -:1021A000C36300F1480423464FF07F0C0DE09FED20 -:1021B000257B83ED007B00221A81DA601A765A763D -:1021C0001A615A6120330CF1FF3CBCF1000FEEDACA -:1021D00000F58252083200F580539C644FF480541D -:1021E000DC6400241C655C654FF0010C83F858C06A -:1021F000DA6583F860C000F5835308334FF0020EB0 -:10220000BEF1000F11DB9C469FED0E7BACEC027B18 -:1022100000229A608CF80C208CF80D20DA601A618C -:102220009A6120330EF1FF3EEAE700F5805383F810 -:10223000C91011B9074B436110BD074800F0DEFC1F -:10224000AFF300800000000000000000BC52000856 -:1022500074520008006400404C52000810B5044657 -:10226000034B19784A1C1A70FFF780FF204610BDF7 -:10227000144A0020002977D070B582B00C46424B3A -:10228000994211D90A234149B1FBF4FC013BDBB26D -:102290009E46581CBCFBF0F100FB11C131B1022B72 -:1022A00064D9013BDBB2F3E71123ECE7BCFBF0F0B0 -:1022B000411EB1F5806F5CD2C3EBC30E1EF103016A -:1022C0004DD4C1F3C70C8DF800C0A3EB0C05EDB2E3 -:1022D0008DF801500CF101064FF47A710CFB0111DD -:1022E000354491FBF5F189B2ADF80210B1F5617F8B -:1022F00018D9BEF1010E34D4CEF3C70E8DF804E028 -:10230000A3EB0E03DBB28DF805300EF101054FF49F -:102310007A710EFB01112B4491FBF3F3ADF80630FB -:10232000019B00939DF800104B1C9DF80160334405 -:1023300000FB03F3154DB5FBF3F3A3421BD10139A9 -:10234000C9B20F2919D8D6B1082E1AD80138108071 -:1023500000239370D170013E1671012007E0073110 -:10236000AFE70EF1070EC7E700207047002002B06C -:1023700070BD0020FBE70020F9E70020F7E7002010 -:10238000F5E70020F3E700BF3F420F0080DE800248 -:1023900070B506460D460024B4F57A7F0BD27369FA -:1023A0005B6803F00103AB4207D04FF47A7001F091 -:1023B0007DFF0134F0E7002000E0012070BD00BF88 -:1023C000032964D870B588B004460D46164600F55A -:1023D000805393F8C830C3F3800113F0040F00D189 -:1023E000114604F5805393F8C82061F3820283F804 -:1023F000C82041F2680303EB451304EB030C05F11D -:10240000840304EB43131B7913F0010F08D03EB192 -:1024100005F1840304EB43131B7913F0080F10D06C -:102420006EB105F1840304EB43131B7913F0080F1D -:1024300005D1843504EB451443F00803237108B03B -:1024400070BD00220023CDE900230023ADF8083041 -:1024500003938DF818308DF819300493059303AB6E -:10246000DCF80800DCF80C10DCF8102007C3BCF81E -:1024700014201A80DDE90C23CDE900230123ADF8F7 -:1024800008302368DB6B694620469847C8E77047E9 -:102490004269936913F0700F23D00023936100E029 -:1024A0000133022B1DDC03F1840200EB421212798E -:1024B00012F0040FF4D003F1840200EB42121279FF -:1024C00012F0020FECD04269064951F823109160D6 -:1024D00003F1840200EB4212117941F00401117101 -:1024E000DEE770476052000870B582B004461646B9 -:1024F0001D4643699A6812F0010F0ED163699A680C -:1025000012F4807F14D163699A6812F4803F1CD161 -:102510002046FFF7BDFF02B070BD9A6801219960A7 -:1025200000960195C2F340020021FFF749FFE5E75D -:102530009A684FF48071996000960195C2F3402229 -:1025400001212046FFF73CFFDDE79A684FF4803118 -:10255000996000960195C2F3404202212046FFF7A0 -:102560002FFFD5E738B504460846002971D16169C7 -:1025700001F10C0CDCF8001011F0030F68D0DCF84E -:102580000010616900F11B052D014D5915F0040F74 -:1025900063D100F11B052D014D596D0DA56100F1B1 -:1025A0001B052D014D5915F0020F03D0A56945F00B -:1025B0008045A56100F11B0501EB05156D6805F06F -:1025C0000F0E84F824E001EB0011D1F8B801207758 -:1025D000D1F8B801000A6077D1F8B801000CA077F3 -:1025E000D1F8B801000EE077D1F8BC0184F82000E2 -:1025F000D1F8BC01000A84F82100D1F8BC01000C1C -:1026000084F82200D1F8BC11090E84F82310382177 -:10261000CCF80010A569E069216A6563A063E163F5 -:10262000A18CA4F84010A262E362002323862368F1 -:10263000DB6B04F128012046984704F5805292F89C -:10264000C83043F0040382F8C8302046FFF720FF6B -:1026500038BD616901F1100C8CE700F11B052D01FB -:102660004D59ED08A56145F00045A56197E700BF0C -:10267000302181F3118862B60021022937DC30B5A0 -:1026800002E0013102292DDC01F1840C00EB4C1C2D -:102690009CF804C01CF0040FF3D101F1840C00EB92 -:1026A0004C1C9CF804C01CF0100FEAD000EB411E3B -:1026B00041F2680C0EEB0C045EF80C506468954215 -:1026C0009C41DED244690C4D55F82150A56001F1C2 -:1026D000840C00EB4C1C9CF804E04EF0040E8CF8CB -:1026E00004E0CEE7002383F3118862B630BD0023F7 -:1026F00083F3118862B670476052000808B5302332 -:1027000083F3118862B6FFF7C3FE002383F31188B9 -:1027100062B608BD43699B6803F0E053B3F1E05F24 -:102720002DD070B505460E465BB3302383F3118878 -:1027300062B6002400E00134022C1ADC04F18403A8 -:1027400005EB43131B7913F0080FF4D104F1840354 -:1027500005EB43131B7913F0040FECD141F2700128 -:1027600001EB44112944304600F0C4FA0028E2D1BC -:1027700000E00120002383F3118862B670BD0120C0 -:1027800070470020FAE700BF08B5302383F31188B3 -:1027900062B600F58050C06DFFF770FA002383F336 -:1027A000118862B61F288CBF0020012008BD00BF21 -:1027B000F8B507460E4614461D4600231370FFF772 -:1027C000E3FF80F00103337025B129463846FFF757 -:1027D000A1FF2070F8BD00BFF8B504460D461646AF -:1027E0001F4600F015FA02460B46297809B93078E1 -:1027F00060B12046FFF73CFF2046FFF77FFF3B46D6 -:10280000324629462046FFF7D3FF0120F8BD00BF1E -:10281000302383F3118862B61C4B1A6C42F00072AD -:102820001A641A6A42F000721A621A6A22F000727E -:102830001A62002383F3118862B600F5805393F87F -:10284000C83013F0010F20D110B5044601B910BDF6 -:10285000302383F3118862B60321132001F0D0FBEB -:102860000321142001F0CCFB0321152001F0C8FB4B -:1028700004F5805494F8C83043F0010384F8C8305C -:10288000002383F3118862B6E1E770470038024005 -:1028900000F5805393F8C930012B00F233812DE904 -:1028A000F0418AB004460E461746984A52F8232053 -:1028B000002A38D0E6602774944B1B68002B36D072 -:1028C00004F5805393F8C930012B06D18F4B18685B -:1028D00003681B6B9847002838D001212046FFF77A -:1028E00097FF302383F3118862B66269136823F07F -:1028F000020313606269136843F0010313606269A5 -:102900000023536183F3118862B601212046FFF74B -:102910003FFD034648BB62694FF400411160184611 -:102920000AB0BDE8F081794A42F82300C2E741F2DB -:10293000D00002F0B1FB054610B10021FFF716FCF4 -:10294000724B1D60002DBBD10023E8E76F4D0021C5 -:102950002868FFF75DFF286803685B683A463146E0 -:10296000984703460028B8D1D9E704F58053D86DBD -:10297000FFF7A0F94FF000082BE020220021684665 -:10298000FEF744FE002302938DF814308DF81530C5 -:1029900003930493069341F2680505EB481504EB95 -:1029A000050EEC46BCE80F006051CEF80410CEF8DE -:1029B0000820CEF80C30BCE80700CEF81000CEF8A6 -:1029C0001410CEF818209CF800308EF81C3008F156 -:1029D0000108B8F1020FD0D904F5805393F8C8204C -:1029E0006FF3820283F8C8200023ADF820308DF801 -:1029F00022308DF823308DF8243008AA3146204645 -:102A0000FFF738FC034600286FD0636961221A6023 -:102A10009DF822301B0603F040739DF8232012041A -:102A200002F4702213439DF82420120502F4E00200 -:102A30001343BDF82020C2F309021343022F59D0DB -:102A4000002162690B43D361636913225A61626991 -:102A5000136823F00103136000212046FFF798FC60 -:102A60000346002849D004F5805292F8C9209ABB49 -:102A70006169D1F8002242F00102C1F800226169C7 -:102A8000D1F8002222F47C5222F00E02C1F800227A -:102A90006169D1F8002242F46062C1F800226169E4 -:102AA0000022C1F814226169C1F80422616941F66B -:102AB000FF70C1F80C026169C1F840226169C1F878 -:102AC000442262690121C2F81C126169D1F8002216 -:102AD00022F00102C1F8002204F5805494F8C820C5 -:102AE00042F0020284F8C82019E762694FF40041FD -:102AF000116014E74FF00041A3E762694FF4004111 -:102B000011600CE700231846704700BF104A0020F0 -:102B100008B500F07DF802460B4652EA030102D0E8 -:102B2000013A43F1FF330449086808B1FFF7DCFCC0 -:102B300001F03AFA08BD00BF104A002008B500F0C5 -:102B400067F802460B4652EA030102D0013A43F10C -:102B5000FF330449086810B10021FFF703FD01F0BD -:102B600023FA08BD104A002008B500F051F80246CB -:102B70000B4652EA030102D0013A43F1FF33044904 -:102B8000086810B10121FFF7EDFC01F00DFA08BD56 -:102B9000104A002000B59BB0EFF309816822684617 -:102BA000FEF720FDEFF30583014B9B6BFEE700BFB3 -:102BB00000ED00E000B59BB0EFF3098168226846A4 -:102BC000FEF710FDEFF30583014B9B6BFEE700BFA3 -:102BD00000ED00E000B59BB0EFF309816822684684 -:102BE000FEF700FDEFF30583014B5B6BFEE700BFD3 -:102BF00000ED00E0FEE700BFFEE700BF0FB408B540 -:102C0000029801F0E3FAFEE708B501F035FE08BDD1 -:102C100008B501F00BFE08BD00207047002070478A -:102C200000207047704700BF30B583B084460D4622 -:102C3000043003C802AA02E9030069B10C461B88EC -:102C400013F0040F08D1DCF800309B6B6046984706 -:102C50002A46C1B20098A047012003B030BD00BF92 -:102C600082B0EC468CE80600031D9CE8030083E874 -:102C70000500012002B0704770B58AB004460E46C8 -:102C8000031D93E803000AAB03E9030069B10D4695 -:102C9000BDF8383013F0040F0AD123689B6B20462F -:102CA00098473246C1B20898A84701200AB070BDC3 -:102CB00000220023CDE900230023ADF80830039360 -:102CC0008DF818308DF819300493059303AB3068F4 -:102CD0007168B26807C3B2891A80FFF799FFCDE91E -:102CE00000010423ADF808302368DB6B69462046F9 -:102CF0009847DAE7036823F0604C0A6822F06041E5 -:102D0000D00FB0EBD37F0FD0002B08DB002A09DBFC -:102D10008C4513D08C452CBF0020012070474FEA12 -:102D20009C4CF3E7890CF3E7C3F38073C2F3807024 -:102D30008C4504D08C452CBF002001207047834275 -:102D4000FCD1F7E7084670470846704708467047C9 -:102D500008467047401A83B2002800DB704703F131 -:102D6000200000B2FAE700BF03780133DBB2037042 -:102D70001F2B01D900230370704700BF082818D902 -:102D800009280BD00A280BD00B280BD00C280BD00D -:102D90000D280BD00E280BD0402070470C20704718 -:102DA000102070471420704718207047202070476B -:102DB00030207047082818D90C280BD910280BD9B7 -:102DC00014280BD918280BD920280BD930280BD957 -:102DD0000F207047092070470A2070470B2070476A -:102DE0000C2070470D2070470E207047034621F0DD -:102DF000604C20F06042C00FB0EBD17F0FD00029B3 -:102E000008DB002B09DB944513D094452CBF002030 -:102E1000012070474FEA9C4CF3E7920CF3E7C1F3B3 -:102E20008071C3F38070944504D094452CBF00207A -:102E3000012070478142FCD1F7E700BF2DE9F04146 -:102E400007460D46D0F82480B8F1000F0CD0464656 -:102E50004446A4B169686068FFF7C8FF30B92368C9 -:102E600026465BB11C46F4E7796208E0A04502D033 -:102E700035602C6003E02C607D6200E02560BDE8D9 -:102E8000F08100BFC37DC3F38402013262F3860385 -:102E9000C375C38A6FF30903C382C37D6FF3C7137E -:102EA000C375704738B504460D46006A04E00168F2 -:102EB00004F10C00FFF74AFF10B10369AB42F6D1F1 -:102EC00038BD00BF2DE9F043079CCE0803EBD405C5 -:102ED00001F0070304F007041A442AE003F007088E -:102EE00004F00707C646B84538BFBE46CEF1080E07 -:102EF000D11A8E4528BF8E464FF47F4C2CFA0EFC1B -:102F00005FFA8CFC4CFA07FCD90800EB060919F8AB -:102F1000011001FA08F1F940C9B24FEAD40815F8D6 -:102F2000087079400CEA01014F4005F808707344BD -:102F300074449342D2D1BDE8F08300BF2DE9F04F35 -:102F400087B004900E4605920393838AB1EBC30FBA -:102F500080F084801146DA0031448A4204D2D2B231 -:102F6000F3B2D21AD3B20593049BDB683BB3272E8E -:102F700036D8C6F12803059A9A422ED35FFA86FB0B -:102F8000CBF1280B5FFA8BFB00230093039B5A467F -:102F9000314604988068FFF795FF5E44059BA3EBDC -:102FA0000B04E4B2049B9F8A07F10057053FFF0022 -:102FB000D3F80C9028214B46B9461F4627E0049BC6 -:102FC0001B69002BD3D100230093039B059A314644 -:102FD00004988068FFF776FF33E0DDF814B0D3E79C -:102FE000059C4FF0000BDDE72546CDF800B0039BB4 -:102FF0002A46711A381DFFF765FF2E44AB445FFA6D -:103000008BFB641BE4B2A9EB0A093F684146A7B1F8 -:103010009CB1CA46B9F1E00F28BF4FF0E00A0AEBB5 -:1030200001084645EFD2A8EB06039C42DCD35FFAC9 -:1030300088F5F3B2ED1AEDB2D7E7049B186900B139 -:1030400024B9BDF9140007B0BDE8F08FCDF800B089 -:10305000039B2246711AFFF735FFF2E70020F2E7E3 -:10306000002070470139002307E0C25C10F801C05E -:1030700000F803C04254013301398B42F5D3704745 -:1030800080EA0120002303E0400080B20133DBB27C -:10309000072B09D810F4004FF6D0400080B280F41E -:1030A000815080F00100F1E7704700BF70B516460F -:1030B0001D46002411E0C4F12003A4F1200C26FADF -:1030C00004F105FA03F3194325FA0CFC41EA0C015B -:1030D000C9B2FFF7D5FF0834A4B23F2CEBD970BDBD -:1030E00038B50C4604E014F8011BFFF7C9FF2A4667 -:1030F000551E002AF7D138BD38B5058C072D0BD9E0 -:103100000446D0E902234FF6FF70FFF7CFFF2A46AF -:10311000E169FFF7E5FF38BD4FF6FF70FBE700BF41 -:1031200010B4016100F1040C002305E001EB43142D -:10313000CCF80040A44601339A42F7D80023CCF8DB -:10314000003002814381838103605DF8044B704746 -:103150000346406848B102685A605A89013292B207 -:103160005A8199898A4200D99A81704708B5FFF738 -:10317000EFFF08B10023036008BD00BF2DE9F84F41 -:103180008246894616461F46CB8AC3F30903052BA0 -:1031900034D018460024042B0BD8BAB2A24208D966 -:1031A000315D09EB0302D17601339BB20134A4B245 -:1031B000F1E7BBB2A34218D9B9F816B0CBF3090BAB -:1031C000ABF1050293083E49A1FB0313C3EBC30314 -:1031D000A2EB83031FFA83F8D9F8041081B150469B -:1031E000FFF7B0FD054601231CE00344B9F81620A3 -:1031F00063F30902A9F81620012055E00024DBE75B -:103200005046FFF7B3FF054601465046FFF79CFDC9 -:10321000C9F80400002D49D04FF000082CE001331C -:103220009BB215462A68002AF9D107EB0B02053A32 -:1032300092082349A1FB021292B2013292B2934248 -:103240001AD2B8F1000F17D15046FFF78FFF286050 -:1032500078B3054610E0325D05EB0C031A710CF1F2 -:10326000010C1FFA8CFC0134A4B2BCF11B0F01D875 -:10327000A142F0D8A14204D8B9B2A1420AD9C446A9 -:10328000F3E75046FFF772FF2860A8B105464FF0FC -:103290000008F1E7B9F81630C3F30902114461F3ED -:1032A0000903A9F816300120BDE8F88F6FF002007D -:1032B000FAE76FF00200F7E76FF00200F4E700BFF3 -:1032C0002549922443680B6041604389013B438157 -:1032D000704700BFF8B506460D460EE006F10C0437 -:1032E0002046FFF72FFD014607682046FFF7EAFF5B -:1032F00039462046FFF728FD686069680029EDD14E -:10330000EB8A6FF30903EB8200200021F8BD00BFB8 -:1033100008B5FFF71DFF034628B100220260426096 -:103320008260C2600261184608BD00BF2DE9F04FFF -:1033300083B001921D465B69002B00F08A808146B4 -:103340008B462B8C1BB1EA69002A00F08580072B85 -:1033500006D94FF0800A4FF000084446474664E023 -:1033600009F10C00FFF7D4FF0446002877D02A8C1F -:10337000E9690830FEF736F9288C013080B2FFF792 -:1033800019FDFFF7FBFC431E9BB22B840133237412 -:103390006B691B7803F01F032A8C43F0C00322449F -:1033A00013724BF00043636021464846FFF746FD29 -:1033B0000127384603B0BDE8F08F002007E0EA6936 -:1033C000125D33441A72013080B20134A4B2034654 -:1033D000062802D82A8CA242F1D82B8CA34235D0E1 -:1033E000013080B2FFF7E6FCFFF7C8FC013880B27D -:1033F0004FEA4813DBB243EA0A0A6B691B7803F011 -:103400001F034AEA030A331883F808A04BF000436D -:1034100073600130307431464846FFF70FFD0137C5 -:103420003FB288F001084FF0000A2B8CA342C0D0B5 -:1034300009F10C00FFF76CFF064698B1002CBCD1D7 -:10344000019B03721B0A43720220C0E74FF0400A3F -:10345000C6E76FF00107ACE76FF00107A9E76FF06F -:103460000207A6E76FF00207A3E700BF30B589B0F7 -:1034700004460D46202200216846FEF7C7F8049551 -:103480002046FFF765FE8646A0B1EC46BCE80F007B -:10349000CEF80000CEF80410CEF80820CEF80C309C -:1034A000BCE80F00CEF81000CEF81410CEF81820AB -:1034B000CEF81C30704609B030BD00BF70B5044670 -:1034C00000F10C063046FFF7D1FF054628B1216A0E -:1034D0003046FFF73DFC28602562284670BD00BFDE -:1034E00038B504460D46036A1BB1FFF7DBFC38B163 -:1034F00038BD0C30FFF7BAFF0028F9D02062F7E79B -:1035000029462046FFF7DAFFF2E700BFF8B5044688 -:103510000E4615461F4630220021FEF777F8A760B9 -:10352000069B6360079BA3626A09B5F5001F01D380 -:103530004FF6FF7292B2314604F10C00FFF7F0FD36 -:10354000F8BD00BF037823B919B111F0800F00D185 -:1035500001707047007870472DE9F84305460C4626 -:10356000D1F81C90B9F1000F23D094F81880B8F16D -:103570001F0F3BD82846FFF7EDFF0646F8B9228C0F -:10358000072A36D8278A37F0030335D149464FF644 -:10359000FF70FFF7A5FD47F6FE7303405B0243EAA9 -:1035A00008633F0207F440773B431E434FF6FF7228 -:1035B0000EE00B8C002BD8D06FF001050FE0238AB2 -:1035C0001B0243EA08631E432046FFF795FD0246AF -:1035D000234631462846FFF7A9FE051E02DC284691 -:1035E000BDE8F8836069FFF7BFFBF8E76FF00105FE -:1035F000F5E76FF00305F2E76FF00105EFE700BFB5 -:1036000070B58AB0044616461D4628220021684639 -:10361000FDF7FCFF02960395BDF83830ADF8103089 -:103620000F9B05939DF840308DF81830119B079340 -:10363000BDF84830ADF8203069462046FFF78CFFD2 -:103640000AB070BD2DE9F04106460F461546D36914 -:103650002BB395F81880B8F11F0F2AD83046FFF722 -:1036600079FF48B32C8A240444EA08642B7844EA9E -:10367000C33444EA0724044344F080042846FFF797 -:103680003BFD02462B4621463046FFF74FFE041E07 -:1036900002DD2B78012B08D02046BDE8F081138C89 -:1036A000002BD6D06FF00104F6E76869FFF75CFBEA -:1036B000F2E76FF00104EFE76FF00304ECE700BFFF -:1036C000F0B58BB004460D4617461E462822002151 -:1036D0006846FDF79BFF9DF84C30012B14BF00237B -:1036E00001238DF80030029703969DF84030ADF825 -:1036F0001030119B05939DF848308DF81830149BBD -:103700000793BDF85430ADF820306A46294620466C -:10371000FFF798FF0BB0F0BD406A00B1043070476E -:1037200008B5416A0B6843620C30FFF7CBFD08BD5A -:103730002DE9F041054616469846076A3C4619E0D1 -:1037400021462846FFF7C6FD05F10C072B6A1968CC -:103750003846FFF7FBFA286221463846FFF7B2FDEC -:103760002C6A274606E0216805F10C00FFF7EEFA07 -:10377000274604460CB3A168E368711A68EB03039B -:103780000F4A8A424FF0000272EB0303EBD22B6A1E -:10379000A342D5D021462846FFF79CFD23683B6015 -:1037A00005F10C0321461C461846FFF78BFD3968CE -:1037B0002046FFF7CBFA0446DCE7BDE8F08100BF06 -:1037C00080841E002DE9F04182B0089E002800F0A0 -:1037D000E28014461D460746002E00F0DF80531E8F -:1037E000DBB23F2B00F2DD80012A02D1002D40F038 -:1037F000DB800023009301936B4622463846FFF797 -:103800009DFB071E3BDD14F0070F0AD002AB03EB54 -:10381000D40111F8083C624202F00702134101F89A -:10382000083C012C0BD0082C2DD9102C2ED9202C83 -:103830002FD9402C00F2BB804FF0080800E0A046D2 -:10384000FFF70EFC40BB9DB1B4EBC80F10D0082CA5 -:1038500027D89DF80020631E22FA03F313F0010F0E -:1038600006D00123A3405B42DBB213438DF8003046 -:10387000002D72D0082C5ED89DF900303370384688 -:1038800002B0BDE8F0814FF00108D9E74FF002081F -:10389000D6E74FF00408D3E741466846FFF7E2FB5E -:1038A000D1E7102C0FD8BDF80020631E22FA03F3D5 -:1038B00013F0010FDCD00123A3405B429BB2134302 -:1038C000ADF80030D4E7202C0CD8009A631E22FA01 -:1038D00003F313F0010FCBD00123A3405B421A4343 -:1038E0000092C5E73F2C65D8DDF800C0019A631E41 -:1038F000C4F12100A4F121012CFA03F302FA00F033 -:10390000034322FA01F10B4313F0010FB0D001235E -:10391000A4F12001C4F1200003FA01F123FA00F020 -:103920000143A3405B4261EB41014CEA03030A43BC -:10393000009301929CE7102C03D8BDF9003033802E -:103940009DE7202C02D8009B336098E7402C34D8A8 -:10395000DDE90023C6E9002391E7012C05D0082CFE -:1039600007D89DF80030337089E79DF80030337038 -:1039700085E7102C03D8BDF8003033807FE7202C7A -:1039800002D8009B33607AE7402C19D8DDE9002388 -:10399000C6E9002373E76FF0010770E76FF00107D6 -:1039A0006DE76FF001076AE76FF0010767E76FF0F7 -:1039B000080764E76FF0080761E76FF008075EE744 -:1039C0006FF008075BE700BFF0B585B005460E460F -:1039D000402A03D8144612B9012400E040240022F2 -:1039E00002920392012C06D0082C22D81B788DF865 -:1039F0000830012703E01B788DF808302746FFF7D1 -:103A00002FFB68BB14F0070F0AD004AB03EBD40103 -:103A100011F8083C624202F00702934001F8083CAA -:103A200000962B462246002102A8FFF74BFA05B06C -:103A3000F0BD102C04D81B88ADF808300227DEE753 -:103A4000202C03D81B6802930427D8E7402C05D804 -:103A5000D3E90023CDE902230827D0E70027CEE7EA -:103A6000394602A8FFF7FEFACCE700BF70B506465C -:103A70000C4605E00D6806F10C00FFF723FCE5603D -:103A8000E1680029F6D10023E360A3602361A382EB -:103A900070BD00BF10F0800F04D010F4004F03D0B1 -:103AA00001207047022070470020704710B504467F -:103AB000FFF7F0FF022802D0C4F3074010BDC4F3A3 -:103AC0000F2014F07F0FF9D100F00300F6E700BFDC -:103AD0002DE9F04F99B006460D4603920493D1F8B4 -:103AE00000904846FFF7D6FF0746022800F088807E -:103AF000C9F30628B9F1000F80F2028219F0C04F15 -:103B000040F001822C7B002C00F00082022F05D0B7 -:103B10003046FFF71FFD404540F0FB81C9F30463C9 -:103B2000099309F07F0A4846FFF7C0FF0A9040EA70 -:103B3000074949EA8A4949EA4869013C2C4494F812 -:103B4000048000220023CDE916235FEAD8130293F4 -:103B500059D07468CDF800A03B46024616A93046FD -:103B6000A047002800F0D88149463046FFF7B8FC4E -:103B70000446002800F0D381A368E168039A059306 -:103B8000D01A0790049B069163EB0103089395F804 -:103B90000DC0CDF82CC094F81AC0CDF830C094F800 -:103BA0001790C9F3840908F01F0B59464846FFF7E0 -:103BB000D1F80D9049465846FFF7CCF86368059A4E -:103BC000069952EA010C34D09D4A07998A424FF077 -:103BD0000002089972EB010C7CD30B9A0C998A4273 -:103BE0001BD0984B079A93424FF00003089A9341D9 -:103BF00072D2029B002B71D00F2871DD002319E0D7 -:103C00004FF0000876E749463046FFF74BF9044687 -:103C10000028B1D16FF00C0085E1029A002AE0D0B3 -:103C20000D9A012A01DD012304E0002BD9D00123E4 -:103C300000E00123002B55D16A7BA37E9A4240F01D -:103C40007181029B13B118F0400F66D1C8F3401385 -:103C5000E27DB3EBD21F40F06981C2F384039B4540 -:103C600040F06781029B002B00F0908018F0400F1D -:103C700040F08C802B7B032B40F25E81039BA36082 -:103C8000049BE360AF1D2B7B033BDBB23A4621462E -:103C900006F10C00FFF772FA00286DDB2B796A79C8 -:103CA00043EA02232383DDE916234FF6FF70FFF773 -:103CB000FDF9A0822A7B033AD2B23946FFF710FA07 -:103CC000A082E37DDA43C2F3C01262F3C713E37547 -:103CD000002028E10123ADE70023ABE70023A9E79B -:103CE0000123A7E7E37D68F38603E375DBB26FF397 -:103CF000C713E37521463046FFF7ECFA6B7BA376DA -:103D0000029B002B98D1E37DC3F38402013262F35E -:103D10008603E3756FF00C0005E1039BA360049A32 -:103D2000E260202200210EA8FDF770FC039B0E9399 -:103D3000049A0F922B1D10932B7B013BDBB2ADF845 -:103D40004C300A9BADF84E308DF850708DF851B064 -:103D5000099B8DF852308DF853A096F82C3083F0E3 -:103D600001038DF85430B3680EA9304698472046B9 -:103D7000FFF788F80020D6E021463046FFF7AAFA80 -:103D80002046FFF77FF86FF00200CCE0029B13B9EA -:103D900018F0400F1ED095F80C9009F1FF395FFA2A -:103DA00089F9B4F81680C8F30908B8F1040F30D8BF -:103DB00043464FF00008042B54D8C84552D205EBB7 -:103DC00008021179E218D176013308F101085FFA8F -:103DD00088F8F0E72F1D2B7B013BDBB23A462146EA -:103DE00006F10C00FFF7CAF9002808DB2A7B013A2C -:103DF000D2B23946A08AFFF773F9A08261E7214663 -:103E00003046FFF767FA2046FFF73CF86FF00200F4 -:103E100089E0616806F10C00FEF794FF024608B1E4 -:103E2000052304E04FF000081CE01C330A4611682B -:103E30000029FAD1A8EB03034FF000080EE000BF01 -:103E400080841E0040420F0005EB08010879D1185C -:103E50000871013308F101085FFA88F81B2B01D8BB -:103E6000C845F1D3039B0E93049B0F9304F11B03EE -:103E70001093616806F10C00FEF764FF1190C845CD -:103E800035D2A84408F104031293E38AC3F309036B -:103E90009944ADF84C900A9BADF84E308DF85070B7 -:103EA0008DF851B0099B8DF852308DF853A096F8DB -:103EB0002C3083F001038DF85430002363602A7B9B -:103EC000013A291DA08AFFF70BF9A082238B9842A3 -:103ED0000FD00EA93046FFF7C9FD2046FEF7D2FFEE -:103EE000A28A238B9A4209D06FF010001BE00023B6 -:103EF000CAE7B3680EA930469847EAE7002012E007 -:103F00006FF009000FE06FF009000CE06FF009009E -:103F100009E06FF00A0006E06FF00B0003E06FF0BD -:103F2000020000E0002019B0BDE8F08F6FF00D0036 -:103F3000F9E76FF00E00F6E76FF00F00F3E700BF50 -:103F4000EFF30983683305494A6B22F001024A63A3 -:103F500083F30988002383F31188704700EF00E0A2 -:103F6000302080F3118862B60C4BD96821F4E061EF -:103F70000904090C0A4A0A43DA60D3F8FC2042F02B -:103F80008072C3F8FC2007490A6842F001020A6007 -:103F90002022DA7783F82200704700BF00ED00E0AE -:103FA0000003FA05001000E0302383F31188104B62 -:103FB0005B6813F4006F03D1002383F3118870470B -:103FC00010B5F1EE103AEFF30984683C4FF08073BE -:103FD000E361084BDB6B236684F3098800F0B8F8D3 -:103FE00010B1054BA36110BD044BA361FBE700BFFB -:103FF00000ED00E000EF00E0430600084606000880 -:104000000901C9B2074A131883F8001300F01F0111 -:10401000400901238B4000F1600142F8213042F851 -:104020002030704700E100E00023037503691B683E -:10403000996882689142FAD203605A6842601060BF -:104040005860704708B50846302383F311880B7D0C -:10405000032B0ED0042B10D043B14FF0FF338361FC -:10406000FFF7E2FF002383F3118808BD83F3118873 -:10407000FBE78B6900221A60EFE74A680B68136060 -:104080004A685A60E9E700BF0023037503691B68AB -:10409000996882689142FAD803605A684260106059 -:1040A0005860704710B5084BD8681C6822681A60C1 -:1040B000536001222275DC60FFF7E6FF01462046CF -:1040C000FCF7AAFA10BD00BF204A002008B5FFF790 -:1040D000ABFF08BD08B5064BD968087518680268BB -:1040E0001A60536001220275D860FCF795FA08BD8A -:1040F000204A002030B587B004460C4BDD68B1F192 -:10410000FF3F0FD02B460A4A684600F04BF9204685 -:10411000FFF7E0FF009B13B1684600F051F9A86972 -:1041200007B030BDFFF7D6FFF9E700BF204A0020F7 -:104130004540000808B5054BD9681B689A688B682C -:104140009A4201D9FFF7AEFF08BD00BF204A002008 -:10415000044BDA681B6898689368984294BF002003 -:1041600001207047204A002010B5084BD8681C6811 -:1041700022681A60536001222275DC60FFF784FF19 -:1041800001462046FCF748FA10BD00BF204A002037 -:1041900008B50B4B01221A70002353B109490A4894 -:1041A00000F078FC064B02221A70002383F311887A -:1041B00008BD034A02EB8302002151600133ECE7A2 -:1041C000884C002000530008204A002008B572B631 -:1041D000044B186500F000FB00F0D6FB024B0322F5 -:1041E0001A70FEE7204A0020884C002008B500F035 -:1041F00021F908BDEFF3118058B9EFF30583C3F33C -:1042000008031BB1302383F311887047302383F3F5 -:104210001188704778B908B5EFF30583C3F3080335 -:104220001BB1002383F3118808BDFFF783FF002330 -:1042300083F31188F8E770478B6002230B75002326 -:104240004B7508610846704708B58168A1F1840381 -:1042500041F8143C026941F8442C426941F8402C71 -:10426000044A41F8242CC368026820390248FFF749 -:10427000E3FF08BD31060008204A002008B5FFF71B -:10428000E3FFFFF723FF08BD08B5034BDB68986128 -:104290000F20FFF71FFF08BD204A002008B530237C -:1042A00083F31188FFF7F0FF08BD00BF08B5014692 -:1042B000302383F311880820FFF71CFF002383F3CA -:1042C000118808BDF8B515461C46C2608B60486071 -:1042D00003680B6059600160092C00D80A24C0688B -:1042E000204400F0C3FB0A2700F0BCFB0646431B3A -:1042F0009C4202D90A2F07D8F8BD7C1C281900F06F -:10430000C3FB27463546EFE7012000F003FCF3E747 -:1043100070B504460D46092900D80A250A266019F9 -:1043200000F0B2FB00F09EFB041BA54202D90A2E4E -:1043300004D870BD013635460446F0E7012000F090 -:10434000E9FBF6E7F8B505460E46174600F08AFB8E -:104350002B689D4209D0EC68041B3C1900D33C46F5 -:104360009B68A34208D82B680CE03B4602463146C6 -:104370002846FFF7A7FF14E03946FFF7C9FFF2E729 -:10438000A41A1B689A689442FAD8B46033605A68D9 -:10439000726016605E609A68121B9A604FF0FF337D -:1043A000AB60F8BD08B50361C260002343610A46F3 -:1043B00001460248FFF7C6FF08BD00BF304A002093 -:1043C00008B51B4B1B69984210D042680368136004 -:1043D00042685A600268816893680B4493600023C6 -:1043E0000360134B4FF0FF329A6108BD1968104A01 -:1043F000134643F8101F4B600021016012699A4276 -:1044000012D0816893680B44936000F02BFB084A3C -:10441000D369A0EB030C126991686145E5D91B1AB9 -:104420001944FFF775FFE0E700F028FBDDE700BF68 -:10443000204A0020F8B50BE0002383F31188E368DD -:10444000216920469847302383F311886369CBB9EB -:104450002C4D2C6900F006FBEB69C21AA568954249 -:1044600042D81D44274BDD61616822680A6061689B -:1044700051600022226053F8102F9A42DCD100F0E4 -:10448000FDFAD9E700F0EEFA0746461B6269B24230 -:104490000CD32B1A13441B4A52F8101F91420AD016 -:1044A0009E1900D23346174A12690CE0022000F030 -:1044B00031FB0023EFE73A4621461348FFF702FF9E -:1044C0001FE05B1A126891688B42FAD8A3602260E1 -:1044D000516861600C6054609168CB1A9360094B1D -:1044E0004FF0FF329A61B3E7064A52F8101F91422B -:1044F00007D0044AD0611B1AA1681944A160FFF7D4 -:1045000007FFF8BD204A0020304A002000207047F5 -:10451000FEE700BF704700BF4FF0FF30704700BF9D -:10452000BFF34F8F024BDB6813F4803FFAD1704723 -:10453000003C0240014BF322DA607047003C02402D -:1045400008B50B4B1B7803B108BDFFF7E9FF094B1A -:104550001B69002B05DB074A136823F48063136093 -:10456000F2E7044B044A5A6002F188325A60F2E7DB -:10457000904C0020003C02402301674508B50C4BDD -:104580001B7803B108BDFFF7CBFF0A4B1A6942F055 -:1045900000421A611A6842F480521A601A6822F4C2 -:1045A00080521A601A6842F480621A60EAE700BF1B -:1045B000904C0020003C024012F0010F65D1F8B58C -:1045C00004460E4615461318B3F1016F5FD8314B00 -:1045D0001B6813F0010F01D1002059E0FFF7B0FF75 -:1045E000FFF7A8FFFFF79CFF032D29D914F0030F55 -:1045F00026D1294A136923F440731361136943F4E4 -:10460000007343F00103136137682760BFF34F8FD6 -:10461000FFF786FF23689F4203D1043D043604342C -:10462000E2E71D4A136923F00103136104E01A4A0B -:10463000136923F001031361FFF7A0FF002027E0B7 -:10464000012D19D9144A136923F4407313611369B6 -:1046500043F4807343F00103136133882380BFF375 -:104660004F8FFFF75DFF23889BB232889A42DED1DD -:10467000023D02360234E3E7074A136923F00103DF -:104680001361FFF77BFF012002E00020704700204C -:10469000F8BD00BF00380240003C0240014B53F817 -:1046A000200070470C5300080B281AD870B5064636 -:1046B0000D4B1B788BB900244FF0006508E00B4BC5 -:1046C00043F824502046FFF7E9FF05440134E4B2E3 -:1046D0000B2CF4D9044B01221A70044B53F826001A -:1046E00070BD0020704700BFC44C0020944C0020D7 -:1046F0000C2070470B2801D90020704738B50546BB -:10470000FFF7D2FF04462846FFF7C8FF30B1236801 -:10471000B3F1FF3F04D104380434F7E7012038BD7A -:104720000020FCE70B2801D90020704738B504466B -:10473000FFF7F6FEFFF704FFFFF7FCFE154BA3FBA8 -:104740000423DB081A4603EB4303A4EB8303DB00DB -:10475000DBB2D201D2B2134343F4007343F002033D -:104760000D4A1361136943F480331361FFF7D8FED8 -:104770002046FFF799FF05462046FFF78FFF0146C9 -:10478000284600F0FDF8FFF7F9FE2046FFF7B2FFDC -:1047900038BD00BFABAAAAAA003C024008B5FFF78B -:1047A0000BFF08BD08B5034610B10A4A127822B1C2 -:1047B00013B9084B1B7833B908BDFFF7C1FE054B91 -:1047C00001221A70F8E7034B00221A70FFF7D6FE99 -:1047D000F2E700BF904C002010B500240BE0074822 -:1047E00004EB44039A00134603445968805800F0D0 -:1047F000C9F80134E4B2012CF1D910BD3C530008D2 -:1048000008B50846114600F069FC08BD08B501204E -:1048100000F064FC08BD00BF08B5084600F07CFC51 -:1048200008BD00BF08B500F01DF908BD70B582B025 -:10483000FFF7E0FC0E4E0546FFF7F4FF32689042AA -:1048400003460ED30B49D1E900411C1941F1000187 -:10485000284601913360FFF7DDFC0199204602B044 -:1048600070BD044A5168146801315160EDE700BF22 -:10487000C84C0020D04C002070B582B0FFF7BAFCC5 -:10488000104E0546FFF7CEFF32689042034613D321 -:104890000D49D1E900411C1941F10001284601915F -:1048A0003360FFF7B7FC01994FF47A72002320467A -:1048B000FBF79EFC02B070BD034A516814680131D9 -:1048C0005160E8E7C84C0020D04C002009E000F11E -:1048D000010C064A52F8202041F8042B1A465FFAD0 -:1048E0008CF0531EDBB2002AF1D1704750280040F3 -:1048F00010B4124B1B6F13F4004F08D10F4B1C6FF9 -:1049000044F400741C671C6F44F400441C670C4C96 -:10491000236843F48073236009E000F1010C51F82F -:10492000044B084A42F820401A465FFA8CF0531EA6 -:10493000DBB2002AF1D15DF8044B70470038024029 -:10494000007000405028004000B583B0012201A94A -:104950000020FFF7BBFF019803B05DF804FB00BF28 -:1049600010B582B00446FFF7EFFFA04201D102B0BC -:1049700010BD0194012201A90020FFF7B9FFF6E75D -:10498000704700BF704700BF704700BF074B45F23C -:1049900055521A6002225A6040F6FF729A604CF635 -:1049A000CC421A60024B01221A707047003000405E -:1049B000DC4C0020034B1B781BB1034B4AF6AA22A8 -:1049C0001A607047DC4C002000300040044B1B682C -:1049D00023B9044BD3F87428014B1A60704700BF09 -:1049E000D84C002000300240024B4FF08072C3F8D8 -:1049F000742870470030024008B5FFF7E7FF024B0C -:104A00001868C0F3407008BDD84C002008B5FFF707 -:104A1000DDFF024B1868C0F3007008BDD84C0020C1 -:104A2000704700BFFEE700BF084B094903E051F89B -:104A3000042B43F8042B074A9342F8D302E00022E8 -:104A400043F8042B044A9342F9D37047684D002081 -:104A5000E8540008684D0020684D002008B500F0BB -:104A6000DBF808BD4FF08043586A70474FF0804331 -:104A7000586300221A610222DA6070474FF08043C7 -:104A80000022DA60704700BF4FF0804358637047E0 -:104A9000FEE700BF70B586B004460E46194B58605D -:104AA000002585620163FFF75BFA24606460A560FE -:104AB000E56204F11003236163614FF0FF33A361EA -:104AC000E561FFF7CFFF02462B46C4E908232565C1 -:104AD00080230D4A04F134012046FFF7ADFBE0606E -:104AE00001230375094A009272680192B26802922A -:104AF0000393074B049305956846FFF7BFFB06B089 -:104B000070BD00BF884C0020545300085C5300085F -:104B1000914A0008024AD36A0343D362704700BF38 -:104B2000204A00204B6843608B688360CB68C36079 -:104B30000B6943614B6903628B6943620B680360D5 -:104B4000704700BF10B5214B1A6940F2FF110A43AC -:104B50001A611A6922F4FF7222F001021A611A69BD -:104B60001A6B0A431A631A6D0A431A651B6D184CB7 -:104B700021461848FFF7D6FF04F11C011648FFF73D -:104B8000D1FF04F138011548FFF7CCFF04F15401BF -:104B90001348FFF7C7FF04F170011248FFF7C2FF87 -:104BA00004F18C011048FFF7BDFF04F1A8010F4884 -:104BB000FFF7B8FF04F1C4010D48FFF7B3FF04F19C -:104BC000E0010C48FFF7AEFF10BD00BF0038024007 -:104BD0006453000800000240000402400008024044 -:104BE000000C024000100240001402400018024075 -:104BF000001C02400020024008B5FFF7A3FF00F0B0 -:104C000095F808BD08B500F025FAFFF7C1FAFFF7DF -:104C1000DDFE08BD704700BF0F4B1A6C42F0010269 -:104C20001A641A6E42F001021A661B6E0B4A9368F0 -:104C300043F0010393604FF0804353229A624FF098 -:104C4000FF32DA6200229A615A63DA605A60012206 -:104C50005A611A60704700BF00380240002004E02B -:104C600008B54FF080421369D168C9B20B40D943EF -:104C7000116113F0020F00D108BD302383F31188B6 -:104C8000FFF7B4FA002383F31188F5E70B4A1368A2 -:104C900043F4807313600A4B1B6F03F44073B3F546 -:104CA000007F05D0064B4FF480321A6700221A6746 -:104CB000024A536823F40073536070470070004049 -:104CC0000038024008B5184B1A696FEAC2526FEA01 -:104CD000D2521A611A69C2F308021A611A695A6932 -:104CE0004FF0FF3058615A69002159615A691A6AB8 -:104CF00062F080521A621A6A02F080521A621A6ACC -:104D00005A6A58625A6A59625A6A1A6C42F0805258 -:104D10001A641A6E42F080521A661B6EFFF7B6FFD5 -:104D200000F076F908BD00BF003802403B4B4FF061 -:104D300080521A643A4A4FF4404111601A6842F0B6 -:104D400001021A60354B1B6813F0020FFAD0334A88 -:104D5000936823F003039360304B9B6813F00C0FB0 -:104D6000FAD12E4B1A6802F0F9021A6000229A60FA -:104D70001A6842F480321A60284B1B6813F4003F13 -:104D8000FAD0264A536F43F001035367234B5B6FFE -:104D900013F0020FFAD0214B224A5A601A6842F0EF -:104DA00080721A601E4B5B6813F4804FFAD01B4B65 -:104DB0001B6813F0007FFAD0184B1B4A9A601B4BFC -:104DC0001A681B4B9A421FD01A4B40F205721A60A8 -:104DD000184B1B6803F00F03052BF9D10F4A93689A -:104DE00043F0020393600D4B9B6803F00C03082B08 -:104DF000F9D10A4B5A6C42F480425A645A6E42F41A -:104E000080425A665B6E70470B4B1A680B4B9A4296 -:104E1000DAD1084B40F205121A60D9E70038024097 -:104E2000007000400854400700948838002004E0D7 -:104E300011640020003C024000ED00E041C20F413F -:104E400008B5074A536903F0010353612BB1054BC1 -:104E50001B6813B1034A50689847FFF7A5F808BDCF -:104E6000003C0140E04C002008B5074A536903F0BC -:104E7000020353612BB1054B9B6813B1034AD06801 -:104E80009847FFF791F808BD003C0140E04C002036 -:104E900008B5074A536903F0040353612BB1054B6E -:104EA0001B6913B1034A50699847FFF77DF808BDA5 -:104EB000003C0140E04C002008B5074A536903F06C -:104EC000080353612BB1054B9B6913B1034AD069A9 -:104ED0009847FFF769F808BD003C0140E04C00200E -:104EE00008B5074A536903F0100353612BB1054B12 -:104EF0001B6A13B1034A506A9847FFF755F808BD7B -:104F0000003C0140E04C002010B51A4B5C6904F4F1 -:104F100078725A6114F0200F05D0174B9B6A13B1B9 -:104F2000154AD06A984714F0400F05D0124B1B6BFE -:104F300013B1114A506B984714F0800F05D00E4BF7 -:104F40009B6B13B10C4AD06B984714F4807F05D04B -:104F5000094B1B6C13B1084A506C984714F4007F3E -:104F600005D0054B9B6C13B1034AD06C9847FFF7F3 -:104F70001BF810BD003C0140E04C002010B51F4B59 -:104F80005C6904F47C425A6114F4806F05D01C4BB8 -:104F90001B6D13B11A4A506D984714F4006F05D079 -:104FA000174B9B6D13B1164AD06D984714F4805F70 -:104FB00005D0134B1B6E13B1114A506E984714F471 -:104FC000005F05D00E4B9B6E13B10D4AD06E984713 -:104FD00014F4804F05D00A4B1B6F13B1084A506F71 -:104FE000984714F4004F05D0054B9B6F13B1044A4A -:104FF000D06F9847FEF7D8FF10BD00BF003C0140BE -:10500000E04C002008B5FFF72BFEFEF7CDFF08BDF2 -:1050100008B506210846FEF7F3FF06210720FEF734 -:10502000EFFF06210820FEF7EBFF06210920FEF71F -:10503000E7FF06210A20FEF7E3FF06211720FEF70F -:10504000DFFF06212820FEF7DBFF07211C20FEF7EB -:10505000D7FF08BD08B5FFF735FE00F005F8FFF7EC -:10506000D9FDFFF7FBFC08BD002307E0054A00213E -:1050700042F8331002EBC302516001330F2BF5D914 -:10508000704700BFE04C00200B460146184600F078 -:105090002DB8000000F040B8012838BF012010B53D -:1050A0000446204600F030F830B900F007F808B99F -:1050B00000F00CF88047F4E710BD0000024B1868C0 -:1050C000BFF35B8F704700BF604D002008B506201E -:1050D00000F084F80120FFF71BFA0000024B0A469B -:1050E00001461868FFF78CBB1C23002010B5054C47 -:1050F00013462CB10A4601460220AFF3008010BDD2 -:105100002046FCE700000000024B01461868FFF74C -:105110007DBB00BF1C230020024B01461868FFF72F -:105120007BBB00BF1C23002010B501390244904214 -:1051300001D1002005E0037811F8014FA34201D00E -:10514000181B10BD0130F2E72DE9F041A3B1C91AD7 -:1051500017780144044603F1FF3C8C42204601D9F4 -:10516000002009E00578BD4204F10104F5D10CEB03 -:105170000405D618A54201D1BDE8F08115F8018DCE -:1051800016F801EDF045F5D0E7E700001F2938B526 -:1051900004460D4604D9162303604FF0FF3038BD96 -:1051A000426C12B152F821304BB9204600F030F871 -:1051B0002A4601462046BDE8384000F017B8012BCA -:1051C0000AD0591C03D1162303600120E7E700240D -:1051D00042F82540284698470020E0E7024B014668 -:1051E0001868FFF7D3BF00BF1C23002038B5074D58 -:1051F00000230446084611462B60FFF78DF9431C37 -:1052000002D12B6803B1236038BD00BF644D00207C -:10521000FFF77CB96F72672E6172647570696C6F8D -:10522000742E41522D46343037536D617274426191 -:105230007400000040A2E4F16468910600000000E0 -:1052400041A3E5F265699207000000004261642015 -:1052500043414E496661636520696E6465782E003E -:1052600080000000008000000000800000000000BE -:1052700000000000111F000891280008D92700082D -:105280001D1F0008511F0008D5200008211F00081D -:10529000311F0008251F00082D1F0008291F0008C6 -:1052A00089200008351F0008612C0008451F0008F0 -:1052B000A92000080000000000000000111F0008E5 -:1052C000F52B0008192C00081D1F0008792C000878 -:1052D000292C0008211F00081D2C0008251F00088C -:1052E000212C0008291F0008252C0008F52B000898 -:1052F000612C0008F52B0008F52B00086330000036 -:10530000FC520008784A0020884C00200040000031 -:1053100000400000004000000040000000000100CC -:105320000000020000000200000002000000020075 -:105330000000020000000200000002000000002047 -:105340000000020001000000000002200000020036 -:10535000020000006D61696E0000000069646C6508 -:10536000000000000000802A00000000AAAAAAAAEB -:1053700000000024FFFF0000000000000090090072 -:105380000000000000000000AAAAAAAA0000000075 -:10539000FFFF00000000000000000000000000050A -:1053A00000000000AAAAAAA600000000FFEF00006B -:1053B00000000000000000000000000000000000ED -:1053C000AAAAAAAA00000000FFFF00000000000037 -:1053D000000000000000000000000000AAAAAAAA25 -:1053E00000000000FFFF00000000000000000000BF -:1053F0000000000000000000AAAAAAAA0000000005 -:10540000FFFF00000000000000000000000000009E -:1054100000000000AAAAAAAA00000000FFFF0000E6 -:10542000000000000000000000000000000000007C -:105430000A0000000000000003000000000000005F -:10544000000000000000000000000000000000005C -:10545000000000000000000000000000000000004C -:10546000C0ADFF7F010000006E04000000000000DE -:1054700000000F000000000040420F00FE2A010063 -:10548000D2040000202300200000000000000000E3 -:10549000000000000000000000000000000000000C -:1054A00000000000000000000000000000000000FC -:1054B00000000000000000000000000000000000EC -:1054C00000000000000000000000000000000000DC -:1054D00000000000000000000000000000000000CC -:0854E0000000000000000000C4 +:1000000000070020F101000805290008A1280008C8 +:10001000E1280008A1280008C1280008F301000811 +:10002000F3010008F3010008F3010008513C000847 +:10003000F3010008F3010008F3010008F3010008D0 +:10004000F3010008F3010008F3010008F3010008C0 +:10005000F3010008F3010008054B00082D4B0008D0 +:10006000554B00087D4B0008A54B0008F301000824 +:10007000F3010008F3010008F3010008F301000890 +:10008000F3010008F3010008F30100081D2800082F +:100090004928000875280008F3010008CD4B000826 +:1000A000F3010008F3010008F3010008F301000860 +:1000B000C94C0008F3010008F3010008F30100082F +:1000C000F3010008F3010008F3010008F301000840 +:1000D000F3010008F3010008F3010008F301000830 +:1000E000414C0008F3010008F3010008F301000887 +:1000F000F3010008F3010008F3010008F301000810 +:10010000F3010008F3010008F3010008F3010008FF +:10011000F3010008F3010008F3010008F3010008EF +:10012000F3010008F3010008F3010008F3010008DF +:10013000F3010008F3010008F3010008F3010008CF +:10014000F3010008F3010008F3010008F3010008BF +:10015000F3010008F3010008F3010008F3010008AF +:10016000F3010008F3010008F3010008F30100089F +:10017000F3010008F3010008F3010008F30100088F +:10018000F3010008F3010008F3010008F30100087F +:10019000F3010008F3010008F3010008F30100086F +:1001A000F3010008F3010008F3010008F30100085F +:1001B000F3010008F3010008F3010008F30100084F +:1001C000F3010008F3010008F3010008F30100083F +:1001D000F3010008F3010008F3010008F30100082F +:1001E000FD110008000000000000000000000000F9 +:1001F00002E000F000F8FEE772B6374880F30888A6 +:10020000364880F3098836483649086040F20000D5 +:10021000CCF200004EF63471CEF200010860BFF35C +:100220004F8FBFF36F8F40F20000C0F2F0004EF628 +:100230008851CEF200010860BFF34F8FBFF36F8F7C +:100240004FF00000E1EE100A4EF63C71CEF20001D4 +:100250000860062080F31488BFF36F8F04F042FA21 +:1002600004F02CFB4FF055301F491B4A91423CBF14 +:1002700041F8040BFAE71D49184A91423CBF41F886 +:10028000040BFAE71A491B4A1B4B9A423EBF51F82E +:10029000040B42F8040BF8E700201849184A914271 +:1002A0003CBF41F8040BFAE704F020FA04F00CFB21 +:1002B000144C154DAC4203DA54F8041B8847F9E797 +:1002C00000F042F8114C124DAC4203DA54F8041B12 +:1002D0008847F9E704F008BA00070020002300204F +:1002E0000000000808ED00E00001002000070020E9 +:1002F00028510008002300208023002080230020B4 +:10030000604D0020E0010008E4010008E40100085D +:10031000E40100082DE9F04F2DED108AC1F80CD052 +:10032000C3689D46BDEC108ABDE8F08F002383F3BF +:1003300011882846A047002003F0F4FDFEE703F0F3 +:1003400079FD00DFFEE70000F8B500F05FFF04F084 +:100350005DF9064604F0B2F90746A8B92C4B9E4257 +:100360002BD001339E422BD026F0FF02294B9A421C +:1003700003D0054641F2883408E0F0B200F042FEB6 +:100380003D4642F2107401E00546002400F040FEB4 +:1003900008B10024254601F0E3FAA0B941F2883300 +:1003A0009C4216D017B11C4B9E4216D1002004F07F +:1003B00039F9BDB900F0A6FE26E005460024E5E7C0 +:1003C00000240125E2E7032000F030F80024254650 +:1003D000E8E74FF47A740125E4E704F067F90024B4 +:1003E0002546E3E700F040F8E4E700F0DDFE4FF4D7 +:1003F0007A7003F09FFD002CF7D002F08BFA401BBF +:10040000A042F2D900F030F802F084FA0546F2E793 +:10041000010007B0000008B0263A09B0302383F38A +:100420001188854680F308880847704708B50C4B4B +:100430001870032806D8DFE800F00A06020E022032 +:1004400000F050FF08BD022000F042FFFAE7054B24 +:1004500000225A60F6E7034B00225A60F2E700BF21 +:10046000802300208423002008B501F079FA034698 +:1004700068B9072B0FD89A0002F1006202F58032AA +:100480001268B2F1FF3F05D00133DBB2F1E7032080 +:10049000FFF7CCFF08BD174B5A68013B9A42F9D9C8 +:1004A000154B9B6803F1006303F580339A42F1D248 +:1004B00004F0CEF804F0E0F8002000F0C3FE0220C3 +:1004C000FFF7B4FF0D4B1A6C00221A64196E1A66FE +:1004D000196E596C5A64596E5A665B6E72B6054B4A +:1004E0004FF0E022C2F8083D59681868FFF796FF00 +:1004F000D0E700BF000001080023002000380240C0 +:10050000094A136899B21B0C49F2690000FB0133D8 +:100510001360064B186882B2000C44F2506101FB74 +:100520000200186080B270471823002014230020B6 +:1005300010B50446FFF7E4FFB0FBF4F304FB13002F +:1005400080B210BD10B40346002202604260826097 +:10055000C260044C07CC186059609A605DF8044B87 +:10056000704700BF107AFF1F70B50E4614461D4637 +:1005700002F078FE60B9022D33D1012C01D00020A9 +:1005800030E019A3D3E90023C6E90023012029E0C4 +:10059000282C1FD00CD8012C15D0052C06D114A363 +:1005A000D3E90023C6E9002301201BE0002019E065 +:1005B000302C06D110A3D3E90023C6E90023012083 +:1005C00010E000200EE00EA3D3E90023C6E90023CB +:1005D000012007E00CA3D3E90023C6E90023012092 +:1005E00000E0002070BD00BF401DA12026812A0B25 +:1005F000F017304A39059E5678F6339F93CACD8D51 +:100600009E6AC421818A46EE26417272DF25D7B7E1 +:1006100070B58AB006460D4602F07CF904464FF4E8 +:10062000C870FFF785FF044404F51674174B1C606F +:10063000EB7E23B9164B00221A700AB070BD05A9D3 +:10064000284600F091FF0028F7D101A8FFF77AFFB4 +:100650009DF81640224601A90DF1170004F0C6FBD3 +:1006600048B90F2C0BD80A4B1C70084A1368A3F525 +:1006700016731360E1E7064B00221A70DDE79DF860 +:100680001410304602F0E6FDD7E700BFA03300208B +:100690009D3300202DE9F043ADF5517D80460E4697 +:1006A0000DF5E2790027719740F27512394672A86C +:1006B00000F036FE0EAC4FF4C4723946204600F00E +:1006C0002FFE02F027F92F4BA3FB003080092E4BA1 +:1006D000186093E8070084E8070002232374677416 +:1006E0000DF15A00FFF72EFF042384F820306E230B +:1006F00084F821300DF1180C244D0FCDACE80F001B +:1007000095E80F00ACE80700ACF800301D2384F832 +:1007100032310DF1180CBCE80F00CDF86B01CDF8AB +:100720006F11CDF87321CDF87731BCE80700CDF813 +:100730007B01CDF87F11CDF883219CF800308DF836 +:10074000873101224946204600F03EFE80B20590E6 +:10075000CDF810900397B37E029306F1190301932D +:100760000123009305A3D3E90023F17E404602F064 +:100770002FFE0DF5517DBDE8F08300BF9E6AC421B8 +:10078000818A46EED34D62108C230020D84E00089B +:10079000F0B5FDB006460D462B4B1C7A6CBB07A985 +:1007A000284600F025FF002845D19DF81D70C82F70 +:1007B00041D84FF4A6620021234800F0B1FD032C7C +:1007C0000AD82202204B4FF48A7101FB0433C3F88C +:1007D000E4200134E4B2F2E71B4C3A460DF11E016D +:1007E00004F1090000F088FDE219002353729DF81E +:1007F0001C3023720BB9EA7E2272812200213AA8B2 +:1008000000F08EFD5BAC012221463AA800F02CFFDF +:1008100080B20590049400230393AB7E029305F10C +:10082000190301932823009305A3D3E90023E97E4C +:10083000304602F0CDFD7DB0F0BD00BFAFF30080CB +:1008400026417272DF25D7B7B0440020134BB3F8AE +:100850002C35834200D9704710B50446002100F0C2 +:100860001BFD01340D4BA3F82C450C4BB3F82C05A4 +:1008700000F0F6FC88B1094BB3F82C0500F002FD3E +:1008800058B9064C0021B4F82C0500F005FDB4F869 +:100890002C350133A4F82C35E7E710BDB044002017 +:1008A0002DE9F041F0B00646274C94F8D8304FF4CB +:1008B0008A7505FB004585F8DC30002785F8E8706F +:1008C000D82239463AA800F02BFD04F10908404629 +:1008D00000F01CFDC2B28DF8F020D5F8E4303A9358 +:1008E0003B9741460DF1F10000F006FD06AD0122F7 +:1008F00029463AA800F0E2FE80B205900495012353 +:1009000003930823029304F1D80301933023009347 +:100910000BA3D3E90023217A0C4802F059FDB84219 +:1009200003DC002070B0BDE8F08101F0F3FF4FF46C +:100930008A7202FB0646C6F8E0000120F2E700BF1B +:1009400078F6339F93CACD8DB0440020A4330020A5 +:1009500038B501F0DFFF0546002408E00532B3EBAF +:10096000420F02D3FFF79CFFF8B10134E4B2032C2D +:100970001BD80E4B93F8D900204400F003004FF42D +:100980008A7202FB003393F8E830002BEDD1074B5D +:1009900002FB0033D3F8E030002BE3D0EB1A034A1C +:1009A0001268F92ADAD8FA22D8E738BDB044002014 +:1009B000F0B58FB000230A938DF834308DF83530C0 +:1009C0000B930C9300242746002C46D101238DF86D +:1009D0000C3000238DF80D3041F2D80204FB02F2F6 +:1009E000204955185258966800200021CDE9000191 +:1009F0000DF10D0203A92846B0479DF80C604EB3D7 +:100A0000194A536983F48053536100230693079373 +:100A10000893099341F2D80304FB03F3114AD35816 +:100A20005F690DF10E0304AA0AA92846B84707AB6F +:100A30000BAA92E8030083E803009DF834308DF898 +:100A400024300A9B0693DDE9042306A9074802F037 +:100A5000C7FE37460134E4B2B6E7002FB2D10FB07B +:100A6000F0BD00BFD833002000080240A4330020AE +:100A700010B586B0BDF828400494099C03949DF8F5 +:100A8000204002940193009202460B46024802F075 +:100A90003FFC06B010BD00BFA433002010B58AB0E3 +:100AA000244802F0DFFB08B10AB010BD01F032FFAC +:100AB000214B1B689842F7D301F02CFF04464FF4FA +:100AC000C870FFF735FD044404F516741A4B1C601A +:100AD00000238DF82030194B1B7813B901238DF8B2 +:100AE000203004A8FFF72EFD144B1978C1F1100433 +:100AF000E4B2062C00D90624224604AB19440DF1B9 +:100B0000210000F0F9FB0134029408AB0193182393 +:100B100000930B4B012205A1D1E90001FFF7A8FFCB +:100B2000064B00221A70BFE7AFF30080401DA120E2 +:100B300026812A0BA4330020A03300209D330020FF +:100B40009C33002010B586B001F0E4FE0F4BA3FBF0 +:100B500000239B090E48036004AC0122214600F0EB +:100B6000DBFC80B20290019418230093094B40F201 +:100B7000551204A1D1E90001FFF77AFF06B010BDBC +:100B8000AFF30080F1C6A7C1D068080FD34D621043 +:100B90008C230020E449002010B502460B46094C86 +:100BA000204602F04DFC204602F05CFB38B1064BBB +:100BB0001B7A2BB10322054B5A71FFF7C3FF10BDFF +:100BC0000222F8E7A4330020B04400208C23002048 +:100BD000012800D0704738B54FF6FF73994200D016 +:100BE00038BD0025084C002D07DB204601F0BCF97C +:100BF00004F586541834013DF5E7044A0449002001 +:100C000004F0A4F8ECE700BFD8330020204A00200D +:100C1000150C000838B50F4C0F4B9C4219D0A4F5A9 +:100C20008653A3F118040D4A43F8182C41F25C03D3 +:100C3000E21812793AB9E5582DB1284600F09EFE27 +:100C4000284604F089F804F58250083000F096FE3A +:100C5000E2E738BDB0440020D8330020384F000808 +:100C6000F0B587B0254802F0DFFB002839D00446F4 +:100C7000002302938DF814308DF8153003930493FC +:100C8000027B8DF8142003AA4068A16803C2226881 +:100C900042F0004202921D461C46D5B941F2D803EB +:100CA00005FB03F3164A9E189B581F6901F036FE98 +:100CB000144A82184FF00003009341F1000302A987 +:100CC0003046B8470028C8BF44F001040135EDB2F2 +:100CD000E3E744B90C4B1B78072B0BD801330A4AC6 +:100CE000137007B0F0BD054802F0A2FB064B0022CE +:100CF0001A70B7E7014802F09BFBF2E7A43300202B +:100D0000D833002040420F00E5490020CA7E9B4BAB +:100D10001B7A9A4240F031812DE9F04700AF084636 +:100D20000024032C0CD8954B4FF48A7202FB043339 +:100D300093F8DC20437E9A4207D00134E4B2F0E716 +:100D4000002323B9BD46BDE8F0870123F9E74FF43E +:100D50008A7104FB01F1E031884B19440A3100F03B +:100D6000D9FC0028EED1854B4FF48A7202FB043483 +:100D7000012384F8E83001F0CDFDD4F8E030C31A47 +:100D8000192B05D940F6B832934202D9134600E038 +:100D900019237A4AD2ED007AF8EE677A9FED787AD5 +:100DA00027EE877A07EE903AF8EE677ADFED756AFC +:100DB00067EEA67A77EE277AFCEEE77AC2ED007A44 +:100DC0003CE013464FF48A7202FB0535002385F898 +:100DD000E830C5F8E030C546684B5B689B0A0133D4 +:100DE000694A1381AEE7002042F8040B013B002B57 +:100DF000F9DA2246304600F07FFA604B5B68002B40 +:100E00004BD05E4B93F8D20000F02AFA82460028BD +:100E100047D05A4BD3F8D430002B4ED0574BD3F891 +:100E2000D430234453454ED85FFA89F23146534BB0 +:100E3000586800F07FFA00284CD1C5464F4B93F814 +:100E4000D9504FF48A7202FB053393F8E830002B37 +:100E5000C2D0E846494A4FF48A7303FB0523D3F80E +:100E6000E41053689942ACD144494FF48A7305FBAE +:100E700003F3CA18B2F8EC40E21C4FEA9209E033DF +:100E800019440E314A4609F1FF3392000732D20865 +:100E9000A8EBC20295466E46A9E7012000F0D2F900 +:100EA000AFE70024354B1C7200F000FA204600F03A +:100EB000C9F9354B0B221A818DE7304B93F8D200DC +:100EC000FFF7C4FCAAE72D4B93F8D2000130FFF7DF +:100ED000BDFCA9E7294B5A6822445A60D3F8D46074 +:100EE0002644C3F8D46093F8D20000F0B9F98642E2 +:100EF0000BD3224B93F8D220013283F8D220D3F8BF +:100F0000D420A2EB0A02C3F8D420FF2C23D91B4C17 +:100F10004FF48A7303FB0545002385F8E830C5F8D4 +:100F2000E030D5F8E43003F58063C5F8E43094F898 +:100F3000D900FFF7B5FCFFF793FE94F8D9300133E1 +:100F40005A4203F0030302F0030258BF534284F8ED +:100F5000D930C54672E70024084B1C7200F0A6F990 +:100F6000204600F06FF900F0FBFC074A108108B141 +:100F7000C546E7E6FFF778FAFAE77047B044002085 +:100F80006666663FCDCCCC3D8C23002038B5054647 +:100F90000C4602F067F950B1E38A282B1CD014D814 +:100FA000012B0FD121462846FFF774FB0CE0237E6E +:100FB000022B09D1E38A012B06D121462846FFF7EF +:100FC00027FB01E0052B0CD038BD302BFCD121468E +:100FD0002846FFF79BFEF7E721462846FFF7D8FB98 +:100FE000F2E7BFF34F8F0549CA6802F4E062044B91 +:100FF0001343CB60BFF34F8F00BFFDE700ED00E070 +:101000000400FA05014B1870704700BF98230020B8 +:1010100030B585B04FF000531A68324B9A420FD06A +:1010200003F056FB044678B32F4A136C43F0007369 +:1010300013642E4B9A6D2E4B9A4228D0002423E045 +:101040004FF00054607DFFF7DDFF227D294B1A72BF +:10105000002309E01902274A4FF48A7000FB03229B +:10106000C2F8E4100133DBB2032BF3D94FF0005484 +:10107000C92204F11601204800F03EF9E0220021C7 +:10108000204600F04DF90124204605B030BD174B35 +:101090001B6E23B37F2B01D90024F5E7174A01AB60 +:1010A00010685168926807C3032101A800F088FB0B +:1010B0000E4B5B6D984201D00024E5E70B4B1B6D96 +:1010C000994201D00024DFE7084D0023AB6595F875 +:1010D0006000FFF797FFEA6D094B1A60D4E7002420 +:1010E000D2E700BF9AAD44C5003802400066004018 +:1010F0005041A0B0B0440020B944002058660040E0 +:101100001023002030B583B000F02AFC1D4B18815D +:1011100002225A71002474B941F2D80304FB03F38C +:1011200019481A5855680122184909681844A847EF +:101130000134E4B2EFE700230193154B0093154B04 +:101140004FF480521449154802F068F8144B19788E +:1011500099B901F0DFFB04464FF4C870FFF7E8F9D6 +:10116000044404F516740F4B1C6003F0A7FA10B189 +:10117000044B0F221A8103B030BD084802F06AF810 +:10118000E7E700BF8C230020D83300201023002085 +:10119000690500088D0F00089C230020A43300205F +:1011A00098230020A033002008B50CE0114B1860F4 +:1011B00001F0B4FBFFF7F0FC13E0C82002F0BAFE28 +:1011C0000D4B1B7AA3B1FFF74BFDFFF7F1FBFFF7C8 +:1011D00065FC01F09FFB074B1B68C31AB3F57A7FD0 +:1011E000E4D2054B1B7A002BE7D0FFF7B1FBE4E715 +:1011F00008BD00BFE0490020B044002008B54FF60C +:10120000FF710120FFF7E4FC08BD00BF10B503F03B +:10121000C3F80A4B1880002406E003F093F8044456 +:10122000074A136801331360B4F5803F05D2034BBE +:101230001B88034A10688342EFD810BD144A00206F +:10124000E849002008B503F001F908BD08B592008F +:1012500000F1006000F5803003F0F4F808BD00BF35 +:1012600008B5064B1B88064A12689B1A834201D8B0 +:10127000002008BD104403F065F8FAE7144A002086 +:10128000E849002008B5034B1B68184403F086F8B2 +:1012900008BD00BFE849002008B5034B1B6818448F +:1012A00003F094F808BD00BFE849002008B5074BDB +:1012B00093F824300BB9012008BD0449002381F8BC +:1012C00024300822086AFFF7C1FFF5E7EC49002047 +:1012D000022800D07047024B4FF080529A61F9E724 +:1012E00000080240022800D07047024B4FF48052A1 +:1012F0009A61F9E700080240002304E011F803C0F6 +:1013000000F803C001339342F8D37047034600202E +:1013100000E0013013F9012B002AFAD1704700BF19 +:10132000034602E003F8011B624602F1FF3C002A7B +:10133000F8D170472DE9F843814688461546214B80 +:1013400093F8243033B31F4A126A02EB83038342BB +:1013500020D0FFF7ABFF0346E0B930E0194E96F816 +:101360002400C0F10804AC4228BF2C46E4B2A70018 +:101370003A46414606EB8000FFF7BEFFB944B84449 +:101380002D1BEDB296F824301C44E4B286F82440BC +:10139000082C0DD095B10B4B93F82430002BDDD1E8 +:1013A0000848C0F820902022FF21FFF7B9FFD5E7B9 +:1013B000FFF77CFF03460028ECD100E0012318462C +:1013C000BDE8F883EC4900202DE9F84380460E463D +:1013D000914640F2791200213046FFF7A1FF4346C3 +:1013E00020220021304602F077F908F1040302229E +:1013F0002021304602F070F908F105030322222172 +:10140000304602F069F908F106030322252130462F +:1014100002F062F908F1080310222821304602F098 +:101420005BF908F1100308223821304602F054F924 +:1014300008F1110308224021304602F04DF908F16D +:10144000120308224821304602F046F908F114033D +:1014500020225021304602F03FF908F118034022C3 +:101460007021304602F038F908F120073B46082287 +:10147000B021304602F030F908F121030822B821EA +:10148000304602F029F9C025002408E03B19023358 +:1014900008222946304602F01FF9083501340F2C86 +:1014A000F4D907F1120308222946304602F014F954 +:1014B00005F108040025BB7C9D420BD205F1100309 +:1014C0003B44033308222146304602F005F9083434 +:1014D0000135F0E7B9F1000F10D0002598F832314E +:1014E0009D4214D205F598734344033308222146E4 +:1014F000304602F0F1F808340135EFE708F599734A +:1015000007222146304602F0E7F80734E5E7E01D00 +:10151000C008BDE8F88300BF38B505460C46002179 +:101520002160C4F8031003462022204602F0D4F8BC +:101530002B1D02222021204602F0CEF86B1D032233 +:101540002221204602F0C8F8AB1D032225212046A7 +:1015500002F0C2F805F1080310222821204602F00B +:10156000BBF8072038BD00BFF0B583B007460E4674 +:10157000047F009100230722194601F0ABFF731C82 +:101580000093002301220721384601F0A3FF3CB15C +:10159000BB8ADB00083BDB08B3700825002414E09D +:1015A000B31C0093002305220821384601F092FF66 +:1015B0000D25F3E73319033300930023082229464E +:1015C000384601F087FF08350134B3789C42F1D3E7 +:1015D0000735ED083B7F2BB1B88A401B18BF0120AF +:1015E00003B0F0BDB88AA8422CBF00200120F7E765 +:1015F000F0B583B007460C46057F00910023082212 +:10160000194601F067FF661C3DB1BB8ADB00083B51 +:10161000DB0863700825002413E0009600230822ED +:101620001146384601F056FF1025F4E7331901330F +:101630000093002308222946384601F04BFF083565 +:10164000013433789C42F1D30735ED083B7F2BB151 +:10165000B88A401B18BF012003B0F0BDB88AA84269 +:101660002CBF00200120F7E7F8B506460F461446C8 +:10167000812200213846FFF753FE3346082200211D +:10168000384602F029F814B10825002410E0731C34 +:1016900007220821384602F01FF80F25F5E7331915 +:1016A000023308222946384602F016F8083501347C +:1016B00073789C42F3D3E81DC008F8BDF8B5064620 +:1016C0000F461446CE2200213846FFF729FE334646 +:1016D00028220021384601F0FFFF083614B12825E2 +:1016E000002410E0334608222821384601F0F4FF98 +:1016F0003025F5E73319013308222946384601F031 +:10170000EBFF0835013433789C42F3D3E81DC00861 +:10171000F8BD00BFF0B583B007460E46047F0091C8 +:1017200001231022002101F0D5FE3CB1BB8ADB0071 +:10173000103BDB0873801025002414E0B31C0093D9 +:10174000002309221021384601F0C4FE1925F3E7D1 +:10175000331904330093002308222946384601F048 +:10176000B9FE0835013473889C42F1D30735ED0882 +:101770003B7F2BB1B88A401B18BF012003B0F0BDDE +:10178000B88AA8422CBF00200120F7E700B58E469A +:101790000AE040F3000C09490CEA010181EA50001B +:1017A0000133DBB2072BF4D91346013A23B11EF8FB +:1017B000013B58400023F5E75DF804FB2083B8EDBA +:1017C00030B583B004460B464FF0FF30014620E0B1 +:1017D000001849410133DBB2072B0BD80029F7DA97 +:1017E00010EB000C41EB010210488CEA000010499C +:1017F0005140EFE70EF1010E5FFA8EFEBEF1030FCE +:1018000006D801AB13F80E3081EA03610023E3E749 +:101810002B465D1EADB22BB154F8043B01934FF043 +:10182000000EEBE7C043C94303B030BD9336EAA9CD +:10183000EBE1F042F0B583B01F4B6A4693E803003A +:1018400082E8030008231D491D4803F0DFFA30B386 +:1018500004460369B3F5702F23D8418B40F26E42E2 +:10186000914220D100F11807164A024402F11001FA +:101870008B421BD39B1AA3F1100511490020FFF7DF +:1018800085FF06462A4639460020FFF77FFFA368FA +:10189000B3420DD1E36883420CD1002004E00A205A +:1018A00002E00B2000E00C2003B0F0BD1020FBE7AD +:1018B0000D20F9E70D20F7E7F84E0008DCFF0E00D9 +:1018C000000001080800FFF7F0B583B0204B6A461E +:1018D00093E8030082E8030008231E491E4803F032 +:1018E00095FA38B304460369B3F5702F24D8B0F8DD +:1018F000661040F26E42914220D100F16407174A0F +:10190000024402F15C018B421BD39B1AA3F15C05DC +:1019100011490020FFF73AFF06462A4639460020C3 +:10192000FFF734FFA368B3420DD1E36883420CD1C3 +:10193000002004E00A2002E00B2000E00C2003B0AD +:10194000F0BD1020FBE70D20F9E70D20F7E700BF01 +:10195000044F000890FF0E00000001080800FFF788 +:1019600010B5FFF767FF044608B9204610BDFFF722 +:10197000ABFF0028F9D10446F7E700BF10B50446D5 +:10198000037C0BB1204610BD006803F027FAF9E78D +:10199000BFF35B8FC368BFF35B8FBFF35B8F82685E +:1019A000BFF35B8F9A4208D94268BFF35B8F8068B0 +:1019B000BFF35B8F101A18447047BFF35B8F8068CA +:1019C000BFF35B8F181A7047BFF35B8F0023C360B0 +:1019D000BFF35B8FBFF35B8F8360BFF35B8F704799 +:1019E0000346406800B97047BFF35B8F9A68BFF346 +:1019F0005B8FBFF35B8FD968BFF35B8F914209D3D5 +:101A00005868BFF35B8FDB68BFF35B8FD21A013A74 +:101A10001044E8E70020F4E738B505460C46FFF728 +:101A2000B7FFA04201D2002038BDBFF35B8FA96889 +:101A3000BFF35B8F0C446968B4FBF1F301FB134403 +:101A4000BFF35B8FAC60BFF35B8F0120ECE700BF9F +:101A500070B504460E461546FFF7C2FFA84200D3F4 +:101A6000284608B9002070BD2368BFF35B8FE26889 +:101A7000BFF35B8F134433606268BFF35B8FE3682F +:101A8000BFF35B8FD11A884207D971602168B160BA +:101A90009B1A1844F0600220E5E770600120E2E73D +:101AA00038B505460C46FFF79BFFA04201D2002047 +:101AB00038BDBFF35B8FE968BFF35B8F0C44696887 +:101AC000B4FBF1F301FB1344BFF35B8FEC60BFF396 +:101AD0005B8F0120ECE700BF2DE9F04385B0814624 +:101AE00088466946FFF7B4FF0746002425460EE006 +:101AF00004AB03EBC40656F80C2C08EB050156F8B2 +:101B0000100CFFF7F9FB56F80C3C1D440134A742BA +:101B1000EEDC29464846FFF7C3FF284605B0BDE87E +:101B2000F08300BFBFF35B8FC368BFF35B8FBFF36E +:101B30005B8F8268BFF35B8F9A4210D94368BFF313 +:101B40005B8F8268BFF35B8F9B1A0B6073B1036876 +:101B5000BFF35B8F8068BFF35B8F18447047BFF3A0 +:101B60005B8F8268BFF35B8F9B1AEEE700207047A4 +:101B7000F0B583B007460E461546FFF709FF044649 +:101B80000190A84200D32C4614B9002003B0F0BD48 +:101B900001A93846FFF7C6FF019B6BB1A34200D9EC +:101BA0000194306001987060A0420DD23B68B36030 +:101BB000241AF4600220E9E73B6833607460002374 +:101BC000B360F3600120E1E70120DFE72DE9F04198 +:101BD00084B088466946FFF7CBFF074600242546B8 +:101BE0000EE004AB03EBC40656F80C2C56F8101CA0 +:101BF00008EB0500FFF780FB56F80C3C1D44013450 +:101C0000A742EEDC284604B0BDE8F08138B50546B1 +:101C1000FFF7DCFF044601462846FFF7FDFE20469D +:101C200038BD00BF10B5026854681A46A04710BD01 +:101C30000020704700207047704700BF00207047A9 +:101C40000E20704700F5805090F8C800C0F34000A7 +:101C5000704700BF00F5805090F9D000704700BF7A +:101C600000F58050C0F8CC1001207047F0B583B06B +:101C7000BDF820500C6814F0005F40F089800C7BA8 +:101C8000082C00F28880302484F311884469A66807 +:101C900016F0806F0ED1A66816F0006F6BD1A668A3 +:101CA00016F0805F02D04FF0020E05E0002080F3B6 +:101CB00011885EE04FF0000EF4460E68002E5DDBEA +:101CC00076050EF1180E4FEA0E1E44F80E600E68EF +:101CD00016F0804F06D00CF118063601A75947F0D0 +:101CE0000207A7510F7B0CF118064FEA061E04EB02 +:101CF000061677608E6804EB0C17C7F88C614E6887 +:101D0000C7F8886154F80E6046F0010644F80E608A +:101D100041F2680E0EEB4C14044400EB4C16764472 +:101D200032607360D1F800E04F688E68C4F808E054 +:101D3000E76026618E89A6820CF1840C00EB4C1CB6 +:101D40009CF8044065F300048CF80440C5F3400699 +:101D5000E4B266F341048CF80440E4B26FF3C304C8 +:101D60008CF80440002484F31188009500F00CFEE8 +:101D7000012003B0F0BD4FF0010E9DE7F60046F0E4 +:101D800004060EF1180E4FEA0E1E44F80E609EE790 +:101D90004FF0FF30EDE74FF0FF30EAE708B53023B2 +:101DA00083F3118800F58050C06DFFF70DFE00230E +:101DB00083F3118808BD00BF70B504460D4641F29B +:101DC0005C068059FFF70CFE1F2801D8002070BD6B +:101DD00020222946A059FFF77FFE202814BF0020AB +:101DE0000120F4E72DE9F04188B006460D4617467C +:101DF0009846302383F3118800220023CDE9002385 +:101E00000024ADF8084003948DF818408DF819406F +:101E10000494059441F25C040059FFF7B9FD1F28B2 +:101E200006D8002070B980F3118808B0BDE8F081B1 +:101E3000202269463059FFF7E9FE202814BF002010 +:101E40000120EFE703AB07CB28606960AA601B881D +:101E5000AB81DDE90023C7E90023BDF80830A8F80D +:101E60000030002383F3118843463A462946304622 +:101E700000F062FDD9E700BF10B5374B03600023C7 +:101E8000436083600246354C42F8184B83611373FC +:101E90005373C36103629FED2E7B80ED0A7B038643 +:101EA000436380F8403080F841308363C36300F1BE +:101EB000480423464FF07F0C0DE09FED257B83ED1A +:101EC000007B00221A81DA601A765A761A615A610A +:101ED00020330CF1FF3CBCF1000FEEDA00F582522A +:101EE000083200F580539C644FF48054DC64002475 +:101EF0001C655C654FF0010C83F858C0DA6583F807 +:101F000060C000F5835308334FF0020EBEF1000F9E +:101F100011DB9C469FED0E7BACEC027B00229A60AD +:101F20008CF80C208CF80D20DA601A619A6120334D +:101F30000EF1FF3EEAE700F5805383F8D01011B9A7 +:101F4000074B436110BD074800F0DEFCAFF3008093 +:101F50000000000000000000804F0008384F00081B +:101F600000640040104F000810B50446034B197878 +:101F70004A1C1A70FFF780FF204610BD1C4A002043 +:101F8000002977D070B582B00C46424B994211D9E6 +:101F90000A234149B1FBF4FC013BDBB29E46581CCD +:101FA000BCFBF0F100FB11C131B1022B64D9013B44 +:101FB000DBB2F3E71123ECE7BCFBF0F0411EB1F517 +:101FC000806F5CD2C3EBC30E1EF103014DD4C1F38D +:101FD000C70C8DF800C0A3EB0C05EDB28DF80150D5 +:101FE0000CF101064FF47A710CFB0111354491FBA1 +:101FF000F5F189B2ADF80210B1F5617F18D9BEF1E3 +:10200000010E34D4CEF3C70E8DF804E0A3EB0E031B +:10201000DBB28DF805300EF101054FF47A710EFB3D +:1020200001112B4491FBF3F3ADF80630019B0093B3 +:102030009DF800104B1C9DF80160334400FB03F336 +:10204000154DB5FBF3F3A3421BD10139C9B20F29DA +:1020500019D8D6B1082E1AD80138108000239370F1 +:10206000D170013E1671012007E00731AFE70EF194 +:10207000070EC7E700207047002002B070BD0020A7 +:10208000FBE70020F9E70020F7E70020F5E7002054 +:10209000F3E700BF3F420F0080DE800270B50646C6 +:1020A0000D460024B4F57A7F0BD273695B6803F0A8 +:1020B0000103AB4207D04FF47A7001F03BFF0134CB +:1020C000F0E7002000E0012070BD00BF032964D8C4 +:1020D00070B588B004460D46164600F5805393F857 +:1020E000C830C3F3800113F0040F00D1114604F58A +:1020F000805393F8C82061F3820283F8C82041F22C +:10210000680303EB451304EB030C05F1840304EBB4 +:1021100043131B7913F0010F08D03EB105F184037E +:1021200004EB43131B7913F0080F10D06EB105F1C7 +:10213000840304EB43131B7913F0080F05D1843596 +:1021400004EB451443F00803237108B070BD00226E +:102150000023CDE900230023ADF8083003938DF868 +:1021600018308DF819300493059303ABDCF80800A0 +:10217000DCF80C10DCF8102007C3BCF814201A801F +:10218000DDE90C23CDE900230123ADF808302368F5 +:10219000DB6B694620469847C8E7704742699369F8 +:1021A00013F0700F23D00023936100E00133022B62 +:1021B0001DDC03F1840200EB4212127912F0040FCD +:1021C000F4D003F1840200EB4212127912F0020FF4 +:1021D000ECD04269064951F82310916003F1840262 +:1021E00000EB4212117941F004011171DEE77047F2 +:1021F000244F000870B582B0044616461D46436958 +:102200009A6812F0010F16D163699A6812F4807F00 +:102210001CD163699A6812F4803F24D104F580537D +:10222000D3F8CC0010B103681B6998472046FFF72C +:10223000B5FF02B070BD9A680121996000960195C2 +:10224000C2F340020021FFF741FFDDE79A684FF437 +:102250008071996000960195C2F3402201212046C9 +:10226000FFF734FFD5E79A684FF480319960009604 +:102270000195C2F3404202212046FFF727FFCDE738 +:1022800038B504460846002977D1616901F10C0C84 +:10229000DCF8001011F0030F6ED0DCF8001061695B +:1022A00000F11B052D014D5915F0040F69D100F106 +:1022B0001B052D014D596D0DA56100F11B052D016B +:1022C0004D5915F0020F03D0A56945F08045A56171 +:1022D00000F11B0501EB05156D6805F00F0E84F884 +:1022E00024E001EB0011D1F8B8012077D1F8B80152 +:1022F000000A6077D1F8B801000CA077D1F8B801D6 +:10230000000EE077D1F8BC0184F82000D1F8BC01C0 +:10231000000A84F82100D1F8BC01000C84F82200E6 +:10232000D1F8BC11090E84F823103821CCF8001024 +:10233000A569E069216A6563A063E163A18CA4F8E3 +:102340004010A262E362002323862368DB6B04F162 +:1023500028012046984704F5805393F8C82042F09E +:10236000040283F8C820D3F8CC0010B103681B69BD +:1023700098472046FFF712FF38BD616901F1100C44 +:1023800086E700F11B052D014D59ED08A56145F0CB +:102390000045A56191E700BF302181F3118800213C +:1023A000022936DC30B502E0013102292DDC01F1D1 +:1023B000840C00EB4C1C9CF804C01CF0040FF3D1FF +:1023C00001F1840C00EB4C1C9CF804C01CF0100FB5 +:1023D000EAD000EB411E41F2680C0EEB0C045EF8F3 +:1023E0000C50646895429C41DED244690B4D55F80F +:1023F0002150A56001F1840C00EB4C1C9CF804E01A +:102400004EF0040E8CF804E0CEE7002383F311882D +:1024100030BD002383F31188704700BF244F0008AC +:1024200008B5302383F31188FFF7B8FE002383F348 +:10243000118808BD43699B6803F0E053B3F1E05F86 +:102440002BD070B505460E464BB3302383F311886D +:10245000002400E00134022C1ADC04F1840305EBB3 +:1024600043131B7913F0080FF4D104F1840305EB37 +:1024700043131B7913F0040FECD141F2700101EB0F +:1024800044112944304600F0BDFA0028E2D100E0B2 +:102490000120002383F3118870BD012070470020C4 +:1024A000FAE700BF08B5302383F3118800F58050A8 +:1024B000C06DFFF76DFA002383F311881F288CBFCE +:1024C0000020012008BD00BFF8B507460E4614469F +:1024D0001D4600231370FFF7E5FF80F00103337002 +:1024E00025B129463846FFF7A5FF2070F8BD00BF8B +:1024F000F8B504460D4616461F4600F00FFA024690 +:102500000B46297809B9307860B12046FFF744FFBF +:102510002046FFF785FF3B46324629462046FFF717 +:10252000D3FF0120F8BD00BF302383F311881B4B7C +:102530001A6C42F000721A641A6A42F000721A624F +:102540001A6A22F000721A62002383F3118800F5E0 +:10255000805393F8C83013F0010F1ED110B5044614 +:1025600001B910BD302383F311880321132001F03A +:10257000CFFB0321142001F0CBFB0321152001F038 +:10258000C7FB04F5805494F8C83043F0010384F885 +:10259000C830002383F31188E3E770470038024016 +:1025A00000F5805393F8D030012B00F231812DE9F2 +:1025B000F0418AB004460E461746974A52F8232047 +:1025C000002A36D0E6602774934B1B68002B34D06A +:1025D00004F5805393F8D030012B06D18E4B186848 +:1025E00003681B6B9847002836D001212046FFF76F +:1025F0009BFF302383F311886269136823F0020381 +:1026000013606269136843F0010313606269002379 +:10261000536183F3118801212046FFF73FFD0346F4 +:1026200048BB62694FF40041116018460AB0BDE82A +:10263000F081794A42F82300C4E741F2D80002F061 +:102640008DFB054610B10021FFF716FC724B1D6093 +:10265000002DBDD10023E8E76F4D00212868FFF76A +:1026600063FF286803685B683A463146984703462B +:102670000028BAD1D9E704F58053D86DFFF7A4F943 +:102680004FF000082BE0202200216846FEF748FEAC +:10269000002302938DF814308DF8153003930493C2 +:1026A000069341F2680505EB481504EB050EEC4670 +:1026B000BCE80F006051CEF80410CEF80820CEF828 +:1026C0000C30BCE80700CEF81000CEF81410CEF89D +:1026D00018209CF800308EF81C3008F10108B8F181 +:1026E000020FD0D904F5805393F8C8206FF382020B +:1026F00083F8C8200023ADF820308DF822308DF803 +:1027000023308DF8243008AA31462046FFF738FCE4 +:10271000034600286FD0636961221A609DF8223059 +:102720001B0603F040739DF82320120402F470226C +:1027300013439DF82420120502F4E0021343BDF870 +:102740002020C2F309021343022F59D000216269ED +:102750000B43D361636913225A616269136823F0E2 +:102760000103136000212046FFF798FC0346002870 +:1027700049D004F5805292F8D0209ABB6169D1F813 +:10278000002242F00102C1F800226169D1F8002262 +:1027900022F47C5222F00E02C1F800226169D1F8C5 +:1027A000002242F46062C1F8002261690022C1F88F +:1027B00014226169C1F80422616941F6FF70C1F811 +:1027C0000C026169C1F840226169C1F84422626962 +:1027D0000121C2F81C126169D1F8002222F0010225 +:1027E000C1F8002204F5805494F8C82042F0020297 +:1027F00084F8C82019E762694FF40041116014E7BA +:102800004FF00041A3E762694FF4004111600CE70B +:1028100000231846704700BF184A002008B500F092 +:102820007DF802460B4652EA030102D0013A43F119 +:10283000FF330449086808B1FFF7DCFC01F03CFAFB +:1028400008BD00BF184A002008B500F067F802462E +:102850000B4652EA030102D0013A43F1FF33044927 +:10286000086810B10021FFF70BFD01F025FA08BD43 +:10287000184A002008B500F051F802460B4652EA0B +:10288000030102D0013A43F1FF330449086810B153 +:102890000121FFF7F5FC01F00FFA08BD184A0020EE +:1028A00000B59BB0EFF3098168226846FEF724FD6E +:1028B000EFF30583014B9B6BFEE700BF00ED00E0EB +:1028C00000B59BB0EFF3098168226846FEF714FD5E +:1028D000EFF30583014B9B6BFEE700BF00ED00E0CB +:1028E00000B59BB0EFF3098168226846FEF704FD4E +:1028F000EFF30583014B5B6BFEE700BF00ED00E0EB +:10290000FEE700BFFEE700BF0FB408B5029801F074 +:10291000C3FAFEE708B501F011FE08BD08B501F0E5 +:10292000E7FD08BD00207047012070470020704778 +:1029300000207047704700BF30B583B084460D4615 +:10294000043003C802AA02E9030069B10C461B88DF +:1029500013F0040F08D1DCF800309B6B60469847F9 +:102960002A46C1B20098A047012003B030BD00BF85 +:1029700082B0EC468CE80600031D9CE8030083E867 +:102980000500012002B0704770B58AB004460E46BB +:10299000031D93E803000AAB03E9030069B10D4688 +:1029A000BDF8383013F0040F0AD123689B6B204622 +:1029B00098473246C1B20898A84701200AB070BDB6 +:1029C00000220023CDE900230023ADF80830039353 +:1029D0008DF818308DF819300493059303AB3068E7 +:1029E0007168B26807C3B2891A80FFF797FFCDE913 +:1029F00000010423ADF808302368DB6B69462046EC +:102A00009847DAE7036823F0604C0A6822F06041D7 +:102A1000D00FB0EBD37F0FD0002B08DB002A09DBEF +:102A20008C4513D08C452CBF0020012070474FEA05 +:102A30009C4CF3E7890CF3E7C3F38073C2F3807017 +:102A40008C4504D08C452CBF002001207047834268 +:102A5000FCD1F7E7084670470846704708467047BC +:102A600008467047401A83B2002800DB704703F124 +:102A7000200000B2FAE700BF03780133DBB2037035 +:102A80001F2B01D900230370704700BF082818D9F5 +:102A900009280BD00A280BD00B280BD00C280BD000 +:102AA0000D280BD00E280BD0402070470C2070470B +:102AB000102070471420704718207047202070475E +:102AC00030207047082818D90C280BD910280BD9AA +:102AD00014280BD918280BD920280BD930280BD94A +:102AE0000F207047092070470A2070470B2070475D +:102AF0000C2070470D2070470E207047034621F0D0 +:102B0000604C20F06042C00FB0EBD17F0FD00029A5 +:102B100008DB002B09DB944513D094452CBF002023 +:102B2000012070474FEA9C4CF3E7920CF3E7C1F3A6 +:102B30008071C3F38070944504D094452CBF00206D +:102B4000012070478142FCD1F7E700BF2DE9F04139 +:102B500007460D46D0F82480B8F1000F0CD0464649 +:102B60004446A4B169686068FFF7C8FF30B92368BC +:102B700026465BB11C46F4E7796208E0A04502D026 +:102B800035602C6003E02C607D6200E02560BDE8CC +:102B9000F08100BFC37DC3F38402013262F3860378 +:102BA000C375C38A6FF30903C382C37D6FF3C71371 +:102BB000C375704738B504460D46006A04E00168E5 +:102BC00004F10C00FFF74AFF10B10369AB42F6D1E4 +:102BD00038BD00BF2DE9F043079CCE0803EBD405B8 +:102BE00001F0070304F007041A442AE003F0070881 +:102BF00004F00707C646B84538BFBE46CEF1080EFA +:102C0000D11A8E4528BF8E464FF47F4C2CFA0EFC0D +:102C10005FFA8CFC4CFA07FCD90800EB060919F89E +:102C2000011001FA08F1F940C9B24FEAD40815F8C9 +:102C3000087079400CEA01014F4005F808707344B0 +:102C400074449342D2D1BDE8F08300BF2DE9F04F28 +:102C500087B004900E4605920393838AB1EBC30FAD +:102C600080F084801146DA0031448A4204D2D2B224 +:102C7000F3B2D21AD3B20593049BDB683BB3272E81 +:102C800036D8C6F12803059A9A422ED35FFA86FBFE +:102C9000CBF1280B5FFA8BFB00230093039B5A4672 +:102CA000314604988068FFF795FF5E44059BA3EBCF +:102CB0000B04E4B2049B9F8A07F10057053FFF0015 +:102CC000D3F80C9028214B46B9461F4627E0049BB9 +:102CD0001B69002BD3D100230093039B059A314637 +:102CE00004988068FFF776FF33E0DDF814B0D3E78F +:102CF000059C4FF0000BDDE72546CDF800B0039BA7 +:102D00002A46711A381DFFF765FF2E44AB445FFA5F +:102D10008BFB641BE4B2A9EB0A093F684146A7B1EB +:102D20009CB1CA46B9F1E00F28BF4FF0E00A0AEBA8 +:102D300001084645EFD2A8EB06039C42DCD35FFABC +:102D400088F5F3B2ED1AEDB2D7E7049B186900B12C +:102D500024B9BDF9140007B0BDE8F08FCDF800B07C +:102D6000039B2246711AFFF735FFF2E70020F2E7D6 +:102D7000002070470139002307E0C25C10F801C051 +:102D800000F803C04254013301398B42F5D3704738 +:102D900080EA0120002303E0400080B20133DBB26F +:102DA000072B09D810F4004FF6D0400080B280F411 +:102DB000815080F00100F1E7704700BF70B5164602 +:102DC0001D46002411E0C4F12003A4F1200C26FAD2 +:102DD00004F105FA03F3194325FA0CFC41EA0C014E +:102DE000C9B2FFF7D5FF0834A4B23F2CEBD970BDB0 +:102DF00038B50C4604E014F8011BFFF7C9FF2A465A +:102E0000551E002AF7D138BD38B5058C072D0BD9D2 +:102E10000446D0E902234FF6FF70FFF7CFFF2A46A2 +:102E2000E169FFF7E5FF38BD4FF6FF70FBE700BF34 +:102E300010B4016100F1040C002305E001EB431420 +:102E4000CCF80040A44601339A42F7D80023CCF8CE +:102E5000003002814381838103605DF8044B704739 +:102E60000346406848B102685A605A89013292B2FA +:102E70005A8199898A4200D99A81704708B5FFF72B +:102E8000EFFF08B10023036008BD00BF2DE9F84F34 +:102E90008246894616461F46CB8AC3F30903052B93 +:102EA00034D018460024042B0BD8BAB2A24208D959 +:102EB000315D09EB0302D17601339BB20134A4B238 +:102EC000F1E7BBB2A34218D9B9F816B0CBF3090B9E +:102ED000ABF1050293083E49A1FB0313C3EBC30307 +:102EE000A2EB83031FFA83F8D9F8041081B150468E +:102EF000FFF7B0FD054601231CE00344B9F8162096 +:102F000063F30902A9F81620012055E00024DBE74D +:102F10005046FFF7B3FF054601465046FFF79CFDBC +:102F2000C9F80400002D49D04FF000082CE001330F +:102F30009BB215462A68002AF9D107EB0B02053A25 +:102F400092082349A1FB021292B2013292B293423B +:102F50001AD2B8F1000F17D15046FFF78FFF286043 +:102F600078B3054610E0325D05EB0C031A710CF1E5 +:102F7000010C1FFA8CFC0134A4B2BCF11B0F01D868 +:102F8000A142F0D8A14204D8B9B2A1420AD9C4469C +:102F9000F3E75046FFF772FF2860A8B105464FF0EF +:102FA0000008F1E7B9F81630C3F30902114461F3E0 +:102FB0000903A9F816300120BDE8F88F6FF0020070 +:102FC000FAE76FF00200F7E76FF00200F4E700BFE6 +:102FD0002549922443680B6041604389013B43814A +:102FE000704700BFF8B506460D460EE006F10C042A +:102FF0002046FFF72FFD014607682046FFF7EAFF4E +:1030000039462046FFF728FD686069680029EDD140 +:10301000EB8A6FF30903EB8200200021F8BD00BFAB +:1030200008B5FFF71DFF034628B100220260426089 +:103030008260C2600261184608BD00BF2DE9F04FF2 +:1030400083B001921D465B69002B00F08A808146A7 +:103050008B462B8C1BB1EA69002A00F08580072B78 +:1030600006D94FF0800A4FF000084446474664E016 +:1030700009F10C00FFF7D4FF0446002877D02A8C12 +:10308000E9690830FEF738F9288C013080B2FFF783 +:1030900019FDFFF7FBFC431E9BB22B840133237405 +:1030A0006B691B7803F01F032A8C43F0C003224492 +:1030B00013724BF00043636021464846FFF746FD1C +:1030C0000127384603B0BDE8F08F002007E0EA6929 +:1030D000125D33441A72013080B20134A4B2034647 +:1030E000062802D82A8CA242F1D82B8CA34235D0D4 +:1030F000013080B2FFF7E6FCFFF7C8FC013880B270 +:103100004FEA4813DBB243EA0A0A6B691B7803F003 +:103110001F034AEA030A331883F808A04BF0004360 +:1031200073600130307431464846FFF70FFD0137B8 +:103130003FB288F001084FF0000A2B8CA342C0D0A8 +:1031400009F10C00FFF76CFF064698B1002CBCD1CA +:10315000019B03721B0A43720220C0E74FF0400A32 +:10316000C6E76FF00107ACE76FF00107A9E76FF062 +:103170000207A6E76FF00207A3E700BF30B589B0EA +:1031800004460D46202200216846FEF7C9F8049542 +:103190002046FFF765FE8646A0B1EC46BCE80F006E +:1031A000CEF80000CEF80410CEF80820CEF80C308F +:1031B000BCE80F00CEF81000CEF81410CEF818209E +:1031C000CEF81C30704609B030BD00BF70B5044663 +:1031D00000F10C063046FFF7D1FF054628B1216A01 +:1031E0003046FFF73DFC28602562284670BD00BFD1 +:1031F00038B504460D46036A1BB1FFF7DBFC38B156 +:1032000038BD0C30FFF7BAFF0028F9D02062F7E78D +:1032100029462046FFF7DAFFF2E700BFF8B504467B +:103220000E4615461F4630220021FEF779F8A760AA +:10323000069B6360079BA3626A09B5F5001F01D373 +:103240004FF6FF7292B2314604F10C00FFF7F0FD29 +:10325000F8BD00BF037823B919B111F0800F00D178 +:1032600001707047007870472DE9F84305460C4619 +:10327000D1F81C90B9F1000F23D094F81880B8F160 +:103280001F0F3BD82846FFF7EDFF0646F8B9228C02 +:10329000072A36D8278A37F0030335D149464FF637 +:1032A000FF70FFF7A5FD47F6FE7303405B0243EA9C +:1032B00008633F0207F440773B431E434FF6FF721B +:1032C0000EE00B8C002BD8D06FF001050FE0238AA5 +:1032D0001B0243EA08631E432046FFF795FD0246A2 +:1032E000234631462846FFF7A9FE051E02DC284684 +:1032F000BDE8F8836069FFF7BFFBF8E76FF00105F1 +:10330000F5E76FF00305F2E76FF00105EFE700BFA7 +:1033100070B58AB0044616461D462822002168462C +:10332000FDF7FEFF02960395BDF83830ADF810307A +:103330000F9B05939DF840308DF81830119B079333 +:10334000BDF84830ADF8203069462046FFF78CFFC5 +:103350000AB070BD2DE9F04106460F461546D36907 +:103360002BB395F81880B8F11F0F2AD83046FFF715 +:1033700079FF48B32C8A240444EA08642B7844EA91 +:10338000C33444EA0724044344F080042846FFF78A +:103390003BFD02462B4621463046FFF74FFE041EFA +:1033A00002DD2B78012B08D02046BDE8F081138C7C +:1033B000002BD6D06FF00104F6E76869FFF75CFBDD +:1033C000F2E76FF00104EFE76FF00304ECE700BFF2 +:1033D000F0B58BB004460D4617461E462822002144 +:1033E0006846FDF79DFF9DF84C30012B14BF00236C +:1033F00001238DF80030029703969DF84030ADF818 +:103400001030119B05939DF848308DF81830149BAF +:103410000793BDF85430ADF820306A46294620465F +:10342000FFF798FF0BB0F0BD406A00B10430704761 +:1034300008B5416A0B6843620C30FFF7CBFD08BD4D +:103440002DE9F041054616469846076A3C4619E0C4 +:1034500021462846FFF7C6FD05F10C072B6A1968BF +:103460003846FFF7FBFA286221463846FFF7B2FDDF +:103470002C6A274606E0216805F10C00FFF7EEFAFA +:10348000274604460CB3A168E368711A68EB03038E +:103490000F4A8A424FF0000272EB0303EBD22B6A11 +:1034A000A342D5D021462846FFF79CFD23683B6008 +:1034B00005F10C0321461C461846FFF78BFD3968C1 +:1034C0002046FFF7CBFA0446DCE7BDE8F08100BFF9 +:1034D00080841E002DE9F04182B0089E002800F093 +:1034E000E28014461D460746002E00F0DF80531E82 +:1034F000DBB23F2B00F2DD80012A02D1002D40F02B +:10350000DB800023009301936B4622463846FFF789 +:103510009DFB071E3BDD14F0070F0AD002AB03EB47 +:10352000D40111F8083C624202F00702134101F88D +:10353000083C012C0BD0082C2DD9102C2ED9202C76 +:103540002FD9402C00F2BB804FF0080800E0A046C5 +:10355000FFF70EFC40BB9DB1B4EBC80F10D0082C98 +:1035600027D89DF80020631E22FA03F313F0010F01 +:1035700006D00123A3405B42DBB213438DF8003039 +:10358000002D72D0082C5ED89DF90030337038467B +:1035900002B0BDE8F0814FF00108D9E74FF0020812 +:1035A000D6E74FF00408D3E741466846FFF7E2FB51 +:1035B000D1E7102C0FD8BDF80020631E22FA03F3C8 +:1035C00013F0010FDCD00123A3405B429BB21343F5 +:1035D000ADF80030D4E7202C0CD8009A631E22FAF4 +:1035E00003F313F0010FCBD00123A3405B421A4336 +:1035F0000092C5E73F2C65D8DDF800C0019A631E34 +:10360000C4F12100A4F121012CFA03F302FA00F025 +:10361000034322FA01F10B4313F0010FB0D0012351 +:10362000A4F12001C4F1200003FA01F123FA00F013 +:103630000143A3405B4261EB41014CEA03030A43AF +:10364000009301929CE7102C03D8BDF90030338021 +:103650009DE7202C02D8009B336098E7402C34D89B +:10366000DDE90023C6E9002391E7012C05D0082CF1 +:1036700007D89DF80030337089E79DF8003033702B +:1036800085E7102C03D8BDF8003033807FE7202C6D +:1036900002D8009B33607AE7402C19D8DDE900237B +:1036A000C6E9002373E76FF0010770E76FF00107C9 +:1036B0006DE76FF001076AE76FF0010767E76FF0EA +:1036C000080764E76FF0080761E76FF008075EE737 +:1036D0006FF008075BE700BFF0B585B005460E4602 +:1036E000402A03D8144612B9012400E040240022E5 +:1036F00002920392012C06D0082C22D81B788DF858 +:103700000830012703E01B788DF808302746FFF7C3 +:103710002FFB68BB14F0070F0AD004AB03EBD401F6 +:1037200011F8083C624202F00702934001F8083C9D +:1037300000962B462246002102A8FFF74BFA05B05F +:10374000F0BD102C04D81B88ADF808300227DEE746 +:10375000202C03D81B6802930427D8E7402C05D8F7 +:10376000D3E90023CDE902230827D0E70027CEE7DD +:10377000394602A8FFF7FEFACCE700BF70B506464F +:103780000C4605E00D6806F10C00FFF723FCE56030 +:10379000E1680029F6D10023E360A3602361A382DE +:1037A00070BD00BF10F0800F04D010F4004F03D0A4 +:1037B00001207047022070470020704710B5044672 +:1037C000FFF7F0FF022802D0C4F3074010BDC4F396 +:1037D0000F2014F07F0FF9D100F00300F6E700BFCF +:1037E0002DE9F04F99B006460D4603920493D1F8A7 +:1037F00000904846FFF7D6FF0746022800F0888071 +:10380000C9F30628B9F1000F80F2028219F0C04F07 +:1038100040F001822C7B002C00F00082022F05D0AA +:103820003046FFF71FFD404540F0FB81C9F30463BC +:10383000099309F07F0A4846FFF7C0FF0A9040EA63 +:10384000074949EA8A4949EA4869013C2C4494F805 +:10385000048000220023CDE916235FEAD8130293E7 +:1038600059D07468CDF800A03B46024616A93046F0 +:10387000A047002800F0D88149463046FFF7B8FC41 +:103880000446002800F0D381A368E168039A0593F9 +:10389000D01A0790049B069163EB0103089395F8F7 +:1038A0000DC0CDF82CC094F81AC0CDF830C094F8F3 +:1038B0001790C9F3840908F01F0B59464846FFF7D3 +:1038C000D1F80D9049465846FFF7CCF86368059A41 +:1038D000069952EA010C34D09D4A07998A424FF06A +:1038E0000002089972EB010C7CD30B9A0C998A4266 +:1038F0001BD0984B079A93424FF00003089A9341CC +:1039000072D2029B002B71D00F2871DD002319E0C9 +:103910004FF0000876E749463046FFF74BF904467A +:103920000028B1D16FF00C0085E1029A002AE0D0A6 +:103930000D9A012A01DD012304E0002BD9D00123D7 +:1039400000E00123002B55D16A7BA37E9A4240F010 +:103950007181029B13B118F0400F66D1C8F3401378 +:10396000E27DB3EBD21F40F06981C2F384039B4533 +:1039700040F06781029B002B00F0908018F0400F10 +:1039800040F08C802B7B032B40F25E81039BA36075 +:10399000049BE360AF1D2B7B033BDBB23A46214621 +:1039A00006F10C00FFF772FA00286DDB2B796A79BB +:1039B00043EA02232383DDE916234FF6FF70FFF766 +:1039C000FDF9A0822A7B033AD2B23946FFF710FAFA +:1039D000A082E37DDA43C2F3C01262F3C713E3753A +:1039E000002028E10123ADE70023ABE70023A9E78E +:1039F0000123A7E7E37D68F38603E375DBB26FF38A +:103A0000C713E37521463046FFF7ECFA6B7BA376CC +:103A1000029B002B98D1E37DC3F38402013262F351 +:103A20008603E3756FF00C0005E1039BA360049A25 +:103A3000E260202200210EA8FDF772FC039B0E938A +:103A4000049A0F922B1D10932B7B013BDBB2ADF838 +:103A50004C300A9BADF84E308DF850708DF851B057 +:103A6000099B8DF852308DF853A096F82C3083F0D6 +:103A700001038DF85430B3680EA9304698472046AC +:103A8000FFF788F80020D6E021463046FFF7AAFA73 +:103A90002046FFF77FF86FF00200CCE0029B13B9DD +:103AA00018F0400F1ED095F80C9009F1FF395FFA1D +:103AB00089F9B4F81680C8F30908B8F1040F30D8B2 +:103AC00043464FF00008042B54D8C84552D205EBAA +:103AD00008021179E218D176013308F101085FFA82 +:103AE00088F8F0E72F1D2B7B013BDBB23A462146DD +:103AF00006F10C00FFF7CAF9002808DB2A7B013A1F +:103B0000D2B23946A08AFFF773F9A08261E7214655 +:103B10003046FFF767FA2046FFF73CF86FF00200E7 +:103B200089E0616806F10C00FEF794FF024608B1D7 +:103B3000052304E04FF000081CE01C330A4611681E +:103B40000029FAD1A8EB03034FF000080EE000BFF4 +:103B500080841E0040420F0005EB08010879D1184F +:103B60000871013308F101085FFA88F81B2B01D8AE +:103B7000C845F1D3039B0E93049B0F9304F11B03E1 +:103B80001093616806F10C00FEF764FF1190C845C0 +:103B900035D2A84408F104031293E38AC3F309035E +:103BA0009944ADF84C900A9BADF84E308DF85070AA +:103BB0008DF851B0099B8DF852308DF853A096F8CE +:103BC0002C3083F001038DF85430002363602A7B8E +:103BD000013A291DA08AFFF70BF9A082238B984296 +:103BE0000FD00EA93046FFF7C9FD2046FEF7D2FFE1 +:103BF000A28A238B9A4209D06FF010001BE00023A9 +:103C0000CAE7B3680EA930469847EAE7002012E0F9 +:103C10006FF009000FE06FF009000CE06FF0090091 +:103C200009E06FF00A0006E06FF00B0003E06FF0B0 +:103C3000020000E0002019B0BDE8F08F6FF00D0029 +:103C4000F9E76FF00E00F6E76FF00F00F3E700BF43 +:103C5000EFF30983683305494A6B22F001024A6396 +:103C600083F30988002383F31188704700EF00E095 +:103C7000302080F3118862B60C4BD96821F4E061E2 +:103C80000904090C0A4A0A43DA60D3F8FC2042F01E +:103C90008072C3F8FC2007490A6842F001020A60FA +:103CA0002022DA7783F82200704700BF00ED00E0A1 +:103CB0000003FA05001000E0302383F31188104B55 +:103CC0005B6813F4006F03D1002383F311887047FE +:103CD00010B5F1EE103AEFF30984683C4FF08073B1 +:103CE000E361084BDB6B236684F3098800F096F8E8 +:103CF00010B1054BA36110BD044BA361FBE700BFEE +:103D000000ED00E000EF00E03F0300084203000880 +:103D10000901C9B2074A131883F8001300F01F0104 +:103D2000400901238B4000F1600142F8213042F844 +:103D30002030704700E100E00023037503691B6831 +:103D4000996882689142FAD203605A6842601060B2 +:103D50005860704708B50846302383F311880B7DFF +:103D6000032B0ED0042B10D043B14FF0FF338361EF +:103D7000FFF7E2FF002383F3118808BD83F3118866 +:103D8000FBE78B6900221A60EFE74A680B68136053 +:103D90004A685A60E9E700BF0023037503691B689E +:103DA000996882689142FAD803605A68426010604C +:103DB0005860704708B5FFF7BFFF08BD08B5064B50 +:103DC000D9680875186802681A6053600122027584 +:103DD000D860FCF79FFA08BD284A002030B587B0AC +:103DE00004460C4BDD68B1F1FF3F0FD02B460A4A69 +:103DF000684600F01BF92046FFF7E0FF009B13B177 +:103E0000684600F021F9A86907B030BDFFF7D6FF7A +:103E1000F9E700BF284A0020553D0008044BDA6846 +:103E20001B6898689368984294BF002001207047EF +:103E3000284A002010B5084BD8681C6822681A6010 +:103E4000536001222275DC60FFF7A6FF0146204681 +:103E5000FCF760FA10BD00BF284A002008B50B4BE4 +:103E600001221A70002353B109490A4800F074FC7A +:103E7000064B02221A70002383F3118808BD034AFF +:103E800002EB8302002151600133ECE7904C0020EB +:103E9000C44F0008284A002008B572B6044B1865C4 +:103EA00000F0EEFA00F0D2FB024B03221A70FEE79C +:103EB000284A0020904C002008B500F0FFF808BD0B +:103EC0008B6002230B7500234B7508610846704711 +:103ED00008B58168A1F1840341F8143C026941F8F6 +:103EE000442C426941F8402C044A41F8242CC36810 +:103EF000026820390248FFF7E3FF08BD2D030008E0 +:103F0000284A002008B5FFF7E3FFFFF753FF08BD7D +:103F100008B5034BDB6898610F20FFF74FFF08BD22 +:103F2000284A002008B5302383F31188FFF7F0FFFB +:103F300008BD00BF08B50146302383F3118808206F +:103F4000FFF74CFF002383F3118808BDF8B5154631 +:103F50001C46C2608B60486003680B60596001605A +:103F6000092C00D80A24C068204400F0E1FB0A278D +:103F700000F0DAFB0646431B9C4202D90A2F07D801 +:103F8000F8BD7C1C281900F0E1FB27463546EFE719 +:103F9000012000F021FCF3E770B504460D46092925 +:103FA00000D80A250A26601900F0D0FB00F0BCFBFF +:103FB000041BA54202D90A2E04D870BD013635462D +:103FC0000446F0E7012000F007FCF6E7F8B50546E7 +:103FD0000E46174600F0A8FB2B689D4209D0EC68FE +:103FE000041B3C1900D33C469B68A34208D82B68AD +:103FF0000CE03B46024631462846FFF7A7FF14E097 +:104000003946FFF7C9FFF2E7A41A1B689A68944281 +:10401000FAD8B46033605A68726016605E609A685D +:10402000121B9A604FF0FF33AB60F8BD08B5036117 +:10403000C260002343610A4601460248FFF7C6FFFB +:1040400008BD00BF384A002008B51B4B1B699842C9 +:1040500010D042680368136042685A600268816841 +:1040600093680B44936000230360134B4FF0FF32BF +:104070009A6108BD1968104A134643F8101F4B6037 +:104080000021016012699A4212D0816893680B4442 +:10409000936000F049FB084AD369A0EB030C126956 +:1040A00091686145E5D91B1A1944FFF775FFE0E7F0 +:1040B00000F046FBDDE700BF284A0020F8B50BE022 +:1040C000002383F31188E368216920469847302351 +:1040D00083F311886369CBB92C4D2C6900F024FB64 +:1040E000EB69C21AA568954242D81D44274BDD6191 +:1040F000616822680A60616851600022226053F89A +:10410000102F9A42DCD100F01BFBD9E700F00CFB2A +:104110000746461B6269B2420CD32B1A13441B4A52 +:1041200052F8101F91420AD09E1900D23346174A06 +:1041300012690CE0022000F04FFB0023EFE73A4643 +:1041400021461348FFF702FF1FE05B1A12689168CF +:104150008B42FAD8A3602260516861600C605460A1 +:104160009168CB1A9360094B4FF0FF329A61B3E725 +:10417000064A52F8101F914207D0044AD0611B1A18 +:10418000A1681944A160FFF707FFF8BD284A002085 +:10419000384A002038B500F0C7FA054AD2E9084588 +:1041A000031B181945F10001C2E9080138BD00BF21 +:1041B000284A002000207047FEE700BF704700BF7C +:1041C0004FF0FF30704700BFBFF34F8F024BDB68EB +:1041D00013F4803FFAD17047003C0240014BF322B8 +:1041E000DA607047003C024008B50B4B1B7803B106 +:1041F00008BDFFF7E9FF094B1B69002B05DB074AE8 +:10420000136823F480631360F2E7044B044A5A6096 +:1042100002F188325A60F2E7984C0020003C0240DC +:104220002301674508B50C4B1B7803B108BDFFF7A8 +:10423000CBFF0A4B1A6942F000421A611A6842F435 +:1042400080521A601A6822F480521A601A6842F486 +:1042500080621A60EAE700BF984C0020003C0240F0 +:1042600012F0010F65D1F8B504460E461546131835 +:10427000B3F1016F5FD8314B1B6813F0010F01D10F +:10428000002059E0FFF7B0FFFFF7A8FFFFF79CFF02 +:10429000032D29D914F0030F26D1294A136923F4D9 +:1042A00040731361136943F4007343F00103136116 +:1042B00037682760BFF34F8FFFF786FF23689F4261 +:1042C00003D1043D04360434E2E71D4A136923F0A8 +:1042D0000103136104E01A4A136923F00103136117 +:1042E000FFF7A0FF002027E0012D19D9144A136918 +:1042F00023F440731361136943F4807343F00103A3 +:10430000136133882380BFF34F8FFFF75DFF23884E +:104310009BB232889A42DED1023D02360234E3E794 +:10432000074A136923F001031361FFF77BFF0120A4 +:1043300002E0002070470020F8BD00BF00380240B6 +:10434000003C0240014B53F820007047D04F00085A +:104350000B281AD870B506460D4B1B788BB9002474 +:104360004FF0006508E00B4B43F824502046FFF760 +:10437000E9FF05440134E4B20B2CF4D9044B0122CB +:104380001A70044B53F8260070BD0020704700BF20 +:10439000CC4C00209C4C00200C2070470B2801D9ED +:1043A0000020704738B50546FFF7D2FF044628467F +:1043B000FFF7C8FF30B12368B3F1FF3F04D10438E1 +:1043C0000434F7E7012038BD0020FCE70B2801D9B1 +:1043D0000020704738B50446FFF7F6FEFFF704FFEC +:1043E000FFF7FCFE154BA3FB0423DB081A4603EB87 +:1043F0004303A4EB8303DB00DBB2D201D2B213434D +:1044000043F4007343F002030D4A1361136943F44C +:1044100080331361FFF7D8FE2046FFF799FF05466A +:104420002046FFF78FFF0146284600F00BF9FFF703 +:10443000F9FE2046FFF7B2FF38BD00BFABAAAAAA1B +:10444000003C024008B5FFF70BFF08BD08B5034666 +:1044500010B10A4A127822B113B9084B1B7833B94C +:1044600008BDFFF7C1FE054B01221A70F8E7034BA8 +:1044700000221A70FFF7D6FEF2E700BF984C00202A +:1044800010B500240BE0074804EB44039A001346E0 +:1044900003445968805800F0D7F80134E4B2012C85 +:1044A000F1D910BD0050000808B50846114600F0CB +:1044B00077FC08BD08B5012000F072FC08BD00BF04 +:1044C00008B5084600F08AFC08BD00BF302383F31E +:1044D00011887047002383F311887047302383F3DA +:1044E00011887047002383F311887047FFF752BE8D +:1044F000EFF3118303BB00B583B0EFF30583C3F380 +:10450000080363B9FFF7E2FFFFF7F0FFCDE9001002 +:10451000FFF7E0FFDDE9001003B05DF804FBFFF7F3 +:10452000DDFFFFF7E3FFCDE90010FFF7DBFFDDE97B +:10453000001003B05DF804FBFFF7D8BF38B5FFF7F4 +:10454000D7FF114C114AC00840EA4170A0FB025E3F +:10455000C908A0FB040C1CEB050CA1FB04404FF0A8 +:1045600000035B41A1FB02121CEB040C43EB0000B7 +:1045700011EB0E0142F10002411842F1000009095D +:1045800041EA007038BD00BFCFF753E3A59BC420BC +:1045900009E000F1010C064A52F8202041F8042BF2 +:1045A0001A465FFA8CF0531EDBB2002AF1D1704735 +:1045B0005028004010B4124B1B6F13F4004F08D169 +:1045C0000F4B1C6F44F400741C671C6F44F40044D0 +:1045D0001C670C4C236843F48073236009E000F1EE +:1045E000010C51F8044B084A42F820401A465FFA81 +:1045F0008CF0531EDBB2002AF1D15DF8044B7047FA +:1046000000380240007000405028004000B583B0E0 +:10461000012201A90020FFF7BBFF019803B05DF85C +:1046200004FB00BF10B582B00446FFF7EFFFA042C5 +:1046300001D102B010BD0194012201A90020FFF7B1 +:10464000B9FFF6E7704700BF704700BF704700BF73 +:10465000074B45F255521A6002225A6040F6FF722B +:104660009A604CF6CC421A60024B01221A707047D5 +:1046700000300040D44C0020034B1B781BB1034B8F +:104680004AF6AA221A607047D44C0020003000403D +:10469000044B1B6823B9044BD3F87428014B1A60F0 +:1046A000704700BFD04C002000300240024B4FF05A +:1046B0008072C3F8742870470030024008B5FFF7D5 +:1046C000E7FF024B1868C0F3407008BDD04C0020D3 +:1046D00008B5FFF7DDFF024B1868C0F3007008BD96 +:1046E000D04C0020704700BFFEE700BF084B0949CF +:1046F00003E051F8042B43F8042B074A9342F8D304 +:1047000002E0002243F8042B044A9342F9D3704795 +:10471000604D0020A8510008604D0020604D002031 +:1047200008B500F0DBF808BD4FF08043586A7047C9 +:104730004FF08043586300221A610222DA6070470A +:104740004FF080430022DA60704700BF4FF0804393 +:1047500058637047FEE700BF70B586B004460E464A +:10476000194B5860002585620163FFF781FA2460C8 +:104770006460A560E56204F11003236163614FF09A +:10478000FF33A361E561FFF7CFFF02462B46C4E983 +:104790000823256580230D4A04F134012046FFF7E4 +:1047A0008FFBE06001230375094A00927268019251 +:1047B000B26802920393074B049305956846FFF78E +:1047C000A1FB06B070BD00BF904C0020185000083F +:1047D0002050000855470008024AD36A0343D362B9 +:1047E000704700BF284A00204B6843608B68836095 +:1047F000CB68C3600B6943614B6903628B69436299 +:104800000B680360704700BF10B5214B1A6940F276 +:10481000FF110A431A611A6922F4FF7222F00102A1 +:104820001A611A691A6B0A431A631A6D0A431A65E8 +:104830001B6D184C21461848FFF7D6FF04F11C01E8 +:104840001648FFF7D1FF04F138011548FFF7CCFFF8 +:1048500004F154011348FFF7C7FF04F17001124837 +:10486000FFF7C2FF04F18C011048FFF7BDFF04F110 +:10487000A8010F48FFF7B8FF04F1C4010D48FFF786 +:10488000B3FF04F1E0010C48FFF7AEFF10BD00BF1D +:104890000038024028500008000002400004024096 +:1048A00000080240000C02400010024000140240C8 +:1048B00000180240001C02400020024008B5FFF72B +:1048C000A3FF00F095F808BD08B500F025FAFFF742 +:1048D000C5FAFFF7DDFE08BD704700BF0F4B1A6C2D +:1048E00042F001021A641A6E42F001021A661B6E4F +:1048F0000B4A936843F0010393604FF080435322C7 +:104900009A624FF0FF32DA6200229A615A63DA60EB +:104910005A6001225A611A60704700BF0038024095 +:10492000002004E008B54FF080421369D168C9B295 +:104930000B40D943116113F0020F00D108BD3023A1 +:1049400083F31188FFF7B8FA002383F31188F5E7A2 +:104950000B4A136843F4807313600A4B1B6F03F414 +:104960004073B3F5007F05D0064B4FF480321A67D1 +:1049700000221A67024A536823F400735360704799 +:10498000007000400038024008B5184B1A696FEA01 +:10499000C2526FEAD2521A611A69C2F308021A614E +:1049A0001A695A694FF0FF3058615A6900215961FC +:1049B0005A691A6A62F080521A621A6A02F08052C8 +:1049C0001A621A6A5A6A58625A6A59625A6A1A6CA0 +:1049D00042F080521A641A6E42F080521A661B6EC0 +:1049E000FFF7B6FF00F076F908BD00BF00380240BF +:1049F0003B4B4FF080521A643A4A4FF440411160E9 +:104A00001A6842F001021A60354B1B6813F0020F5E +:104A1000FAD0334A936823F003039360304B9B68CA +:104A200013F00C0FFAD12E4B1A6802F0F9021A603B +:104A300000229A601A6842F480321A60284B1B6880 +:104A400013F4003FFAD0264A536F43F00103536733 +:104A5000234B5B6F13F0020FFAD0214B224A5A60AE +:104A60001A6842F080721A601E4B5B6813F4804F24 +:104A7000FAD01B4B1B6813F0007FFAD0184B1B4A6F +:104A80009A601B4B1A681B4B9A421FD01A4B40F27C +:104A900005721A60184B1B6803F00F03052BF9D140 +:104AA0000F4A936843F0020393600D4B9B6803F039 +:104AB0000C03082BF9D10A4B5A6C42F480425A6419 +:104AC0005A6E42F480425A665B6E70470B4B1A680E +:104AD0000B4B9A42DAD1084B40F205121A60D9E723 +:104AE00000380240007000400854400700948838A5 +:104AF000002004E011640020003C024000ED00E0D2 +:104B000041C20F4108B5074A536903F001035361DD +:104B10002BB1054B1B6813B1034A50689847FFF748 +:104B2000CBF808BD003C0140D84C002008B5074A2E +:104B3000536903F0020353612BB1054B9B6813B11A +:104B4000034AD0689847FFF7B7F808BD003C01401A +:104B5000D84C002008B5074A536903F00403536199 +:104B60002BB1054B1B6913B1034A50699847FFF7F6 +:104B7000A3F808BD003C0140D84C002008B5074A06 +:104B8000536903F0080353612BB1054B9B6913B1C3 +:104B9000034AD0699847FFF78FF808BD003C0140F1 +:104BA000D84C002008B5074A536903F0100353613D +:104BB0002BB1054B1B6A13B1034A506A9847FFF7A4 +:104BC0007BF808BD003C0140D84C002010B51A4BC2 +:104BD0005C6904F478725A6114F0200F05D0174B09 +:104BE0009B6A13B1154AD06A984714F0400F05D05C +:104BF000124B1B6B13B1114A506B984714F0800F86 +:104C000005D00E4B9B6B13B10C4AD06B984714F434 +:104C1000807F05D0094B1B6C13B1084A506C984734 +:104C200014F4007F05D0054B9B6C13B1034AD06C84 +:104C30009847FFF741F810BD003C0140D84C0020D8 +:104C400010B51F4B5C6904F47C425A6114F4806F08 +:104C500005D01C4B1B6D13B11A4A506D984714F4C4 +:104C6000006F05D0174B9B6D13B1164AD06D984756 +:104C700014F4805F05D0134B1B6E13B1114A506EB4 +:104C8000984714F4005F05D00E4B9B6E13B10D4A8C +:104C9000D06E984714F4804F05D00A4B1B6F13B1A8 +:104CA000084A506F984714F4004F05D0054B9B6F8E +:104CB00013B1044AD06F9847FEF7FEFF10BD00BF46 +:104CC000003C0140D84C002008B5FFF72BFEFEF752 +:104CD000F3FF08BD08B506210846FFF719F80621BD +:104CE0000720FFF715F806210820FFF711F8062125 +:104CF0000920FFF70DF806210A20FFF709F8062121 +:104D00001720FFF705F806212820FFF701F80721F3 +:104D10001C20FEF7FDFF08BD08B5FFF735FE00F0CB +:104D200005F8FFF7D9FDFFF7FBFC08BD002307E0FE +:104D3000054A002142F8331002EBC30251600133EF +:104D40000F2BF5D9704700BFD84C00200B46014609 +:104D5000184600F02DB8000000F040B8012838BF18 +:104D6000012010B50446204600F030F830B900F0BC +:104D700007F808B900F00CF88047F4E710BD000010 +:104D8000024B1868BFF35B8F704700BF584D00207F +:104D900008B5062000F084F80120FFF70DFA0000A6 +:104DA000024B0A4601461868FFF77EBB1C23002011 +:104DB00010B5054C13462CB10A4601460220AFF34C +:104DC000008010BD2046FCE700000000024B0146B9 +:104DD0001868FFF76FBB00BF1C230020024B014681 +:104DE0001868FFF76DBB00BF1C23002010B5013908 +:104DF0000244904201D1002005E0037811F8014FF0 +:104E0000A34201D0181B10BD0130F2E72DE9F0419B +:104E1000A3B1C91A17780144044603F1FF3C8C4240 +:104E2000204601D9002009E00578BD4204F10104C3 +:104E3000F5D10CEB0405D618A54201D1BDE8F081EF +:104E400015F8018D16F801EDF045F5D0E7E7000003 +:104E50001F2938B504460D4604D9162303604FF0C8 +:104E6000FF3038BD426C12B152F821304BB92046A8 +:104E700000F030F82A4601462046BDE8384000F0F0 +:104E800017B8012B0AD0591C03D116230360012047 +:104E9000E7E7002442F82540284698470020E0E74D +:104EA000024B01461868FFF7D3BF00BF1C23002048 +:104EB00038B5074D00230446084611462B60FFF71E +:104EC0007FF9431C02D12B6803B1236038BD00BFBA +:104ED0005C4D0020FFF76EB96F72672E61726475CA +:104EE00070696C6F742E41522D46343037536D61AA +:104EF000727442617400000040A2E4F1646891069B +:104F00000000000041A3E5F265699207000000007F +:104F10004261642043414E496661636520696E6465 +:104F200065782E00800000000080000000008000F6 +:104F30000000000000000000251C0008A12500085A +:104F4000F1240008611C00086D1C0008E51D000824 +:104F5000311C0008411C0008351C00083D1C0008DD +:104F6000391C00089D1D0008451C00087129000817 +:104F7000551C0008B91D00080000000000000000DA +:104F8000251C0008012900082529000829290008F6 +:104F90008929000839290008311C00082D2900083A +:104FA000351C000831290008391C00083529000883 +:104FB00001290008712900080129000801290008B9 +:104FC00063300000C04F0008804A0020904C002051 +:104FD00000400000004000000040000000400000D1 +:104FE00000000100000002000000020000000200BA +:104FF00000000200000002000000020000000200A9 +:105000000001002000FF010001000000000002205C +:1050100000000200020000006D61696E00000000E7 +:1050200069646C65000000000000802A0000000038 +:10503000AAAAAAAA00000024FFFF000000000000A6 +:10504000009009000000000000000000AAAAAAAA1F +:1050500000000000FFFF0000000000000000000052 +:105060000000000500000000AAAAAAA60000000097 +:10507000FFEF000000000000000000000000000042 +:1050800000000000AAAAAAAA00000000FFFF00007A +:105090000000000000000000000000000000000010 +:1050A000AAAAAAAA00000000FFFF0000000000005A +:1050B000000000000000000000000000AAAAAAAA48 +:1050C00000000000FFFF00000000000000000000E2 +:1050D0000000000000000000AAAAAAAA0000000028 +:1050E000FFFF0000000000000000000000000000C2 +:1050F000000000000A0000000000000003000000A3 +:10510000000000000000000000000000000000009F +:10511000000000000000000000000000000000008F +:1051200000000000000000006E040000000000000D +:1051300000000F000000000040420F00FE2A0100A6 +:10514000D204000020230020000000000000000026 +:10515000000000000000000000000000000000004F +:10516000000000000000000000000000000000003F +:10517000000000000000000000000000000000002F +:10518000000000000000000000000000000000001F +:10519000000000000000000000000000000000000F +:0851A000000000000000000007 :00000001FF diff --git a/Tools/bootloaders/ARK_CANNODE_bl.bin b/Tools/bootloaders/ARK_CANNODE_bl.bin old mode 100644 new mode 100755 index 3d2eb3c643b5fc..a3f1f4315e0d1e Binary files a/Tools/bootloaders/ARK_CANNODE_bl.bin and b/Tools/bootloaders/ARK_CANNODE_bl.bin differ diff --git a/Tools/bootloaders/ARK_CANNODE_bl.hex b/Tools/bootloaders/ARK_CANNODE_bl.hex index 352197b9428a9e..4f899ae93904d8 100644 --- a/Tools/bootloaders/ARK_CANNODE_bl.hex +++ b/Tools/bootloaders/ARK_CANNODE_bl.hex @@ -1,1376 +1,1376 @@ :020000040800F2 -:1000000000070020F5040008FD2A0008B52A0008B2 -:10001000DD2A0008B52A0008D52A0008F7040008E0 -:10002000F7040008F7040008F7040008F13A000894 -:10003000F7040008F7040008F7040008F7040008B4 -:10004000F7040008F7040008F7040008F7040008A4 -:10005000F7040008F7040008254F00084D4F00087A -:10006000754F00089D4F0008C54F0008F7040008B1 -:10007000F7040008F7040008F7040008F704000874 -:10008000F7040008F7040008F7040008692A0008CC -:10009000952A0008A52A0008F7040008ED4F00087B -:1000A000F7040008F7040008F7040008F704000844 -:1000B000F7040008F7040008F7040008F704000834 -:1000C000F7040008F7040008F7040008F704000824 -:1000D000F7040008C1500008D5500008F7040008D4 -:1000E00051500008F7040008F7040008F70400085E -:1000F000F7040008F7040008F7040008F7040008F4 -:10010000F7040008F7040008E9500008F7040008A5 -:10011000F7040008F7040008F7040008F7040008D3 -:10012000F7040008F7040008F7040008F7040008C3 -:10013000F7040008F7040008F7040008F7040008B3 -:10014000F7040008F7040008F7040008F7040008A3 -:10015000F7040008F7040008F7040008F704000893 -:10016000F7040008F7040008F7040008F704000883 -:10017000F7040008F7040008F7040008F704000873 -:10018000F7040008F7040008F7040008F704000863 -:10019000F7040008F7040008F7040008F704000853 -:1001A000F7040008F7040008F7040008F704000843 -:1001B000F7040008F7040008F7040008F704000833 -:1001C000F7040008F7040008F7040008F704000823 -:1001D000F7040008F7040008F7040008F704000813 -:1001E000D916000800000000000000000000000018 -:1001F00053B94AB9002908BF00281CBF4FF0FF318E -:100200004FF0FF3000F074B9ADF1080C6DE904CE89 -:1002100000F006F8DDF804E0DDE9022304B07047E1 -:100220002DE9F047089D04468E46002B4DD18A42A9 -:10023000944669D9B2FA82F252B101FA02F3C2F1DC -:10024000200120FA01F10CFA02FC41EA030E94406D -:100250004FEA1C48210CBEFBF8F61FFA8CF708FB8E -:1002600016E341EA034306FB07F199420AD91CEB66 -:10027000030306F1FF3080F01F81994240F21C8198 -:10028000023E63445B1AA4B2B3FBF8F008FB1033E0 -:1002900044EA034400FB07F7A7420AD91CEB040415 -:1002A00000F1FF3380F00A81A74240F207816444E5 -:1002B000023840EA0640E41B00261DB1D44000236A -:1002C000C5E900433146BDE8F0878B4209D9002DCE -:1002D00000F0EF800026C5E9000130463146BDE858 -:1002E000F087B3FA83F6002E4AD18B4202D38242C2 -:1002F00000F2F980841A61EB030301209E46002D71 -:10030000E0D0C5E9004EDDE702B9FFDEB2FA82F2C5 -:10031000002A40F09280A1EB0C014FEA1C471FFA23 -:100320008CFE0126200CB1FBF7F307FB131140EA0A -:1003300001410EFB03F0884208D91CEB010103F1D7 -:10034000FF3802D2884200F2CB804346091AA4B299 -:10035000B1FBF7F007FB101144EA01440EFB00FE6D -:10036000A64508D91CEB040400F1FF3102D2A645D2 -:1003700000F2BB800846A4EB0E0440EA03409CE771 -:10038000C6F12007B34022FA07FC4CEA030C20FA1E -:1003900007F401FA06F31C43F9404FEA1C4900FA3E -:1003A00006F3B1FBF9F8200C1FFA8CFE09FB1811BB -:1003B00040EA014108FB0EF0884202FA06F20BD92E -:1003C0001CEB010108F1FF3A80F08880884240F27E -:1003D0008580A8F102086144091AA4B2B1FBF9F0C2 -:1003E00009FB101144EA014100FB0EFE8E4508D9BD -:1003F0001CEB010100F1FF346CD28E456AD9023842 -:10040000614440EA0840A0FB0294A1EB0E01A14226 -:10041000C846A64656D353D05DB1B3EB080261EB94 -:100420000E0101FA07F722FA06F3F1401F43C5E96E -:10043000007100263146BDE8F087C2F12003D840A4 -:100440000CFA02FC21FA03F3914001434FEA1C47E6 -:100450001FFA8CFEB3FBF7F007FB10360B0C43EAD8 -:10046000064300FB0EF69E4204FA02F408D91CEB88 -:10047000030300F1FF382FD29E422DD90238634486 -:100480009B1B89B2B3FBF7F607FB163341EA034126 -:1004900006FB0EF38B4208D91CEB010106F1FF3875 -:1004A00016D28B4214D9023E6144C91A46EA00466C -:1004B00038E72E46284605E70646E3E61846F8E6FE -:1004C0004B45A9D2B9EB020864EB0C0E0138A3E747 -:1004D0004646EAE7204694E74046D1E7D0467BE728 -:1004E000023B614432E7304609E76444023842E7A0 -:1004F000704700BF02E000F000F8FEE772B6374830 -:1005000080F30888364880F3098836483649086001 -:1005100040F20000CCF200004EF63471CEF2000141 -:100520000860BFF34F8FBFF36F8F40F20000C0F23F -:10053000F0004EF68851CEF200010860BFF34F8FF5 -:10054000BFF36F8F4FF00000E1EE100A4EF63C71E2 -:10055000CEF200010860062080F31488BFF36F8F8D -:1005600004F0E2FA04F07AFB4FF055301F491B4AC1 -:1005700091423CBF41F8040BFAE71D49184A9142E9 -:100580003CBF41F8040BFAE71A491B4A1B4B9A423D -:100590003EBF51F8040B42F8040BF8E7002018495D -:1005A000184A91423CBF41F8040BFAE704F0C0FA44 -:1005B00004F0A2FB144C154DAC4203DA54F8041BB2 -:1005C0008847F9E700F042F8114C124DAC4203DACB -:1005D00054F8041B8847F9E704F0A8BA0007002084 -:1005E000002300200000000808ED00E000010020CA -:1005F0000007002090550008002300208C230020D5 -:1006000090230020284F0020E0010008E4010008AA -:10061000E4010008E40100082DE9F04F2DED108AF7 -:10062000C1F80CD0C3689D46BDEC108ABDE8F08FC0 -:10063000002383F311882846A047002003F0D4FE4E -:10064000FEE703F037FE00DFFEE70000F8B501F03B -:1006500055F804F003FA074604F052FA0546B8BB11 -:10066000204B9F4234D001339F4234D01E4B27F0A1 -:10067000FF029A4232D1F8B200F044FE2E4642F216 -:10068000107400F045FE08B10024264601F02AFB54 -:1006900020B1032000F07CF80024264635B1134B2E -:1006A0009F4203D004F024FA00242646002004F0E0 -:1006B000DFF90EB100F082F801F0A4F900F086FE37 -:1006C00001F088F8204600F0CDF800F077F8F9E75F -:1006D0002E460024D5E704460126D2E7064641F21D -:1006E0008834CEE7010007B0000008B0263A09B010 -:1006F00008B501F03BF8A0F120035842584108BD6D -:1007000007B541F21203022101A8ADF8043001F04F -:100710004BF803B05DF804FB38B5302383F3118840 -:10072000174803680BB103F01DFF164A1448002355 -:100730004FF47A7103F00CFF002383F31188124CFD -:10074000236813B12368013B2360636813B16368B6 -:10075000013B63600D4D2B7833B963687BB9022090 -:1007600001F0E6F8322363602B78032B07D163682E -:100770002BB9022001F0DCF84FF47A73636038BDC6 -:100780009023002019070008B0240020A82300208F -:10079000084B187003280CD8DFE800F008050208A1 -:1007A000022001F0C3B8022001F0BEB8024B0022C3 -:1007B0005A607047A8230020B024002010B501F033 -:1007C00091FA30B1204B03221A70204B00225A605C -:1007D00010BD1F4B1F4A1C4619680131F8D0043365 -:1007E0009342F9D162681C4B9A42F1D91B4B9B682A -:1007F00003F1006303F580339A42E9D204F04CF927 -:1008000004F05EF9002000F0FFFF0220FFF7C0FFB8 -:10081000134B1A6C00221A64196E1A66196E596C01 -:100820005A64596E5A665B6E72B64FF0E0233021FF -:10083000C3F8084DD4E9003281F311889D4683F353 -:1008400008881047C4E700BFA8230020B024002078 -:100850000000010820000108FFFF0008002300201D -:10086000003802402DE9F04F93B0AC4B00902022AD -:10087000FF210AA89D6801F06FF8A94A1378A3B96F -:10088000A848012103601170302383F311880368A5 -:100890000BB103F067FEA44AA24800234FF47A711B -:1008A00003F056FE002383F31188009B13B19F4B86 -:1008B000009A1A609E4A009C1378032B1EBF0023E7 -:1008C00013709A4A4FF0000A18BF5360D346564639 -:1008D000D146012001F02AF824B1944B1B68002B6B -:1008E00000F01582002000F041FF0390039B002BD5 -:1008F00001DA00F0B3FD039B002BEDDB012001F0DA -:1009000013F8039B213B162BE3D801A252F823F0E6 -:100910006D09000895090008290A0008D308000895 -:10092000D3080008D3080008B30A0008830C0008A5 -:100930009D0B0008FF0B0008270C00084D0C000859 -:10094000D30800085F0C0008D3080008D10C000889 -:100950000D0A0008D3080008150D000879090008E1 -:100960000D0A0008D3080008FF0B00080220FFF75B -:10097000BFFE002840F0F581009B0221BAF1000F74 -:1009800008BF1C4605A841F21233ADF8143000F040 -:100990000BFF9EE74FF47A7000F0E8FE071EEBDBDA -:1009A0000220FFF7A5FE0028E6D0013F052F00F248 -:1009B000DA81DFE807F0030A0D10133605230593EB -:1009C000042105A800F0F0FE17E054480421F9E7DF -:1009D00058480421F6E758480421F3E74FF01C0873 -:1009E000404600F013FF08F104080590042105A813 -:1009F00000F0DAFEB8F12C0FF2D1012000FA07F76F -:100A000047EA0B0B5FFA8BFB4FF0000900F0F0FF99 -:100A100026B10BF00B030B2B08BF0024FFF770FE71 -:100A200057E746480421CDE7002EA5D00BF00B0375 -:100A30000B2BA1D10220FFF75BFE074600289BD0BD -:100A4000012000F0E1FE0220FFF7A2FE00265FFA7F -:100A500086F8404600F0E8FE044690B1002140468A -:100A600000F0F2FE01360028F1D1BA46044641F208 -:100A70001213022105A8ADF814303E4600F094FE92 -:100A800027E70120FFF784FE2546244B9B68AB42F5 -:100A900007D9284600F0BAFE013040F067810435DE -:100AA000F3E7234B00251D70204BBA465D603E46A0 -:100AB000ACE7002E3FF460AF0BF00B030B2B7FF481 -:100AC0005BAF0220FFF764FE322000F04FFEB0F172 -:100AD0000008FFF651AF18F003077FF44DAF0F4A3F -:100AE000926808EB050393423FF646AFB8F5807F66 -:100AF0003FF742AF124B0193B84523DD4FF47A70B4 -:100B000000F034FE0390039A002AFFF635AF019BF4 -:100B1000039A03F8012B0137EDE700BF0023002003 -:100B2000AC2400209023002019070008B0240020E6 -:100B3000A823002004230020082300200C230020E9 -:100B4000AC230020C820FFF7D3FD074600283FF460 -:100B500013AF1F2D11D8C5F1200242450AAB25F075 -:100B6000030028BF424683490192184400F0E2FE88 -:100B7000019A8048FF2100F0EFFE4FEAA8037D496B -:100B80000193C8F38702284600F0EEFE06460028CF -:100B90003FF46DAF019B05EB830537E70220FFF7BC -:100BA000A7FD00283FF4E8AE00F06EFE00283FF4F9 -:100BB000E3AE0027B846704B9B68BB4218D91F2F85 -:100BC00011D80A9B01330ED027F0030312AA134455 -:100BD00053F8203C05934046042205A901F03AF859 -:100BE00004378046E7E7384600F010FE0590F2E74C -:100BF000CDF81480042105A800F0D6FD06E70023F7 -:100C0000642104A8049300F0C5FD00287FF4B4AE6D -:100C10000220FFF76DFD00283FF4AEAE049800F00F -:100C20001BFE0590E6E70023642104A8049300F06E -:100C3000B1FD00287FF4A0AE0220FFF759FD002887 -:100C40003FF49AAE049800F017FEEAE70220FFF79F -:100C50004FFD00283FF490AE00F026FEE1E70220B1 -:100C6000FFF746FD00283FF487AE05A9142000F0E9 -:100C700021FE04210746049004A800F095FD3946A2 -:100C8000B9E7322000F072FD071EFFF675AEBB0714 -:100C90007FF472AE384A926807EB090393423FF63D -:100CA0006BAE0220FFF724FD00283FF465AE27F06D -:100CB00003074F44B9453FF4A9AE484600F0A6FDEE -:100CC0000421059005A800F06FFD09F10409F1E782 -:100CD0004FF47A70FFF70CFD00283FF44DAE00F0A2 -:100CE000D3FD002844D00A9B01330BD008220AA967 -:100CF000002000F039FE00283AD02022FF210AA867 -:100D000000F02AFEFFF7FCFC1C4803F073FB13B055 -:100D1000BDE8F08F002E3FF42FAE0BF00B030B2B32 -:100D20007FF42AAE0023642105A8059300F032FD6C -:100D3000074600287FF420AE0220FFF7D9FC80464A -:100D400000283FF419AEFFF7DBFC41F2883003F0D6 -:100D500051FB059800F06AFE464600F049FE3C460D -:100D6000B7E5064652E64FF0000905E6BA467EE6CC -:100D700037467CE6AC23002000230020A08601003B -:100D8000094A136849F2690099B21B0C00FB013350 -:100D90001360064B186844F2506182B2000C01FBEC -:100DA0000200186080B2704718230020142300202E -:100DB00010B500211022044600F0CEFD034B03CBFA -:100DC000206061601868A06010BD00BF107AFF1F2E -:100DD0002DE9F041ADF54E7D0DF134086CAC40F2DB -:100DE000751207460D460EA80021C8F8001000F045 -:100DF000B3FD4FF4C4720021204600F0ADFD01F0B8 -:100E000085FE254B4FF47A72B0FBF2F0186093E840 -:100E10000700012384E807000DF5E9702382FFF73E -:100E2000C7FF4FF4A6431D49238406A804F072FAB5 -:100E3000192384F832310DF2E32206AB0DF1300CA8 -:100E40001E4603CE664510605160334602F108022B -:100E5000F6D13378137041460122204600F000FE9F -:100E600000230393AB7E029305F11903019380B233 -:100E70000123CDE904800093E97E05A3D3E9002393 -:100E8000384602F00BFA0DF54E7DBDE8F08100BF4B -:100E90009E6AC421818A46EEB824002024530008AB -:100EA0002DE9F043224DBBB001F030FEAB6840F2BB -:100EB000ED22C31A934232D906AFA8602B462822EE -:100EC0000021384602F09AFB05F10E0000F03CFDCF -:100ED000002604465FFA80F905F10E08F3B2F1002E -:100EE000994501F1280107D908EB06030822384685 -:100EF00002F084FB0136F1E708230122CDE902323A -:100F000005340C4B0193A4B230230093CDE9047453 -:100F100005A3D3E90023297B074802F0BFF93BB0C2 -:100F2000BDE8F083AFF3008078F6339F93CACD8D90 -:100F3000D0450020DD450020D0340020F0B58B8A5C -:100F4000013B9BB2C92BC9B006460C4647D8274D7A -:100F50002F7B27BB05F10C03009308223B46394643 -:100F6000204602F00FFA7B1CFAB2D9001F46A38A72 -:100F7000013B9A4205DA0E322A44009200230822ED -:100F8000EEE700230022C5E900230023AB6085F8CB -:100F9000D730C5F8D8302B7B0BB9E37E2B73812279 -:100FA000002106AD27A800F0D7FC0122294627A87A -:100FB00000F024FE00230393A37E029304F119039F -:100FC00080B201932823CDE90450E17E009330469E -:100FD00004A3D3E9002302F061F9FFF761FF49B0F0 -:100FE000F0BD00BF26417272DF25D7B7D045002083 -:100FF00070B50D4614461E4602F0ACF850B9022EEC -:1010000010D1012C0ED112A3D3E90023C5E900238E -:10101000012007E0282C10D005D8012C09D0052C80 -:101020000FD0002070BD302CFBD10BA3D3E90023DF -:10103000ECE70BA3D3E90023E8E70BA3D3E90023F4 -:10104000E4E70BA3D3E90023E0E700BFAFF30080A0 -:10105000401DA12026812A0B78F6339F93CACD8D9F -:101060009E6AC421818A46EE26417272DF25D7B777 -:10107000F017304A39059E562DE9F04F8DB002AF7A -:1010800080460D4602F066F8044600285CD12B7EAF -:10109000022B1BD1EB8A012B18D101F037FD06463C -:1010A000FFF76EFE03464FF4C870DFF81C92B3FBE7 -:1010B000F0F206F5167602FB103316FA83F3C9F840 -:1010C0000030EB7E33B97B4B00221A702C37BD46C3 -:1010D000BDE8F08FAB8AE6B2013BB34204F10104F4 -:1010E0000CD907F108031E44E100009600230822F2 -:1010F00001F0F801284602F045F9EBE707F1180086 -:10110000FFF756FE324607F1180107F1080004F018 -:101110008BF80028D7D10F2E08D8664B1E70D9F84F -:101120000030A3F51673C9F80030CFE7FB1DF87146 -:101130000146009307220346284602F023F9F97975 -:10114000404601F0FFFFC1E7EB8A282B26D010D8DC -:10115000012B1ED0052BB9D1BFF34F8F5649574BEA -:10116000CA6802F4E0621343CB60BFF34F8F00BF45 -:10117000FDE7302BAAD16B7E514C0133627BDBB291 -:101180009342E94603D1EA7E237B9A420BD0CD46B7 -:101190009CE729464046FFF71BFE97E72946404655 -:1011A000FFF7CCFE92E74FF0000807F11803A7F80D -:1011B00018801022009341460123284602F0E2F8ED -:1011C000AE8A023EB6B2F31C9B109B000733DB08CD -:1011D000A9EBC3039D460DF1080A1FFA88F34FEAF5 -:1011E000C8019E4201F110010AD90AEB08030093DD -:1011F00008220023284602F0C5F808F10108ECE7B0 -:1012000094F8D70000F010FBD4F8D810054619B9AF -:1012100094F8D70000F018FBD4F8D83033449D423E -:1012200005D294F8D7000021013000F00DFB4FEA01 -:10123000960B4FF000081FFA88F18B45D4E9003275 -:1012400009D90AEB880103EB8800012200F08CFB2E -:1012500008F10108EFE7F31842F10002C4E9003297 -:10126000D4F8D83094F8D70006EB0308C4F8D88037 -:1012700000F0DAFA804509D394F8D730D4F8D800D2 -:101280000133401B84F8D730C4F8D800FF2E0D4D31 -:1012900009D80023237300F0F7FA00F023FD28811A -:1012A00008B9FFF78BFA23689B0A01332B810023CF -:1012B000A3606CE7C934002000ED00E00400FA05EB -:1012C000D0450020B8240020CC34002010B50A4BB3 -:1012D0000A4A1A6003F5805393F860203AB9DC6D2E -:1012E0002CB1204600F076FD204603F053FFBDE808 -:1012F0001040034800F06EBD00350020DC530008AC -:1013000048450020014B1870704700BFC4240020DE -:1013100030B54FF00054244B22689A4285B007D074 -:1013200003F0F8FB0446A8B90024204605B030BD00 -:101330001E4B627D1A701E48237D03731D49C9220E -:101340000E3000F0F7FA2046E022002100F004FB06 -:101350000124EAE7184A194D136C43F00073136433 -:10136000AA6D174B9A42DFD12B6E013B7E2BDBD847 -:10137000144A07CA01AB83E807001846032100F0AE -:101380007FFC6B6D83424FF00003CDD12A6D8A4202 -:1013900001BFAB65054B2A6E1A7003BF0A4BEA6D9D -:1013A0001A601C46C1E700BF9AAD44C5C4240020A2 -:1013B000D0450020160000200038024000660040A2 -:1013C0005041A0B0586600401023002037B51A4D98 -:1013D00000F088FC02236B71184B288119681848AB -:1013E000012201F031FA00230193164B16490093B4 -:1013F0001648174B4FF4805201F07CFE154B1978BC -:1014000011B1124801F09EFE01F080FB0446FFF787 -:10141000B7FC4FF4C873B0FBF3F202FB130304F5FF -:10142000167010FA83F00C4B186003F069FB08B1DA -:101430000F232B8103B030BDB824002010230020DF -:1014400000350020F10F0008C8240020D03400200F -:1014500079100008C4240020CC3400202DE9F04F7E -:101460002DED028B93A7D7E900670FF25029D9E938 -:1014700000898A4C95B0DFF84CA2DFF84CB22046C8 -:1014800001F038FF034650B30025CDE91155109502 -:10149000ADF84C50027B8DF84C209968406811AA39 -:1014A00003C21B6843F00043109301F031FB10EBC3 -:1014B0000A0241F10003009510A9584600F0F2FD20 -:1014C000A842774A05DD204601F018FF744A1570DE -:1014D000D5E71378072B00F2B980013313700DADF7 -:1014E0009FED6C8B0023DFF8E0B10C93ADF83C303E -:1014F0000D936B6000230DF125028DED008B4FF0F5 -:10150000010A09A958468DF825308DF824A001F06C -:101510004BF99DF824200023002A40F09B802046B0 -:1015200001F018FE0546002847D1DFF8A0B101F010 -:10153000EDFADBF8003098423FD301F0E7FA07906C -:10154000FFF71EFC079A4FF4C87302F51672B0FB42 -:10155000F3F101FB130312FA83F3CBF80030DFF849 -:1015600070B19BF800100791002914BF2B46534619 -:1015700010A88DF83030FFF71BFC0799C1F110025D -:10158000D2B2062A10AB28BF062219440DF1310051 -:10159000079200F0CFF9079A0CAB0393182302933C -:1015A0000132404BD2B2CDE900A304923B46324611 -:1015B000204601F015FE8BF8005001F0A7FA3A4AD8 -:1015C0003A4D1368C31AB3F57A7F32D3106001F035 -:1015D0009FFA02460B46204601F09AFE204601F093 -:1015E000B9FD30B32B7BDFF8ECA0002B14BF032335 -:1015F00002238AF8053001F089FA0DF1400B4FF40F -:101600007A730122B0FBF3F05946CAF80000504645 -:1016100000F0CCFA18230293254B019380B240F2DC -:101620005513CDE903B0009342464B46204601F0E6 -:10163000D7FD2B7B2BB1FFF733FC2B7B002B7FF4EB -:101640001AAF15B0BDEC028BBDE8F08F204601F05B -:1016500055FE44E71946102210A800F07DF90DF15F -:1016600026030AAA0CA9584600F01AFE95E80300C2 -:1016700011AB83E803009DF83C308DF84C300C9B97 -:10168000109310A9DDE90A23204602F015F831E78E -:10169000AFF300800000000000000000D034002004 -:1016A000B5460020C8340020B0460020D0450020B8 -:1016B000B4460020401DA12026812A0BF1C6A7C1F7 -:1016C000D068080F40420F0000350020CC340020C5 -:1016D000C9340020B824002008B5054800F07AFE7F -:1016E000BDE80840034A0449002003F04DBD00BF97 -:1016F0000035002004470020CD120008704700008C -:101700002DE9F84F4FF47A73DFF85880DFF85890DE -:1017100006460D4602FB03F7002498F900305A1CD8 -:101720005FFA84FA01D0A34212D159F82400036869 -:101730002A46D3F820B031463B46D847854207D1E8 -:10174000074B012083F800A0BDE8F88F0124E4E7EF -:10175000002CFBD04FF4FA7002F04CFE0020F3E7AF -:10176000F84600201C2300202023002007B500237A -:10177000024601210DF107008DF80730FFF7C0FF89 -:1017800020B19DF8070003B05DF804FB4FF0FF3077 -:10179000F9E700000A4608B50421FFF7B1FF80F021 -:1017A0000100C0B2404208BD30B4074B0A46197868 -:1017B000064B53F821402368DD69054B0146AC46D2 -:1017C000204630BC604700BFF846002020230020A0 -:1017D000A086010070B502F0D1FF094E094D30809E -:1017E000002428683388834208D902F0C1FF2B689F -:1017F00004440133B4F5803F2B60F2D370BD00BFC9 -:10180000FA460020B846002003F07AB800F10060E4 -:1018100000F580300068704700F10060920000F52C -:10182000803002F0F9BF0000054B1A68054B1B8899 -:101830009B1A834202D9104402F09ABF00207047DD -:10184000B8460020FA460020024B1B68184402F0FC -:10185000AFBF00BFB846002010F003030AD1B0F5B7 -:10186000047F05D200F10050A0F51040D0F80038F8 -:10187000184670470023FBE700F10050A0F5104028 -:10188000D0F8100A70470000064991F8243033B1AF -:101890000023086A81F824300822FFF7BDBF012029 -:1018A000704700BFBC460020014B1868704700BF5E -:1018B000002004E070B5194B1D68194B0138C5F3C1 -:1018C0000B0408442D0C04221E88A6420BD15C6830 -:1018D0000A46013C824213460FD214F9016F4EB101 -:1018E00002F8016BF6E7013A03F10803ECD18142FB -:1018F0000B4602D22C2203F8012B0A4A0524168833 -:10190000AE4204D1984284BF967803F8016B013C43 -:1019100002F10402F3D1581A70BD00BF002004E0A8 -:10192000805300086C5300087047000070470000A7 -:101930007047000010B50023934203D0CC5CC45420 -:101940000133F9E710BD000003460246D01A12F930 -:10195000011B0029FAD1704702440346934202D08A -:1019600003F8011BFAE770472DE9F8431F4D1446B1 -:1019700095F824200746884652BBDFF870909CB348 -:1019800095F824302BB92022FF2148462F62FFF71B -:10199000E3FF95F82400C0F10802A24228BF2246C6 -:1019A000D6B24146920005EB8000FFF7C3FF95F8E1 -:1019B0002430A41B1E44F6B2082E17449044E4B20F -:1019C00085F82460DBD1FFF75FFF0028D7D108E05E -:1019D0002B6A03EB82038342CFD0FFF755FF002829 -:1019E000CBD10020BDE8F8830120FBE7BC460020F6 -:1019F000024B1A78024B1A70704700BFF84600205D -:101A00001C23002010B5074C074920684FF4E13330 -:101A10000B6002F0B5FB60680349BDE8104002F0BE -:101A2000AFBB00BF20230020E4460020094B10B5C7 -:101A30001422044600211846FFF78EFF064A074B82 -:101A4000127804600146BDE8104053F8220002F00D -:101A500097BB00BFE4460020F8460020202300206A -:101A60002DE9F0470D46044600219046284640F2F5 -:101A70007912FFF771FF234620220021284601F04A -:101A8000BDFD231D02222021284601F0B7FD631D64 -:101A900003222221284601F0B1FDA31D03222521A6 -:101AA000284601F0ABFD04F1080310222821284646 -:101AB00001F0A4FD04F1100308223821284601F0AA -:101AC0009DFD04F1110308224021284601F096FDF6 -:101AD00004F1120308224821284601F08FFD04F189 -:101AE000140320225021284601F088FD04F1180338 -:101AF00040227021284601F081FD04F120030822D4 -:101B0000B021284601F07AFD04F121030822B82112 -:101B1000284601F073FD04F12207C0263B463146FA -:101B200008222846083601F069FDB6F5A07F07F1C6 -:101B30000107F3D104F1320308223146284601F0AF -:101B40005DFD002704F1330A94F832304FEAC709EB -:101B50009F4209F5A47615D3B8F1000F08D131469C -:101B600004F599730722284601F048FD09F24F1643 -:101B7000274694F832213B1B93420CD3F01DC0083A -:101B8000BDE8F0870AEB070308223146284601F03A -:101B900035FD0137D8E707F23313314608222846CE -:101BA00001F02CFD08360137E3E7000013B50446C9 -:101BB0000846002101602346C0F80310202201904E -:101BC00001F01CFD0198231D0222202101F016FDC9 -:101BD0000198631D0322222101F010FD0198A31D2D -:101BE0000322252101F00AFD019804F108031022C7 -:101BF000282101F003FD072002B010BDF8B50E4604 -:101C000005461446002181223046FFF7A5FE2B46EB -:101C100008220021304601F0F1FC7CB96B1C072240 -:101C20000821304601F0EAFC0F2401236A785F1C8A -:101C3000013B934204D3E01DC008F8BD0824F4E73B -:101C4000EB1921460822304601F0D8FC08343B4607 -:101C5000ECE7000030B5094D0A4491420DD011F86F -:101C6000013B5840082340F30004013B2C4013F093 -:101C7000FF0384EA5000F6D1EFE730BD2083B8EDD2 -:101C8000F7B54FF0FF33DFF854C0DFF854E000EB56 -:101C900081011A4688421CD050F8044B019401AFD0 -:101CA000042417F8015B82EA05620825DB18164652 -:101CB00005F1FF355241002EBCBF83EA0C0382EAD6 -:101CC0000E0215F0FF05F1D1013C14F0FF04E8D13C -:101CD000E0E7D843D14303B0F0BD00BF9336EAA993 -:101CE000EBE1F042F7B5354A106851686B4603C323 -:101CF0006A4633493348082303F0A6FA044688BBF2 -:101D00000A25314A106851686B4603C36A462F4959 -:101D10002C48082303F098FA0446002845D00369AC -:101D2000B3F5702F41D8B0F86620532A3DD1284A28 -:101D3000024402F15C018B4237D35C3B2149002015 -:101D40009E1AFFF787FF3246074604F16401002020 -:101D5000FFF780FFA3689F4227D1E368984208BF3E -:101D6000002522E00369B3F5702F25D8428B532A52 -:101D700020D1174A024402F110018B4218D3103BC4 -:101D8000104900209D1AFFF765FF2A46064604F118 -:101D900018010020FFF75EFFA3689E4202D1E368AE -:101DA000984201D00D25ACE70025284603B0F0BDD0 -:101DB0001025A6E70C25A4E70B25A2E7A0530008F1 -:101DC000DCFF0E0000000108A953000890FF0E0080 -:101DD0000800FFF710B5037C044613B9006803F050 -:101DE0001BFA204610BD00000023BFF35B8FC360C9 -:101DF000BFF35B8FBFF35B8F8360BFF35B8F704775 -:101E0000BFF35B8F0068BFF35B8F704770B505460B -:101E10000C30FFF7F5FF05F1080604463046FFF7E2 -:101E2000EFFFA04206D930466D68FFF7E9FF254471 -:101E3000281A70BD3046FFF7E3FF201AF9E70000CB -:101E400070B50546406898B105F10800FFF7D8FF66 -:101E500005F10C0604463046FFF7D2FF84423046B7 -:101E600094BF6D680025FFF7CBFF013C2C44201A7E -:101E700070BD000038B50C460546FFF7C7FFA0420D -:101E800010D305F10800FFF7BBFF04446868B4FBFA -:101E9000F0F100FB1144BFF35B8F0120AC60BFF396 -:101EA0005B8F38BD0020FCE72DE9F0411446074662 -:101EB0000D46FFF7C5FF844228BF0446D4B1B8469B -:101EC00058F80C6B4046FFF79BFF304428604046B3 -:101ED0007E68FFF795FF331A9C4203D86C6001209F -:101EE000BDE8F0816B60A41B3B68AB602044E860F8 -:101EF0000220F5E72046F3E738B50C460546FFF724 -:101F00009FFFA04210D305F10C00FFF779FF0444B6 -:101F10006868B4FBF0F100FB1144BFF35B8F012054 -:101F2000EC60BFF35B8F38BD0020FCE72DE9FF417B -:101F3000884669460746FFF7B7FF6C4606B204EBD2 -:101F4000C6060025B44209D06268206808EB050186 -:101F5000FFF7F0FC636808341D44F3E72946384670 -:101F6000FFF7CAFF284604B0BDE8F081F8B5054682 -:101F70000C300F46FFF744FF05F1080604463046D3 -:101F8000FFF73EFFA042304688BF6C68FFF738FF7E -:101F9000201A386020B130462C68FFF731FF20440A -:101FA000F8BD000073B5144606460D46FFF72EFF38 -:101FB000844228BF04460190DCB101A93046FFF7F6 -:101FC000D5FF019B33B93268C5E90233C5E9002466 -:101FD00001200CE09C4238BF0194286001986860A1 -:101FE0008442F5D93368AB60241AEC60022002B059 -:101FF00070BD2046FBE700002DE9FF410F46694612 -:10200000FFF7D0FF6C4600B204EBC0050026AC42DF -:1020100009D0D4F8048054F8081BB8194246FFF7D9 -:1020200089FC4644F3E7304604B0BDE8F081000087 -:1020300038B50546FFF7E0FF044601462846FFF79E -:1020400019FF204638BD0000302383F3118862B6A3 -:1020500070470000002383F3118862B670470000C8 -:1020600010B4026854681A4623465DF8044B1847BA -:102070000120704700207047002070477047000023 -:10208000002070470E20704700F5805090F8C8007F -:10209000C0F340007047000000F5805090F9C9007F -:1020A00070470000F7B50C68BDF8207014F00054BC -:1020B0001E466FD10B7B082B6CD8FFF7C5FF456917 -:1020C000AB685B010CD4AB681B0108D4AC6814F09E -:1020D00080545DD1FFF7BEFF204603B0F0BD012460 -:1020E0000B6804F1180C002BB8BFDB004FEA0C1C86 -:1020F000B4BF43F004035B0545F80C300B680FFADE -:1021000084FC13F0804F18BF05EB0C1E05EB0C1C74 -:102110001EBFDEF8803143F00203CEF880310B7B26 -:10212000CCF8843105EB04158B68C5F88C314B680D -:10213000C5F88831DCF8803143F00103CCF88031F8 -:1021400000EB441541F268031D4403EB44130344C0 -:10215000C5E9002608330D4601F10C0C55F804EBD7 -:1021600043F804EB6545F9D184342D881D8000EBDC -:10217000441407F00303257925F00B052B43237145 -:10218000FFF768FF0097334600F0E2FC0120A4E768 -:102190000224A5E74FF0FF309FE7000013B500F5DC -:1021A00080540191E06DFFF74BFE1F280AD9019979 -:1021B000E06D2022FFF7BAFEA0F1200358425841FB -:1021C00002B010BD0020FBE708B500F58050FFF716 -:1021D0003BFFC06DFFF708FEBDE80840FFF73ABFC0 -:1021E00000220260828142608260704710B5002246 -:1021F0000023C0E900230023044603810C30FFF7CD -:10220000EFFF204610BD0000F0B5054600F58050F8 -:102210000C4690F8C83013F0040FC3F3800108BFD8 -:10222000114661F3820304F1840680F8C83005EB9F -:10223000461389B01B79D8072ED57AB319072DD448 -:102240006846FFF7D3FF05EB441303F5835303F10F -:10225000180703AA103318685968144603C40833D2 -:10226000BB422246F7D1186820609B88A380DDE935 -:102270000E23CDE900230123ADF808302B68694611 -:10228000DB6B2846984705EB46152B791A075CBF90 -:1022900043F008032B7101E0002AF4D109B0F0BD2E -:1022A0002DE9F047074688B007F5805468469A46FE -:1022B0008846FFF7C9FE9146FFF798FFE06DFFF7EC -:1022C000A5FD1F2829D9E06D20226946FFF7B0FE41 -:1022D000202822D103AD444605AB2E4603CE9E42B4 -:1022E00020606160354604F10804F6D13068206052 -:1022F000B388A380DDE90023C9E90023BDF80830D5 -:10230000AAF80030FFF7A6FE4A4653464146384633 -:1023100008B0BDE8F04700F009BCFFF79BFE0020C5 -:1023200008B0BDE8F08700002DE9F84F0023C0E9B0 -:102330000133254B044640F8183B0F46FFF750FF8A -:1023400004F12800FFF752FF04F1480804F5825514 -:102350004646083530462036FFF748FFAE42F9D1F1 -:1023600004F580554FF480534FF00009C5E9133947 -:10237000C5F848800123EE6504F5875804F58456B6 -:10238000C5F8549085F8583085F86030083608F163 -:1023900008084FF0000A4FF0000B46E908ABA6F121 -:1023A0001800FFF71DFF203646F8289C4645F4D15B -:1023B00085F8C97017B1054800F0A2FB044B6361B2 -:1023C0002046BDE8F88F00BFDC530008B453000876 -:1023D0000064004010B5044B197804464A1C1A707A -:1023E000FFF7A2FF204610BD004700202DE9F0476F -:1023F000002950D0294B2A4FB7FBF1F599428CBFE9 -:102400000A231123581EB5FBF3FC03FB1C53C4B273 -:102410002BB102280346F5D80020BDE8F0870CF167 -:10242000FF36B6F5806FF7D2C4EBC40E0EF103038E -:102430004FEAE309C3F3C703A4EB030809F1010A58 -:102440004FF47A755FFA88F009FB05555AFA88F857 -:10245000B5FBF8F5B5F5617FC1BF0EF1FF33C3F3EE -:10246000C703E01AC0B25C1C50FA84F40CFB04F4FD -:10247000B7FBF4F4A142CFD1013BDBB20F2BCBD899 -:102480000138C0B20728C7D800211071168091709A -:10249000D3700120C1E70846BFE700BF3F420F00ED -:1024A00040787D0170B505460E464FF47A746B692D -:1024B0005B6803F00103B34207D04FF47A7001F078 -:1024C00099FF013CF3D1204670BD0120FCE70000DC -:1024D00030B54269936913F0700F16D000230B4C8E -:1024E000936103F1840200EB421211794D0709D583 -:1024F000890707D5416954F823508D60117941F05F -:10250000040111710133032BEBD130BDC853000816 -:1025100073B51D46436916469A68D207044609D525 -:102520009A6801219960C2F34002CDE9006500215B -:10253000FFF76AFE63699A68D1050BD59A684FF474 -:1025400080719960C2F34022CDE9006501212046E7 -:10255000FFF75AFE63699A68D2030BD59A684FF465 -:1025600080319960C2F34042CDE9006502212046E6 -:10257000FFF74AFE204602B0BDE87040FFF7A8BF53 -:10258000F8B50446466900296CD106F10C07386895 -:1025900080076AD006EB01153868D5F8B00110F055 -:1025A000040FD5F8B0011ABFC00840F00040400D3C -:1025B000A061D5F8B0C11CF0020F1CBF40F08040F4 -:1025C000A061D5F8B40106EB011100F00F0084F80A -:1025D0002400D1F8B8012077D1F8B801000A60775B -:1025E000D1F8B801000CA077D1F8B801000EE0775F -:1025F000D1F8BC0184F82000D1F8BC01000A84F8AD -:102600002100D1F8BC01000C84F82200D1F8BC11E3 -:10261000090E84F823103821396004F1340004F1E4 -:10262000180104F1240551F8046B40F8046BA94229 -:10263000F9D109880180C4E90A23214600232386B1 -:1026400051F8283B2046DB6B984704F58052204622 -:1026500092F8C83043F0040382F8C830BDE8F8406F -:10266000FFF736BF06F1100791E7F8BD10B5044635 -:1026700000F04EFA02460B4652EA030102D0013A3C -:1026800063F100030449086820B12146BDE8104009 -:10269000FFF776BF10BD00BFFC460020F8B500F57F -:1026A00083511E46FFF7D0FCDFF844C008310024F8 -:1026B00004F1840500EB45152B795F070ED4DB068A -:1026C0000CD5D1E900739742B34107D243695CF856 -:1026D00024709F602B7943F004032B710134032C89 -:1026E00001F12001E4D1BDE8F840FFF7B3BC00BF21 -:1026F000C853000808B5FFF7A7FCFFF7E9FEBDE8DF -:102700000840FFF7A7BC0000F8B543690546986884 -:1027100000F0E050B0F1E05F0F461FD0E8B1FFF7E6 -:1027200093FC05F583541034002606F1840305EB71 -:1027300043131B791A0706D50136032E04F1200432 -:10274000F3D1012007E05B07F6D42146384600F0BC -:1027500039FA0028F0D1FFF77DFCF8BD0120FCE735 -:1027600000F5805008B5FFF76FFCC06DFFF74EFB1A -:10277000FFF770FC43090CBF0120002008BD0000DA -:10278000F8B51D46002313700F4606461446FFF7A2 -:10279000E7FF80F00100387025B129463046FFF789 -:1027A000B3FF2070F8BD00002DE9B8410C46154676 -:1027B0001F46804600F0ACF90B462178024609B965 -:1027C000287850B14046FFF769FFFFF793FF3B467B -:1027D0002A462146FFF7D4FF0120BDE8B88100005A -:1027E00010B5FFF731FC174B1A6C42F000721A64F7 -:1027F0001A6A42F000721A621A6A00F5805422F0D6 -:1028000000721A62FFF726FC94F8C830DB0718D470 -:10281000B9B103211320FFF717FC01F0E5FA0321FA -:10282000142001F0E1FA0321152001F0DDFA94F8FB -:10283000C83043F0010384F8C830BDE81040FFF70A -:1028400009BC10BD003802402DE9F04700F5805565 -:1028500088B095F8C930012B0446884616467FD8C3 -:10286000804F57F823200AB947F82300D7F800A073 -:10287000C4F80C802674BAF1000F63D095F8C93003 -:10288000012B6FD001212046FFF7AAFFFFF7DCFBE9 -:102890006269136823F0020313606269136843F0EE -:1028A00001031360636900275F6101212046FFF780 -:1028B000D1FBFFF7F7FD002800F09580E86DFFF7EA -:1028C00093FA04F58359BA4609F108092022002138 -:1028D0006846FFF741F802A8FFF782FCCDF818A080 -:1028E0006A4609EB07030DF1180E9446BCE8030095 -:1028F000F44518605960624603F10803F5D1DCF82D -:102900000000186020379CF804201A71602FDDD178 -:1029100095F8C8306FF38203002785F8C8306A46FF -:1029200041462046ADF80070ADF802708DF8047095 -:10293000FFF75CFD636948BB4FF400421A6008B0C2 -:10294000BDE8F08741F2D00002F026FC814610B1CC -:102950005146FFF7E9FCC7F80090B9F1000F8DD19F -:102960000020ECE7386803681B6B98470146002895 -:1029700088D13868FFF734FF3868036832465B68EF -:102980004146984700287FF47DAFE9E761221A604D -:102990009DF802309DF803201B06120402F47022F9 -:1029A00003F040731343BDF80020C2F30902134340 -:1029B0009DF804201205022E02F4E0020CBF4FF035 -:1029C00000410021134362690B43D3616369132201 -:1029D0005A616269136823F0010313603946204687 -:1029E000FFF760FD08B96369A6E795F8C93093BBA6 -:1029F0006169D1F8002242F00102C1F80022616948 -:102A0000D1F8002222F47C5222F00E02C1F80022FA -:102A10006169D1F8002242F46062C1F80022626963 -:102A2000C2F814326269C2F80432626941F6FF7179 -:102A3000C2F80C126269C2F840326269C2F84432CC -:102A400063690122C3F81C226269D2F8003223F0C4 -:102A50000103C2F8003295F8C83043F0020385F84C -:102A6000C8306CE7FC46002008B500F051F850EA89 -:102A70000103024602D0421E61F10001044B1868B6 -:102A800010B10B46FFF744FDBDE8084001F064B803 -:102A9000FC46002008B50020FFF7E8FDBDE808402F -:102AA00001F05AB808B50120FFF7E0FDBDE8084085 -:102AB00001F052B800B59BB0EFF309816822684677 -:102AC000FEF738FFEFF30583014B9B6BFEE700BF7A -:102AD00000ED00E008B5FFF7EDFF000000B59BB08A -:102AE000EFF3098168226846FEF724FFEFF30583C0 -:102AF000014B5B6BFEE700BF00ED00E0FEE700006E -:102B00000FB408B5029801F00BFCFEE701F044BFDA -:102B100001F01CBF13B56C4684E80600031D94E861 -:102B2000030083E80500012002B010BD73B585687D -:102B3000019155B11B885B0707D4D0E900369B6B28 -:102B40009847019AC1B23046A847012002B070BD33 -:102B5000F0B5866889B005460C465EB1BDF83830E0 -:102B60005B070AD4D0E900379B6B98472246C1B275 -:102B70003846B047012009B0F0BD00220023CDE95E -:102B800000230023ADF808300A4603AB01F1080624 -:102B9000106851681C4603C40832B2422346F7D17C -:102BA000106820609288A280FFF7B2FF0423ADF87E -:102BB00008302B68CDE90001DB6B69462846984751 -:102BC000D8E7000030B503680968DD0FB5EBD17FA9 -:102BD00023F0604421F060424FEAD1700BD0002B0B -:102BE000B8BFA40C0029B8BF920C944202D034BFE5 -:102BF0000120002030BD944205D1C1F38070C3F3A1 -:102C000080738342F6D194422CBF00200120F1E76B -:102C10002DE9F041456A15B94162BDE8F0814B6884 -:102C200023F06047C3F38A464FEAD37EC3F380782C -:102C300016EA230638BF3E46AC462B465A68BEEB22 -:102C4000D27F22F060440AD0002A18DAA40CB442E1 -:102C500017D19D420FD10D60DEE71346EEE7A74284 -:102C600007D102F08044C2F3807242450BD054B1C8 -:102C7000EFE708D2EDE7CCF800100B60CDE7B442E7 -:102C800001D0B442E5D81A689C46002AE5D1196003 -:102C9000C3E700002DE9F047089D01F007044FEA63 -:102CA000D508224405F0070500EBD1004FF47F4919 -:102CB000944201D1BDE8F08704F0070705F0070A48 -:102CC00057453E4638BF5646C6F10806111B8E4290 -:102CD00028BF0E46E10808EBD50E415C13F80EC084 -:102CE000B94029FA06F721FA0AF1FFB28CEA01018C -:102CF00047FA0AF739408CEA010C03F80EC0344455 -:102D00003544D5E780EA0120082341F2210201B2CF -:102D10004000002980B203F1FF33B8BF504013F0E8 -:102D2000FF03F4D17047000038B50C468D18A5425A -:102D300000D138BD14F8011BFFF7E4FFF7E70000EE -:102D400042684AB1136843604389818901339BB269 -:102D50009942438138BF83811046704770B588B06F -:102D6000202204460D4668460021FEF7F5FD204668 -:102D70000495FFF7E5FF024658B16B46054608AEDD -:102D80001C4603CCB44228606960234605F108055F -:102D9000F6D1104608B070BD082817D909280CD004 -:102DA0000A280CD00B280CD00C280CD00D280CD0E5 -:102DB0000E2814BF4020302070470C207047102090 -:102DC000704714207047182070472020704700007B -:102DD000082817D90C280CD910280CD914280CD97C -:102DE00018280CD920280CD930288CBF0F200E2091 -:102DF0007047092070470A2070470B2070470C204D -:102E000070470D20704700002DE9F843078C072F0D -:102E100004461ED9D0E9029800254FF6FF73C5F18C -:102E20002006A5F1200029FA05F108FA06F628FA8D -:102E300000F031430143C9B21846FFF763FF08357C -:102E4000402D0346EBD1E1693A46BDE8F843FFF770 -:102E50006BBF4FF6FF70BDE8F883000010B54B68FC -:102E600023B9CA8A63F30902CA8210BD04691A68C9 -:102E70001C600361C38A013BC3824A60EFE7000024 -:102E80002DE9F84F1D46CB8A0F46C3F309010529EA -:102E9000814692460B4630D00020AAB207F11A04B0 -:102EA0009EB2042E1FFA80F80FD8904503F101035B -:102EB00006D3FB8A0A4462F30903FB8201201AE06D -:102EC0001AF80060E6540130EAE79045F1D2A1F12A -:102ED000050B1C237C68BBFBF3F203FB12BB1FFA40 -:102EE0008BF6002C45D14846FFF72AFF044638B937 -:102EF00078606FF00200BDE8F88F4FF00008E6E759 -:102F0000002606607860ADB24FF0000B454510D941 -:102F10000AEB0803221D13F8011B9155B1B208F109 -:102F200001081B291FFA88F82BD0454506F1010638 -:102F3000F1D8FB8AC3F30902154465F30903BCE722 -:102F4000013292B21C462368002BF9D16B1F0B444F -:102F50001C21B3FBF1F301339BB29A42D3D2BBF1F4 -:102F6000000FD0D14846FFF7EBFE20B9C4F800B0FF -:102F7000BFE70122E7E7C0F800B05E4620600446E4 -:102F8000C1E74545D5D94846FFF7DAFE08B92060C4 -:102F9000AFE7C0F800B0002620600446B6E70000A6 -:102FA0002DE9F04F2DED028B1C4683B05B69019239 -:102FB00007468846002B00F09A80238C2BB1E269EB -:102FC000002A00F09480072B35D807F10C00FFF79A -:102FD000B7FE054638B96FF00205284603B0BDECD0 -:102FE000028BBDE8F08F14220021FEF7B5FC228C85 -:102FF000E16905F10800FEF79DFC208C013080B2EC -:10300000FFF7E6FEFFF7C8FE013880B220840130EA -:1030100028746369228C1B782A4403F01F0363F031 -:103020003F0348F000411372384669602946FFF7B4 -:10303000EFFD0125D1E700F10C034FF0000908EE88 -:10304000103A4FF0800A4E464D4618EE100AFFF730 -:1030500077FE83460028BED014220021FEF77CFCB8 -:10306000002E3AD1019BABF8083002220BF1080E7A -:103070001FFA82FC0CF10100BCF1060F218C80B21A -:1030800001D88E422BD3FFF7A3FEFFF785FE6269BE -:103090001278013802F01F028E4208BF4FF0400A3A -:1030A00042EA49121BFA80F14AEA020A013048F06A -:1030B000004281F808A08BF81000CBF80420594694 -:1030C0003846FFF7A5FD238C0135B3422DB289F0B8 -:1030D00001094FF0000AB8D17FE70022C6E7E16995 -:1030E000895D0EF802100136B6B20132C0E76FF00A -:1030F000010572E7F8B515460E4630220021044658 -:103100001F46FEF729FC069B6360B5F5001F079B71 -:10311000A76034BF6A094FF6FF72A36297B2E661F7 -:1031200004F1100000239A4206D800230360A7820E -:10313000E3822383E360F8BD066001333046203626 -:10314000F1E7000003781BB94BB2002BC8BF017038 -:103150007047000000787047F8B50C46C96907460B -:1031600011B9238C002B37D1257E1F2D34D8387808 -:1031700028BB228C072A2CD8268A36F003032BD1B1 -:103180004FF6FF70FFF7D0FD20F001003102400440 -:1031900041EA0561400C41EA40254FF6FF722346A3 -:1031A00029463846FFF7FCFE002807DD62691378E0 -:1031B0000133DBB21F2B88BF00231370F8BD218AB7 -:1031C0002D0645EA012505432046FFF71DFE024670 -:1031D000E5E76FF00300F1E76FF00100EEE70000B4 -:1031E00070B58AB0044616460021282268461D465E -:1031F000FEF7B2FBBDF83830ADF810300F9B0593E9 -:103200009DF840308DF81830119B07936946BDF842 -:103210004830ADF820302046CDE90265FFF79CFF2D -:103220000AB070BD2DE9F041D36905460C4616463B -:103230000BB9138C5BBB377E1F2F28D895F8008005 -:10324000B8F1000F26D03046FFF7DEFD33782102BB -:1032500041EAC33141EA0801338A41EA076141EAA0 -:1032600003410246334641F080012846FFF798FEAD -:1032700000280ADD3378012B07D1726913780133F6 -:10328000DBB21F2B88BF00231370BDE8F0816FF005 -:103290000100FAE76FF00300F7E70000F0B58BB02C -:1032A00004460D4617460021282268461E46FEF7B2 -:1032B00053FB9DF84C305A1E534253418DF8003059 -:1032C0009DF84030ADF81030119B05939DF84830C3 -:1032D0008DF81830149B07936A46BDF85430ADF84A -:1032E000203029462046CDE90276FFF79BFF0BB040 -:1032F000F0BD0000406A00B104307047436A1A68AC -:10330000426202691A600361C38A013BC38270474B -:103310002DE9F041D0F82080194E14461D46414653 -:10332000002709B9BDE8F081D1E90223A21A65EBB3 -:103330000303964277EB03031ED2036A8B420DD13F -:10334000FFF78CFD036A1B68036203690B60C38A85 -:103350000161016A013BC3828846E2E7FFF77EFD17 -:103360000B68C8F8003003690B60C38A0161013B38 -:10337000C382D8F80010D4E788460968D1E700BFB7 -:1033800080841E002DE9F04F8BB00D46DDF8509083 -:1033900014469B468046002800F01981B9F1000FC1 -:1033A00000F01581531E3F2B00F21181012A03D139 -:1033B000BBF1000F40F00B810023CDE90833B8F8D2 -:1033C0001430B5EBC30F4FEAC30703D300200BB093 -:1033D000BDE8F08F2B199F42D8F80C303ABF7F1B05 -:1033E000FFB227461BB9D8F81030002B7AD0272D12 -:1033F0004ED8C5F12806B7424FF000032CBFF6B2F5 -:103400003E4600932946D8F8080008AB3246FFF73D -:1034100041FCA7EB060A35445FFA8AFAB8F8143083 -:1034200003F10053053BDB000493D8F80C30039301 -:103430002821039B13B1BAF1000F2CD1D8F810004A -:1034400040B1BAF1000F05D0009608AB5246691A98 -:10345000FFF720FC38B2002FB8D066070AD00AABBD -:1034600003EBD401624211F8083C02F00702134159 -:1034700001F8083C082C3CD9102C40F2B580202CD7 -:1034800040F2B780BBF1000F00F09C80082334E0CD -:10349000BA460026C2E7049BE02B28BFE023069330 -:1034A0000B44AB42059314D95A1B039800969245DE -:1034B00034BF5246D2B2691A08AB04300792FFF704 -:1034C000E9FB079A1644AAEB020A1544F6B25FFA22 -:1034D0008AFA049B069A05999B1A0493039B1B681E -:1034E0000393A6E70093D8F8080008AB3A462946AC -:1034F000AEE7BBF1000F13D00123B4EBC30F6CD0C8 -:10350000082C12D89DF82030621E23FA02F2D5074B -:1035100006D54FF0FF3202FA04F423438DF8203031 -:103520009DF8203089F8003051E7102C12D8BDF8F2 -:103530002030621E23FA02F2D10706D54FF0FF3287 -:1035400002FA04F42343ADF82030BDF82030A9F886 -:1035500000303CE7202C0FD80899631E21FA03F3B2 -:10356000DA0705D54FF0FF3202FA04F40C43089451 -:10357000089BC9F800302AE7402C2BD0DDE908650C -:10358000611EC4F12102A4F1210326FA01F105FA1A -:1035900002F225FA03F311431943CB0712D5012296 -:1035A000A4F12003C4F1200102FA03F322FA01F18D -:1035B000A240524243EA010363EB430332432B43ED -:1035C000CDE90823DDE90823C9E90023FFE66FF010 -:1035D0000100FCE66FF00800F9E6082CA0D9102CD9 -:1035E000B3D9202CEED8C3E7BBF1000FADD0022336 -:1035F00083E7BBF1000FBBD004237EE730B5012A7F -:10360000144638BF0124402C85B028BF4024002533 -:10361000012ACDE9025518D81B788DF808306307C8 -:103620000AD004AB03EBD405624215F8083C02F063 -:103630000702934005F8083C00910346224600210A -:1036400002A8FFF727FB05B030BD082AE4D9102AED -:1036500003D81B88ADF80830E1E7202A8DBFD3E9F5 -:1036600000231B680293CDE90223D8E710B5CB688D -:103670001BB98B600B618B8210BD04691A681C60DA -:103680000361C38A013BC382CA60F0E703064CBFF3 -:10369000C0F3C0300220704708B50246FFF7F6FFBE -:1036A000022806D15306C2F30F2001D100F0030017 -:1036B00008BDC2F30740FBE72DE9F04F93B0CDE919 -:1036C00003230A6804461046FFF7E0FF022814BFF0 -:1036D000C2F306260026002A0D46824680F2F281B9 -:1036E00012F0C04940F0EE81097B002900F0EA8128 -:1036F000022803D02378B34240F0E781C2F3046389 -:103700000693104602F07F030593FFF7C5FF059B64 -:1037100029444FEA834848EA0A4848EA4668CE788E -:1037200000230022CDE90823F309834648EA000874 -:10373000029367D0059B009302466768534608A929 -:103740002046B847002800F0C381276A4FB9414698 -:1037500004F10C00FFF702FB074690B96FF002007E -:1037600054E03B6998450DD03F68002FF9D14146A0 -:1037700004F10C00FFF7F2FA07460028EED0236AA6 -:103780003B60276297F817C006F01F08CCF3840C43 -:10379000ACEB08001FFA80FE0028B8BF0EF1200035 -:1037A000A8EB0C031FFA83FED7E90221B8BF00B2D1 -:1037B000002B0793BEBF0EF120031BB2079352EA02 -:1037C000010338D0039BDFF824E39A1A049B4FF0DF -:1037D000000C63EB010196457CEB01032BD36B7B63 -:1037E00097F81AE0734519D1029B002B78D0012875 -:1037F00021DC7868F8B9DFF8F0C2944570EB01037A -:1038000016D337E0276A27B96FF00C0013B0BDE874 -:10381000F08F3B699845B5D03F68F4E7B2489042D5 -:103820007CEB010301D30020F0E7029B002BFAD0D0 -:10383000079B0F2B17DCFA7DB30002F0030203F0A5 -:103840007C031343FB7539462046FFF707FB6B7B70 -:10385000BB76029B3BB9FB7DC3F38402013262F36A -:103860008603FB75D0E76A7BBB7E9A42DBD1029B65 -:10387000002B35D0B309022B32D0039BBB60049BD5 -:10388000FB60142200210DA8FEF766F8039B0A9343 -:10389000049B0B932B1D0C932B7BADF83EB0013B8F -:1038A000DBB2ADF83C30069B8DF84230059B8DF8BD -:1038B000433094F82C308DF840A083F001038DF84C -:1038C00044308DF84180A3680AA920469847FB7DC3 -:1038D000C3F38403013303F01F039B02FB82A2E7BF -:1038E000FB7DC6F34012B2EBD31F40F0F480C3F36C -:1038F0008403434540F0F280029A2B7BB609002AEC -:103900004DD0F2075DD4032B40F2EB80039BBB60EC -:10391000049BFB602B7BAE1D033BDBB2324639467A -:1039200004F10C00FFF7ACFA00280CDA3946204607 -:10393000FFF794FAFB7DC3F38403013303F01F0305 -:103940009B02FB820AE7DDE90884AB883B834FF6E4 -:10395000FF73C9F12000A9F1200228FA09F104FA45 -:1039600000F0014324FA02F211431846C9B2FFF7EE -:10397000C9F909F10809B9F1400F0346E9D1B88244 -:103980002A7B033AD2B23146FFF7CEF9FB7DB882EB -:10399000DA43C2F3C01262F3C713FB7543E786B97B -:1039A0002E1D013BDBB23246394604F10C00FFF715 -:1039B00067FA0028BADB2A7BB88A013AD2B23146CC -:1039C000E2E7F98AC1F30901013B0429DAB25BD8C5 -:1039D000281D002307F11B069A4208D910F801CBD5 -:1039E00006F801C0013101330529DBB2F4D1039996 -:1039F0000A9104990B91934207F11B010C9138BF76 -:103A0000043379680D9134BF55FA83F300230E9384 -:103A1000FB8AADF83EB0C3F309031A44069B8DF848 -:103A20004230059B8DF8433094F82C30ADF83C20A3 -:103A300083F001038DF8443000238DF840A08DF809 -:103A400041807B602A7BB88A013A291DFFF76CF917 -:103A50003B8BB882834203D1A3680AA920469847CA -:103A600020460AA9FFF702FEFB7DBA8AC3F384034E -:103A7000013303F01F039B02FB823B8B9A420CBF76 -:103A800000206FF01000C1E67B68002BAFD005204E -:103A900001E01C3033461E68002EFAD1091A081DB9 -:103AA0002E1D184401EB090CBCF11B0F5FFA89F3C2 -:103AB0009DD89A429BD916F8013B00F8013B09F1C9 -:103AC0000109EFE76FF00900A0E66FF00A009DE63C -:103AD0006FF00B009AE66FF00D0097E66FF00E00A6 -:103AE00094E66FF00F0091E640420F0080841E00C4 -:103AF000EFF3098305494A6B22F001024A636833F8 -:103B000083F30988002383F31188704700EF00E0F6 -:103B1000302080F3118862B60C4B0D4AD96821F42D -:103B2000E0610904090C0A43DA60D3F8FC20094972 -:103B300042F08072C3F8FC200A6842F001020A6079 -:103B40002022DA7783F82200704700BF00ED00E002 -:103B50000003FA05001000E010B5302383F311884C -:103B60000E4B5B6813F4006314D0F1EE103AEFF3E0 -:103B70000984683C4FF08073E361094BDB6B23667B -:103B800084F3098800F08AFB10B1064BA36110BDD5 -:103B9000054BFBE783F31188F9E700BF00ED00E078 -:103BA00000EF00E04306000846060008026843688C -:103BB0001143016003B1184770470000024AD368FF -:103BC00043F0C003D360704700100140024AD3683D -:103BD00043F0C003D36070470044004010B50A4C66 -:103BE0000A4A2046002100F0A9FA094B094AC4E913 -:103BF0009723094C094A0021204600F09FFA084902 -:103C0000084BC4E9971310BD08470020BD3B0008CE -:103C100080F0FA020010014074490020CD3B0008FA -:103C20000044004040787D012A4A037C002918BFE7 -:103C30000A46012B30B5C0F868220CD1264B9842B9 -:103C400039D1264B596C41F010015964596E41F03D -:103C5000100159665B6EB2F904501468D0F86032F6 -:103C6000D0F85C12002D03EB5403B3FBF4F3BEBF9A -:103C700023F0070503F0070343EA450394888B60AC -:103C8000D38843F040030B61138943F001034B6178 -:103C900044F4045343F02C03CB6004F4A0540023F9 -:103CA0000B60B4F5806F0B684B680CBF7F23FF235C -:103CB00080F8643230BD0A4B9842CCD1074B196C66 -:103CC00041F400311964196E41F4003119661B6E1C -:103CD000C1E700BF1C54000808470020003802401C -:103CE000744900202DE9F041D0F85C62F768336830 -:103CF000DA0504469DB20DD5302383F311884FF4C5 -:103D000080610430FFF752FF6FF48073336000234B -:103D100083F31188302383F3118804F1040815F02C -:103D20002F033AD183F31188380615D5290613D508 -:103D3000302383F3118804F1380000F07BF9002868 -:103D40004EDA0821201DFFF731FF4FF67F733B400D -:103D5000F360002383F311887A0616D56B0614D519 -:103D6000302383F31188D4E913239A420AD1236CB8 -:103D700043B127F040073F041021201D3F0CFFF7FF -:103D800015FFF760002383F31188D4F86822D36805 -:103D900043B3BDE8F041106918472B0714D015F064 -:103DA000080F0CBF00214FF48071E80748BF41F0B5 -:103DB0002001AA0748BF41F040016B0748BF41F00E -:103DC00080014046FFF7F2FEAD06736805D594F812 -:103DD00064122046194000F0E1F93568ADB29EE763 -:103DE0007060B6E7BDE8F08100F1604303F5614320 -:103DF0000901C9B283F80013012200F01F039A40A1 -:103E000043099B0003F1604303F56143C3F880213C -:103E10001A607047F8B5154682680669AA420B46D3 -:103E2000816938BF8568761AB54204460BD21846B8 -:103E30002A46FDF77FFDA3692B44A361A3685B1BA2 -:103E4000A3602846F8BD0CD918463246FDF772FD2E -:103E5000AF1BE1683A463044FDF76CFDE3683B4434 -:103E6000EBE718462A46FDF765FDE368E5E7000045 -:103E700083689342F7B51546044638BF8568D0E994 -:103E80000460361AB5420BD22A46FDF753FD63692A -:103E90002B446361A36828465B1BA36003B0F0BD9D -:103EA0000DD932460191FDF745FD0199E068AF1B40 -:103EB0003A463144FDF73EFDE3683B44E9E72A46D4 -:103EC000FDF738FDE368E4E710B50A440024C36158 -:103ED000029B8460C0E90000C0E90511C160026175 -:103EE000036210BD08B5D0E90532934201D1826862 -:103EF00082B98268013282605A1C42611970D0E92D -:103F000004329A4224BFC3684361002100F08EFA54 -:103F1000002008BD4FF0FF30FBE7000070B53023F4 -:103F200004460E4683F31188A568A5B1A368A2696B -:103F3000013BA360531CA36115782269934224BFFF -:103F4000E368A361E3690BB120469847002383F33C -:103F50001188284607E03146204600F057FA00282D -:103F6000E2DA85F3118870BD2DE9F74F04460E465D -:103F700017469846D0F81C904FF0300A8AF3118803 -:103F80004FF0000B154665B12A4631462046FFF733 -:103F900041FF034660B94146204600F037FA002849 -:103FA000F1D0002383F31188781B03B0BDE8F08FB4 -:103FB000B9F1000F03D001902046C847019B8BF355 -:103FC0001188ED1A1E448AF31188DCE7C0E9051157 -:103FD000C160C3611144009B8260C0E900000161BF -:103FE00003627047F8B504460D461646302383F346 -:103FF0001188A768A7B1A368013BA36063695A1C35 -:1040000062611D70D4E904329A4224BFE36863619F -:10401000E3690BB120469847002080F3118807E040 -:104020003146204600F0F2F90028E2DA87F31188E1 -:10403000F8BD0000D0E905239A4210B501D182688D -:104040007AB98268013282605A1C82611C780369E5 -:104050009A4224BFC3688361002100F0E7F920463B -:1040600010BD4FF0FF30FBE72DE9F74F04460E4639 -:1040700017469846D0F81C904FF0300A8AF3118802 -:104080004FF0000B154665B12A4631462046FFF732 -:10409000EFFE034660B94146204600F0B7F900281C -:1040A000F1D0002383F31188781B03B0BDE8F08FB3 -:1040B000B9F1000F03D001902046C847019B8BF354 -:1040C0001188ED1A1E448AF31188DCE70268436800 -:1040D0001143016003B11847704700001430FFF727 -:1040E00043BF00004FF0FF331430FFF73DBF000027 -:1040F0003830FFF7B9BF00004FF0FF333830FFF71B -:10410000B3BF00001430FFF709BF00004FF0FF31CC -:104110001430FFF703BF00003830FFF763BF000023 -:104120004FF0FF323830FFF75DBF0000012914BFA8 -:104130006FF0130000207047FFF750BD37B51546EC -:104140000E4A026000224260C0E9022201220446B7 -:1041500002740B46009000F15C014FF48072143041 -:10416000FFF7B2FE00942B464FF4807204F5AE7157 -:1041700004F13800FFF72AFF03B030BD30540008C7 -:1041800010B53023044683F31188FFF74DFD022359 -:104190002374002080F3118810BD000038B5C36976 -:1041A00004460D461BB904210844FFF78FFF29463A -:1041B00004F11400FFF796FE002806DA201D4FF4E4 -:1041C0000061BDE83840FFF781BF38BD00230375AB -:1041D000826803691B6899689142FBD25A68036040 -:1041E000426010605860704700230375826803695D -:1041F0001B6899689142FBD85A680360426010605E -:104200005860704708B50846302383F311880B7D4A -:10421000032B05D0042B0DD02BB983F3118808BDD7 -:104220008B6900221A604FF0FF338361FFF7CEFFE6 -:104230000023F2E7D1E9003213605A60F3E700008F -:10424000FFF7C4BF054BD9680875186802681A6083 -:10425000536001220275D860FCF7DEB9E04B002004 -:1042600030B50C4BDD684B1C87B004460FD02B4695 -:10427000094A684600F06CF92046FFF7E3FF009B0F -:1042800013B1684600F06EF9A86907B030BDFFF7BA -:10429000D9FFF9E7E04B002005420008044B1A68FB -:1042A000DB6890689B68984294BF002001207047AB -:1042B000E04B0020084B10B51C68D86822681A60D3 -:1042C000536001222275DC60FFF78EFF0146204615 -:1042D000BDE81040FCF7A0B9E04B0020044B1A6881 -:1042E000DB6892689B689A4201D9FFF7E3BF704789 -:1042F000E04B002038B5074C07490848012300254A -:104300002370656000F052FC0223237085F311884E -:1043100038BD00BF484E00205C540008E04B002030 -:1043200008B572B6044B186500F0FEFA00F0B2FB57 -:10433000024B03221A70FEE7E04B0020484E00209B -:1043400000F046B9EFF3118020B9EFF30583302276 -:1043500082F311887047000010B530B9EFF305847F -:10436000C4F3080414B180F3118810BDFFF7B6FF41 -:1043700084F31188F9E700008B60022308618B82C7 -:10438000084670478368A3F1840243F8142C02693D -:1043900043F8442C426943F8402C094A43F8242C42 -:1043A000C26843F8182C022203F80C2C002203F8F0 -:1043B0000B2C044A43F8102CA3F12000704700BFD7 -:1043C00031060008E04B002008B5FFF7DBFFBDE831 -:1043D0000840FFF735BF0000024BDB6898610F20F3 -:1043E000FFF730BFE04B0020302383F31188FFF745 -:1043F000F3BF000008B50146302383F3118808207D -:10440000FFF72EFF002383F3118808BD064BDB68FE -:1044100039B1426818605A60136043600420FFF7A6 -:104420001FBF4FF0FF307047E04B002003689842F9 -:1044300006D01A680260506099611846FFF700BF05 -:104440007047000010B503689C68A2420CD85C68F5 -:104450008A600B604C602160596099688A1A9A6082 -:104460004FF0FF33836010BD1B68121BECE70000A8 -:104470000A2938BF0A2170B504460D460A2660197C -:1044800000F08CFB00F074FB041BA54203D8751CE4 -:104490002E460446F3E70A2E04D9BDE870400120F9 -:1044A00000F0C4BB70BD0000F8B5144B0D46D961D7 -:1044B00003F1100141600A2A1969826038BF0A229B -:1044C000016048601861A818144600F057FB0A27DD -:1044D00000F04EFB431BA342064606D37C1C281962 -:1044E00000F05CFB27463546F2E70A2F04D9BDE809 -:1044F000F840012000F09ABBF8BD00BFE04B00205F -:10450000F8B506460D4600F033FB0F4A134653F844 -:10451000107F9F4206D12A4601463046BDE8F8404A -:10452000FFF7C2BFD169BB68441A2C1928BF2C46BB -:10453000A34202D92946FFF79BFF22463146034892 -:10454000BDE8F840FFF77EBFE04B0020F04B0020B5 -:1045500010B4C0E9032300235DF8044B4361FFF767 -:10456000CFBF000010B5194C236998420DD0D0E997 -:104570000032816813605A609A680A449A60002386 -:1045800003604FF0FF33A36110BD2346026843F878 -:10459000102F53600022026022699A4203D1BDE8C5 -:1045A000104000F0F5BA936881680B44936000F006 -:1045B000DFFA2269E1699268441AA242E4D91144FF -:1045C000BDE81040091AFFF753BF00BFE04B0020C1 -:1045D0002DE9F047DFF8BC8008F110072C4ED8F821 -:1045E000105000F0C5FAD8F81C40AA68031B9A4284 -:1045F0003ED81444D5E900324FF00009C8F81C40F9 -:1046000013605A60C5F80090D8F81030B34201D159 -:1046100000F0BEFA89F31188D5E90331284698479E -:10462000302383F311886B69002BD8D000F0A0FAF7 -:104630006A69A0EB04094A4582460DD2022000F0C7 -:10464000F5FA0022D8F81030B34208D15146284676 -:10465000BDE8F047FFF728BF121A2244F2E712EB39 -:10466000090938BF4A4629463846FFF7EBFEB5E749 -:10467000D8F81030B34208D01444211AC8F81C00EE -:10468000A960BDE8F047FFF7F3BEBDE8F08700BFC3 -:10469000F04B0020E04B002000207047FEE70000B8 -:1046A000704700004FF0FF3070470000BFF34F8F9E -:1046B000024AD368DB03FCD4704700BF003C0240D1 -:1046C00008B5094B1B7873B9FFF7F0FF074B1A6960 -:1046D000002ABFBF064A5A6002F188325A601A683F -:1046E00022F480621A6008BD504E0020003C024057 -:1046F0002301674508B50B4B1B7893B9FFF7D6FF2D -:10470000094B1A6942F000421A611A6842F4805259 -:104710001A601A6822F480521A601A6842F48062A1 -:104720001A6008BD504E0020003C02400B28F0B536 -:1047300016D80C4C0C4923787BB90C4D0E460C2333 -:104740004FF0006255F8047B46F8042B013B13F050 -:10475000FF033A44F6D10123237051F82000F0BD45 -:104760000020FCE7844E0020544E002068540008CE -:10477000014B53F820007047685400080C20704724 -:104780000B2810B5044601D9002010BDFFF7CEFF5D -:10479000064B53F824301844C21A0BB90120F4E731 -:1047A00012680132F0D1043BF6E700BF68540008FC -:1047B0000B2838B5044628D8FFF7C4FDFFF776FF6D -:1047C000FFF77EFF124AF323D360E300DBB243F42A -:1047D000007343F002031361136943F480331361E0 -:1047E00005462046FFF762FFFFF7A0FF094B53F88D -:1047F000241000F04BF92846FFF77CFFFFF7ACFDD3 -:104800002046BDE83840FFF7BBBF002038BD00BFE1 -:10481000003C02406854000812F001032DE9F04109 -:1048200005460E4614464BD18218B2F1016F61D88D -:10483000314B1B6813F001035CD0304FFFF782FD52 -:10484000FFF73EFFF323FB60FFF730FF314640F2F6 -:104850000128032C18D824F00104284E0C446D1AAA -:1048600040F20118A142336905EB01072AD123F078 -:1048700001033361FFF73EFFFFF76EFD0120BDE846 -:10488000F081043C0435E4E7AB07E4D13B6923F451 -:1048900040733B613B6943EA08033B6151F8046B99 -:1048A0002E60BFF34F8FFFF701FF2B689E42E8D0C9 -:1048B0003B6923F001033B61FFF71CFFFFF74CFD51 -:1048C0000020DCE723F440733361336943EA0803D3 -:1048D00033610B883B80BFF34F8FFFF7E7FE3F88C4 -:1048E00031F8023BBFB2BB42BCD0336923F00103B5 -:1048F0003361E1E71846C2E700380240003C02405D -:10490000084908B50B7828B11BB9FFF7D9FE012378 -:104910000B7008BD002BFCD0BDE808400870FFF705 -:10492000E9BE00BF504E00204FF480214FF00050F0 -:1049300000F0AEB80846114600F050BC012000F06F -:104940004DBC0000084600F067BC000070B582B0A6 -:10495000FFF7F8FC0E4E054600F00AF93268904267 -:1049600037BF0C4A0B49516814682EBFD1E900418A -:10497000013151600419034641F1000128460191BB -:104980003360FFF7E9FC0199204602B070BD00BF1B -:10499000884E0020904E002070B582B0FFF7D2FC08 -:1049A000104E054600F0E4F83268904237BF0E4AD8 -:1049B0000D49516814682EBFD1E9004101315160A1 -:1049C000041941F100010346284601913360FFF7C5 -:1049D000C3FC01994FF47A7200232046FBF708FCD0 -:1049E00002B070BD884E0020904E002010B50244E9 -:1049F000064BD2B2904200D110BD441C00B253F815 -:104A0000200041F8040BE0B2F4E700BF502800405A -:104A10000F4B30B51C6F240407D41C6F44F4007492 -:104A20001C671C6F44F400441C670A4C236843F461 -:104A3000807323600244084BD2B2904200D130BD53 -:104A4000441C00B251F8045B43F82050E0B2F4E794 -:104A500000380240007000405028004007B5012295 -:104A600001A90020FFF7C2FF019803B05DF804FB25 -:104A700013B50446FFF7F2FFA04205D0012201A9B9 -:104A800000200194FFF7C4FF02B010BD7047000082 -:104A90007047000070470000074B45F255521A60FE -:104AA00002225A6040F6FF729A604CF6CC421A60BD -:104AB000024B01221A707047003000409C4E0020CB -:104AC000034B1B781BB1034B4AF6AA221A607047AE -:104AD0009C4E002000300040034B1A681AB9034A6C -:104AE000D2F874281A607047984E002000300240B7 -:104AF000024B4FF08072C3F87428704700300240B8 -:104B000008B5FFF7E9FF024B1868C0F3407008BD15 -:104B1000984E002008B5FFF7DFFF024B1868C0F37E -:104B2000007008BD984E002070470000FEE70000AE -:104B30000A4B0B480B4A90420BD30B4BDA1C121A50 -:104B4000C11E22F003028B4238BF00220021FCF775 -:104B500003BF53F8041B40F8041BECE71C56000885 -:104B6000284F0020284F0020284F002000F0D0B808 -:104B7000014B586A704700BF000C0040034B0022F5 -:104B800058631A610222DA60704700BF000C0040CF -:104B9000014B0022DA607047000C0040014B586363 -:104BA000704700BF000C0040FEE7000070B51B4BD3 -:104BB00001630025044686B0586085620E46FEF704 -:104BC000A7FF04F11003C4E904334FF0FF33C4E935 -:104BD0000635C4E90044A560E562FFF7C9FF2B462E -:104BE0000246C4E9082304F134010D4A25658023F7 -:104BF0002046FFF7C1FB0123E0600A4A03750092DB -:104C000072680192B268CDE90223074B6846CDE98C -:104C10000435FFF7D9FB06B070BD00BF484E002039 -:104C2000985400089D540008A94B0008024AD36A12 -:104C30001843D062704700BFE04B00204B684360D0 -:104C40008B688360CB68C3600B6943614B69036207 -:104C50008B6943620B6803607047000008B5234B03 -:104C600023481A6942F0FF021A611A6922F0FF0212 -:104C70001A611A691A6B42F0FF021A631A6D42F048 -:104C8000FF021A651B4A1B6D1146FFF7D7FF02F1A1 -:104C90001C0100F58060FFF7D1FF02F1380100F53B -:104CA0008060FFF7CBFF02F1540100F58060FFF751 -:104CB000C5FF02F1700100F58060FFF7BFFF02F150 -:104CC0008C0100F58060FFF7B9FF02F1A80100F543 -:104CD0008060FFF7B3FF02F1C40100F58060FFF7C9 -:104CE000ADFFBDE8084000F08FB800BF00380240BB -:104CF00000000240A454000808B500F029FAFFF7AC -:104D0000F9FABDE80840FFF7E7BE00007047000071 -:104D10000E4B1A6C42F008021A641A6E42F0080236 -:104D20001A660B4A1B6E936843F008039360094BA5 -:104D300031229A624FF0FF32DA6200229A615A639E -:104D4000DA605A6001225A611A60704700380240E6 -:104D5000002004E0000C0040094A08B51169D3683E -:104D60000B40D9B2C9439B07116107D5302383F3A8 -:104D70001188FFF7E5FA002383F3118808BD00BF0F -:104D8000000C00401E4B1A6962F0FF021A611A699A -:104D9000D2B21A614FF0FF301A695A695861002186 -:104DA0005A6959615A691A6A62F080521A621A6A1B -:104DB00002F080521A621A6A5A6A58625A6A596232 -:104DC0005A6A1A6C42F080521A641A6E42F080528B -:104DD0001A661A6E0B4A106840F480701060186FE3 -:104DE00000F44070B0F5007F1EBF4FF480301867AC -:104DF0001967536823F40073536000F07DB900BF56 -:104E000000380240007000403B4B3C4A1A643C4A68 -:104E10004FF4404111601A6842F001021A601A68AA -:104E20009007FCD59A6822F003029A60324B9A6888 -:104E300012F00C02FBD1196801F0F90119609A60B7 -:104E40001A6842F480321A601A689103FCD55A6FCE -:104E500042F001025A67284B5A6F9207FCD5294A43 -:104E60005A601A6842F080721A60254A53685804E2 -:104E7000FCD5214B1A689101FCD5234AC3F8842044 -:104E80001A6842F080621A601A681201FCD51F4A43 -:104E90009A600322C3F88C204FF00062C3F894207C -:104EA0001B4B1A681B4B9A421B4B21D11B4A1168A2 -:104EB0001B4A91421CD140F203121A60164A136831 -:104EC00003F00F03032BFAD10B4B9A6842F0020256 -:104ED0009A609A6802F00C02082AFAD15A6C42F4DD -:104EE00080425A645A6E42F480425A665B6E704742 -:104EF00040F20372E1E700BF0038024000040010F6 -:104F000000700040041940020830002400948838E2 -:104F1000002004E011640020003C024000ED00E0AD -:104F200041C20F41074A08B5536903F001035361B9 -:104F300023B1054A13680BB150689847BDE8084093 -:104F4000FEF70ABE003C0140A04E0020074A08B50B -:104F5000536903F00203536123B1054A93680BB10F -:104F6000D0689847BDE80840FEF7F6BD003C014018 -:104F7000A04E0020074A08B5536903F004035361AB -:104F800023B1054A13690BB150699847BDE8084041 -:104F9000FEF7E2BD003C0140A04E0020074A08B5E4 -:104FA000536903F00803536123B1054A93690BB1B8 -:104FB000D0699847BDE80840FEF7CEBD003C0140EF -:104FC000A04E0020074A08B5536903F0100353614F -:104FD00023B1054A136A0BB1506A9847BDE80840EF -:104FE000FEF7BABD003C0140A04E0020164B10B5A4 -:104FF0005C6904F478725A61A30604D5134A936A73 -:105000000BB1D06A9847600604D5104A136B0BB1F8 -:10501000506B9847210604D50C4A936B0BB1D06BAB -:105020009847E20504D5094A136C0BB1506C9847B8 -:10503000A30504D5054A936C0BB1D06C9847BDE825 -:105040001040FEF789BD00BF003C0140A04E00208B -:10505000194B10B55C6904F47C425A61620504D5B1 -:10506000164A136D0BB1506D9847230504D5134AAA -:10507000936D0BB1D06D9847E00404D50F4A136EC1 -:105080000BB1506E9847A10404D50C4A936E0BB136 -:10509000D06E9847620404D5084A136F0BB1506F65 -:1050A0009847230404D5054A936F0BB1D06F9847F6 -:1050B000BDE81040FEF750BD003C0140A04E00206E -:1050C00008B50348FEF70EFEBDE80840FEF744BDF4 -:1050D0000847002008B50348FEF704FEBDE8084075 -:1050E000FEF73ABD7449002008B5FFF735FEBDE86C -:1050F0000840FEF731BD0000062108B50846FEF75E -:1051000073FE06210720FEF76FFE06210820FEF73A -:105110006BFE06210920FEF767FE06210A20FEF736 -:1051200063FE06211720FEF75FFE06212820FEF70A -:105130005BFE07213220FEF757FE0C212520FEF7EB -:1051400053FEBDE808400C212620FEF74DBE0000AE -:1051500008B5FFF717FE00F009F8FEF7EDFFFFF7BF -:10516000D5FDBDE80840FFF701BD00000023054A5A -:1051700019460133102BC2E9001102F10802F8D1DF -:10518000704700BFA04E00200B460146184600F0B5 -:105190002DB8000000F040B8012838BF012010B53C -:1051A0000446204600F030F830B900F007F808B99E -:1051B00000F00CF88047F4E710BD0000024B1868BF -:1051C000BFF35B8F704700BF204F002008B506205B -:1051D00000F084F80120FFF761FA0000024B0A4654 -:1051E00001461868FFF7A6BB2823002010B5054C20 -:1051F00013462CB10A4601460220AFF3008010BDD1 -:105200002046FCE700000000024B01461868FFF74B -:1052100095BB00BF28230020024B01461868FFF70A -:1052200091BB00BF2823002010B5013902449042F1 -:1052300001D1002005E0037811F8014FA34201D00D -:10524000181B10BD0130F2E72DE9F041A3B1C91AD6 -:1052500017780144044603F1FF3C8C42204601D9F3 -:10526000002009E00578BD4204F10104F5D10CEB02 -:105270000405D618A54201D1BDE8F08115F8018DCD -:1052800016F801EDF045F5D0E7E700001F2938B525 -:1052900004460D4604D9162303604FF0FF3038BD95 -:1052A000426C12B152F821304BB9204600F030F870 -:1052B0002A4601462046BDE8384000F017B8012BC9 -:1052C0000AD0591C03D1162303600120E7E700240C -:1052D00042F82540284698470020E0E7024B014667 -:1052E0001868FFF7D3BF00BF2823002038B5074D4B -:1052F00000230446084611462B60FFF7D3F9431CF0 -:1053000002D12B6803B1236038BD00BF244F0020B9 -:10531000FFF7C2B9034611F8012B03F8012B002A4D -:10532000F9D170476F72672E6172647570696C6F26 -:10533000742E41524B5F43414E4E4F444500000096 -:1053400053544D3332463F3F3F0053544D33324662 -:105350003430780053544D3332463432780053544D -:105360004D333246343436585800000001203300A3 -:105370000010410001105A000310590007103100BD -:105380000000000040530008130400004A530008C6 -:105390001904000054530008210400005E53000863 -:1053A00040A2E4F1646891060041A3E5F2656992C8 -:1053B000070000004261642043414E496661636515 -:1053C00020696E6465782E00800000000080000077 -:1053D00000008000000000000000000061200008C4 -:1053E00049280008A927000871200008A520000806 -:1053F000A1220008752000088520000879200008F7 -:10540000812000087D200008C921000889200008AB -:10541000152B0008992000089D2100080096000027 -:10542000000000000000000000000000000000007C -:1054300000000000F9400008E54000082141000894 -:105440000D4100081941000805410008F14000081D -:10545000DD4000082D41000863300000585400086A -:10546000384C0020484E0020004000000040000062 -:1054700000400000004000000000010000000200A9 -:105480000000020000000200000002000000020014 -:1054900000000200000002006D61696E0069646C2A -:1054A00065000000A00195AA00070000AAAAAAAA08 -:1054B00050010064FFF900000077000000900970BF -:1054C0008000000100000000AAAAAAAA4000000172 -:1054D000FFFF00000070000000000000000000500E -:1054E00000000000AAAAAA5A00000000FF3F000026 -:1054F00000000000000000000000000000000000AC -:10550000AAAAAAAA00000000FFFF000000000000F5 -:10551000000000000000000000000000AAAAAAAAE3 -:1055200000000000FFFF000000000000000000007D -:105530000000000000000000AAAAAAAA00000000C3 -:10554000FFFF00000000000000000000000000005D -:1055500000000000AAAAAAAA00000000FFFF0000A5 -:10556000000000000000000000000000000000003B -:105570000A0000000000000003000000000000001E -:10558000000000009CACFF7F010000000000000054 +:1000000000070020F10100086D2B0008252B0008D7 +:100010004D2B0008252B0008452B0008F301000894 +:10002000F3010008F3010008F3010008613B000838 +:10003000F3010008F3010008F3010008F3010008D0 +:10004000F3010008F3010008F3010008F3010008C0 +:10005000F3010008F3010008314F0008594F000870 +:10006000814F0008A94F0008D14F0008F301000894 +:10007000F3010008F3010008F3010008F301000890 +:10008000F3010008F3010008F3010008D92A000871 +:10009000052B0008152B0008F3010008F94F000894 +:1000A000F3010008F3010008F3010008F301000860 +:1000B000F3010008F3010008F3010008F301000850 +:1000C000F3010008F3010008F3010008F301000840 +:1000D000F3010008CD500008E1500008F3010008CA +:1000E0005D500008F3010008F3010008F301000867 +:1000F000F3010008F3010008F3010008F301000810 +:10010000F3010008F3010008F5500008F3010008AE +:10011000F3010008F3010008F3010008F3010008EF +:10012000F3010008F3010008F3010008F3010008DF +:10013000F3010008F3010008F3010008F3010008CF +:10014000F3010008F3010008F3010008F3010008BF +:10015000F3010008F3010008F3010008F3010008AF +:10016000F3010008F3010008F3010008F30100089F +:10017000F3010008F3010008F3010008F30100088F +:10018000F3010008F3010008F3010008F30100087F +:10019000F3010008F3010008F3010008F30100086F +:1001A000F3010008F3010008F3010008F30100085F +:1001B000F3010008F3010008F3010008F30100084F +:1001C000F3010008F3010008F3010008F30100083F +:1001D000F3010008F3010008F3010008F30100082F +:1001E00051150008000000000000000000000000A1 +:1001F00002E000F000F8FEE772B6374880F30888A6 +:10020000364880F3098836483649086040F20000D5 +:10021000CCF200004EF63471CEF200010860BFF35C +:100220004F8FBFF36F8F40F20000C0F2F0004EF628 +:100230008851CEF200010860BFF34F8FBFF36F8F7C +:100240004FF00000E1EE100A4EF63C71CEF20001D4 +:100250000860062080F31488BFF36F8F04F06AFCF7 +:1002600004F002FD4FF055301F491B4A91423CBF3C +:1002700041F8040BFAE71D49184A91423CBF41F886 +:10028000040BFAE71A491B4A1B4B9A423EBF51F82E +:10029000040B42F8040BF8E700201849184A914271 +:1002A0003CBF41F8040BFAE704F048FC04F02AFDD7 +:1002B000144C154DAC4203DA54F8041B8847F9E797 +:1002C00000F042F8114C124DAC4203DA54F8041B12 +:1002D0008847F9E704F030BC000700200023002025 +:1002E0000000000808ED00E00001002000070020E9 +:1002F00090550008002300208C230020902300202C +:1003000070530020E0010008E4010008E401000847 +:10031000E40100082DE9F04F2DED108AC1F80CD052 +:10032000C3689D46BDEC108ABDE8F08F002383F3BF +:1003300011882846A047002004F068F8FEE703F083 +:10034000F1FF00DFFEE70000F8B501F07DF904F0F1 +:100350008BFB074604F0DAFB0546A8BB1F4B9F4208 +:1003600032D001339F4232D01D4B27F0FF029A4218 +:1003700030D1F8B200F004FF2E4642F2107400F0C3 +:1003800005FF08B10024264601F0D2FC20B103206D +:1003900000F07AF80024264635B1124B9F4203D074 +:1003A00004F0ACFB00242646002004F067FB0EB1ED +:1003B00000F080F801F068FA00F054FF204600F0E9 +:1003C000CDF800F077F8F9E72E460024D7E7044689 +:1003D0000126D4E7064641F28834D0E7010007B091 +:1003E000000008B0263A09B008B501F0F9F8A0F10C +:1003F00020035842584108BD07B541F212030221BB +:1004000001A8ADF8043001F009F903B05DF804FB70 +:1004100038B5302383F31188174803680BB104F013 +:10042000B3F8164A144800234FF47A7104F0A2F886 +:10043000002383F31188124C236813B12368013B16 +:100440002360636813B16368013B63600D4D2B78D3 +:1004500033B963687BB9022001F0ACF932236360E1 +:100460002B78032B07D163682BB9022001F0A2F986 +:100470004FF47A73636038BD9023002011040008A4 +:10048000B0240020A8230020084B187003280CD8A3 +:10049000DFE800F008050208022001F089B9022017 +:1004A00001F084B9024B00225A607047A823002053 +:1004B000B024002010B501F03BFC30B1204B0322EA +:1004C0001A70204B00225A6010BD1F4B1F4A1C4659 +:1004D00019680131F8D004339342F9D162681C4B9A +:1004E0009A42F1D91B4B9B6803F1006303F58033FB +:1004F0009A42E9D204F0D6FA04F0E8FA002001F0BA +:10050000BDF80220FFF7C0FF134B1A6C00221A64DB +:10051000196E1A66196E596C5A64596E5A665B6E7A +:1005200072B64FF0E0233021C3F8084DD4E9003211 +:1005300081F311889D4683F308881047C4E700BF04 +:10054000A8230020B024002000000108200001089A +:10055000FFFF000800230020003802402DE9F04F83 +:1005600093B0AC4B00902022FF210AA89D6801F0B7 +:1005700035F9A94A1378A3B9A8480121036011707D +:10058000302383F3118803680BB103F0FDFFA44A05 +:10059000A24800234FF47A7103F0ECFF002383F3A9 +:1005A0001188009B13B19F4B009A1A609E4A009CD1 +:1005B0001378032B1EBF002313709A4A4FF0000AD2 +:1005C00018BF5360D3465646D146012001F0F0F8DB +:1005D00024B1944B1B68002B00F01582002000F022 +:1005E000FFFF0390039B002B01DA00F083FE039BC7 +:1005F000002BEDDB012001F0D9F8039B213B162BEA +:10060000E3D801A252F823F0650600088D06000821 +:1006100021070008CB050008CB050008CB05000822 +:10062000AB0700087B09000895080008F7080008D8 +:100630001F09000845090008CB05000857090008F4 +:10064000CB050008C909000805070008CB0500080C +:100650000D0A00087106000805070008CB05000810 +:10066000F70800080220FFF7BFFE002840F0F581E0 +:10067000009B0221BAF1000F08BF1C4605A841F2F9 +:100680001233ADF8143000F0C9FF9EE74FF47A70D2 +:1006900000F0A6FF071EEBDB0220FFF7A5FE0028F7 +:1006A000E6D0013F052F00F2DA81DFE807F0030A08 +:1006B0000D10133605230593042105A800F0AEFFA5 +:1006C00017E054480421F9E758480421F6E7584850 +:1006D0000421F3E74FF01C08404600F0D1FF08F179 +:1006E00004080590042105A800F098FFB8F12C0F2C +:1006F000F2D1012000FA07F747EA0B0B5FFA8BFBF8 +:100700004FF0000901F0B6F826B10BF00B030B2BEC +:1007100008BF0024FFF770FE57E746480421CDE7E5 +:10072000002EA5D00BF00B030B2BA1D10220FFF75D +:100730005BFE074600289BD0012000F09FFF0220AF +:10074000FFF7A2FE00261FFA86F8404600F0A6FF3B +:10075000044690B10021404600F0B8FF0136002861 +:10076000F1D1BA46044641F21213022105A8ADF8B0 +:1007700014303E4600F052FF27E70120FFF784FEC9 +:100780002546244B9B68AB4207D9284600F078FFEA +:10079000013040F067810435F3E7234B00251D70DD +:1007A000204BBA465D603E46ACE7002E3FF460AF9A +:1007B0000BF00B030B2B7FF45BAF0220FFF764FE03 +:1007C000322000F00DFFB0F10008FFF651AF18F035 +:1007D00003077FF44DAF0F4A926808EB050393427D +:1007E0003FF646AFB8F5807F3FF742AF124B01931B +:1007F000B84523DD4FF47A7000F0F2FE0390039ABF +:10080000002AFFF635AF019B039A03F8012B01374D +:10081000EDE700BF00230020AC240020902300203F +:1008200011040008B0240020A82300200423002085 +:10083000082300200C230020AC230020C820FFF751 +:10084000D3FD074600283FF413AF1F2D11D8C5F183 +:10085000200242450AAB25F0030028BF42468349E7 +:100860000192184400F0A8FF019A8048FF2100F08F +:10087000B5FF4FEAA8037D490193C8F387022846D4 +:1008800000F0B4FF064600283FF46DAF019B05EB76 +:10089000830537E70220FFF7A7FD00283FF4E8AE05 +:1008A00000F034FF00283FF4E3AE0027B846704B59 +:1008B0009B68BB4218D91F2F11D80A9B01330ED059 +:1008C00027F0030312AA134453F8203C0593404633 +:1008D000042205A901F0E4F904378046E7E7384629 +:1008E00000F0CEFE0590F2E7CDF81480042105A8B3 +:1008F00000F094FE06E70023642104A8049300F0AE +:1009000083FE00287FF4B4AE0220FFF76DFD0028BF +:100910003FF4AEAE049800F0E1FE0590E6E7002358 +:10092000642104A8049300F06FFE00287FF4A0AEB9 +:100930000220FFF759FD00283FF49AAE049800F01A +:10094000DDFEEAE70220FFF74FFD00283FF490AEFE +:1009500000F0ECFEE1E70220FFF746FD00283FF43F +:1009600087AE05A9142000F0E7FE04210746049095 +:1009700004A800F053FE3946B9E7322000F030FEFB +:10098000071EFFF675AEBB077FF472AE384A926859 +:1009900007EB090393423FF66BAE0220FFF724FDFD +:1009A00000283FF465AE27F003074F44B9453FF4F4 +:1009B000A9AE484600F064FE0421059005A800F0A9 +:1009C0002DFE09F10409F1E74FF47A70FFF70CFDF1 +:1009D00000283FF44DAE00F099FE002844D00A9B59 +:1009E00001330BD008220AA9002000F0FFFE0028E6 +:1009F0003AD02022FF210AA800F0F0FEFFF7FCFC0D +:100A00001C4803F009FD13B0BDE8F08F002E3FF441 +:100A10002FAE0BF00B030B2B7FF42AAE00236421C7 +:100A200005A8059300F0F0FD074600287FF420AEEE +:100A30000220FFF7D9FC804600283FF419AEFFF7EB +:100A4000DBFC41F2883003F0E7FC059800F030FF52 +:100A5000464600F00FFF3C46B7E5064652E64FF02B +:100A6000000905E6BA467EE637467CE6AC23002060 +:100A700000230020A0860100094A136849F269009A +:100A800099B21B0C00FB01331360064B186844F24B +:100A9000506182B2000C01FB0200186080B2704706 +:100AA000182300201423002010B500211022044632 +:100AB00000F094FE034B03CB206061601868A060D7 +:100AC00010BD00BF107AFF1F2DE9F041ADF54E7D3E +:100AD0000DF134086CAC40F2751207460D460EA8B5 +:100AE0000021C8F8001000F079FE4FF4C472002114 +:100AF000204600F073FE02F041F8254B4FF47A7265 +:100B0000B0FBF2F0186093E80700022384E80700C6 +:100B10000DF5E9702382FFF7C7FF4FF4A6431D4987 +:100B2000238406A804F0FCFB192384F832310DF26B +:100B3000E32206AB0DF1300C1E4603CE6645106075 +:100B40005160334602F10802F6D133781370414602 +:100B50000122204600F0C6FE00230393AB7E0293E1 +:100B600005F11903019380B20123CDE904800093BC +:100B7000E97E05A3D3E90023384602F0C7FB0DF553 +:100B80004E7DBDE8F08100BF9E6AC421818A46EE99 +:100B9000B8240020305300082DE9F0412C4C237A72 +:100BA000DAB080460D465BBB27A9284600F0AAFFB5 +:100BB0000746002842D19DF89D60C82E3ED80146C8 +:100BC0004FF4A662204600F009FE4FF48073C4F88B +:100BD000F8314FF40073C4F80C334FF44073C4F889 +:100BE000203432460DF19E0104F1090000F0E4FDCD +:100BF00026449DF89C30777223720BB9EB7E2372EA +:100C00008122002106AC27A800F0E8FD0122214640 +:100C100027A800F0B3FF00230393AB7E029305F1F6 +:100C2000190380B201932823CDE904400093E97EA3 +:100C300005A3D3E90023404602F068FB5AB0BDE8A3 +:100C4000F08100BFAFF3008026417272DF25D7B775 +:100C5000D8450020F0B5254E4FF48A7505FB006598 +:100C6000F1B096F8D83085F8DC300024D82221463F +:100C700085F8E8403AA800F0B1FD06F1090000F05F +:100C8000A5FDD5F8E4308DF8F000C2B206AF06F14C +:100C900009010DF1F100CDE93A3400F08DFD39463E +:100CA00001223AA800F096FF80B2CDE90470082333 +:100CB0000127CDE9023706F1D803019330230093D1 +:100CC000317A0B4807A3D3E9002302F01FFBA042AF +:100CD00006DD01F053FFC5F8E000384671B0F0BD05 +:100CE0002046FBE778F6339F93CACD8DD845002088 +:100CF000D03400202DE9F0411D4D1E4E1E4F86B010 +:100D0000284602F02FFB034658B30024CDE90344E4 +:100D1000ADF81440027B8DF8142099684068029465 +:100D200003AA03C21B68DFF8548043F00043029318 +:100D300001F026FF821941F10003009402A9384610 +:100D400001F0CEF9A04205DD284602F00FFB88F83D +:100D50000040D5E798F80030072B05D8013388F814 +:100D6000003006B0BDE8F081014802F0FFFAF8E774 +:100D7000D034002040420F00003500200D4B0020F1 +:100D800070B50D4614461E4602F01CFA50B9022EEC +:100D900010D1012C0ED112A3D3E90023C5E9002301 +:100DA000012007E0282C10D005D8012C09D0052CF3 +:100DB0000FD0002070BD302CFBD10BA3D3E9002352 +:100DC000ECE70BA3D3E90023E8E70BA3D3E9002367 +:100DD000E4E70BA3D3E90023E0E700BFAFF3008013 +:100DE000401DA12026812A0B78F6339F93CACD8D12 +:100DF0009E6AC421818A46EE26417272DF25D7B7EA +:100E0000F017304A39059E5638B505460E4C00217C +:100E1000013500F05BFCA4F82C55B4F82C0500F06B +:100E20003DFC78B1B4F82C0500F048FC014648B907 +:100E3000B4F82C0500F04AFCB4F82C350133A4F8C2 +:100E40002C35EAE738BD00BFD845002010B50A4B65 +:100E50000A4A1A6003F5805393F860203AB9DC6DB2 +:100E60002CB1204600F0DCFF204604F099F9BDE8E3 +:100E70001040034800F0D4BF00350020E8530008BC +:100E8000484500202DE9F04F8FB000AF05460C46D5 +:100E900002F098F9002849D1237E022B1BD1E38A66 +:100EA000012B18D101F06AFE0646FFF7E5FD034667 +:100EB0004FF4C870DFF8C482B3FBF0F206F5167683 +:100EC00002FB103316FA83F3C8F80030E37E33B91F +:100ED000A34B00221A703C37BD46BDE8F08F07F1E6 +:100EE0002401204600F0CCFD0028F4D107F11400C5 +:100EF000FFF7DAFD97F8264007F11401224607F1C3 +:100F0000270004F097F90028E2D10F2C08D8944B61 +:100F10001C70D8F80030A3F51673C8F80030DAE773 +:100F200097F82410284602F045F9D4E7E38A282BE5 +:100F30002BD010D8012B23D0052BCCD1BFF34F8F52 +:100F40008849894BCA6802F4E0621343CB60BFF35F +:100F50004F8F00BFFDE7302BBDD1844EE17E327A4A +:100F60009142B8D1607E3146002291F8DC50854232 +:100F700000F0A5800132042A01F58A71F5D1AAE7B3 +:100F800021462846FFF7A0FDA5E721462846FFF7A2 +:100F900003FEA0E7B2F8EC507B6005F103094FEACD +:100FA00099094FEA8902D11DC908A8EBC1039D46E2 +:100FB000EB460021584600F011FC04F1EE012A46F0 +:100FC0003144584600F0F8FB7B6813B9012000F06B +:100FD00055FB96F8D20000F061FB044630B9307240 +:100FE00000F094FB204600F049FBB1E0D6F8D42095 +:100FF0003AB996F8D200B6F82C25824201D8FFF70C +:1010000003FFD6F8D4202A44944208D296F8D2009E +:10101000B6F82C250130824201D8FFF7F5FE706842 +:101020005FFA89F2594600F0E1FB08B9C54679E05C +:10103000726896F8D2002A447260D6F8D42005EB84 +:101040000209C6F8D49000F029FB814509D396F82F +:10105000D220D6F8D4000132001B86F8D220C6F880 +:10106000D400FF2D0FD80024347200F04FFB20462F +:1010700000F004FB00F05CFE3D4B188108B9FFF75F +:1010800019FAC54627E7BB6896F8D9000AFB036240 +:10109000FB68D2F8E41082F8E83001F58061C2F80C +:1010A000E030C2F8E410FFF7D5FDFFF723FE96F815 +:1010B000D920013202F0030286F8D920B6E74FF4B6 +:1010C0008A7A0AFB02F505F1EA013144204600F074 +:1010D000ADFDF86000287FF4FEAE3544012285F8AE +:1010E000E82001F04BFDD5F8E020D6ED007ADFEDE9 +:1010F000216A801A192838BF192040F6B832904268 +:1011000028BF1046B8EE677A07EE900AF8EEE77A45 +:1011100067EEA67ADFED186AE7EE267AFCEEE77A4C +:10112000C6ED007A96F8D930BB60BA6873680AFBDE +:1011300002F4321992F8E81059B1D2F8E4108B4257 +:10114000E8463FF427AF002182F8E810C2F8E0102B +:10115000C5467368064A9B0A01331381BBE600BF8C +:10116000C934002000ED00E00400FA05D845002055 +:10117000B8240020CDCCCC3D6666663FCC34002040 +:10118000014B1870704700BFC424002030B54FF0E9 +:1011900000542B4B22689A4285B007D003F0C0FC64 +:1011A000044620BB0024204605B030BD254B627D9F +:1011B00025481A70237D03724FF48073C0F8F8310C +:1011C0004FF40073C0F80C3300254FF44073C0F89F +:1011D00020341E49C0F8E450C922093000F0ECFA6E +:1011E0002046E022294600F0F9FA0124DBE7184AFC +:1011F000184D136C43F000731364AA6D164B9A429A +:10120000D0D12B6E013B7E2BCCD8144A07CA01AB40 +:1012100083E807001846032100F058FD6B6D8342F8 +:101220004FF00003BED12A6D8A4201BFAB65054B6A +:101230002A6E1A7003BF0A4BEA6D1A601C46B2E7A9 +:101240009AAD44C5C4240020D845002016000020D3 +:1012500000380240006600405041A0B0586600408F +:101260001023002037B51A4D00F062FD02236B7188 +:10127000184B288119681848012201F01BFB002334 +:101280000193164B164900931648174B4FF48052A2 +:1012900001F068FF154B197811B1124801F08AFF6F +:1012A00001F06CFC0446FFF7E7FB4FF4C873B0FB9A +:1012B000F3F202FB130304F5167010FA83F00C4BE3 +:1012C000186003F023FC08B10F232B8103B030BD5D +:1012D000B82400201023002000350020810D0008D4 +:1012E000C8240020D0340020850E0008C42400202B +:1012F000CC3400202DE9F04F2DED028B8CA7D7E9DF +:1013000000670FF23429D9E90089844C95B00DADFE +:101310009FED808BFFF7EEFCDFF824B200230C93E7 +:10132000ADF83C300D936B6000230DF125028DED7F +:10133000008B4FF0010A09A958468DF825308DF829 +:1013400024A001F065FA9DF824200023002A40F033 +:10135000AE80204601F036FF0546002847D1DFF871 +:10136000E4B101F00BFCDBF8003098423FD301F010 +:1013700005FC0790FFF780FB079A4FF4C873B0FB9A +:10138000F3F101FB130302F5167010FA83F0CBF8AA +:101390000000DFF8B4B19BF800100791002914BFDA +:1013A0002B46534610A88DF83030FFF77DFB079988 +:1013B000C1F11002D2B2062A10AB28BF062219448E +:1013C0000DF13100079200F0F7F9079A0CAB039387 +:1013D000182302930132524BD2B2CDE900A30492FA +:1013E0003B463246204601F033FF8BF8005001F0B7 +:1013F000C5FB4C4A4C4D1368C31AB3F57A7F32D300 +:10140000106001F0BDFB02460B46204601F0B8FF1C +:10141000204601F0D7FE30B32B7ADFF830A1002B45 +:1014200014BF032302238AF8053001F0A7FB0DF156 +:10143000400B4FF47A730122B0FBF3F05946CAF81F +:101440000000504600F0F4FA18230293374B019342 +:1014500080B240F25513CDE903B0009342464B46AB +:10146000204601F0F5FE2B7AABB101F087FB4FF07F +:10147000000A83464FF48A7295F8D900504400F070 +:10148000030002FB005393F8E81071B30AF1010A5C +:10149000BAF1040FF0D1C82002F0BEFF2B7A002B66 +:1014A0007FF435AF15B0BDEC028BBDE8F08F194667 +:1014B000102210A800F092F90DF126030AAA0CA937 +:1014C000584600F00DFF95E8030011AB83E80300D8 +:1014D0009DF83C308DF84C300C9B109310A9DDE941 +:1014E0000A23204602F020F91EE7D3F8E01049B1A4 +:1014F0002B68FA2B38BFFA23ABEB01010533B1EBB4 +:10150000430FC3D3FFF7A6FB4FF48A720028BDD167 +:10151000C1E700BF0000000000000000D034002040 +:10152000C8340020084B0020D84500200C4B002078 +:10153000401DA12026812A0BF1C6A7C1D068080F43 +:1015400000350020CC340020C9340020B82400200D +:1015500008B5054800F060FFBDE80840034A0449AB +:10156000002003F017BE00BF003500205C4B0020B8 +:101570004D0E00082DE9F84F4FF47A73DFF85880CC +:10158000DFF8589006460D4602FB03F7002498F951 +:1015900000305A1C5FFA84FA01D0A34212D159F8E4 +:1015A000240003682A46D3F820B031463B46D8478A +:1015B000854207D1074B012083F800A0BDE8F88FD2 +:1015C0000124E4E7002CFBD04FF4FA7002F024FF72 +:1015D0000020F3E7504B00201C2300202023002094 +:1015E00007B50023024601210DF107008DF80730F1 +:1015F000FFF7C0FF20B19DF8070003B05DF804FBC2 +:101600004FF0FF30F9E700000A4608B50421FFF764 +:10161000B1FF80F00100C0B2404208BD30B4074BBA +:101620000A461978064B53F821402368DD69054BBB +:101630000146AC46204630BC604700BF504B0020FE +:1016400020230020A086010070B503F0B9F8094EF0 +:10165000094D3080002428683388834208D903F07C +:10166000A9F82B6804440133B4F5803F2B60F2D312 +:1016700070BD00BF524B0020104B002003F04EB94C +:1016800000F1006000F580300068704700F10060F4 +:10169000920000F5803003F0D9B80000054B1A68BD +:1016A000054B1B889B1A834202D9104403F082B871 +:1016B00000207047104B0020524B0020024B1B684B +:1016C000184403F07FB800BF104B0020024B1B688A +:1016D000184403F08FB800BF104B002010F0030334 +:1016E0000AD1B0F5047F05D200F10050A0F51040FA +:1016F000D0F80038184670470023FBE700F100508F +:10170000A0F51040D0F8100A70470000064991F883 +:10171000243033B10023086A81F824300822FFF70F +:10172000B5BF0120704700BF144B0020014B186863 +:10173000704700BF002004E070B5194B1D68194BBD +:101740000138C5F30B0408442D0C04221E88A64260 +:101750000BD15C680A46013C824213460FD214F951 +:10176000016F4EB102F8016BF6E7013A03F108038D +:10177000ECD181420B4602D22C2203F8012B0A4AFB +:1017800005241688AE4204D1984284BF967803F8A7 +:10179000016B013C02F10402F3D1581A70BD00BF85 +:1017A000002004E08C5300087853000870470000C4 +:1017B000704700007047000010B50023934203D02B +:1017C000CC5CC4540133F9E710BD00000346024667 +:1017D000D01A12F9011B0029FAD1704702440346BE +:1017E000934202D003F8011BFAE770472DE9F84352 +:1017F0001F4D144695F824200746884652BBDFF853 +:1018000070909CB395F824302BB92022FF214846D4 +:101810002F62FFF7E3FF95F82400C0F10802A2420F +:1018200028BF2246D6B24146920005EB8000FFF762 +:10183000C3FF95F82430A41B1E44F6B2082E1744AB +:101840009044E4B285F82460DBD1FFF75FFF002805 +:10185000D7D108E02B6A03EB82038342CFD0FFF796 +:1018600055FF0028CBD10020BDE8F8830120FBE71D +:10187000144B0020024B1A78024B1A70704700BFBD +:10188000504B00201C23002010B5074C074920684E +:101890004FF4E1330B6002F0ABFC60680349BDE834 +:1018A000104002F0A5BC00BF202300203C4B0020CC +:1018B000094B10B51422044600211846FFF78EFF8D +:1018C000064A074B127804600146BDE8104053F801 +:1018D000220002F08DBC00BF3C4B0020504B00208A +:1018E000202300202DE9F0470D46044600219046B4 +:1018F000284640F27912FFF771FF2346202200218B +:10190000284601F0B3FE231D02222021284601F0C3 +:10191000ADFE631D03222221284601F0A7FEA31D70 +:1019200003222521284601F0A1FE04F1080310221C +:101930002821284601F09AFE04F1100308223821DC +:10194000284601F093FE04F11103082240212846A5 +:1019500001F08CFE04F1120308224821284601F010 +:1019600085FE04F1140320225021284601F07EFE5A +:1019700004F1180340227021284601F077FE04F19B +:1019800020030822B021284601F070FE04F1210353 +:101990000822B821284601F069FE04F12207C0267A +:1019A0003B46314608222846083601F05FFEB6F570 +:1019B000A07F07F10107F3D104F132030822314679 +:1019C000284601F053FE002704F1330A94F8323020 +:1019D0004FEAC7099F4209F5A47615D3B8F1000F65 +:1019E00008D1314604F599730722284601F03EFEDE +:1019F00009F24F16274694F832213B1B93420CD331 +:101A0000F01DC008BDE8F0870AEB07030822314645 +:101A1000284601F02BFE0137D8E707F23313314691 +:101A20000822284601F022FE08360137E3E70000CD +:101A300013B504460846002101602346C0F8031090 +:101A40002022019001F012FE0198231D0222202184 +:101A500001F00CFE0198631D0322222101F006FE15 +:101A60000198A31D0322252101F000FE019804F135 +:101A700008031022282101F0F9FD072002B010BD53 +:101A8000F7B50023047F00910E460722194605464C +:101A900001F0B0FC731C00930122002307212846AB +:101AA00001F0A8FCC4B9B31C009305222346082109 +:101AB000284601F09FFC0D243746B278BB1B9342A9 +:101AC00011D32B7FA88A0734E408BBB9844294BFA2 +:101AD0000020012003B0F0BDAB8ADB00083BDB082F +:101AE000B3700824E8E7FB1C00932146002308227A +:101AF000284601F07FFC08340137DEE7201A18BFC2 +:101B00000120E7E7F7B50023047F00910E46082285 +:101B10001946054601F06EFC731CC4B908220093F7 +:101B200011462346284601F065FC102401237278F3 +:101B30005F1C013B934211D32B7FA88A0734E40832 +:101B4000BBB9844294BF0020012003B0F0BDAB8A32 +:101B5000DB00083BDB0873700824E7E7F319009308 +:101B6000214600230822284601F044FC08343B4665 +:101B7000DDE7201A18BF0120E7E70000F8B50E46A0 +:101B800005461446002181223046FFF727FE2B46EA +:101B900008220021304601F069FD7CB96B1C072248 +:101BA0000821304601F062FD0F2401236A785F1C92 +:101BB000013B934204D3E01DC008F8BD0824F4E7BC +:101BC000EB1921460822304601F050FD08343B460F +:101BD000ECE70000F8B50E46054614460021CE227B +:101BE0003046FFF7FBFD2B4628220021304601F04E +:101BF0003DFD7CB905F1080308222821304601F09B +:101C000035FD30242F462A7A7B1B934204D3E01DF6 +:101C1000C008F8BD2824F5E707F10903214608228A +:101C2000304601F023FD08340137ECE7F7B5047FB7 +:101C300000910E46012310220021054601F0DAFB37 +:101C4000C4B9B31C0093092223461021284601F091 +:101C5000D1FB192437467288BB1B9A4211D82B7FBF +:101C6000A88A0734E408BBB9844294BF002001204D +:101C700003B0F0BDAB8ADB00103BDB08738010249F +:101C8000E8E73B1D0093214600230822284601F087 +:101C9000B1FB08340137DEE7201A18BF0120E7E75F +:101CA00030B5094D0A4491420DD011F8013B58401E +:101CB000082340F30004013B2C4013F0FF0384EAA7 +:101CC0005000F6D1EFE730BD2083B8EDF7B54FF007 +:101CD000FF33DFF854C0DFF854E000EB81011A460F +:101CE00088421CD050F8044B019401AF042417F82B +:101CF000015B82EA05620825DB18164605F1FF350F +:101D00005241002EBCBF83EA0C0382EA0E0215F09A +:101D1000FF05F1D1013C14F0FF04E8D1E0E7D8431E +:101D2000D14303B0F0BD00BF9336EAA9EBE1F04226 +:101D3000F7B5354A106851686B4603C36A463349A4 +:101D40003348082303F086FA044688BB0A25314A43 +:101D5000106851686B4603C36A462F492C48082314 +:101D600003F078FA0446002845D00369B3F5702FD4 +:101D700041D8B0F86620532A3DD1284A024402F1E6 +:101D80005C018B4237D35C3B214900209E1AFFF750 +:101D900087FF3246074604F164010020FFF780FF09 +:101DA000A3689F4227D1E368984208BF002522E03C +:101DB0000369B3F5702F25D8428B532A20D1174AD7 +:101DC000024402F110018B4218D3103B104900204D +:101DD0009D1AFFF765FF2A46064604F11801002008 +:101DE000FFF75EFFA3689E4202D1E368984201D0EC +:101DF0000D25ACE70025284603B0F0BD1025A6E769 +:101E00000C25A4E70B25A2E7AC530008DCFF0E006D +:101E100000000108B553000890FF0E000800FFF70E +:101E200010B5037C044613B9006803F0FBF92046A3 +:101E300010BD00000023BFF35B8FC360BFF35B8F57 +:101E4000BFF35B8F8360BFF35B8F7047BFF35B8F24 +:101E50000068BFF35B8F704770B505460C30FFF725 +:101E6000F5FF05F1080604463046FFF7EFFFA042F4 +:101E700006D930466D68FFF7E9FF2544281A70BD82 +:101E80003046FFF7E3FF201AF9E7000070B505467A +:101E9000406898B105F10800FFF7D8FF05F10C067E +:101EA00004463046FFF7D2FF8442304694BF6D6847 +:101EB0000025FFF7CBFF013C2C44201A70BD000029 +:101EC00038B50C460546FFF7C7FFA04210D305F111 +:101ED0000800FFF7BBFF04446868B4FBF0F100FBA7 +:101EE0001144BFF35B8F0120AC60BFF35B8F38BD43 +:101EF0000020FCE72DE9F041144607460D46FFF7A8 +:101F0000C5FF844228BF0446D4B1B84658F80C6BCC +:101F10004046FFF79BFF3044286040467E68FFF74D +:101F200095FF331A9C4203D86C600120BDE8F08114 +:101F30006B60A41B3B68AB602044E8600220F5E7BF +:101F40002046F3E738B50C460546FFF79FFFA04251 +:101F500010D305F10C00FFF779FF04446868B4FB67 +:101F6000F0F100FB1144BFF35B8F0120EC60BFF385 +:101F70005B8F38BD0020FCE72DE9FF4188466946AC +:101F80000746FFF7B7FF6C4606B204EBC60600250E +:101F9000B44209D06268206808EB0501FFF70CFC29 +:101FA000636808341D44F3E729463846FFF7CAFF43 +:101FB000284604B0BDE8F081F8B505460C300F4660 +:101FC000FFF744FF05F1080604463046FFF73EFFE1 +:101FD000A042304688BF6C68FFF738FF201A38608F +:101FE00020B130462C68FFF731FF2044F8BD0000D7 +:101FF00073B5144606460D46FFF72EFF844228BFF0 +:1020000004460190DCB101A93046FFF7D5FF019BE2 +:1020100033B93268C5E90233C5E9002401200CE078 +:102020009C4238BF01942860019868608442F5D9C9 +:102030003368AB60241AEC60022002B070BD204609 +:10204000FBE700002DE9FF410F466946FFF7D0FF8F +:102050006C4600B204EBC0050026AC4209D0D4F8AF +:10206000048054F8081BB8194246FFF7A5FB464404 +:10207000F3E7304604B0BDE8F081000038B505460E +:10208000FFF7E0FF044601462846FFF719FF204608 +:1020900038BD000010B4026854681A4623465DF843 +:1020A000044B18470020704700207047704700001D +:1020B000002070470E20704700F5805090F8C8004F +:1020C000C0F340007047000000F5805090F9D00048 +:1020D0007047000000F58050C0F8CC100120704718 +:1020E000F7B50C68BDF8207014F0005470D10D7B6A +:1020F000082D6DD8302585F311884569AE687601C5 +:102100000CD4AC68240108D4AC6814F080545DD1C0 +:1021100084F31188204603B0F0BD01240E6804F159 +:10212000180C002EB8BFF6004FEA0C1CB4BF46F0E6 +:102130000406760545F80C600E680FFA84FC16F06C +:10214000804F18BF05EB0C1E05EB0C1C1EBFDEF804 +:10215000806146F00206CEF880610E7BCCF8846187 +:1021600005EB04158E68C5F88C614E68C5F888616A +:10217000DCF8805145F00105CCF8805100EB4416A5 +:1021800041F268052E4405EB44150544C6E90023D9 +:1021900008350E4601F10C0C56F804EB45F804EB3B +:1021A0006645F9D1843436882E8000EB441407F05C +:1021B0000305267926F00B0635432571002484F3A8 +:1021C0001188009700F0FCFC0120A4E70224A5E799 +:1021D0004FF0FF309FE7000013B500F580540191E8 +:1021E000E06DFFF753FE1F280AD90199E06D202208 +:1021F000FFF7C2FEA0F120035842584102B010BDC3 +:102200000020FBE708B5302383F3118800F58050E8 +:10221000C06DFFF70FFE002383F3118808BD000097 +:1022200000220260828142608260704710B5002205 +:102230000023C0E900230023044603810C30FFF78C +:10224000EFFF204610BD0000F0B5054600F58050B8 +:102250000C4690F8C83013F0040FC3F3800108BF98 +:10226000114661F3820304F1840680F8C83005EB5F +:10227000461389B01B79D8072ED57AB319072DD408 +:102280006846FFF7D3FF05EB441303F5835303F1CF +:10229000180703AA103318685968144603C4083392 +:1022A000BB422246F7D1186820609B88A380DDE9F5 +:1022B0000E23CDE900230123ADF808302B686946D1 +:1022C000DB6B2846984705EB46152B791A075CBF50 +:1022D00043F008032B7101E0002AF4D109B0F0BDEE +:1022E0002DE9F0479A4688B0074688469146302344 +:1022F00083F3118807F580546846FFF797FFE06D78 +:10230000FFF7AAFD1F282AD9E06D20226946FFF7B2 +:10231000B5FE202823D103AD444605AB2E4603CE9F +:102320009E4220606160354604F10804F6D13068B1 +:102330002060B388A380DDE90023C9E90023BDF84C +:102340000830AAF80030002383F3118853464A4628 +:102350004146384608B0BDE8F04700F01FBC0020F9 +:1023600080F3118808B0BDE8F08700002DE9F84F30 +:102370000023C0E90133254B044640F8183B0F46C3 +:10238000FFF74EFF04F12800FFF750FF04F1480863 +:1023900004F582554646083530462036FFF746FF9D +:1023A000AE42F9D104F580554FF480534FF0000947 +:1023B000C5E91339C5F848800123EE6504F587584F +:1023C00004F58456C5F8549085F8583085F8603087 +:1023D000083608F108084FF0000A4FF0000B46E9F4 +:1023E00008ABA6F11800FFF71BFF203646F8289C23 +:1023F0004645F4D185F8D07017B1054800F0B8FB18 +:10240000044B63612046BDE8F88F00BFE853000825 +:10241000C05300080064004010B5044B197804460E +:102420004A1C1A70FFF7A2FF204610BD584B00202F +:102430002DE9F047002950D0294B2A4FB7FBF1F581 +:1024400099428CBF0A231123581EB5FBF3FC03FBF2 +:102450001C53C4B22BB102280346F5D80020BDE8B6 +:10246000F0870CF1FF36B6F5806FF7D2C4EBC40EDF +:102470000EF103034FEAE309C3F3C703A4EB030818 +:1024800009F1010A4FF47A755FFA88F009FB0555E6 +:102490005AFA88F8B5FBF8F5B5F5617FC1BF0EF1C2 +:1024A000FF33C3F3C703E01AC0B25C1C50FA84F4D4 +:1024B0000CFB04F4B7FBF4F4A142CFD1013BDBB237 +:1024C0000F2BCBD80138C0B20728C7D80021107114 +:1024D00016809170D3700120C1E70846BFE700BFA6 +:1024E0003F420F0040787D0170B505460E464FF41F +:1024F0007A746B695B6803F00103B34207D04FF451 +:102500007A7001F089FF013CF3D1204670BD0120B3 +:10251000FCE7000030B54269936913F0700F16D0E4 +:1025200000230B4C936103F1840200EB42121179FA +:102530004D0709D5890707D5416954F823508D60A7 +:10254000117941F0040111710133032BEBD130BD3E +:10255000D453000873B51D46436916469A68D207DE +:10256000044609D59A6801219960C2F34002CDE979 +:1025700000650021FFF768FE63699A68D1050BD5F5 +:102580009A684FF480719960C2F34022CDE90065EA +:1025900001212046FFF758FE63699A68D2030BD5E4 +:1025A0009A684FF480319960C2F34042CDE90065EA +:1025B00002212046FFF748FE04F58053D3F8CC00F3 +:1025C00010B103681B699847204602B0BDE870400F +:1025D000FFF7A0BFF8B504464669002972D106F19D +:1025E0000C073868800770D006EB01153868D5F8FD +:1025F000B00110F0040FD5F8B0011ABFC00840F0C8 +:102600000040400DA061D5F8B0C11CF0020F1CBF06 +:1026100040F08040A061D5F8B40106EB011100F054 +:102620000F0084F82400D1F8B8012077D1F8B80160 +:10263000000A6077D1F8B801000CA077D1F8B80192 +:10264000000EE077D1F8BC0184F82000D1F8BC017D +:10265000000A84F82100D1F8BC01000C84F82200A3 +:10266000D1F8BC11090E84F823103821396004F127 +:10267000340004F1180104F1240551F8046B40F80A +:10268000046BA942F9D109880180C4E90A232146D3 +:102690000023238651F8283B2046DB6B984704F53E +:1026A000805393F8C820D3F8CC0042F0040283F89A +:1026B000C82010B103681B6998472046BDE8F84060 +:1026C000FFF728BF06F110078BE7F8BD10B50446E9 +:1026D00000F056FA02460B4652EA030102D0013AD4 +:1026E00063F100030449086820B12146BDE81040A9 +:1026F000FFF770BF10BD00BF544B0020F0B5302174 +:1027000081F31188DFF848C000F5835108310024B7 +:1027100004F1840500EB45152E7977070ED4F606F3 +:102720000CD5D1E9007697429E4107D246695CF804 +:102730002470B7602E7946F004062E710134032C04 +:1027400001F12001E4D1002383F31188F0BD00BF23 +:10275000D453000808B5302383F31188FFF7DAFE5D +:10276000002383F3118808BDF8B5436905469868CE +:1027700000F0E050B0F1E05F0F4621D0F8B1302317 +:1027800083F3118805F583541034002606F1840381 +:1027900005EB43131B791A0706D50136032E04F106 +:1027A0002004F3D1012007E05B07F6D42146384628 +:1027B00000F040FA0028F0D1002383F31188F8BD1F +:1027C0000120FCE708B5302383F3118800F5805021 +:1027D000C06DFFF741FB002383F3118843090CBF51 +:1027E0000120002008BD0000F8B51D46002313702D +:1027F0000F4606461446FFF7E5FF80F001003870EB +:1028000025B129463046FFF7AFFF2070F8BD000024 +:102810002DE9B8410C4615461F46804600F0B0F938 +:102820000B462178024609B9287850B14046FFF797 +:1028300065FFFFF78FFF3B462A462146FFF7D4FF8F +:102840000120BDE8B881000070B5302686F31188FC +:10285000174B1A6C42F000721A641A6A42F0007246 +:102860001A621A6A22F000721A62002383F3118836 +:1028700000F5805494F8C83013F0010516D1A9B1C1 +:1028800086F311880321132001F0E6FA03211420B6 +:1028900001F0E2FA0321152001F0DEFA94F8C830C5 +:1028A00043F0010384F8C83085F3118870BD00BF80 +:1028B000003802402DE9F04700F5805588B095F8C2 +:1028C000D030012B04468846164600F28180814FA5 +:1028D00057F823200AB947F82300D7F800A0C4F816 +:1028E0000C802674BAF1000F64D095F8D030012B1B +:1028F00070D001212046FFF7A7FF302383F3118812 +:102900006269136823F0020313606269136843F07D +:1029100001031360636900275F6187F31188012158 +:102920002046FFF7E1FD002800F09580E86DFFF7F5 +:1029300081FA04F58359BA4609F1080920220021D9 +:102940006846FEF74BFF02A8FFF76AFCCDF818A017 +:102950006A4609EB07030DF1180E9446BCE8030024 +:10296000F44518605960624603F10803F5D1DCF8BC +:102970000000186020379CF804201A71602FDDD108 +:1029800095F8C8306FF38203002785F8C8306A468F +:1029900041462046ADF80070ADF802708DF8047025 +:1029A000FFF746FD636948BB4FF400421A6008B068 +:1029B000BDE8F08741F2D80002F0F4FB814610B187 +:1029C0005146FFF7D3FCC7F80090B9F1000F8CD146 +:1029D0000020ECE7386803681B6B98470146002825 +:1029E00087D13868FFF730FF3868036832465B6884 +:1029F0004146984700287FF47CAFE9E761221A60DE +:102A00009DF802309DF803201B06120402F4702288 +:102A100003F040731343BDF80020C2F309021343CF +:102A20009DF804201205022E02F4E0020CBF4FF0C4 +:102A300000410021134362690B43D3616369132290 +:102A40005A616269136823F0010313603946204616 +:102A5000FFF74AFD08B96369A6E795F8D03093BB44 +:102A60006169D1F8002242F00102C1F800226169D7 +:102A7000D1F8002222F47C5222F00E02C1F800228A +:102A80006169D1F8002242F46062C1F800226269F3 +:102A9000C2F814326269C2F80432626941F6FF7109 +:102AA000C2F80C126269C2F840326269C2F844325C +:102AB00063690122C3F81C226269D2F8003223F054 +:102AC0000103C2F8003295F8C83043F0020385F8DC +:102AD000C8306CE7544B002008B500F051F850EABC +:102AE0000103024602D0421E61F10001044B186846 +:102AF00010B10B46FFF72EFDBDE8084001F064B8A9 +:102B0000544B002008B50020FFF7E0FDBDE8084069 +:102B100001F05AB808B50120FFF7D8FDBDE808401C +:102B200001F052B800B59BB0EFF309816822684606 +:102B3000FEF742FEEFF30583014B9B6BFEE700BF00 +:102B400000ED00E008B5FFF7EDFF000000B59BB019 +:102B5000EFF3098168226846FEF72EFEEFF3058346 +:102B6000014B5B6BFEE700BF00ED00E0FEE70000FD +:102B70000FB408B5029801F0FFFBFEE701F012BFA9 +:102B800001F0F4BE13B56C4684E80600031D94E81A +:102B9000030083E80500012002B010BD73B585680D +:102BA000019155B11B885B0707D4D0E900369B6BB8 +:102BB0009847019AC1B23046A847012002B070BDC3 +:102BC000F0B5866889B005460C465EB1BDF8383070 +:102BD0005B070AD4D0E900379B6B98472246C1B205 +:102BE0003846B047012009B0F0BD00220023CDE9EE +:102BF00000230023ADF808300A4603AB01F10806B4 +:102C0000106851681C4603C40832B2422346F7D10B +:102C1000106820609288A280FFF7B2FF0423ADF80D +:102C200008302B68CDE90001DB6B694628469847E0 +:102C3000D8E7000030B503680968DD0FB5EBD17F38 +:102C400023F0604421F060424FEAD1700BD0002B9A +:102C5000B8BFA40C0029B8BF920C944202D034BF74 +:102C60000120002030BD944205D1C1F38070C3F330 +:102C700080738342F6D194422CBF00200120F1E7FB +:102C80002DE9F041456A15B94162BDE8F0814B6814 +:102C900023F06047C3F38A464FEAD37EC3F38078BC +:102CA00016EA230638BF3E46AC462B465A68BEEBB2 +:102CB000D27F22F060440AD0002A18DAA40CB44271 +:102CC00017D19D420FD10D60DEE71346EEE7A74214 +:102CD00007D102F08044C2F3807242450BD054B158 +:102CE000EFE708D2EDE7CCF800100B60CDE7B44277 +:102CF00001D0B442E5D81A689C46002AE5D1196093 +:102D0000C3E700002DE9F047089D01F007044FEAF2 +:102D1000D508224405F0070500EBD1004FF47F49A8 +:102D2000944201D1BDE8F08704F0070705F0070AD7 +:102D300057453E4638BF5646C6F10806111B8E421F +:102D400028BF0E46E10808EBD50E415C13F80EC013 +:102D5000B94029FA06F721FA0AF1FFB28CEA01011B +:102D600047FA0AF739408CEA010C03F80EC03444E4 +:102D70003544D5E780EA0120082341F2210201B25F +:102D80004000002980B203F1FF33B8BF504013F078 +:102D9000FF03F4D17047000038B50C468D18A542EA +:102DA00000D138BD14F8011BFFF7E4FFF7E700007E +:102DB00042684AB1136843604389818901339BB2F9 +:102DC0009942438138BF83811046704770B588B0FF +:102DD000202204460D4668460021FEF7FFFC2046EF +:102DE0000495FFF7E5FF024658B16B46054608AE6D +:102DF0001C4603CCB44228606960234605F10805EF +:102E0000F6D1104608B070BD082817D909280CD093 +:102E10000A280CD00B280CD00C280CD00D280CD074 +:102E20000E2814BF4020302070470C20704710201F +:102E3000704714207047182070472020704700000A +:102E4000082817D90C280CD910280CD914280CD90B +:102E500018280CD920280CD930288CBF0F200E2020 +:102E60007047092070470A2070470B2070470C20DC +:102E700070470D20704700002DE9F843078C072F9D +:102E800004461ED9D0E9029800254FF6FF73C5F11C +:102E90002006A5F1200029FA05F108FA06F628FA1D +:102EA00000F031430143C9B21846FFF763FF08350C +:102EB000402D0346EBD1E1693A46BDE8F843FFF700 +:102EC0006BBF4FF6FF70BDE8F883000010B54B688C +:102ED00023B9CA8A63F30902CA8210BD04691A6859 +:102EE0001C600361C38A013BC3824A60EFE70000B4 +:102EF0002DE9F84F1D46CB8A0F46C3F3090105297A +:102F0000814692460B4630D00020AAB207F11A043F +:102F10009EB2042E1FFA80F80FD8904503F10103EA +:102F200006D3FB8A0A4462F30903FB8201201AE0FC +:102F30001AF80060E6540130EAE79045F1D2A1F1B9 +:102F4000050B1C237C68BBFBF3F203FB12BB1FFACF +:102F50008BF6002C45D14846FFF72AFF044638B9C6 +:102F600078606FF00200BDE8F88F4FF00008E6E7E8 +:102F7000002606607860ADB24FF0000B454510D9D1 +:102F80000AEB0803221D13F8011B9155B1B208F199 +:102F900001081B291FFA88F82BD0454506F10106C8 +:102FA000F1D8FB8AC3F30902154465F30903BCE7B2 +:102FB000013292B21C462368002BF9D16B1F0B44DF +:102FC0001C21B3FBF1F301339BB29A42D3D2BBF184 +:102FD000000FD0D14846FFF7EBFE20B9C4F800B08F +:102FE000BFE70122E7E7C0F800B05E462060044674 +:102FF000C1E74545D5D94846FFF7DAFE08B9206054 +:10300000AFE7C0F800B0002620600446B6E7000035 +:103010002DE9F04F2DED028B1C4683B05B690192C8 +:1030200007468846002B00F09A80238C2BB1E2697A +:10303000002A00F09480072B35D807F10C00FFF729 +:10304000B7FE054638B96FF00205284603B0BDEC5F +:10305000028BBDE8F08F14220021FEF7BFFB228C0B +:10306000E16905F10800FEF7A7FB208C013080B272 +:10307000FFF7E6FEFFF7C8FE013880B2208401307A +:1030800028746369228C1B782A4403F01F0363F0C1 +:103090003F0348F000411372384669602946FFF744 +:1030A000EFFD0125D1E700F10C034FF0000908EE18 +:1030B000103A4FF0800A4E464D4618EE100AFFF7C0 +:1030C00077FE83460028BED014220021FEF786FB3F +:1030D000002E3AD1019BABF8083002220BF1080E0A +:1030E0001FFA82FC0CF10100BCF1060F218C80B2AA +:1030F00001D88E422BD3FFF7A3FEFFF785FE62694E +:103100001278013802F01F028E4208BF4FF0400AC9 +:1031100042EA49121BFA80F14AEA020A013048F0F9 +:10312000004281F808A08BF81000CBF80420594623 +:103130003846FFF7A5FD238C0135B3422DB289F047 +:1031400001094FF0000AB8D17FE70022C6E7E16924 +:10315000895D0EF802100136B6B20132C0E76FF099 +:10316000010572E7F8B515460E46302200210446E7 +:103170001F46FEF733FB069B6360B5F5001F079BF8 +:10318000A76034BF6A094FF6FF72A36297B2E66187 +:1031900004F1100000239A4206D800230360A7829E +:1031A000E3822383E360F8BD0660013330462036B6 +:1031B000F1E7000003781BB94BB2002BC8BF0170C8 +:1031C0007047000000787047F8B50C46C96907469B +:1031D00011B9238C002B37D1257E1F2D34D8387898 +:1031E00028BB228C072A2CD8268A36F003032BD141 +:1031F0004FF6FF70FFF7D0FD20F0010031024004D0 +:1032000041EA0561400C41EA40254FF6FF72234632 +:1032100029463846FFF7FCFE002807DD626913786F +:103220000133DBB21F2B88BF00231370F8BD218A46 +:103230002D0645EA012505432046FFF71DFE0246FF +:10324000E5E76FF00300F1E76FF00100EEE7000043 +:1032500070B58AB0044616460021282268461D46ED +:10326000FEF7BCFABDF83830ADF810300F9B05936F +:103270009DF840308DF81830119B07936946BDF8D2 +:103280004830ADF820302046CDE90265FFF79CFFBD +:103290000AB070BD2DE9F041D36905460C461646CB +:1032A0000BB9138C5BBB377E1F2F28D895F8008095 +:1032B000B8F1000F26D03046FFF7DEFD337821024B +:1032C00041EAC33141EA0801338A41EA076141EA30 +:1032D00003410246334641F080012846FFF798FE3D +:1032E00000280ADD3378012B07D172691378013386 +:1032F000DBB21F2B88BF00231370BDE8F0816FF095 +:103300000100FAE76FF00300F7E70000F0B58BB0BB +:1033100004460D4617460021282268461E46FEF741 +:103320005DFA9DF84C305A1E534253418DF80030DF +:103330009DF84030ADF81030119B05939DF8483052 +:103340008DF81830149B07936A46BDF85430ADF8D9 +:10335000203029462046CDE90276FFF79BFF0BB0CF +:10336000F0BD0000406A00B104307047436A1A683B +:10337000426202691A600361C38A013BC3827047DB +:103380002DE9F041D0F82080194E14461D464146E3 +:10339000002709B9BDE8F081D1E90223A21A65EB43 +:1033A0000303964277EB03031ED2036A8B420DD1CF +:1033B000FFF78CFD036A1B68036203690B60C38A15 +:1033C0000161016A013BC3828846E2E7FFF77EFDA7 +:1033D0000B68C8F8003003690B60C38A0161013BC8 +:1033E000C382D8F80010D4E788460968D1E700BF47 +:1033F00080841E002DE9F04F8BB00D46DDF8509013 +:1034000014469B468046002800F01981B9F1000F50 +:1034100000F01581531E3F2B00F21181012A03D1C8 +:10342000BBF1000F40F00B810023CDE90833B8F861 +:103430001430B5EBC30F4FEAC30703D300200BB022 +:10344000BDE8F08F2B199F42D8F80C303ABF7F1B94 +:10345000FFB227461BB9D8F81030002B7AD0272DA1 +:103460004ED8C5F12806B7424FF000032CBFF6B284 +:103470003E4600932946D8F8080008AB3246FFF7CD +:1034800041FCA7EB060A35445FFA8AFAB8F8143013 +:1034900003F10053053BDB000493D8F80C30039391 +:1034A0002821039B13B1BAF1000F2CD1D8F81000DA +:1034B00040B1BAF1000F05D0009608AB5246691A28 +:1034C000FFF720FC38B2002FB8D066070AD00AAB4D +:1034D00003EBD401624211F8083C02F007021341E9 +:1034E00001F8083C082C3CD9102C40F2B580202C67 +:1034F00040F2B780BBF1000F00F09C80082334E05D +:10350000BA460026C2E7049BE02B28BFE0230693BF +:103510000B44AB42059314D95A1B0398009692456D +:1035200034BF5246D2B2691A08AB04300792FFF793 +:10353000E9FB079A1644AAEB020A1544F6B25FFAB1 +:103540008AFA049B069A05999B1A0493039B1B68AD +:103550000393A6E70093D8F8080008AB3A4629463B +:10356000AEE7BBF1000F13D00123B4EBC30F6CD057 +:10357000082C12D89DF82030621E23FA02F2D507DB +:1035800006D54FF0FF3202FA04F423438DF82030C1 +:103590009DF8203089F8003051E7102C12D8BDF882 +:1035A0002030621E23FA02F2D10706D54FF0FF3217 +:1035B00002FA04F42343ADF82030BDF82030A9F816 +:1035C00000303CE7202C0FD80899631E21FA03F342 +:1035D000DA0705D54FF0FF3202FA04F40C430894E1 +:1035E000089BC9F800302AE7402C2BD0DDE908659C +:1035F000611EC4F12102A4F1210326FA01F105FAAA +:1036000002F225FA03F311431943CB0712D5012225 +:10361000A4F12003C4F1200102FA03F322FA01F11C +:10362000A240524243EA010363EB430332432B437C +:10363000CDE90823DDE90823C9E90023FFE66FF09F +:103640000100FCE66FF00800F9E6082CA0D9102C68 +:10365000B3D9202CEED8C3E7BBF1000FADD00223C5 +:1036600083E7BBF1000FBBD004237EE730B5012A0E +:10367000144638BF0124402C85B028BF40240025C3 +:10368000012ACDE9025518D81B788DF80830630758 +:103690000AD004AB03EBD405624215F8083C02F0F3 +:1036A0000702934005F8083C00910346224600219A +:1036B00002A8FFF727FB05B030BD082AE4D9102A7D +:1036C00003D81B88ADF80830E1E7202A8DBFD3E985 +:1036D00000231B680293CDE90223D8E710B5CB681D +:1036E0001BB98B600B618B8210BD04691A681C606A +:1036F0000361C38A013BC382CA60F0E703064CBF83 +:10370000C0F3C0300220704708B50246FFF7F6FF4D +:10371000022806D15306C2F30F2001D100F00300A6 +:1037200008BDC2F30740FBE72DE9F04F93B0CDE9A8 +:1037300003230A6804461046FFF7E0FF022814BF7F +:10374000C2F306260026002A0D46824680F2F28148 +:1037500012F0C04940F0EE81097B002900F0EA81B7 +:10376000022803D02378B34240F0E781C2F3046318 +:103770000693104602F07F030593FFF7C5FF059BF4 +:1037800029444FEA834848EA0A4848EA4668CE781E +:1037900000230022CDE90823F309834648EA000804 +:1037A000029367D0059B009302466768534608A9B9 +:1037B0002046B847002800F0C381276A4FB9414628 +:1037C00004F10C00FFF702FB074690B96FF002000E +:1037D00054E03B6998450DD03F68002FF9D1414630 +:1037E00004F10C00FFF7F2FA07460028EED0236A36 +:1037F0003B60276297F817C006F01F08CCF3840CD3 +:10380000ACEB08001FFA80FE0028B8BF0EF12000C4 +:10381000A8EB0C031FFA83FED7E90221B8BF00B260 +:10382000002B0793BEBF0EF120031BB2079352EA91 +:10383000010338D0039BDFF824E39A1A049B4FF06E +:10384000000C63EB010196457CEB01032BD36B7BF2 +:1038500097F81AE0734519D1029B002B78D0012804 +:1038600021DC7868F8B9DFF8F0C2944570EB010309 +:1038700016D337E0276A27B96FF00C0013B0BDE804 +:10388000F08F3B699845B5D03F68F4E7B248904265 +:103890007CEB010301D30020F0E7029B002BFAD060 +:1038A000079B0F2B17DCFA7DB30002F0030203F035 +:1038B0007C031343FB7539462046FFF707FB6B7B00 +:1038C000BB76029B3BB9FB7DC3F38402013262F3FA +:1038D0008603FB75D0E76A7BBB7E9A42DBD1029BF5 +:1038E000002B35D0B309022B32D0039BBB60049B65 +:1038F000FB60142200210DA8FDF770FF039B0A93C3 +:10390000049B0B932B1D0C932B7BADF83EB0013B1E +:10391000DBB2ADF83C30069B8DF84230059B8DF84C +:10392000433094F82C308DF840A083F001038DF8DB +:1039300044308DF84180A3680AA920469847FB7D52 +:10394000C3F38403013303F01F039B02FB82A2E74E +:10395000FB7DC6F34012B2EBD31F40F0F480C3F3FB +:103960008403434540F0F280029A2B7BB609002A7B +:103970004DD0F2075DD4032B40F2EB80039BBB607C +:10398000049BFB602B7BAE1D033BDBB2324639460A +:1039900004F10C00FFF7ACFA00280CDA3946204697 +:1039A000FFF794FAFB7DC3F38403013303F01F0395 +:1039B0009B02FB820AE7DDE90884AB883B834FF674 +:1039C000FF73C9F12000A9F1200228FA09F104FAD5 +:1039D00000F0014324FA02F211431846C9B2FFF77E +:1039E000C9F909F10809B9F1400F0346E9D1B882D4 +:1039F0002A7B033AD2B23146FFF7CEF9FB7DB8827B +:103A0000DA43C2F3C01262F3C713FB7543E786B90A +:103A10002E1D013BDBB23246394604F10C00FFF7A4 +:103A200067FA0028BADB2A7BB88A013AD2B231465B +:103A3000E2E7F98AC1F30901013B0429DAB25BD854 +:103A4000281D002307F11B069A4208D910F801CB64 +:103A500006F801C0013101330529DBB2F4D1039925 +:103A60000A9104990B91934207F11B010C9138BF05 +:103A7000043379680D9134BF55FA83F300230E9314 +:103A8000FB8AADF83EB0C3F309031A44069B8DF8D8 +:103A90004230059B8DF8433094F82C30ADF83C2033 +:103AA00083F001038DF8443000238DF840A08DF899 +:103AB00041807B602A7BB88A013A291DFFF76CF9A7 +:103AC0003B8BB882834203D1A3680AA9204698475A +:103AD00020460AA9FFF702FEFB7DBA8AC3F38403DE +:103AE000013303F01F039B02FB823B8B9A420CBF06 +:103AF00000206FF01000C1E67B68002BAFD00520DE +:103B000001E01C3033461E68002EFAD1091A081D48 +:103B10002E1D184401EB090CBCF11B0F5FFA89F351 +:103B20009DD89A429BD916F8013B00F8013B09F158 +:103B30000109EFE76FF00900A0E66FF00A009DE6CB +:103B40006FF00B009AE66FF00D0097E66FF00E0035 +:103B500094E66FF00F0091E640420F0080841E0053 +:103B6000EFF3098305494A6B22F001024A63683387 +:103B700083F30988002383F31188704700EF00E086 +:103B8000302080F3118862B60C4B0D4AD96821F4BD +:103B9000E0610904090C0A43DA60D3F8FC20094902 +:103BA00042F08072C3F8FC200A6842F001020A6009 +:103BB0002022DA7783F82200704700BF00ED00E092 +:103BC0000003FA05001000E010B5302383F31188DC +:103BD0000E4B5B6813F4006314D0F1EE103AEFF370 +:103BE0000984683C4FF08073E361094BDB6B23660B +:103BF00084F3098800F08AFB10B1064BA36110BD65 +:103C0000054BFBE783F31188F9E700BF00ED00E007 +:103C100000EF00E03F030008420300080268436829 +:103C20001143016003B1184770470000024AD3688E +:103C300043F0C003D360704700100140024AD368CC +:103C400043F0C003D36070470044004010B50A4CF5 +:103C50000A4A2046002100F0A9FA094B094AC4E9A2 +:103C60009723094C094A0021204600F09FFA084991 +:103C7000084BC4E9971310BD604B00202D3C000891 +:103C800080F0FA0200100140CC4D00203D3C0008BD +:103C90000044004040787D012A4A037C002918BF77 +:103CA0000A46012B30B5C0F868220CD1264B984249 +:103CB00039D1264B596C41F010015964596E41F0CD +:103CC000100159665B6EB2F904501468D0F8603286 +:103CD000D0F85C12002D03EB5403B3FBF4F3BEBF2A +:103CE00023F0070503F0070343EA450394888B603C +:103CF000D38843F040030B61138943F001034B6108 +:103D000044F4045343F02C03CB6004F4A054002388 +:103D10000B60B4F5806F0B684B680CBF7F23FF23EB +:103D200080F8643230BD0A4B9842CCD1074B196CF5 +:103D300041F400311964196E41F4003119661B6EAB +:103D4000C1E700BF28540008604B00200038024043 +:103D5000CC4D00202DE9F041D0F85C62F768336863 +:103D6000DA0504469DB20DD5302383F311884FF454 +:103D700080610430FFF752FF6FF4807333600023DB +:103D800083F31188302383F3118804F1040815F0BC +:103D90002F033AD183F31188380615D5290613D598 +:103DA000302383F3118804F1380000F07BF90028F8 +:103DB0004EDA0821201DFFF731FF4FF67F733B409D +:103DC000F360002383F311887A0616D56B0614D5A9 +:103DD000302383F31188D4E913239A420AD1236C48 +:103DE00043B127F040073F041021201D3F0CFFF78F +:103DF00015FFF760002383F31188D4F86822D36895 +:103E000043B3BDE8F041106918472B0714D015F0F3 +:103E1000080F0CBF00214FF48071E80748BF41F044 +:103E20002001AA0748BF41F040016B0748BF41F09D +:103E300080014046FFF7F2FEAD06736805D594F8A1 +:103E400064122046194000F0E1F93568ADB29EE7F2 +:103E50007060B6E7BDE8F08100F1604303F56143AF +:103E60000901C9B283F80013012200F01F039A4030 +:103E700043099B0003F1604303F56143C3F88021CC +:103E80001A607047F8B5154682680669AA420B4663 +:103E9000816938BF8568761AB54204460BD2184648 +:103EA0002A46FDF789FCA3692B44A361A3685B1B29 +:103EB000A3602846F8BD0CD918463246FDF77CFCB5 +:103EC000AF1BE1683A463044FDF776FCE3683B44BB +:103ED000EBE718462A46FDF76FFCE368E5E70000CC +:103EE00083689342F7B51546044638BF8568D0E924 +:103EF0000460361AB5420BD22A46FDF75DFC6369B1 +:103F00002B446361A36828465B1BA36003B0F0BD2C +:103F10000DD932460191FDF74FFC0199E068AF1BC6 +:103F20003A463144FDF748FCE3683B44E9E72A465A +:103F3000FDF742FCE368E4E710B50A440024C361DE +:103F4000029B8460C0E90000C0E90511C160026104 +:103F5000036210BD08B5D0E90532934201D18268F1 +:103F600082B98268013282605A1C42611970D0E9BC +:103F700004329A4224BFC3684361002100F068FA0A +:103F8000002008BD4FF0FF30FBE7000070B5302384 +:103F900004460E4683F31188A568A5B1A368A269FB +:103FA000013BA360531CA36115782269934224BF8F +:103FB000E368A361E3690BB120469847002383F3CC +:103FC0001188284607E03146204600F031FA0028E3 +:103FD000E2DA85F3118870BD2DE9F74F04460E46ED +:103FE00017469846D0F81C904FF0300A8AF3118893 +:103FF0004FF0000B154665B12A4631462046FFF7C3 +:1040000041FF034660B94146204600F011FA0028FE +:10401000F1D0002383F31188781B03B0BDE8F08F43 +:10402000B9F1000F03D001902046C847019B8BF3E4 +:104030001188ED1A1E448AF31188DCE7C0E90511E6 +:10404000C160C3611144009B8260C0E9000001614E +:1040500003627047F8B504460D461646302383F3D5 +:104060001188A768A7B1A368013BA36063695A1CC4 +:1040700062611D70D4E904329A4224BFE36863612F +:10408000E3690BB120469847002080F3118807E0D0 +:104090003146204600F0CCF90028E2DA87F3118897 +:1040A000F8BD0000D0E905239A4210B501D182681D +:1040B0007AB98268013282605A1C82611C78036975 +:1040C0009A4224BFC3688361002100F0C1F92046F1 +:1040D00010BD4FF0FF30FBE72DE9F74F04460E46C9 +:1040E00017469846D0F81C904FF0300A8AF3118892 +:1040F0004FF0000B154665B12A4631462046FFF7C2 +:10410000EFFE034660B94146204600F091F90028D1 +:10411000F1D0002383F31188781B03B0BDE8F08F42 +:10412000B9F1000F03D001902046C847019B8BF3E3 +:104130001188ED1A1E448AF31188DCE7026843688F +:104140001143016003B11847704700001430FFF7B6 +:1041500043BF00004FF0FF331430FFF73DBF0000B6 +:104160003830FFF7B9BF00004FF0FF333830FFF7AA +:10417000B3BF00001430FFF709BF00004FF0FF315C +:104180001430FFF703BF00003830FFF763BF0000B3 +:104190004FF0FF323830FFF75DBF0000012914BF38 +:1041A0006FF0130000207047FFF750BD37B515467C +:1041B0000E4A026000224260C0E902220122044647 +:1041C00002740B46009000F15C014FF480721430D1 +:1041D000FFF7B2FE00942B464FF4807204F5AE71E7 +:1041E00004F13800FFF72AFF03B030BD3C5400084B +:1041F00010B53023044683F31188FFF74DFD0223E9 +:104200002374002080F3118810BD000038B5C36905 +:1042100004460D461BB904210844FFF78FFF2946C9 +:1042200004F11400FFF796FE002806DA201D4FF473 +:104230000061BDE83840FFF781BF38BD002303753A +:10424000826803691B6899689142FBD25A680360CF +:1042500042601060586070470023037582680369EC +:104260001B6899689142FBD85A68036042601060ED +:104270005860704708B50846302383F311880B7DDA +:10428000032B05D0042B0DD02BB983F3118808BD67 +:104290008B6900221A604FF0FF338361FFF7CEFF76 +:1042A0000023F2E7D1E9003213605A60F3E700001F +:1042B000FFF7C4BF054BD9680875186802681A6013 +:1042C000536001220275D860FCF724B838500020F2 +:1042D00030B50C4BDD684B1C87B004460FD02B4625 +:1042E000094A684600F046F92046FFF7E3FF009BC5 +:1042F00013B1684600F048F9A86907B030BDFFF770 +:10430000D9FFF9E73850002075420008044B1A68BD +:10431000DB6890689B68984294BF0020012070473A +:1043200038500020084B10B51C68D86822681A6005 +:10433000536001222275DC60FFF78EFF01462046A4 +:10434000BDE81040FBF7E6BF3850002038B5074CF9 +:1043500007490848012300252370656000F02CFC04 +:104360000223237085F3118838BD00BFA0520020BE +:10437000685400083850002008B572B6044B186520 +:1043800000F0E0FA00F08CFB024B03221A70FEE70B +:1043900038500020A052002000F02CB98B6002237E +:1043A00008618B82084670478368A3F1840243F852 +:1043B000142C026943F8442C426943F8402C094A02 +:1043C00043F8242CC26843F8182C022203F80C2C62 +:1043D000002203F80B2C044A43F8102CA3F1200010 +:1043E000704700BF2D0300083850002008B5FFF7C4 +:1043F000DBFFBDE80840FFF75BBF0000024BDB6856 +:1044000098610F20FFF756BF38500020302383F308 +:104410001188FFF7F3BF000008B50146302383F38E +:1044200011880820FFF754FF002383F3118808BD8B +:10443000064BDB6839B1426818605A60136043600C +:104440000420FFF745BF4FF0FF3070473850002081 +:104450000368984206D01A68026050609961184655 +:10446000FFF726BF7047000010B503689C68A242A2 +:104470000CD85C688A600B604C6021605960996858 +:104480008A1A9A604FF0FF33836010BD1B68121BBD +:10449000ECE700000A2938BF0A2170B504460D4632 +:1044A0000A26601900F080FB00F068FB041BA5429F +:1044B00003D8751C2E460446F3E70A2E04D9BDE83E +:1044C0007040012000F0B8BB70BD0000F8B5144B7F +:1044D0000D46D96103F1100141600A2A1969826011 +:1044E00038BF0A22016048601861A818144600F01D +:1044F0004BFB0A2700F042FB431BA342064606D3B0 +:104500007C1C281900F050FB27463546F2E70A2F9D +:1045100004D9BDE8F840012000F08EBBF8BD00BF13 +:1045200038500020F8B506460D4600F027FB0F4A2C +:10453000134653F8107F9F4206D12A460146304663 +:10454000BDE8F840FFF7C2BFD169BB68441A2C1917 +:1045500028BF2C46A34202D92946FFF79BFF2246DB +:1045600031460348BDE8F840FFF77EBF38500020D1 +:104570004850002010B4C0E9032300235DF8044B29 +:104580004361FFF7CFBF000010B5194C2369984273 +:104590000DD0D0E90032816813605A609A680A44ED +:1045A0009A60002303604FF0FF33A36110BD2346E0 +:1045B000026843F8102F53600022026022699A4279 +:1045C00003D1BDE8104000F0E9BA936881680B445C +:1045D000936000F0D3FA2269E1699268441AA2421A +:1045E000E4D91144BDE81040091AFFF753BF00BFDA +:1045F000385000202DE9F047DFF8BC8008F11007A3 +:104600002C4ED8F8105000F0B9FAD8F81C40AA681F +:10461000031B9A423ED81444D5E900324FF00009FA +:10462000C8F81C4013605A60C5F80090D8F81030E4 +:10463000B34201D100F0B2FA89F31188D5E9033110 +:1046400028469847302383F311886B69002BD8D014 +:1046500000F094FA6A69A0EB04094A4582460DD23B +:10466000022000F0E9FA0022D8F81030B34208D155 +:1046700051462846BDE8F047FFF728BF121A2244EA +:10468000F2E712EB090938BF4A4629463846FFF7D8 +:10469000EBFEB5E7D8F81030B34208D01444211A25 +:1046A000C8F81C00A960BDE8F047FFF7F3BEBDE8FD +:1046B000F08700BF485000203850002038B500F087 +:1046C0005DFA054AD2E90845031B181945F10001B6 +:1046D000C2E9080138BD00BF3850002000207047F3 +:1046E000FEE70000704700004FF0FF307047000009 +:1046F000BFF34F8F024AD368DB03FCD4704700BF7F +:10470000003C024008B5094B1B7873B9FFF7F0FF76 +:10471000074B1A69002ABFBF064A5A6002F1883265 +:104720005A601A6822F480621A6008BDA8520020FC +:10473000003C02402301674508B50B4B1B7893B939 +:10474000FFF7D6FF094B1A6942F000421A611A6856 +:1047500042F480521A601A6822F480521A601A6871 +:1047600042F480621A6008BDA8520020003C02405A +:104770000B28F0B516D80C4C0C4923787BB90C4D9E +:104780000E460C234FF0006255F8047B46F8042BCC +:10479000013B13F0FF033A44F6D10123237051F893 +:1047A0002000F0BD0020FCE7DC520020AC520020CD +:1047B00074540008014B53F82000704774540008EB +:1047C0000C2070470B2810B5044601D9002010BDFD +:1047D000FFF7CEFF064B53F824301844C21A0BB92A +:1047E0000120F4E712680132F0D1043BF6E700BF84 +:1047F000745400080B2810B5044621D8FFF778FF41 +:10480000FFF780FF0F4AF323D360C300DBB243F40A +:10481000007343F002031361136943F4803313619F +:10482000FFF766FFFFF7A4FF074B53F8241000F0D3 +:1048300033F9FFF781FF2046BDE81040FFF7C2BF04 +:10484000002010BD003C024074540008F8B512F07E +:104850000103144642D18218B2F1016F57D82D4B93 +:104860001B6813F0010352D02B4DFFF74BFFF323CE +:10487000EB60FFF73DFF40F20127032C15D824F031 +:1048800001046618244C401A40F20117B142236912 +:1048900000EB010524D123F001032361FFF74CFF56 +:1048A0000120F8BD043C0430E7E78307E7D12B691A +:1048B00023F440732B612B693B432B6151F8046B4C +:1048C0000660BFF34F8FFFF713FF03689E42E9D0E6 +:1048D0002B6923F001032B61FFF72EFF0020E0E797 +:1048E00023F44073236123693B4323610B882B80AE +:1048F000BFF34F8FFFF7FCFE2D8831F8023BADB2BE +:10490000AB42C3D0236923F001032361E4E71846D7 +:10491000C7E700BF00380240003C0240084908B524 +:104920000B7828B11BB9FFF7EDFE01230B7008BD12 +:10493000002BFCD0BDE808400870FFF7FDBE00BFAB +:10494000A85200200149024800F0A8B800FF030067 +:10495000000100200846114600F046BC012000F08E +:1049600043BC0000084600F05DBC000038B5EFF322 +:1049700011859DB9EFF30584C4F30804302334B1E5 +:1049800083F31188FFF79AFE85F3118838BD83F30E +:104990001188FFF793FE84F3118838BDBDE83840D5 +:1049A000FFF78CBE38B5FFF7E1FF114C114AC00884 +:1049B00040EA4170A0FB025EC908A0FB040C1CEB9E +:1049C000050CA1FB04404FF000035B41A1FB021268 +:1049D0001CEB040C43EB000011EB0E0142F1000252 +:1049E000411842F10000090941EA007038BD00BFDA +:1049F000CFF753E3A59BC42010B50244064BD2B2B7 +:104A0000904200D110BD441C00B253F8200041F880 +:104A1000040BE0B2F4E700BF502800400F4B30B564 +:104A20001C6F240407D41C6F44F400741C671C6FB3 +:104A300044F400441C670A4C236843F480732360E9 +:104A40000244084BD2B2904200D130BD441C00B2A7 +:104A500051F8045B43F82050E0B2F4E7003802401C +:104A6000007000405028004007B5012201A9002035 +:104A7000FFF7C2FF019803B05DF804FB13B50446CD +:104A8000FFF7F2FFA04205D0012201A90020019406 +:104A9000FFF7C4FF02B010BD704700007047000070 +:104AA00070470000074B45F255521A6002225A60C7 +:104AB00040F6FF729A604CF6CC421A60024B01221B +:104AC0001A70704700300040E4520020034B1B78FE +:104AD0001BB1034B4AF6AA221A607047E452002029 +:104AE00000300040034B1A681AB9034AD2F8742800 +:104AF0001A607047E052002000300240024B4FF035 +:104B00008072C3F8742870470030024008B5FFF780 +:104B1000E9FF024B1868C0F3407008BDE052002066 +:104B200008B5FFF7DFFF024B1868C0F3007008BD3F +:104B3000E052002070470000FEE700000A4B0B48DF +:104B40000B4A90420BD30B4BDA1C121AC11E22F0F7 +:104B500003028B4238BF00220021FCF73FBE53F80E +:104B6000041B40F8041BECE71C560008705300209F +:104B7000705300207053002000F0D0B8014B586AE9 +:104B8000704700BF000C0040034B002258631A61BD +:104B90000222DA60704700BF000C0040014B002287 +:104BA000DA607047000C0040014B5863704700BF4B +:104BB000000C0040FEE7000070B51B4B01630025B0 +:104BC000044686B0586085620E46FEF7D9FF04F1B0 +:104BD0001003C4E904334FF0FF33C4E90635C4E9D8 +:104BE0000044A560E562FFF7C9FF2B460246C4E911 +:104BF000082304F134010D4A256580232046FFF780 +:104C0000CDFB0123E0600A4A0375009272680192AD +:104C1000B268CDE90223074B6846CDE90435FFF7BA +:104C2000E5FB06B070BD00BFA0520020A4540008F0 +:104C3000A9540008B54B0008024AD36A1843D06251 +:104C4000704700BF385000204B6843608B6883601A +:104C5000CB68C3600B6943614B6903628B69436234 +:104C60000B6803607047000008B5234B23481A699E +:104C700042F0FF021A611A6922F0FF021A611A69F2 +:104C80001A6B42F0FF021A631A6D42F0FF021A65B6 +:104C90001B4A1B6D1146FFF7D7FF02F11C0100F5FF +:104CA0008060FFF7D1FF02F1380100F58060FFF767 +:104CB000CBFF02F1540100F58060FFF7C5FF02F160 +:104CC000700100F58060FFF7BFFF02F18C0100F575 +:104CD0008060FFF7B9FF02F1A80100F58060FFF7DF +:104CE000B3FF02F1C40100F58060FFF7ADFFBDE83E +:104CF000084000F08FB800BF0038024000000240BA +:104D0000B054000808B500F029FAFFF71FFBBDE812 +:104D10000840FFF7E7BE0000704700000E4B1A6C1A +:104D200042F008021A641A6E42F008021A660B4A30 +:104D30001B6E936843F008039360094B31229A621B +:104D40004FF0FF32DA6200229A615A63DA605A60E9 +:104D500001225A611A60704700380240002004E0C6 +:104D6000000C0040094A08B51169D3680B40D9B25C +:104D7000C9439B07116107D5302383F31188FFF7DF +:104D80000BFB002383F3118808BD00BF000C00401B +:104D90001E4B1A6962F0FF021A611A69D2B21A61D7 +:104DA0004FF0FF301A695A69586100215A695961F8 +:104DB0005A691A6A62F080521A621A6A02F08052C4 +:104DC0001A621A6A5A6A58625A6A59625A6A1A6C9C +:104DD00042F080521A641A6E42F080521A661A6EBD +:104DE0000B4A106840F480701060186F00F4407037 +:104DF000B0F5007F1EBF4FF4803018671967536805 +:104E000023F40073536000F07DB900BF0038024006 +:104E1000007000403B4B3C4A1A643C4A4FF440410E +:104E200011601A6842F001021A601A689007FCD5F6 +:104E30009A6822F003029A60324B9A6812F00C02D0 +:104E4000FBD1196801F0F90119609A601A6842F4FF +:104E500080321A601A689103FCD55A6F42F0010241 +:104E60005A67284B5A6F9207FCD5294A5A601A682C +:104E700042F080721A60254A53685804FCD5214BD1 +:104E80001A689101FCD5234AC3F884201A6842F0BD +:104E900080621A601A681201FCD51F4A9A600322C8 +:104EA000C3F88C204FF00062C3F894201B4B1A68A3 +:104EB0001B4B9A421B4B21D11B4A11681B4A914242 +:104EC0001CD140F203121A60164A136803F00F0354 +:104ED000032BFAD10B4B9A6842F002029A609A684F +:104EE00002F00C02082AFAD15A6C42F480425A6449 +:104EF0005A6E42F480425A665B6E704740F203720B +:104F0000E1E700BF003802400004001000700040DC +:104F1000041940020830002400948838002004E07E +:104F200011640020003C024000ED00E041C20F414E +:104F3000074A08B5536903F00103536123B1054AD9 +:104F400013680BB150689847BDE80840FEF73CBEB7 +:104F5000003C0140E8520020074A08B5536903F0BD +:104F60000203536123B1054A93680BB1D068984797 +:104F7000BDE80840FEF728BE003C0140E852002092 +:104F8000074A08B5536903F00403536123B1054A86 +:104F900013690BB150699847BDE80840FEF714BE8D +:104FA000003C0140E8520020074A08B5536903F06D +:104FB0000803536123B1054A93690BB1D06998473F +:104FC000BDE80840FEF700BE003C0140E85200206A +:104FD000074A08B5536903F01003536123B1054A2A +:104FE000136A0BB1506A9847BDE80840FEF7ECBD64 +:104FF000003C0140E8520020164B10B55C6904F4F7 +:1050000078725A61A30604D5134A936A0BB1D06A29 +:105010009847600604D5104A136B0BB1506B984744 +:10502000210604D50C4A936B0BB1D06B9847E2056F +:1050300004D5094A136C0BB1506C9847A30504D5ED +:10504000054A936C0BB1D06C9847BDE81040FEF751 +:10505000BBBD00BF003C0140E8520020194B10B519 +:105060005C6904F47C425A61620504D5164A136DEA +:105070000BB1506D9847230504D5134A936D0BB1BE +:10508000D06D9847E00404D50F4A136E0BB1506EF3 +:105090009847A10404D50C4A936E0BB1D06E984783 +:1050A000620404D5084A136F0BB1506F984723046C +:1050B00004D5054A936F0BB1D06F9847BDE81040F7 +:1050C000FEF782BD003C0140E852002008B50348CD +:1050D000FEF740FEBDE80840FEF776BD604B0020BD +:1050E00008B50348FEF736FEBDE80840FEF76CBD84 +:1050F000CC4D002008B5FFF735FEBDE80840FEF7AF +:1051000063BD0000062108B50846FEF7A5FE06218E +:105110000720FEF7A1FE06210820FEF79DFE0621CE +:105120000920FEF799FE06210A20FEF795FE0621CA +:105130001720FEF791FE06212820FEF78DFE07219D +:105140003220FEF789FE0C212520FEF785FEBDE802 +:1051500008400C212620FEF77FBE000008B5FFF7AF +:1051600017FE00F009F8FFF71FF8FFF7D5FDBDE8BF +:105170000840FFF701BD00000023054A194601332E +:10518000102BC2E9001102F10802F8D1704700BFEC +:10519000E85200200B460146184600F02DB80000EA +:1051A00000F040B8012838BF012010B50446204661 +:1051B00000F030F830B900F007F808B900F00CF84A +:1051C0008047F4E710BD0000024B1868BFF35B8F07 +:1051D000704700BF6853002008B5062000F084F82F +:1051E0000120FFF77DFA0000024B0A4601461868CD +:1051F000FFF7B0BB2823002010B5054C13462CB197 +:105200000A4601460220AFF3008010BD2046FCE7AD +:1052100000000000024B01461868FFF79FBB00BF6B +:1052200028230020024B01461868FFF79BBB00BFF4 +:105230002823002010B501390244904201D10020FA +:1052400005E0037811F8014FA34201D0181B10BDEF +:105250000130F2E72DE9F041A3B1C91A17780144F2 +:10526000044603F1FF3C8C42204601D9002009E0AE +:105270000578BD4204F10104F5D10CEB0405D61804 +:10528000A54201D1BDE8F08115F8018D16F801EDB8 +:10529000F045F5D0E7E700001F2938B504460D4674 +:1052A00004D9162303604FF0FF3038BD426C12B1B1 +:1052B00052F821304BB9204600F030F82A4601461A +:1052C0002046BDE8384000F017B8012B0AD0591C21 +:1052D00003D1162303600120E7E7002442F82540AC +:1052E000284698470020E0E7024B01461868FFF780 +:1052F000D3BF00BF2823002038B5074D0023044644 +:10530000084611462B60FFF7EFF9431C02D12B68CA +:1053100003B1236038BD00BF6C530020FFF7DEB936 +:10532000034611F8012B03F8012B002AF9D170472D +:105330006F72672E6172647570696C6F742E415262 +:105340004B5F43414E4E4F444500000053544D3394 +:1053500032463F3F3F0053544D333246343078009D +:1053600053544D3332463432780053544D33324621 +:10537000343436585800000001203300001041003A +:1053800001105A00031059000710310000000000FE +:105390004C53000813040000565300081904000081 +:1053A00060530008210400006A53000840A2E4F1A1 +:1053B000646891060041A3E5F26569920700000068 +:1053C0004261642043414E496661636520696E64B1 +:1053D00065782E0080000000008000000000800042 +:1053E000000000000000000095200008B52800081B +:1053F00011280008D5200008E1200008E12200085B +:10540000A5200008B5200008A9200008B120000848 +:10541000AD20000805220008B9200008852B0008EF +:10542000C9200008D92100080096000000000000F3 +:10543000000000000000000000000000000000006C +:105440006941000855410008914100087D4100086C +:105450008941000875410008614100084D4100087C +:105460009D41000863300000645400089050002003 +:10547000A05200200040000000400000004000005A +:1054800000400000000001000000020000000200D7 +:105490000000020000000200000002000000020004 +:1054A000000002006D61696E0069646C65000000B7 +:1054B000A00195AA00070000AAAAAAAA50010064A8 +:1054C000FFF90000007700000090097080000001E3 +:1054D00000000000AAAAAAAA40000001FFFF0000E5 +:1054E00000700000000000000000005000000000FC +:1054F000AAAAAA5A00000000FF3F00000000000016 +:10550000000000000000000000000000AAAAAAAAF3 +:1055100000000000FFFF000000000000000000008D +:105520000000000000000000AAAAAAAA00000000D3 +:10553000FFFF00000000000000000000000000006D +:1055400000000000AAAAAAAA00000000FFFF0000B5 +:10555000000000000000000000000000000000004B +:10556000AAAAAAAA00000000FFFF00000000000095 +:105570000000000000000000000000000A00000021 +:105580000000000003000000000000000000000018 :10559000530000000000000000000F0000000000A9 :1055A00040420F00FE2A0100D2040000FF0000006C -:1055B00008470020744900202C2300200000000030 +:1055B000604B0020CC4D00202C2300200000000078 :1055C00000000000000000000000000000000000DB :1055D00000000000000000000000000000000000CB :1055E00000000000000000000000000000000000BB diff --git a/Tools/bootloaders/ARK_GPS_bl.bin b/Tools/bootloaders/ARK_GPS_bl.bin index 35f306f9c63f2a..12dcfd7eff154b 100755 Binary files a/Tools/bootloaders/ARK_GPS_bl.bin and b/Tools/bootloaders/ARK_GPS_bl.bin differ diff --git a/Tools/bootloaders/ARK_GPS_bl.hex b/Tools/bootloaders/ARK_GPS_bl.hex index e705911e53c6aa..efc643d73f845f 100644 --- a/Tools/bootloaders/ARK_GPS_bl.hex +++ b/Tools/bootloaders/ARK_GPS_bl.hex @@ -1,1283 +1,1233 @@ :020000040800F2 -:1000000000070020F5040008E52600089D260008EA -:10001000C52600089D260008BD260008F704000834 -:10002000F7040008F7040008F7040008D9360008B0 -:10003000F7040008F7040008F7040008F7040008B4 -:10004000F7040008F7040008F7040008F7040008A4 -:10005000F7040008F7040008E54400080D4500080F -:10006000354500085D45000885450008F70400088F -:10007000F7040008F7040008F7040008F704000874 -:10008000F7040008F7040008F704000851260008E8 -:100090007D2600088D260008F7040008AD450008FD -:1000A000F7040008F7040008F7040008F704000844 -:1000B00095460008F7040008F7040008F704000854 -:1000C000F7040008F7040008F7040008F704000824 -:1000D000F7040008F704000881460008F704000848 -:1000E00011460008F7040008F7040008F7040008A8 -:1000F000F7040008F7040008F7040008F7040008F4 -:10010000F7040008F7040008F7040008F7040008E3 -:10011000F7040008F7040008F7040008F7040008D3 -:10012000F7040008F7040008F7040008F7040008C3 -:10013000F7040008F7040008F7040008F7040008B3 -:10014000F7040008F7040008F7040008F7040008A3 -:10015000F7040008F7040008F7040008F704000893 -:10016000F7040008F7040008F7040008F704000883 -:10017000F7040008F7040008F7040008F704000873 -:10018000F7040008F7040008F7040008F704000863 -:10019000F7040008F7040008F7040008F704000853 -:1001A000F7040008F7040008F7040008F704000843 -:1001B000F7040008F7040008F7040008F704000833 -:1001C000F7040008F7040008F7040008F704000823 -:1001D000F7040008F7040008F7040008F704000813 -:1001E000CD12000800000000000000000000000028 -:1001F00053B94AB9002908BF00281CBF4FF0FF318E -:100200004FF0FF3000F074B9ADF1080C6DE904CE89 -:1002100000F006F8DDF804E0DDE9022304B07047E1 -:100220002DE9F047089D04468E46002B4DD18A42A9 -:10023000944669D9B2FA82F252B101FA02F3C2F1DC -:10024000200120FA01F10CFA02FC41EA030E94406D -:100250004FEA1C48210CBEFBF8F61FFA8CF708FB8E -:1002600016E341EA034306FB07F199420AD91CEB66 -:10027000030306F1FF3080F01F81994240F21C8198 -:10028000023E63445B1AA4B2B3FBF8F008FB1033E0 -:1002900044EA034400FB07F7A7420AD91CEB040415 -:1002A00000F1FF3380F00A81A74240F207816444E5 -:1002B000023840EA0640E41B00261DB1D44000236A -:1002C000C5E900433146BDE8F0878B4209D9002DCE -:1002D00000F0EF800026C5E9000130463146BDE858 -:1002E000F087B3FA83F6002E4AD18B4202D38242C2 -:1002F00000F2F980841A61EB030301209E46002D71 -:10030000E0D0C5E9004EDDE702B9FFDEB2FA82F2C5 -:10031000002A40F09280A1EB0C014FEA1C471FFA23 -:100320008CFE0126200CB1FBF7F307FB131140EA0A -:1003300001410EFB03F0884208D91CEB010103F1D7 -:10034000FF3802D2884200F2CB804346091AA4B299 -:10035000B1FBF7F007FB101144EA01440EFB00FE6D -:10036000A64508D91CEB040400F1FF3102D2A645D2 -:1003700000F2BB800846A4EB0E0440EA03409CE771 -:10038000C6F12007B34022FA07FC4CEA030C20FA1E -:1003900007F401FA06F31C43F9404FEA1C4900FA3E -:1003A00006F3B1FBF9F8200C1FFA8CFE09FB1811BB -:1003B00040EA014108FB0EF0884202FA06F20BD92E -:1003C0001CEB010108F1FF3A80F08880884240F27E -:1003D0008580A8F102086144091AA4B2B1FBF9F0C2 -:1003E00009FB101144EA014100FB0EFE8E4508D9BD -:1003F0001CEB010100F1FF346CD28E456AD9023842 -:10040000614440EA0840A0FB0294A1EB0E01A14226 -:10041000C846A64656D353D05DB1B3EB080261EB94 -:100420000E0101FA07F722FA06F3F1401F43C5E96E -:10043000007100263146BDE8F087C2F12003D840A4 -:100440000CFA02FC21FA03F3914001434FEA1C47E6 -:100450001FFA8CFEB3FBF7F007FB10360B0C43EAD8 -:10046000064300FB0EF69E4204FA02F408D91CEB88 -:10047000030300F1FF382FD29E422DD90238634486 -:100480009B1B89B2B3FBF7F607FB163341EA034126 -:1004900006FB0EF38B4208D91CEB010106F1FF3875 -:1004A00016D28B4214D9023E6144C91A46EA00466C -:1004B00038E72E46284605E70646E3E61846F8E6FE -:1004C0004B45A9D2B9EB020864EB0C0E0138A3E747 -:1004D0004646EAE7204694E74046D1E7D0467BE728 -:1004E000023B614432E7304609E76444023842E7A0 -:1004F000704700BF02E000F000F8FEE772B6374830 -:1005000080F30888364880F3098836483649086001 -:1005100040F20000CCF200004EF63471CEF2000141 -:100520000860BFF34F8FBFF36F8F40F20000C0F23F -:10053000F0004EF68851CEF200010860BFF34F8FF5 -:10054000BFF36F8F4FF00000E1EE100A4EF63C71E2 -:10055000CEF200010860062080F31488BFF36F8F8D -:1005600003F0CAFD03F05CFE4FF055301F491B4AF3 -:1005700091423CBF41F8040BFAE71D49184A9142E9 -:100580003CBF41F8040BFAE71A491B4A1B4B9A423D -:100590003EBF51F8040B42F8040BF8E7002018495D -:1005A000184A91423CBF41F8040BFAE703F0A8FD5A -:1005B00003F084FE144C154DAC4203DA54F8041BCE -:1005C0008847F9E700F042F8114C124DAC4203DACB -:1005D00054F8041B8847F9E703F090BD000700209A -:1005E000002300200000000808ED00E000010020CA -:1005F00000070020904F00080023002080230020E7 -:1006000080230020C44F0020E0010008E40100081E -:10061000E4010008E40100082DE9F04F2DED108AF7 -:10062000C1F80CD0C3689D46BDEC108ABDE8F08FC0 -:10063000002383F311882846A047002003F0CEF959 -:10064000FEE703F031F900DFFEE70000F8B500F047 -:100650004FFE03F0EBFC074603F03AFD0546002889 -:100660003FD12C4B9F423CD001339F423CD02A4B80 -:1006700027F0FF029A423AD1F8B200F045FC2E462C -:1006800042F2107400F046FC08B10024264601F046 -:100690001DF980B3032000F045F80024264635B14B -:1006A0001E4B9F4203D003F00BFD00242646002082 -:1006B00003F0C6FC1A4B1B691B0422D40EB100F0D8 -:1006C00047F800F093FC00F015FE02F013F8054621 -:1006D000CCB102F00FF8401BA04214D900F038F85A -:1006E000F3E72E460024CDE704460126CAE7064676 -:1006F0004FF47A74C6E7002CD1D04FF47A740126F7 -:10070000CDE70024DDE700F0B9FC4FF47A7003F088 -:100710006BF9DDE7010007B0000008B0263A09B028 -:1007200000040240084B187003280CD8DFE800F0E2 -:1007300008050208022000F03BBE022000F02EBE99 -:10074000024B00225A60704780230020842300203F -:1007500010B501F0BBF830B1204B03221A70204BCA -:1007600000225A6010BD1F4B1F4A1C4619680131F8 -:10077000F8D004339342F9D162681C4B9A42F1D904 -:100780001B4B9B6803F1006303F580339A42E9D267 -:1007900003F06AFC03F07CFC002000F0C5FD0220A1 -:1007A000FFF7C0FF134B1A6C00221A64196E1A6609 -:1007B000196E596C5A64596E5A665B6E72B64FF078 -:1007C000E0233021C3F8084DD4E9003281F31188C9 -:1007D0009D4683F308881047C4E700BF80230020AC -:1007E000842300200000010820000108FFFF00080A -:1007F0000023002000380240094A136849F26900CA -:1008000099B21B0C00FB01331360064B186844F2CD -:10081000506182B2000C01FB0200186080B2704788 -:10082000182300201423002010B5002110220446B4 -:1008300000F0DAFD034B03CB206061601868A06014 -:1008400010BD00BF107AFF1F2DE9F041ADF54E7DC0 -:100850000DF134086CAC40F2751207460D460EA837 -:100860000021C8F8001000F0BFFD4FF4C472002151 -:10087000204600F0B9FD01F03DFF274B4FF47A729E -:10088000B0FBF2F0186093E80700022384E8070049 -:100890000DF5E9702382FFF7C7FF4FF4A2431F490C -:1008A000238407A804F07CFA152384F832310DF272 -:1008B000E32207AB0DF12C0C1E4603CE66451060FB -:1008C0005160334602F10802F6D130681060337986 -:1008D000137141460122204600F0D2FD002303930C -:1008E000AB7E029305F11903019380B20123CDE998 -:1008F00004800093E97E06A3D3E90023384602F082 -:10090000C1FA0DF54E7DBDE8F08100BFAFF3008068 -:100910009E6AC421818A46EE8C230020B04D0008D7 -:100920002DE9F0412C4C237ADAB080460D465BBBB2 -:1009300027A9284600F0B4FE0746002842D19DF8BA -:100940009D60C82E3ED801464FF4A662204600F0B6 -:100950004BFD4FF48073C4F8F8314FF40073C4F8C2 -:100960000C334FF44073C4F8203432460DF19E012D -:1009700004F1090000F026FD26449DF89C307772B2 -:1009800023720BB9EB7E23728122002106AC27A8CB -:1009900000F02AFD0122214627A800F0BDFE002319 -:1009A0000393AB7E029305F1190380B201932823D0 -:1009B000CDE904400093E97E05A3D3E90023404636 -:1009C00002F060FA5AB0BDE8F08100BFAFF30080DA -:1009D00026417272DF25D7B7A8440020F0B5254E16 -:1009E0004FF48A7505FB0065F1B096F8D83085F8AC -:1009F000DC300024D822214685F8E8403AA800F0EF -:100A0000F3FC06F1090000F0E7FCD5F8E4308DF8BE -:100A1000F000C2B206AF06F109010DF1F100CDE917 -:100A20003A3400F0CFFC394601223AA800F0A0FE8B -:100A300080B2CDE9047008230127CDE9023706F121 -:100A4000D803019330230093317A0B4807A3D3E9ED -:100A5000002302F017FAA04206DD01F04BFEC5F8B4 -:100A6000E000384671B0F0BD2046FBE778F6339FD2 -:100A700093CACD8DA8440020A43300202DE9F04175 -:100A80001D4D1E4E1E4F86B0284602F027FA034623 -:100A900058B30024CDE90344ADF81440027B8DF82F -:100AA000142099684068029403AA03C21B68DFF807 -:100AB000548043F00043029301F01EFE821941F17D -:100AC0000003009402A9384601F0E0F8A04205DDD9 -:100AD000284602F007FA88F80040D5E798F8003079 -:100AE000072B05D8013388F8003006B0BDE8F08147 -:100AF000014802F0F7F9F8E7A433002040420F0064 -:100B0000D8330020DD49002070B50D4614461E463E -:100B100002F014F950B9022E10D1012C0ED112A3FB -:100B2000D3E90023C5E90023012007E0282C10D0D9 -:100B300005D8012C09D0052C0FD0002070BD302C19 -:100B4000FBD10BA3D3E90023ECE70BA3D3E90023EC -:100B5000E8E70BA3D3E90023E4E70BA3D3E90023E1 -:100B6000E0E700BFAFF30080401DA12026812A0BE3 -:100B700078F6339F93CACD8D9E6AC421818A46EE52 -:100B800026417272DF25D7B7F017304A39059E56D5 -:100B900038B505460E4C0021013500F0E7FBA4F8FE -:100BA0002C55B4F82C0500F0C9FB78B1B4F82C052D -:100BB00000F0D4FB014648B9B4F82C0500F0D6FB90 -:100BC000B4F82C350133A4F82C35EAE738BD00BF62 -:100BD000A844002010B50A4B0A4A1A6003F5805356 -:100BE00093F860203AB9DC6D2CB1204600F0E6FEA7 -:100BF000204604F015F8BDE81040034800F0DEBEC2 -:100C0000D8330020044E0008204400202DE9F04F86 -:100C10008FB000AF05460C4602F090F8002849D18D -:100C2000237E022B1BD1E38A012B18D101F062FD38 -:100C30000646FFF7E1FD03464FF4C870DFF8C482B3 -:100C4000B3FBF0F206F5167602FB103316FA83F3C7 -:100C5000C8F80030E37E33B9A34B00221A703C374A -:100C6000BD46BDE8F08F07F12401204600F0D6FC18 -:100C70000028F4D107F11400FFF7D6FD97F82640BD -:100C800007F11401224607F1270004F013F80028A9 -:100C9000E2D10F2C08D8944B1C70D8F80030A3F583 -:100CA0001673C8F80030DAE797F82410284602F0E7 -:100CB0003DF8D4E7E38A282B2BD010D8012B23D082 -:100CC000052BCCD1BFF34F8F8849894BCA6802F4FA -:100CD000E0621343CB60BFF34F8F00BFFDE7302BC3 -:100CE000BDD1844EE17E327A9142B8D1607E3146E8 -:100CF000002291F8DC50854200F0A5800132042AE0 -:100D000001F58A71F5D1AAE721462846FFF79CFD37 -:100D1000A5E721462846FFF703FEA0E7B2F8EC500E -:100D20007B6005F103094FEA99094FEA8902D11D59 -:100D3000C908A8EBC1039D46EB460021584600F0C8 -:100D400053FB04F1EE012A463144584600F03AFBC9 -:100D50007B6813B9012000F0E7FA96F8D20000F0A2 -:100D6000EDFA044630B9307200F008FB204600F07E -:100D7000DBFAB1E0D6F8D4203AB996F8D200B6F84A -:100D80002C25824201D8FFF703FFD6F8D4202A444D -:100D9000944208D296F8D200B6F82C25013082424F -:100DA00001D8FFF7F5FE70685FFA89F2594600F046 -:100DB00023FB08B9C54679E0726896F8D2002A4448 -:100DC0007260D6F8D42005EB0209C6F8D49000F082 -:100DD000B5FA814509D396F8D220D6F8D40001326D -:100DE000001B86F8D220C6F8D400FF2D0FD80024AF -:100DF000347200F0C3FA204600F096FA00F066FD67 -:100E00003D4B188108B9FFF7A3FCC54627E7BB682F -:100E100096F8D9000AFB0362FB68D2F8E41082F866 -:100E2000E83001F58061C2F8E030C2F8E410FFF765 -:100E3000D5FDFFF723FE96F8D920013202F0030218 -:100E400086F8D920B6E74FF48A7A0AFB02F505F155 -:100E5000EA013144204600F0B7FCF86000287FF436 -:100E6000FEAE3544012285F8E82001F043FCD5F8B8 -:100E7000E020D6ED007ADFED216A801A192838BF0C -:100E8000192040F6B832904228BF1046B8EE677A73 -:100E900007EE900AF8EEE77A67EEA67ADFED186AB9 -:100EA000E7EE267AFCEEE77AC6ED007A96F8D930BE -:100EB000BB60BA6873680AFB02F4321992F8E81052 -:100EC00059B1D2F8E4108B42E8463FF427AF002135 -:100ED00082F8E810C2F8E010C5467368064A9B0A1B -:100EE00001331381BBE600BF9D33002000ED00E01D -:100EF0000400FA05A84400208C230020CDCCCC3D72 -:100F00006666663FA0330020014B1870704700BF33 -:100F10009823002030B54FF000542B4B22689A42A2 -:100F200085B007D003F0DEF8044620BB002420463D -:100F300005B030BD254B627D25481A70237D0372B4 -:100F40004FF48073C0F8F8314FF40073C0F80C33DD -:100F500000254FF44073C0F820341E49C0F8E45017 -:100F6000C922093000F02EFA2046E022294600F07E -:100F70003BFA0124DBE7184A184D136C43F0007369 -:100F80001364AA6D164B9A42D0D12B6E013B7E2B77 -:100F9000CCD8144A07CA01AB83E8070018460321DE -:100FA00000F062FC6B6D83424FF00003BED12A6DEE -:100FB0008A4201BFAB65054B2A6E1A7003BF0A4B0C -:100FC000EA6D1A601C46B2E79AAD44C5982300202A -:100FD000A8440020160000200038024000660040AF -:100FE0005041A0B0586600401023002037B51A4D7C -:100FF00000F06CFC02236B71184B288119681848AB -:10100000012201F015FA00230193164B16490093B3 -:101010001648174B4FF4805201F060FE154B1978BB -:1010200011B1124801F082FE01F064FB0446FFF7A3 -:10103000E3FB4FF4C873B0FBF3F202FB130304F5B8 -:10104000167010FA83F00C4B186003F041F808B1E9 -:101050000F232B8103B030BD8C23002010230020F0 -:10106000D8330020090B00089C230020A433002063 -:101070000D0C000898230020A03300202DE9F04F2C -:101080002DED028B0FF23829D9E90089834C93B0FA -:101090000BAE9FED7E8BFFF7F1FC814FDFF828A2AE -:1010A00000230A93ADF834300B9373604FF0000BBC -:1010B0005B468DED008B01250DF11D0207A9384619 -:1010C0008DF81C508DF81DB001F062F99DF81C30B0 -:1010D000002B40F0A580204601F030FE0646002897 -:1010E00045D1704F01F006FB3B6898423FD301F0B9 -:1010F00001FB8246FFF780FB4FF4C873B0FBF3F2AD -:1011000002FB13030AF5167010FA83F03860664F7D -:1011100097F800B0CBF1100ABBF1000F14BF3346B3 -:101120002B465FFA8AFA0EA88DF82830FFF77CFB71 -:10113000BAF1060F28BF4FF0060A0EAB03EB0B0106 -:1011400052460DF1290000F03DF90AAB0393182334 -:1011500002930AF10102554BD2B2CDE90053049239 -:1011600020464CA3D3E9002301F02EFE3E7001F08F -:10117000C1FA4F4A4F4D1368C31AB3F57A7F2ED385 -:10118000106001F0B9FA02460B46204601F0B4FEA9 -:10119000204601F0D3FD10B32B7A474E002B14BF2D -:1011A00003230223737101F0A5FA0EAF4FF47A7393 -:1011B0000122B0FBF3F039463060304600F006FA09 -:1011C000182302933D4B019380B240F25513CDE9B1 -:1011D0000370009342464B46204601F0F5FD2B7A02 -:1011E00093B101F087FA002607464FF48A7A95F802 -:1011F000D900304400F003000AFB005393F8E820C4 -:1012000092B30136042EF2D1C82002F0EDFB2B7A06 -:10121000002B7FF43DAF13B0BDEC028BBDE8F08F27 -:10122000DAF8143083F48063CAF814305946102277 -:101230000EA800F0D9F80DF11E0308AA0AA9384635 -:1012400000F022FE96E803000FAB83E803009DF850 -:1012500034308DF844300A9B0E930EA9DDE9082343 -:10126000204602F01DF821E7D3F8E02042B12B68B8 -:10127000FA2B38BFFA23BA1A0533B2EB430FC0D3A7 -:10128000FFF7ACFB0028BCD1BEE700BF00000000A8 -:1012900000000000401DA12026812A0BA43300205D -:1012A000D8330020A03300209D3300209C33002041 -:1012B000D8490020A84400208C230020DC490020CD -:1012C000F1C6A7C1D068080F0000024008B5054864 -:1012D00000F074FEBDE80840034A0449002003F012 -:1012E00099BC00BFD8330020184A0020D50B000855 -:1012F0007047000070B502F03BFD094E094D30808B -:10130000002428683388834208D902F02BFD2B681B -:1013100004440133B4F5803F2B60F2D370BD00BFAD -:101320000C4A0020E049002002F0D2BD00F100602C -:10133000920000F5803002F061BD0000054B1A6894 -:10134000054B1B889B1A834202D9104402F00ABD48 -:1013500000207047E04900200C4A0020024B1B6827 -:10136000184402F007BD00BFE0490020024B1B6893 -:10137000184402F017BD00BFE0490020064991F86B -:10138000243033B10023086A81F824300822FFF7A3 -:10139000CDBF0120704700BFE4490020022802BFF2 -:1013A000024B4FF080629A61704700BF000002401C -:1013B000022802BF024B4FF480629A61704700BF5F -:1013C0000000024010B50023934203D0CC5CC4540B -:1013D0000133F9E710BD000003460246D01A12F9A6 -:1013E000011B0029FAD1704702440346934202D000 -:1013F00003F8011BFAE770472DE9F8431F4D144627 -:1014000095F824200746884652BBDFF870909CB3BD -:1014100095F824302BB92022FF2148462F62FFF790 -:10142000E3FF95F82400C0F10802A24228BF22463B -:10143000D6B24146920005EB8000FFF7C3FF95F856 -:101440002430A41B1E44F6B2082E17449044E4B284 -:1014500085F82460DBD1FFF791FF0028D7D108E0A1 -:101460002B6A03EB82038342CFD0FFF787FF00286C -:10147000CBD10020BDE8F8830120FBE7E449002040 -:101480002DE9F0470D46044600219046284640F2DB -:101490007912FFF7A9FF234620220021284601F0F8 -:1014A000A1FE231D02222021284601F09BFE631D80 -:1014B00003222221284601F095FEA31D03222521A7 -:1014C000284601F08FFE04F1080310222821284647 -:1014D00001F088FE04F1100308223821284601F0AB -:1014E00081FE04F1110308224021284601F07AFE12 -:1014F00004F1120308224821284601F073FE04F18A -:10150000140320225021284601F06CFE04F1180338 -:1015100040227021284601F065FE04F120030822D4 -:10152000B021284601F05EFE04F121030822B82113 -:10153000284601F057FE04F12207C0263B463146FB -:1015400008222846083601F04DFEB6F5A07F07F1C7 -:101550000107F3D104F1320308223146284601F095 -:1015600041FE002704F1330A94F832304FEAC709EC -:101570009F4209F5A47615D3B8F1000F08D1314682 -:1015800004F599730722284601F02CFE09F24F1644 -:10159000274694F832213B1B93420CD3F01DC00820 -:1015A000BDE8F0870AEB070308223146284601F020 -:1015B00019FE0137D8E707F23313314608222846CF -:1015C00001F010FE08360137E3E7000013B50446CA -:1015D0000846002101602346C0F803102022019034 -:1015E00001F000FE0198231D0222202101F0FAFDE6 -:1015F0000198631D0322222101F0F4FD0198A31D2F -:101600000322252101F0EEFD019804F108031022C8 -:10161000282101F0E7FD072002B010BDF7B5002337 -:10162000047F00910E4607221946054601F09EFCF4 -:10163000731C0093012200230721284601F096FC29 -:10164000C4B9B31C0093052223460821284601F0A3 -:101650008DFC0D243746B278BB1B934211D32B7FF0 -:10166000A88A0734E408BBB9844294BF0020012053 -:1016700003B0F0BDAB8ADB00083BDB08B370082485 -:10168000E8E7FB1C0093214600230822284601F0CE -:101690006DFC08340137DEE7201A18BF0120E7E7A8 -:1016A000F7B50023047F00910E460822194605462F -:1016B00001F05CFC731CC4B9082200931146234658 -:1016C000284601F053FC1024012372785F1C013B73 -:1016D000934211D32B7FA88A0734E408BBB9844214 -:1016E00094BF0020012003B0F0BDAB8ADB00083BB3 -:1016F000DB0873700824E7E7F31900932146002301 -:101700000822284601F032FC08343B46DDE7201A67 -:1017100018BF0120E7E70000F8B50E46054614465D -:10172000002181223046FFF75FFE2B460822002170 -:10173000304601F057FD7CB96B1C0722082130466A -:1017400001F050FD0F2401236A785F1C013B934296 -:1017500004D3E01DC008F8BD0824F4E7EB192146C6 -:101760000822304601F03EFD08343B46ECE700001D -:10177000F8B50E46054614460021CE223046FFF746 -:1017800033FE2B4628220021304601F02BFD7CB988 -:1017900005F1080308222821304601F023FD3024FA -:1017A0002F462A7A7B1B934204D3E01DC008F8BD64 -:1017B0002824F5E707F1090321460822304601F005 -:1017C00011FD08340137ECE7F7B5047F00910E46B0 -:1017D000012310220021054601F0C8FBC4B9B31C47 -:1017E0000093092223461021284601F0BFFB19244B -:1017F00037467288BB1B9A4211D82B7FA88A0734C0 -:10180000E408BBB9844294BF0020012003B0F0BDBE -:10181000AB8ADB00103BDB0873801024E8E73B1D3C -:101820000093214600230822284601F09FFB08343C -:101830000137DEE7201A18BF0120E7E730B5094D70 -:101840000A4491420DD011F8013B5840082340F35F -:101850000004013B2C4013F0FF0384EA5000F6D152 -:10186000EFE730BD2083B8EDF7B54FF0FF33DFF879 -:1018700054C0DFF854E000EB81011A4688421CD0C6 -:1018800050F8044B019401AF042417F8015B82EA7D -:1018900005620825DB18164605F1FF355241002E7A -:1018A000BCBF83EA0C0382EA0E0215F0FF05F1D1FA -:1018B000013C14F0FF04E8D1E0E7D843D14303B082 -:1018C000F0BD00BF9336EAA9EBE1F042F7B5354A27 -:1018D000106851686B4603C36A463349334808238E -:1018E00003F0F8F9044688BB0A25314A10685168AC -:1018F0006B4603C36A462F492C48082303F0EAF9D4 -:101900000446002845D00369B3F5E02F41D8B0F86C -:101910006620512A3DD1284A024402F15C018B42E3 -:1019200037D35C3B214900209E1AFFF787FF3246E0 -:10193000074604F164010020FFF780FFA3689F427F -:1019400027D1E368984208BF002522E00369B3F578 -:10195000E02F25D8428B512A20D1174A024402F1A8 -:1019600010018B4218D3103B104900209D1AFFF73D -:1019700065FF2A46064604F118010020FFF75EFFC6 -:10198000A3689E4202D1E368984201D00D25ACE7DE -:101990000025284603B0F0BD1025A6E70C25A4E7D6 -:1019A0000B25A2E7C84D0008DCFF06000000010877 -:1019B000D14D000890FF06000800FFF710B5037C2A -:1019C000044613B9006803F06DF9204610BD00000D -:1019D0000023BFF35B8FC360BFF35B8FBFF35B8FED -:1019E0008360BFF35B8F7047BFF35B8F0068BFF30B -:1019F0005B8F704770B505460C30FFF7F5FF05F1BA -:101A0000080604463046FFF7EFFFA04206D93046ED -:101A10006D68FFF7E9FF2544281A70BD3046FFF7CF -:101A2000E3FF201AF9E7000070B50546406898B159 -:101A300005F10800FFF7D8FF05F10C060446304613 -:101A4000FFF7D2FF8442304694BF6D680025FFF750 -:101A5000CBFF013C2C44201A70BD000038B50C4669 -:101A60000546FFF7C7FFA04210D305F10800FFF7B6 -:101A7000BBFF04446868B4FBF0F100FB1144BFF302 -:101A80005B8F0120AC60BFF35B8F38BD0020FCE7AB -:101A90002DE9F041144607460D46FFF7C5FF844285 -:101AA00028BF0446D4B1B84658F80C6B4046FFF73F -:101AB0009BFF3044286040467E68FFF795FF331A4D -:101AC0009C4203D86C600120BDE8F0816B60A41BD0 -:101AD0003B68AB602044E8600220F5E72046F3E76E -:101AE00038B50C460546FFF79FFFA04210D305F11D -:101AF0000C00FFF779FF04446868B4FBF0F100FBC9 -:101B00001144BFF35B8F0120EC60BFF35B8F38BDE6 -:101B10000020FCE72DE9FF41884669460746FFF7AC -:101B2000B7FF6C4606B204EBC6060025B44209D0E6 -:101B30006268206808EB0501FFF744FC636808341D -:101B40001D44F3E729463846FFF7CAFF284604B08C -:101B5000BDE8F081F8B505460C300F46FFF744FFAD -:101B600005F1080604463046FFF73EFFA042304626 -:101B700088BF6C68FFF738FF201A386020B1304604 -:101B80002C68FFF731FF2044F8BD000073B5144600 -:101B900006460D46FFF72EFF844228BF04460190FB -:101BA000DCB101A93046FFF7D5FF019B33B932689C -:101BB000C5E90233C5E9002401200CE09C4238BF8E -:101BC00001942860019868608442F5D93368AB605D -:101BD000241AEC60022002B070BD2046FBE7000032 -:101BE0002DE9FF410F466946FFF7D0FF6C4600B272 -:101BF00004EBC0050026AC4209D0D4F8048054F8A8 -:101C0000081BB8194246FFF7DDFB4644F3E73046B0 -:101C100004B0BDE8F081000038B50546FFF7E0FFED -:101C2000044601462846FFF719FF204638BD00004C -:101C3000302383F3118862B670470000002383F3DA -:101C4000118862B67047000010B4026854681A46E2 -:101C500023465DF8044B1847012070470020704769 -:101C60000020704770470000002070470E2070472A -:101C700000F5805090F8C800C0F3400070470000A5 -:101C800000F5805090F9C90070470000F7B50C6866 -:101C9000BDF8207014F000541E466FD10B7B082B4A -:101CA0006CD8FFF7C5FF4569AB685B010CD4AB6826 -:101CB0001B0108D4AC6814F080545DD1FFF7BEFF5F -:101CC000204603B0F0BD01240B6804F1180C002B72 -:101CD000B8BFDB004FEA0C1CB4BF43F004035B0544 -:101CE00045F80C300B680FFA84FC13F0804F18BFD6 -:101CF00005EB0C1E05EB0C1C1EBFDEF8803143F01B -:101D00000203CEF880310B7BCCF8843105EB04154F -:101D10008B68C5F88C314B68C5F88831DCF88031A8 -:101D200043F00103CCF8803100EB441541F2680325 -:101D30001D4403EB44130344C5E9002608330D4654 -:101D400001F10C0C55F804EB43F804EB6545F9D1AF -:101D500084342D881D8000EB441407F0030325799B -:101D600025F00B052B432371FFF768FF00973346DF -:101D700000F0E2FC0120A4E70224A5E74FF0FF30C9 -:101D80009FE7000013B500F580540191E06DFFF767 -:101D90004BFE1F280AD90199E06D2022FFF7BAFEF9 -:101DA000A0F120035842584102B010BD0020FBE7CB -:101DB00008B500F58050FFF73BFFC06DFFF708FE48 -:101DC000BDE80840FFF73ABF00220260828142600E -:101DD0008260704710B500220023C0E90023002371 -:101DE000044603810C30FFF7EFFF204610BD0000D2 -:101DF000F0B5054600F580500C4690F8C83013F059 -:101E0000040FC3F3800108BF114661F3820304F19C -:101E1000840680F8C83005EB461389B01B79D807D3 -:101E20002ED57AB319072DD46846FFF7D3FF05EBFB -:101E3000441303F5835303F1180703AA10331868FA -:101E40005968144603C40833BB422246F7D11868C8 -:101E500020609B88A380DDE90E23CDE900230123C8 -:101E6000ADF808302B686946DB6B2846984705EBD0 -:101E700046152B791A075CBF43F008032B7101E06C -:101E8000002AF4D109B0F0BD2DE9F047074688B02B -:101E900007F5805468469A468846FFF7C9FE914682 -:101EA000FFF798FFE06DFFF7A5FD1F2829D9E06D2A -:101EB00020226946FFF7B0FE202822D103AD444618 -:101EC00005AB2E4603CE9E4220606160354604F18C -:101ED0000804F6D130682060B388A380DDE90023D0 -:101EE000C9E90023BDF80830AAF80030FFF7A6FEC4 -:101EF0004A4653464146384608B0BDE8F04700F030 -:101F000009BCFFF79BFE002008B0BDE8F087000089 -:101F10002DE9F84F0023C0E90133254B044640F872 -:101F2000183B0F46FFF750FF04F12800FFF752FF60 -:101F300004F1480804F582554646083530462036F7 -:101F4000FFF748FFAE42F9D104F580554FF48053B6 -:101F50004FF00009C5E91339C5F848800123EE6543 -:101F600004F5875804F58456C5F8549085F8583020 -:101F700085F86030083608F108084FF0000A4FF085 -:101F8000000B46E908ABA6F11800FFF71DFF20364D -:101F900046F8289C4645F4D185F8C97017B1054824 -:101FA00000F0A2FB044B63612046BDE8F88F00BF40 -:101FB000044E0008DC4D00080064004010B5044BDE -:101FC000197804464A1C1A70FFF7A2FF204610BD7C -:101FD000144A00202DE9F047002950D0294B2A4F00 -:101FE000B7FBF1F599428CBF0A231123581EB5FBAC -:101FF000F3FC03FB1C53C4B22BB102280346F5D8F3 -:102000000020BDE8F0870CF1FF36B6F5806FF7D2FF -:10201000C4EBC40E0EF103034FEAE309C3F3C70395 -:10202000A4EB030809F1010A4FF47A755FFA88F00E -:1020300009FB05555AFA88F8B5FBF8F5B5F5617F47 -:10204000C1BF0EF1FF33C3F3C703E01AC0B25C1C7B -:1020500050FA84F40CFB04F4B7FBF4F4A142CFD1A2 -:10206000013BDBB20F2BCBD80138C0B20728C7D851 -:102070000021107116809170D3700120C1E70846CD -:10208000BFE700BF3F420F0040787D0170B50546B5 -:102090000E464FF47A746B695B6803F00103B34238 -:1020A00007D04FF47A7001F09FFC013CF3D1204639 -:1020B00070BD0120FCE7000030B54269936913F060 -:1020C000700F16D000230B4C936103F1840200EBD8 -:1020D000421211794D0709D5890707D5416954F88E -:1020E00023508D60117941F0040111710133032BEC -:1020F000EBD130BDF04D000873B51D46436916465F -:102100009A68D207044609D59A6801219960C2F3FA -:102110004002CDE900650021FFF76AFE63699A6815 -:10212000D1050BD59A684FF480719960C2F34022B3 -:10213000CDE9006501212046FFF75AFE63699A68E0 -:10214000D2030BD59A684FF480319960C2F34042B4 -:10215000CDE9006502212046FFF74AFE204602B085 -:10216000BDE87040FFF7A8BFF8B5044646690029EE -:102170006CD106F10C07386880076AD006EB0115B0 -:102180003868D5F8B00110F0040FD5F8B0011ABFC7 -:10219000C00840F00040400DA061D5F8B0C11CF06F -:1021A000020F1CBF40F08040A061D5F8B40106EBDF -:1021B000011100F00F0084F82400D1F8B801207755 -:1021C000D1F8B801000A6077D1F8B801000CA07707 -:1021D000D1F8B801000EE077D1F8BC0184F82000F6 -:1021E000D1F8BC01000A84F82100D1F8BC01000C30 -:1021F00084F82200D1F8BC11090E84F8231038218C -:10220000396004F1340004F1180104F1240551F897 -:10221000046B40F8046BA942F9D109880180C4E934 -:102220000A2321460023238651F8283B2046DB6BF6 -:10223000984704F58052204692F8C83043F00403D2 -:1022400082F8C830BDE8F840FFF736BF06F1100746 -:1022500091E7F8BD10B5044600F04EFA02460B4671 -:1022600052EA030102D0013A63F10003044908680D -:1022700020B12146BDE81040FFF776BF10BD00BF7A -:10228000104A0020F8B500F583511E46FFF7D0FC38 -:10229000DFF844C00831002404F1840500EB451543 -:1022A0002B795F070ED4DB060CD5D1E9007397427A -:1022B000B34107D243695CF824709F602B7943F0E7 -:1022C00004032B710134032C01F12001E4D1BDE89A -:1022D000F840FFF7B3BC00BFF04D000808B5FFF7AA -:1022E000A7FCFFF7E9FEBDE80840FFF7A7BC000028 -:1022F000F8B543690546986800F0E050B0F1E05F3A -:102300000F461FD0E8B1FFF793FC05F58354103456 -:10231000002606F1840305EB43131B791A0706D543 -:102320000136032E04F12004F3D1012007E05B07FE -:10233000F6D42146384600F039FA0028F0D1FFF7EC -:102340007DFCF8BD0120FCE700F5805008B5FFF7E3 -:102350006FFCC06DFFF74EFBFFF770FC43090CBF2D -:102360000120002008BD0000F8B51D4600231370B1 -:102370000F4606461446FFF7E7FF80F0010038706D -:1023800025B129463046FFF7B3FF2070F8BD0000A5 -:102390002DE9B8410C4615461F46804600F0ACF9C1 -:1023A0000B462178024609B9287850B14046FFF71C -:1023B00069FFFFF793FF3B462A462146FFF7D4FF0C -:1023C0000120BDE8B881000010B5FFF731FC174BC4 -:1023D0001A6C42F000721A641A6A42F000721A62B1 -:1023E0001A6A00F5805422F000721A62FFF726FC88 -:1023F00094F8C830DB0718D4B9B103211320FFF7D4 -:1024000017FC01F0C7F90321142001F0C3F90321DF -:10241000152001F0BFF994F8C83043F0010384F8A7 -:10242000C830BDE81040FFF709BC10BD00380240BD -:102430002DE9F04700F5805588B095F8C930012B9B -:102440000446884616467FD8804F57F823200AB99D -:1024500047F82300D7F800A0C4F80C802674BAF11E -:10246000000F63D095F8C930012B6FD001212046B1 -:10247000FFF7AAFFFFF7DCFB6269136823F0020392 -:1024800013606269136843F00103136063690027F6 -:102490005F6101212046FFF7D1FBFFF7F7FD002820 -:1024A00000F09580E86DFFF793FA04F58359BA467A -:1024B00009F10809202200216846FEF795FF02A8CD -:1024C000FFF782FCCDF818A06A4609EB07030DF16F -:1024D000180E9446BCE80300F44518605960624643 -:1024E00003F10803F5D1DCF80000186020379CF8F0 -:1024F00004201A71602FDDD195F8C8306FF3820384 -:10250000002785F8C8306A4641462046ADF800707D -:10251000ADF802708DF80470FFF75CFD636948BB8D -:102520004FF400421A6008B0BDE8F08741F2D000D5 -:1025300002F078FB814610B15146FFF7E9FCC7F87D -:102540000090B9F1000F8DD10020ECE738680368E6 -:102550001B6B98470146002888D13868FFF734FF85 -:102560003868036832465B684146984700287FF424 -:102570007DAFE9E761221A609DF802309DF80320E3 -:102580001B06120402F4702203F040731343BDF8DB -:102590000020C2F3090213439DF804201205022E05 -:1025A00002F4E0020CBF4FF00041002113436269C6 -:1025B0000B43D361636913225A616269136823F084 -:1025C0000103136039462046FFF760FD08B96369CF -:1025D000A6E795F8C93093BB6169D1F8002242F0B3 -:1025E0000102C1F800226169D1F8002222F47C5274 -:1025F00022F00E02C1F800226169D1F8002242F4F3 -:102600006062C1F800226269C2F814326269C2F8DD -:102610000432626941F6FF71C2F80C126269C2F8B5 -:1026200040326269C2F8443263690122C3F81C2255 -:102630006269D2F8003223F00103C2F8003295F843 -:10264000C83043F0020385F8C8306CE7104A002018 -:1026500008B500F051F850EA0103024602D0421ECC -:1026600061F10001044B186810B10B46FFF744FDFF -:10267000BDE8084001F064B8104A002008B5002009 -:10268000FFF7E8FDBDE8084001F05AB808B50120A1 -:10269000FFF7E0FDBDE8084001F052B800B59BB07F -:1026A000EFF3098168226846FEF78CFEEFF305839D -:1026B000014B9B6BFEE700BF00ED00E008B5FFF7A4 -:1026C000EDFF000000B59BB0EFF30981682268467A -:1026D000FEF778FEEFF30583014B5B6BFEE700BF6F -:1026E00000ED00E0FEE700000FB408B5029801F02D -:1026F00011F9FEE701F038BC01F010BC13B56C46CF -:1027000084E80600031D94E8030083E80500012027 -:1027100002B010BD73B58568019155B11B885B0788 -:1027200007D4D0E900369B6B9847019AC1B2304676 -:10273000A847012002B070BDF0B5866889B0054693 -:102740000C465EB1BDF838305B070AD4D0E90037DB -:102750009B6B98472246C1B23846B047012009B06A -:10276000F0BD00220023CDE900230023ADF808309E -:102770000A4603AB01F10806106851681C4603C401 -:102780000832B2422346F7D1106820609288A280B6 -:10279000FFF7B2FF0423ADF808302B68CDE9000144 -:1027A000DB6B694628469847D8E7000030B50368D8 -:1027B0000968DD0FB5EBD17F23F0604421F0604262 -:1027C0004FEAD1700BD0002BB8BFA40C0029B8BFC2 -:1027D000920C944202D034BF0120002030BD9442BC -:1027E00005D1C1F38070C3F380738342F6D1944264 -:1027F0002CBF00200120F1E72DE9F041456A15B911 -:102800004162BDE8F0814B6823F06047C3F38A461C -:102810004FEAD37EC3F3807816EA230638BF3E46DC -:10282000AC462B465A68BEEBD27F22F060440AD0F9 -:10283000002A18DAA40CB44217D19D420FD10D60C2 -:10284000DEE71346EEE7A74207D102F08044C2F369 -:10285000807242450BD054B1EFE708D2EDE7CCF8D7 -:1028600000100B60CDE7B44201D0B442E5D81A683D -:102870009C46002AE5D11960C3E700002DE9F04726 -:10288000089D01F007044FEAD508224405F007052A -:1028900000EBD1004FF47F49944201D1BDE8F087AD -:1028A00004F0070705F0070A57453E4638BF56466D -:1028B000C6F10806111B8E4228BF0E46E10808EB40 -:1028C000D50E415C13F80EC0B94029FA06F721FA7B -:1028D0000AF1FFB28CEA010147FA0AF739408CEAA3 -:1028E000010C03F80EC034443544D5E780EA0120DA -:1028F000082341F2210201B24000002980B203F115 -:10290000FF33B8BF504013F0FF03F4D1704700000D -:1029100038B50C468D18A54200D138BD14F8011BFE -:10292000FFF7E4FFF7E7000042684AB1136843602D -:102930004389818901339BB29942438138BF8381A6 -:102940001046704770B588B0202204460D46684690 -:102950000021FEF749FD20460495FFF7E5FF0246FA -:1029600058B16B46054608AE1C4603CCB4422860FD -:102970006960234605F10805F6D1104608B070BD20 -:10298000082817D909280CD00A280CD00B280CD0FD -:102990000C280CD00D280CD00E2814BF402030205D -:1029A00070470C2070471020704714207047182083 -:1029B0007047202070470000082817D90C280CD930 -:1029C00010280CD914280CD918280CD920280CD977 -:1029D00030288CBF0F200E207047092070470A2036 -:1029E00070470B2070470C2070470D207047000087 -:1029F0002DE9F843078C072F04461ED9D0E9029829 -:102A000000254FF6FF73C5F12006A5F1200029FA35 -:102A100005F108FA06F628FA00F031430143C9B27D -:102A20001846FFF763FF0835402D0346EBD1E169F7 -:102A30003A46BDE8F843FFF76BBF4FF6FF70BDE8BD -:102A4000F883000010B54B6823B9CA8A63F3090202 -:102A5000CA8210BD04691A681C600361C38A013B05 -:102A6000C3824A60EFE700002DE9F84F1D46CB8A8C -:102A70000F46C3F309010529814692460B4630D023 -:102A80000020AAB207F11A049EB2042E1FFA80F8A1 -:102A90000FD8904503F1010306D3FB8A0A4462F381 -:102AA0000903FB8201201AE01AF80060E6540130A5 -:102AB000EAE79045F1D2A1F1050B1C237C68BBFB32 -:102AC000F3F203FB12BB1FFA8BF6002C45D14846EC -:102AD000FFF72AFF044638B978606FF00200BDE8BE -:102AE000F88F4FF00008E6E7002606607860ADB288 -:102AF0004FF0000B454510D90AEB0803221D13F8CF -:102B0000011B9155B1B208F101081B291FFA88F881 -:102B10002BD0454506F10106F1D8FB8AC3F3090223 -:102B2000154465F30903BCE7013292B21C462368E1 -:102B3000002BF9D16B1F0B441C21B3FBF1F30133C4 -:102B40009BB29A42D3D2BBF1000FD0D14846FFF7D7 -:102B5000EBFE20B9C4F800B0BFE70122E7E7C0F8F8 -:102B600000B05E4620600446C1E74545D5D94846D9 -:102B7000FFF7DAFE08B92060AFE7C0F800B0002622 -:102B800020600446B6E700002DE9F04F2DED028BE2 -:102B90001C4683B05B69019207468846002B00F013 -:102BA0009A80238C2BB1E269002A00F09480072BD5 -:102BB00035D807F10C00FFF7B7FE054638B96FF0BE -:102BC0000205284603B0BDEC028BBDE8F08F14224D -:102BD0000021FEF709FC228CE16905F10800FEF7EF -:102BE000F1FB208C013080B2FFF7E6FEFFF7C8FE54 -:102BF000013880B22084013028746369228C1B78EC -:102C00002A4403F01F0363F03F0348F000411372AE -:102C1000384669602946FFF7EFFD0125D1E700F14D -:102C20000C034FF0000908EE103A4FF0800A4E46B0 -:102C30004D4618EE100AFFF777FE83460028BED0F7 -:102C400014220021FEF7D0FB002E3AD1019BABF8F5 -:102C5000083002220BF1080E1FFA82FC0CF1010071 -:102C6000BCF1060F218C80B201D88E422BD3FFF726 -:102C7000A3FEFFF785FE62691278013802F01F0299 -:102C80008E4208BF4FF0400A42EA49121BFA80F117 -:102C90004AEA020A013048F0004281F808A08BF8A5 -:102CA0001000CBF8042059463846FFF7A5FD238CC9 -:102CB0000135B3422DB289F001094FF0000AB8D1B5 -:102CC0007FE70022C6E7E169895D0EF80210013650 -:102CD000B6B20132C0E76FF0010572E7F8B51546EC -:102CE0000E463022002104461F46FEF77DFB069B60 -:102CF0006360B5F5001F079BA76034BF6A094FF6F4 -:102D0000FF72A36297B2E66104F1100000239A42B9 -:102D100006D800230360A782E3822383E360F8BD23 -:102D20000660013330462036F1E7000003781BB916 -:102D30004BB2002BC8BF017070470000007870478D -:102D4000F8B50C46C969074611B9238C002B37D159 -:102D5000257E1F2D34D8387828BB228C072A2CD802 -:102D6000268A36F003032BD14FF6FF70FFF7D0FD14 -:102D700020F001003102400441EA0561400C41EAC3 -:102D800040254FF6FF72234629463846FFF7FCFEE2 -:102D9000002807DD626913780133DBB21F2B88BF7F -:102DA00000231370F8BD218A2D0645EA012505434D -:102DB0002046FFF71DFE0246E5E76FF00300F1E74E -:102DC0006FF00100EEE7000070B58AB004461646C9 -:102DD0000021282268461D46FEF706FBBDF8383064 -:102DE000ADF810300F9B05939DF840308DF81830EA -:102DF000119B07936946BDF84830ADF82030204656 -:102E0000CDE90265FFF79CFF0AB070BD2DE9F041E6 -:102E1000D36905460C4616460BB9138C5BBB377E4F -:102E20001F2F28D895F80080B8F1000F26D0304623 -:102E3000FFF7DEFD3378210241EAC33141EA0801A0 -:102E4000338A41EA076141EA03410246334641F0D1 -:102E500080012846FFF798FE00280ADD3378012B11 -:102E600007D1726913780133DBB21F2B88BF0023AF -:102E70001370BDE8F0816FF00100FAE76FF0030016 -:102E8000F7E70000F0B58BB004460D461746002169 -:102E9000282268461E46FEF7A7FA9DF84C305A1EB7 -:102EA000534253418DF800309DF84030ADF810305A -:102EB000119B05939DF848308DF81830149B0793AB -:102EC0006A46BDF85430ADF8203029462046CDE999 -:102ED0000276FFF79BFF0BB0F0BD0000406A00B127 -:102EE00004307047436A1A68426202691A600361DB -:102EF000C38A013BC38270472DE9F041D0F820809E -:102F0000194E14461D464146002709B9BDE8F08117 -:102F1000D1E90223A21A65EB0303964277EB030380 -:102F20001ED2036A8B420DD1FFF78CFD036A1B682A -:102F3000036203690B60C38A0161016A013BC382BA -:102F40008846E2E7FFF77EFD0B68C8F800300369AA -:102F50000B60C38A0161013BC382D8F80010D4E73B -:102F600088460968D1E700BF80841E002DE9F04F34 -:102F70008BB00D46DDF8509014469B4680460028E5 -:102F800000F01981B9F1000F00F01581531E3F2B9D -:102F900000F21181012A03D1BBF1000F40F00B8137 -:102FA0000023CDE90833B8F81430B5EBC30F4FEA6E -:102FB000C30703D300200BB0BDE8F08F2B199F424D -:102FC000D8F80C303ABF7F1BFFB227461BB9D8F8A0 -:102FD0001030002B7AD0272D4ED8C5F12806B742E5 -:102FE0004FF000032CBFF6B23E4600932946D8F8B6 -:102FF000080008AB3246FFF741FCA7EB060A354450 -:103000005FFA8AFAB8F8143003F10053053BDB008D -:103010000493D8F80C3003932821039B13B1BAF121 -:10302000000F2CD1D8F8100040B1BAF1000F05D034 -:10303000009608AB5246691AFFF720FC38B2002F01 -:10304000B8D066070AD00AAB03EBD401624211F88C -:10305000083C02F00702134101F8083C082C3CD957 -:10306000102C40F2B580202C40F2B780BBF1000F4D -:1030700000F09C80082334E0BA460026C2E7049B97 -:10308000E02B28BFE02306930B44AB42059314D9F1 -:103090005A1B03980096924534BF5246D2B2691A21 -:1030A00008AB04300792FFF7E9FB079A1644AAEB36 -:1030B000020A1544F6B25FFA8AFA049B069A059949 -:1030C0009B1A0493039B1B680393A6E70093D8F80D -:1030D000080008AB3A462946AEE7BBF1000F13D013 -:1030E0000123B4EBC30F6CD0082C12D89DF820300C -:1030F000621E23FA02F2D50706D54FF0FF3202FA1C -:1031000004F423438DF820309DF8203089F80030F6 -:1031100051E7102C12D8BDF82030621E23FA02F2BB -:10312000D10706D54FF0FF3202FA04F42343ADF87D -:103130002030BDF82030A9F800303CE7202C0FD813 -:103140000899631E21FA03F3DA0705D54FF0FF3221 -:1031500002FA04F40C430894089BC9F800302AE7EB -:10316000402C2BD0DDE90865611EC4F12102A4F1D9 -:10317000210326FA01F105FA02F225FA03F31143BD -:103180001943CB0712D50122A4F12003C4F1200179 -:1031900002FA03F322FA01F1A240524243EA010388 -:1031A00063EB430332432B43CDE90823DDE90823D6 -:1031B000C9E90023FFE66FF00100FCE66FF00800AC -:1031C000F9E6082CA0D9102CB3D9202CEED8C3E7EF -:1031D000BBF1000FADD0022383E7BBF1000FBBD0E2 -:1031E00004237EE730B5012A144638BF0124402C61 -:1031F00085B028BF40240025012ACDE9025518D802 -:103200001B788DF8083063070AD004AB03EBD405B4 -:10321000624215F8083C02F00702934005F8083CAA -:10322000009103462246002102A8FFF727FB05B0C4 -:1032300030BD082AE4D9102A03D81B88ADF808301D -:10324000E1E7202A8DBFD3E900231B680293CDE973 -:103250000223D8E710B5CB681BB98B600B618B825A -:1032600010BD04691A681C600361C38A013BC382F4 -:10327000CA60F0E703064CBFC0F3C03002207047BD -:1032800008B50246FFF7F6FF022806D15306C2F33F -:103290000F2001D100F0030008BDC2F30740FBE797 -:1032A0002DE9F04F93B0CDE903230A680446104698 -:1032B000FFF7E0FF022814BFC2F306260026002A0B -:1032C0000D46824680F2F28112F0C04940F0EE8154 -:1032D000097B002900F0EA81022803D02378B34259 -:1032E00040F0E781C2F304630693104602F07F03C7 -:1032F0000593FFF7C5FF059B29444FEA834848EA39 -:103300000A4848EA4668CE7800230022CDE908231F -:10331000F309834648EA0008029367D0059B0093AF -:1033200002466768534608A92046B847002800F0BF -:10333000C381276A4FB9414604F10C00FFF702FB35 -:10334000074690B96FF0020054E03B6998450DD0F4 -:103350003F68002FF9D1414604F10C00FFF7F2FA63 -:1033600007460028EED0236A3B60276297F817C013 -:1033700006F01F08CCF3840CACEB08001FFA80FEAB -:103380000028B8BF0EF12000A8EB0C031FFA83FE43 -:10339000D7E90221B8BF00B2002B0793BEBF0EF1E0 -:1033A00020031BB2079352EA010338D0039BDFF8D6 -:1033B00024E39A1A049B4FF0000C63EB010196453D -:1033C0007CEB01032BD36B7B97F81AE0734519D183 -:1033D000029B002B78D0012821DC7868F8B9DFF84F -:1033E000F0C2944570EB010316D337E0276A27B982 -:1033F0006FF00C0013B0BDE8F08F3B699845B5D075 -:103400003F68F4E7B24890427CEB010301D300200F -:10341000F0E7029B002BFAD0079B0F2B17DCFA7DFD -:10342000B30002F0030203F07C031343FB7539463B -:103430002046FFF707FB6B7BBB76029B3BB9FB7D0E -:10344000C3F38402013262F38603FB75D0E76A7B23 -:10345000BB7E9A42DBD1029B002B35D0B309022BF5 -:1034600032D0039BBB60049BFB60142200210DA89B -:10347000FDF7BAFF039B0A93049B0B932B1D0C9340 -:103480002B7BADF83EB0013BDBB2ADF83C30069B88 -:103490008DF84230059B8DF8433094F82C308DF830 -:1034A00040A083F001038DF844308DF84180A3687B -:1034B0000AA920469847FB7DC3F38403013303F038 -:1034C0001F039B02FB82A2E7FB7DC6F34012B2EB17 -:1034D000D31F40F0F480C3F38403434540F0F280EF -:1034E000029A2B7BB609002A4DD0F2075DD4032B3C -:1034F00040F2EB80039BBB60049BFB602B7BAE1D0B -:10350000033BDBB23246394604F10C00FFF7ACFA5C -:1035100000280CDA39462046FFF794FAFB7DC3F306 -:103520008403013303F01F039B02FB820AE7DDE9FA -:103530000884AB883B834FF6FF73C9F12000A9F1E3 -:10354000200228FA09F104FA00F0014324FA02F2F9 -:1035500011431846C9B2FFF7C9F909F10809B9F1D1 -:10356000400F0346E9D1B8822A7B033AD2B23146F2 -:10357000FFF7CEF9FB7DB882DA43C2F3C01262F3E3 -:10358000C713FB7543E786B92E1D013BDBB23246FC -:10359000394604F10C00FFF767FA0028BADB2A7BF2 -:1035A000B88A013AD2B23146E2E7F98AC1F3090199 -:1035B000013B0429DAB25BD8281D002307F11B0662 -:1035C0009A4208D910F801CB06F801C00131013345 -:1035D0000529DBB2F4D103990A9104990B91934226 -:1035E00007F11B010C9138BF043379680D9134BF8A -:1035F00055FA83F300230E93FB8AADF83EB0C3F374 -:1036000009031A44069B8DF84230059B8DF8433020 -:1036100094F82C30ADF83C2083F001038DF8443051 -:1036200000238DF840A08DF841807B602A7BB88A0A -:10363000013A291DFFF76CF93B8BB882834203D115 -:10364000A3680AA92046984720460AA9FFF702FE68 -:10365000FB7DBA8AC3F38403013303F01F039B028B -:10366000FB823B8B9A420CBF00206FF01000C1E63A -:103670007B68002BAFD0052001E01C3033461E686C -:10368000002EFAD1091A081D2E1D184401EB090C51 -:10369000BCF11B0F5FFA89F39DD89A429BD916F8AB -:1036A000013B00F8013B09F10109EFE76FF0090068 -:1036B000A0E66FF00A009DE66FF00B009AE66FF04F -:1036C0000D0097E66FF00E0094E66FF00F0091E6A4 -:1036D00040420F0080841E00EFF3098305494A6BC6 -:1036E00022F001024A63683383F30988002383F3DD -:1036F0001188704700EF00E0302080F3118862B637 -:103700000C4B0D4AD96821F4E0610904090C0A4305 -:10371000DA60D3F8FC20094942F08072C3F8FC203B -:103720000A6842F001020A602022DA7783F8220058 -:10373000704700BF00ED00E00003FA05001000E054 -:1037400010B5302383F311880E4B5B6813F40063CC -:1037500014D0F1EE103AEFF30984683C4FF0807317 -:10376000E361094BDB6B236684F3098800F090F872 -:1037700010B1064BA36110BD054BFBE783F3118825 -:10378000F9E700BF00ED00E000EF00E043060008AD -:103790004606000800F1604303F561430901C9B220 -:1037A00083F80013012200F01F039A4043099B0095 -:1037B00003F1604303F56143C3F880211A60704749 -:1037C00000230375826803691B6899689142FBD2E4 -:1037D0005A680360426010605860704700230375A8 -:1037E000826803691B6899689142FBD85A68036034 -:1037F000426010605860704708B50846302383F374 -:1038000011880B7D032B05D0042B0DD02BB983F32E -:10381000118808BD8B6900221A604FF0FF33836165 -:10382000FFF7CEFF0023F2E7D1E9003213605A60C0 -:10383000F3E70000FFF7C4BF054BD96808751868A7 -:1038400002681A60536001220275D860FCF7E4BE7A -:10385000204A002030B50C4BDD684B1C87B0044675 -:103860000FD02B46094A684600F06CF92046FFF756 -:10387000E3FF009B13B1684600F06EF9A86907B03A -:1038800030BDFFF7D9FFF9E7204A0020F9370008DB -:10389000044B1A68DB6890689B68984294BF0020CC -:1038A00001207047204A0020084B10B51C68D868DA -:1038B00022681A60536001222275DC60FFF78EFFD8 -:1038C00001462046BDE81040FCF7A6BE204A002075 -:1038D000044B1A68DB6892689B689A4201D9FFF72B -:1038E000E3BF7047204A002038B5074C0749084815 -:1038F000012300252370656000F03AFC0223237049 -:1039000085F3118838BD00BF884C0020484E000860 -:10391000204A002008B572B6044B186500F0ECFA96 -:1039200000F0A0FB024B03221A70FEE7204A0020A1 -:10393000884C002000F046B9EFF3118020B9EFF376 -:103940000583302282F311887047000010B530B92A -:10395000EFF30584C4F3080414B180F3118810BD9B -:10396000FFF7B6FF84F31188F9E700008B600223AC -:1039700008618B82084670478368A3F1840243F88C -:10398000142C026943F8442C426943F8402C094A3C -:1039900043F8242CC26843F8182C022203F80C2C9C -:1039A000002203F80B2C044A43F8102CA3F120004A -:1039B000704700BF31060008204A002008B5FFF715 -:1039C000DBFFBDE80840FFF735BF0000024BDB68B6 -:1039D00098610F20FFF730BF204A0020302383F387 -:1039E0001188FFF7F3BF000008B50146302383F3C9 -:1039F00011880820FFF72EFF002383F3118808BDEC -:103A0000064BDB6839B1426818605A601360436046 -:103A10000420FFF71FBF4FF0FF307047204A0020FF -:103A20000368984206D01A6802605060996118468F -:103A3000FFF700BF7047000010B503689C68A24202 -:103A40000CD85C688A600B604C6021605960996892 -:103A50008A1A9A604FF0FF33836010BD1B68121BF7 -:103A6000ECE700000A2938BF0A2170B504460D466C -:103A70000A26601900F076FB00F062FB041BA542E9 -:103A800003D8751C2E460446F3E70A2E04D9BDE878 -:103A90007040012000F0ACBB70BD0000F8B5144BC5 -:103AA0000D46D96103F1100141600A2A196982604B -:103AB00038BF0A22016048601861A818144600F057 -:103AC00043FB0A2700F03CFB431BA342064606D3F8 -:103AD0007C1C281900F046FB27463546F2E70A2FE2 -:103AE00004D9BDE8F840012000F082BBF8BD00BF5A -:103AF000204A0020F8B506460D4600F021FB0F4A8B -:103B0000134653F8107F9F4206D12A46014630469D -:103B1000BDE8F840FFF7C2BFD169BB68441A2C1951 -:103B200028BF2C46A34202D92946FFF79BFF224615 -:103B300031460348BDE8F840FFF77EBF204A002029 -:103B4000304A002010B4C0E9032300235DF8044B81 -:103B50004361FFF7CFBF000010B5194C23699842AD -:103B60000DD0D0E90032816813605A609A680A4427 -:103B70009A60002303604FF0FF33A36110BD23461A -:103B8000026843F8102F53600022026022699A42B3 -:103B900003D1BDE8104000F0DFBA936881680B44A0 -:103BA000936000F0CDFA2269E1699268441AA2425A -:103BB000E4D91144BDE81040091AFFF753BF00BF14 -:103BC000204A00202DE9F047DFF8BC8008F11007FB -:103BD0002C4ED8F8105000F0B3FAD8F81C40AA6860 -:103BE000031B9A423ED81444D5E900324FF0000935 -:103BF000C8F81C4013605A60C5F80090D8F810301F -:103C0000B34201D100F0A8FA89F31188D5E9033154 -:103C100028469847302383F311886B69002BD8D04E -:103C200000F08EFA6A69A0EB04094A4582460DD27B -:103C3000022000F0DDFA0022D8F81030B34208D19B -:103C400051462846BDE8F047FFF728BF121A224424 -:103C5000F2E712EB090938BF4A4629463846FFF712 -:103C6000EBFEB5E7D8F81030B34208D01444211A5F -:103C7000C8F81C00A960BDE8F047FFF7F3BEBDE837 -:103C8000F08700BF304A0020204A00200020704703 -:103C9000FEE70000704700004FF0FF307047000063 -:103CA000BFF34F8F024AD368DB03FCD4704700BFD9 -:103CB000003C024008B5094B1B7873B9FFF7F0FFD1 -:103CC000074B1A69002ABFBF064A5A6002F18832C0 -:103CD0005A601A6822F480621A6008BD904C002075 -:103CE000003C02402301674508B50B4B1B7893B994 -:103CF000FFF7D6FF094B1A6942F000421A611A68B1 -:103D000042F480521A601A6822F480521A601A68CB -:103D100042F480621A6008BD904C0020003C0240D2 -:103D20000728F0B516D80C4C0C4923787BB90C4DFC -:103D30000E4608234FF0006255F8047B46F8042B2A -:103D4000013B13F0FF033A44F6D10123237051F8ED -:103D50002000F0BD0020FCE7B44C0020944C002073 -:103D6000544E0008014B53F820007047544E000891 -:103D700008207047072810B5044601D9002010BD5F -:103D8000FFF7CEFF064B53F824301844C21A0BB984 -:103D90000120F4E712680132F0D1043BF6E700BFDE -:103DA000544E0008072810B5044621D8FFF778FFC5 -:103DB000FFF780FF0F4AF323D360C300DBB243F465 -:103DC000007343F002031361136943F480331361FA -:103DD000FFF766FFFFF7A4FF074B53F8241000F02E -:103DE0003DF9FFF781FF2046BDE81040FFF7C2BF55 -:103DF000002010BD003C0240544E0008F8B512F0FF -:103E00000103144642D185182E4A954257D82E4BAD -:103E10001B6813F0010352D02C4DFFF74BFFF32327 -:103E2000EB60FFF73DFF40F20127032C15D824F08B -:103E300001046618254C401A40F20117B14223696B -:103E400000EB010524D123F001032361FFF74CFFB0 -:103E50000120F8BD043C0430E7E78307E7D12B6974 -:103E600023F440732B612B693B432B6151F8046BA6 -:103E70000660BFF34F8FFFF713FF03689E42E9D040 -:103E80002B6923F001032B61FFF72EFF0020E0E7F1 -:103E900023F44073236123693B4323610B882B8008 -:103EA000BFF34F8FFFF7FCFE2D8831F8023BADB218 -:103EB000AB42C3D0236923F001032361E4E7184632 -:103EC000C7E700BF0000080800380240003C02407D -:103ED000084908B50B7828B11BB9FFF7EBFE0123A1 -:103EE0000B7008BD002BFCD0BDE808400870FFF740 -:103EF000FBBE00BF904C00204FF480214FF00050DB -:103F000000F0AEB80846114600F0AEBE012000F049 -:103F1000ABBE0000084600F0C5BE000070B582B020 -:103F2000FFF70AFD0E4E054600F00AF9326890428E -:103F300037BF0C4A0B49516814682EBFD1E90041C4 -:103F4000013151600419034641F1000128460191F5 -:103F50003360FFF7FBFC0199204602B070BD00BF43 -:103F6000B84C0020C04C002070B582B0FFF7E4FCD4 -:103F7000104E054600F0E4F83268904237BF0E4A12 -:103F80000D49516814682EBFD1E9004101315160DB -:103F9000041941F100010346284601913360FFF7FF -:103FA000D5FC01994FF47A7200232046FCF720F9E2 -:103FB00002B070BDB84C0020C04C002010B50244C7 -:103FC000064BD2B2904200D110BD441C00B253F84F -:103FD000200041F8040BE0B2F4E700BF5028004095 -:103FE0000F4B30B51C6F240407D41C6F44F40074CD -:103FF0001C671C6F44F400441C670A4C236843F49C -:10400000807323600244084BD2B2904200D130BD8D -:10401000441C00B251F8045B43F82050E0B2F4E7CE -:1040200000380240007000405028004007B50122CF -:1040300001A90020FFF7C2FF019803B05DF804FB5F -:1040400013B50446FFF7F2FFA04205D0012201A9F3 -:1040500000200194FFF7C4FF02B010BD70470000BC -:104060007047000070470000074B45F255521A6038 -:1040700002225A6040F6FF729A604CF6CC421A60F7 -:10408000024B01221A70704700300040CC4C0020D7 -:10409000034B1B781BB1034B4AF6AA221A607047E8 -:1040A000CC4C002000300040034B1A681AB9034A78 -:1040B000D2F874281A607047C84C002000300240C3 -:1040C000024B4FF08072C3F87428704700300240F2 -:1040D00008B5FFF7E9FF024B1868C0F3407008BD50 -:1040E000C84C002008B5FFF7DFFF024B1868C0F38B -:1040F000007008BDC84C002070470000FEE70000BB -:104100000A4B0B480B4A90420BD30B4BDA1C121A8A -:10411000C11E22F003028B4238BF00220021FDF7AE -:1041200063B953F8041B40F8041BECE71050000877 -:10413000C44F0020C44F0020C44F002000F0CAB874 -:104140004FF08043586A70474FF080430022586315 -:104150001A610222DA6070474FF080430022DA6071 -:10416000704700004FF0804358637047FEE700003F -:1041700070B51B4B01630025044686B0586085620C -:104180000E46FFF7B9FA04F11003C4E904334FF007 -:10419000FF33C4E90635C4E90044A560E562FFF7D2 -:1041A000CFFF2B460246C4E9082304F134010D4A2F -:1041B000256580232046FFF7D9FB0123E0600A4AEA -:1041C0000375009272680192B268CDE90223074B31 -:1041D0006846CDE90435FFF7F1FB06B070BD00BFBE -:1041E000884C0020744E0008794E00086D4100088C -:1041F000024AD36A1843D062704700BF204A0020A9 -:104200004B6843608B688360CB68C3600B69436114 -:104210004B6903628B6943620B680360704700005F -:1042200008B5234B23481A6942F0FF021A611A6944 -:1042300022F0FF021A611A691A6B42F0FF021A6338 -:104240001A6D42F0FF021A651B4A1B6D1146FFF7FB -:10425000D7FF02F11C0100F58060FFF7D1FF02F1EA -:10426000380100F58060FFF7CBFF02F1540100F543 -:104270008060FFF7C5FF02F1700100F58060FFF775 -:10428000BFFF02F18C0100F58060FFF7B9FF02F17A -:10429000A80100F58060FFF7B3FF02F1C40100F54B -:1042A0008060FFF7ADFFBDE8084000F08DB800BFAB -:1042B0000038024000000240804E000808B500F0BF -:1042C00019FAFFF711FBBDE80840FFF7EDBE00004B -:1042D000704700000F4B1A6C42F001021A641A6E0C -:1042E00042F001021A660C4A1B6E936843F0010308 -:1042F00093604FF0804331229A624FF0FF32DA62CE -:1043000000229A615A63DA605A6001225A611A6087 -:10431000704700BF00380240002004E04FF08042A8 -:1043200008B51169D3680B40D9B2C9439B07116125 -:1043300007D5302383F31188FFF7FCFA002383F3BA -:10434000118808BD1E4B1A6962F0FF021A611A69D2 -:10435000D2B21A614FF0FF301A695A6958610021D0 -:104360005A6959615A691A6A62F080521A621A6A65 -:1043700002F080521A621A6A5A6A58625A6A59627C -:104380005A6A1A6C42F080521A641A6E42F08052D5 -:104390001A661A6E0B4A106840F480701060186F2D -:1043A00000F44070B0F5007F1EBF4FF480301867F6 -:1043B0001967536823F40073536000F073B900BFAA -:1043C00000380240007000403B4B3C4A1A643C4AB3 -:1043D0004FF4404111601A6842F001021A601A68F5 -:1043E0009007FCD59A6822F003029A60324B9A68D3 -:1043F00012F00C02FBD1196801F0F90119609A6002 -:104400001A6842F480321A601A689103FCD55A6F18 -:1044100042F001025A67284B5A6F9207FCD5294A8D -:104420005A601A6842F080721A60254A536858042C -:10443000FCD5214B1A689101FCD5234AC3F884208E -:104440001A6842F080621A601A681201FCD51F4A8D -:104450009A600322C3F88C204FF00062C3F89420C6 -:104460001B4B1A681B4B9A421B4B21D11B4A1168EC -:104470001B4A91421CD140F203121A60164A13687B -:1044800003F00F03032BFAD10B4B9A6842F00202A0 -:104490009A609A6802F00C02082AFAD15A6C42F427 -:1044A00080425A645A6E42F480425A665B6E70478C -:1044B00040F20372E1E700BF003802400004001040 -:1044C000007000400419400208300024009488382D -:1044D000002004E011640020003C024000ED00E0F8 -:1044E00041C20F41074A08B5536903F00103536104 -:1044F00023B1054A13680BB150689847BDE80840DE -:10450000FFF71EB9003C0140D04C0020074A08B517 -:10451000536903F00203536123B1054A93680BB159 -:10452000D0689847BDE80840FFF70AB9003C014051 -:10453000D04C0020074A08B5536903F004035361C7 -:1045400023B1054A13690BB150699847BDE808408B -:10455000FFF7F6B8003C0140D04C0020074A08B5F0 -:10456000536903F00803536123B1054A93690BB102 -:10457000D0699847BDE80840FFF7E2B8003C014029 -:10458000D04C0020074A08B5536903F0100353616B -:1045900023B1054A136A0BB1506A9847BDE8084039 -:1045A000FFF7CEB8003C0140D04C0020164B10B5B0 -:1045B0005C6904F478725A61A30604D5134A936ABD -:1045C0000BB1D06A9847600604D5104A136B0BB143 -:1045D000506B9847210604D50C4A936B0BB1D06BF6 -:1045E0009847E20504D5094A136C0BB1506C984703 -:1045F000A30504D5054A936C0BB1D06C9847BDE870 -:104600001040FFF79DB800BF003C0140D04C002097 -:10461000194B10B55C6904F47C425A61620504D5FB -:10462000164A136D0BB1506D9847230504D5134AF4 -:10463000936D0BB1D06D9847E00404D50F4A136E0B -:104640000BB1506E9847A10404D50C4A936E0BB180 -:10465000D06E9847620404D5084A136F0BB1506FAF -:104660009847230404D5054A936F0BB1D06F984740 -:10467000BDE81040FFF764B8003C0140D04C00207A -:1046800008B5034800F0E8F8BDE80840FFF758B85F -:10469000504D002008B5FFF741FEBDE80840FFF788 -:1046A0004FB80000062108B50846FFF773F8062149 -:1046B0000720FFF76FF806210820FFF76BF80621A7 -:1046C0000920FFF767F806210A20FFF763F80621A3 -:1046D0001720FFF75FF806212820FFF75BF8072176 -:1046E0001C20FFF757F8BDE808400C212620FFF7F3 -:1046F00051B8000008B5FFF725FE00F07BF800F088 -:104700003DF8FFF7E5FDBDE80840FFF717BD0000E5 -:10471000026843681143016003B118477047000005 -:10472000143000F0C5B900004FF0FF33143000F032 -:10473000BFB90000383000F03BBA00004FF0FF3343 -:10474000383000F035BA0000143000F08BB90000AA -:104750004FF0FF31143000F085B90000383000F020 -:10476000E5B900004FF0FF32383000F0DFB900004B -:10477000012914BF6FF013000020704700F058B8F3 -:1047800037B515460E4A026000224260C0E9022297 -:104790000122044602740B46009000F15C014FF4C4 -:1047A0008072143000F034F900942B464FF480727C -:1047B00004F5AE7104F1380000F0ACF903B030BD7F -:1047C000604F000838B5C36904460D461BB9042183 -:1047D0000844FFF79DFF294604F1140000F026F974 -:1047E000002806DA201D4FF40061BDE83840FFF7CD -:1047F0008FBF38BD0023054A19460133102BC2E98B -:10480000001102F10802F8D1704700BFD04C00201F -:10481000026843681143016003B118477047000004 -:10482000024AD36843F0C003D3607047004400409D -:1048300010B5054C054A00212046FFF7A1FF044AA8 -:10484000044BC4E9972310BD504D002021480008B7 -:104850000044004040787D012DE9F041D0F85C62D1 -:10486000F7683368DA0504469DB20DD5302383F32B -:1048700011884FF480610430FFF7CAFF6FF4807332 -:104880003360002383F31188302383F3118804F10C -:10489000040815F02F033AD183F31188380615D593 -:1048A000290613D5302383F3118804F1380000F072 -:1048B00065F900284EDA0821201DFFF7A9FF4FF601 -:1048C0007F733B40F360002383F311887A0616D58B -:1048D0006B0614D5302383F31188D4E913239A424D -:1048E0000AD1236C43B127F040073F041021201D5B -:1048F0003F0CFFF78DFFF760002383F31188D4F896 -:104900006822D36843B3BDE8F041106918472B070C -:1049100014D015F0080F0CBF00214FF48071E80788 -:1049200048BF41F02001AA0748BF41F040016B0792 -:1049300048BF41F080014046FFF76AFFAD0673684B -:1049400005D594F8641220461940FFF73BFF3568FF -:10495000ADB29EE77060B6E7BDE8F081F8B51546E8 -:1049600082680669AA420B46816938BF8568761A53 -:10497000B54204460BD218462A46FCF723FDA3692C -:104980002B44A361A3685B1BA3602846F8BD0CD928 -:1049900018463246FCF716FDAF1BE1683A46304434 -:1049A000FCF710FDE3683B44EBE718462A46FCF7AA -:1049B00009FDE368E5E7000083689342F7B5154613 -:1049C000044638BF8568D0E90460361AB5420BD278 -:1049D0002A46FCF7F7FC63692B446361A368284609 -:1049E0005B1BA36003B0F0BD0DD932460191FCF70B -:1049F000E9FC0199E068AF1B3A463144FCF7E2FC60 -:104A0000E3683B44E9E72A46FCF7DCFCE368E4E7BB -:104A100010B50A440024C361029B8460C0E9000011 -:104A2000C0E90511C1600261036210BD08B5D0E99B -:104A30000532934201D1826882B982680132826074 -:104A40005A1C42611970D0E904329A4224BFC368EB -:104A500043610021FEF7E4FF002008BD4FF0FF3066 -:104A6000FBE7000070B5302304460E4683F311883F -:104A7000A568A5B1A368A269013BA360531CA3610B -:104A800015782269934224BFE368A361E3690BB1FF -:104A900020469847002383F31188284607E03146D3 -:104AA0002046FEF7ADFF0028E2DA85F3118870BDDD -:104AB0002DE9F74F04460E4617469846D0F81C904D -:104AC0004FF0300A8AF311884FF0000B154665B19C -:104AD0002A4631462046FFF741FF034660B941466A -:104AE0002046FEF78DFF0028F1D0002383F31188C4 -:104AF000781B03B0BDE8F08FB9F1000F03D001902F -:104B00002046C847019B8BF31188ED1A1E448AF397 -:104B10001188DCE7C0E90511C160C3611144009B45 -:104B20008260C0E90000016103627047F8B5044685 -:104B30000D461646302383F31188A768A7B1A368F2 -:104B4000013BA36063695A1C62611D70D4E90432A1 -:104B50009A4224BFE3686361E3690BB1204698473A -:104B6000002080F3118807E031462046FEF748FF19 -:104B70000028E2DA87F31188F8BD0000D0E90523A8 -:104B80009A4210B501D182687AB982680132826096 -:104B90005A1C82611C7803699A4224BFC3688361EE -:104BA0000021FEF73DFF204610BD4FF0FF30FBE730 -:104BB0002DE9F74F04460E4617469846D0F81C904C -:104BC0004FF0300A8AF311884FF0000B154665B19B -:104BD0002A4631462046FFF7EFFE034660B94146BC -:104BE0002046FEF70DFF0028F1D0002383F3118843 -:104BF000781B03B0BDE8F08FB9F1000F03D001902E -:104C00002046C847019B8BF31188ED1A1E448AF396 -:104C10001188DCE70B460146184600F02DB800006D -:104C200000F040B8012838BF012010B504462046E6 -:104C300000F030F830B900F007F808B900F00CF8CF -:104C40008047F4E710BD0000024B1868BFF35B8F8C -:104C5000704700BFBC4F002008B5062000F084F864 -:104C60000120FFF715F80000024B0A4601461868BC -:104C7000FFF748B91C23002010B5054C13462CB192 -:104C80000A4601460220AFF3008010BD2046FCE733 -:104C900000000000024B01461868FFF737B900BF5B -:104CA0001C230020024B01461868FFF733B900BFF0 -:104CB0001C23002010B501390244904201D100208C -:104CC00005E0037811F8014FA34201D0181B10BD75 -:104CD0000130F2E72DE9F041A3B1C91A1778014478 -:104CE000044603F1FF3C8C42204601D9002009E034 -:104CF0000578BD4204F10104F5D10CEB0405D6188A -:104D0000A54201D1BDE8F08115F8018D16F801ED3D -:104D1000F045F5D0E7E700001F2938B504460D46F9 -:104D200004D9162303604FF0FF3038BD426C12B136 -:104D300052F821304BB9204600F030F82A4601469F -:104D40002046BDE8384000F017B8012B0AD0591CA6 -:104D500003D1162303600120E7E7002442F8254031 -:104D6000284698470020E0E7024B01461868FFF705 -:104D7000D3BF00BF1C23002038B5074D00230446D5 -:104D8000084611462B60FEF787FF431C02D12B68B3 -:104D900003B1236038BD00BFC04F0020FEF776BFCF -:104DA000034611F8012B03F8012B002AF9D17047B3 -:104DB0006F72672E6172647570696C6F742E4152E8 -:104DC0004B5F47505300000040A2E4F16468910635 -:104DD0000041A3E5F265699207000000426164208A -:104DE00043414E496661636520696E6465782E00B3 -:104DF0008000000000800000000080000000000033 -:104E000000000000491C000831240008912300081C -:104E1000591C00088D1C0008891E00085D1C000834 -:104E20006D1C0008611C0008691C0008651C000856 -:104E3000B11D0008711C0008FD260008811C000837 -:104E4000851D000863300000444E0008784A0020A9 -:104E5000884C00200040000000400000004000009E -:104E600000400000000001000000020000000200FD -:104E7000000002006D61696E0069646C65000000ED -:104E8000A000902A00000000AAAAAAAA50000024AC -:104E9000FFFB000000770000009009000100000502 -:104EA00000000000AAAAAAA501000080FFCF000010 -:104EB00000000000000000000000000000000000F2 -:104EC000AAAAAAAA00000000FFFF0000000000003C -:104ED000000000000000000000000000AAAAAAAA2A -:104EE00000000000FFFF00000000000000000000C4 -:104EF0000000000000000000AAAAAAAA000000000A -:104F0000FFFF0000000000000000000000000000A3 -:104F100000000000AAAAAAAA00000000FFFF0000EB -:104F20000000000000000000000000000000000081 -:104F3000AAAAAAAA00000000FFFF000000000000CB -:104F40000000000000000000000000000A00000057 -:104F5000000000000300000000000000000000004E -:104F6000000000003D470008294700086547000889 -:104F7000514700085D4700084947000835470008C9 -:104F8000214700087147000898B2FF7F0100000028 -:104F900051000000000000000000070000000000B9 -:104FA00040420F00FE2A0100D2040000202300200E -:104FB00000000000000000000000000000000000F1 -:104FC00000000000000000000000000000000000E1 -:104FD00000000000000000000000000000000000D1 -:104FE00000000000000000000000000000000000C1 -:104FF00000000000000000000000000000000000B1 -:1050000000000000000000000000000000000000A0 +:1000000000070020F1010008FD230008B5230008C7 +:10001000DD230008B5230008D5230008F3010008FC +:10002000F3010008F3010008F3010008F1330008B0 +:10003000F3010008F3010008F3010008F3010008D0 +:10004000F3010008F3010008F3010008F3010008C0 +:10005000F3010008F3010008C1410008E94100086C +:10006000114200083942000861420008F30100080B +:10007000F3010008F3010008F3010008F301000890 +:10008000F3010008F3010008F301000869230008E8 +:1000900095230008A5230008F30100088942000801 +:1000A000F3010008F3010008F3010008F301000860 +:1000B00071430008F3010008F3010008F301000890 +:1000C000F3010008F3010008F3010008F301000840 +:1000D000F3010008F30100085D430008F301000884 +:1000E000ED420008F3010008F3010008F3010008E5 +:1000F000F3010008F3010008F3010008F301000810 +:10010000F3010008F3010008F3010008F3010008FF +:10011000F3010008F3010008F3010008F3010008EF +:10012000F3010008F3010008F3010008F3010008DF +:10013000F3010008F3010008F3010008F3010008CF +:10014000F3010008F3010008F3010008F3010008BF +:10015000F3010008F3010008F3010008F3010008AF +:10016000F3010008F3010008F3010008F30100089F +:10017000F3010008F3010008F3010008F30100088F +:10018000F3010008F3010008F3010008F30100087F +:10019000F3010008F3010008F3010008F30100086F +:1001A000F3010008F3010008F3010008F30100085F +:1001B000F3010008F3010008F3010008F30100084F +:1001C000F3010008F3010008F3010008F30100083F +:1001D000F3010008F3010008F3010008F30100082F +:1001E000C50F000800000000000000000000000033 +:1001F00002E000F000F8FEE772B6374880F30888A6 +:10020000364880F3098836483649086040F20000D5 +:10021000CCF200004EF63471CEF200010860BFF35C +:100220004F8FBFF36F8F40F20000C0F2F0004EF628 +:100230008851CEF200010860BFF34F8FBFF36F8F7C +:100240004FF00000E1EE100A4EF63C71CEF20001D4 +:100250000860062080F31488BFF36F8F03F0BAFDA7 +:1002600003F04CFE4FF055301F491B4A91423CBFF2 +:1002700041F8040BFAE71D49184A91423CBF41F886 +:10028000040BFAE71A491B4A1B4B9A423EBF51F82E +:10029000040B42F8040BF8E700201849184A914271 +:1002A0003CBF41F8040BFAE703F098FD03F074FE3D +:1002B000144C154DAC4203DA54F8041B8847F9E797 +:1002C00000F042F8114C124DAC4203DA54F8041B12 +:1002D0008847F9E703F080BD0007002000230020D5 +:1002E0000000000808ED00E00001002000070020E9 +:1002F000684C000800230020802300208023002079 +:10030000BC4F0020E0010008E4010008E4010008FF +:10031000E40100082DE9F04F2DED108AC1F80CD052 +:10032000C3689D46BDEC108ABDE8F08F002383F3BF +:1003300011882846A047002003F0B6F9FEE703F035 +:100340003FF900DFFEE70000F8B500F04DFE03F0D6 +:10035000DBFC074603F02AFD064600283DD12B4B67 +:100360009F423AD001339F423AD0294B27F0FF02F7 +:100370009A4238D1F8B200F043FC354642F210748C +:1003800000F044FC08B10024254601F019F970B3CF +:10039000032000F043F80024254636B11D4B9F4250 +:1003A00003D003F0FBFC00242546002003F0B6FC3C +:1003B000194B1B691B041FD40DB100F045F800F068 +:1003C00091FC02F023F80546C4B102F01FF8401B6F +:1003D000A04213D900F038F8F3E735460024CFE700 +:1003E00004460125CCE705464FF47A74C8E7B4F516 +:1003F0007A7F08BF0125D0E70024E0E700F0BAFCCF +:100400004FF47A7003F056F9DEE700BF010007B041 +:10041000000008B0263A09B000040240084B1870EA +:1004200003280CD8DFE800F008050208022000F0DD +:1004300039BE022000F02CBE024B00225A607047E9 +:10044000802300208423002010B501F0B9F830B1DA +:10045000204B03221A70204B00225A6010BD1F4B04 +:100460001F4A1C4619680131F8D004339342F9D170 +:1004700062681C4B9A42F1D91B4B9B6803F10063E5 +:1004800003F580339A42E9D203F05CFC03F06EFC82 +:10049000002000F0C3FD0220FFF7C0FF134B1A6CD1 +:1004A00000221A64196E1A66196E596C5A64596ED4 +:1004B0005A665B6E72B64FF0E0233021C3F8084DE8 +:1004C000D4E9003281F311889D4683F308881047F0 +:1004D000C4E700BF8023002084230020000001081F +:1004E00020000108FFFF0008002300200038024020 +:1004F000094A136849F2690099B21B0C00FB0133E9 +:100500001360064B186844F2506182B2000C01FB84 +:100510000200186080B270471823002014230020C6 +:1005200010B500211022044600F0D8FD034B03CB88 +:10053000206061601868A06010BD00BF107AFF1FC6 +:100540002DE9F041ADF54E7D0DF134086CAC40F273 +:10055000751207460D460EA80021C8F8001000F0DD +:10056000BDFD4FF4C4720021204600F0B7FD01F03C +:100570004DFF274B4FF47A72B0FBF2F0186093E80E +:100580000700022384E807000DF5E9702382FFF7D6 +:10059000C7FF4FF4A2431F49238407A804F06EFA53 +:1005A000152384F832310DF2E32207AB0DF12C0C48 +:1005B0001E4603CE664510605160334602F10802C4 +:1005C000F6D130681060337913714146012220461C +:1005D00000F0D0FD00230393AB7E029305F11903D5 +:1005E000019380B20123CDE904800093E97E06A344 +:1005F000D3E90023384602F0D1FA0DF54E7DBDE86F +:10060000F08100BFAFF300809E6AC421818A46EE6C +:100610008C2300208C4A00082DE9F0412C4C237AD1 +:10062000DAB080460D465BBB27A9284600F0B2FE33 +:100630000746002842D19DF89D60C82E3ED801464D +:100640004FF4A662204600F049FD4FF48073C4F8D1 +:10065000F8314FF40073C4F80C334FF44073C4F80E +:10066000203432460DF19E0104F1090000F024FD12 +:1006700026449DF89C30777223720BB9EB7E23726F +:100680008122002106AC27A800F028FD0122214686 +:1006900027A800F0BBFE00230393AB7E029305F175 +:1006A000190380B201932823CDE904400093E97E29 +:1006B00005A3D3E90023404602F070FA5AB0BDE822 +:1006C000F08100BFAFF3008026417272DF25D7B7FB +:1006D000B0440020F0B5254E4FF48A7505FB006547 +:1006E000F1B096F8D83085F8DC300024D8222146C5 +:1006F00085F8E8403AA800F0F1FC06F1090000F0A6 +:10070000E5FCD5F8E4308DF8F000C2B206AF06F192 +:1007100009010DF1F100CDE93A3400F0CDFC394684 +:1007200001223AA800F09EFE80B2CDE904700823B1 +:100730000127CDE9023706F1D80301933023009356 +:10074000317A0B4807A3D3E9002302F027FAA0422D +:1007500006DD01F05BFEC5F8E000384671B0F0BD83 +:100760002046FBE778F6339F93CACD8DB044002036 +:10077000A43300202DE9F0411D4D1E4E1E4F86B0C2 +:10078000284602F037FA034658B30024CDE9034463 +:10079000ADF81440027B8DF81420996840680294EB +:1007A00003AA03C21B68DFF8548043F0004302939E +:1007B00001F02EFE821941F10003009402A938468F +:1007C00001F0D6F8A04205DD284602F017FA88F8B5 +:1007D0000040D5E798F80030072B05D8013388F89A +:1007E000003006B0BDE8F081014802F007FAF8E7F2 +:1007F000A433002040420F00D8330020E5490020F8 +:1008000070B50D4614461E4602F024F950B9022E6A +:1008100010D1012C0ED112A3D3E90023C5E9002386 +:10082000012007E0282C10D005D8012C09D0052C78 +:100830000FD0002070BD302CFBD10BA3D3E90023D7 +:10084000ECE70BA3D3E90023E8E70BA3D3E90023EC +:10085000E4E70BA3D3E90023E0E700BFAFF3008098 +:10086000401DA12026812A0B78F6339F93CACD8D97 +:100870009E6AC421818A46EE26417272DF25D7B76F +:10088000F017304A39059E5638B505460E4C002102 +:10089000013500F0E5FBA4F82C55B4F82C0500F068 +:1008A000C7FB78B1B4F82C0500F0D2FB014648B97B +:1008B000B4F82C0500F0D4FBB4F82C350133A4F8BF +:1008C0002C35EAE738BD00BFB044002010B50A4B14 +:1008D0000A4A1A6003F5805393F860203AB9DC6D38 +:1008E0002CB1204600F0E4FE204604F007F8BDE8F5 +:1008F0001040034800F0DCBED8330020E04A000876 +:10090000204400202DE9F04F8FB000AF05460C4683 +:1009100002F0A0F8002849D1237E022B1BD1E38AE4 +:10092000012B18D101F072FD0646FFF7E1FD0346E9 +:100930004FF4C870DFF8C482B3FBF0F206F5167608 +:1009400002FB103316FA83F3C8F80030E37E33B9A4 +:10095000A34B00221A703C37BD46BDE8F08F07F16B +:100960002401204600F0D4FC0028F4D107F1140043 +:10097000FFF7D6FD97F8264007F11401224607F14C +:10098000270004F005F80028E2D10F2C08D8944B7A +:100990001C70D8F80030A3F51673C8F80030DAE7F9 +:1009A00097F82410284602F04DF8D4E7E38A282B64 +:1009B0002BD010D8012B23D0052BCCD1BFF34F8FD8 +:1009C0008849894BCA6802F4E0621343CB60BFF3E5 +:1009D0004F8F00BFFDE7302BBDD1844EE17E327AD0 +:1009E0009142B8D1607E3146002291F8DC508542B8 +:1009F00000F0A5800132042A01F58A71F5D1AAE739 +:100A000021462846FFF79CFDA5E721462846FFF72B +:100A100003FEA0E7B2F8EC507B6005F103094FEA52 +:100A200099094FEA8902D11DC908A8EBC1039D4667 +:100A3000EB460021584600F051FB04F1EE012A4636 +:100A40003144584600F038FB7B6813B9012000F0B0 +:100A5000E5FA96F8D20000F0EBFA044630B93072AD +:100A600000F006FB204600F0D9FAB1E0D6F8D42019 +:100A70003AB996F8D200B6F82C25824201D8FFF791 +:100A800003FFD6F8D4202A44944208D296F8D20024 +:100A9000B6F82C250130824201D8FFF7F5FE7068C8 +:100AA0005FFA89F2594600F021FB08B9C54679E0A2 +:100AB000726896F8D2002A447260D6F8D42005EB0A +:100AC0000209C6F8D49000F0B3FA814509D396F82C +:100AD000D220D6F8D4000132001B86F8D220C6F806 +:100AE000D400FF2D0FD80024347200F0C1FA204644 +:100AF00000F094FA00F064FD3D4B188108B9FFF74F +:100B0000A3FCC54627E7BB6896F8D9000AFB036239 +:100B1000FB68D2F8E41082F8E83001F58061C2F891 +:100B2000E030C2F8E410FFF7D5FDFFF723FE96F89A +:100B3000D920013202F0030286F8D920B6E74FF43B +:100B40008A7A0AFB02F505F1EA013144204600F0F9 +:100B5000B5FCF86000287FF4FEAE3544012285F82C +:100B6000E82001F053FCD5F8E020D6ED007ADFED67 +:100B7000216A801A192838BF192040F6B8329042ED +:100B800028BF1046B8EE677A07EE900AF8EEE77ACB +:100B900067EEA67ADFED186AE7EE267AFCEEE77AD2 +:100BA000C6ED007A96F8D930BB60BA6873680AFB64 +:100BB00002F4321992F8E81059B1D2F8E4108B42DD +:100BC000E8463FF427AF002182F8E810C2F8E010B1 +:100BD000C5467368064A9B0A01331381BBE600BF12 +:100BE0009D33002000ED00E00400FA05B044002031 +:100BF0008C230020CDCCCC3D6666663FA033002020 +:100C0000014B1870704700BF9823002030B54FF09B +:100C100000542B4B22689A4285B007D003F0D0F8DD +:100C2000044620BB0024204605B030BD254B627D24 +:100C300025481A70237D03724FF48073C0F8F83191 +:100C40004FF40073C0F80C3300254FF44073C0F824 +:100C500020341E49C0F8E450C922093000F02CFAB3 +:100C60002046E022294600F039FA0124DBE7184A41 +:100C7000184D136C43F000731364AA6D164B9A421F +:100C8000D0D12B6E013B7E2BCCD8144A07CA01ABC6 +:100C900083E807001846032100F060FC6B6D834277 +:100CA0004FF00003BED12A6D8A4201BFAB65054BF0 +:100CB0002A6E1A7003BF0A4BEA6D1A601C46B2E72F +:100CC0009AAD44C598230020B044002016000020AF +:100CD00000380240006600405041A0B05866004015 +:100CE0001023002037B51A4D00F06AFC02236B7107 +:100CF000184B288119681848012201F023FA0023B3 +:100D00000193164B164900931648174B4FF4805227 +:100D100001F070FE154B197811B1124801F092FEE6 +:100D200001F074FB0446FFF7E3FB4FF4C873B0FB1C +:100D3000F3F202FB130304F5167010FA83F00C4B68 +:100D4000186003F033F808B10F232B8103B030BDD6 +:100D50008C23002010230020D83300200108000835 +:100D60009C230020A43300200509000898230020BC +:100D7000A03300202DE9F04F2DED028B0FF2382922 +:100D8000D9E90089834C93B00BAE9FED7E8BFFF7C2 +:100D9000F1FC814FDFF828A200230A93ADF834302C +:100DA0000B9373604FF0000B5B468DED008B0125BC +:100DB0000DF11D0207A938468DF81C508DF81DB0A5 +:100DC00001F06EF99DF81C30002B40F0A580204604 +:100DD00001F040FE0646002845D1704F01F016FB99 +:100DE0003B6898423FD301F011FB8246FFF780FB3E +:100DF0004FF4C873B0FBF3F202FB13030AF516704D +:100E000010FA83F03860664F97F800B0CBF1100A03 +:100E1000BBF1000F14BF33462B465FFA8AFA0EA8C7 +:100E20008DF82830FFF77CFBBAF1060F28BF4FF092 +:100E3000060A0EAB03EB0B0152460DF1290000F040 +:100E40003BF90AAB0393182302930AF10102554BB5 +:100E5000D2B2CDE90053049220464CA3D3E900233B +:100E600001F03EFE3E7001F0D1FA4F4A4F4D13683B +:100E7000C31AB3F57A7F2ED3106001F0C9FA024687 +:100E80000B46204601F0C4FE204601F0E3FD10B3FE +:100E90002B7A474E002B14BF03230223737101F0FA +:100EA000B5FA0EAF4FF47A730122B0FBF3F0394676 +:100EB0003060304600F004FA182302933D4B019352 +:100EC00080B240F25513CDE90370009342464B4681 +:100ED000204601F005FE2B7A93B101F097FA002627 +:100EE00007464FF48A7A95F8D900304400F00300A1 +:100EF0000AFB005393F8E82092B30136042EF2D196 +:100F0000C82002F0D7FB2B7A002B7FF43DAF13B043 +:100F1000BDEC028BBDE8F08FDAF8143083F4806307 +:100F2000CAF81430594610220EA800F0D7F80DF177 +:100F30001E0308AA0AA9384600F01AFE96E8030024 +:100F40000FAB83E803009DF834308DF844300A9BE2 +:100F50000E930EA9DDE90823204602F02DF821E7C3 +:100F6000D3F8E02042B12B68FA2B38BFFA23BA1A23 +:100F70000533B2EB430FC0D3FFF7ACFB0028BCD165 +:100F8000BEE700BF0000000000000000401DA120DF +:100F900026812A0BA4330020D8330020A033002060 +:100FA0009D3300209C330020E0490020B044002005 +:100FB0008C230020E4490020F1C6A7C1D068080FA7 +:100FC0000000024008B5054800F06EFEBDE808408C +:100FD000034A0449002003F08BBC00BFD833002033 +:100FE000204A0020CD08000870B502F037FD094EF8 +:100FF000094D3080002428683388834208D902F0E4 +:1010000027FD2B6804440133B4F5803F2B60F2D3F5 +:1010100070BD00BF144A0020E849002002F0CEBD98 +:1010200000F10060920000F5803002F05DBD00002C +:10103000054B1A68054B1B889B1A834202D9104442 +:1010400002F006BD00207047E8490020144A002045 +:10105000024B1B68184402F003BD00BFE8490020A2 +:10106000024B1B68184402F013BD00BFE849002082 +:10107000064991F8243033B10023086A81F82430FE +:101080000822FFF7CDBF0120704700BFEC490020C8 +:10109000022802BF024B4FF080629A61704700BF86 +:1010A00000000240022802BF024B4FF480629A61A6 +:1010B000704700BF0000024010B50023934203D0E8 +:1010C000CC5CC4540133F9E710BD0000034602466E +:1010D000D01A12F9011B0029FAD1704702440346C5 +:1010E000934202D003F8011BFAE770472DE9F84359 +:1010F0001F4D144695F824200746884652BBDFF85A +:1011000070909CB395F824302BB92022FF214846DB +:101110002F62FFF7E3FF95F82400C0F10802A24216 +:1011200028BF2246D6B24146920005EB8000FFF769 +:10113000C3FF95F82430A41B1E44F6B2082E1744B2 +:101140009044E4B285F82460DBD1FFF791FF0028DA +:10115000D7D108E02B6A03EB82038342CFD0FFF79D +:1011600087FF0028CBD10020BDE8F8830120FBE7F2 +:10117000EC4900202DE9F0470D4604460021904639 +:10118000284640F27912FFF7A9FF234620220021CA +:10119000284601F0B3FE231D02222021284601F03B +:1011A000ADFE631D03222221284601F0A7FEA31DE8 +:1011B00003222521284601F0A1FE04F10803102294 +:1011C0002821284601F09AFE04F110030822382154 +:1011D000284601F093FE04F111030822402128461D +:1011E00001F08CFE04F1120308224821284601F088 +:1011F00085FE04F1140320225021284601F07EFED2 +:1012000004F1180340227021284601F077FE04F112 +:1012100020030822B021284601F070FE04F12103CA +:101220000822B821284601F069FE04F12207C026F1 +:101230003B46314608222846083601F05FFEB6F5E7 +:10124000A07F07F10107F3D104F1320308223146F0 +:10125000284601F053FE002704F1330A94F8323097 +:101260004FEAC7099F4209F5A47615D3B8F1000FDC +:1012700008D1314604F599730722284601F03EFE55 +:1012800009F24F16274694F832213B1B93420CD3A8 +:10129000F01DC008BDE8F0870AEB070308223146BD +:1012A000284601F02BFE0137D8E707F23313314609 +:1012B0000822284601F022FE08360137E3E7000045 +:1012C00013B504460846002101602346C0F8031008 +:1012D0002022019001F012FE0198231D02222021FC +:1012E00001F00CFE0198631D0322222101F006FE8D +:1012F0000198A31D0322252101F000FE019804F1AD +:1013000008031022282101F0F9FD072002B010BDCA +:10131000F7B50023047F00910E46072219460546C3 +:1013200001F0B0FC731C0093012200230721284622 +:1013300001F0A8FCC4B9B31C009305222346082180 +:10134000284601F09FFC0D243746B278BB1B934220 +:1013500011D32B7FA88A0734E408BBB9844294BF19 +:101360000020012003B0F0BDAB8ADB00083BDB08A6 +:10137000B3700824E8E7FB1C0093214600230822F1 +:10138000284601F07FFC08340137DEE7201A18BF39 +:101390000120E7E7F7B50023047F00910E460822FD +:1013A0001946054601F06EFC731CC4B9082200936F +:1013B00011462346284601F065FC1024012372786B +:1013C0005F1C013B934211D32B7FA88A0734E408AA +:1013D000BBB9844294BF0020012003B0F0BDAB8AAA +:1013E000DB00083BDB0873700824E7E7F319009380 +:1013F000214600230822284601F044FC08343B46DD +:10140000DDE7201A18BF0120E7E70000F8B50E4617 +:1014100005461446002181223046FFF75FFE2B4629 +:1014200008220021304601F069FD7CB96B1C0722BF +:101430000821304601F062FD0F2401236A785F1C09 +:10144000013B934204D3E01DC008F8BD0824F4E733 +:10145000EB1921460822304601F050FD08343B4686 +:10146000ECE70000F8B50E46054614460021CE22F2 +:101470003046FFF733FE2B4628220021304601F08C +:101480003DFD7CB905F1080308222821304601F012 +:1014900035FD30242F462A7A7B1B934204D3E01D6E +:1014A000C008F8BD2824F5E707F109032146082202 +:1014B000304601F023FD08340137ECE7F7B5047F2F +:1014C00000910E46012310220021054601F0DAFBAF +:1014D000C4B9B31C0093092223461021284601F009 +:1014E000D1FB192437467288BB1B9A4211D82B7F37 +:1014F000A88A0734E408BBB9844294BF00200120C5 +:1015000003B0F0BDAB8ADB00103BDB087380102416 +:10151000E8E73B1D0093214600230822284601F0FE +:10152000B1FB08340137DEE7201A18BF0120E7E7D6 +:1015300030B5094D0A4491420DD011F8013B584095 +:10154000082340F30004013B2C4013F0FF0384EA1E +:101550005000F6D1EFE730BD2083B8EDF7B54FF07E +:10156000FF33DFF854C0DFF854E000EB81011A4686 +:1015700088421CD050F8044B019401AF042417F8A2 +:10158000015B82EA05620825DB18164605F1FF3586 +:101590005241002EBCBF83EA0C0382EA0E0215F012 +:1015A000FF05F1D1013C14F0FF04E8D1E0E7D84396 +:1015B000D14303B0F0BD00BF9336EAA9EBE1F0429E +:1015C000F7B5354A106851686B4603C36A4633491C +:1015D0003348082303F0ECF9044688BB0A25314A56 +:1015E000106851686B4603C36A462F492C4808238C +:1015F00003F0DEF90446002845D00369B3F5E02F77 +:1016000041D8B0F86620512A3DD1284A024402F15F +:101610005C018B4237D35C3B214900209E1AFFF7C7 +:1016200087FF3246074604F164010020FFF780FF80 +:10163000A3689F4227D1E368984208BF002522E0B3 +:101640000369B3F5E02F25D8428B512A20D1174AE0 +:10165000024402F110018B4218D3103B10490020C4 +:101660009D1AFFF765FF2A46064604F1180100207F +:10167000FFF75EFFA3689E4202D1E368984201D063 +:101680000D25ACE70025284603B0F0BD1025A6E7E0 +:101690000C25A4E70B25A2E7A44A0008DCFF0600FE +:1016A00000000108AD4A000890FF06000800FFF79F +:1016B00010B5037C044613B9006803F061F92046B5 +:1016C00010BD00000023BFF35B8FC360BFF35B8FCF +:1016D000BFF35B8F8360BFF35B8F7047BFF35B8F9C +:1016E0000068BFF35B8F704770B505460C30FFF79D +:1016F000F5FF05F1080604463046FFF7EFFFA0426C +:1017000006D930466D68FFF7E9FF2544281A70BDF9 +:101710003046FFF7E3FF201AF9E7000070B50546F1 +:10172000406898B105F10800FFF7D8FF05F10C06F5 +:1017300004463046FFF7D2FF8442304694BF6D68BE +:101740000025FFF7CBFF013C2C44201A70BD0000A0 +:1017500038B50C460546FFF7C7FFA04210D305F188 +:101760000800FFF7BBFF04446868B4FBF0F100FB1E +:101770001144BFF35B8F0120AC60BFF35B8F38BDBA +:101780000020FCE72DE9F041144607460D46FFF71F +:10179000C5FF844228BF0446D4B1B84658F80C6B44 +:1017A0004046FFF79BFF3044286040467E68FFF7C5 +:1017B00095FF331A9C4203D86C600120BDE8F0818C +:1017C0006B60A41B3B68AB602044E8600220F5E737 +:1017D0002046F3E738B50C460546FFF79FFFA042C9 +:1017E00010D305F10C00FFF779FF04446868B4FBDF +:1017F000F0F100FB1144BFF35B8F0120EC60BFF3FD +:101800005B8F38BD0020FCE72DE9FF418846694623 +:101810000746FFF7B7FF6C4606B204EBC606002585 +:10182000B44209D06268206808EB0501FFF744FC68 +:10183000636808341D44F3E729463846FFF7CAFFBA +:10184000284604B0BDE8F081F8B505460C300F46D7 +:10185000FFF744FF05F1080604463046FFF73EFF58 +:10186000A042304688BF6C68FFF738FF201A386006 +:1018700020B130462C68FFF731FF2044F8BD00004E +:1018800073B5144606460D46FFF72EFF844228BF67 +:1018900004460190DCB101A93046FFF7D5FF019B5A +:1018A00033B93268C5E90233C5E9002401200CE0F0 +:1018B0009C4238BF01942860019868608442F5D941 +:1018C0003368AB60241AEC60022002B070BD204681 +:1018D000FBE700002DE9FF410F466946FFF7D0FF07 +:1018E0006C4600B204EBC0050026AC4209D0D4F827 +:1018F000048054F8081BB8194246FFF7DDFB464444 +:10190000F3E7304604B0BDE8F081000038B5054685 +:10191000FFF7E0FF044601462846FFF719FF20467F +:1019200038BD000010B4026854681A4623465DF8BA +:10193000044B184700207047002070477047000094 +:10194000002070470E20704700F5805090F8C800C6 +:10195000C0F340007047000000F5805090F9D000BF +:101960007047000000F58050C0F8CC10012070478F +:10197000F7B50C68BDF8207014F0005470D10D7BE1 +:10198000082D6DD8302585F311884569AE6876013C +:101990000CD4AC68240108D4AC6814F080545DD138 +:1019A00084F31188204603B0F0BD01240E6804F1D1 +:1019B000180C002EB8BFF6004FEA0C1CB4BF46F05E +:1019C0000406760545F80C600E680FFA84FC16F0E4 +:1019D000804F18BF05EB0C1E05EB0C1C1EBFDEF87C +:1019E000806146F00206CEF880610E7BCCF88461FF +:1019F00005EB04158E68C5F88C614E68C5F88861E2 +:101A0000DCF8805145F00105CCF8805100EB44161C +:101A100041F268052E4405EB44150544C6E9002350 +:101A200008350E4601F10C0C56F804EB45F804EBB2 +:101A30006645F9D1843436882E8000EB441407F0D3 +:101A40000305267926F00B0635432571002484F31F +:101A50001188009700F0FCFC0120A4E70224A5E710 +:101A60004FF0FF309FE7000013B500F5805401915F +:101A7000E06DFFF753FE1F280AD90199E06D20227F +:101A8000FFF7C2FEA0F120035842584102B010BD3A +:101A90000020FBE708B5302383F3118800F5805060 +:101AA000C06DFFF70FFE002383F3118808BD00000F +:101AB00000220260828142608260704710B500227D +:101AC0000023C0E900230023044603810C30FFF704 +:101AD000EFFF204610BD0000F0B5054600F5805030 +:101AE0000C4690F8C83013F0040FC3F3800108BF10 +:101AF000114661F3820304F1840680F8C83005EBD7 +:101B0000461389B01B79D8072ED57AB319072DD47F +:101B10006846FFF7D3FF05EB441303F5835303F146 +:101B2000180703AA103318685968144603C4083309 +:101B3000BB422246F7D1186820609B88A380DDE96C +:101B40000E23CDE900230123ADF808302B68694648 +:101B5000DB6B2846984705EB46152B791A075CBFC7 +:101B600043F008032B7101E0002AF4D109B0F0BD65 +:101B70002DE9F0479A4688B00746884691463023BB +:101B800083F3118807F580546846FFF797FFE06DEF +:101B9000FFF7AAFD1F282AD9E06D20226946FFF72A +:101BA000B5FE202823D103AD444605AB2E4603CE17 +:101BB0009E4220606160354604F10804F6D1306829 +:101BC0002060B388A380DDE90023C9E90023BDF8C4 +:101BD0000830AAF80030002383F3118853464A46A0 +:101BE0004146384608B0BDE8F04700F01FBC002071 +:101BF00080F3118808B0BDE8F08700002DE9F84FA8 +:101C00000023C0E90133254B044640F8183B0F463A +:101C1000FFF74EFF04F12800FFF750FF04F14808DA +:101C200004F582554646083530462036FFF746FF14 +:101C3000AE42F9D104F580554FF480534FF00009BE +:101C4000C5E91339C5F848800123EE6504F58758C6 +:101C500004F58456C5F8549085F8583085F86030FE +:101C6000083608F108084FF0000A4FF0000B46E96B +:101C700008ABA6F11800FFF71BFF203646F8289C9A +:101C80004645F4D185F8D07017B1054800F0B8FB8F +:101C9000044B63612046BDE8F88F00BFE04A0008AE +:101CA000B84A00080064004010B5044B1978044697 +:101CB0004A1C1A70FFF7A2FF204610BD1C4A0020E4 +:101CC0002DE9F047002950D0294B2A4FB7FBF1F5F9 +:101CD00099428CBF0A231123581EB5FBF3FC03FB6A +:101CE0001C53C4B22BB102280346F5D80020BDE82E +:101CF000F0870CF1FF36B6F5806FF7D2C4EBC40E57 +:101D00000EF103034FEAE309C3F3C703A4EB03088F +:101D100009F1010A4FF47A755FFA88F009FB05555D +:101D20005AFA88F8B5FBF8F5B5F5617FC1BF0EF139 +:101D3000FF33C3F3C703E01AC0B25C1C50FA84F44B +:101D40000CFB04F4B7FBF4F4A142CFD1013BDBB2AE +:101D50000F2BCBD80138C0B20728C7D8002110718B +:101D600016809170D3700120C1E70846BFE700BF1D +:101D70003F420F0040787D0170B505460E464FF496 +:101D80007A746B695B6803F00103B34207D04FF4C8 +:101D90007A7001F08FFC013CF3D1204670BD012028 +:101DA000FCE7000030B54269936913F0700F16D05C +:101DB00000230B4C936103F1840200EB4212117972 +:101DC0004D0709D5890707D5416954F823508D601F +:101DD000117941F0040111710133032BEBD130BDB6 +:101DE000CC4A000873B51D46436916469A68D20767 +:101DF000044609D59A6801219960C2F34002CDE9F1 +:101E000000650021FFF768FE63699A68D1050BD56C +:101E10009A684FF480719960C2F34022CDE9006561 +:101E200001212046FFF758FE63699A68D2030BD55B +:101E30009A684FF480319960C2F34042CDE9006561 +:101E400002212046FFF748FE04F58053D3F8CC006A +:101E500010B103681B699847204602B0BDE8704086 +:101E6000FFF7A0BFF8B504464669002972D106F114 +:101E70000C073868800770D006EB01153868D5F874 +:101E8000B00110F0040FD5F8B0011ABFC00840F03F +:101E90000040400DA061D5F8B0C11CF0020F1CBF7E +:101EA00040F08040A061D5F8B40106EB011100F0CC +:101EB0000F0084F82400D1F8B8012077D1F8B801D8 +:101EC000000A6077D1F8B801000CA077D1F8B8010A +:101ED000000EE077D1F8BC0184F82000D1F8BC01F5 +:101EE000000A84F82100D1F8BC01000C84F822001B +:101EF000D1F8BC11090E84F823103821396004F19F +:101F0000340004F1180104F1240551F8046B40F881 +:101F1000046BA942F9D109880180C4E90A2321464A +:101F20000023238651F8283B2046DB6B984704F5B5 +:101F3000805393F8C820D3F8CC0042F0040283F811 +:101F4000C82010B103681B6998472046BDE8F840D7 +:101F5000FFF728BF06F110078BE7F8BD10B5044660 +:101F600000F056FA02460B4652EA030102D0013A4B +:101F700063F100030449086820B12146BDE8104020 +:101F8000FFF770BF10BD00BF184A0020F0B5302128 +:101F900081F31188DFF848C000F58351083100242F +:101FA00004F1840500EB45152E7977070ED4F6066B +:101FB0000CD5D1E9007697429E4107D246695CF87C +:101FC0002470B7602E7946F004062E710134032C7C +:101FD00001F12001E4D1002383F31188F0BD00BF9B +:101FE000CC4A000808B5302383F31188FFF7DAFEE6 +:101FF000002383F3118808BDF8B543690546986846 +:1020000000F0E050B0F1E05F0F4621D0F8B130238E +:1020100083F3118805F583541034002606F18403F8 +:1020200005EB43131B791A0706D50136032E04F17D +:102030002004F3D1012007E05B07F6D4214638469F +:1020400000F040FA0028F0D1002383F31188F8BD96 +:102050000120FCE708B5302383F3118800F5805098 +:10206000C06DFFF741FB002383F3118843090CBFC8 +:102070000120002008BD0000F8B51D4600231370A4 +:102080000F4606461446FFF7E5FF80F00100387062 +:1020900025B129463046FFF7AFFF2070F8BD00009C +:1020A0002DE9B8410C4615461F46804600F0B0F9B0 +:1020B0000B462178024609B9287850B14046FFF70F +:1020C00065FFFFF78FFF3B462A462146FFF7D4FF07 +:1020D0000120BDE8B881000070B5302686F3118874 +:1020E000174B1A6C42F000721A641A6A42F00072BE +:1020F0001A621A6A22F000721A62002383F31188AE +:1021000000F5805494F8C83013F0010516D1A9B138 +:1021100086F311880321132001F0C8F9032114204C +:1021200001F0C4F90321152001F0C0F994F8C8307A +:1021300043F0010384F8C83085F3118870BD00BFF7 +:10214000003802402DE9F04700F5805588B095F839 +:10215000D030012B04468846164600F28180814F1C +:1021600057F823200AB947F82300D7F800A0C4F88D +:102170000C802674BAF1000F64D095F8D030012B92 +:1021800070D001212046FFF7A7FF302383F3118889 +:102190006269136823F0020313606269136843F0F5 +:1021A00001031360636900275F6187F311880121D0 +:1021B0002046FFF7E1FD002800F09580E86DFFF76D +:1021C00081FA04F58359BA4609F108092022002151 +:1021D0006846FEF783FF02A8FFF76AFCCDF818A057 +:1021E0006A4609EB07030DF1180E9446BCE803009C +:1021F000F44518605960624603F10803F5D1DCF834 +:102200000000186020379CF804201A71602FDDD17F +:1022100095F8C8306FF38203002785F8C8306A4606 +:1022200041462046ADF80070ADF802708DF804709C +:10223000FFF746FD636948BB4FF400421A6008B0DF +:10224000BDE8F08741F2D80002F05AFB814610B198 +:102250005146FFF7D3FCC7F80090B9F1000F8CD1BD +:102260000020ECE7386803681B6B9847014600289C +:1022700087D13868FFF730FF3868036832465B68FB +:102280004146984700287FF47CAFE9E761221A6055 +:102290009DF802309DF803201B06120402F4702200 +:1022A00003F040731343BDF80020C2F30902134347 +:1022B0009DF804201205022E02F4E0020CBF4FF03C +:1022C00000410021134362690B43D3616369132208 +:1022D0005A616269136823F001031360394620468E +:1022E000FFF74AFD08B96369A6E795F8D03093BBBC +:1022F0006169D1F8002242F00102C1F8002261694F +:10230000D1F8002222F47C5222F00E02C1F8002201 +:102310006169D1F8002242F46062C1F8002262696A +:10232000C2F814326269C2F80432626941F6FF7180 +:10233000C2F80C126269C2F840326269C2F84432D3 +:1023400063690122C3F81C226269D2F8003223F0CB +:102350000103C2F8003295F8C83043F0020385F853 +:10236000C8306CE7184A002008B500F051F850EA70 +:102370000103024602D0421E61F10001044B1868BD +:1023800010B10B46FFF72EFDBDE8084001F064B820 +:10239000184A002008B50020FFF7E0FDBDE808401E +:1023A00001F05AB808B50120FFF7D8FDBDE8084094 +:1023B00001F052B800B59BB0EFF30981682268467E +:1023C000FEF77AFEEFF30583014B9B6BFEE700BF40 +:1023D00000ED00E008B5FFF7EDFF000000B59BB091 +:1023E000EFF3098168226846FEF766FEEFF3058386 +:1023F000014B5B6BFEE700BF00ED00E0FEE7000075 +:102400000FB408B5029801F005F9FEE701F01ABC17 +:1024100001F0FCBB13B56C4684E80600031D94E88C +:10242000030083E80500012002B010BD73B5856884 +:10243000019155B11B885B0707D4D0E900369B6B2F +:102440009847019AC1B23046A847012002B070BD3A +:10245000F0B5866889B005460C465EB1BDF83830E7 +:102460005B070AD4D0E900379B6B98472246C1B27C +:102470003846B047012009B0F0BD00220023CDE965 +:1024800000230023ADF808300A4603AB01F108062B +:10249000106851681C4603C40832B2422346F7D183 +:1024A000106820609288A280FFF7B2FF0423ADF885 +:1024B00008302B68CDE90001DB6B69462846984758 +:1024C000D8E7000030B503680968DD0FB5EBD17FB0 +:1024D00023F0604421F060424FEAD1700BD0002B12 +:1024E000B8BFA40C0029B8BF920C944202D034BFEC +:1024F0000120002030BD944205D1C1F38070C3F3A8 +:1025000080738342F6D194422CBF00200120F1E772 +:102510002DE9F041456A15B94162BDE8F0814B688B +:1025200023F06047C3F38A464FEAD37EC3F3807833 +:1025300016EA230638BF3E46AC462B465A68BEEB29 +:10254000D27F22F060440AD0002A18DAA40CB442E8 +:1025500017D19D420FD10D60DEE71346EEE7A7428B +:1025600007D102F08044C2F3807242450BD054B1CF +:10257000EFE708D2EDE7CCF800100B60CDE7B442EE +:1025800001D0B442E5D81A689C46002AE5D119600A +:10259000C3E700002DE9F047089D01F007044FEA6A +:1025A000D508224405F0070500EBD1004FF47F4920 +:1025B000944201D1BDE8F08704F0070705F0070A4F +:1025C00057453E4638BF5646C6F10806111B8E4297 +:1025D00028BF0E46E10808EBD50E415C13F80EC08B +:1025E000B94029FA06F721FA0AF1FFB28CEA010193 +:1025F00047FA0AF739408CEA010C03F80EC034445C +:102600003544D5E780EA0120082341F2210201B2D6 +:102610004000002980B203F1FF33B8BF504013F0EF +:10262000FF03F4D17047000038B50C468D18A54261 +:1026300000D138BD14F8011BFFF7E4FFF7E70000F5 +:1026400042684AB1136843604389818901339BB270 +:102650009942438138BF83811046704770B588B076 +:10266000202204460D4668460021FEF737FD20462D +:102670000495FFF7E5FF024658B16B46054608AEE4 +:102680001C4603CCB44228606960234605F1080566 +:10269000F6D1104608B070BD082817D909280CD00B +:1026A0000A280CD00B280CD00C280CD00D280CD0EC +:1026B0000E2814BF4020302070470C207047102097 +:1026C0007047142070471820704720207047000082 +:1026D000082817D90C280CD910280CD914280CD983 +:1026E00018280CD920280CD930288CBF0F200E2098 +:1026F0007047092070470A2070470B2070470C2054 +:1027000070470D20704700002DE9F843078C072F14 +:1027100004461ED9D0E9029800254FF6FF73C5F193 +:102720002006A5F1200029FA05F108FA06F628FA94 +:1027300000F031430143C9B21846FFF763FF083583 +:10274000402D0346EBD1E1693A46BDE8F843FFF777 +:102750006BBF4FF6FF70BDE8F883000010B54B6803 +:1027600023B9CA8A63F30902CA8210BD04691A68D0 +:102770001C600361C38A013BC3824A60EFE700002B +:102780002DE9F84F1D46CB8A0F46C3F309010529F1 +:10279000814692460B4630D00020AAB207F11A04B7 +:1027A0009EB2042E1FFA80F80FD8904503F1010362 +:1027B00006D3FB8A0A4462F30903FB8201201AE074 +:1027C0001AF80060E6540130EAE79045F1D2A1F131 +:1027D000050B1C237C68BBFBF3F203FB12BB1FFA47 +:1027E0008BF6002C45D14846FFF72AFF044638B93E +:1027F00078606FF00200BDE8F88F4FF00008E6E760 +:10280000002606607860ADB24FF0000B454510D948 +:102810000AEB0803221D13F8011B9155B1B208F110 +:1028200001081B291FFA88F82BD0454506F101063F +:10283000F1D8FB8AC3F30902154465F30903BCE729 +:10284000013292B21C462368002BF9D16B1F0B4456 +:102850001C21B3FBF1F301339BB29A42D3D2BBF1FB +:10286000000FD0D14846FFF7EBFE20B9C4F800B006 +:10287000BFE70122E7E7C0F800B05E4620600446EB +:10288000C1E74545D5D94846FFF7DAFE08B92060CB +:10289000AFE7C0F800B0002620600446B6E70000AD +:1028A0002DE9F04F2DED028B1C4683B05B69019240 +:1028B00007468846002B00F09A80238C2BB1E269F2 +:1028C000002A00F09480072B35D807F10C00FFF7A1 +:1028D000B7FE054638B96FF00205284603B0BDECD7 +:1028E000028BBDE8F08F14220021FEF7F7FB228C4B +:1028F000E16905F10800FEF7DFFB208C013080B2B2 +:10290000FFF7E6FEFFF7C8FE013880B220840130F1 +:1029100028746369228C1B782A4403F01F0363F038 +:102920003F0348F000411372384669602946FFF7BB +:10293000EFFD0125D1E700F10C034FF0000908EE8F +:10294000103A4FF0800A4E464D4618EE100AFFF737 +:1029500077FE83460028BED014220021FEF7BEFB7E +:10296000002E3AD1019BABF8083002220BF1080E81 +:102970001FFA82FC0CF10100BCF1060F218C80B221 +:1029800001D88E422BD3FFF7A3FEFFF785FE6269C5 +:102990001278013802F01F028E4208BF4FF0400A41 +:1029A00042EA49121BFA80F14AEA020A013048F071 +:1029B000004281F808A08BF81000CBF8042059469B +:1029C0003846FFF7A5FD238C0135B3422DB289F0BF +:1029D00001094FF0000AB8D17FE70022C6E7E1699C +:1029E000895D0EF802100136B6B20132C0E76FF011 +:1029F000010572E7F8B515460E463022002104465F +:102A00001F46FEF76BFB069B6360B5F5001F079B37 +:102A1000A76034BF6A094FF6FF72A36297B2E661FE +:102A200004F1100000239A4206D800230360A78215 +:102A3000E3822383E360F8BD06600133304620362D +:102A4000F1E7000003781BB94BB2002BC8BF01703F +:102A50007047000000787047F8B50C46C969074612 +:102A600011B9238C002B37D1257E1F2D34D838780F +:102A700028BB228C072A2CD8268A36F003032BD1B8 +:102A80004FF6FF70FFF7D0FD20F001003102400447 +:102A900041EA0561400C41EA40254FF6FF722346AA +:102AA00029463846FFF7FCFE002807DD62691378E7 +:102AB0000133DBB21F2B88BF00231370F8BD218ABE +:102AC0002D0645EA012505432046FFF71DFE024677 +:102AD000E5E76FF00300F1E76FF00100EEE70000BB +:102AE00070B58AB0044616460021282268461D4665 +:102AF000FEF7F4FABDF83830ADF810300F9B0593AF +:102B00009DF840308DF81830119B07936946BDF849 +:102B10004830ADF820302046CDE90265FFF79CFF34 +:102B20000AB070BD2DE9F041D36905460C46164642 +:102B30000BB9138C5BBB377E1F2F28D895F800800C +:102B4000B8F1000F26D03046FFF7DEFD33782102C2 +:102B500041EAC33141EA0801338A41EA076141EAA7 +:102B600003410246334641F080012846FFF798FEB4 +:102B700000280ADD3378012B07D1726913780133FD +:102B8000DBB21F2B88BF00231370BDE8F0816FF00C +:102B90000100FAE76FF00300F7E70000F0B58BB033 +:102BA00004460D4617460021282268461E46FEF7B9 +:102BB00095FA9DF84C305A1E534253418DF800301F +:102BC0009DF84030ADF81030119B05939DF84830CA +:102BD0008DF81830149B07936A46BDF85430ADF851 +:102BE000203029462046CDE90276FFF79BFF0BB047 +:102BF000F0BD0000406A00B104307047436A1A68B3 +:102C0000426202691A600361C38A013BC382704752 +:102C10002DE9F041D0F82080194E14461D4641465A +:102C2000002709B9BDE8F081D1E90223A21A65EBBA +:102C30000303964277EB03031ED2036A8B420DD146 +:102C4000FFF78CFD036A1B68036203690B60C38A8C +:102C50000161016A013BC3828846E2E7FFF77EFD1E +:102C60000B68C8F8003003690B60C38A0161013B3F +:102C7000C382D8F80010D4E788460968D1E700BFBE +:102C800080841E002DE9F04F8BB00D46DDF850908A +:102C900014469B468046002800F01981B9F1000FC8 +:102CA00000F01581531E3F2B00F21181012A03D140 +:102CB000BBF1000F40F00B810023CDE90833B8F8D9 +:102CC0001430B5EBC30F4FEAC30703D300200BB09A +:102CD000BDE8F08F2B199F42D8F80C303ABF7F1B0C +:102CE000FFB227461BB9D8F81030002B7AD0272D19 +:102CF0004ED8C5F12806B7424FF000032CBFF6B2FC +:102D00003E4600932946D8F8080008AB3246FFF744 +:102D100041FCA7EB060A35445FFA8AFAB8F814308A +:102D200003F10053053BDB000493D8F80C30039308 +:102D30002821039B13B1BAF1000F2CD1D8F8100051 +:102D400040B1BAF1000F05D0009608AB5246691A9F +:102D5000FFF720FC38B2002FB8D066070AD00AABC4 +:102D600003EBD401624211F8083C02F00702134160 +:102D700001F8083C082C3CD9102C40F2B580202CDE +:102D800040F2B780BBF1000F00F09C80082334E0D4 +:102D9000BA460026C2E7049BE02B28BFE023069337 +:102DA0000B44AB42059314D95A1B039800969245E5 +:102DB00034BF5246D2B2691A08AB04300792FFF70B +:102DC000E9FB079A1644AAEB020A1544F6B25FFA29 +:102DD0008AFA049B069A05999B1A0493039B1B6825 +:102DE0000393A6E70093D8F8080008AB3A462946B3 +:102DF000AEE7BBF1000F13D00123B4EBC30F6CD0CF +:102E0000082C12D89DF82030621E23FA02F2D50752 +:102E100006D54FF0FF3202FA04F423438DF8203038 +:102E20009DF8203089F8003051E7102C12D8BDF8F9 +:102E30002030621E23FA02F2D10706D54FF0FF328E +:102E400002FA04F42343ADF82030BDF82030A9F88D +:102E500000303CE7202C0FD80899631E21FA03F3B9 +:102E6000DA0705D54FF0FF3202FA04F40C43089458 +:102E7000089BC9F800302AE7402C2BD0DDE9086513 +:102E8000611EC4F12102A4F1210326FA01F105FA21 +:102E900002F225FA03F311431943CB0712D501229D +:102EA000A4F12003C4F1200102FA03F322FA01F194 +:102EB000A240524243EA010363EB430332432B43F4 +:102EC000CDE90823DDE90823C9E90023FFE66FF017 +:102ED0000100FCE66FF00800F9E6082CA0D9102CE0 +:102EE000B3D9202CEED8C3E7BBF1000FADD002233D +:102EF00083E7BBF1000FBBD004237EE730B5012A86 +:102F0000144638BF0124402C85B028BF402400253A +:102F1000012ACDE9025518D81B788DF808306307CF +:102F20000AD004AB03EBD405624215F8083C02F06A +:102F30000702934005F8083C009103462246002111 +:102F400002A8FFF727FB05B030BD082AE4D9102AF4 +:102F500003D81B88ADF80830E1E7202A8DBFD3E9FC +:102F600000231B680293CDE90223D8E710B5CB6894 +:102F70001BB98B600B618B8210BD04691A681C60E1 +:102F80000361C38A013BC382CA60F0E703064CBFFA +:102F9000C0F3C0300220704708B50246FFF7F6FFC5 +:102FA000022806D15306C2F30F2001D100F003001E +:102FB00008BDC2F30740FBE72DE9F04F93B0CDE920 +:102FC00003230A6804461046FFF7E0FF022814BFF7 +:102FD000C2F306260026002A0D46824680F2F281C0 +:102FE00012F0C04940F0EE81097B002900F0EA812F +:102FF000022803D02378B34240F0E781C2F3046390 +:103000000693104602F07F030593FFF7C5FF059B6B +:1030100029444FEA834848EA0A4848EA4668CE7895 +:1030200000230022CDE90823F309834648EA00087B +:10303000029367D0059B009302466768534608A930 +:103040002046B847002800F0C381276A4FB941469F +:1030500004F10C00FFF702FB074690B96FF0020085 +:1030600054E03B6998450DD03F68002FF9D14146A7 +:1030700004F10C00FFF7F2FA07460028EED0236AAD +:103080003B60276297F817C006F01F08CCF3840C4A +:10309000ACEB08001FFA80FE0028B8BF0EF120003C +:1030A000A8EB0C031FFA83FED7E90221B8BF00B2D8 +:1030B000002B0793BEBF0EF120031BB2079352EA09 +:1030C000010338D0039BDFF824E39A1A049B4FF0E6 +:1030D000000C63EB010196457CEB01032BD36B7B6A +:1030E00097F81AE0734519D1029B002B78D001287C +:1030F00021DC7868F8B9DFF8F0C2944570EB010381 +:1031000016D337E0276A27B96FF00C0013B0BDE87B +:10311000F08F3B699845B5D03F68F4E7B2489042DC +:103120007CEB010301D30020F0E7029B002BFAD0D7 +:10313000079B0F2B17DCFA7DB30002F0030203F0AC +:103140007C031343FB7539462046FFF707FB6B7B77 +:10315000BB76029B3BB9FB7DC3F38402013262F371 +:103160008603FB75D0E76A7BBB7E9A42DBD1029B6C +:10317000002B35D0B309022B32D0039BBB60049BDC +:10318000FB60142200210DA8FDF7A8FF039B0A9302 +:10319000049B0B932B1D0C932B7BADF83EB0013B96 +:1031A000DBB2ADF83C30069B8DF84230059B8DF8C4 +:1031B000433094F82C308DF840A083F001038DF853 +:1031C00044308DF84180A3680AA920469847FB7DCA +:1031D000C3F38403013303F01F039B02FB82A2E7C6 +:1031E000FB7DC6F34012B2EBD31F40F0F480C3F373 +:1031F0008403434540F0F280029A2B7BB609002AF3 +:103200004DD0F2075DD4032B40F2EB80039BBB60F3 +:10321000049BFB602B7BAE1D033BDBB23246394681 +:1032200004F10C00FFF7ACFA00280CDA394620460E +:10323000FFF794FAFB7DC3F38403013303F01F030C +:103240009B02FB820AE7DDE90884AB883B834FF6EB +:10325000FF73C9F12000A9F1200228FA09F104FA4C +:1032600000F0014324FA02F211431846C9B2FFF7F5 +:10327000C9F909F10809B9F1400F0346E9D1B8824B +:103280002A7B033AD2B23146FFF7CEF9FB7DB882F2 +:10329000DA43C2F3C01262F3C713FB7543E786B982 +:1032A0002E1D013BDBB23246394604F10C00FFF71C +:1032B00067FA0028BADB2A7BB88A013AD2B23146D3 +:1032C000E2E7F98AC1F30901013B0429DAB25BD8CC +:1032D000281D002307F11B069A4208D910F801CBDC +:1032E00006F801C0013101330529DBB2F4D103999D +:1032F0000A9104990B91934207F11B010C9138BF7D +:10330000043379680D9134BF55FA83F300230E938B +:10331000FB8AADF83EB0C3F309031A44069B8DF84F +:103320004230059B8DF8433094F82C30ADF83C20AA +:1033300083F001038DF8443000238DF840A08DF810 +:1033400041807B602A7BB88A013A291DFFF76CF91E +:103350003B8BB882834203D1A3680AA920469847D1 +:1033600020460AA9FFF702FEFB7DBA8AC3F3840355 +:10337000013303F01F039B02FB823B8B9A420CBF7D +:1033800000206FF01000C1E67B68002BAFD0052055 +:1033900001E01C3033461E68002EFAD1091A081DC0 +:1033A0002E1D184401EB090CBCF11B0F5FFA89F3C9 +:1033B0009DD89A429BD916F8013B00F8013B09F1D0 +:1033C0000109EFE76FF00900A0E66FF00A009DE643 +:1033D0006FF00B009AE66FF00D0097E66FF00E00AD +:1033E00094E66FF00F0091E640420F0080841E00CB +:1033F000EFF3098305494A6B22F001024A636833FF +:1034000083F30988002383F31188704700EF00E0FD +:10341000302080F3118862B60C4B0D4AD96821F434 +:10342000E0610904090C0A43DA60D3F8FC20094979 +:1034300042F08072C3F8FC200A6842F001020A6080 +:103440002022DA7783F82200704700BF00ED00E009 +:103450000003FA05001000E010B5302383F3118853 +:103460000E4B5B6813F4006314D0F1EE103AEFF3E7 +:103470000984683C4FF08073E361094BDB6B236682 +:1034800084F3098800F090F810B1064BA36110BDD9 +:10349000054BFBE783F31188F9E700BF00ED00E07F +:1034A00000EF00E03F0300084203000800F1604322 +:1034B00003F561430901C9B283F80013012200F04A +:1034C0001F039A4043099B0003F1604303F56143E6 +:1034D000C3F880211A60704700230375826803696E +:1034E0001B6899689142FBD25A6803604260106081 +:1034F0005860704700230375826803691B689968E8 +:103500009142FBD85A68036042601060586070476F +:1035100008B50846302383F311880B7D032B05D0B3 +:10352000042B0DD02BB983F3118808BD8B690022C1 +:103530001A604FF0FF338361FFF7CEFF0023F2E7FD +:10354000D1E9003213605A60F3E70000FFF7C4BF0F +:10355000054BD9680875186802681A605360012223 +:103560000275D860FCF7D6BE284A002030B50C4B57 +:10357000DD684B1C87B004460FD02B46094A6846CD +:1035800000F046F92046FFF7E3FF009B13B16846C1 +:1035900000F048F9A86907B030BDFFF7D9FFF9E797 +:1035A000284A002011350008044B1A68DB6890682F +:1035B0009B68984294BF002001207047284A002051 +:1035C000084B10B51C68D86822681A605360012245 +:1035D0002275DC60FFF78EFF01462046BDE81040F3 +:1035E000FCF798BE284A002038B5074C0749084820 +:1035F000012300252370656000F028FC022323705E +:1036000085F3118838BD00BF904C0020244B000882 +:10361000284A002008B572B6044B186500F0E2FA9B +:1036200000F08EFB024B03221A70FEE7284A0020AE +:10363000904C002000F02CB98B60022308618B8233 +:10364000084670478368A3F1840243F8142C02698A +:1036500043F8442C426943F8402C094A43F8242C8F +:10366000C26843F8182C022203F80C2C002203F83D +:103670000B2C044A43F8102CA3F12000704700BF24 +:103680002D030008284A002008B5FFF7DBFFBDE83E +:103690000840FFF75BBF0000024BDB6898610F201A +:1036A000FFF756BF284A0020302383F31188FFF725 +:1036B000F3BF000008B50146302383F311880820CA +:1036C000FFF754FF002383F3118808BD064BDB6826 +:1036D00039B1426818605A60136043600420FFF7F4 +:1036E00045BF4FF0FF307047284A002003689842DA +:1036F00006D01A680260506099611846FFF726BF2D +:103700007047000010B503689C68A2420CD85C6842 +:103710008A600B604C602160596099688A1A9A60CF +:103720004FF0FF33836010BD1B68121BECE70000F5 +:103730000A2938BF0A2170B504460D460A266019C9 +:1037400000F07EFB00F06AFB041BA54203D8751C49 +:103750002E460446F3E70A2E04D9BDE87040012046 +:1037600000F0B4BB70BD0000F8B5144B0D46D96134 +:1037700003F1100141600A2A1969826038BF0A22E8 +:10378000016048601861A818144600F04BFB0A2736 +:1037900000F044FB431BA342064606D37C1C2819B9 +:1037A00000F04EFB27463546F2E70A2F04D9BDE864 +:1037B000F840012000F08ABBF8BD00BF284A002075 +:1037C000F8B506460D4600F029FB0F4A134653F89C +:1037D000107F9F4206D12A4601463046BDE8F84098 +:1037E000FFF7C2BFD169BB68441A2C1928BF2C4609 +:1037F000A34202D92946FFF79BFF224631460348E0 +:10380000BDE8F840FFF77EBF284A0020384A002074 +:1038100010B4C0E9032300235DF8044B4361FFF7B4 +:10382000CFBF000010B5194C236998420DD0D0E9E4 +:103830000032816813605A609A680A449A600023D3 +:1038400003604FF0FF33A36110BD2346026843F8C5 +:10385000102F53600022026022699A4203D1BDE812 +:10386000104000F0E7BA936881680B44936000F061 +:10387000D5FA2269E1699268441AA242E4D9114456 +:10388000BDE81040091AFFF753BF00BF284A0020C7 +:103890002DE9F047DFF8BC8008F110072C4ED8F86E +:1038A000105000F0BBFAD8F81C40AA68031B9A42DB +:1038B0003ED81444D5E900324FF00009C8F81C4046 +:1038C00013605A60C5F80090D8F81030B34201D1A7 +:1038D00000F0B0FA89F31188D5E9033128469847FA +:1038E000302383F311886B69002BD8D000F096FA4F +:1038F0006A69A0EB04094A4582460DD2022000F015 +:10390000E5FA0022D8F81030B34208D151462846D3 +:10391000BDE8F047FFF728BF121A2244F2E712EB86 +:10392000090938BF4A4629463846FFF7EBFEB5E796 +:10393000D8F81030B34208D01444211AC8F81C003B +:10394000A960BDE8F047FFF7F3BEBDE8F08700BF10 +:10395000384A0020284A002038B500F05FFA054AAE +:10396000D2E90845031B181945F10001C2E9080115 +:1039700038BD00BF284A002000207047FEE7000045 +:10398000704700004FF0FF3070470000BFF34F8FCB +:10399000024AD368DB03FCD4704700BF003C0240FE +:1039A00008B5094B1B7873B9FFF7F0FF074B1A698D +:1039B000002ABFBF064A5A6002F188325A601A686C +:1039C00022F480621A6008BD984C0020003C02403E +:1039D0002301674508B50B4B1B7893B9FFF7D6FF5A +:1039E000094B1A6942F000421A611A6842F4805287 +:1039F0001A601A6822F480521A601A6842F48062CF +:103A00001A6008BD984C0020003C02400728F0B521 +:103A100016D80C4C0C4923787BB90C4D0E46082364 +:103A20004FF0006255F8047B46F8042B013B13F07D +:103A3000FF033A44F6D10123237051F82000F0BD72 +:103A40000020FCE7BC4C00209C4C0020304B0008C0 +:103A5000014B53F820007047304B00080820704796 +:103A6000072810B5044601D9002010BDFFF7CEFF8E +:103A7000064B53F824301844C21A0BB90120F4E75E +:103A800012680132F0D1043BF6E700BF304B00086A +:103A9000072810B5044621D8FFF778FFFFF780FF0D +:103AA0000F4AF323D360C300DBB243F4007343F047 +:103AB00002031361136943F480331361FFF766FF58 +:103AC000FFF7A4FF074B53F8241000F035F9FFF778 +:103AD00081FF2046BDE81040FFF7C2BF002010BDA7 +:103AE000003C0240304B0008F8B512F001031446C8 +:103AF00042D185182E4A954257D82E4B1B6813F099 +:103B0000010352D02C4DFFF74BFFF323EB60FFF77F +:103B10003DFF40F20127032C15D824F0010466185C +:103B2000254C401A40F20117B142236900EB010510 +:103B300024D123F001032361FFF74CFF0120F8BDDE +:103B4000043C0430E7E78307E7D12B6923F4407393 +:103B50002B612B693B432B6151F8046B0660BFF36B +:103B60004F8FFFF713FF03689E42E9D02B6923F0C4 +:103B700001032B61FFF72EFF0020E0E723F44073E1 +:103B8000236123693B4323610B882B80BFF34F8F55 +:103B9000FFF7FCFE2D8831F8023BADB2AB42C3D03B +:103BA000236923F001032361E4E71846C7E700BF58 +:103BB0000000080800380240003C0240084908B5EF +:103BC0000B7828B11BB9FFF7EBFE01230B7008BD82 +:103BD000002BFCD0BDE808400870FFF7FBBE00BF1B +:103BE000984C00200149024800F0A8B800FF0300EB +:103BF000000100200846114600F0A4BE012000F09C +:103C0000A1BE0000084600F0BBBE000038B5EFF3CF +:103C100011859DB9EFF30584C4F30804302334B152 +:103C200083F31188FFF798FE85F3118838BD83F37D +:103C30001188FFF791FE84F3118838BDBDE8384044 +:103C4000FFF78ABE38B5FFF7E1FF114C114AC008F3 +:103C500040EA4170A0FB025EC908A0FB040C1CEB0B +:103C6000050CA1FB04404FF000035B41A1FB0212D5 +:103C70001CEB040C43EB000011EB0E0142F10002BF +:103C8000411842F10000090941EA007038BD00BF47 +:103C9000CFF753E3A59BC42010B50244064BD2B224 +:103CA000904200D110BD441C00B253F8200041F8EE +:103CB000040BE0B2F4E700BF502800400F4B30B5D2 +:103CC0001C6F240407D41C6F44F400741C671C6F21 +:103CD00044F400441C670A4C236843F48073236057 +:103CE0000244084BD2B2904200D130BD441C00B215 +:103CF00051F8045B43F82050E0B2F4E7003802408A +:103D0000007000405028004007B5012201A90020A2 +:103D1000FFF7C2FF019803B05DF804FB13B504463A +:103D2000FFF7F2FFA04205D0012201A90020019473 +:103D3000FFF7C4FF02B010BD7047000070470000DD +:103D400070470000074B45F255521A6002225A6034 +:103D500040F6FF729A604CF6CC421A60024B012288 +:103D60001A70704700300040C44C0020034B1B7891 +:103D70001BB1034B4AF6AA221A607047C44C0020BC +:103D800000300040034B1A681AB9034AD2F874286D +:103D90001A607047C04C002000300240024B4FF0C8 +:103DA0008072C3F8742870470030024008B5FFF7EE +:103DB000E9FF024B1868C0F3407008BDC04C0020FA +:103DC00008B5FFF7DFFF024B1868C0F3007008BDAD +:103DD000C04C002070470000FEE700000A4B0B4873 +:103DE0000B4A90420BD30B4BDA1C121AC11E22F065 +:103DF00003028B4238BF00220021FDF76FB953F850 +:103E0000041B40F8041BECE7E84C0008BC4F002002 +:103E1000BC4F0020BC4F002000F0CAB84FF08043D8 +:103E2000586A70474FF08043002258631A6102229B +:103E3000DA6070474FF080430022DA60704700007C +:103E40004FF0804358637047FEE7000070B51B4B8E +:103E500001630025044686B0586085620E46FFF770 +:103E6000D7FA04F11003C4E904334FF0FF33C4E977 +:103E70000635C4E90044A560E562FFF7CFFF2B4695 +:103E80000246C4E9082304F134010D4A2565802364 +:103E90002046FFF7D1FB0123E0600A4A0375009238 +:103EA00072680192B268CDE90223074B6846CDE9FA +:103EB0000435FFF7E9FB06B070BD00BF904C002051 +:103EC000504B0008554B0008493E0008024AD36A8F +:103ED0001843D062704700BF284A00204B684360F7 +:103EE0008B688360CB68C3600B6943614B69036275 +:103EF0008B6943620B6803607047000008B5234B71 +:103F000023481A6942F0FF021A611A6922F0FF027F +:103F10001A611A691A6B42F0FF021A631A6D42F0B5 +:103F2000FF021A651B4A1B6D1146FFF7D7FF02F10E +:103F30001C0100F58060FFF7D1FF02F1380100F5A8 +:103F40008060FFF7CBFF02F1540100F58060FFF7BE +:103F5000C5FF02F1700100F58060FFF7BFFF02F1BD +:103F60008C0100F58060FFF7B9FF02F1A80100F5B0 +:103F70008060FFF7B3FF02F1C40100F58060FFF736 +:103F8000ADFFBDE8084000F08DB800BF003802402A +:103F9000000002405C4B000808B500F019FAFFF77A +:103FA00023FBBDE80840FFF7EDBE000070470000AE +:103FB0000F4B1A6C42F001021A641A6E42F00102B1 +:103FC0001A660C4A1B6E936843F0010393604FF02E +:103FD000804331229A624FF0FF32DA6200229A6106 +:103FE0005A63DA605A6001225A611A60704700BF52 +:103FF00000380240002004E04FF0804208B511690B +:10400000D3680B40D9B2C9439B07116107D5302350 +:1040100083F31188FFF70EFB002383F3118808BD9B +:104020001E4B1A6962F0FF021A611A69D2B21A6154 +:104030004FF0FF301A695A69586100215A69596175 +:104040005A691A6A62F080521A621A6A02F0805241 +:104050001A621A6A5A6A58625A6A59625A6A1A6C19 +:1040600042F080521A641A6E42F080521A661A6E3A +:104070000B4A106840F480701060186F00F44070B4 +:10408000B0F5007F1EBF4FF4803018671967536882 +:1040900023F40073536000F073B900BF003802408E +:1040A000007000403B4B3C4A1A643C4A4FF440418C +:1040B00011601A6842F001021A601A689007FCD574 +:1040C0009A6822F003029A60324B9A6812F00C024E +:1040D000FBD1196801F0F90119609A601A6842F47D +:1040E00080321A601A689103FCD55A6F42F00102BF +:1040F0005A67284B5A6F9207FCD5294A5A601A68AA +:1041000042F080721A60254A53685804FCD5214B4E +:104110001A689101FCD5234AC3F884201A6842F03A +:1041200080621A601A681201FCD51F4A9A60032245 +:10413000C3F88C204FF00062C3F894201B4B1A6820 +:104140001B4B9A421B4B21D11B4A11681B4A9142BF +:104150001CD140F203121A60164A136803F00F03D1 +:10416000032BFAD10B4B9A6842F002029A609A68CC +:1041700002F00C02082AFAD15A6C42F480425A64C6 +:104180005A6E42F480425A665B6E704740F2037288 +:10419000E1E700BF0038024000040010007000405A +:1041A000041940020830002400948838002004E0FC +:1041B00011640020003C024000ED00E041C20F41CC +:1041C000074A08B5536903F00103536123B1054A57 +:1041D00013680BB150689847BDE80840FFF73CB939 +:1041E000003C0140C84C0020074A08B5536903F061 +:1041F0000203536123B1054A93680BB1D068984715 +:10420000BDE80840FFF728B9003C0140C84C002039 +:10421000074A08B5536903F00403536123B1054A03 +:1042200013690BB150699847BDE80840FFF714B90E +:10423000003C0140C84C0020074A08B5536903F010 +:104240000803536123B1054A93690BB1D0699847BC +:10425000BDE80840FFF700B9003C0140C84C002011 +:10426000074A08B5536903F01003536123B1054AA7 +:10427000136A0BB1506A9847BDE80840FFF7ECB8E5 +:10428000003C0140C84C0020164B10B55C6904F49A +:1042900078725A61A30604D5134A936A0BB1D06AA7 +:1042A0009847600604D5104A136B0BB1506B9847C2 +:1042B000210604D50C4A936B0BB1D06B9847E205ED +:1042C00004D5094A136C0BB1506C9847A30504D56B +:1042D000054A936C0BB1D06C9847BDE81040FFF7CE +:1042E000BBB800BF003C0140C84C0020194B10B5C2 +:1042F0005C6904F47C425A61620504D5164A136D68 +:104300000BB1506D9847230504D5134A936D0BB13B +:10431000D06D9847E00404D50F4A136E0BB1506E70 +:104320009847A10404D50C4A936E0BB1D06E984700 +:10433000620404D5084A136F0BB1506F98472304E9 +:1043400004D5054A936F0BB1D06F9847BDE8104074 +:10435000FFF782B8003C0140C84C002008B5034874 +:1043600000F0E8F8BDE80840FFF776B8484D0020B7 +:1043700008B5FFF741FEBDE80840FFF76DB8000043 +:10438000062108B50846FFF791F806210720FFF738 +:104390008DF806210820FFF789F806210920FFF78C +:1043A00085F806210A20FFF781F806211720FFF77C +:1043B0007DF806212820FFF779F807211C20FFF758 +:1043C00075F8BDE808400C212620FFF76FB8000003 +:1043D00008B5FFF725FE00F07BF800F03DF8FFF789 +:1043E000E5FDBDE80840FFF717BD0000026843681F +:1043F0001143016003B1184770470000143000F00A +:10440000C5B900004FF0FF33143000F0BFB9000011 +:10441000383000F03BBA00004FF0FF33383000F086 +:1044200035BA0000143000F08BB900004FF0FF31B6 +:10443000143000F085B90000383000F0E5B9000014 +:104440004FF0FF32383000F0DFB90000012914BF0F +:104450006FF013000020704700F058B837B51546CC +:104460000E4A026000224260C0E902220122044694 +:1044700002740B46009000F15C014FF4807214301E +:1044800000F034F900942B464FF4807204F5AE71BD +:1044900004F1380000F0ACF903B030BD3C4C00082A +:1044A00038B5C36904460D461BB904210844FFF71B +:1044B0009DFF294604F1140000F026F9002806DAD1 +:1044C000201D4FF40061BDE83840FFF78FBF38BDB5 +:1044D0000023054A19460133102BC2E9001102F1ED +:1044E0000802F8D1704700BFC84C0020026843683A +:1044F0001143016003B1184770470000024AD368B6 +:1045000043F0C003D36070470044004010B5054C31 +:10451000054A00212046FFF7A1FF044A044BC4E9E5 +:10452000972310BD484D0020FD4400080044004082 +:1045300040787D012DE9F041D0F85C62F76833687E +:10454000DA0504469DB20DD5302383F311884FF46C +:1045500080610430FFF7CAFF6FF48073336000237B +:1045600083F31188302383F3118804F1040815F0D4 +:104570002F033AD183F31188380615D5290613D5B0 +:10458000302383F3118804F1380000F065F9002826 +:104590004EDA0821201DFFF7A9FF4FF67F733B403D +:1045A000F360002383F311887A0616D56B0614D5C1 +:1045B000302383F31188D4E913239A420AD1236C60 +:1045C00043B127F040073F041021201D3F0CFFF7A7 +:1045D0008DFFF760002383F31188D4F86822D36835 +:1045E00043B3BDE8F041106918472B0714D015F00C +:1045F000080F0CBF00214FF48071E80748BF41F05D +:104600002001AA0748BF41F040016B0748BF41F0B5 +:1046100080014046FFF76AFFAD06736805D594F840 +:10462000641220461940FFF73BFF3568ADB29EE7A4 +:104630007060B6E7BDE8F081F8B515468268066996 +:10464000AA420B46816938BF8568761AB54204468E +:104650000BD218462A46FCF72FFDA3692B44A36111 +:10466000A3685B1BA3602846F8BD0CD918463246E8 +:10467000FCF722FDAF1BE1683A463044FCF71CFD15 +:10468000E3683B44EBE718462A46FCF715FDE36870 +:10469000E5E7000083689342F7B51546044638BF46 +:1046A0008568D0E90460361AB5420BD22A46FCF779 +:1046B00003FD63692B446361A36828465B1BA36009 +:1046C00003B0F0BD0DD932460191FCF7F5FC01991C +:1046D000E068AF1B3A463144FCF7EEFCE3683B442C +:1046E000E9E72A46FCF7E8FCE368E4E710B50A448A +:1046F0000024C361029B8460C0E90000C0E9051189 +:10470000C1600261036210BD08B5D0E90532934271 +:1047100001D1826882B98268013282605A1C42618A +:104720001970D0E904329A4224BFC3684361002162 +:10473000FEF7DCFF002008BD4FF0FF30FBE7000074 +:1047400070B5302304460E4683F31188A568A5B1E1 +:10475000A368A269013BA360531CA3611578226979 +:10476000934224BFE368A361E3690BB120469847F5 +:10477000002383F31188284607E031462046FEF7E0 +:10478000A5FF0028E2DA85F3118870BD2DE9F74F07 +:1047900004460E4617469846D0F81C904FF0300A53 +:1047A0008AF311884FF0000B154665B12A46314651 +:1047B0002046FFF741FF034660B941462046FEF719 +:1047C00085FF0028F1D0002383F31188781B03B004 +:1047D000BDE8F08FB9F1000F03D001902046C84723 +:1047E000019B8BF31188ED1A1E448AF31188DCE7D4 +:1047F000C0E90511C160C3611144009B8260C0E93A +:104800000000016103627047F8B504460D46164684 +:10481000302383F31188A768A7B1A368013BA36085 +:1048200063695A1C62611D70D4E904329A4224BF44 +:10483000E3686361E3690BB120469847002080F389 +:10484000118807E031462046FEF740FF0028E2DAF3 +:1048500087F31188F8BD0000D0E905239A4210B50E +:1048600001D182687AB98268013282605A1C826101 +:104870001C7803699A4224BFC36883610021FEF754 +:1048800035FF204610BD4FF0FF30FBE72DE9F74F15 +:1048900004460E4617469846D0F81C904FF0300A52 +:1048A0008AF311884FF0000B154665B12A46314650 +:1048B0002046FFF7EFFE034660B941462046FEF76B +:1048C00005FF0028F1D0002383F31188781B03B083 +:1048D000BDE8F08FB9F1000F03D001902046C84722 +:1048E000019B8BF31188ED1A1E448AF31188DCE7D3 +:1048F0000B460146184600F02DB8000000F040B805 +:10490000012838BF012010B50446204600F030F8D9 +:1049100030B900F007F808B900F00CF88047F4E768 +:1049200010BD0000024B1868BFF35B8F704700BFDB +:10493000B44F002008B5062000F084F80120FFF7EE +:104940001DF80000024B0A4601461868FFF752B9ED +:104950001C23002010B5054C13462CB10A46014615 +:104960000220AFF3008010BD2046FCE700000000ED +:10497000024B01461868FFF741B900BF1C23002015 +:10498000024B01461868FFF73DB900BF1C23002009 +:1049900010B501390244904201D1002005E00378AE +:1049A00011F8014FA34201D0181B10BD0130F2E7EE +:1049B0002DE9F041A3B1C91A17780144044603F167 +:1049C000FF3C8C42204601D9002009E00578BD4219 +:1049D00004F10104F5D10CEB0405D618A54201D170 +:1049E000BDE8F08115F8018D16F801EDF045F5D020 +:1049F000E7E700001F2938B504460D4604D9162301 +:104A000003604FF0FF3038BD426C12B152F82130D4 +:104A10004BB9204600F030F82A4601462046BDE852 +:104A2000384000F017B8012B0AD0591C03D11623C7 +:104A300003600120E7E7002442F825402846984714 +:104A40000020E0E7024B01461868FFF7D3BF00BF24 +:104A50001C23002038B5074D0023044608461146A4 +:104A60002B60FEF78FFF431C02D12B6803B123603C +:104A700038BD00BFB84F0020FEF77EBF034611F8D7 +:104A8000012B03F8012B002AF9D170476F72672EB2 +:104A90006172647570696C6F742E41524B5F475040 +:104AA0005300000040A2E4F1646891060041A3E5D0 +:104AB000F2656992070000004261642043414E495B +:104AC0006661636520696E6465782E008000000071 +:104AD00000800000000080000000000000000000D6 +:104AE0002519000845210008A120000865190008C3 +:104AF00071190008711B00083519000845190008D4 +:104B000039190008411900083D190008951A0008D4 +:104B1000491900081524000859190008691A0008E5 +:104B200063300000204B0008804A0020904C002099 +:104B30000040000000400000004000000040000075 +:104B4000000001000000020000000200000002005E +:104B50006D61696E0069646C65000000A000902AB8 +:104B600000000000AAAAAAAA50000024FFFB00002F +:104B7000007700000090090001000005000000001F +:104B8000AAAAAAA501000080FFCF00000000000033 +:104B9000000000000000000000000000AAAAAAAA6D +:104BA00000000000FFFF0000000000000000000007 +:104BB0000000000000000000AAAAAAAA000000004D +:104BC000FFFF0000000000000000000000000000E7 +:104BD00000000000AAAAAAAA00000000FFFF00002F +:104BE00000000000000000000000000000000000C5 +:104BF000AAAAAAAA00000000FFFF0000000000000F +:104C0000000000000000000000000000AAAAAAAAFC +:104C100000000000FFFF0000000000000000000096 +:104C200000000000000000000A000000000000007A +:104C30000300000000000000000000000000000071 +:104C40001944000805440008414400082D440008A8 +:104C5000394400082544000811440008FD430008B9 +:104C60004D4400080000000051000000000000005A +:104C7000000007000000000040420F00FE2A010073 +:104C8000D2040000202300200000000000000000EB +:104C90000000000000000000000000000000000014 +:104CA0000000000000000000000000000000000004 +:104CB00000000000000000000000000000000000F4 +:104CC00000000000000000000000000000000000E4 +:104CD00000000000000000000000000000000000D4 +:084CE0000000000000000000CC :00000001FF diff --git a/Tools/bootloaders/ARK_RTK_GPS_bl.bin b/Tools/bootloaders/ARK_RTK_GPS_bl.bin index cb886cefcad8e2..c90d50e0777f91 100755 Binary files a/Tools/bootloaders/ARK_RTK_GPS_bl.bin and b/Tools/bootloaders/ARK_RTK_GPS_bl.bin differ diff --git a/Tools/bootloaders/ARK_RTK_GPS_bl.hex b/Tools/bootloaders/ARK_RTK_GPS_bl.hex index 74f82628901d96..a9dedf72f0d2ed 100644 --- a/Tools/bootloaders/ARK_RTK_GPS_bl.hex +++ b/Tools/bootloaders/ARK_RTK_GPS_bl.hex @@ -1,1283 +1,1232 @@ :020000040800F2 -:1000000000070020F5040008DD26000895260008FA -:10001000BD26000895260008B5260008F70400084C -:10002000F7040008F7040008F7040008D1360008B8 -:10003000F7040008F7040008F7040008F7040008B4 -:10004000F7040008F7040008F7040008F7040008A4 -:10005000F7040008F7040008DD440008054500081F -:100060002D450008554500087D450008F7040008A7 -:10007000F7040008F7040008F7040008F704000874 -:10008000F7040008F7040008F704000849260008F0 -:100090007526000885260008F7040008A545000815 -:1000A000F7040008F7040008F7040008F704000844 -:1000B0008D460008F7040008F7040008F70400085C -:1000C000F7040008F7040008F7040008F704000824 -:1000D000F7040008F704000879460008F704000850 -:1000E00009460008F7040008F7040008F7040008B0 -:1000F000F7040008F7040008F7040008F7040008F4 -:10010000F7040008F7040008F7040008F7040008E3 -:10011000F7040008F7040008F7040008F7040008D3 -:10012000F7040008F7040008F7040008F7040008C3 -:10013000F7040008F7040008F7040008F7040008B3 -:10014000F7040008F7040008F7040008F7040008A3 -:10015000F7040008F7040008F7040008F704000893 -:10016000F7040008F7040008F7040008F704000883 -:10017000F7040008F7040008F7040008F704000873 -:10018000F7040008F7040008F7040008F704000863 -:10019000F7040008F7040008F7040008F704000853 -:1001A000F7040008F7040008F7040008F704000843 -:1001B000F7040008F7040008F7040008F704000833 -:1001C000F7040008F7040008F7040008F704000823 -:1001D000F7040008F7040008F7040008F704000813 -:1001E000C512000800000000000000000000000030 -:1001F00053B94AB9002908BF00281CBF4FF0FF318E -:100200004FF0FF3000F074B9ADF1080C6DE904CE89 -:1002100000F006F8DDF804E0DDE9022304B07047E1 -:100220002DE9F047089D04468E46002B4DD18A42A9 -:10023000944669D9B2FA82F252B101FA02F3C2F1DC -:10024000200120FA01F10CFA02FC41EA030E94406D -:100250004FEA1C48210CBEFBF8F61FFA8CF708FB8E -:1002600016E341EA034306FB07F199420AD91CEB66 -:10027000030306F1FF3080F01F81994240F21C8198 -:10028000023E63445B1AA4B2B3FBF8F008FB1033E0 -:1002900044EA034400FB07F7A7420AD91CEB040415 -:1002A00000F1FF3380F00A81A74240F207816444E5 -:1002B000023840EA0640E41B00261DB1D44000236A -:1002C000C5E900433146BDE8F0878B4209D9002DCE -:1002D00000F0EF800026C5E9000130463146BDE858 -:1002E000F087B3FA83F6002E4AD18B4202D38242C2 -:1002F00000F2F980841A61EB030301209E46002D71 -:10030000E0D0C5E9004EDDE702B9FFDEB2FA82F2C5 -:10031000002A40F09280A1EB0C014FEA1C471FFA23 -:100320008CFE0126200CB1FBF7F307FB131140EA0A -:1003300001410EFB03F0884208D91CEB010103F1D7 -:10034000FF3802D2884200F2CB804346091AA4B299 -:10035000B1FBF7F007FB101144EA01440EFB00FE6D -:10036000A64508D91CEB040400F1FF3102D2A645D2 -:1003700000F2BB800846A4EB0E0440EA03409CE771 -:10038000C6F12007B34022FA07FC4CEA030C20FA1E -:1003900007F401FA06F31C43F9404FEA1C4900FA3E -:1003A00006F3B1FBF9F8200C1FFA8CFE09FB1811BB -:1003B00040EA014108FB0EF0884202FA06F20BD92E -:1003C0001CEB010108F1FF3A80F08880884240F27E -:1003D0008580A8F102086144091AA4B2B1FBF9F0C2 -:1003E00009FB101144EA014100FB0EFE8E4508D9BD -:1003F0001CEB010100F1FF346CD28E456AD9023842 -:10040000614440EA0840A0FB0294A1EB0E01A14226 -:10041000C846A64656D353D05DB1B3EB080261EB94 -:100420000E0101FA07F722FA06F3F1401F43C5E96E -:10043000007100263146BDE8F087C2F12003D840A4 -:100440000CFA02FC21FA03F3914001434FEA1C47E6 -:100450001FFA8CFEB3FBF7F007FB10360B0C43EAD8 -:10046000064300FB0EF69E4204FA02F408D91CEB88 -:10047000030300F1FF382FD29E422DD90238634486 -:100480009B1B89B2B3FBF7F607FB163341EA034126 -:1004900006FB0EF38B4208D91CEB010106F1FF3875 -:1004A00016D28B4214D9023E6144C91A46EA00466C -:1004B00038E72E46284605E70646E3E61846F8E6FE -:1004C0004B45A9D2B9EB020864EB0C0E0138A3E747 -:1004D0004646EAE7204694E74046D1E7D0467BE728 -:1004E000023B614432E7304609E76444023842E7A0 -:1004F000704700BF02E000F000F8FEE772B6374830 -:1005000080F30888364880F3098836483649086001 -:1005100040F20000CCF200004EF63471CEF2000141 -:100520000860BFF34F8FBFF36F8F40F20000C0F23F -:10053000F0004EF68851CEF200010860BFF34F8FF5 -:10054000BFF36F8F4FF00000E1EE100A4EF63C71E2 -:10055000CEF200010860062080F31488BFF36F8F8D -:1005600003F0C6FD03F058FE4FF055301F491B4AFB -:1005700091423CBF41F8040BFAE71D49184A9142E9 -:100580003CBF41F8040BFAE71A491B4A1B4B9A423D -:100590003EBF51F8040B42F8040BF8E7002018495D -:1005A000184A91423CBF41F8040BFAE703F0A4FD5E -:1005B00003F080FE144C154DAC4203DA54F8041BD2 -:1005C0008847F9E700F042F8114C124DAC4203DACB -:1005D00054F8041B8847F9E703F08CBD000700209E -:1005E000002300200000000808ED00E000010020CA -:1005F00000070020904F00080023002080230020E7 -:1006000080230020C44F0020E0010008E40100081E -:10061000E4010008E40100082DE9F04F2DED108AF7 -:10062000C1F80CD0C3689D46BDEC108ABDE8F08FC0 -:10063000002383F311882846A047002003F0CAF95D -:10064000FEE703F02DF900DFFEE70000F8B500F04B -:100650004BFE03F0E7FC074603F036FD0546002895 -:100660003FD12C4B9F423CD001339F423CD02A4B80 -:1006700027F0FF029A423AD1F8B200F041FC2E4630 -:1006800042F2107400F042FC08B10024264601F04A -:1006900019F980B3032000F045F80024264635B14F -:1006A0001E4B9F4203D003F007FD00242646002086 -:1006B00003F0C2FC1A4B1B691B0422D40EB100F0DC -:1006C00047F800F08FFC00F011FE02F00FF805462D -:1006D000CCB102F00BF8401BA04214D900F038F85E -:1006E000F3E72E460024CDE704460126CAE7064676 -:1006F0004FF47A74C6E7002CD1D04FF47A740126F7 -:10070000CDE70024DDE700F0B5FC4FF47A7003F08C -:1007100067F9DDE7010007B0000008B0263A09B02C -:1007200000040240084B187003280CD8DFE800F0E2 -:1007300008050208022000F037BE022000F02ABEA1 -:10074000024B00225A60704780230020842300203F -:1007500010B501F0B7F830B1204B03221A70204BCE -:1007600000225A6010BD1F4B1F4A1C4619680131F8 -:10077000F8D004339342F9D162681C4B9A42F1D904 -:100780001B4B9B6803F1006303F580339A42E9D267 -:1007900003F066FC03F078FC002000F0C1FD0220AD -:1007A000FFF7C0FF134B1A6C00221A64196E1A6609 -:1007B000196E596C5A64596E5A665B6E72B64FF078 -:1007C000E0233021C3F8084DD4E9003281F31188C9 -:1007D0009D4683F308881047C4E700BF80230020AC -:1007E000842300200000010820000108FFFF00080A -:1007F0000023002000380240094A136849F26900CA -:1008000099B21B0C00FB01331360064B186844F2CD -:10081000506182B2000C01FB0200186080B2704788 -:10082000182300201423002010B5002110220446B4 -:1008300000F0D6FD034B03CB206061601868A06018 -:1008400010BD00BF107AFF1F2DE9F041ADF54E7DC0 -:100850000DF134086CAC40F2751207460D460EA837 -:100860000021C8F8001000F0BBFD4FF4C472002155 -:10087000204600F0B5FD01F039FF254B4FF47A72A8 -:10088000B0FBF2F0186093E80700022384E8070049 -:100890000DF5E9702382FFF7C7FF4FF4A4431D490C -:1008A000238406A804F078FA192384F832310DF273 -:1008B000E32206AB0DF1300C1E4603CE66451060F8 -:1008C0005160334602F10802F6D133781370414685 -:1008D0000122204600F0D0FD00230393AB7E02935B -:1008E00005F11903019380B20123CDE9048000933F -:1008F000E97E05A3D3E90023384602F0BFFA0DF5DF -:100900004E7DBDE8F08100BF9E6AC421818A46EE1B -:100910008C230020A84D00082DE9F0412C4C237AAF -:10092000DAB080460D465BBB27A9284600F0B4FE2E -:100930000746002842D19DF89D60C82E3ED801464A -:100940004FF4A662204600F04BFD4FF48073C4F8CC -:10095000F8314FF40073C4F80C334FF44073C4F80B -:10096000203432460DF19E0104F1090000F026FD0D -:1009700026449DF89C30777223720BB9EB7E23726C -:100980008122002106AC27A800F02AFD0122214681 -:1009900027A800F0BDFE00230393AB7E029305F170 -:1009A000190380B201932823CDE904400093E97E26 -:1009B00005A3D3E90023404602F060FA5AB0BDE82F -:1009C000F08100BFAFF3008026417272DF25D7B7F8 -:1009D000A8440020F0B5254E4FF48A7505FB00654C -:1009E000F1B096F8D83085F8DC300024D8222146C2 -:1009F00085F8E8403AA800F0F3FC06F1090000F0A1 -:100A0000E7FCD5F8E4308DF8F000C2B206AF06F18D -:100A100009010DF1F100CDE93A3400F0CFFC39467F -:100A200001223AA800F0A0FE80B2CDE904700823AC -:100A30000127CDE9023706F1D80301933023009353 -:100A4000317A0B4807A3D3E9002302F017FAA0423A -:100A500006DD01F04BFEC5F8E000384671B0F0BD90 -:100A60002046FBE778F6339F93CACD8DA84400203B -:100A7000A43300202DE9F0411D4D1E4E1E4F86B0BF -:100A8000284602F027FA034658B30024CDE9034470 -:100A9000ADF81440027B8DF81420996840680294E8 -:100AA00003AA03C21B68DFF8548043F0004302939B -:100AB00001F01EFE821941F10003009402A938469C -:100AC00001F0E0F8A04205DD284602F007FA88F8B8 -:100AD0000040D5E798F80030072B05D8013388F897 -:100AE000003006B0BDE8F081014802F0F7F9F8E700 -:100AF000A433002040420F00D8330020DD490020FD -:100B000070B50D4614461E4602F014F950B9022E77 -:100B100010D1012C0ED112A3D3E90023C5E9002383 -:100B2000012007E0282C10D005D8012C09D0052C75 -:100B30000FD0002070BD302CFBD10BA3D3E90023D4 -:100B4000ECE70BA3D3E90023E8E70BA3D3E90023E9 -:100B5000E4E70BA3D3E90023E0E700BFAFF3008095 -:100B6000401DA12026812A0B78F6339F93CACD8D94 -:100B70009E6AC421818A46EE26417272DF25D7B76C -:100B8000F017304A39059E5638B505460E4C0021FF -:100B9000013500F0E7FBA4F82C55B4F82C0500F063 -:100BA000C9FB78B1B4F82C0500F0D4FB014648B974 -:100BB000B4F82C0500F0D6FBB4F82C350133A4F8BA -:100BC0002C35EAE738BD00BFA844002010B50A4B19 -:100BD0000A4A1A6003F5805393F860203AB9DC6D35 -:100BE0002CB1204600F0E6FE204604F015F8BDE8E2 -:100BF0001040034800F0DEBED8330020004E00084D -:100C0000204400202DE9F04F8FB000AF05460C4680 -:100C100002F090F8002849D1237E022B1BD1E38AF1 -:100C2000012B18D101F062FD0646FFF7E5FD0346F2 -:100C30004FF4C870DFF8C482B3FBF0F206F5167605 -:100C400002FB103316FA83F3C8F80030E37E33B9A1 -:100C5000A34B00221A703C37BD46BDE8F08F07F168 -:100C60002401204600F0D6FC0028F4D107F114003E -:100C7000FFF7DAFD97F8264007F11401224607F145 -:100C8000270004F013F80028E2D10F2C08D8944B69 -:100C90001C70D8F80030A3F51673C8F80030DAE7F6 -:100CA00097F82410284602F03DF8D4E7E38A282B71 -:100CB0002BD010D8012B23D0052BCCD1BFF34F8FD5 -:100CC0008849894BCA6802F4E0621343CB60BFF3E2 -:100CD0004F8F00BFFDE7302BBDD1844EE17E327ACD -:100CE0009142B8D1607E3146002291F8DC508542B5 -:100CF00000F0A5800132042A01F58A71F5D1AAE736 -:100D000021462846FFF7A0FDA5E721462846FFF724 -:100D100003FEA0E7B2F8EC507B6005F103094FEA4F -:100D200099094FEA8902D11DC908A8EBC1039D4664 -:100D3000EB460021584600F053FB04F1EE012A4631 -:100D40003144584600F03AFB7B6813B9012000F0AB -:100D5000E7FA96F8D20000F0EDFA044630B93072A6 -:100D600000F008FB204600F0DBFAB1E0D6F8D42012 -:100D70003AB996F8D200B6F82C25824201D8FFF78E -:100D800003FFD6F8D4202A44944208D296F8D20021 -:100D9000B6F82C250130824201D8FFF7F5FE7068C5 -:100DA0005FFA89F2594600F023FB08B9C54679E09D -:100DB000726896F8D2002A447260D6F8D42005EB07 -:100DC0000209C6F8D49000F0B5FA814509D396F827 -:100DD000D220D6F8D4000132001B86F8D220C6F803 -:100DE000D400FF2D0FD80024347200F0C3FA20463F -:100DF00000F096FA00F066FD3D4B188108B9FFF748 -:100E0000A7FCC54627E7BB6896F8D9000AFB036232 -:100E1000FB68D2F8E41082F8E83001F58061C2F88E -:100E2000E030C2F8E410FFF7D5FDFFF723FE96F897 -:100E3000D920013202F0030286F8D920B6E74FF438 -:100E40008A7A0AFB02F505F1EA013144204600F0F6 -:100E5000B7FCF86000287FF4FEAE3544012285F827 -:100E6000E82001F043FCD5F8E020D6ED007ADFED74 -:100E7000216A801A192838BF192040F6B8329042EA -:100E800028BF1046B8EE677A07EE900AF8EEE77AC8 -:100E900067EEA67ADFED186AE7EE267AFCEEE77ACF -:100EA000C6ED007A96F8D930BB60BA6873680AFB61 -:100EB00002F4321992F8E81059B1D2F8E4108B42DA -:100EC000E8463FF427AF002182F8E810C2F8E010AE -:100ED000C5467368064A9B0A01331381BBE600BF0F -:100EE0009D33002000ED00E00400FA05A844002036 -:100EF0008C230020CDCCCC3D6666663FA03300201D -:100F0000014B1870704700BF9823002030B54FF098 -:100F100000542B4B22689A4285B007D003F0DEF8CC -:100F2000044620BB0024204605B030BD254B627D21 -:100F300025481A70237D03724FF48073C0F8F8318E -:100F40004FF40073C0F80C3300254FF44073C0F821 -:100F500020341E49C0F8E450C922093000F02EFAAE -:100F60002046E022294600F03BFA0124DBE7184A3C -:100F7000184D136C43F000731364AA6D164B9A421C -:100F8000D0D12B6E013B7E2BCCD8144A07CA01ABC3 -:100F900083E807001846032100F062FC6B6D834272 -:100FA0004FF00003BED12A6D8A4201BFAB65054BED -:100FB0002A6E1A7003BF0A4BEA6D1A601C46B2E72C -:100FC0009AAD44C598230020A844002016000020B4 -:100FD00000380240006600405041A0B05866004012 -:100FE0001023002037B51A4D00F06CFC02236B7102 -:100FF000184B288119681848012201F015FA0023BE -:101000000193164B164900931648174B4FF4805224 -:1010100001F060FE154B197811B1124801F082FE03 -:1010200001F064FB0446FFF7E7FB4FF4C873B0FB25 -:10103000F3F202FB130304F5167010FA83F00C4B65 -:10104000186003F041F808B10F232B8103B030BDC5 -:101050008C23002010230020D8330020010B00082F -:101060009C230020A4330020050C000898230020B6 -:10107000A03300202DE9F04F2DED028B0FF238291F -:10108000D9E90089834C93B00BAE9FED7E8BFFF7BF -:10109000F1FC814FDFF828A200230A93ADF8343029 -:1010A0000B9373604FF0000B5B468DED008B0125B9 -:1010B0000DF11D0207A938468DF81C508DF81DB0A2 -:1010C00001F062F99DF81C30002B40F0A58020460D -:1010D00001F030FE0646002845D1704F01F006FBB6 -:1010E0003B6898423FD301F001FB8246FFF784FB47 -:1010F0004FF4C873B0FBF3F202FB13030AF516704A -:1011000010FA83F03860664F97F800B0CBF1100A00 -:10111000BBF1000F14BF33462B465FFA8AFA0EA8C4 -:101120008DF82830FFF780FBBAF1060F28BF4FF08B -:10113000060A0EAB03EB0B0152460DF1290000F03D -:101140003DF90AAB0393182302930AF10102554BB0 -:10115000D2B2CDE90053049220464CA3D3E9002338 -:1011600001F02EFE3E7001F0C1FA4F4A4F4D136858 -:10117000C31AB3F57A7F2ED3106001F0B9FA024694 -:101180000B46204601F0B4FE204601F0D3FD10B31B -:101190002B7A474E002B14BF03230223737101F0F7 -:1011A000A5FA0EAF4FF47A730122B0FBF3F0394683 -:1011B0003060304600F006FA182302933D4B01934D -:1011C00080B240F25513CDE90370009342464B467E -:1011D000204601F0F5FD2B7A93B101F087FA002645 -:1011E00007464FF48A7A95F8D900304400F003009E -:1011F0000AFB005393F8E82092B30136042EF2D193 -:10120000C82002F0EDFB2B7A002B7FF43DAF13B02A -:10121000BDEC028BBDE8F08FDAF8143083F4806304 -:10122000CAF81430594610220EA800F0D9F80DF172 -:101230001E0308AA0AA9384600F022FE96E8030019 -:101240000FAB83E803009DF834308DF844300A9BDF -:101250000E930EA9DDE90823204602F01DF821E7D0 -:10126000D3F8E02042B12B68FA2B38BFFA23BA1A20 -:101270000533B2EB430FC0D3FFF7ACFB0028BCD162 -:10128000BEE700BF0000000000000000401DA120DC -:1012900026812A0BA4330020D8330020A03300205D -:1012A0009D3300209C330020D8490020A844002012 -:1012B0008C230020DC490020F1C6A7C1D068080FAC -:1012C0000000024008B5054800F074FEBDE8084083 -:1012D000034A0449002003F099BC00BFD833002022 -:1012E000184A0020CD0B00087047000070B502F0CE -:1012F0003BFD094E094D3080002428683388834225 -:1013000008D902F02BFD2B6804440133B4F5803F6B -:101310002B60F2D370BD00BF0C4A0020E0490020D2 -:1013200002F0D2BD00F10060920000F5803002F0C2 -:1013300061BD0000054B1A68054B1B889B1A834250 -:1013400002D9104402F00ABD00207047E049002095 -:101350000C4A0020024B1B68184402F007BD00BF76 -:10136000E0490020024B1B68184402F017BD00BF83 -:10137000E0490020064991F8243033B10023086A7F -:1013800081F824300822FFF7CDBF0120704700BF4D -:10139000E4490020022802BF024B4FF080629A61AC -:1013A000704700BF00000240022802BF024B4FF40A -:1013B00080629A61704700BF0000024010B50023B0 -:1013C000934203D0CC5CC4540133F9E710BD000054 -:1013D00003460246D01A12F9011B0029FAD17047C0 -:1013E00002440346934202D003F8011BFAE7704718 -:1013F0002DE9F8431F4D144695F8242007468846EA -:1014000052BBDFF870909CB395F824302BB92022A2 -:10141000FF2148462F62FFF7E3FF95F82400C0F153 -:101420000802A24228BF2246D6B24146920005EBEE -:101430008000FFF7C3FF95F82430A41B1E44F6B2CA -:10144000082E17449044E4B285F82460DBD1FFF7FE -:1014500091FF0028D7D108E02B6A03EB8203834277 -:10146000CFD0FFF787FF0028CBD10020BDE8F8835D -:101470000120FBE7E44900202DE9F0470D46044632 -:1014800000219046284640F27912FFF7A9FF234633 -:1014900020220021284601F0A1FE231D0222202146 -:1014A000284601F09BFE631D03222221284601F0FD -:1014B00095FEA31D03222521284601F08FFE04F18D -:1014C000080310222821284601F088FE04F11003A9 -:1014D00008223821284601F081FE04F11103082278 -:1014E0004021284601F07AFE04F112030822482127 -:1014F000284601F073FE04F11403202250212846EF -:1015000001F06CFE04F1180340227021284601F01E -:1015100065FE04F120030822B021284601F05EFE9A -:1015200004F121030822B821284601F057FE04F1F6 -:101530002207C0263B46314608222846083601F0DD -:101540004DFEB6F5A07F07F10107F3D104F1320398 -:1015500008223146284601F041FE002704F1330AF3 -:1015600094F832304FEAC7099F4209F5A47615D3A3 -:10157000B8F1000F08D1314604F5997307222846C7 -:1015800001F02CFE09F24F16274694F832213B1B3E -:1015900093420CD3F01DC008BDE8F0870AEB0703A7 -:1015A00008223146284601F019FE0137D8E707F234 -:1015B000331331460822284601F010FE0836013761 -:1015C000E3E7000013B50446084600210160234606 -:1015D000C0F803102022019001F000FE0198231DA5 -:1015E0000222202101F0FAFD0198631D032222212D -:1015F00001F0F4FD0198A31D0322252101F0EEFD69 -:10160000019804F108031022282101F0E7FD0720CA -:1016100002B010BDF7B50023047F00910E460722EB -:101620001946054601F09EFC731C0093012200231D -:101630000721284601F096FCC4B9B31C009305228B -:1016400023460821284601F08DFC0D243746B27848 -:10165000BB1B934211D32B7FA88A0734E408BBB984 -:10166000844294BF0020012003B0F0BDAB8ADB00B0 -:10167000083BDB08B3700824E8E7FB1C0093214615 -:1016800000230822284601F06DFC08340137DEE70C -:10169000201A18BF0120E7E7F7B50023047F009167 -:1016A0000E4608221946054601F05CFC731CC4B9BD -:1016B0000822009311462346284601F053FC1024CB -:1016C000012372785F1C013B934211D32B7FA88AC0 -:1016D0000734E408BBB9844294BF0020012003B062 -:1016E000F0BDAB8ADB00083BDB0873700824E7E73A -:1016F000F3190093214600230822284601F032FC0A -:1017000008343B46DDE7201A18BF0120E7E7000058 -:10171000F8B50E4605461446002181223046FFF7F3 -:101720005FFE2B4608220021304601F057FD7CB9B0 -:101730006B1C07220821304601F050FD0F240123C5 -:101740006A785F1C013B934204D3E01DC008F8BDDA -:101750000824F4E7EB1921460822304601F03EFD4B -:1017600008343B46ECE70000F8B50E460546144643 -:101770000021CE223046FFF733FE2B4628220021DF -:10178000304601F02BFD7CB905F108030822282121 -:10179000304601F023FD30242F462A7A7B1B9342EA -:1017A00004D3E01DC008F8BD2824F5E707F10903BC -:1017B00021460822304601F011FD08340137ECE7DC -:1017C000F7B5047F00910E46012310220021054643 -:1017D00001F0C8FBC4B9B31C0093092223461021B1 -:1017E000284601F0BFFB192437467288BB1B9A427A -:1017F00011D82B7FA88A0734E408BBB9844294BF70 -:101800000020012003B0F0BDAB8ADB00103BDB08F9 -:1018100073801024E8E73B1D009321460023082233 -:10182000284601F09FFB08340137DEE7201A18BF75 -:101830000120E7E730B5094D0A4491420DD011F877 -:10184000013B5840082340F30004013B2C4013F0B7 -:10185000FF0384EA5000F6D1EFE730BD2083B8EDF6 -:10186000F7B54FF0FF33DFF854C0DFF854E000EB7A -:1018700081011A4688421CD050F8044B019401AFF4 -:10188000042417F8015B82EA05620825DB18164676 -:1018900005F1FF355241002EBCBF83EA0C0382EAFA -:1018A0000E0215F0FF05F1D1013C14F0FF04E8D160 -:1018B000E0E7D843D14303B0F0BD00BF9336EAA9B7 -:1018C000EBE1F042F7B5354A106851686B4603C347 -:1018D0006A4633493348082303F0F8F9044688BBC5 -:1018E0000A25314A106851686B4603C36A462F497E -:1018F0002C48082303F0EAF90446002845D0036980 -:10190000B3F5E02F41D8B0F86620522A3DD1284ADD -:10191000024402F15C018B4237D35C3B2149002039 -:101920009E1AFFF787FF3246074604F16401002044 -:10193000FFF780FFA3689F4227D1E368984208BF62 -:10194000002522E00369B3F5E02F25D8428B522A07 -:1019500020D1174A024402F110018B4218D3103BE8 -:10196000104900209D1AFFF765FF2A46064604F13C -:1019700018010020FFF75EFFA3689E4202D1E368D2 -:10198000984201D00D25ACE70025284603B0F0BDF4 -:101990001025A6E70C25A4E70B25A2E7C44D0008F7 -:1019A000DCFF060000000108CD4D000890FF060096 -:1019B0000800FFF710B5037C044613B9006803F074 -:1019C0006DF9204610BD00000023BFF35B8FC3609C -:1019D000BFF35B8FBFF35B8F8360BFF35B8F704799 -:1019E000BFF35B8F0068BFF35B8F704770B5054630 -:1019F0000C30FFF7F5FF05F1080604463046FFF707 -:101A0000EFFFA04206D930466D68FFF7E9FF254495 -:101A1000281A70BD3046FFF7E3FF201AF9E70000EF -:101A200070B50546406898B105F10800FFF7D8FF8A -:101A300005F10C0604463046FFF7D2FF84423046DB -:101A400094BF6D680025FFF7CBFF013C2C44201AA2 -:101A500070BD000038B50C460546FFF7C7FFA04231 -:101A600010D305F10800FFF7BBFF04446868B4FB1E -:101A7000F0F100FB1144BFF35B8F0120AC60BFF3BA -:101A80005B8F38BD0020FCE72DE9F0411446074686 -:101A90000D46FFF7C5FF844228BF0446D4B1B846BF -:101AA00058F80C6B4046FFF79BFF304428604046D7 -:101AB0007E68FFF795FF331A9C4203D86C600120C3 -:101AC000BDE8F0816B60A41B3B68AB602044E8601C -:101AD0000220F5E72046F3E738B50C460546FFF748 -:101AE0009FFFA04210D305F10C00FFF779FF0444DB -:101AF0006868B4FBF0F100FB1144BFF35B8F012079 -:101B0000EC60BFF35B8F38BD0020FCE72DE9FF419F -:101B1000884669460746FFF7B7FF6C4606B204EBF6 -:101B2000C6060025B44209D06268206808EB0501AA -:101B3000FFF744FC636808341D44F3E72946384640 -:101B4000FFF7CAFF284604B0BDE8F081F8B50546A6 -:101B50000C300F46FFF744FF05F1080604463046F7 -:101B6000FFF73EFFA042304688BF6C68FFF738FFA2 -:101B7000201A386020B130462C68FFF731FF20442E -:101B8000F8BD000073B5144606460D46FFF72EFF5C -:101B9000844228BF04460190DCB101A93046FFF71A -:101BA000D5FF019B33B93268C5E90233C5E900248A -:101BB00001200CE09C4238BF0194286001986860C5 -:101BC0008442F5D93368AB60241AEC60022002B07D -:101BD00070BD2046FBE700002DE9FF410F46694636 -:101BE000FFF7D0FF6C4600B204EBC0050026AC4204 -:101BF00009D0D4F8048054F8081BB8194246FFF7FE -:101C0000DDFB4644F3E7304604B0BDE8F081000058 -:101C100038B50546FFF7E0FF044601462846FFF7C2 -:101C200019FF204638BD0000302383F3118862B6C7 -:101C300070470000002383F3118862B670470000EC -:101C400010B4026854681A4623465DF8044B1847DE -:101C50000120704700207047002070477047000047 -:101C6000002070470E20704700F5805090F8C800A3 -:101C7000C0F340007047000000F5805090F9C900A3 -:101C800070470000F7B50C68BDF8207014F00054E0 -:101C90001E466FD10B7B082B6CD8FFF7C5FF45693B -:101CA000AB685B010CD4AB681B0108D4AC6814F0C2 -:101CB00080545DD1FFF7BEFF204603B0F0BD012484 -:101CC0000B6804F1180C002BB8BFDB004FEA0C1CAA -:101CD000B4BF43F004035B0545F80C300B680FFA02 -:101CE00084FC13F0804F18BF05EB0C1E05EB0C1C99 -:101CF0001EBFDEF8803143F00203CEF880310B7B4B -:101D0000CCF8843105EB04158B68C5F88C314B6831 -:101D1000C5F88831DCF8803143F00103CCF880311C -:101D200000EB441541F268031D4403EB44130344E4 -:101D3000C5E9002608330D4601F10C0C55F804EBFB -:101D400043F804EB6545F9D184342D881D8000EB00 -:101D5000441407F00303257925F00B052B43237169 -:101D6000FFF768FF0097334600F0E2FC0120A4E78C -:101D70000224A5E74FF0FF309FE7000013B500F500 -:101D800080540191E06DFFF74BFE1F280AD901999D -:101D9000E06D2022FFF7BAFEA0F12003584258411F -:101DA00002B010BD0020FBE708B500F58050FFF73A -:101DB0003BFFC06DFFF708FEBDE80840FFF73ABFE4 -:101DC00000220260828142608260704710B500226A -:101DD0000023C0E900230023044603810C30FFF7F1 -:101DE000EFFF204610BD0000F0B5054600F580501D -:101DF0000C4690F8C83013F0040FC3F3800108BFFD -:101E0000114661F3820304F1840680F8C83005EBC3 -:101E1000461389B01B79D8072ED57AB319072DD46C -:101E20006846FFF7D3FF05EB441303F5835303F133 -:101E3000180703AA103318685968144603C40833F6 -:101E4000BB422246F7D1186820609B88A380DDE959 -:101E50000E23CDE900230123ADF808302B68694635 -:101E6000DB6B2846984705EB46152B791A075CBFB4 -:101E700043F008032B7101E0002AF4D109B0F0BD52 -:101E80002DE9F047074688B007F5805468469A4622 -:101E90008846FFF7C9FE9146FFF798FFE06DFFF710 -:101EA000A5FD1F2829D9E06D20226946FFF7B0FE65 -:101EB000202822D103AD444605AB2E4603CE9E42D8 -:101EC00020606160354604F10804F6D13068206076 -:101ED000B388A380DDE90023C9E90023BDF80830F9 -:101EE000AAF80030FFF7A6FE4A4653464146384658 -:101EF00008B0BDE8F04700F009BCFFF79BFE0020EA -:101F000008B0BDE8F08700002DE9F84F0023C0E9D4 -:101F10000133254B044640F8183B0F46FFF750FFAE -:101F200004F12800FFF752FF04F1480804F5825538 -:101F30004646083530462036FFF748FFAE42F9D115 -:101F400004F580554FF480534FF00009C5E913396B -:101F5000C5F848800123EE6504F5875804F58456DA -:101F6000C5F8549085F8583085F86030083608F187 -:101F700008084FF0000A4FF0000B46E908ABA6F145 -:101F80001800FFF71DFF203646F8289C4645F4D17F -:101F900085F8C97017B1054800F0A2FB044B6361D6 -:101FA0002046BDE8F88F00BF004E0008D84D00085D -:101FB0000064004010B5044B197804464A1C1A709E -:101FC000FFF7A2FF204610BD144A00202DE9F0477C -:101FD000002950D0294B2A4FB7FBF1F599428CBF0D -:101FE0000A231123581EB5FBF3FC03FB1C53C4B298 -:101FF0002BB102280346F5D80020BDE8F0870CF18C -:10200000FF36B6F5806FF7D2C4EBC40E0EF10303B2 -:102010004FEAE309C3F3C703A4EB030809F1010A7C -:102020004FF47A755FFA88F009FB05555AFA88F87B -:10203000B5FBF8F5B5F5617FC1BF0EF1FF33C3F312 -:10204000C703E01AC0B25C1C50FA84F40CFB04F421 -:10205000B7FBF4F4A142CFD1013BDBB20F2BCBD8BD -:102060000138C0B20728C7D80021107116809170BE -:10207000D3700120C1E70846BFE700BF3F420F0011 -:1020800040787D0170B505460E464FF47A746B6951 -:102090005B6803F00103B34207D04FF47A7001F09C -:1020A0009FFC013CF3D1204670BD0120FCE70000FD -:1020B00030B54269936913F0700F16D000230B4CB2 -:1020C000936103F1840200EB421211794D0709D5A7 -:1020D000890707D5416954F823508D60117941F083 -:1020E000040111710133032BEBD130BDEC4D00081D -:1020F00073B51D46436916469A68D207044609D54A -:102100009A6801219960C2F34002CDE9006500217F -:10211000FFF76AFE63699A68D1050BD59A684FF498 -:1021200080719960C2F34022CDE90065012120460B -:10213000FFF75AFE63699A68D2030BD59A684FF489 -:1021400080319960C2F34042CDE90065022120460A -:10215000FFF74AFE204602B0BDE87040FFF7A8BF77 -:10216000F8B50446466900296CD106F10C073868B9 -:1021700080076AD006EB01153868D5F8B00110F079 -:10218000040FD5F8B0011ABFC00840F00040400D60 -:10219000A061D5F8B0C11CF0020F1CBF40F0804018 -:1021A000A061D5F8B40106EB011100F00F0084F82E -:1021B0002400D1F8B8012077D1F8B801000A60777F -:1021C000D1F8B801000CA077D1F8B801000EE07783 -:1021D000D1F8BC0184F82000D1F8BC01000A84F8D1 -:1021E0002100D1F8BC01000C84F82200D1F8BC1108 -:1021F000090E84F823103821396004F1340004F109 -:10220000180104F1240551F8046B40F8046BA9424D -:10221000F9D109880180C4E90A23214600232386D5 -:1022200051F8283B2046DB6B984704F58052204646 -:1022300092F8C83043F0040382F8C830BDE8F84093 -:10224000FFF736BF06F1100791E7F8BD10B5044659 -:1022500000F04EFA02460B4652EA030102D0013A60 -:1022600063F100030449086820B12146BDE810402D -:10227000FFF776BF10BD00BF104A0020F8B500F58B -:1022800083511E46FFF7D0FCDFF844C0083100241C -:1022900004F1840500EB45152B795F070ED4DB06AE -:1022A0000CD5D1E900739742B34107D243695CF87A -:1022B00024709F602B7943F004032B710134032CAD -:1022C00001F12001E4D1BDE8F840FFF7B3BC00BF45 -:1022D000EC4D000808B5FFF7A7FCFFF7E9FEBDE8E5 -:1022E0000840FFF7A7BC0000F8B5436905469868A9 -:1022F00000F0E050B0F1E05F0F461FD0E8B1FFF70B -:1023000093FC05F583541034002606F1840305EB95 -:1023100043131B791A0706D50136032E04F1200456 -:10232000F3D1012007E05B07F6D42146384600F0E0 -:1023300039FA0028F0D1FFF77DFCF8BD0120FCE759 -:1023400000F5805008B5FFF76FFCC06DFFF74EFB3E -:10235000FFF770FC43090CBF0120002008BD0000FE -:10236000F8B51D46002313700F4606461446FFF7C6 -:10237000E7FF80F00100387025B129463046FFF7AD -:10238000B3FF2070F8BD00002DE9B8410C4615469A -:102390001F46804600F0ACF90B462178024609B989 -:1023A000287850B14046FFF769FFFFF793FF3B469F -:1023B0002A462146FFF7D4FF0120BDE8B88100007E -:1023C00010B5FFF731FC174B1A6C42F000721A641B -:1023D0001A6A42F000721A621A6A00F5805422F0FA -:1023E00000721A62FFF726FC94F8C830DB0718D495 -:1023F000B9B103211320FFF717FC01F0C7F903213E -:10240000142001F0C3F90321152001F0BFF994F85D -:10241000C83043F0010384F8C830BDE81040FFF72E -:1024200009BC10BD003802402DE9F04700F5805589 -:1024300088B095F8C930012B0446884616467FD8E7 -:10244000804F57F823200AB947F82300D7F800A097 -:10245000C4F80C802674BAF1000F63D095F8C93027 -:10246000012B6FD001212046FFF7AAFFFFF7DCFB0D -:102470006269136823F0020313606269136843F012 -:1024800001031360636900275F6101212046FFF7A4 -:10249000D1FBFFF7F7FD002800F09580E86DFFF70E -:1024A00093FA04F58359BA4609F10809202200215C -:1024B0006846FEF795FF02A8FFF782FCCDF818A04A -:1024C0006A4609EB07030DF1180E9446BCE80300B9 -:1024D000F44518605960624603F10803F5D1DCF851 -:1024E0000000186020379CF804201A71602FDDD19D -:1024F00095F8C8306FF38203002785F8C8306A4624 -:1025000041462046ADF80070ADF802708DF80470B9 -:10251000FFF75CFD636948BB4FF400421A6008B0E6 -:10252000BDE8F08741F2D00002F078FB814610B19F -:102530005146FFF7E9FCC7F80090B9F1000F8DD1C3 -:102540000020ECE7386803681B6B984701460028B9 -:1025500088D13868FFF734FF3868036832465B6813 -:102560004146984700287FF47DAFE9E761221A6071 -:102570009DF802309DF803201B06120402F470221D -:1025800003F040731343BDF80020C2F30902134364 -:102590009DF804201205022E02F4E0020CBF4FF059 -:1025A00000410021134362690B43D3616369132225 -:1025B0005A616269136823F00103136039462046AB -:1025C000FFF760FD08B96369A6E795F8C93093BBCA -:1025D0006169D1F8002242F00102C1F8002261696C -:1025E000D1F8002222F47C5222F00E02C1F800221F -:1025F0006169D1F8002242F46062C1F80022626988 -:10260000C2F814326269C2F80432626941F6FF719D -:10261000C2F80C126269C2F840326269C2F84432F0 -:1026200063690122C3F81C226269D2F8003223F0E8 -:102630000103C2F8003295F8C83043F0020385F870 -:10264000C8306CE7104A002008B500F051F850EA95 -:102650000103024602D0421E61F10001044B1868DA -:1026600010B10B46FFF744FDBDE8084001F064B827 -:10267000104A002008B50020FFF7E8FDBDE808403B -:1026800001F05AB808B50120FFF7E0FDBDE80840A9 -:1026900001F052B800B59BB0EFF30981682268469B -:1026A000FEF78CFEEFF30583014B9B6BFEE700BF4B -:1026B00000ED00E008B5FFF7EDFF000000B59BB0AE -:1026C000EFF3098168226846FEF778FEEFF3058391 -:1026D000014B5B6BFEE700BF00ED00E0FEE7000092 -:1026E0000FB408B5029801F011F9FEE701F038BC0B -:1026F00001F010BC13B56C4684E80600031D94E895 -:10270000030083E80500012002B010BD73B58568A1 -:10271000019155B11B885B0707D4D0E900369B6B4C -:102720009847019AC1B23046A847012002B070BD57 -:10273000F0B5866889B005460C465EB1BDF8383004 -:102740005B070AD4D0E900379B6B98472246C1B299 -:102750003846B047012009B0F0BD00220023CDE982 -:1027600000230023ADF808300A4603AB01F1080648 -:10277000106851681C4603C40832B2422346F7D1A0 -:10278000106820609288A280FFF7B2FF0423ADF8A2 -:1027900008302B68CDE90001DB6B69462846984775 -:1027A000D8E7000030B503680968DD0FB5EBD17FCD -:1027B00023F0604421F060424FEAD1700BD0002B2F -:1027C000B8BFA40C0029B8BF920C944202D034BF09 -:1027D0000120002030BD944205D1C1F38070C3F3C5 -:1027E00080738342F6D194422CBF00200120F1E790 -:1027F0002DE9F041456A15B94162BDE8F0814B68A9 -:1028000023F06047C3F38A464FEAD37EC3F3807850 -:1028100016EA230638BF3E46AC462B465A68BEEB46 -:10282000D27F22F060440AD0002A18DAA40CB44205 -:1028300017D19D420FD10D60DEE71346EEE7A742A8 -:1028400007D102F08044C2F3807242450BD054B1EC -:10285000EFE708D2EDE7CCF800100B60CDE7B4420B -:1028600001D0B442E5D81A689C46002AE5D1196027 -:10287000C3E700002DE9F047089D01F007044FEA87 -:10288000D508224405F0070500EBD1004FF47F493D -:10289000944201D1BDE8F08704F0070705F0070A6C -:1028A00057453E4638BF5646C6F10806111B8E42B4 -:1028B00028BF0E46E10808EBD50E415C13F80EC0A8 -:1028C000B94029FA06F721FA0AF1FFB28CEA0101B0 -:1028D00047FA0AF739408CEA010C03F80EC0344479 -:1028E0003544D5E780EA0120082341F2210201B2F4 -:1028F0004000002980B203F1FF33B8BF504013F00D -:10290000FF03F4D17047000038B50C468D18A5427E -:1029100000D138BD14F8011BFFF7E4FFF7E7000012 -:1029200042684AB1136843604389818901339BB28D -:102930009942438138BF83811046704770B588B093 -:10294000202204460D4668460021FEF749FD204638 -:102950000495FFF7E5FF024658B16B46054608AE01 -:102960001C4603CCB44228606960234605F1080583 -:10297000F6D1104608B070BD082817D909280CD028 -:102980000A280CD00B280CD00C280CD00D280CD009 -:102990000E2814BF4020302070470C2070471020B4 -:1029A000704714207047182070472020704700009F -:1029B000082817D90C280CD910280CD914280CD9A0 -:1029C00018280CD920280CD930288CBF0F200E20B5 -:1029D0007047092070470A2070470B2070470C2071 -:1029E00070470D20704700002DE9F843078C072F32 -:1029F00004461ED9D0E9029800254FF6FF73C5F1B1 -:102A00002006A5F1200029FA05F108FA06F628FAB1 -:102A100000F031430143C9B21846FFF763FF0835A0 -:102A2000402D0346EBD1E1693A46BDE8F843FFF794 -:102A30006BBF4FF6FF70BDE8F883000010B54B6820 -:102A400023B9CA8A63F30902CA8210BD04691A68ED -:102A50001C600361C38A013BC3824A60EFE7000048 -:102A60002DE9F84F1D46CB8A0F46C3F3090105290E -:102A7000814692460B4630D00020AAB207F11A04D4 -:102A80009EB2042E1FFA80F80FD8904503F101037F -:102A900006D3FB8A0A4462F30903FB8201201AE091 -:102AA0001AF80060E6540130EAE79045F1D2A1F14E -:102AB000050B1C237C68BBFBF3F203FB12BB1FFA64 -:102AC0008BF6002C45D14846FFF72AFF044638B95B -:102AD00078606FF00200BDE8F88F4FF00008E6E77D -:102AE000002606607860ADB24FF0000B454510D966 -:102AF0000AEB0803221D13F8011B9155B1B208F12E -:102B000001081B291FFA88F82BD0454506F101065C -:102B1000F1D8FB8AC3F30902154465F30903BCE746 -:102B2000013292B21C462368002BF9D16B1F0B4473 -:102B30001C21B3FBF1F301339BB29A42D3D2BBF118 -:102B4000000FD0D14846FFF7EBFE20B9C4F800B023 -:102B5000BFE70122E7E7C0F800B05E462060044608 -:102B6000C1E74545D5D94846FFF7DAFE08B92060E8 -:102B7000AFE7C0F800B0002620600446B6E70000CA -:102B80002DE9F04F2DED028B1C4683B05B6901925D -:102B900007468846002B00F09A80238C2BB1E2690F -:102BA000002A00F09480072B35D807F10C00FFF7BE -:102BB000B7FE054638B96FF00205284603B0BDECF4 -:102BC000028BBDE8F08F14220021FEF709FC228C55 -:102BD000E16905F10800FEF7F1FB208C013080B2BD -:102BE000FFF7E6FEFFF7C8FE013880B2208401300F -:102BF00028746369228C1B782A4403F01F0363F056 -:102C00003F0348F000411372384669602946FFF7D8 -:102C1000EFFD0125D1E700F10C034FF0000908EEAC -:102C2000103A4FF0800A4E464D4618EE100AFFF754 -:102C300077FE83460028BED014220021FEF7D0FB89 -:102C4000002E3AD1019BABF8083002220BF1080E9E -:102C50001FFA82FC0CF10100BCF1060F218C80B23E -:102C600001D88E422BD3FFF7A3FEFFF785FE6269E2 -:102C70001278013802F01F028E4208BF4FF0400A5E -:102C800042EA49121BFA80F14AEA020A013048F08E -:102C9000004281F808A08BF81000CBF804205946B8 -:102CA0003846FFF7A5FD238C0135B3422DB289F0DC -:102CB00001094FF0000AB8D17FE70022C6E7E169B9 -:102CC000895D0EF802100136B6B20132C0E76FF02E -:102CD000010572E7F8B515460E463022002104467C -:102CE0001F46FEF77DFB069B6360B5F5001F079B43 -:102CF000A76034BF6A094FF6FF72A36297B2E6611C -:102D000004F1100000239A4206D800230360A78232 -:102D1000E3822383E360F8BD06600133304620364A -:102D2000F1E7000003781BB94BB2002BC8BF01705C -:102D30007047000000787047F8B50C46C96907462F -:102D400011B9238C002B37D1257E1F2D34D838782C -:102D500028BB228C072A2CD8268A36F003032BD1D5 -:102D60004FF6FF70FFF7D0FD20F001003102400464 -:102D700041EA0561400C41EA40254FF6FF722346C7 -:102D800029463846FFF7FCFE002807DD6269137804 -:102D90000133DBB21F2B88BF00231370F8BD218ADB -:102DA0002D0645EA012505432046FFF71DFE024694 -:102DB000E5E76FF00300F1E76FF00100EEE70000D8 -:102DC00070B58AB0044616460021282268461D4682 -:102DD000FEF706FBBDF83830ADF810300F9B0593B9 -:102DE0009DF840308DF81830119B07936946BDF867 -:102DF0004830ADF820302046CDE90265FFF79CFF52 -:102E00000AB070BD2DE9F041D36905460C4616465F -:102E10000BB9138C5BBB377E1F2F28D895F8008029 -:102E2000B8F1000F26D03046FFF7DEFD33782102DF -:102E300041EAC33141EA0801338A41EA076141EAC4 -:102E400003410246334641F080012846FFF798FED1 -:102E500000280ADD3378012B07D17269137801331A -:102E6000DBB21F2B88BF00231370BDE8F0816FF029 -:102E70000100FAE76FF00300F7E70000F0B58BB050 -:102E800004460D4617460021282268461E46FEF7D6 -:102E9000A7FA9DF84C305A1E534253418DF800302A -:102EA0009DF84030ADF81030119B05939DF84830E7 -:102EB0008DF81830149B07936A46BDF85430ADF86E -:102EC000203029462046CDE90276FFF79BFF0BB064 -:102ED000F0BD0000406A00B104307047436A1A68D0 -:102EE000426202691A600361C38A013BC382704770 -:102EF0002DE9F041D0F82080194E14461D46414678 -:102F0000002709B9BDE8F081D1E90223A21A65EBD7 -:102F10000303964277EB03031ED2036A8B420DD163 -:102F2000FFF78CFD036A1B68036203690B60C38AA9 -:102F30000161016A013BC3828846E2E7FFF77EFD3B -:102F40000B68C8F8003003690B60C38A0161013B5C -:102F5000C382D8F80010D4E788460968D1E700BFDB -:102F600080841E002DE9F04F8BB00D46DDF85090A7 -:102F700014469B468046002800F01981B9F1000FE5 -:102F800000F01581531E3F2B00F21181012A03D15D -:102F9000BBF1000F40F00B810023CDE90833B8F8F6 -:102FA0001430B5EBC30F4FEAC30703D300200BB0B7 -:102FB000BDE8F08F2B199F42D8F80C303ABF7F1B29 -:102FC000FFB227461BB9D8F81030002B7AD0272D36 -:102FD0004ED8C5F12806B7424FF000032CBFF6B219 -:102FE0003E4600932946D8F8080008AB3246FFF762 -:102FF00041FCA7EB060A35445FFA8AFAB8F81430A8 -:1030000003F10053053BDB000493D8F80C30039325 -:103010002821039B13B1BAF1000F2CD1D8F810006E -:1030200040B1BAF1000F05D0009608AB5246691ABC -:10303000FFF720FC38B2002FB8D066070AD00AABE1 -:1030400003EBD401624211F8083C02F0070213417D -:1030500001F8083C082C3CD9102C40F2B580202CFB -:1030600040F2B780BBF1000F00F09C80082334E0F1 -:10307000BA460026C2E7049BE02B28BFE023069354 -:103080000B44AB42059314D95A1B03980096924502 -:1030900034BF5246D2B2691A08AB04300792FFF728 -:1030A000E9FB079A1644AAEB020A1544F6B25FFA46 -:1030B0008AFA049B069A05999B1A0493039B1B6842 -:1030C0000393A6E70093D8F8080008AB3A462946D0 -:1030D000AEE7BBF1000F13D00123B4EBC30F6CD0EC -:1030E000082C12D89DF82030621E23FA02F2D50770 -:1030F00006D54FF0FF3202FA04F423438DF8203056 -:103100009DF8203089F8003051E7102C12D8BDF816 -:103110002030621E23FA02F2D10706D54FF0FF32AB -:1031200002FA04F42343ADF82030BDF82030A9F8AA -:1031300000303CE7202C0FD80899631E21FA03F3D6 -:10314000DA0705D54FF0FF3202FA04F40C43089475 -:10315000089BC9F800302AE7402C2BD0DDE9086530 -:10316000611EC4F12102A4F1210326FA01F105FA3E -:1031700002F225FA03F311431943CB0712D50122BA -:10318000A4F12003C4F1200102FA03F322FA01F1B1 -:10319000A240524243EA010363EB430332432B4311 -:1031A000CDE90823DDE90823C9E90023FFE66FF034 -:1031B0000100FCE66FF00800F9E6082CA0D9102CFD -:1031C000B3D9202CEED8C3E7BBF1000FADD002235A -:1031D00083E7BBF1000FBBD004237EE730B5012AA3 -:1031E000144638BF0124402C85B028BF4024002558 -:1031F000012ACDE9025518D81B788DF808306307ED -:103200000AD004AB03EBD405624215F8083C02F087 -:103210000702934005F8083C00910346224600212E -:1032200002A8FFF727FB05B030BD082AE4D9102A11 -:1032300003D81B88ADF80830E1E7202A8DBFD3E919 -:1032400000231B680293CDE90223D8E710B5CB68B1 -:103250001BB98B600B618B8210BD04691A681C60FE -:103260000361C38A013BC382CA60F0E703064CBF17 -:10327000C0F3C0300220704708B50246FFF7F6FFE2 -:10328000022806D15306C2F30F2001D100F003003B -:1032900008BDC2F30740FBE72DE9F04F93B0CDE93D -:1032A00003230A6804461046FFF7E0FF022814BF14 -:1032B000C2F306260026002A0D46824680F2F281DD -:1032C00012F0C04940F0EE81097B002900F0EA814C -:1032D000022803D02378B34240F0E781C2F30463AD -:1032E0000693104602F07F030593FFF7C5FF059B89 -:1032F00029444FEA834848EA0A4848EA4668CE78B3 -:1033000000230022CDE90823F309834648EA000898 -:10331000029367D0059B009302466768534608A94D -:103320002046B847002800F0C381276A4FB94146BC -:1033300004F10C00FFF702FB074690B96FF00200A2 -:1033400054E03B6998450DD03F68002FF9D14146C4 -:1033500004F10C00FFF7F2FA07460028EED0236ACA -:103360003B60276297F817C006F01F08CCF3840C67 -:10337000ACEB08001FFA80FE0028B8BF0EF1200059 -:10338000A8EB0C031FFA83FED7E90221B8BF00B2F5 -:10339000002B0793BEBF0EF120031BB2079352EA26 -:1033A000010338D0039BDFF824E39A1A049B4FF003 -:1033B000000C63EB010196457CEB01032BD36B7B87 -:1033C00097F81AE0734519D1029B002B78D0012899 -:1033D00021DC7868F8B9DFF8F0C2944570EB01039E -:1033E00016D337E0276A27B96FF00C0013B0BDE899 -:1033F000F08F3B699845B5D03F68F4E7B2489042FA -:103400007CEB010301D30020F0E7029B002BFAD0F4 -:10341000079B0F2B17DCFA7DB30002F0030203F0C9 -:103420007C031343FB7539462046FFF707FB6B7B94 -:10343000BB76029B3BB9FB7DC3F38402013262F38E -:103440008603FB75D0E76A7BBB7E9A42DBD1029B89 -:10345000002B35D0B309022B32D0039BBB60049BF9 -:10346000FB60142200210DA8FDF7BAFF039B0A930D -:10347000049B0B932B1D0C932B7BADF83EB0013BB3 -:10348000DBB2ADF83C30069B8DF84230059B8DF8E1 -:10349000433094F82C308DF840A083F001038DF870 -:1034A00044308DF84180A3680AA920469847FB7DE7 -:1034B000C3F38403013303F01F039B02FB82A2E7E3 -:1034C000FB7DC6F34012B2EBD31F40F0F480C3F390 -:1034D0008403434540F0F280029A2B7BB609002A10 -:1034E0004DD0F2075DD4032B40F2EB80039BBB6011 -:1034F000049BFB602B7BAE1D033BDBB2324639469F -:1035000004F10C00FFF7ACFA00280CDA394620462B -:10351000FFF794FAFB7DC3F38403013303F01F0329 -:103520009B02FB820AE7DDE90884AB883B834FF608 -:10353000FF73C9F12000A9F1200228FA09F104FA69 -:1035400000F0014324FA02F211431846C9B2FFF712 -:10355000C9F909F10809B9F1400F0346E9D1B88268 -:103560002A7B033AD2B23146FFF7CEF9FB7DB8820F -:10357000DA43C2F3C01262F3C713FB7543E786B99F -:103580002E1D013BDBB23246394604F10C00FFF739 -:1035900067FA0028BADB2A7BB88A013AD2B23146F0 -:1035A000E2E7F98AC1F30901013B0429DAB25BD8E9 -:1035B000281D002307F11B069A4208D910F801CBF9 -:1035C00006F801C0013101330529DBB2F4D10399BA -:1035D0000A9104990B91934207F11B010C9138BF9A -:1035E000043379680D9134BF55FA83F300230E93A9 -:1035F000FB8AADF83EB0C3F309031A44069B8DF86D -:103600004230059B8DF8433094F82C30ADF83C20C7 -:1036100083F001038DF8443000238DF840A08DF82D -:1036200041807B602A7BB88A013A291DFFF76CF93B -:103630003B8BB882834203D1A3680AA920469847EE -:1036400020460AA9FFF702FEFB7DBA8AC3F3840372 -:10365000013303F01F039B02FB823B8B9A420CBF9A -:1036600000206FF01000C1E67B68002BAFD0052072 -:1036700001E01C3033461E68002EFAD1091A081DDD -:103680002E1D184401EB090CBCF11B0F5FFA89F3E6 -:103690009DD89A429BD916F8013B00F8013B09F1ED -:1036A0000109EFE76FF00900A0E66FF00A009DE660 -:1036B0006FF00B009AE66FF00D0097E66FF00E00CA -:1036C00094E66FF00F0091E640420F0080841E00E8 -:1036D000EFF3098305494A6B22F001024A6368331C -:1036E00083F30988002383F31188704700EF00E01B -:1036F000302080F3118862B60C4B0D4AD96821F452 -:10370000E0610904090C0A43DA60D3F8FC20094996 -:1037100042F08072C3F8FC200A6842F001020A609D -:103720002022DA7783F82200704700BF00ED00E026 -:103730000003FA05001000E010B5302383F3118870 -:103740000E4B5B6813F4006314D0F1EE103AEFF304 -:103750000984683C4FF08073E361094BDB6B23669F -:1037600084F3098800F090F810B1064BA36110BDF6 -:10377000054BFBE783F31188F9E700BF00ED00E09C -:1037800000EF00E0430600084606000800F1604331 -:1037900003F561430901C9B283F80013012200F067 -:1037A0001F039A4043099B0003F1604303F5614303 -:1037B000C3F880211A60704700230375826803698B -:1037C0001B6899689142FBD25A680360426010609E -:1037D0005860704700230375826803691B68996805 -:1037E0009142FBD85A68036042601060586070478D -:1037F00008B50846302383F311880B7D032B05D0D1 -:10380000042B0DD02BB983F3118808BD8B690022DE -:103810001A604FF0FF338361FFF7CEFF0023F2E71A -:10382000D1E9003213605A60F3E70000FFF7C4BF2C -:10383000054BD9680875186802681A605360012240 -:103840000275D860FCF7E8BE204A002030B50C4B6A -:10385000DD684B1C87B004460FD02B46094A6846EA -:1038600000F06CF92046FFF7E3FF009B13B16846B8 -:1038700000F06EF9A86907B030BDFFF7D9FFF9E78E -:10388000204A0020F1370008044B1A68DB68906872 -:103890009B68984294BF002001207047204A002076 -:1038A000084B10B51C68D86822681A605360012262 -:1038B0002275DC60FFF78EFF01462046BDE8104010 -:1038C000FCF7AABE204A0020044B1A68DB68926805 -:1038D0009B689A4201D9FFF7E3BF7047204A002056 -:1038E00038B5074C07490848012300252370656057 -:1038F00000F03AFC0223237085F3118838BD00BF25 -:10390000884C0020444E0008204A002008B572B6BA -:10391000044B186500F0ECFA00F0A0FB024B032208 -:103920001A70FEE7204A0020884C002000F046B9BB -:10393000EFF3118020B9EFF30583302282F3118871 -:103940007047000010B530B9EFF30584C4F30804E4 -:1039500014B180F3118810BDFFF7B6FF84F311880E -:10396000F9E700008B60022308618B8208467047EC -:103970008368A3F1840243F8142C026943F8442CB1 -:10398000426943F8402C094A43F8242CC26843F8A2 -:10399000182C022203F80C2C002203F80B2C044AEA -:1039A00043F8102CA3F12000704700BF3106000837 -:1039B000204A002008B5FFF7DBFFBDE80840FFF70D -:1039C00035BF0000024BDB6898610F20FFF730BF66 -:1039D000204A0020302383F31188FFF7F3BF000053 -:1039E00008B50146302383F311880820FFF72EFF26 -:1039F000002383F3118808BD064BDB6839B14268A8 -:103A000018605A60136043600420FFF71FBF4FF037 -:103A1000FF307047204A00200368984206D01A6899 -:103A20000260506099611846FFF700BF70470000C0 -:103A300010B503689C68A2420CD85C688A600B6071 -:103A40004C602160596099688A1A9A604FF0FF3380 -:103A5000836010BD1B68121BECE700000A2938BF09 -:103A60000A2170B504460D460A26601900F076FB5F -:103A700000F062FB041BA54203D8751C2E460446C9 -:103A8000F3E70A2E04D9BDE87040012000F0ACBB7A -:103A900070BD0000F8B5144B0D46D96103F110015B -:103AA00041600A2A1969826038BF0A2201604860B1 -:103AB0001861A818144600F043FB0A2700F03CFBED -:103AC000431BA342064606D37C1C281900F046FB84 -:103AD00027463546F2E70A2F04D9BDE8F840012011 -:103AE00000F082BBF8BD00BF204A0020F8B50646B2 -:103AF0000D4600F021FB0F4A134653F8107F9F42FA -:103B000006D12A4601463046BDE8F840FFF7C2BF5D -:103B1000D169BB68441A2C1928BF2C46A34202D98C -:103B20002946FFF79BFF224631460348BDE8F8408F -:103B3000FFF77EBF204A0020304A002010B4C0E9C1 -:103B4000032300235DF8044B4361FFF7CFBF000060 -:103B500010B5194C236998420DD0D0E90032816824 -:103B600013605A609A680A449A60002303604FF019 -:103B7000FF33A36110BD2346026843F8102F536042 -:103B80000022026022699A4203D1BDE8104000F091 -:103B9000DFBA936881680B44936000F0CDFA226924 -:103BA000E1699268441AA242E4D91144BDE8104088 -:103BB000091AFFF753BF00BF204A00202DE9F04744 -:103BC000DFF8BC8008F110072C4ED8F8105000F038 -:103BD000B3FAD8F81C40AA68031B9A423ED8144492 -:103BE000D5E900324FF00009C8F81C4013605A6054 -:103BF000C5F80090D8F81030B34201D100F0A8FA0F -:103C000089F31188D5E9033128469847302383F397 -:103C100011886B69002BD8D000F08EFA6A69A0EB8E -:103C200004094A4582460DD2022000F0DDFA002246 -:103C3000D8F81030B34208D151462846BDE8F047C5 -:103C4000FFF728BF121A2244F2E712EB090938BF26 -:103C50004A4629463846FFF7EBFEB5E7D8F810305C -:103C6000B34208D01444211AC8F81C00A960BDE86A -:103C7000F047FFF7F3BEBDE8F08700BF304A0020F1 -:103C8000204A002000207047FEE700007047000037 -:103C90004FF0FF3070470000BFF34F8F024AD368E8 -:103CA000DB03FCD4704700BF003C024008B5094B61 -:103CB0001B7873B9FFF7F0FF074B1A69002ABFBFE3 -:103CC000064A5A6002F188325A601A6822F4806209 -:103CD0001A6008BD904C0020003C0240230167455B -:103CE00008B50B4B1B7893B9FFF7D6FF094B1A6940 -:103CF00042F000421A611A6842F480521A601A684F -:103D000022F480521A601A6842F480621A6008BD78 -:103D1000904C0020003C02400728F0B516D80C4C0F -:103D20000C4923787BB90C4D0E4608234FF00062F6 -:103D300055F8047B46F8042B013B13F0FF033A448B -:103D4000F6D10123237051F82000F0BD0020FCE7DC -:103D5000B44C0020944C0020504E0008014B53F806 -:103D600020007047504E000808207047072810B503 -:103D7000044601D9002010BDFFF7CEFF064B53F8D3 -:103D800024301844C21A0BB90120F4E7126801323A -:103D9000F0D1043BF6E700BF504E0008072810B5ED -:103DA000044621D8FFF778FFFFF780FF0F4AF3237F -:103DB000D360C300DBB243F4007343F0020313612A -:103DC000136943F480331361FFF766FFFFF7A4FF25 -:103DD000074B53F8241000F03DF9FFF781FF204610 -:103DE000BDE81040FFF7C2BF002010BD003C0240FC -:103DF000504E0008F8B512F00103144642D1851860 -:103E00002E4A954257D82E4B1B6813F0010352D00F -:103E10002C4DFFF74BFFF323EB60FFF73DFF40F224 -:103E20000127032C15D824F001046618254C401AEC -:103E300040F20117B142236900EB010524D123F0C0 -:103E400001032361FFF74CFF0120F8BD043C04305F -:103E5000E7E78307E7D12B6923F440732B612B69D4 -:103E60003B432B6151F8046B0660BFF34F8FFFF7A4 -:103E700013FF03689E42E9D02B6923F001032B61F5 -:103E8000FFF72EFF0020E0E723F44073236123694E -:103E90003B4323610B882B80BFF34F8FFFF7FCFE62 -:103EA0002D8831F8023BADB2AB42C3D0236923F079 -:103EB00001032361E4E71846C7E700BF00000808D4 -:103EC00000380240003C0240084908B50B7828B190 -:103ED0001BB9FFF7EBFE01230B7008BD002BFCD0D4 -:103EE000BDE808400870FFF7FBBE00BF904C002003 -:103EF0004FF480214FF0005000F0AEB80846114654 -:103F000000F0AEBE012000F0ABBE0000084600F09D -:103F1000C5BE000070B582B0FFF70AFD0E4E054623 -:103F200000F00AF93268904237BF0C4A0B495168D9 -:103F300014682EBFD1E900410131516004190346D4 -:103F400041F10001284601913360FFF7FBFC019924 -:103F5000204602B070BD00BFB84C0020C04C00200D -:103F600070B582B0FFF7E4FC104E054600F0E4F8AF -:103F70003268904237BF0E4A0D49516814682EBF0F -:103F8000D1E9004101315160041941F100010346BA -:103F9000284601913360FFF7D5FC01994FF47A72FE -:103FA00000232046FCF724F902B070BDB84C002075 -:103FB000C04C002010B50244064BD2B2904200D152 -:103FC00010BD441C00B253F8200041F8040BE0B2CD -:103FD000F4E700BF502800400F4B30B51C6F24049D -:103FE00007D41C6F44F400741C671C6F44F4004435 -:103FF0001C670A4C236843F4807323600244084B17 -:10400000D2B2904200D130BD441C00B251F8045BE2 -:1040100043F82050E0B2F4E700380240007000405E -:104020005028004007B5012201A90020FFF7C2FF78 -:10403000019803B05DF804FB13B50446FFF7F2FFE7 -:10404000A04205D0012201A900200194FFF7C4FF7E -:1040500002B010BD704700007047000070470000BC -:10406000074B45F255521A6002225A6040F6FF7221 -:104070009A604CF6CC421A60024B01221A707047CB -:1040800000300040CC4C0020034B1B781BB1034B8D -:104090004AF6AA221A607047CC4C0020003000403B -:1040A000034B1A681AB9034AD2F874281A60704789 -:1040B000C84C002000300240024B4FF08072C3F821 -:1040C000742870470030024008B5FFF7E9FF024B43 -:1040D0001868C0F3407008BDC84C002008B5FFF751 -:1040E000DFFF024B1868C0F3007008BDC84C002009 -:1040F00070470000FEE700000A4B0B480B4A904255 -:104100000BD30B4BDA1C121AC11E22F003028B4296 -:1041100038BF00220021FDF763B953F8041B40F8B3 -:10412000041BECE710500008C44F0020C44F0020CF -:10413000C44F002000F0CAB84FF08043586A70475F -:104140004FF08043002258631A610222DA60704700 -:104150004FF080430022DA60704700004FF0804348 -:1041600058637047FEE7000070B51B4B01630025E4 -:10417000044686B0586085620E46FFF7B9FA04F12E -:104180001003C4E904334FF0FF33C4E90635C4E932 -:104190000044A560E562FFF7CFFF2B460246C4E965 -:1041A000082304F134010D4A256580232046FFF7DA -:1041B000D9FB0123E0600A4A0375009272680192FC -:1041C000B268CDE90223074B6846CDE90435FFF715 -:1041D000F1FB06B070BD00BF884C0020704E000897 -:1041E000754E000865410008024AD36A1843D06240 -:1041F000704700BF204A00204B6843608B68836093 -:10420000CB68C3600B6943614B6903628B6943628E -:104210000B6803607047000008B5234B23481A69F8 -:1042200042F0FF021A611A6922F0FF021A611A694C -:104230001A6B42F0FF021A631A6D42F0FF021A6510 -:104240001B4A1B6D1146FFF7D7FF02F11C0100F559 -:104250008060FFF7D1FF02F1380100F58060FFF7C1 -:10426000CBFF02F1540100F58060FFF7C5FF02F1BA -:10427000700100F58060FFF7BFFF02F18C0100F5CF -:104280008060FFF7B9FF02F1A80100F58060FFF739 -:10429000B3FF02F1C40100F58060FFF7ADFFBDE898 -:1042A000084000F08DB800BF003802400000024016 -:1042B0007C4E000808B500F019FAFFF711FBBDE8C5 -:1042C0000840FFF7EDBE0000704700000F4B1A6C6E -:1042D00042F001021A641A6E42F001021A660C4A98 -:1042E0001B6E936843F0010393604FF080433122CB -:1042F0009A624FF0FF32DA6200229A615A63DA6002 -:104300005A6001225A611A60704700BF00380240AB -:10431000002004E04FF0804208B51169D3680B40DB -:10432000D9B2C9439B07116107D5302383F31188A4 -:10433000FFF7FCFA002383F3118808BD1E4B1A69AE -:1043400062F0FF021A611A69D2B21A614FF0FF30AF -:104350001A695A69586100215A6959615A691A6A79 -:1043600062F080521A621A6A02F080521A621A6A65 -:104370005A6A58625A6A59625A6A1A6C42F08052F2 -:104380001A641A6E42F080521A661A6E0B4A10684E -:1043900040F480701060186F00F44070B0F5007F3A -:1043A0001EBF4FF4803018671967536823F40073F9 -:1043B000536000F073B900BF003802400070004045 -:1043C0003B4B3C4A1A643C4A4FF4404111601A6826 -:1043D00042F001021A601A689007FCD59A6822F030 -:1043E00003029A60324B9A6812F00C02FBD11968F2 -:1043F00001F0F90119609A601A6842F480321A607B -:104400001A689103FCD55A6F42F001025A67284B93 -:104410005A6F9207FCD5294A5A601A6842F0807296 -:104420001A60254A53685804FCD5214B1A6891013B -:10443000FCD5234AC3F884201A6842F080621A60CF -:104440001A681201FCD51F4A9A600322C3F88C2017 -:104450004FF00062C3F894201B4B1A681B4B9A4222 -:104460001B4B21D11B4A11681B4A91421CD140F2BF -:1044700003121A60164A136803F00F03032BFAD1D4 -:104480000B4B9A6842F002029A609A6802F00C02A2 -:10449000082AFAD15A6C42F480425A645A6E42F4A5 -:1044A00080425A665B6E704740F20372E1E700BFDC -:1044B000003802400004001000700040041940025F -:1044C0000830002400948838002004E011640020A3 -:1044D000003C024000ED00E041C20F41074A08B530 -:1044E000536903F00103536123B1054A13680BB10B -:1044F00050689847BDE80840FFF71EB9003C0140EE -:10450000D04C0020074A08B5536903F002035361F9 -:1045100023B1054A93680BB1D0689847BDE80840BD -:10452000FFF70AB9003C0140D04C0020074A08B50B -:10453000536903F00403536123B1054A13690BB1B6 -:1045400050699847BDE80840FFF7F6B8003C0140C5 -:10455000D04C0020074A08B5536903F008035361A3 -:1045600023B1054A93690BB1D0699847BDE808406B -:10457000FFF7E2B8003C0140D04C0020074A08B5E4 -:10458000536903F01003536123B1054A136A0BB159 -:10459000506A9847BDE80840FFF7CEB8003C01409C -:1045A000D04C0020164B10B55C6904F478725A6147 -:1045B000A30604D5134A936A0BB1D06A98476006E4 -:1045C00004D5104A136B0BB1506B9847210604D5E4 -:1045D0000C4A936B0BB1D06B9847E20504D5094A9E -:1045E000136C0BB1506C9847A30504D5054A936C26 -:1045F0000BB1D06C9847BDE81040FFF79DB800BFE5 -:10460000003C0140D04C0020194B10B55C6904F40B -:104610007C425A61620504D5164A136D0BB1506D88 -:104620009847230504D5134A936D0BB1D06D984775 -:10463000E00404D50F4A136E0BB1506E9847A104E5 -:1046400004D50C4A936E0BB1D06E9847620404D522 -:10465000084A136F0BB1506F9847230404D5054ADD -:10466000936F0BB1D06F9847BDE81040FFF764B867 -:10467000003C0140D04C002008B5034800F0E8F8A9 -:10468000BDE80840FFF758B8504D002008B5FFF7C7 -:1046900041FEBDE80840FFF74FB80000062108B50D -:1046A0000846FFF773F806210720FFF76FF8062189 -:1046B0000820FFF76BF806210920FFF767F80621AD -:1046C0000A20FFF763F806211720FFF75FF806219D -:1046D0002820FFF75BF807211C20FFF757F8BDE8FB -:1046E00008400C212620FFF751B8000008B5FFF75D -:1046F00025FE00F07BF800F03DF8FFF7E5FDBDE892 -:104700000840FFF717BD00000268436811430160CD -:1047100003B1184770470000143000F0C5B900001D -:104720004FF0FF33143000F0BFB90000383000F014 -:104730003BBA00004FF0FF33383000F035BA0000CC -:10474000143000F08BB900004FF0FF31143000F04E -:1047500085B90000383000F0E5B900004FF0FF32B5 -:10476000383000F0DFB90000012914BF6FF01300EA -:104770000020704700F058B837B515460E4A026061 -:1047800000224260C0E902220122044602740B4664 -:10479000009000F15C014FF48072143000F034F9A5 -:1047A00000942B464FF4807204F5AE7104F138008A -:1047B00000F0ACF903B030BD5C4F000838B5C369F8 -:1047C00004460D461BB904210844FFF79DFF294606 -:1047D00004F1140000F026F9002806DA201D4FF439 -:1047E0000061BDE83840FFF78FBF38BD0023054AA0 -:1047F00019460133102BC2E9001102F10802F8D169 -:10480000704700BFD04C002002684368114301602C -:1048100003B1184770470000024AD36843F0C00351 -:10482000D36070470044004010B5054C054A002194 -:104830002046FFF7A1FF044A044BC4E9972310BDAB -:10484000504D0020194800080044004040787D0188 -:104850002DE9F041D0F85C62F7683368DA05044668 -:104860009DB20DD5302383F311884FF4806104305D -:10487000FFF7CAFF6FF480733360002383F311885E -:10488000302383F3118804F1040815F02F033AD183 -:1048900083F31188380615D5290613D5302383F301 -:1048A000118804F1380000F065F900284EDA08217B -:1048B000201DFFF7A9FF4FF67F733B40F3600023F5 -:1048C00083F311887A0616D56B0614D5302383F34B -:1048D0001188D4E913239A420AD1236C43B127F0FB -:1048E00040073F041021201D3F0CFFF78DFFF760AC -:1048F000002383F31188D4F86822D36843B3BDE85A -:10490000F041106918472B0714D015F0080F0CBFA1 -:1049100000214FF48071E80748BF41F02001AA0749 -:1049200048BF41F040016B0748BF41F0800140465D -:10493000FFF76AFFAD06736805D594F86412204648 -:104940001940FFF73BFF3568ADB29EE77060B6E7F0 -:10495000BDE8F081F8B5154682680669AA420B46A3 -:10496000816938BF8568761AB54204460BD218466D -:104970002A46FCF723FDA3692B44A361A3685B1BB4 -:10498000A3602846F8BD0CD918463246FCF716FD40 -:10499000AF1BE1683A463044FCF710FDE3683B4446 -:1049A000EBE718462A46FCF709FDE368E5E7000057 -:1049B00083689342F7B51546044638BF8568D0E949 -:1049C0000460361AB5420BD22A46FCF7F7FC63693D -:1049D0002B446361A36828465B1BA36003B0F0BD52 -:1049E0000DD932460191FCF7E9FC0199E068AF1B53 -:1049F0003A463144FCF7E2FCE3683B44E9E72A46E7 -:104A0000FCF7DCFCE368E4E710B50A440024C3616A -:104A1000029B8460C0E90000C0E90511C160026129 -:104A2000036210BD08B5D0E90532934201D1826816 -:104A300082B98268013282605A1C42611970D0E9E1 -:104A400004329A4224BFC36843610021FEF7E4FFA9 -:104A5000002008BD4FF0FF30FBE7000070B53023A9 -:104A600004460E4683F31188A568A5B1A368A26920 -:104A7000013BA360531CA36115782269934224BFB4 -:104A8000E368A361E3690BB120469847002383F3F1 -:104A90001188284607E031462046FEF7ADFF002882 -:104AA000E2DA85F3118870BD2DE9F74F04460E4612 -:104AB00017469846D0F81C904FF0300A8AF31188B8 -:104AC0004FF0000B154665B12A4631462046FFF7E8 -:104AD00041FF034660B941462046FEF78DFF00289E -:104AE000F1D0002383F31188781B03B0BDE8F08F69 -:104AF000B9F1000F03D001902046C847019B8BF30A -:104B00001188ED1A1E448AF31188DCE7C0E905110B -:104B1000C160C3611144009B8260C0E90000016173 -:104B200003627047F8B504460D461646302383F3FA -:104B30001188A768A7B1A368013BA36063695A1CE9 -:104B400062611D70D4E904329A4224BFE368636154 -:104B5000E3690BB120469847002080F3118807E0F5 -:104B600031462046FEF748FF0028E2DA87F3118835 -:104B7000F8BD0000D0E905239A4210B501D1826842 -:104B80007AB98268013282605A1C82611C7803699A -:104B90009A4224BFC36883610021FEF73DFF20468F -:104BA00010BD4FF0FF30FBE72DE9F74F04460E46EE -:104BB00017469846D0F81C904FF0300A8AF31188B7 -:104BC0004FF0000B154665B12A4631462046FFF7E7 -:104BD000EFFE034660B941462046FEF70DFF002870 -:104BE000F1D0002383F31188781B03B0BDE8F08F68 -:104BF000B9F1000F03D001902046C847019B8BF309 -:104C00001188ED1A1E448AF31188DCE70B46014631 -:104C1000184600F02DB8000000F040B8012838BF59 -:104C2000012010B50446204600F030F830B900F0FD -:104C300007F808B900F00CF88047F4E710BD000051 -:104C4000024B1868BFF35B8F704700BFBC4F00205A -:104C500008B5062000F084F80120FFF715F80000E1 -:104C6000024B0A4601461868FFF748B91C2300208A -:104C700010B5054C13462CB10A4601460220AFF38D -:104C8000008010BD2046FCE700000000024B0146FA -:104C90001868FFF737B900BF1C230020024B0146FC -:104CA0001868FFF733B900BF1C23002010B5013985 -:104CB0000244904201D1002005E0037811F8014F31 -:104CC000A34201D0181B10BD0130F2E72DE9F041DD -:104CD000A3B1C91A17780144044603F1FF3C8C4282 -:104CE000204601D9002009E00578BD4204F1010405 -:104CF000F5D10CEB0405D618A54201D1BDE8F08131 -:104D000015F8018D16F801EDF045F5D0E7E7000044 -:104D10001F2938B504460D4604D9162303604FF009 -:104D2000FF3038BD426C12B152F821304BB92046E9 -:104D300000F030F82A4601462046BDE8384000F031 -:104D400017B8012B0AD0591C03D116230360012088 -:104D5000E7E7002442F82540284698470020E0E78E -:104D6000024B01461868FFF7D3BF00BF1C23002089 -:104D700038B5074D00230446084611462B60FEF760 -:104D800087FF431C02D12B6803B1236038BD00BFED -:104D9000C04F0020FEF776BF034611F8012B03F841 -:104DA000012B002AF9D170476F72672E617264750A -:104DB00070696C6F742E41524B5F52544B5F475079 -:104DC0005300000040A2E4F1646891060041A3E5AD -:104DD000F2656992070000004261642043414E4938 -:104DE0006661636520696E6465782E00800000004E -:104DF00000800000000080000000000000000000B3 -:104E0000411C00082924000889230008511C0008BF -:104E1000851C0008811E0008551C0008651C000840 -:104E2000591C0008611C00085D1C0008A91D000831 -:104E3000691C0008F5260008791C00087D1D000883 -:104E400063300000404E0008784A0020884C002063 -:104E50000040000000400000004000000040000052 -:104E6000000001000000020000000200000002003B -:104E70006D61696E0069646C65000000A000902A95 -:104E800000000000AAAAAAAA50000024FFFB00000C -:104E900000770000009009000100000500000000FC -:104EA000AAAAAAA501000080FFCF00000000000010 -:104EB000000000000000000000000000AAAAAAAA4A -:104EC00000000000FFFF00000000000000000000E4 -:104ED0000000000000000000AAAAAAAA000000002A -:104EE000FFFF0000000000000000000000000000C4 -:104EF00000000000AAAAAAAA00000000FFFF00000C -:104F000000000000000000000000000000000000A1 -:104F1000AAAAAAAA00000000FFFF000000000000EB -:104F2000000000000000000000000000AAAAAAAAD9 -:104F300000000000FFFF0000000000000000000073 -:104F400000000000000000000A0000000000000057 -:104F5000030000000000000000000000000000004E -:104F600035470008214700085D4700084947000809 -:104F700055470008414700082D4700081947000819 -:104F8000694700089CB2FF7F01000000000000009C -:104F900052000000000000000000070000000000B8 -:104FA00040420F00FE2A0100D2040000202300200E -:104FB00000000000000000000000000000000000F1 -:104FC00000000000000000000000000000000000E1 -:104FD00000000000000000000000000000000000D1 -:104FE00000000000000000000000000000000000C1 -:104FF00000000000000000000000000000000000B1 -:1050000000000000000000000000000000000000A0 +:1000000000070020F1010008F5230008AD230008D7 +:10001000D5230008AD230008CD230008F301000814 +:10002000F3010008F3010008F3010008E9330008B8 +:10003000F3010008F3010008F3010008F3010008D0 +:10004000F3010008F3010008F3010008F3010008C0 +:10005000F3010008F3010008B9410008E14100087C +:10006000094200083142000859420008F301000823 +:10007000F3010008F3010008F3010008F301000890 +:10008000F3010008F3010008F301000861230008F0 +:100090008D2300089D230008F30100088142000819 +:1000A000F3010008F3010008F3010008F301000860 +:1000B00069430008F3010008F3010008F301000898 +:1000C000F3010008F3010008F3010008F301000840 +:1000D000F3010008F301000855430008F30100088C +:1000E000E5420008F3010008F3010008F3010008ED +:1000F000F3010008F3010008F3010008F301000810 +:10010000F3010008F3010008F3010008F3010008FF +:10011000F3010008F3010008F3010008F3010008EF +:10012000F3010008F3010008F3010008F3010008DF +:10013000F3010008F3010008F3010008F3010008CF +:10014000F3010008F3010008F3010008F3010008BF +:10015000F3010008F3010008F3010008F3010008AF +:10016000F3010008F3010008F3010008F30100089F +:10017000F3010008F3010008F3010008F30100088F +:10018000F3010008F3010008F3010008F30100087F +:10019000F3010008F3010008F3010008F30100086F +:1001A000F3010008F3010008F3010008F30100085F +:1001B000F3010008F3010008F3010008F30100084F +:1001C000F3010008F3010008F3010008F30100083F +:1001D000F3010008F3010008F3010008F30100082F +:1001E000BD0F00080000000000000000000000003B +:1001F00002E000F000F8FEE772B6374880F30888A6 +:10020000364880F3098836483649086040F20000D5 +:10021000CCF200004EF63471CEF200010860BFF35C +:100220004F8FBFF36F8F40F20000C0F2F0004EF628 +:100230008851CEF200010860BFF34F8FBFF36F8F7C +:100240004FF00000E1EE100A4EF63C71CEF20001D4 +:100250000860062080F31488BFF36F8F03F0B6FDAB +:1002600003F048FE4FF055301F491B4A91423CBFF6 +:1002700041F8040BFAE71D49184A91423CBF41F886 +:10028000040BFAE71A491B4A1B4B9A423EBF51F82E +:10029000040B42F8040BF8E700201849184A914271 +:1002A0003CBF41F8040BFAE703F094FD03F070FE45 +:1002B000144C154DAC4203DA54F8041B8847F9E797 +:1002C00000F042F8114C124DAC4203DA54F8041B12 +:1002D0008847F9E703F07CBD0007002000230020D9 +:1002E0000000000808ED00E00001002000070020E9 +:1002F000604C000800230020802300208023002081 +:10030000BC4F0020E0010008E4010008E4010008FF +:10031000E40100082DE9F04F2DED108AC1F80CD052 +:10032000C3689D46BDEC108ABDE8F08F002383F3BF +:1003300011882846A047002003F0B2F9FEE703F039 +:100340003BF900DFFEE70000F8B500F049FE03F0DE +:10035000D7FC074603F026FD064600283DD12B4B6F +:100360009F423AD001339F423AD0294B27F0FF02F7 +:100370009A4238D1F8B200F03FFC354642F2107490 +:1003800000F040FC08B10024254601F015F970B3D7 +:10039000032000F043F80024254636B11D4B9F4250 +:1003A00003D003F0F7FC00242546002003F0B2FC44 +:1003B000194B1B691B041FD40DB100F045F800F068 +:1003C0008DFC02F01FF80546C4B102F01BF8401B7B +:1003D000A04213D900F038F8F3E735460024CFE700 +:1003E00004460125CCE705464FF47A74C8E7B4F516 +:1003F0007A7F08BF0125D0E70024E0E700F0B6FCD3 +:100400004FF47A7003F052F9DEE700BF010007B045 +:10041000000008B0263A09B000040240084B1870EA +:1004200003280CD8DFE800F008050208022000F0DD +:1004300035BE022000F028BE024B00225A607047F1 +:10044000802300208423002010B501F0B5F830B1DE +:10045000204B03221A70204B00225A6010BD1F4B04 +:100460001F4A1C4619680131F8D004339342F9D170 +:1004700062681C4B9A42F1D91B4B9B6803F10063E5 +:1004800003F580339A42E9D203F058FC03F06AFC8A +:10049000002000F0BFFD0220FFF7C0FF134B1A6CD5 +:1004A00000221A64196E1A66196E596C5A64596ED4 +:1004B0005A665B6E72B64FF0E0233021C3F8084DE8 +:1004C000D4E9003281F311889D4683F308881047F0 +:1004D000C4E700BF8023002084230020000001081F +:1004E00020000108FFFF0008002300200038024020 +:1004F000094A136849F2690099B21B0C00FB0133E9 +:100500001360064B186844F2506182B2000C01FB84 +:100510000200186080B270471823002014230020C6 +:1005200010B500211022044600F0D4FD034B03CB8C +:10053000206061601868A06010BD00BF107AFF1FC6 +:100540002DE9F041ADF54E7D0DF134086CAC40F273 +:10055000751207460D460EA80021C8F8001000F0DD +:10056000B9FD4FF4C4720021204600F0B3FD01F044 +:1005700049FF254B4FF47A72B0FBF2F0186093E814 +:100580000700022384E807000DF5E9702382FFF7D6 +:10059000C7FF4FF4A4431D49238406A804F06AFA58 +:1005A000192384F832310DF2E32206AB0DF1300C41 +:1005B0001E4603CE664510605160334602F10802C4 +:1005C000F6D13378137041460122204600F0CEFD6B +:1005D00000230393AB7E029305F11903019380B2CC +:1005E0000123CDE904800093E97E05A3D3E900232C +:1005F000384602F0CFFA0DF54E7DBDE8F08100BF20 +:100600009E6AC421818A46EE8C230020844A000819 +:100610002DE9F0412C4C237ADAB080460D465BBBC5 +:1006200027A9284600F0B2FE0746002842D19DF8CF +:100630009D60C82E3ED801464FF4A662204600F0C9 +:1006400049FD4FF48073C4F8F8314FF40073C4F8D7 +:100650000C334FF44073C4F8203432460DF19E0140 +:1006600004F1090000F024FD26449DF89C307772C7 +:1006700023720BB9EB7E23728122002106AC27A8DE +:1006800000F028FD0122214627A800F0BBFE002330 +:100690000393AB7E029305F1190380B201932823E3 +:1006A000CDE904400093E97E05A3D3E90023404649 +:1006B00002F070FA5AB0BDE8F08100BFAFF30080DD +:1006C00026417272DF25D7B7B0440020F0B5254E21 +:1006D0004FF48A7505FB0065F1B096F8D83085F8BF +:1006E000DC300024D822214685F8E8403AA800F002 +:1006F000F1FC06F1090000F0E5FCD5F8E4308DF8D6 +:10070000F000C2B206AF06F109010DF1F100CDE92A +:100710003A3400F0CDFC394601223AA800F09EFEA2 +:1007200080B2CDE9047008230127CDE9023706F134 +:10073000D803019330230093317A0B4807A3D3E900 +:10074000002302F027FAA04206DD01F05BFEC5F8A7 +:10075000E000384671B0F0BD2046FBE778F6339FE5 +:1007600093CACD8DB0440020A43300202DE9F04180 +:100770001D4D1E4E1E4F86B0284602F037FA034626 +:1007800058B30024CDE90344ADF81440027B8DF842 +:10079000142099684068029403AA03C21B68DFF81A +:1007A000548043F00043029301F02EFE821941F180 +:1007B0000003009402A9384601F0D6F8A04205DDF6 +:1007C000284602F017FA88F80040D5E798F800307C +:1007D000072B05D8013388F8003006B0BDE8F0815A +:1007E000014802F007FAF8E7A433002040420F0066 +:1007F000D8330020E549002070B50D4614461E464A +:1008000002F024F950B9022E10D1012C0ED112A3FE +:10081000D3E90023C5E90023012007E0282C10D0EC +:1008200005D8012C09D0052C0FD0002070BD302C2C +:10083000FBD10BA3D3E90023ECE70BA3D3E90023FF +:10084000E8E70BA3D3E90023E4E70BA3D3E90023F4 +:10085000E0E700BFAFF30080401DA12026812A0BF6 +:1008600078F6339F93CACD8D9E6AC421818A46EE65 +:1008700026417272DF25D7B7F017304A39059E56E8 +:1008800038B505460E4C0021013500F0E5FBA4F813 +:100890002C55B4F82C0500F0C7FB78B1B4F82C0542 +:1008A00000F0D2FB014648B9B4F82C0500F0D4FBA7 +:1008B000B4F82C350133A4F82C35EAE738BD00BF75 +:1008C000B044002010B50A4B0A4A1A6003F5805361 +:1008D00093F860203AB9DC6D2CB1204600F0E4FEBC +:1008E000204604F007F8BDE81040034800F0DCBEE5 +:1008F000D8330020DC4A0008204400202DE9F04FC6 +:100900008FB000AF05460C4602F0A0F8002849D190 +:10091000237E022B1BD1E38A012B18D101F072FD3B +:100920000646FFF7E5FD03464FF4C870DFF8C482C2 +:10093000B3FBF0F206F5167602FB103316FA83F3DA +:10094000C8F80030E37E33B9A34B00221A703C375D +:10095000BD46BDE8F08F07F12401204600F0D4FC2D +:100960000028F4D107F11400FFF7DAFD97F82640CC +:1009700007F11401224607F1270004F005F80028CA +:10098000E2D10F2C08D8944B1C70D8F80030A3F596 +:100990001673C8F80030DAE797F82410284602F0FA +:1009A0004DF8D4E7E38A282B2BD010D8012B23D085 +:1009B000052BCCD1BFF34F8F8849894BCA6802F40D +:1009C000E0621343CB60BFF34F8F00BFFDE7302BD6 +:1009D000BDD1844EE17E327A9142B8D1607E3146FB +:1009E000002291F8DC50854200F0A5800132042AF3 +:1009F00001F58A71F5D1AAE721462846FFF7A0FD47 +:100A0000A5E721462846FFF703FEA0E7B2F8EC5021 +:100A10007B6005F103094FEA99094FEA8902D11D6C +:100A2000C908A8EBC1039D46EB460021584600F0DB +:100A300051FB04F1EE012A463144584600F038FBE0 +:100A40007B6813B9012000F0E5FA96F8D20000F0B7 +:100A5000EBFA044630B9307200F006FB204600F095 +:100A6000D9FAB1E0D6F8D4203AB996F8D200B6F85F +:100A70002C25824201D8FFF703FFD6F8D4202A4460 +:100A8000944208D296F8D200B6F82C250130824262 +:100A900001D8FFF7F5FE70685FFA89F2594600F059 +:100AA00021FB08B9C54679E0726896F8D2002A445D +:100AB0007260D6F8D42005EB0209C6F8D49000F095 +:100AC000B3FA814509D396F8D220D6F8D400013282 +:100AD000001B86F8D220C6F8D400FF2D0FD80024C2 +:100AE000347200F0C1FA204600F094FA00F064FD80 +:100AF0003D4B188108B9FFF7A7FCC54627E7BB683F +:100B000096F8D9000AFB0362FB68D2F8E41082F879 +:100B1000E83001F58061C2F8E030C2F8E410FFF778 +:100B2000D5FDFFF723FE96F8D920013202F003022B +:100B300086F8D920B6E74FF48A7A0AFB02F505F168 +:100B4000EA013144204600F0B5FCF86000287FF44B +:100B5000FEAE3544012285F8E82001F053FCD5F8BB +:100B6000E020D6ED007ADFED216A801A192838BF1F +:100B7000192040F6B832904228BF1046B8EE677A86 +:100B800007EE900AF8EEE77A67EEA67ADFED186ACC +:100B9000E7EE267AFCEEE77AC6ED007A96F8D930D1 +:100BA000BB60BA6873680AFB02F4321992F8E81065 +:100BB00059B1D2F8E4108B42E8463FF427AF002148 +:100BC00082F8E810C2F8E010C5467368064A9B0A2E +:100BD00001331381BBE600BF9D33002000ED00E030 +:100BE0000400FA05B04400208C230020CDCCCC3D7D +:100BF0006666663FA0330020014B1870704700BF47 +:100C00009823002030B54FF000542B4B22689A42B5 +:100C100085B007D003F0D0F8044620BB002420465E +:100C200005B030BD254B627D25481A70237D0372C7 +:100C30004FF48073C0F8F8314FF40073C0F80C33F0 +:100C400000254FF44073C0F820341E49C0F8E4502A +:100C5000C922093000F02CFA2046E022294600F093 +:100C600039FA0124DBE7184A184D136C43F000737E +:100C70001364AA6D164B9A42D0D12B6E013B7E2B8A +:100C8000CCD8144A07CA01AB83E8070018460321F1 +:100C900000F060FC6B6D83424FF00003BED12A6D03 +:100CA0008A4201BFAB65054B2A6E1A7003BF0A4B1F +:100CB000EA6D1A601C46B2E79AAD44C5982300203D +:100CC000B0440020160000200038024000660040BA +:100CD0005041A0B0586600401023002037B51A4D8F +:100CE00000F06AFC02236B71184B288119681848C0 +:100CF000012201F023FA00230193164B16490093B9 +:100D00001648174B4FF4805201F070FE154B1978BE +:100D100011B1124801F092FE01F074FB0446FFF796 +:100D2000E7FB4FF4C873B0FBF3F202FB130304F5C7 +:100D3000167010FA83F00C4B186003F033F808B10A +:100D40000F232B8103B030BD8C2300201023002003 +:100D5000D8330020F90700089C230020A43300208A +:100D6000FD08000898230020A03300202DE9F04F53 +:100D70002DED028B0FF23829D9E90089834C93B00D +:100D80000BAE9FED7E8BFFF7F1FC814FDFF828A2C1 +:100D900000230A93ADF834300B9373604FF0000BCF +:100DA0005B468DED008B01250DF11D0207A938462C +:100DB0008DF81C508DF81DB001F06EF99DF81C30B7 +:100DC000002B40F0A580204601F040FE064600289A +:100DD00045D1704F01F016FB3B6898423FD301F0BC +:100DE00011FB8246FFF784FB4FF4C873B0FBF3F2AC +:100DF00002FB13030AF5167010FA83F03860664F91 +:100E000097F800B0CBF1100ABBF1000F14BF3346C6 +:100E10002B465FFA8AFA0EA88DF82830FFF780FB80 +:100E2000BAF1060F28BF4FF0060A0EAB03EB0B0119 +:100E300052460DF1290000F03BF90AAB0393182349 +:100E400002930AF10102554BD2B2CDE9005304924C +:100E500020464CA3D3E9002301F03EFE3E7001F092 +:100E6000D1FA4F4A4F4D1368C31AB3F57A7F2ED388 +:100E7000106001F0C9FA02460B46204601F0C4FE9C +:100E8000204601F0E3FD10B32B7A474E002B14BF30 +:100E900003230223737101F0B5FA0EAF4FF47A7396 +:100EA0000122B0FBF3F039463060304600F004FA1E +:100EB000182302933D4B019380B240F25513CDE9C4 +:100EC0000370009342464B46204601F005FE2B7A04 +:100ED00093B101F097FA002607464FF48A7A95F805 +:100EE000D900304400F003000AFB005393F8E820D7 +:100EF00092B30136042EF2D1C82002F0D7FB2B7A30 +:100F0000002B7FF43DAF13B0BDEC028BBDE8F08F3A +:100F1000DAF8143083F48063CAF81430594610228A +:100F20000EA800F0D7F80DF11E0308AA0AA938464A +:100F300000F01AFE96E803000FAB83E803009DF86B +:100F400034308DF844300A9B0E930EA9DDE9082356 +:100F5000204602F02DF821E7D3F8E02042B12B68BB +:100F6000FA2B38BFFA23BA1A0533B2EB430FC0D3BA +:100F7000FFF7ACFB0028BCD1BEE700BF00000000BB +:100F800000000000401DA12026812A0BA433002070 +:100F9000D8330020A03300209D3300209C33002054 +:100FA000E0490020B04400208C230020E4490020C8 +:100FB000F1C6A7C1D068080F0000024008B5054877 +:100FC00000F06EFEBDE80840034A0449002003F02B +:100FD0008BBC00BFD8330020204A0020C508000881 +:100FE00070B502F037FD094E094D308000242868A5 +:100FF0003388834208D902F027FD2B68044401336B +:10100000B4F5803F2B60F2D370BD00BF144A0020BE +:10101000E849002002F0CEBD00F10060920000F52A +:10102000803002F05DBD0000054B1A68054B1B883F +:101030009B1A834202D9104402F006BD002070477B +:10104000E8490020144A0020024B1B68184402F0B3 +:1010500003BD00BFE8490020024B1B68184402F0A2 +:1010600013BD00BFE8490020064991F8243033B190 +:101070000023086A81F824300822FFF7CDBF012041 +:10108000704700BFEC490020022802BF024B4FF01E +:1010900080629A61704700BF00000240022802BFD0 +:1010A000024B4FF480629A61704700BF000002401B +:1010B00010B50023934203D0CC5CC4540133F9E74C +:1010C00010BD000003460246D01A12F9011B002988 +:1010D000FAD1704702440346934202D003F8011B41 +:1010E000FAE770472DE9F8431F4D144695F8242080 +:1010F0000746884652BBDFF870909CB395F82430C1 +:101100002BB92022FF2148462F62FFF7E3FF95F815 +:101110002400C0F10802A24228BF2246D6B24146AE +:10112000920005EB8000FFF7C3FF95F82430A41B65 +:101130001E44F6B2082E17449044E4B285F82460A9 +:10114000DBD1FFF791FF0028D7D108E02B6A03EB32 +:1011500082038342CFD0FFF787FF0028CBD1002046 +:10116000BDE8F8830120FBE7EC4900202DE9F047BA +:101170000D46044600219046284640F27912FFF7BA +:10118000A9FF234620220021284601F0B3FE231D9B +:1011900002222021284601F0ADFE631D03222221F8 +:1011A000284601F0A7FEA31D03222521284601F0B1 +:1011B000A1FE04F1080310222821284601F09AFE1E +:1011C00004F1100308223821284601F093FE04F1AF +:1011D000110308224021284601F08CFE04F112037D +:1011E00008224821284601F085FE04F1140320223C +:1011F0005021284601F07EFE04F1180340227021A0 +:10120000284601F077FE04F120030822B021284689 +:1012100001F070FE04F121030822B821284601F0F4 +:1012200069FE04F12207C0263B46314608222846C3 +:10123000083601F05FFEB6F5A07F07F10107F3D194 +:1012400004F1320308223146284601F053FE0027FC +:1012500004F1330A94F832304FEAC7099F4209F586 +:10126000A47615D3B8F1000F08D1314604F599736F +:101270000722284601F03EFE09F24F16274694F851 +:1012800032213B1B93420CD3F01DC008BDE8F08710 +:101290000AEB070308223146284601F02BFE0137EE +:1012A000D8E707F2331331460822284601F022FE20 +:1012B00008360137E3E7000013B50446084600216D +:1012C00001602346C0F803102022019001F012FEB5 +:1012D0000198231D0222202101F00CFE0198631DBC +:1012E0000322222101F006FE0198A31D03222521DD +:1012F00001F000FE019804F108031022282101F0FA +:10130000F9FD072002B010BDF7B50023047F00915E +:101310000E4607221946054601F0B0FC731C0093E7 +:10132000012200230721284601F0A8FCC4B9B31C00 +:101330000093052223460821284601F09FFC0D2436 +:101340003746B278BB1B934211D32B7FA88A073450 +:10135000E408BBB9844294BF0020012003B0F0BD73 +:10136000AB8ADB00083BDB08B3700824E8E7FB1C12 +:101370000093214600230822284601F07FFC083410 +:101380000137DEE7201A18BF0120E7E7F7B5002391 +:10139000047F00910E4608221946054601F06EFCB6 +:1013A000731CC4B90822009311462346284601F055 +:1013B00065FC1024012372785F1C013B934211D31A +:1013C0002B7FA88A0734E408BBB9844294BF00206D +:1013D000012003B0F0BDAB8ADB00083BDB08737073 +:1013E0000824E7E7F3190093214600230822284642 +:1013F00001F044FC08343B46DDE7201A18BF012009 +:10140000E7E70000F8B50E460546144600218122A4 +:101410003046FFF75FFE2B4608220021304601F0E0 +:1014200069FD7CB96B1C07220821304601F062FD82 +:101430000F2401236A785F1C013B934204D3E01D13 +:10144000C008F8BD0824F4E7EB192146082230460D +:1014500001F050FD08343B46ECE70000F8B50E46BD +:10146000054614460021CE223046FFF733FE2B46B8 +:1014700028220021304601F03DFD7CB905F108032A +:1014800008222821304601F035FD30242F462A7AE3 +:101490007B1B934204D3E01DC008F8BD2824F5E768 +:1014A00007F1090321460822304601F023FD0834E4 +:1014B0000137ECE7F7B5047F00910E4601231022B7 +:1014C0000021054601F0DAFBC4B9B31C00930922E0 +:1014D00023461021284601F0D1FB19243746728893 +:1014E000BB1B9A4211D82B7FA88A0734E408BBB9EA +:1014F000844294BF0020012003B0F0BDAB8ADB0022 +:10150000103BDB0873801024E8E73B1D0093214665 +:1015100000230822284601F0B1FB08340137DEE73A +:10152000201A18BF0120E7E730B5094D0A4491425F +:101530000DD011F8013B5840082340F30004013B53 +:101540002C4013F0FF0384EA5000F6D1EFE730BDE2 +:101550002083B8EDF7B54FF0FF33DFF854C0DFF864 +:1015600054E000EB81011A4688421CD050F8044B2D +:10157000019401AF042417F8015B82EA0562082593 +:10158000DB18164605F1FF355241002EBCBF83EA39 +:101590000C0382EA0E0215F0FF05F1D1013C14F0B4 +:1015A000FF04E8D1E0E7D843D14303B0F0BD00BF6A +:1015B0009336EAA9EBE1F042F7B5354A1068516875 +:1015C0006B4603C36A4633493348082303F0ECF9FA +:1015D000044688BB0A25314A106851686B4603C32C +:1015E0006A462F492C48082303F0DEF904460028F8 +:1015F00045D00369B3F5E02F41D8B0F86620522AF0 +:101600003DD1284A024402F15C018B4237D35C3B56 +:10161000214900209E1AFFF787FF3246074604F152 +:1016200064010020FFF780FFA3689F4227D1E36891 +:10163000984208BF002522E00369B3F5E02F25D8C2 +:10164000428B522A20D1174A024402F110018B42E8 +:1016500018D3103B104900209D1AFFF765FF2A465A +:10166000064604F118010020FFF75EFFA3689E42C2 +:1016700002D1E368984201D00D25ACE70025284649 +:1016800003B0F0BD1025A6E70C25A4E70B25A2E7C3 +:10169000A04A0008DCFF060000000108A94A000873 +:1016A00090FF06000800FFF710B5037C044613B94D +:1016B000006803F061F9204610BD00000023BFF36D +:1016C0005B8FC360BFF35B8FBFF35B8F8360BFF340 +:1016D0005B8F7047BFF35B8F0068BFF35B8F704712 +:1016E00070B505460C30FFF7F5FF05F10806044616 +:1016F0003046FFF7EFFFA04206D930466D68FFF78E +:10170000E9FF2544281A70BD3046FFF7E3FF201A91 +:10171000F9E7000070B50546406898B105F108008A +:10172000FFF7D8FF05F10C0604463046FFF7D2FF5D +:101730008442304694BF6D680025FFF7CBFF013C23 +:101740002C44201A70BD000038B50C460546FFF742 +:10175000C7FFA04210D305F10800FFF7BBFF044408 +:101760006868B4FBF0F100FB1144BFF35B8F01200C +:10177000AC60BFF35B8F38BD0020FCE72DE9F04182 +:10178000144607460D46FFF7C5FF844228BF0446AE +:10179000D4B1B84658F80C6B4046FFF79BFF304475 +:1017A000286040467E68FFF795FF331A9C4203D8B5 +:1017B0006C600120BDE8F0816B60A41B3B68AB60EE +:1017C0002044E8600220F5E72046F3E738B50C46F0 +:1017D0000546FFF79FFFA04210D305F10C00FFF76D +:1017E00079FF04446868B4FBF0F100FB1144BFF3D7 +:1017F0005B8F0120EC60BFF35B8F38BD0020FCE7FE +:101800002DE9FF41884669460746FFF7B7FF6C465A +:1018100006B204EBC6060025B44209D0626820680F +:1018200008EB0501FFF744FC636808341D44F3E747 +:1018300029463846FFF7CAFF284604B0BDE8F081C4 +:10184000F8B505460C300F46FFF744FF05F10806D2 +:1018500004463046FFF73EFFA042304688BF6C6822 +:10186000FFF738FF201A386020B130462C68FFF7A8 +:1018700031FF2044F8BD000073B5144606460D46FE +:10188000FFF72EFF844228BF04460190DCB101A976 +:101890003046FFF7D5FF019B33B93268C5E9023303 +:1018A000C5E9002401200CE09C4238BF0194286067 +:1018B000019868608442F5D93368AB60241AEC6003 +:1018C000022002B070BD2046FBE700002DE9FF4179 +:1018D0000F466946FFF7D0FF6C4600B204EBC00527 +:1018E0000026AC4209D0D4F8048054F8081BB8197B +:1018F0004246FFF7DDFB4644F3E7304604B0BDE85F +:10190000F081000038B50546FFF7E0FF04460146C8 +:101910002846FFF719FF204638BD000010B40268C2 +:1019200054681A4623465DF8044B18470020704758 +:101930000020704770470000002070470E2070475D +:1019400000F5805090F8C800C0F3400070470000D8 +:1019500000F5805090F9D0007047000000F58050ED +:10196000C0F8CC1001207047F7B50C68BDF82070A6 +:1019700014F0005470D10D7B082D6DD8302585F3FF +:1019800011884569AE6876010CD4AC68240108D48E +:10199000AC6814F080545DD184F31188204603B004 +:1019A000F0BD01240E6804F1180C002EB8BFF6003B +:1019B0004FEA0C1CB4BF46F00406760545F80C60EF +:1019C0000E680FFA84FC16F0804F18BF05EB0C1E52 +:1019D00005EB0C1C1EBFDEF8806146F00206CEF857 +:1019E00080610E7BCCF8846105EB04158E68C5F828 +:1019F0008C614E68C5F88861DCF8805145F00105BE +:101A0000CCF8805100EB441641F268052E4405EBFA +:101A100044150544C6E9002308350E4601F10C0CB7 +:101A200056F804EB45F804EB6645F9D18434368862 +:101A30002E8000EB441407F00305267926F00B06F0 +:101A400035432571002484F31188009700F0FCFCD5 +:101A50000120A4E70224A5E74FF0FF309FE7000034 +:101A600013B500F580540191E06DFFF753FE1F2878 +:101A70000AD90199E06D2022FFF7C2FEA0F12003F0 +:101A80005842584102B010BD0020FBE708B5302392 +:101A900083F3118800F58050C06DFFF70FFE00231F +:101AA00083F3118808BD0000002202608281426039 +:101AB0008260704710B500220023C0E90023002394 +:101AC000044603810C30FFF7EFFF204610BD0000F5 +:101AD000F0B5054600F580500C4690F8C83013F07C +:101AE000040FC3F3800108BF114661F3820304F1C0 +:101AF000840680F8C83005EB461389B01B79D807F7 +:101B00002ED57AB319072DD46846FFF7D3FF05EB1E +:101B1000441303F5835303F1180703AA103318681D +:101B20005968144603C40833BB422246F7D11868EB +:101B300020609B88A380DDE90E23CDE900230123EB +:101B4000ADF808302B686946DB6B2846984705EBF3 +:101B500046152B791A075CBF43F008032B7101E08F +:101B6000002AF4D109B0F0BD2DE9F0479A4688B0BB +:101B7000074688469146302383F3118807F5805441 +:101B80006846FFF797FFE06DFFF7AAFD1F282AD9E7 +:101B9000E06D20226946FFF7B5FE202823D103AD72 +:101BA000444605AB2E4603CE9E422060616035461A +:101BB00004F10804F6D130682060B388A380DDE921 +:101BC0000023C9E90023BDF80830AAF8003000233B +:101BD00083F3118853464A464146384608B0BDE86B +:101BE000F04700F01FBC002080F3118808B0BDE86A +:101BF000F08700002DE9F84F0023C0E90133254BA1 +:101C0000044640F8183B0F46FFF74EFF04F128004A +:101C1000FFF750FF04F1480804F5825546460835A1 +:101C200030462036FFF746FFAE42F9D104F5805525 +:101C30004FF480534FF00009C5E91339C5F84880C7 +:101C40000123EE6504F5875804F58456C5F85490D1 +:101C500085F8583085F86030083608F108084FF0EC +:101C6000000A4FF0000B46E908ABA6F11800FFF799 +:101C70001BFF203646F8289C4645F4D185F8D070E5 +:101C800017B1054800F0B8FB044B63612046BDE87E +:101C9000F88F00BFDC4A0008B44A00080064004026 +:101CA00010B5044B197804464A1C1A70FFF7A2FFBE +:101CB000204610BD1C4A00202DE9F047002950D0D5 +:101CC000294B2A4FB7FBF1F599428CBF0A23112308 +:101CD000581EB5FBF3FC03FB1C53C4B22BB1022806 +:101CE0000346F5D80020BDE8F0870CF1FF36B6F5C5 +:101CF000806FF7D2C4EBC40E0EF103034FEAE30981 +:101D0000C3F3C703A4EB030809F1010A4FF47A7582 +:101D10005FFA88F009FB05555AFA88F8B5FBF8F523 +:101D2000B5F5617FC1BF0EF1FF33C3F3C703E01AFE +:101D3000C0B25C1C50FA84F40CFB04F4B7FBF4F45E +:101D4000A142CFD1013BDBB20F2BCBD80138C0B2BF +:101D50000728C7D80021107116809170D370012018 +:101D6000C1E70846BFE700BF3F420F0040787D0152 +:101D700070B505460E464FF47A746B695B6803F0E4 +:101D80000103B34207D04FF47A7001F08FFC013C9D +:101D9000F3D1204670BD0120FCE7000030B5426958 +:101DA000936913F0700F16D000230B4C936103F16D +:101DB000840200EB421211794D0709D5890707D536 +:101DC000416954F823508D60117941F0040111717B +:101DD0000133032BEBD130BDC84A000873B51D4653 +:101DE000436916469A68D207044609D59A680121C4 +:101DF0009960C2F34002CDE900650021FFF768FE5B +:101E000063699A68D1050BD59A684FF4807199601F +:101E1000C2F34022CDE9006501212046FFF758FEBC +:101E200063699A68D2030BD59A684FF48031996040 +:101E3000C2F34042CDE9006502212046FFF748FE8B +:101E400004F58053D3F8CC0010B103681B699847A0 +:101E5000204602B0BDE87040FFF7A0BFF8B50446C9 +:101E60004669002972D106F10C073868800770D0E6 +:101E700006EB01153868D5F8B00110F0040FD5F85D +:101E8000B0011ABFC00840F00040400DA061D5F875 +:101E9000B0C11CF0020F1CBF40F08040A061D5F81B +:101EA000B40106EB011100F00F0084F82400D1F812 +:101EB000B8012077D1F8B801000A6077D1F8B801ED +:101EC000000CA077D1F8B801000EE077D1F8BC0182 +:101ED00084F82000D1F8BC01000A84F82100D1F870 +:101EE000BC01000C84F82200D1F8BC11090E84F862 +:101EF00023103821396004F1340004F1180104F191 +:101F0000240551F8046B40F8046BA942F9D1098803 +:101F10000180C4E90A2321460023238651F8283B87 +:101F20002046DB6B984704F5805393F8C820D3F81C +:101F3000CC0042F0040283F8C82010B103681B698A +:101F400098472046BDE8F840FFF728BF06F1100784 +:101F50008BE7F8BD10B5044600F056FA02460B4672 +:101F600052EA030102D0013A63F100030449086810 +:101F700020B12146BDE81040FFF770BF10BD00BF83 +:101F8000184A0020F0B5302181F31188DFF848C0ED +:101F900000F583510831002404F1840500EB451558 +:101FA0002E7977070ED4F6060CD5D1E90076974244 +:101FB0009E4107D246695CF82470B7602E7946F0DE +:101FC00004062E710134032C01F12001E4D1002319 +:101FD00083F31188F0BD00BFC84A000808B530235C +:101FE00083F31188FFF7DAFE002383F3118808BD1D +:101FF000F8B543690546986800F0E050B0F1E05F3D +:102000000F4621D0F8B1302383F3118805F58354AE +:102010001034002606F1840305EB43131B791A07DD +:1020200006D50136032E04F12004F3D1012007E088 +:102030005B07F6D42146384600F040FA0028F0D17C +:10204000002383F31188F8BD0120FCE708B5302395 +:1020500083F3118800F58050C06DFFF741FB00232A +:1020600083F3118843090CBF0120002008BD000044 +:10207000F8B51D46002313700F4606461446FFF7B9 +:10208000E5FF80F00100387025B129463046FFF7A2 +:10209000AFFF2070F8BD00002DE9B8410C46154691 +:1020A0001F46804600F0B0F90B462178024609B978 +:1020B000287850B14046FFF765FFFFF78FFF3B469A +:1020C0002A462146FFF7D4FF0120BDE8B881000071 +:1020D00070B5302686F31188174B1A6C42F00072E7 +:1020E0001A641A6A42F000721A621A6A22F00072C6 +:1020F0001A62002383F3118800F5805494F8C830E5 +:1021000013F0010516D1A9B186F31188032113201C +:1021100001F0C8F90321142001F0C4F903211520AE +:1021200001F0C0F994F8C83043F0010384F8C830D6 +:1021300085F3118870BD00BF003802402DE9F047DB +:1021400000F5805588B095F8D030012B04468846BC +:10215000164600F28180814F57F823200AB947F8CC +:102160002300D7F800A0C4F80C802674BAF1000F41 +:1021700064D095F8D030012B70D001212046FFF7B4 +:10218000A7FF302383F311886269136823F00203E9 +:1021900013606269136843F00103136063690027E9 +:1021A0005F6187F3118801212046FFF7E1FD0028D8 +:1021B00000F09580E86DFFF781FA04F58359BA467F +:1021C00009F10809202200216846FEF783FF02A8D2 +:1021D000FFF76AFCCDF818A06A4609EB07030DF17A +:1021E000180E9446BCE80300F44518605960624636 +:1021F00003F10803F5D1DCF80000186020379CF8E3 +:1022000004201A71602FDDD195F8C8306FF3820376 +:10221000002785F8C8306A4641462046ADF8007070 +:10222000ADF802708DF80470FFF746FD636948BB96 +:102230004FF400421A6008B0BDE8F08741F2D800C0 +:1022400002F05AFB814610B15146FFF7D3FCC7F8A4 +:102250000090B9F1000F8CD10020ECE738680368DA +:102260001B6B98470146002887D13868FFF730FF7D +:102270003868036832465B684146984700287FF417 +:102280007CAFE9E761221A609DF802309DF80320D7 +:102290001B06120402F4702203F040731343BDF8CE +:1022A0000020C2F3090213439DF804201205022EF8 +:1022B00002F4E0020CBF4FF00041002113436269B9 +:1022C0000B43D361636913225A616269136823F077 +:1022D0000103136039462046FFF74AFD08B96369D8 +:1022E000A6E795F8D03093BB6169D1F8002242F09F +:1022F0000102C1F800226169D1F8002222F47C5267 +:1023000022F00E02C1F800226169D1F8002242F4E5 +:102310006062C1F800226269C2F814326269C2F8D0 +:102320000432626941F6FF71C2F80C126269C2F8A8 +:1023300040326269C2F8443263690122C3F81C2248 +:102340006269D2F8003223F00103C2F8003295F836 +:10235000C83043F0020385F8C8306CE7184A002003 +:1023600008B500F051F850EA0103024602D0421EBF +:1023700061F10001044B186810B10B46FFF72EFD08 +:10238000BDE8084001F064B8184A002008B50020F4 +:10239000FFF7E0FDBDE8084001F05AB808B501209C +:1023A000FFF7D8FDBDE8084001F052B800B59BB07A +:1023B000EFF3098168226846FEF77AFEEFF30583A2 +:1023C000014B9B6BFEE700BF00ED00E008B5FFF797 +:1023D000EDFF000000B59BB0EFF30981682268466D +:1023E000FEF766FEEFF30583014B5B6BFEE700BF74 +:1023F00000ED00E0FEE700000FB408B5029801F020 +:1024000005F9FEE701F01ABC01F0FCBB13B56C4600 +:1024100084E80600031D94E8030083E8050001201A +:1024200002B010BD73B58568019155B11B885B077B +:1024300007D4D0E900369B6B9847019AC1B2304669 +:10244000A847012002B070BDF0B5866889B0054686 +:102450000C465EB1BDF838305B070AD4D0E90037CE +:102460009B6B98472246C1B23846B047012009B05D +:10247000F0BD00220023CDE900230023ADF8083091 +:102480000A4603AB01F10806106851681C4603C4F4 +:102490000832B2422346F7D1106820609288A280A9 +:1024A000FFF7B2FF0423ADF808302B68CDE9000137 +:1024B000DB6B694628469847D8E7000030B50368CB +:1024C0000968DD0FB5EBD17F23F0604421F0604255 +:1024D0004FEAD1700BD0002BB8BFA40C0029B8BFB5 +:1024E000920C944202D034BF0120002030BD9442AF +:1024F00005D1C1F38070C3F380738342F6D1944257 +:102500002CBF00200120F1E72DE9F041456A15B903 +:102510004162BDE8F0814B6823F06047C3F38A460F +:102520004FEAD37EC3F3807816EA230638BF3E46CF +:10253000AC462B465A68BEEBD27F22F060440AD0EC +:10254000002A18DAA40CB44217D19D420FD10D60B5 +:10255000DEE71346EEE7A74207D102F08044C2F35C +:10256000807242450BD054B1EFE708D2EDE7CCF8CA +:1025700000100B60CDE7B44201D0B442E5D81A6830 +:102580009C46002AE5D11960C3E700002DE9F04719 +:10259000089D01F007044FEAD508224405F007051D +:1025A00000EBD1004FF47F49944201D1BDE8F087A0 +:1025B00004F0070705F0070A57453E4638BF564660 +:1025C000C6F10806111B8E4228BF0E46E10808EB33 +:1025D000D50E415C13F80EC0B94029FA06F721FA6E +:1025E0000AF1FFB28CEA010147FA0AF739408CEA96 +:1025F000010C03F80EC034443544D5E780EA0120CD +:10260000082341F2210201B24000002980B203F107 +:10261000FF33B8BF504013F0FF03F4D17047000000 +:1026200038B50C468D18A54200D138BD14F8011BF1 +:10263000FFF7E4FFF7E7000042684AB11368436020 +:102640004389818901339BB29942438138BF838199 +:102650001046704770B588B0202204460D46684683 +:102660000021FEF737FD20460495FFF7E5FF0246FF +:1026700058B16B46054608AE1C4603CCB4422860F0 +:102680006960234605F10805F6D1104608B070BD13 +:10269000082817D909280CD00A280CD00B280CD0F0 +:1026A0000C280CD00D280CD00E2814BF4020302050 +:1026B00070470C2070471020704714207047182076 +:1026C0007047202070470000082817D90C280CD923 +:1026D00010280CD914280CD918280CD920280CD96A +:1026E00030288CBF0F200E207047092070470A2029 +:1026F00070470B2070470C2070470D20704700007A +:102700002DE9F843078C072F04461ED9D0E902981B +:1027100000254FF6FF73C5F12006A5F1200029FA28 +:1027200005F108FA06F628FA00F031430143C9B270 +:102730001846FFF763FF0835402D0346EBD1E169EA +:102740003A46BDE8F843FFF76BBF4FF6FF70BDE8B0 +:10275000F883000010B54B6823B9CA8A63F30902F5 +:10276000CA8210BD04691A681C600361C38A013BF8 +:10277000C3824A60EFE700002DE9F84F1D46CB8A7F +:102780000F46C3F309010529814692460B4630D016 +:102790000020AAB207F11A049EB2042E1FFA80F894 +:1027A0000FD8904503F1010306D3FB8A0A4462F374 +:1027B0000903FB8201201AE01AF80060E654013098 +:1027C000EAE79045F1D2A1F1050B1C237C68BBFB25 +:1027D000F3F203FB12BB1FFA8BF6002C45D14846DF +:1027E000FFF72AFF044638B978606FF00200BDE8B1 +:1027F000F88F4FF00008E6E7002606607860ADB27B +:102800004FF0000B454510D90AEB0803221D13F8C1 +:10281000011B9155B1B208F101081B291FFA88F874 +:102820002BD0454506F10106F1D8FB8AC3F3090216 +:10283000154465F30903BCE7013292B21C462368D4 +:10284000002BF9D16B1F0B441C21B3FBF1F30133B7 +:102850009BB29A42D3D2BBF1000FD0D14846FFF7CA +:10286000EBFE20B9C4F800B0BFE70122E7E7C0F8EB +:1028700000B05E4620600446C1E74545D5D94846CC +:10288000FFF7DAFE08B92060AFE7C0F800B0002615 +:1028900020600446B6E700002DE9F04F2DED028BD5 +:1028A0001C4683B05B69019207468846002B00F006 +:1028B0009A80238C2BB1E269002A00F09480072BC8 +:1028C00035D807F10C00FFF7B7FE054638B96FF0B1 +:1028D0000205284603B0BDEC028BBDE8F08F142240 +:1028E0000021FEF7F7FB228CE16905F10800FEF7F5 +:1028F000DFFB208C013080B2FFF7E6FEFFF7C8FE59 +:10290000013880B22084013028746369228C1B78DE +:102910002A4403F01F0363F03F0348F000411372A1 +:10292000384669602946FFF7EFFD0125D1E700F140 +:102930000C034FF0000908EE103A4FF0800A4E46A3 +:102940004D4618EE100AFFF777FE83460028BED0EA +:1029500014220021FEF7BEFB002E3AD1019BABF8FA +:10296000083002220BF1080E1FFA82FC0CF1010064 +:10297000BCF1060F218C80B201D88E422BD3FFF719 +:10298000A3FEFFF785FE62691278013802F01F028C +:102990008E4208BF4FF0400A42EA49121BFA80F10A +:1029A0004AEA020A013048F0004281F808A08BF898 +:1029B0001000CBF8042059463846FFF7A5FD238CBC +:1029C0000135B3422DB289F001094FF0000AB8D1A8 +:1029D0007FE70022C6E7E169895D0EF80210013643 +:1029E000B6B20132C0E76FF0010572E7F8B51546DF +:1029F0000E463022002104461F46FEF76BFB069B65 +:102A00006360B5F5001F079BA76034BF6A094FF6E6 +:102A1000FF72A36297B2E66104F1100000239A42AC +:102A200006D800230360A782E3822383E360F8BD16 +:102A30000660013330462036F1E7000003781BB909 +:102A40004BB2002BC8BF0170704700000078704780 +:102A5000F8B50C46C969074611B9238C002B37D14C +:102A6000257E1F2D34D8387828BB228C072A2CD8F5 +:102A7000268A36F003032BD14FF6FF70FFF7D0FD07 +:102A800020F001003102400441EA0561400C41EAB6 +:102A900040254FF6FF72234629463846FFF7FCFED5 +:102AA000002807DD626913780133DBB21F2B88BF72 +:102AB00000231370F8BD218A2D0645EA0125054340 +:102AC0002046FFF71DFE0246E5E76FF00300F1E741 +:102AD0006FF00100EEE7000070B58AB004461646BC +:102AE0000021282268461D46FEF7F4FABDF838306A +:102AF000ADF810300F9B05939DF840308DF81830DD +:102B0000119B07936946BDF84830ADF82030204648 +:102B1000CDE90265FFF79CFF0AB070BD2DE9F041D9 +:102B2000D36905460C4616460BB9138C5BBB377E42 +:102B30001F2F28D895F80080B8F1000F26D0304616 +:102B4000FFF7DEFD3378210241EAC33141EA080193 +:102B5000338A41EA076141EA03410246334641F0C4 +:102B600080012846FFF798FE00280ADD3378012B04 +:102B700007D1726913780133DBB21F2B88BF0023A2 +:102B80001370BDE8F0816FF00100FAE76FF0030009 +:102B9000F7E70000F0B58BB004460D46174600215C +:102BA000282268461E46FEF795FA9DF84C305A1EBC +:102BB000534253418DF800309DF84030ADF810304D +:102BC000119B05939DF848308DF81830149B07939E +:102BD0006A46BDF85430ADF8203029462046CDE98C +:102BE0000276FFF79BFF0BB0F0BD0000406A00B11A +:102BF00004307047436A1A68426202691A600361CE +:102C0000C38A013BC38270472DE9F041D0F8208090 +:102C1000194E14461D464146002709B9BDE8F0810A +:102C2000D1E90223A21A65EB0303964277EB030373 +:102C30001ED2036A8B420DD1FFF78CFD036A1B681D +:102C4000036203690B60C38A0161016A013BC382AD +:102C50008846E2E7FFF77EFD0B68C8F8003003699D +:102C60000B60C38A0161013BC382D8F80010D4E72E +:102C700088460968D1E700BF80841E002DE9F04F27 +:102C80008BB00D46DDF8509014469B4680460028D8 +:102C900000F01981B9F1000F00F01581531E3F2B90 +:102CA00000F21181012A03D1BBF1000F40F00B812A +:102CB0000023CDE90833B8F81430B5EBC30F4FEA61 +:102CC000C30703D300200BB0BDE8F08F2B199F4240 +:102CD000D8F80C303ABF7F1BFFB227461BB9D8F893 +:102CE0001030002B7AD0272D4ED8C5F12806B742D8 +:102CF0004FF000032CBFF6B23E4600932946D8F8A9 +:102D0000080008AB3246FFF741FCA7EB060A354442 +:102D10005FFA8AFAB8F8143003F10053053BDB0080 +:102D20000493D8F80C3003932821039B13B1BAF114 +:102D3000000F2CD1D8F8100040B1BAF1000F05D027 +:102D4000009608AB5246691AFFF720FC38B2002FF4 +:102D5000B8D066070AD00AAB03EBD401624211F87F +:102D6000083C02F00702134101F8083C082C3CD94A +:102D7000102C40F2B580202C40F2B780BBF1000F40 +:102D800000F09C80082334E0BA460026C2E7049B8A +:102D9000E02B28BFE02306930B44AB42059314D9E4 +:102DA0005A1B03980096924534BF5246D2B2691A14 +:102DB00008AB04300792FFF7E9FB079A1644AAEB29 +:102DC000020A1544F6B25FFA8AFA049B069A05993C +:102DD0009B1A0493039B1B680393A6E70093D8F800 +:102DE000080008AB3A462946AEE7BBF1000F13D006 +:102DF0000123B4EBC30F6CD0082C12D89DF82030FF +:102E0000621E23FA02F2D50706D54FF0FF3202FA0E +:102E100004F423438DF820309DF8203089F80030E9 +:102E200051E7102C12D8BDF82030621E23FA02F2AE +:102E3000D10706D54FF0FF3202FA04F42343ADF870 +:102E40002030BDF82030A9F800303CE7202C0FD806 +:102E50000899631E21FA03F3DA0705D54FF0FF3214 +:102E600002FA04F40C430894089BC9F800302AE7DE +:102E7000402C2BD0DDE90865611EC4F12102A4F1CC +:102E8000210326FA01F105FA02F225FA03F31143B0 +:102E90001943CB0712D50122A4F12003C4F120016C +:102EA00002FA03F322FA01F1A240524243EA01037B +:102EB00063EB430332432B43CDE90823DDE90823C9 +:102EC000C9E90023FFE66FF00100FCE66FF008009F +:102ED000F9E6082CA0D9102CB3D9202CEED8C3E7E2 +:102EE000BBF1000FADD0022383E7BBF1000FBBD0D5 +:102EF00004237EE730B5012A144638BF0124402C54 +:102F000085B028BF40240025012ACDE9025518D8F4 +:102F10001B788DF8083063070AD004AB03EBD405A7 +:102F2000624215F8083C02F00702934005F8083C9D +:102F3000009103462246002102A8FFF727FB05B0B7 +:102F400030BD082AE4D9102A03D81B88ADF8083010 +:102F5000E1E7202A8DBFD3E900231B680293CDE966 +:102F60000223D8E710B5CB681BB98B600B618B824D +:102F700010BD04691A681C600361C38A013BC382E7 +:102F8000CA60F0E703064CBFC0F3C03002207047B0 +:102F900008B50246FFF7F6FF022806D15306C2F332 +:102FA0000F2001D100F0030008BDC2F30740FBE78A +:102FB0002DE9F04F93B0CDE903230A68044610468B +:102FC000FFF7E0FF022814BFC2F306260026002AFE +:102FD0000D46824680F2F28112F0C04940F0EE8147 +:102FE000097B002900F0EA81022803D02378B3424C +:102FF00040F0E781C2F304630693104602F07F03BA +:103000000593FFF7C5FF059B29444FEA834848EA2B +:103010000A4848EA4668CE7800230022CDE9082312 +:10302000F309834648EA0008029367D0059B0093A2 +:1030300002466768534608A92046B847002800F0B2 +:10304000C381276A4FB9414604F10C00FFF702FB28 +:10305000074690B96FF0020054E03B6998450DD0E7 +:103060003F68002FF9D1414604F10C00FFF7F2FA56 +:1030700007460028EED0236A3B60276297F817C006 +:1030800006F01F08CCF3840CACEB08001FFA80FE9E +:103090000028B8BF0EF12000A8EB0C031FFA83FE36 +:1030A000D7E90221B8BF00B2002B0793BEBF0EF1D3 +:1030B00020031BB2079352EA010338D0039BDFF8C9 +:1030C00024E39A1A049B4FF0000C63EB0101964530 +:1030D0007CEB01032BD36B7B97F81AE0734519D176 +:1030E000029B002B78D0012821DC7868F8B9DFF842 +:1030F000F0C2944570EB010316D337E0276A27B975 +:103100006FF00C0013B0BDE8F08F3B699845B5D067 +:103110003F68F4E7B24890427CEB010301D3002002 +:10312000F0E7029B002BFAD0079B0F2B17DCFA7DF0 +:10313000B30002F0030203F07C031343FB7539462E +:103140002046FFF707FB6B7BBB76029B3BB9FB7D01 +:10315000C3F38402013262F38603FB75D0E76A7B16 +:10316000BB7E9A42DBD1029B002B35D0B309022BE8 +:1031700032D0039BBB60049BFB60142200210DA88E +:10318000FDF7A8FF039B0A93049B0B932B1D0C9345 +:103190002B7BADF83EB0013BDBB2ADF83C30069B7B +:1031A0008DF84230059B8DF8433094F82C308DF823 +:1031B00040A083F001038DF844308DF84180A3686E +:1031C0000AA920469847FB7DC3F38403013303F02B +:1031D0001F039B02FB82A2E7FB7DC6F34012B2EB0A +:1031E000D31F40F0F480C3F38403434540F0F280E2 +:1031F000029A2B7BB609002A4DD0F2075DD4032B2F +:1032000040F2EB80039BBB60049BFB602B7BAE1DFD +:10321000033BDBB23246394604F10C00FFF7ACFA4F +:1032200000280CDA39462046FFF794FAFB7DC3F3F9 +:103230008403013303F01F039B02FB820AE7DDE9ED +:103240000884AB883B834FF6FF73C9F12000A9F1D6 +:10325000200228FA09F104FA00F0014324FA02F2EC +:1032600011431846C9B2FFF7C9F909F10809B9F1C4 +:10327000400F0346E9D1B8822A7B033AD2B23146E5 +:10328000FFF7CEF9FB7DB882DA43C2F3C01262F3D6 +:10329000C713FB7543E786B92E1D013BDBB23246EF +:1032A000394604F10C00FFF767FA0028BADB2A7BE5 +:1032B000B88A013AD2B23146E2E7F98AC1F309018C +:1032C000013B0429DAB25BD8281D002307F11B0655 +:1032D0009A4208D910F801CB06F801C00131013338 +:1032E0000529DBB2F4D103990A9104990B91934219 +:1032F00007F11B010C9138BF043379680D9134BF7D +:1033000055FA83F300230E93FB8AADF83EB0C3F366 +:1033100009031A44069B8DF84230059B8DF8433013 +:1033200094F82C30ADF83C2083F001038DF8443044 +:1033300000238DF840A08DF841807B602A7BB88AFD +:10334000013A291DFFF76CF93B8BB882834203D108 +:10335000A3680AA92046984720460AA9FFF702FE5B +:10336000FB7DBA8AC3F38403013303F01F039B027E +:10337000FB823B8B9A420CBF00206FF01000C1E62D +:103380007B68002BAFD0052001E01C3033461E685F +:10339000002EFAD1091A081D2E1D184401EB090C44 +:1033A000BCF11B0F5FFA89F39DD89A429BD916F89E +:1033B000013B00F8013B09F10109EFE76FF009005B +:1033C000A0E66FF00A009DE66FF00B009AE66FF042 +:1033D0000D0097E66FF00E0094E66FF00F0091E697 +:1033E00040420F0080841E00EFF3098305494A6BB9 +:1033F00022F001024A63683383F30988002383F3D0 +:103400001188704700EF00E0302080F3118862B629 +:103410000C4B0D4AD96821F4E0610904090C0A43F8 +:10342000DA60D3F8FC20094942F08072C3F8FC202E +:103430000A6842F001020A602022DA7783F822004B +:10344000704700BF00ED00E00003FA05001000E047 +:1034500010B5302383F311880E4B5B6813F40063BF +:1034600014D0F1EE103AEFF30984683C4FF080730A +:10347000E361094BDB6B236684F3098800F090F865 +:1034800010B1064BA36110BD054BFBE783F3118818 +:10349000F9E700BF00ED00E000EF00E03F030008A7 +:1034A0004203000800F1604303F561430901C9B21A +:1034B00083F80013012200F01F039A4043099B0088 +:1034C00003F1604303F56143C3F880211A6070473C +:1034D00000230375826803691B6899689142FBD2D7 +:1034E0005A6803604260106058607047002303759B +:1034F000826803691B6899689142FBD85A68036027 +:10350000426010605860704708B50846302383F366 +:1035100011880B7D032B05D0042B0DD02BB983F321 +:10352000118808BD8B6900221A604FF0FF33836158 +:10353000FFF7CEFF0023F2E7D1E9003213605A60B3 +:10354000F3E70000FFF7C4BF054BD968087518689A +:1035500002681A60536001220275D860FCF7DABE77 +:10356000284A002030B50C4BDD684B1C87B0044660 +:103570000FD02B46094A684600F046F92046FFF76F +:10358000E3FF009B13B1684600F048F9A86907B053 +:1035900030BDFFF7D9FFF9E7284A002009350008B8 +:1035A000044B1A68DB6890689B68984294BF0020BF +:1035B00001207047284A0020084B10B51C68D868C5 +:1035C00022681A60536001222275DC60FFF78EFFCB +:1035D00001462046BDE81040FCF79CBE284A00206A +:1035E00038B5074C0749084801230025237065605A +:1035F00000F028FC0223237085F3118838BD00BF3A +:10360000904C0020204B0008284A002008B572B6D4 +:10361000044B186500F0E2FA00F08EFB024B032227 +:103620001A70FEE7284A0020904C002000F02CB9C8 +:103630008B60022308618B82084670478368A3F180 +:10364000840243F8142C026943F8442C426943F87D +:10365000402C094A43F8242CC26843F8182C022253 +:1036600003F80C2C002203F80B2C044A43F8102C0E +:10367000A3F12000704700BF2D030008284A002056 +:1036800008B5FFF7DBFFBDE80840FFF75BBF0000B0 +:10369000024BDB6898610F20FFF756BF284A0020D5 +:1036A000302383F31188FFF7F3BF000008B501460C +:1036B000302383F311880820FFF754FF002383F39E +:1036C000118808BD064BDB6839B1426818605A6042 +:1036D000136043600420FFF745BF4FF0FF30704791 +:1036E000284A00200368984206D01A680260506099 +:1036F00099611846FFF726BF7047000010B50368B0 +:103700009C68A2420CD85C688A600B604C602160A7 +:10371000596099688A1A9A604FF0FF33836010BD30 +:103720001B68121BECE700000A2938BF0A2170B59C +:1037300004460D460A26601900F07EFB00F06AFB85 +:10374000041BA54203D8751C2E460446F3E70A2E37 +:1037500004D9BDE87040012000F0B4BB70BD00008A +:10376000F8B5144B0D46D96103F1100141600A2AE6 +:103770001969826038BF0A22016048601861A81880 +:10378000144600F04BFB0A2700F044FB431BA34206 +:10379000064606D37C1C281900F04EFB274635460A +:1037A000F2E70A2F04D9BDE8F840012000F08ABBF7 +:1037B000F8BD00BF284A0020F8B506460D4600F0C7 +:1037C00029FB0F4A134653F8107F9F4206D12A4621 +:1037D00001463046BDE8F840FFF7C2BFD169BB687B +:1037E000441A2C1928BF2C46A34202D92946FFF7B8 +:1037F0009BFF224631460348BDE8F840FFF77EBFF5 +:10380000284A0020384A002010B4C0E903230023CE +:103810005DF8044B4361FFF7CFBF000010B5194CB2 +:10382000236998420DD0D0E90032816813605A6054 +:103830009A680A449A60002303604FF0FF33A36143 +:1038400010BD2346026843F8102F53600022026027 +:1038500022699A4203D1BDE8104000F0E7BA9368AC +:1038600081680B44936000F0D5FA2269E16992689F +:10387000441AA242E4D91144BDE81040091AFFF7E6 +:1038800053BF00BF284A00202DE9F047DFF8BC8075 +:1038900008F110072C4ED8F8105000F0BBFAD8F8F9 +:1038A0001C40AA68031B9A423ED81444D5E9003252 +:1038B0004FF00009C8F81C4013605A60C5F800902A +:1038C000D8F81030B34201D100F0B0FA89F3118872 +:1038D000D5E9033128469847302383F311886B6973 +:1038E000002BD8D000F096FA6A69A0EB04094A458B +:1038F00082460DD2022000F0E5FA0022D8F81030FE +:10390000B34208D151462846BDE8F047FFF728BF2B +:10391000121A2244F2E712EB090938BF4A46294637 +:103920003846FFF7EBFEB5E7D8F81030B34208D0C1 +:103930001444211AC8F81C00A960BDE8F047FFF73D +:10394000F3BEBDE8F08700BF384A0020284A0020B7 +:1039500038B500F05FFA054AD2E90845031B18198B +:1039600045F10001C2E9080138BD00BF284A002026 +:1039700000207047FEE70000704700004FF0FF3066 +:1039800070470000BFF34F8F024AD368DB03FCD4BB +:10399000704700BF003C024008B5094B1B7873B963 +:1039A000FFF7F0FF074B1A69002ABFBF064A5A60AB +:1039B00002F188325A601A6822F480621A6008BDE7 +:1039C000984C0020003C02402301674508B50B4B92 +:1039D0001B7893B9FFF7D6FF094B1A6942F00042F2 +:1039E0001A611A6842F480521A601A6822F48052EE +:1039F0001A601A6842F480621A6008BD984C002070 +:103A0000003C02400728F0B516D80C4C0C4923782E +:103A10007BB90C4D0E4608234FF0006255F8047B2D +:103A200046F8042B013B13F0FF033A44F6D101237F +:103A3000237051F82000F0BD0020FCE7BC4C0020B2 +:103A40009C4C00202C4B0008014B53F82000704781 +:103A50002C4B000808207047072810B5044601D9F0 +:103A6000002010BDFFF7CEFF064B53F8243018445A +:103A7000C21A0BB90120F4E712680132F0D1043BFD +:103A8000F6E700BF2C4B0008072810B5044621D8E4 +:103A9000FFF778FFFFF780FF0F4AF323D360C300DF +:103AA000DBB243F4007343F002031361136943F480 +:103AB00080331361FFF766FFFFF7A4FF074B53F84E +:103AC000241000F035F9FFF781FF2046BDE81040D3 +:103AD000FFF7C2BF002010BD003C02402C4B000885 +:103AE000F8B512F00103144642D185182E4A9542CA +:103AF00057D82E4B1B6813F0010352D02C4DFFF703 +:103B00004BFFF323EB60FFF73DFF40F20127032C4F +:103B100015D824F001046618254C401A40F201170C +:103B2000B142236900EB010524D123F00103236195 +:103B3000FFF74CFF0120F8BD043C0430E7E78307A2 +:103B4000E7D12B6923F440732B612B693B432B6135 +:103B500051F8046B0660BFF34F8FFFF713FF036844 +:103B60009E42E9D02B6923F001032B61FFF72EFF62 +:103B70000020E0E723F44073236123693B43236182 +:103B80000B882B80BFF34F8FFFF7FCFE2D8831F899 +:103B9000023BADB2AB42C3D0236923F001032361E2 +:103BA000E4E71846C7E700BF0000080800380240F5 +:103BB000003C0240084908B50B7828B11BB9FFF753 +:103BC000EBFE01230B7008BD002BFCD0BDE80840C4 +:103BD0000870FFF7FBBE00BF984C00200149024867 +:103BE00000F0A8B800FF03000001002008461146BD +:103BF00000F0A4BE012000F0A1BE0000084600F0C5 +:103C0000BBBE000038B5EFF311859DB9EFF3058415 +:103C1000C4F30804302334B183F31188FFF798FE0E +:103C200085F3118838BD83F31188FFF791FE84F383 +:103C3000118838BDBDE83840FFF78ABE38B5FFF7B8 +:103C4000E1FF114C114AC00840EA4170A0FB025E3E +:103C5000C908A0FB040C1CEB050CA1FB04404FF0B1 +:103C600000035B41A1FB02121CEB040C43EB0000C0 +:103C700011EB0E0142F10002411842F10000090966 +:103C800041EA007038BD00BFCFF753E3A59BC420C5 +:103C900010B50244064BD2B2904200D110BD441C74 +:103CA00000B253F8200041F8040BE0B2F4E700BF83 +:103CB000502800400F4B30B51C6F240407D41C6FF4 +:103CC00044F400741C671C6F44F400441C670A4CE5 +:103CD000236843F4807323600244084BD2B29042BD +:103CE00000D130BD441C00B251F8045B43F82050B1 +:103CF000E0B2F4E700380240007000405028004075 +:103D000007B5012201A90020FFF7C2FF019803B007 +:103D10005DF804FB13B50446FFF7F2FFA04205D09F +:103D2000012201A900200194FFF7C4FF02B010BDD9 +:103D3000704700007047000070470000074B45F2D5 +:103D400055521A6002225A6040F6FF729A604CF691 +:103D5000CC421A60024B01221A70704700300040BA +:103D6000C44C0020034B1B781BB1034B4AF6AA221C +:103D70001A607047C44C002000300040034B1A68A2 +:103D80001AB9034AD2F874281A607047C04C002050 +:103D900000300240024B4FF08072C3F87428704725 +:103DA0000030024008B5FFF7E9FF024B1868C0F386 +:103DB000407008BDC04C002008B5FFF7DFFF024B84 +:103DC0001868C0F3007008BDC04C002070470000A8 +:103DD000FEE700000A4B0B480B4A90420BD30B4BFB +:103DE000DA1C121AC11E22F003028B4238BF0022D5 +:103DF0000021FDF76FB953F8041B40F8041BECE7F2 +:103E0000E04C0008BC4F0020BC4F0020BC4F0020FD +:103E100000F0CAB84FF08043586A70474FF08043B3 +:103E2000002258631A610222DA6070474FF0804323 +:103E30000022DA60704700004FF0804358637047FB +:103E4000FEE7000070B51B4B01630025044686B0F9 +:103E5000586085620E46FFF7D7FA04F11003C4E9F3 +:103E600004334FF0FF33C4E90635C4E90044A560CC +:103E7000E562FFF7CFFF2B460246C4E9082304F1B1 +:103E800034010D4A256580232046FFF7D1FB01232D +:103E9000E0600A4A0375009272680192B268CDE947 +:103EA0000223074B6846CDE90435FFF7E9FB06B06E +:103EB00070BD00BF904C00204C4B0008514B0008D7 +:103EC000413E0008024AD36A1843D062704700BFDF +:103ED000284A00204B6843608B688360CB68C360CE +:103EE0000B6943614B6903628B6943620B68036032 +:103EF0007047000008B5234B23481A6942F0FF02BF +:103F00001A611A6922F0FF021A611A691A6B42F0EB +:103F1000FF021A631A6D42F0FF021A651B4A1B6DFD +:103F20001146FFF7D7FF02F11C0100F58060FFF793 +:103F3000D1FF02F1380100F58060FFF7CBFF02F1FD +:103F4000540100F58060FFF7C5FF02F1700100F534 +:103F50008060FFF7BFFF02F18C0100F58060FFF782 +:103F6000B9FF02F1A80100F58060FFF7B3FF02F18D +:103F7000C40100F58060FFF7ADFFBDE8084000F028 +:103F80008DB800BF0038024000000240584B0008C6 +:103F900008B500F019FAFFF723FBBDE80840FFF76A +:103FA000EDBE0000704700000F4B1A6C42F001029A +:103FB0001A641A6E42F001021A660C4A1B6E93686C +:103FC00043F0010393604FF0804331229A624FF037 +:103FD000FF32DA6200229A615A63DA605A60012283 +:103FE0005A611A60704700BF00380240002004E0A8 +:103FF0004FF0804208B51169D3680B40D9B2C9436C +:104000009B07116107D5302383F31188FFF70EFB5F +:10401000002383F3118808BD1E4B1A6962F0FF026A +:104020001A611A69D2B21A614FF0FF301A695A69DF +:10403000586100215A6959615A691A6A62F08052BE +:104040001A621A6A02F080521A621A6A5A6A58622E +:104050005A6A59625A6A1A6C42F080521A641A6E8D +:1040600042F080521A661A6E0B4A106840F4807053 +:104070001060186F00F44070B0F5007F1EBF4FF461 +:10408000803018671967536823F40073536000F099 +:1040900073B900BF00380240007000403B4B3C4AFF +:1040A0001A643C4A4FF4404111601A6842F0010220 +:1040B0001A601A689007FCD59A6822F003029A6089 +:1040C000324B9A6812F00C02FBD1196801F0F90129 +:1040D00019609A601A6842F480321A601A68910373 +:1040E000FCD55A6F42F001025A67284B5A6F92076B +:1040F000FCD5294A5A601A6842F080721A60254A33 +:1041000053685804FCD5214B1A689101FCD5234A09 +:10411000C3F884201A6842F080621A601A6812019B +:10412000FCD51F4A9A600322C3F88C204FF000622E +:10413000C3F894201B4B1A681B4B9A421B4B21D18E +:104140001B4A11681B4A91421CD140F203121A60AB +:10415000164A136803F00F03032BFAD10B4B9A682E +:1041600042F002029A609A6802F00C02082AFAD120 +:104170005A6C42F480425A645A6E42F480425A6643 +:104180005B6E704740F20372E1E700BF0038024007 +:1041900000040010007000400419400208300024A0 +:1041A00000948838002004E011640020003C0240A4 +:1041B00000ED00E041C20F41074A08B5536903F022 +:1041C0000103536123B1054A13680BB15068984746 +:1041D000BDE80840FFF73CB9003C0140C84C002056 +:1041E000074A08B5536903F00203536123B1054A36 +:1041F00093680BB1D0689847BDE80840FFF728B92D +:10420000003C0140C84C0020074A08B5536903F040 +:104210000403536123B1054A13690BB150699847F0 +:10422000BDE80840FFF714B9003C0140C84C00202D +:10423000074A08B5536903F00803536123B1054ADF +:1042400093690BB1D0699847BDE80840FFF700B902 +:10425000003C0140C84C0020074A08B5536903F0F0 +:104260001003536123B1054A136A0BB1506A984792 +:10427000BDE80840FFF7ECB8003C0140C84C002006 +:10428000164B10B55C6904F478725A61A30604D524 +:10429000134A936A0BB1D06A9847600604D5104A56 +:1042A000136B0BB1506B9847210604D50C4A936BE6 +:1042B0000BB1D06B9847E20504D5094A136C0BB1DA +:1042C000506C9847A30504D5054A936C0BB1D06C8C +:1042D0009847BDE81040FFF7BBB800BF003C014065 +:1042E000C84C0020194B10B55C6904F47C425A613B +:1042F000620504D5164A136D0BB1506D984723051E +:1043000004D5134A936D0BB1D06D9847E00404D5E2 +:104310000F4A136E0BB1506E9847A10404D50C4A96 +:10432000936E0BB1D06E9847620404D5084A136FA0 +:104330000BB1506F9847230404D5054A936F0BB116 +:10434000D06F9847BDE81040FFF782B8003C0140AD +:10435000C84C002008B5034800F0E8F8BDE8084064 +:10436000FFF776B8484D002008B5FFF741FEBDE8DD +:104370000840FFF76DB80000062108B50846FFF7B2 +:1043800091F806210720FFF78DF806210820FFF796 +:1043900089F806210920FFF785F806210A20FFF792 +:1043A00081F806211720FFF77DF806212820FFF766 +:1043B00079F807211C20FFF775F8BDE808400C21AB +:1043C0002620FFF76FB8000008B5FFF725FE00F0C4 +:1043D0007BF800F03DF8FFF7E5FDBDE80840FFF78A +:1043E00017BD0000026843681143016003B118471C +:1043F00070470000143000F0C5B900004FF0FF33E3 +:10440000143000F0BFB90000383000F03BBA0000B3 +:104410004FF0FF33383000F035BA0000143000F0B0 +:104420008BB900004FF0FF31143000F085B9000067 +:10443000383000F0E5B900004FF0FF32383000F0BE +:10444000DFB90000012914BF6FF01300002070478E +:1044500000F058B837B515460E4A02600022426097 +:10446000C0E902220122044602740B46009000F1CA +:104470005C014FF48072143000F034F900942B4644 +:104480004FF4807204F5AE7104F1380000F0ACF91D +:1044900003B030BD384C000838B5C36904460D463A +:1044A0001BB904210844FFF79DFF294604F11400BD +:1044B00000F026F9002806DA201D4FF40061BDE85F +:1044C0003840FFF78FBF38BD0023054A1946013336 +:1044D000102BC2E9001102F10802F8D1704700BFA9 +:1044E000C84C0020026843681143016003B11847BB +:1044F00070470000024AD36843F0C003D36070479E +:104500000044004010B5054C054A00212046FFF745 +:10451000A1FF044A044BC4E9972310BD484D002075 +:10452000F54400080044004040787D012DE9F04149 +:10453000D0F85C62F7683368DA0504469DB20DD5A1 +:10454000302383F311884FF480610430FFF7CAFFF2 +:104550006FF480733360002383F31188302383F377 +:10456000118804F1040815F02F033AD183F3118860 +:10457000380615D5290613D5302383F3118804F1A5 +:10458000380000F065F900284EDA0821201DFFF7F9 +:10459000A9FF4FF67F733B40F360002383F311883C +:1045A0007A0616D56B0614D5302383F31188D4E927 +:1045B00013239A420AD1236C43B127F040073F04EA +:1045C0001021201D3F0CFFF78DFFF760002383F3C0 +:1045D0001188D4F86822D36843B3BDE8F04110696C +:1045E00018472B0714D015F0080F0CBF00214FF40B +:1045F0008071E80748BF41F02001AA0748BF41F099 +:1046000040016B0748BF41F080014046FFF76AFF59 +:10461000AD06736805D594F8641220461940FFF77B +:104620003BFF3568ADB29EE77060B6E7BDE8F0814C +:10463000F8B5154682680669AA420B46816938BFFB +:104640008568761AB54204460BD218462A46FCF70E +:104650002FFDA3692B44A361A3685B1BA3602846BD +:10466000F8BD0CD918463246FCF722FDAF1BE168B5 +:104670003A463044FCF71CFDE3683B44EBE7184640 +:104680002A46FCF715FDE368E5E7000083689342DE +:10469000F7B51546044638BF8568D0E90460361A78 +:1046A000B5420BD22A46FCF703FD63692B446361D4 +:1046B000A36828465B1BA36003B0F0BD0DD932464A +:1046C0000191FCF7F5FC0199E068AF1B3A463144D3 +:1046D000FCF7EEFCE3683B44E9E72A46FCF7E8FC1C +:1046E000E368E4E710B50A440024C361029B8460D8 +:1046F000C0E90000C0E90511C1600261036210BD9C +:1047000008B5D0E90532934201D1826882B9826846 +:10471000013282605A1C42611970D0E904329A4217 +:1047200024BFC36843610021FEF7DCFF002008BD01 +:104730004FF0FF30FBE7000070B5302304460E4613 +:1047400083F31188A568A5B1A368A269013BA360A2 +:10475000531CA36115782269934224BFE368A361C7 +:10476000E3690BB120469847002383F3118828465C +:1047700007E031462046FEF7A5FF0028E2DA85F380 +:10478000118870BD2DE9F74F04460E46174698462E +:10479000D0F81C904FF0300A8AF311884FF0000BCC +:1047A000154665B12A4631462046FFF741FF0346CC +:1047B00060B941462046FEF785FF0028F1D000236E +:1047C00083F31188781B03B0BDE8F08FB9F1000FB7 +:1047D00003D001902046C847019B8BF31188ED1A46 +:1047E0001E448AF31188DCE7C0E90511C160C3618A +:1047F0001144009B8260C0E90000016103627047C0 +:10480000F8B504460D461646302383F31188A76891 +:10481000A7B1A368013BA36063695A1C62611D7064 +:10482000D4E904329A4224BFE3686361E3690BB1BF +:1048300020469847002080F3118807E03146204643 +:10484000FEF740FF0028E2DA87F31188F8BD000088 +:10485000D0E905239A4210B501D182687AB98268FD +:10486000013282605A1C82611C7803699A4224BF1B +:10487000C36883610021FEF735FF204610BD4FF06D +:10488000FF30FBE72DE9F74F04460E4617469846E2 +:10489000D0F81C904FF0300A8AF311884FF0000BCB +:1048A000154665B12A4631462046FFF7EFFE03461E +:1048B00060B941462046FEF705FF0028F1D00023ED +:1048C00083F31188781B03B0BDE8F08FB9F1000FB6 +:1048D00003D001902046C847019B8BF31188ED1A45 +:1048E0001E448AF31188DCE70B460146184600F0A7 +:1048F0002DB8000000F040B8012838BF012010B5E5 +:104900000446204600F030F830B900F007F808B946 +:1049100000F00CF88047F4E710BD0000024B186867 +:10492000BFF35B8F704700BFB44F002008B506206F +:1049300000F084F80120FFF71DF80000024B0A4642 +:1049400001461868FFF752B91C23002010B5054C2A +:1049500013462CB10A4601460220AFF3008010BD79 +:104960002046FCE700000000024B01461868FFF7F4 +:1049700041B900BF1C230020024B01461868FFF715 +:104980003DB900BF1C23002010B5013902449042FC +:1049900001D1002005E0037811F8014FA34201D0B6 +:1049A000181B10BD0130F2E72DE9F041A3B1C91A7F +:1049B00017780144044603F1FF3C8C42204601D99C +:1049C000002009E00578BD4204F10104F5D10CEBAB +:1049D0000405D618A54201D1BDE8F08115F8018D76 +:1049E00016F801EDF045F5D0E7E700001F2938B5CE +:1049F00004460D4604D9162303604FF0FF3038BD3E +:104A0000426C12B152F821304BB9204600F030F818 +:104A10002A4601462046BDE8384000F017B8012B71 +:104A20000AD0591C03D1162303600120E7E70024B4 +:104A300042F82540284698470020E0E7024B01460F +:104A40001868FFF7D3BF00BF1C23002038B5074DFF +:104A500000230446084611462B60FEF78FFF431CD7 +:104A600002D12B6803B1236038BD00BFB84F0020CE +:104A7000FEF77EBF034611F8012B03F8012B002A35 +:104A8000F9D170476F72672E6172647570696C6FCF +:104A9000742E41524B5F52544B5F475053000000FD +:104AA00040A2E4F1646891060041A3E5F2656992D1 +:104AB000070000004261642043414E49666163651E +:104AC00020696E6465782E00800000000080000080 +:104AD0000000800000000000000000001D19000818 +:104AE0003D210008992000085D1900086919000897 +:104AF000691B00082D1900083D190008311900082C +:104B000039190008351900088D1A000841190008E4 +:104B10000D24000851190008611A000863300000D4 +:104B20001C4B0008804A0020904C002000400000F0 +:104B300000400000004000000040000000000100B4 +:104B40000000020000000200000002006D61696EBA +:104B50000069646C65000000A000902A000000005D +:104B6000AAAAAAAA50000024FFFB000000770000B8 +:104B7000009009000100000500000000AAAAAAA5F3 +:104B800001000080FFCF00000000000000000000D6 +:104B90000000000000000000AAAAAAAA000000006D +:104BA000FFFF000000000000000000000000000007 +:104BB00000000000AAAAAAAA00000000FFFF00004F +:104BC00000000000000000000000000000000000E5 +:104BD000AAAAAAAA00000000FFFF0000000000002F +:104BE000000000000000000000000000AAAAAAAA1D +:104BF00000000000FFFF00000000000000000000B7 +:104C00000000000000000000AAAAAAAA00000000FC +:104C1000FFFF000000000000000000000000000096 +:104C2000000000000A000000000000000300000077 +:104C30000000000000000000000000001144000817 +:104C4000FD430008394400082544000831440008A9 +:104C50001D44000809440008F543000845440008C5 +:104C600052000000000000000000070000000000EB +:104C700040420F00FE2A0100D20400002023002041 +:104C80000000000000000000000000000000000024 +:104C90000000000000000000000000000000000014 +:104CA0000000000000000000000000000000000004 +:104CB00000000000000000000000000000000000F4 +:104CC00000000000000000000000000000000000E4 +:104CD00000000000000000000000000000000000D4 :00000001FF diff --git a/Tools/bootloaders/AeroFox-Airspeed-DLVR_bl.bin b/Tools/bootloaders/AeroFox-Airspeed-DLVR_bl.bin index 6ecf3bd9743e61..ba9a627090e008 100755 Binary files a/Tools/bootloaders/AeroFox-Airspeed-DLVR_bl.bin and b/Tools/bootloaders/AeroFox-Airspeed-DLVR_bl.bin differ diff --git a/Tools/bootloaders/AeroFox-Airspeed_bl.bin b/Tools/bootloaders/AeroFox-Airspeed_bl.bin index 03d0aecf8a2425..05cff056a4a85d 100755 Binary files a/Tools/bootloaders/AeroFox-Airspeed_bl.bin and b/Tools/bootloaders/AeroFox-Airspeed_bl.bin differ diff --git a/Tools/bootloaders/AeroFox-GNSS_F9P_bl.bin b/Tools/bootloaders/AeroFox-GNSS_F9P_bl.bin index c83805c9feb01f..a5415f8768da73 100755 Binary files a/Tools/bootloaders/AeroFox-GNSS_F9P_bl.bin and b/Tools/bootloaders/AeroFox-GNSS_F9P_bl.bin differ diff --git a/Tools/bootloaders/AeroFox-PMU_bl.bin b/Tools/bootloaders/AeroFox-PMU_bl.bin index 359a9d498bb3c8..a8a4fec817da6a 100755 Binary files a/Tools/bootloaders/AeroFox-PMU_bl.bin and b/Tools/bootloaders/AeroFox-PMU_bl.bin differ diff --git a/Tools/bootloaders/BirdCANdy_bl.bin b/Tools/bootloaders/BirdCANdy_bl.bin index d1858f4735aee3..4c07f052d0cfdd 100755 Binary files a/Tools/bootloaders/BirdCANdy_bl.bin and b/Tools/bootloaders/BirdCANdy_bl.bin differ diff --git a/Tools/bootloaders/BirdCANdy_bl.elf b/Tools/bootloaders/BirdCANdy_bl.elf index 2a38b21e51206f..fb979f48265879 100755 Binary files a/Tools/bootloaders/BirdCANdy_bl.elf and b/Tools/bootloaders/BirdCANdy_bl.elf differ diff --git a/Tools/bootloaders/BirdCANdy_bl.hex b/Tools/bootloaders/BirdCANdy_bl.hex index 2f9950b2c8cbc8..dc28b0b5ad6313 100644 --- a/Tools/bootloaders/BirdCANdy_bl.hex +++ b/Tools/bootloaders/BirdCANdy_bl.hex @@ -1,1283 +1,1232 @@ :020000040800F2 -:1000000000070020F5040008DD26000895260008FA -:10001000BD26000895260008B5260008F70400084C -:10002000F7040008F7040008F7040008D1360008B8 -:10003000F7040008F7040008F7040008F7040008B4 -:10004000F7040008F7040008F7040008F7040008A4 -:10005000F7040008F7040008DD440008054500081F -:100060002D450008554500087D450008F7040008A7 -:10007000F7040008F7040008F7040008F704000874 -:10008000F7040008F7040008F704000849260008F0 -:100090007526000885260008F7040008A545000815 -:1000A000F7040008F7040008F7040008F704000844 -:1000B0008D460008F7040008F7040008F70400085C -:1000C000F7040008F7040008F7040008F704000824 -:1000D000F7040008F7040008F7040008F704000814 -:1000E00009460008F7040008F7040008F7040008B0 -:1000F000F7040008F7040008F7040008F7040008F4 -:10010000F7040008F7040008F7040008F7040008E3 -:10011000F7040008F7040008F7040008F7040008D3 -:10012000F7040008F7040008F7040008F7040008C3 -:10013000F7040008F7040008F7040008F7040008B3 -:10014000F7040008F7040008F7040008F7040008A3 -:10015000F7040008F7040008F704000879460008CF -:10016000F7040008F7040008F7040008F704000883 -:10017000F7040008F7040008F7040008F704000873 -:10018000F7040008F7040008F7040008F704000863 -:10019000F7040008F7040008F7040008F704000853 -:1001A000F7040008F7040008F7040008F704000843 -:1001B000F7040008F7040008F7040008F704000833 -:1001C000F7040008F7040008F7040008F704000823 -:1001D000F7040008F7040008F7040008F704000813 -:1001E000BD12000800000000000000000000000038 -:1001F00053B94AB9002908BF00281CBF4FF0FF318E -:100200004FF0FF3000F074B9ADF1080C6DE904CE89 -:1002100000F006F8DDF804E0DDE9022304B07047E1 -:100220002DE9F047089D04468E46002B4DD18A42A9 -:10023000944669D9B2FA82F252B101FA02F3C2F1DC -:10024000200120FA01F10CFA02FC41EA030E94406D -:100250004FEA1C48210CBEFBF8F61FFA8CF708FB8E -:1002600016E341EA034306FB07F199420AD91CEB66 -:10027000030306F1FF3080F01F81994240F21C8198 -:10028000023E63445B1AA4B2B3FBF8F008FB1033E0 -:1002900044EA034400FB07F7A7420AD91CEB040415 -:1002A00000F1FF3380F00A81A74240F207816444E5 -:1002B000023840EA0640E41B00261DB1D44000236A -:1002C000C5E900433146BDE8F0878B4209D9002DCE -:1002D00000F0EF800026C5E9000130463146BDE858 -:1002E000F087B3FA83F6002E4AD18B4202D38242C2 -:1002F00000F2F980841A61EB030301209E46002D71 -:10030000E0D0C5E9004EDDE702B9FFDEB2FA82F2C5 -:10031000002A40F09280A1EB0C014FEA1C471FFA23 -:100320008CFE0126200CB1FBF7F307FB131140EA0A -:1003300001410EFB03F0884208D91CEB010103F1D7 -:10034000FF3802D2884200F2CB804346091AA4B299 -:10035000B1FBF7F007FB101144EA01440EFB00FE6D -:10036000A64508D91CEB040400F1FF3102D2A645D2 -:1003700000F2BB800846A4EB0E0440EA03409CE771 -:10038000C6F12007B34022FA07FC4CEA030C20FA1E -:1003900007F401FA06F31C43F9404FEA1C4900FA3E -:1003A00006F3B1FBF9F8200C1FFA8CFE09FB1811BB -:1003B00040EA014108FB0EF0884202FA06F20BD92E -:1003C0001CEB010108F1FF3A80F08880884240F27E -:1003D0008580A8F102086144091AA4B2B1FBF9F0C2 -:1003E00009FB101144EA014100FB0EFE8E4508D9BD -:1003F0001CEB010100F1FF346CD28E456AD9023842 -:10040000614440EA0840A0FB0294A1EB0E01A14226 -:10041000C846A64656D353D05DB1B3EB080261EB94 -:100420000E0101FA07F722FA06F3F1401F43C5E96E -:10043000007100263146BDE8F087C2F12003D840A4 -:100440000CFA02FC21FA03F3914001434FEA1C47E6 -:100450001FFA8CFEB3FBF7F007FB10360B0C43EAD8 -:10046000064300FB0EF69E4204FA02F408D91CEB88 -:10047000030300F1FF382FD29E422DD90238634486 -:100480009B1B89B2B3FBF7F607FB163341EA034126 -:1004900006FB0EF38B4208D91CEB010106F1FF3875 -:1004A00016D28B4214D9023E6144C91A46EA00466C -:1004B00038E72E46284605E70646E3E61846F8E6FE -:1004C0004B45A9D2B9EB020864EB0C0E0138A3E747 -:1004D0004646EAE7204694E74046D1E7D0467BE728 -:1004E000023B614432E7304609E76444023842E7A0 -:1004F000704700BF02E000F000F8FEE772B6374830 -:1005000080F30888364880F3098836483649086001 -:1005100040F20000CCF200004EF63471CEF2000141 -:100520000860BFF34F8FBFF36F8F40F20000C0F23F -:10053000F0004EF68851CEF200010860BFF34F8FF5 -:10054000BFF36F8F4FF00000E1EE100A4EF63C71E2 -:10055000CEF200010860062080F31488BFF36F8F8D -:1005600003F0C6FD03F058FE4FF055301F491B4AFB -:1005700091423CBF41F8040BFAE71D49184A9142E9 -:100580003CBF41F8040BFAE71A491B4A1B4B9A423D -:100590003EBF51F8040B42F8040BF8E7002018495D -:1005A000184A91423CBF41F8040BFAE703F0A4FD5E -:1005B00003F080FE144C154DAC4203DA54F8041BD2 -:1005C0008847F9E700F042F8114C124DAC4203DACB -:1005D00054F8041B8847F9E703F08CBD000700209E -:1005E000002300200000000808ED00E000010020CA -:1005F00000070020884F00080023002080230020EF -:1006000080230020C44F0020E0010008E40100081E -:10061000E4010008E40100082DE9F04F2DED108AF7 -:10062000C1F80CD0C3689D46BDEC108ABDE8F08FC0 -:10063000002383F311882846A047002003F0CAF95D -:10064000FEE703F02DF900DFFEE70000F8B500F04B -:1006500047FE03F0E7FC074603F036FD0546D0BB36 -:10066000294B9F4237D001339F4237D0274B27F089 -:10067000FF029A4235D1F8B200F03EFC2E4642F21B -:10068000107400F03FFC08B10024264601F014F974 -:1006900058B3032000F03EF80024264635B11C4B29 -:1006A0009F4203D003F008FD00242646002003F0FB -:1006B000C3FC0EB100F044F800F090FC00F012FE14 -:1006C00002F014F80546B4B900F0D0FC4FF47A708B -:1006D00003F086F9F7E72E460024D2E70446012608 -:1006E000CFE706464FF47A74CBE7002CD6D04FF410 -:1006F0007A740126D2E701F0F9FF431BA342E3D944 -:1007000000F01EF8DCE700BF010007B0000008B0F1 -:10071000263A09B0084B187003280CD8DFE800F01F -:1007200008050208022000F039BE022000F02EBEAB -:10073000024B00225A60704780230020842300204F -:1007400010B501F0B9F830B1204B03221A70204BDC -:1007500000225A6010BD1F4B1F4A1C461968013108 -:10076000F8D004339342F9D162681C4B9A42F1D914 -:100770001B4B9B6803F1006303F580339A42E9D277 -:1007800003F06EFC03F080FC002000F0C5FD0220A9 -:10079000FFF7C0FF134B1A6C00221A64196E1A6619 -:1007A000196E596C5A64596E5A665B6E72B64FF088 -:1007B000E0233021C3F8084DD4E9003281F31188D9 -:1007C0009D4683F308881047C4E700BF80230020BC -:1007D000842300200000010820000108FFFF00081A -:1007E0000023002000380240094A136849F26900DA -:1007F00099B21B0C00FB01331360064B186844F2DE -:10080000506182B2000C01FB0200186080B2704798 -:10081000182300201423002010B5002110220446C4 -:1008200000F0D8FD034B03CB206061601868A06026 -:1008300010BD00BF107AFF1F2DE9F041ADF54E7DD0 -:100840000DF134086CAC40F2751207460D460EA847 -:100850000021C8F8001000F0BDFD4FF4C472002163 -:10086000204600F0B7FD01F041FF274B4FF47A72AC -:10087000B0FBF2F0186093E80700022384E8070059 -:100880000DF5E9702382FFF7C7FF41F204431F49CA -:10089000238407A804F080FA172384F832310DF27C -:1008A000E32207AB0DF12C0C1E4603CE664510600B -:1008B0005160334602F10802F6D130681060B18809 -:1008C000B3799371918020464146012200F0CEFD1C -:1008D00000230393AB7E029305F11903019380B2C9 -:1008E0000123CDE904800093E97E05A3D3E9002329 -:1008F000384602F0C3FA0DF54E7DBDE8F08100BF29 -:100900009E6AC421818A46EE8C230020A84D0008EF -:100910002DE9F0412C4C237ADAB080460D465BBBC2 -:1009200027A9284600F0B2FE0746002842D19DF8CC -:100930009D60C82E3ED801464FF4A662204600F0C6 -:1009400049FD4FF48073C4F8F8314FF40073C4F8D4 -:100950000C334FF44073C4F8203432460DF19E013D -:1009600004F1090000F024FD26449DF89C307772C4 -:1009700023720BB9EB7E23728122002106AC27A8DB -:1009800000F028FD0122214627A800F0BBFE00232D -:100990000393AB7E029305F1190380B201932823E0 -:1009A000CDE904400093E97E05A3D3E90023404646 -:1009B00002F064FA5AB0BDE8F08100BFAFF30080E6 -:1009C00026417272DF25D7B7A8440020F0B5254E26 -:1009D0004FF48A7505FB0065F1B096F8D83085F8BC -:1009E000DC300024D822214685F8E8403AA800F0FF -:1009F000F1FC06F1090000F0E5FCD5F8E4308DF8D3 -:100A0000F000C2B206AF06F109010DF1F100CDE927 -:100A10003A3400F0CDFC394601223AA800F09EFE9F -:100A200080B2CDE9047008230127CDE9023706F131 -:100A3000D803019330230093317A0B4807A3D3E9FD -:100A4000002302F01BFAA04206DD01F04FFEC5F8BC -:100A5000E000384671B0F0BD2046FBE778F6339FE2 -:100A600093CACD8DA8440020A43300202DE9F04185 -:100A70001D4D1E4E1E4F86B0284602F02BFA03462F -:100A800058B30024CDE90344ADF81440027B8DF83F -:100A9000142099684068029403AA03C21B68DFF817 -:100AA000548043F00043029301F022FE821941F189 -:100AB0000003009402A9384601F0E4F8A04205DDE5 -:100AC000284602F00BFA88F80040D5E798F8003085 -:100AD000072B05D8013388F8003006B0BDE8F08157 -:100AE000014802F0FBF9F8E7A433002040420F0070 -:100AF000D8330020DD49002070B50D4614461E464F -:100B000002F018F950B9022E10D1012C0ED112A307 -:100B1000D3E90023C5E90023012007E0282C10D0E9 -:100B200005D8012C09D0052C0FD0002070BD302C29 -:100B3000FBD10BA3D3E90023ECE70BA3D3E90023FC -:100B4000E8E70BA3D3E90023E4E70BA3D3E90023F1 -:100B5000E0E700BFAFF30080401DA12026812A0BF3 -:100B600078F6339F93CACD8D9E6AC421818A46EE62 -:100B700026417272DF25D7B7F017304A39059E56E5 -:100B800038B505460E4C0021013500F0E7FBA4F80E -:100B90002C55B4F82C0500F0C9FB78B1B4F82C053D -:100BA00000F0D4FB014648B9B4F82C0500F0D6FBA0 -:100BB000B4F82C350133A4F82C35EAE738BD00BF72 -:100BC000A844002010B50A4B0A4A1A6003F5805366 -:100BD00093F860203AB9DC6D2CB1204600F0EAFEB3 -:100BE000204604F019F8BDE81040034800F0E2BECA -:100BF000D8330020FC4D0008204400202DE9F04FA0 -:100C00008FB000AF05460C4602F094F8002849D199 -:100C1000237E022B1BD1E38A012B18D101F066FD44 -:100C20000646FFF7E1FD03464FF4C870DFF8C482C3 -:100C3000B3FBF0F206F5167602FB103316FA83F3D7 -:100C4000C8F80030E37E33B9A34B00221A703C375A -:100C5000BD46BDE8F08F07F12401204600F0D4FC2A -:100C60000028F4D107F11400FFF7D6FD97F82640CD -:100C700007F11401224607F1270004F017F80028B5 -:100C8000E2D10F2C08D8944B1C70D8F80030A3F593 -:100C90001673C8F80030DAE797F82410284602F0F7 -:100CA00041F8D4E7E38A282B2BD010D8012B23D08E -:100CB000052BCCD1BFF34F8F8849894BCA6802F40A -:100CC000E0621343CB60BFF34F8F00BFFDE7302BD3 -:100CD000BDD1844EE17E327A9142B8D1607E3146F8 -:100CE000002291F8DC50854200F0A5800132042AF0 -:100CF00001F58A71F5D1AAE721462846FFF79CFD48 -:100D0000A5E721462846FFF703FEA0E7B2F8EC501E -:100D10007B6005F103094FEA99094FEA8902D11D69 -:100D2000C908A8EBC1039D46EB460021584600F0D8 -:100D300051FB04F1EE012A463144584600F038FBDD -:100D40007B6813B9012000F0E7FA96F8D20000F0B2 -:100D5000EDFA044630B9307200F008FB204600F08E -:100D6000DBFAB1E0D6F8D4203AB996F8D200B6F85A -:100D70002C25824201D8FFF703FFD6F8D4202A445D -:100D8000944208D296F8D200B6F82C25013082425F -:100D900001D8FFF7F5FE70685FFA89F2594600F056 -:100DA00021FB08B9C54679E0726896F8D2002A445A -:100DB0007260D6F8D42005EB0209C6F8D49000F092 -:100DC000B5FA814509D396F8D220D6F8D40001327D -:100DD000001B86F8D220C6F8D400FF2D0FD80024BF -:100DE000347200F0C3FA204600F096FA00F064FD79 -:100DF0003D4B188108B9FFF7A3FCC54627E7BB6840 -:100E000096F8D9000AFB0362FB68D2F8E41082F876 -:100E1000E83001F58061C2F8E030C2F8E410FFF775 -:100E2000D5FDFFF723FE96F8D920013202F0030228 -:100E300086F8D920B6E74FF48A7A0AFB02F505F165 -:100E4000EA013144204600F0B5FCF86000287FF448 -:100E5000FEAE3544012285F8E82001F047FCD5F8C4 -:100E6000E020D6ED007ADFED216A801A192838BF1C -:100E7000192040F6B832904228BF1046B8EE677A83 -:100E800007EE900AF8EEE77A67EEA67ADFED186AC9 -:100E9000E7EE267AFCEEE77AC6ED007A96F8D930CE -:100EA000BB60BA6873680AFB02F4321992F8E81062 -:100EB00059B1D2F8E4108B42E8463FF427AF002145 -:100EC00082F8E810C2F8E010C5467368064A9B0A2B -:100ED00001331381BBE600BF9D33002000ED00E02D -:100EE0000400FA05A84400208C230020CDCCCC3D82 -:100EF0006666663FA0330020014B1870704700BF44 -:100F00009823002030B54FF000542B4B22689A42B2 -:100F100085B007D003F0E2F8044620BB0024204649 -:100F200005B030BD254B627D25481A70237D0372C4 -:100F30004FF48073C0F8F8314FF40073C0F80C33ED -:100F400000254FF44073C0F820341E49C0F8E45027 -:100F5000C922093000F02CFA2046E022294600F090 -:100F600039FA0124DBE7184A184D136C43F000737B -:100F70001364AA6D164B9A42D0D12B6E013B7E2B87 -:100F8000CCD8144A07CA01AB83E8070018460321EE -:100F900000F060FC6B6D83424FF00003BED12A6D00 -:100FA0008A4201BFAB65054B2A6E1A7003BF0A4B1C -:100FB000EA6D1A601C46B2E79AAD44C5982300203A -:100FC000A8440020160000200038024000660040BF -:100FD0005041A0B0586600401023002037B51A4D8C -:100FE00000F06AFC02236B71184B288119681848BD -:100FF000012201F019FA00230193164B16490093C0 -:101000001648174B4FF4805201F064FE154B1978C7 -:1010100011B1124801F086FE01F068FB0446FFF7AB -:10102000E3FB4FF4C873B0FBF3F202FB130304F5C8 -:10103000167010FA83F00C4B186003F045F808B1F5 -:101040000F232B8103B030BD8C2300201023002000 -:10105000D8330020F90A00089C230020A433002084 -:10106000FD0B000898230020A03300202DE9F04F4D -:101070002DED028B0FF23829D9E90089834C93B00A -:101080000BAE9FED7E8BFFF7F1FC814FDFF828A2BE -:1010900000230A93ADF834300B9373604FF0000BCC -:1010A0005B468DED008B01250DF11D0207A9384629 -:1010B0008DF81C508DF81DB001F066F99DF81C30BC -:1010C000002B40F0A580204601F034FE06460028A3 -:1010D00045D1704F01F00AFB3B6898423FD301F0C5 -:1010E00005FB8246FFF780FB4FF4C873B0FBF3F2B9 -:1010F00002FB13030AF5167010FA83F03860664F8E -:1011000097F800B0CBF1100ABBF1000F14BF3346C3 -:101110002B465FFA8AFA0EA88DF82830FFF77CFB81 -:10112000BAF1060F28BF4FF0060A0EAB03EB0B0116 -:1011300052460DF1290000F03BF90AAB0393182346 -:1011400002930AF10102554BD2B2CDE90053049249 -:1011500020464CA3D3E9002301F032FE3E7001F09B -:10116000C5FA4F4A4F4D1368C31AB3F57A7F2ED391 -:10117000106001F0BDFA02460B46204601F0B8FEB1 -:10118000204601F0D7FD10B32B7A474E002B14BF39 -:1011900003230223737101F0A9FA0EAF4FF47A739F -:1011A0000122B0FBF3F039463060304600F004FA1B -:1011B000182302933D4B019380B240F25513CDE9C1 -:1011C0000370009342464B46204601F0F9FD2B7A0E -:1011D00093B101F08BFA002607464FF48A7A95F80E -:1011E000D900304400F003000AFB005393F8E820D4 -:1011F00092B30136042EF2D1C82002F0F1FB2B7A13 -:10120000002B7FF43DAF13B0BDEC028BBDE8F08F37 -:10121000DAF8143083F02003CAF81430594610224B -:101220000EA800F0D7F80DF11E0308AA0AA9384647 -:1012300000F026FE96E803000FAB83E803009DF85C -:1012400034308DF844300A9B0E930EA9DDE9082353 -:10125000204602F021F821E7D3F8E02042B12B68C4 -:10126000FA2B38BFFA23BA1A0533B2EB430FC0D3B7 -:10127000FFF7ACFB0028BCD1BEE700BF00000000B8 -:1012800000000000401DA12026812A0BA43300206D -:10129000D8330020A03300209D3300209C33002051 -:1012A000D8490020A84400208C230020DC490020DD -:1012B000F1C6A7C1D068080F0000024008B5054874 -:1012C00000F078FEBDE80840034A0449002003F01E -:1012D0009DBC00BFD8330020184A0020C50B000871 -:1012E0007047000070B502F03FFD094E094D308097 -:1012F000002428683388834208D902F02FFD2B6828 -:1013000004440133B4F5803F2B60F2D370BD00BFBD -:101310000C4A0020E049002002F0D6BD00F1006038 -:10132000920000F5803002F065BD0000054B1A68A0 -:10133000054B1B889B1A834202D9104402F00EBD54 -:1013400000207047E04900200C4A0020024B1B6837 -:10135000184402F00BBD00BFE0490020024B1B689F -:10136000184402F01BBD00BFE0490020064991F877 -:10137000243033B10023086A81F824300822FFF7B3 -:10138000CDBF0120704700BFE4490020022802BF02 -:10139000014B20229A61704700000240022802BFE0 -:1013A000024B4FF400129A61704700BF00000240E8 -:1013B00010B50023934203D0CC5CC4540133F9E749 -:1013C00010BD000003460246D01A12F9011B002985 -:1013D000FAD1704702440346934202D003F8011B3E -:1013E000FAE770472DE9F8431F4D144695F824207D -:1013F0000746884652BBDFF870909CB395F82430BE -:101400002BB92022FF2148462F62FFF7E3FF95F812 -:101410002400C0F10802A24228BF2246D6B24146AB -:10142000920005EB8000FFF7C3FF95F82430A41B62 -:101430001E44F6B2082E17449044E4B285F82460A6 -:10144000DBD1FFF793FF0028D7D108E02B6A03EB2D -:1014500082038342CFD0FFF789FF0028CBD1002041 -:10146000BDE8F8830120FBE7E44900202DE9F047BF -:101470000D46044600219046284640F27912FFF7B7 -:10148000A9FF234620220021284601F0A7FE231DA4 -:1014900002222021284601F0A1FE631D0322222101 -:1014A000284601F09BFEA31D03222521284601F0BA -:1014B00095FE04F1080310222821284601F08EFE33 -:1014C00004F1100308223821284601F087FE04F1B8 -:1014D000110308224021284601F080FE04F1120386 -:1014E00008224821284601F079FE04F11403202245 -:1014F0005021284601F072FE04F1180340227021A9 -:10150000284601F06BFE04F120030822B021284692 -:1015100001F064FE04F121030822B821284601F0FD -:101520005DFE04F12207C0263B46314608222846CC -:10153000083601F053FEB6F5A07F07F10107F3D19D -:1015400004F1320308223146284601F047FE002705 -:1015500004F1330A94F832304FEAC7099F4209F583 -:10156000A47615D3B8F1000F08D1314604F599736C -:101570000722284601F032FE09F24F16274694F85A -:1015800032213B1B93420CD3F01DC008BDE8F0870D -:101590000AEB070308223146284601F01FFE0137F7 -:1015A000D8E707F2331331460822284601F016FE29 -:1015B00008360137E3E7000013B50446084600216A -:1015C00001602346C0F803102022019001F006FEBE -:1015D0000198231D0222202101F000FE0198631DC5 -:1015E0000322222101F0FAFD0198A31D03222521E7 -:1015F00001F0F4FD019804F108031022282101F004 -:10160000EDFD072002B010BDF7B50023047F009167 -:101610000E4607221946054601F0A4FC731C0093F0 -:10162000012200230721284601F09CFCC4B9B31C09 -:101630000093052223460821284601F093FC0D243F -:101640003746B278BB1B934211D32B7FA88A07344D -:10165000E408BBB9844294BF0020012003B0F0BD70 -:10166000AB8ADB00083BDB08B3700824E8E7FB1C0F -:101670000093214600230822284601F073FC083419 -:101680000137DEE7201A18BF0120E7E7F7B500238E -:10169000047F00910E4608221946054601F062FCBF -:1016A000731CC4B90822009311462346284601F052 -:1016B00059FC1024012372785F1C013B934211D323 -:1016C0002B7FA88A0734E408BBB9844294BF00206A -:1016D000012003B0F0BDAB8ADB00083BDB08737070 -:1016E0000824E7E7F319009321460023082228463F -:1016F00001F038FC08343B46DDE7201A18BF012012 -:10170000E7E70000F8B50E460546144600218122A1 -:101710003046FFF75FFE2B4608220021304601F0DD -:101720005DFD7CB96B1C07220821304601F056FD97 -:101730000F2401236A785F1C013B934204D3E01D10 -:10174000C008F8BD0824F4E7EB192146082230460A -:1017500001F044FD08343B46ECE70000F8B50E46C6 -:10176000054614460021CE223046FFF733FE2B46B5 -:1017700028220021304601F031FD7CB905F1080333 -:1017800008222821304601F029FD30242F462A7AEC -:101790007B1B934204D3E01DC008F8BD2824F5E765 -:1017A00007F1090321460822304601F017FD0834ED -:1017B0000137ECE7F7B5047F00910E4601231022B4 -:1017C0000021054601F0CEFBC4B9B31C00930922E9 -:1017D00023461021284601F0C5FB1924374672889C -:1017E000BB1B9A4211D82B7FA88A0734E408BBB9E7 -:1017F000844294BF0020012003B0F0BDAB8ADB001F -:10180000103BDB0873801024E8E73B1D0093214662 -:1018100000230822284601F0A5FB08340137DEE743 -:10182000201A18BF0120E7E730B5094D0A4491425C -:101830000DD011F8013B5840082340F30004013B50 -:101840002C4013F0FF0384EA5000F6D1EFE730BDDF -:101850002083B8EDF7B54FF0FF33DFF854C0DFF861 -:1018600054E000EB81011A4688421CD050F8044B2A -:10187000019401AF042417F8015B82EA0562082590 -:10188000DB18164605F1FF355241002EBCBF83EA36 -:101890000C0382EA0E0215F0FF05F1D1013C14F0B1 -:1018A000FF04E8D1E0E7D843D14303B0F0BD00BF67 -:1018B0009336EAA9EBE1F042F7B5384A106851686F -:1018C0006B4603C36A4636493648082303F0FEF9DF -:1018D0000446002833D10A25334A106851686B4604 -:1018E00003C36A4631492F48082303F0EFF9044641 -:1018F000002849D00369B3F5E02F45D8B0F8661049 -:1019000040F2144291423FD1294A024402F15C0163 -:101910008B4239D35C3B234900209E1AFFF784FF9A -:101920003246074604F164010020FFF77DFFA368FB -:101930009F4229D1E368984208BF002524E003694B -:10194000B3F5E02F27D8418B40F21442914220D1C9 -:10195000174A024402F110018B4218D3103B11497F -:1019600000209D1AFFF760FF2A46064604F1180181 -:101970000020FFF759FFA3689E4202D1E368984216 -:1019800001D00D25A8E70025284603B0F0BD10259D -:10199000A2E70C25A0E70B259EE700BFC04D00087D -:1019A000DCFF060000000108C94D000890FF06009A -:1019B0000800FFF710B5037C044613B9006803F074 -:1019C0006DF9204610BD00000023BFF35B8FC3609C -:1019D000BFF35B8FBFF35B8F8360BFF35B8F704799 -:1019E000BFF35B8F0068BFF35B8F704770B5054630 -:1019F0000C30FFF7F5FF05F1080604463046FFF707 -:101A0000EFFFA04206D930466D68FFF7E9FF254495 -:101A1000281A70BD3046FFF7E3FF201AF9E70000EF -:101A200070B50546406898B105F10800FFF7D8FF8A -:101A300005F10C0604463046FFF7D2FF84423046DB -:101A400094BF6D680025FFF7CBFF013C2C44201AA2 -:101A500070BD000038B50C460546FFF7C7FFA04231 -:101A600010D305F10800FFF7BBFF04446868B4FB1E -:101A7000F0F100FB1144BFF35B8F0120AC60BFF3BA -:101A80005B8F38BD0020FCE72DE9F0411446074686 -:101A90000D46FFF7C5FF844228BF0446D4B1B846BF -:101AA00058F80C6B4046FFF79BFF304428604046D7 -:101AB0007E68FFF795FF331A9C4203D86C600120C3 -:101AC000BDE8F0816B60A41B3B68AB602044E8601C -:101AD0000220F5E72046F3E738B50C460546FFF748 -:101AE0009FFFA04210D305F10C00FFF779FF0444DB -:101AF0006868B4FBF0F100FB1144BFF35B8F012079 -:101B0000EC60BFF35B8F38BD0020FCE72DE9FF419F -:101B1000884669460746FFF7B7FF6C4606B204EBF6 -:101B2000C6060025B44209D06268206808EB0501AA -:101B3000FFF73EFC636808341D44F3E72946384646 -:101B4000FFF7CAFF284604B0BDE8F081F8B50546A6 -:101B50000C300F46FFF744FF05F1080604463046F7 -:101B6000FFF73EFFA042304688BF6C68FFF738FFA2 -:101B7000201A386020B130462C68FFF731FF20442E -:101B8000F8BD000073B5144606460D46FFF72EFF5C -:101B9000844228BF04460190DCB101A93046FFF71A -:101BA000D5FF019B33B93268C5E90233C5E900248A -:101BB00001200CE09C4238BF0194286001986860C5 -:101BC0008442F5D93368AB60241AEC60022002B07D -:101BD00070BD2046FBE700002DE9FF410F46694636 -:101BE000FFF7D0FF6C4600B204EBC0050026AC4204 -:101BF00009D0D4F8048054F8081BB8194246FFF7FE -:101C0000D7FB4644F3E7304604B0BDE8F08100005E -:101C100038B50546FFF7E0FF044601462846FFF7C2 -:101C200019FF204638BD0000302383F3118862B6C7 -:101C300070470000002383F3118862B670470000EC -:101C400010B4026854681A4623465DF8044B1847DE -:101C50000120704700207047002070477047000047 -:101C6000002070470E20704700F5805090F8C800A3 -:101C7000C0F340007047000000F5805090F9C900A3 -:101C800070470000F7B50C68BDF8207014F00054E0 -:101C90001E466FD10B7B082B6CD8FFF7C5FF45693B -:101CA000AB685B010CD4AB681B0108D4AC6814F0C2 -:101CB00080545DD1FFF7BEFF204603B0F0BD012484 -:101CC0000B6804F1180C002BB8BFDB004FEA0C1CAA -:101CD000B4BF43F004035B0545F80C300B680FFA02 -:101CE00084FC13F0804F18BF05EB0C1E05EB0C1C99 -:101CF0001EBFDEF8803143F00203CEF880310B7B4B -:101D0000CCF8843105EB04158B68C5F88C314B6831 -:101D1000C5F88831DCF8803143F00103CCF880311C -:101D200000EB441541F268031D4403EB44130344E4 -:101D3000C5E9002608330D4601F10C0C55F804EBFB -:101D400043F804EB6545F9D184342D881D8000EB00 -:101D5000441407F00303257925F00B052B43237169 -:101D6000FFF768FF0097334600F0E2FC0120A4E78C -:101D70000224A5E74FF0FF309FE7000013B500F500 -:101D800080540191E06DFFF74BFE1F280AD901999D -:101D9000E06D2022FFF7BAFEA0F12003584258411F -:101DA00002B010BD0020FBE708B500F58050FFF73A -:101DB0003BFFC06DFFF708FEBDE80840FFF73ABFE4 -:101DC00000220260828142608260704710B500226A -:101DD0000023C0E900230023044603810C30FFF7F1 -:101DE000EFFF204610BD0000F0B5054600F580501D -:101DF0000C4690F8C83013F0040FC3F3800108BFFD -:101E0000114661F3820304F1840680F8C83005EBC3 -:101E1000461389B01B79D8072ED57AB319072DD46C -:101E20006846FFF7D3FF05EB441303F5835303F133 -:101E3000180703AA103318685968144603C40833F6 -:101E4000BB422246F7D1186820609B88A380DDE959 -:101E50000E23CDE900230123ADF808302B68694635 -:101E6000DB6B2846984705EB46152B791A075CBFB4 -:101E700043F008032B7101E0002AF4D109B0F0BD52 -:101E80002DE9F047074688B007F5805468469A4622 -:101E90008846FFF7C9FE9146FFF798FFE06DFFF710 -:101EA000A5FD1F2829D9E06D20226946FFF7B0FE65 -:101EB000202822D103AD444605AB2E4603CE9E42D8 -:101EC00020606160354604F10804F6D13068206076 -:101ED000B388A380DDE90023C9E90023BDF80830F9 -:101EE000AAF80030FFF7A6FE4A4653464146384658 -:101EF00008B0BDE8F04700F009BCFFF79BFE0020EA -:101F000008B0BDE8F08700002DE9F84F0023C0E9D4 -:101F10000133254B044640F8183B0F46FFF750FFAE -:101F200004F12800FFF752FF04F1480804F5825538 -:101F30004646083530462036FFF748FFAE42F9D115 -:101F400004F580554FF480534FF00009C5E913396B -:101F5000C5F848800123EE6504F5875804F58456DA -:101F6000C5F8549085F8583085F86030083608F187 -:101F700008084FF0000A4FF0000B46E908ABA6F145 -:101F80001800FFF71DFF203646F8289C4645F4D17F -:101F900085F8C97017B1054800F0A2FB044B6361D6 -:101FA0002046BDE8F88F00BFFC4D0008D44D000866 -:101FB0000064004010B5044B197804464A1C1A709E -:101FC000FFF7A2FF204610BD144A00202DE9F0477C -:101FD000002950D0294B2A4FB7FBF1F599428CBF0D -:101FE0000A231123581EB5FBF3FC03FB1C53C4B298 -:101FF0002BB102280346F5D80020BDE8F0870CF18C -:10200000FF36B6F5806FF7D2C4EBC40E0EF10303B2 -:102010004FEAE309C3F3C703A4EB030809F1010A7C -:102020004FF47A755FFA88F009FB05555AFA88F87B -:10203000B5FBF8F5B5F5617FC1BF0EF1FF33C3F312 -:10204000C703E01AC0B25C1C50FA84F40CFB04F421 -:10205000B7FBF4F4A142CFD1013BDBB20F2BCBD8BD -:102060000138C0B20728C7D80021107116809170BE -:10207000D3700120C1E70846BFE700BF3F420F0011 -:1020800040787D0170B505460E464FF47A746B6951 -:102090005B6803F00103B34207D04FF47A7001F09C -:1020A0009FFC013CF3D1204670BD0120FCE70000FD -:1020B00030B54269936913F0700F16D000230B4CB2 -:1020C000936103F1840200EB421211794D0709D5A7 -:1020D000890707D5416954F823508D60117941F083 -:1020E000040111710133032BEBD130BDE84D000821 -:1020F00073B51D46436916469A68D207044609D54A -:102100009A6801219960C2F34002CDE9006500217F -:10211000FFF76AFE63699A68D1050BD59A684FF498 -:1021200080719960C2F34022CDE90065012120460B -:10213000FFF75AFE63699A68D2030BD59A684FF489 -:1021400080319960C2F34042CDE90065022120460A -:10215000FFF74AFE204602B0BDE87040FFF7A8BF77 -:10216000F8B50446466900296CD106F10C073868B9 -:1021700080076AD006EB01153868D5F8B00110F079 -:10218000040FD5F8B0011ABFC00840F00040400D60 -:10219000A061D5F8B0C11CF0020F1CBF40F0804018 -:1021A000A061D5F8B40106EB011100F00F0084F82E -:1021B0002400D1F8B8012077D1F8B801000A60777F -:1021C000D1F8B801000CA077D1F8B801000EE07783 -:1021D000D1F8BC0184F82000D1F8BC01000A84F8D1 -:1021E0002100D1F8BC01000C84F82200D1F8BC1108 -:1021F000090E84F823103821396004F1340004F109 -:10220000180104F1240551F8046B40F8046BA9424D -:10221000F9D109880180C4E90A23214600232386D5 -:1022200051F8283B2046DB6B984704F58052204646 -:1022300092F8C83043F0040382F8C830BDE8F84093 -:10224000FFF736BF06F1100791E7F8BD10B5044659 -:1022500000F04EFA02460B4652EA030102D0013A60 -:1022600063F100030449086820B12146BDE810402D -:10227000FFF776BF10BD00BF104A0020F8B500F58B -:1022800083511E46FFF7D0FCDFF844C0083100241C -:1022900004F1840500EB45152B795F070ED4DB06AE -:1022A0000CD5D1E900739742B34107D243695CF87A -:1022B00024709F602B7943F004032B710134032CAD -:1022C00001F12001E4D1BDE8F840FFF7B3BC00BF45 -:1022D000E84D000808B5FFF7A7FCFFF7E9FEBDE8E9 -:1022E0000840FFF7A7BC0000F8B5436905469868A9 -:1022F00000F0E050B0F1E05F0F461FD0E8B1FFF70B -:1023000093FC05F583541034002606F1840305EB95 -:1023100043131B791A0706D50136032E04F1200456 -:10232000F3D1012007E05B07F6D42146384600F0E0 -:1023300039FA0028F0D1FFF77DFCF8BD0120FCE759 -:1023400000F5805008B5FFF76FFCC06DFFF74EFB3E -:10235000FFF770FC43090CBF0120002008BD0000FE -:10236000F8B51D46002313700F4606461446FFF7C6 -:10237000E7FF80F00100387025B129463046FFF7AD -:10238000B3FF2070F8BD00002DE9B8410C4615469A -:102390001F46804600F0ACF90B462178024609B989 -:1023A000287850B14046FFF769FFFFF793FF3B469F -:1023B0002A462146FFF7D4FF0120BDE8B88100007E -:1023C00010B5FFF731FC174B1A6C42F000721A641B -:1023D0001A6A42F000721A621A6A00F5805422F0FA -:1023E00000721A62FFF726FC94F8C830DB0718D495 -:1023F000B9B103211320FFF717FC01F0C7F903213E -:10240000142001F0C3F90321152001F0BFF994F85D -:10241000C83043F0010384F8C830BDE81040FFF72E -:1024200009BC10BD003802402DE9F04700F5805589 -:1024300088B095F8C930012B0446884616467FD8E7 -:10244000804F57F823200AB947F82300D7F800A097 -:10245000C4F80C802674BAF1000F63D095F8C93027 -:10246000012B6FD001212046FFF7AAFFFFF7DCFB0D -:102470006269136823F0020313606269136843F012 -:1024800001031360636900275F6101212046FFF7A4 -:10249000D1FBFFF7F7FD002800F09580E86DFFF70E -:1024A00093FA04F58359BA4609F10809202200215C -:1024B0006846FEF78FFF02A8FFF782FCCDF818A050 -:1024C0006A4609EB07030DF1180E9446BCE80300B9 -:1024D000F44518605960624603F10803F5D1DCF851 -:1024E0000000186020379CF804201A71602FDDD19D -:1024F00095F8C8306FF38203002785F8C8306A4624 -:1025000041462046ADF80070ADF802708DF80470B9 -:10251000FFF75CFD636948BB4FF400421A6008B0E6 -:10252000BDE8F08741F2D00002F078FB814610B19F -:102530005146FFF7E9FCC7F80090B9F1000F8DD1C3 -:102540000020ECE7386803681B6B984701460028B9 -:1025500088D13868FFF734FF3868036832465B6813 -:102560004146984700287FF47DAFE9E761221A6071 -:102570009DF802309DF803201B06120402F470221D -:1025800003F040731343BDF80020C2F30902134364 -:102590009DF804201205022E02F4E0020CBF4FF059 -:1025A00000410021134362690B43D3616369132225 -:1025B0005A616269136823F00103136039462046AB -:1025C000FFF760FD08B96369A6E795F8C93093BBCA -:1025D0006169D1F8002242F00102C1F8002261696C -:1025E000D1F8002222F47C5222F00E02C1F800221F -:1025F0006169D1F8002242F46062C1F80022626988 -:10260000C2F814326269C2F80432626941F6FF719D -:10261000C2F80C126269C2F840326269C2F84432F0 -:1026200063690122C3F81C226269D2F8003223F0E8 -:102630000103C2F8003295F8C83043F0020385F870 -:10264000C8306CE7104A002008B500F051F850EA95 -:102650000103024602D0421E61F10001044B1868DA -:1026600010B10B46FFF744FDBDE8084001F064B827 -:10267000104A002008B50020FFF7E8FDBDE808403B -:1026800001F05AB808B50120FFF7E0FDBDE80840A9 -:1026900001F052B800B59BB0EFF30981682268469B -:1026A000FEF786FEEFF30583014B9B6BFEE700BF51 -:1026B00000ED00E008B5FFF7EDFF000000B59BB0AE -:1026C000EFF3098168226846FEF772FEEFF3058397 -:1026D000014B5B6BFEE700BF00ED00E0FEE7000092 -:1026E0000FB408B5029801F011F9FEE701F038BC0B -:1026F00001F010BC13B56C4684E80600031D94E895 -:10270000030083E80500012002B010BD73B58568A1 -:10271000019155B11B885B0707D4D0E900369B6B4C -:102720009847019AC1B23046A847012002B070BD57 -:10273000F0B5866889B005460C465EB1BDF8383004 -:102740005B070AD4D0E900379B6B98472246C1B299 -:102750003846B047012009B0F0BD00220023CDE982 -:1027600000230023ADF808300A4603AB01F1080648 -:10277000106851681C4603C40832B2422346F7D1A0 -:10278000106820609288A280FFF7B2FF0423ADF8A2 -:1027900008302B68CDE90001DB6B69462846984775 -:1027A000D8E7000030B503680968DD0FB5EBD17FCD -:1027B00023F0604421F060424FEAD1700BD0002B2F -:1027C000B8BFA40C0029B8BF920C944202D034BF09 -:1027D0000120002030BD944205D1C1F38070C3F3C5 -:1027E00080738342F6D194422CBF00200120F1E790 -:1027F0002DE9F041456A15B94162BDE8F0814B68A9 -:1028000023F06047C3F38A464FEAD37EC3F3807850 -:1028100016EA230638BF3E46AC462B465A68BEEB46 -:10282000D27F22F060440AD0002A18DAA40CB44205 -:1028300017D19D420FD10D60DEE71346EEE7A742A8 -:1028400007D102F08044C2F3807242450BD054B1EC -:10285000EFE708D2EDE7CCF800100B60CDE7B4420B -:1028600001D0B442E5D81A689C46002AE5D1196027 -:10287000C3E700002DE9F047089D01F007044FEA87 -:10288000D508224405F0070500EBD1004FF47F493D -:10289000944201D1BDE8F08704F0070705F0070A6C -:1028A00057453E4638BF5646C6F10806111B8E42B4 -:1028B00028BF0E46E10808EBD50E415C13F80EC0A8 -:1028C000B94029FA06F721FA0AF1FFB28CEA0101B0 -:1028D00047FA0AF739408CEA010C03F80EC0344479 -:1028E0003544D5E780EA0120082341F2210201B2F4 -:1028F0004000002980B203F1FF33B8BF504013F00D -:10290000FF03F4D17047000038B50C468D18A5427E -:1029100000D138BD14F8011BFFF7E4FFF7E7000012 -:1029200042684AB1136843604389818901339BB28D -:102930009942438138BF83811046704770B588B093 -:10294000202204460D4668460021FEF743FD20463E -:102950000495FFF7E5FF024658B16B46054608AE01 -:102960001C4603CCB44228606960234605F1080583 -:10297000F6D1104608B070BD082817D909280CD028 -:102980000A280CD00B280CD00C280CD00D280CD009 -:102990000E2814BF4020302070470C2070471020B4 -:1029A000704714207047182070472020704700009F -:1029B000082817D90C280CD910280CD914280CD9A0 -:1029C00018280CD920280CD930288CBF0F200E20B5 -:1029D0007047092070470A2070470B2070470C2071 -:1029E00070470D20704700002DE9F843078C072F32 -:1029F00004461ED9D0E9029800254FF6FF73C5F1B1 -:102A00002006A5F1200029FA05F108FA06F628FAB1 -:102A100000F031430143C9B21846FFF763FF0835A0 -:102A2000402D0346EBD1E1693A46BDE8F843FFF794 -:102A30006BBF4FF6FF70BDE8F883000010B54B6820 -:102A400023B9CA8A63F30902CA8210BD04691A68ED -:102A50001C600361C38A013BC3824A60EFE7000048 -:102A60002DE9F84F1D46CB8A0F46C3F3090105290E -:102A7000814692460B4630D00020AAB207F11A04D4 -:102A80009EB2042E1FFA80F80FD8904503F101037F -:102A900006D3FB8A0A4462F30903FB8201201AE091 -:102AA0001AF80060E6540130EAE79045F1D2A1F14E -:102AB000050B1C237C68BBFBF3F203FB12BB1FFA64 -:102AC0008BF6002C45D14846FFF72AFF044638B95B -:102AD00078606FF00200BDE8F88F4FF00008E6E77D -:102AE000002606607860ADB24FF0000B454510D966 -:102AF0000AEB0803221D13F8011B9155B1B208F12E -:102B000001081B291FFA88F82BD0454506F101065C -:102B1000F1D8FB8AC3F30902154465F30903BCE746 -:102B2000013292B21C462368002BF9D16B1F0B4473 -:102B30001C21B3FBF1F301339BB29A42D3D2BBF118 -:102B4000000FD0D14846FFF7EBFE20B9C4F800B023 -:102B5000BFE70122E7E7C0F800B05E462060044608 -:102B6000C1E74545D5D94846FFF7DAFE08B92060E8 -:102B7000AFE7C0F800B0002620600446B6E70000CA -:102B80002DE9F04F2DED028B1C4683B05B6901925D -:102B900007468846002B00F09A80238C2BB1E2690F -:102BA000002A00F09480072B35D807F10C00FFF7BE -:102BB000B7FE054638B96FF00205284603B0BDECF4 -:102BC000028BBDE8F08F14220021FEF703FC228C5B -:102BD000E16905F10800FEF7EBFB208C013080B2C3 -:102BE000FFF7E6FEFFF7C8FE013880B2208401300F -:102BF00028746369228C1B782A4403F01F0363F056 -:102C00003F0348F000411372384669602946FFF7D8 -:102C1000EFFD0125D1E700F10C034FF0000908EEAC -:102C2000103A4FF0800A4E464D4618EE100AFFF754 -:102C300077FE83460028BED014220021FEF7CAFB8F -:102C4000002E3AD1019BABF8083002220BF1080E9E -:102C50001FFA82FC0CF10100BCF1060F218C80B23E -:102C600001D88E422BD3FFF7A3FEFFF785FE6269E2 -:102C70001278013802F01F028E4208BF4FF0400A5E -:102C800042EA49121BFA80F14AEA020A013048F08E -:102C9000004281F808A08BF81000CBF804205946B8 -:102CA0003846FFF7A5FD238C0135B3422DB289F0DC -:102CB00001094FF0000AB8D17FE70022C6E7E169B9 -:102CC000895D0EF802100136B6B20132C0E76FF02E -:102CD000010572E7F8B515460E463022002104467C -:102CE0001F46FEF777FB069B6360B5F5001F079B49 -:102CF000A76034BF6A094FF6FF72A36297B2E6611C -:102D000004F1100000239A4206D800230360A78232 -:102D1000E3822383E360F8BD06600133304620364A -:102D2000F1E7000003781BB94BB2002BC8BF01705C -:102D30007047000000787047F8B50C46C96907462F -:102D400011B9238C002B37D1257E1F2D34D838782C -:102D500028BB228C072A2CD8268A36F003032BD1D5 -:102D60004FF6FF70FFF7D0FD20F001003102400464 -:102D700041EA0561400C41EA40254FF6FF722346C7 -:102D800029463846FFF7FCFE002807DD6269137804 -:102D90000133DBB21F2B88BF00231370F8BD218ADB -:102DA0002D0645EA012505432046FFF71DFE024694 -:102DB000E5E76FF00300F1E76FF00100EEE70000D8 -:102DC00070B58AB0044616460021282268461D4682 -:102DD000FEF700FBBDF83830ADF810300F9B0593BF -:102DE0009DF840308DF81830119B07936946BDF867 -:102DF0004830ADF820302046CDE90265FFF79CFF52 -:102E00000AB070BD2DE9F041D36905460C4616465F -:102E10000BB9138C5BBB377E1F2F28D895F8008029 -:102E2000B8F1000F26D03046FFF7DEFD33782102DF -:102E300041EAC33141EA0801338A41EA076141EAC4 -:102E400003410246334641F080012846FFF798FED1 -:102E500000280ADD3378012B07D17269137801331A -:102E6000DBB21F2B88BF00231370BDE8F0816FF029 -:102E70000100FAE76FF00300F7E70000F0B58BB050 -:102E800004460D4617460021282268461E46FEF7D6 -:102E9000A1FA9DF84C305A1E534253418DF8003030 -:102EA0009DF84030ADF81030119B05939DF84830E7 -:102EB0008DF81830149B07936A46BDF85430ADF86E -:102EC000203029462046CDE90276FFF79BFF0BB064 -:102ED000F0BD0000406A00B104307047436A1A68D0 -:102EE000426202691A600361C38A013BC382704770 -:102EF0002DE9F041D0F82080194E14461D46414678 -:102F0000002709B9BDE8F081D1E90223A21A65EBD7 -:102F10000303964277EB03031ED2036A8B420DD163 -:102F2000FFF78CFD036A1B68036203690B60C38AA9 -:102F30000161016A013BC3828846E2E7FFF77EFD3B -:102F40000B68C8F8003003690B60C38A0161013B5C -:102F5000C382D8F80010D4E788460968D1E700BFDB -:102F600080841E002DE9F04F8BB00D46DDF85090A7 -:102F700014469B468046002800F01981B9F1000FE5 -:102F800000F01581531E3F2B00F21181012A03D15D -:102F9000BBF1000F40F00B810023CDE90833B8F8F6 -:102FA0001430B5EBC30F4FEAC30703D300200BB0B7 -:102FB000BDE8F08F2B199F42D8F80C303ABF7F1B29 -:102FC000FFB227461BB9D8F81030002B7AD0272D36 -:102FD0004ED8C5F12806B7424FF000032CBFF6B219 -:102FE0003E4600932946D8F8080008AB3246FFF762 -:102FF00041FCA7EB060A35445FFA8AFAB8F81430A8 -:1030000003F10053053BDB000493D8F80C30039325 -:103010002821039B13B1BAF1000F2CD1D8F810006E -:1030200040B1BAF1000F05D0009608AB5246691ABC -:10303000FFF720FC38B2002FB8D066070AD00AABE1 -:1030400003EBD401624211F8083C02F0070213417D -:1030500001F8083C082C3CD9102C40F2B580202CFB -:1030600040F2B780BBF1000F00F09C80082334E0F1 -:10307000BA460026C2E7049BE02B28BFE023069354 -:103080000B44AB42059314D95A1B03980096924502 -:1030900034BF5246D2B2691A08AB04300792FFF728 -:1030A000E9FB079A1644AAEB020A1544F6B25FFA46 -:1030B0008AFA049B069A05999B1A0493039B1B6842 -:1030C0000393A6E70093D8F8080008AB3A462946D0 -:1030D000AEE7BBF1000F13D00123B4EBC30F6CD0EC -:1030E000082C12D89DF82030621E23FA02F2D50770 -:1030F00006D54FF0FF3202FA04F423438DF8203056 -:103100009DF8203089F8003051E7102C12D8BDF816 -:103110002030621E23FA02F2D10706D54FF0FF32AB -:1031200002FA04F42343ADF82030BDF82030A9F8AA -:1031300000303CE7202C0FD80899631E21FA03F3D6 -:10314000DA0705D54FF0FF3202FA04F40C43089475 -:10315000089BC9F800302AE7402C2BD0DDE9086530 -:10316000611EC4F12102A4F1210326FA01F105FA3E -:1031700002F225FA03F311431943CB0712D50122BA -:10318000A4F12003C4F1200102FA03F322FA01F1B1 -:10319000A240524243EA010363EB430332432B4311 -:1031A000CDE90823DDE90823C9E90023FFE66FF034 -:1031B0000100FCE66FF00800F9E6082CA0D9102CFD -:1031C000B3D9202CEED8C3E7BBF1000FADD002235A -:1031D00083E7BBF1000FBBD004237EE730B5012AA3 -:1031E000144638BF0124402C85B028BF4024002558 -:1031F000012ACDE9025518D81B788DF808306307ED -:103200000AD004AB03EBD405624215F8083C02F087 -:103210000702934005F8083C00910346224600212E -:1032200002A8FFF727FB05B030BD082AE4D9102A11 -:1032300003D81B88ADF80830E1E7202A8DBFD3E919 -:1032400000231B680293CDE90223D8E710B5CB68B1 -:103250001BB98B600B618B8210BD04691A681C60FE -:103260000361C38A013BC382CA60F0E703064CBF17 -:10327000C0F3C0300220704708B50246FFF7F6FFE2 -:10328000022806D15306C2F30F2001D100F003003B -:1032900008BDC2F30740FBE72DE9F04F93B0CDE93D -:1032A00003230A6804461046FFF7E0FF022814BF14 -:1032B000C2F306260026002A0D46824680F2F281DD -:1032C00012F0C04940F0EE81097B002900F0EA814C -:1032D000022803D02378B34240F0E781C2F30463AD -:1032E0000693104602F07F030593FFF7C5FF059B89 -:1032F00029444FEA834848EA0A4848EA4668CE78B3 -:1033000000230022CDE90823F309834648EA000898 -:10331000029367D0059B009302466768534608A94D -:103320002046B847002800F0C381276A4FB94146BC -:1033300004F10C00FFF702FB074690B96FF00200A2 -:1033400054E03B6998450DD03F68002FF9D14146C4 -:1033500004F10C00FFF7F2FA07460028EED0236ACA -:103360003B60276297F817C006F01F08CCF3840C67 -:10337000ACEB08001FFA80FE0028B8BF0EF1200059 -:10338000A8EB0C031FFA83FED7E90221B8BF00B2F5 -:10339000002B0793BEBF0EF120031BB2079352EA26 -:1033A000010338D0039BDFF824E39A1A049B4FF003 -:1033B000000C63EB010196457CEB01032BD36B7B87 -:1033C00097F81AE0734519D1029B002B78D0012899 -:1033D00021DC7868F8B9DFF8F0C2944570EB01039E -:1033E00016D337E0276A27B96FF00C0013B0BDE899 -:1033F000F08F3B699845B5D03F68F4E7B2489042FA -:103400007CEB010301D30020F0E7029B002BFAD0F4 -:10341000079B0F2B17DCFA7DB30002F0030203F0C9 -:103420007C031343FB7539462046FFF707FB6B7B94 -:10343000BB76029B3BB9FB7DC3F38402013262F38E -:103440008603FB75D0E76A7BBB7E9A42DBD1029B89 -:10345000002B35D0B309022B32D0039BBB60049BF9 -:10346000FB60142200210DA8FDF7B4FF039B0A9313 -:10347000049B0B932B1D0C932B7BADF83EB0013BB3 -:10348000DBB2ADF83C30069B8DF84230059B8DF8E1 -:10349000433094F82C308DF840A083F001038DF870 -:1034A00044308DF84180A3680AA920469847FB7DE7 -:1034B000C3F38403013303F01F039B02FB82A2E7E3 -:1034C000FB7DC6F34012B2EBD31F40F0F480C3F390 -:1034D0008403434540F0F280029A2B7BB609002A10 -:1034E0004DD0F2075DD4032B40F2EB80039BBB6011 -:1034F000049BFB602B7BAE1D033BDBB2324639469F -:1035000004F10C00FFF7ACFA00280CDA394620462B -:10351000FFF794FAFB7DC3F38403013303F01F0329 -:103520009B02FB820AE7DDE90884AB883B834FF608 -:10353000FF73C9F12000A9F1200228FA09F104FA69 -:1035400000F0014324FA02F211431846C9B2FFF712 -:10355000C9F909F10809B9F1400F0346E9D1B88268 -:103560002A7B033AD2B23146FFF7CEF9FB7DB8820F -:10357000DA43C2F3C01262F3C713FB7543E786B99F -:103580002E1D013BDBB23246394604F10C00FFF739 -:1035900067FA0028BADB2A7BB88A013AD2B23146F0 -:1035A000E2E7F98AC1F30901013B0429DAB25BD8E9 -:1035B000281D002307F11B069A4208D910F801CBF9 -:1035C00006F801C0013101330529DBB2F4D10399BA -:1035D0000A9104990B91934207F11B010C9138BF9A -:1035E000043379680D9134BF55FA83F300230E93A9 -:1035F000FB8AADF83EB0C3F309031A44069B8DF86D -:103600004230059B8DF8433094F82C30ADF83C20C7 -:1036100083F001038DF8443000238DF840A08DF82D -:1036200041807B602A7BB88A013A291DFFF76CF93B -:103630003B8BB882834203D1A3680AA920469847EE -:1036400020460AA9FFF702FEFB7DBA8AC3F3840372 -:10365000013303F01F039B02FB823B8B9A420CBF9A -:1036600000206FF01000C1E67B68002BAFD0052072 -:1036700001E01C3033461E68002EFAD1091A081DDD -:103680002E1D184401EB090CBCF11B0F5FFA89F3E6 -:103690009DD89A429BD916F8013B00F8013B09F1ED -:1036A0000109EFE76FF00900A0E66FF00A009DE660 -:1036B0006FF00B009AE66FF00D0097E66FF00E00CA -:1036C00094E66FF00F0091E640420F0080841E00E8 -:1036D000EFF3098305494A6B22F001024A6368331C -:1036E00083F30988002383F31188704700EF00E01B -:1036F000302080F3118862B60C4B0D4AD96821F452 -:10370000E0610904090C0A43DA60D3F8FC20094996 -:1037100042F08072C3F8FC200A6842F001020A609D -:103720002022DA7783F82200704700BF00ED00E026 -:103730000003FA05001000E010B5302383F3118870 -:103740000E4B5B6813F4006314D0F1EE103AEFF304 -:103750000984683C4FF08073E361094BDB6B23669F -:1037600084F3098800F090F810B1064BA36110BDF6 -:10377000054BFBE783F31188F9E700BF00ED00E09C -:1037800000EF00E0430600084606000800F1604331 -:1037900003F561430901C9B283F80013012200F067 -:1037A0001F039A4043099B0003F1604303F5614303 -:1037B000C3F880211A60704700230375826803698B -:1037C0001B6899689142FBD25A680360426010609E -:1037D0005860704700230375826803691B68996805 -:1037E0009142FBD85A68036042601060586070478D -:1037F00008B50846302383F311880B7D032B05D0D1 -:10380000042B0DD02BB983F3118808BD8B690022DE -:103810001A604FF0FF338361FFF7CEFF0023F2E71A -:10382000D1E9003213605A60F3E70000FFF7C4BF2C -:10383000054BD9680875186802681A605360012240 -:103840000275D860FCF7E8BE204A002030B50C4B6A -:10385000DD684B1C87B004460FD02B46094A6846EA -:1038600000F06CF92046FFF7E3FF009B13B16846B8 -:1038700000F06EF9A86907B030BDFFF7D9FFF9E78E -:10388000204A0020F1370008044B1A68DB68906872 -:103890009B68984294BF002001207047204A002076 -:1038A000084B10B51C68D86822681A605360012262 -:1038B0002275DC60FFF78EFF01462046BDE8104010 -:1038C000FCF7AABE204A0020044B1A68DB68926805 -:1038D0009B689A4201D9FFF7E3BF7047204A002056 -:1038E00038B5074C07490848012300252370656057 -:1038F00000F03AFC0223237085F3118838BD00BF25 -:10390000884C0020404E0008204A002008B572B6BE -:10391000044B186500F0ECFA00F0A0FB024B032208 -:103920001A70FEE7204A0020884C002000F046B9BB -:10393000EFF3118020B9EFF30583302282F3118871 -:103940007047000010B530B9EFF30584C4F30804E4 -:1039500014B180F3118810BDFFF7B6FF84F311880E -:10396000F9E700008B60022308618B8208467047EC -:103970008368A3F1840243F8142C026943F8442CB1 -:10398000426943F8402C094A43F8242CC26843F8A2 -:10399000182C022203F80C2C002203F80B2C044AEA -:1039A00043F8102CA3F12000704700BF3106000837 -:1039B000204A002008B5FFF7DBFFBDE80840FFF70D -:1039C00035BF0000024BDB6898610F20FFF730BF66 -:1039D000204A0020302383F31188FFF7F3BF000053 -:1039E00008B50146302383F311880820FFF72EFF26 -:1039F000002383F3118808BD064BDB6839B14268A8 -:103A000018605A60136043600420FFF71FBF4FF037 -:103A1000FF307047204A00200368984206D01A6899 -:103A20000260506099611846FFF700BF70470000C0 -:103A300010B503689C68A2420CD85C688A600B6071 -:103A40004C602160596099688A1A9A604FF0FF3380 -:103A5000836010BD1B68121BECE700000A2938BF09 -:103A60000A2170B504460D460A26601900F076FB5F -:103A700000F062FB041BA54203D8751C2E460446C9 -:103A8000F3E70A2E04D9BDE87040012000F0ACBB7A -:103A900070BD0000F8B5144B0D46D96103F110015B -:103AA00041600A2A1969826038BF0A2201604860B1 -:103AB0001861A818144600F043FB0A2700F03CFBED -:103AC000431BA342064606D37C1C281900F046FB84 -:103AD00027463546F2E70A2F04D9BDE8F840012011 -:103AE00000F082BBF8BD00BF204A0020F8B50646B2 -:103AF0000D4600F021FB0F4A134653F8107F9F42FA -:103B000006D12A4601463046BDE8F840FFF7C2BF5D -:103B1000D169BB68441A2C1928BF2C46A34202D98C -:103B20002946FFF79BFF224631460348BDE8F8408F -:103B3000FFF77EBF204A0020304A002010B4C0E9C1 -:103B4000032300235DF8044B4361FFF7CFBF000060 -:103B500010B5194C236998420DD0D0E90032816824 -:103B600013605A609A680A449A60002303604FF019 -:103B7000FF33A36110BD2346026843F8102F536042 -:103B80000022026022699A4203D1BDE8104000F091 -:103B9000DFBA936881680B44936000F0CDFA226924 -:103BA000E1699268441AA242E4D91144BDE8104088 -:103BB000091AFFF753BF00BF204A00202DE9F04744 -:103BC000DFF8BC8008F110072C4ED8F8105000F038 -:103BD000B3FAD8F81C40AA68031B9A423ED8144492 -:103BE000D5E900324FF00009C8F81C4013605A6054 -:103BF000C5F80090D8F81030B34201D100F0A8FA0F -:103C000089F31188D5E9033128469847302383F397 -:103C100011886B69002BD8D000F08EFA6A69A0EB8E -:103C200004094A4582460DD2022000F0DDFA002246 -:103C3000D8F81030B34208D151462846BDE8F047C5 -:103C4000FFF728BF121A2244F2E712EB090938BF26 -:103C50004A4629463846FFF7EBFEB5E7D8F810305C -:103C6000B34208D01444211AC8F81C00A960BDE86A -:103C7000F047FFF7F3BEBDE8F08700BF304A0020F1 -:103C8000204A002000207047FEE700007047000037 -:103C90004FF0FF3070470000BFF34F8F024AD368E8 -:103CA000DB03FCD4704700BF003C024008B5094B61 -:103CB0001B7873B9FFF7F0FF074B1A69002ABFBFE3 -:103CC000064A5A6002F188325A601A6822F4806209 -:103CD0001A6008BD904C0020003C0240230167455B -:103CE00008B50B4B1B7893B9FFF7D6FF094B1A6940 -:103CF00042F000421A611A6842F480521A601A684F -:103D000022F480521A601A6842F480621A6008BD78 -:103D1000904C0020003C02400728F0B516D80C4C0F -:103D20000C4923787BB90C4D0E4608234FF00062F6 -:103D300055F8047B46F8042B013B13F0FF033A448B -:103D4000F6D10123237051F82000F0BD0020FCE7DC -:103D5000B44C0020944C00204C4E0008014B53F80A -:103D6000200070474C4E000808207047072810B507 -:103D7000044601D9002010BDFFF7CEFF064B53F8D3 -:103D800024301844C21A0BB90120F4E7126801323A -:103D9000F0D1043BF6E700BF4C4E0008072810B5F1 -:103DA000044621D8FFF778FFFFF780FF0F4AF3237F -:103DB000D360C300DBB243F4007343F0020313612A -:103DC000136943F480331361FFF766FFFFF7A4FF25 -:103DD000074B53F8241000F03DF9FFF781FF204610 -:103DE000BDE81040FFF7C2BF002010BD003C0240FC -:103DF0004C4E0008F8B512F00103144642D1851864 -:103E00002E4A954257D82E4B1B6813F0010352D00F -:103E10002C4DFFF74BFFF323EB60FFF73DFF40F224 -:103E20000127032C15D824F001046618254C401AEC -:103E300040F20117B142236900EB010524D123F0C0 -:103E400001032361FFF74CFF0120F8BD043C04305F -:103E5000E7E78307E7D12B6923F440732B612B69D4 -:103E60003B432B6151F8046B0660BFF34F8FFFF7A4 -:103E700013FF03689E42E9D02B6923F001032B61F5 -:103E8000FFF72EFF0020E0E723F44073236123694E -:103E90003B4323610B882B80BFF34F8FFFF7FCFE62 -:103EA0002D8831F8023BADB2AB42C3D0236923F079 -:103EB00001032361E4E71846C7E700BF00000808D4 -:103EC00000380240003C0240084908B50B7828B190 -:103ED0001BB9FFF7EBFE01230B7008BD002BFCD0D4 -:103EE000BDE808400870FFF7FBBE00BF904C002003 -:103EF0004FF480214FF0005000F0AEB80846114654 -:103F000000F0AEBE012000F0ABBE0000084600F09D -:103F1000C5BE000070B582B0FFF70AFD0E4E054623 -:103F200000F00AF93268904237BF0C4A0B495168D9 -:103F300014682EBFD1E900410131516004190346D4 -:103F400041F10001284601913360FFF7FBFC019924 -:103F5000204602B070BD00BFB84C0020C04C00200D -:103F600070B582B0FFF7E4FC104E054600F0E4F8AF -:103F70003268904237BF0E4A0D49516814682EBF0F -:103F8000D1E9004101315160041941F100010346BA -:103F9000284601913360FFF7D5FC01994FF47A72FE -:103FA00000232046FCF724F902B070BDB84C002075 -:103FB000C04C002010B50244064BD2B2904200D152 -:103FC00010BD441C00B253F8200041F8040BE0B2CD -:103FD000F4E700BF502800400F4B30B51C6F24049D -:103FE00007D41C6F44F400741C671C6F44F4004435 -:103FF0001C670A4C236843F4807323600244084B17 -:10400000D2B2904200D130BD441C00B251F8045BE2 -:1040100043F82050E0B2F4E700380240007000405E -:104020005028004007B5012201A90020FFF7C2FF78 -:10403000019803B05DF804FB13B50446FFF7F2FFE7 -:10404000A04205D0012201A900200194FFF7C4FF7E -:1040500002B010BD704700007047000070470000BC -:10406000074B45F255521A6002225A6040F6FF7221 -:104070009A604CF6CC421A60024B01221A707047CB -:1040800000300040CC4C0020034B1B781BB1034B8D -:104090004AF6AA221A607047CC4C0020003000403B -:1040A000034B1A681AB9034AD2F874281A60704789 -:1040B000C84C002000300240024B4FF08072C3F821 -:1040C000742870470030024008B5FFF7E9FF024B43 -:1040D0001868C0F3407008BDC84C002008B5FFF751 -:1040E000DFFF024B1868C0F3007008BDC84C002009 -:1040F00070470000FEE700000A4B0B480B4A904255 -:104100000BD30B4BDA1C121AC11E22F003028B4296 -:1041100038BF00220021FDF75DB953F8041B40F8B9 -:10412000041BECE708500008C44F0020C44F0020D7 -:10413000C44F002000F0CAB84FF08043586A70475F -:104140004FF08043002258631A610222DA60704700 -:104150004FF080430022DA60704700004FF0804348 -:1041600058637047FEE7000070B51B4B01630025E4 -:10417000044686B0586085620E46FFF7B9FA04F12E -:104180001003C4E904334FF0FF33C4E90635C4E932 -:104190000044A560E562FFF7CFFF2B460246C4E965 -:1041A000082304F134010D4A256580232046FFF7DA -:1041B000D9FB0123E0600A4A0375009272680192FC -:1041C000B268CDE90223074B6846CDE90435FFF715 -:1041D000F1FB06B070BD00BF884C00206C4E00089B -:1041E000714E000865410008024AD36A1843D06244 -:1041F000704700BF204A00204B6843608B68836093 -:10420000CB68C3600B6943614B6903628B6943628E -:104210000B6803607047000008B5234B23481A69F8 -:1042200042F0FF021A611A6922F0FF021A611A694C -:104230001A6B42F0FF021A631A6D42F0FF021A6510 -:104240001B4A1B6D1146FFF7D7FF02F11C0100F559 -:104250008060FFF7D1FF02F1380100F58060FFF7C1 -:10426000CBFF02F1540100F58060FFF7C5FF02F1BA -:10427000700100F58060FFF7BFFF02F18C0100F5CF -:104280008060FFF7B9FF02F1A80100F58060FFF739 -:10429000B3FF02F1C40100F58060FFF7ADFFBDE898 -:1042A000084000F08DB800BF003802400000024016 -:1042B000784E000808B500F019FAFFF711FBBDE8C9 -:1042C0000840FFF7EDBE0000704700000F4B1A6C6E -:1042D00042F001021A641A6E42F001021A660C4A98 -:1042E0001B6E936843F0010393604FF080433122CB -:1042F0009A624FF0FF32DA6200229A615A63DA6002 -:104300005A6001225A611A60704700BF00380240AB -:10431000002004E04FF0804208B51169D3680B40DB -:10432000D9B2C9439B07116107D5302383F31188A4 -:10433000FFF7FCFA002383F3118808BD1E4B1A69AE -:1043400062F0FF021A611A69D2B21A614FF0FF30AF -:104350001A695A69586100215A6959615A691A6A79 -:1043600062F080521A621A6A02F080521A621A6A65 -:104370005A6A58625A6A59625A6A1A6C42F08052F2 -:104380001A641A6E42F080521A661A6E0B4A10684E -:1043900040F480701060186F00F44070B0F5007F3A -:1043A0001EBF4FF4803018671967536823F40073F9 -:1043B000536000F073B900BF003802400070004045 -:1043C0003B4B3C4A1A643C4A4FF4404111601A6826 -:1043D00042F001021A601A689007FCD59A6822F030 -:1043E00003029A60324B9A6812F00C02FBD11968F2 -:1043F00001F0F90119609A601A6842F480321A607B -:104400001A689103FCD55A6F42F001025A67284B93 -:104410005A6F9207FCD5294A5A601A6842F0807296 -:104420001A60254A53685804FCD5214B1A6891013B -:10443000FCD5234AC3F884201A6842F080621A60CF -:104440001A681201FCD51F4A9A600322C3F88C2017 -:104450004FF00062C3F894201B4B1A681B4B9A4222 -:104460001B4B21D11B4A11681B4A91421CD140F2BF -:1044700003121A60164A136803F00F03032BFAD1D4 -:104480000B4B9A6842F002029A609A6802F00C02A2 -:10449000082AFAD15A6C42F480425A645A6E42F4A5 -:1044A00080425A665B6E704740F20372E1E700BFDC -:1044B000003802400004001000700040081940025B -:1044C0001030002400948838002004E0116400209B -:1044D000003C024000ED00E041C20F41074A08B530 -:1044E000536903F00103536123B1054A13680BB10B -:1044F00050689847BDE80840FFF71EB9003C0140EE -:10450000D04C0020074A08B5536903F002035361F9 -:1045100023B1054A93680BB1D0689847BDE80840BD -:10452000FFF70AB9003C0140D04C0020074A08B50B -:10453000536903F00403536123B1054A13690BB1B6 -:1045400050699847BDE80840FFF7F6B8003C0140C5 -:10455000D04C0020074A08B5536903F008035361A3 -:1045600023B1054A93690BB1D0699847BDE808406B -:10457000FFF7E2B8003C0140D04C0020074A08B5E4 -:10458000536903F01003536123B1054A136A0BB159 -:10459000506A9847BDE80840FFF7CEB8003C01409C -:1045A000D04C0020164B10B55C6904F478725A6147 -:1045B000A30604D5134A936A0BB1D06A98476006E4 -:1045C00004D5104A136B0BB1506B9847210604D5E4 -:1045D0000C4A936B0BB1D06B9847E20504D5094A9E -:1045E000136C0BB1506C9847A30504D5054A936C26 -:1045F0000BB1D06C9847BDE81040FFF79DB800BFE5 -:10460000003C0140D04C0020194B10B55C6904F40B -:104610007C425A61620504D5164A136D0BB1506D88 -:104620009847230504D5134A936D0BB1D06D984775 -:10463000E00404D50F4A136E0BB1506E9847A104E5 -:1046400004D50C4A936E0BB1D06E9847620404D522 -:10465000084A136F0BB1506F9847230404D5054ADD -:10466000936F0BB1D06F9847BDE81040FFF764B867 -:10467000003C0140D04C002008B5034800F0E8F8A9 -:10468000BDE80840FFF758B8504D002008B5FFF7C7 -:1046900041FEBDE80840FFF74FB80000062108B50D -:1046A0000846FFF773F806210720FFF76FF8062189 -:1046B0000820FFF76BF806210920FFF767F80621AD -:1046C0000A20FFF763F806211720FFF75FF806219D -:1046D0002820FFF75BF807211C20FFF757F8BDE8FB -:1046E00008400C214720FFF751B8000008B5FFF73C -:1046F00025FE00F07BF800F03DF8FFF7E5FDBDE892 -:104700000840FFF717BD00000268436811430160CD -:1047100003B1184770470000143000F0C5B900001D -:104720004FF0FF33143000F0BFB90000383000F014 -:104730003BBA00004FF0FF33383000F035BA0000CC -:10474000143000F08BB900004FF0FF31143000F04E -:1047500085B90000383000F0E5B900004FF0FF32B5 -:10476000383000F0DFB90000012914BF6FF01300EA -:104770000020704700F058B837B515460E4A026061 -:1047800000224260C0E902220122044602740B4664 -:10479000009000F15C014FF48072143000F034F9A5 -:1047A00000942B464FF4807204F5AE7104F138008A -:1047B00000F0ACF903B030BD584F000838B5C369FC -:1047C00004460D461BB904210844FFF79DFF294606 -:1047D00004F1140000F026F9002806DA201D4FF439 -:1047E0000061BDE83840FFF78FBF38BD0023054AA0 -:1047F00019460133102BC2E9001102F10802F8D169 -:10480000704700BFD04C002002684368114301602C -:1048100003B1184770470000024AD36843F0C00351 -:10482000D36070470014014010B5054C054A0021C3 -:104830002046FFF7A1FF044A044BC4E9972310BDAB -:10484000504D0020194800080014014080F0FA0281 -:104850002DE9F041D0F85C62F7683368DA05044668 -:104860009DB20DD5302383F311884FF4806104305D -:10487000FFF7CAFF6FF480733360002383F311885E -:10488000302383F3118804F1040815F02F033AD183 -:1048900083F31188380615D5290613D5302383F301 -:1048A000118804F1380000F065F900284EDA08217B -:1048B000201DFFF7A9FF4FF67F733B40F3600023F5 -:1048C00083F311887A0616D56B0614D5302383F34B -:1048D0001188D4E913239A420AD1236C43B127F0FB -:1048E00040073F041021201D3F0CFFF78DFFF760AC -:1048F000002383F31188D4F86822D36843B3BDE85A -:10490000F041106918472B0714D015F0080F0CBFA1 -:1049100000214FF48071E80748BF41F02001AA0749 -:1049200048BF41F040016B0748BF41F0800140465D -:10493000FFF76AFFAD06736805D594F86412204648 -:104940001940FFF73BFF3568ADB29EE77060B6E7F0 -:10495000BDE8F081F8B5154682680669AA420B46A3 -:10496000816938BF8568761AB54204460BD218466D -:104970002A46FCF71DFDA3692B44A361A3685B1BBA -:10498000A3602846F8BD0CD918463246FCF710FD46 -:10499000AF1BE1683A463044FCF70AFDE3683B444C -:1049A000EBE718462A46FCF703FDE368E5E700005D -:1049B00083689342F7B51546044638BF8568D0E949 -:1049C0000460361AB5420BD22A46FCF7F1FC636943 -:1049D0002B446361A36828465B1BA36003B0F0BD52 -:1049E0000DD932460191FCF7E3FC0199E068AF1B59 -:1049F0003A463144FCF7DCFCE3683B44E9E72A46ED -:104A0000FCF7D6FCE368E4E710B50A440024C36170 -:104A1000029B8460C0E90000C0E90511C160026129 -:104A2000036210BD08B5D0E90532934201D1826816 -:104A300082B98268013282605A1C42611970D0E9E1 -:104A400004329A4224BFC36843610021FEF7E4FFA9 -:104A5000002008BD4FF0FF30FBE7000070B53023A9 -:104A600004460E4683F31188A568A5B1A368A26920 -:104A7000013BA360531CA36115782269934224BFB4 -:104A8000E368A361E3690BB120469847002383F3F1 -:104A90001188284607E031462046FEF7ADFF002882 -:104AA000E2DA85F3118870BD2DE9F74F04460E4612 -:104AB00017469846D0F81C904FF0300A8AF31188B8 -:104AC0004FF0000B154665B12A4631462046FFF7E8 -:104AD00041FF034660B941462046FEF78DFF00289E -:104AE000F1D0002383F31188781B03B0BDE8F08F69 -:104AF000B9F1000F03D001902046C847019B8BF30A -:104B00001188ED1A1E448AF31188DCE7C0E905110B -:104B1000C160C3611144009B8260C0E90000016173 -:104B200003627047F8B504460D461646302383F3FA -:104B30001188A768A7B1A368013BA36063695A1CE9 -:104B400062611D70D4E904329A4224BFE368636154 -:104B5000E3690BB120469847002080F3118807E0F5 -:104B600031462046FEF748FF0028E2DA87F3118835 -:104B7000F8BD0000D0E905239A4210B501D1826842 -:104B80007AB98268013282605A1C82611C7803699A -:104B90009A4224BFC36883610021FEF73DFF20468F -:104BA00010BD4FF0FF30FBE72DE9F74F04460E46EE -:104BB00017469846D0F81C904FF0300A8AF31188B7 -:104BC0004FF0000B154665B12A4631462046FFF7E7 -:104BD000EFFE034660B941462046FEF70DFF002870 -:104BE000F1D0002383F31188781B03B0BDE8F08F68 -:104BF000B9F1000F03D001902046C847019B8BF309 -:104C00001188ED1A1E448AF31188DCE70B46014631 -:104C1000184600F02DB8000000F040B8012838BF59 -:104C2000012010B50446204600F030F830B900F0FD -:104C300007F808B900F00CF88047F4E710BD000051 -:104C4000024B1868BFF35B8F704700BFBC4F00205A -:104C500008B5062000F084F80120FFF715F80000E1 -:104C6000024B0A4601461868FFF748B91C2300208A -:104C700010B5054C13462CB10A4601460220AFF38D -:104C8000008010BD2046FCE700000000024B0146FA -:104C90001868FFF737B900BF1C230020024B0146FC -:104CA0001868FFF733B900BF1C23002010B5013985 -:104CB0000244904201D1002005E0037811F8014F31 -:104CC000A34201D0181B10BD0130F2E72DE9F041DD -:104CD000A3B1C91A17780144044603F1FF3C8C4282 -:104CE000204601D9002009E00578BD4204F1010405 -:104CF000F5D10CEB0405D618A54201D1BDE8F08131 -:104D000015F8018D16F801EDF045F5D0E7E7000044 -:104D10001F2938B504460D4604D9162303604FF009 -:104D2000FF3038BD426C12B152F821304BB92046E9 -:104D300000F030F82A4601462046BDE8384000F031 -:104D400017B8012B0AD0591C03D116230360012088 -:104D5000E7E7002442F82540284698470020E0E78E -:104D6000024B01461868FFF7D3BF00BF1C23002089 -:104D700038B5074D00230446084611462B60FEF760 -:104D800087FF431C02D12B6803B1236038BD00BFED -:104D9000C04F0020FEF776BF034611F8012B03F841 -:104DA000012B002AF9D170476F72672E617264750A -:104DB00070696C6F742E4269726443414E6479006D -:104DC00040A2E4F1646891060041A3E5F2656992AE -:104DD000070000004261642043414E4966616365FB -:104DE00020696E6465782E0080000000008000005D -:104DF000000080000000000000000000411C0008CE -:104E00002924000889230008511C0008851C00087B -:104E1000811E0008551C0008651C0008591C00086C -:104E2000611C00085D1C0008A91D0008691C000821 -:104E3000F5260008791C00087D1D0008633000007D -:104E40003C4E0008784A0020884C002000400000BA -:104E50000040000000400000004000000000010091 -:104E60000000020000000200000002006D61696E97 -:104E70000069646C650000000004802A00000000E6 -:104E8000AAAAAAAA00004025DFFF00000000000037 -:104E90000080080010000A00000000009AAAAAAAD8 -:104EA00000000000FBFF0000000000008800000080 -:104EB0000000000000000000AAAAAAAA000000004A -:104EC000FFFF0000000000000000000000000000E4 -:104ED00000000000AAAAAAAA00000000FFFF00002C -:104EE00000000000000000000000000000000000C2 -:104EF000AAAAAAAA00000000FFFF0000000000000C -:104F0000000000000000000000000000AAAAAAAAF9 -:104F100000000000FFFF0000000000000000000093 -:104F20000000000000000000AAAAAAAA00000000D9 -:104F3000FFFF000000000000000000000000000073 -:104F4000000000000A000000000000000300000054 -:104F500000000000000000000000000035470008CD -:104F6000214700085D4700084947000855470008E9 -:104F7000414700082D470008194700086947000805 -:104F8000A0B2FF7F01000000140400000000000038 -:104F9000000007000000000040420F00FE2A010050 -:104FA000D2040000202300200000000000000000C8 -:104FB00000000000000000000000000000000000F1 -:104FC00000000000000000000000000000000000E1 -:104FD00000000000000000000000000000000000D1 -:104FE00000000000000000000000000000000000C1 -:104FF00000000000000000000000000000000000B1 -:085000000000000000000000A8 +:1000000000070020F1010008F1230008A9230008DF +:10001000D1230008A9230008C9230008F301000820 +:10002000F3010008F3010008F3010008E5330008BC +:10003000F3010008F3010008F3010008F3010008D0 +:10004000F3010008F3010008F3010008F3010008C0 +:10005000F3010008F3010008B5410008DD41000884 +:10006000054200082D42000855420008F30100082F +:10007000F3010008F3010008F3010008F301000890 +:10008000F3010008F3010008F30100085D230008F4 +:100090008923000899230008F30100087D42000825 +:1000A000F3010008F3010008F3010008F301000860 +:1000B00065430008F3010008F3010008F30100089C +:1000C000F3010008F3010008F3010008F301000840 +:1000D000F3010008F3010008F3010008F301000830 +:1000E000E1420008F3010008F3010008F3010008F1 +:1000F000F3010008F3010008F3010008F301000810 +:10010000F3010008F3010008F3010008F3010008FF +:10011000F3010008F3010008F3010008F3010008EF +:10012000F3010008F3010008F3010008F3010008DF +:10013000F3010008F3010008F3010008F3010008CF +:10014000F3010008F3010008F3010008F3010008BF +:10015000F3010008F3010008F3010008514300080F +:10016000F3010008F3010008F3010008F30100089F +:10017000F3010008F3010008F3010008F30100088F +:10018000F3010008F3010008F3010008F30100087F +:10019000F3010008F3010008F3010008F30100086F +:1001A000F3010008F3010008F3010008F30100085F +:1001B000F3010008F3010008F3010008F30100084F +:1001C000F3010008F3010008F3010008F30100083F +:1001D000F3010008F3010008F3010008F30100082F +:1001E000B10F000800000000000000000000000047 +:1001F00002E000F000F8FEE772B6374880F30888A6 +:10020000364880F3098836483649086040F20000D5 +:10021000CCF200004EF63471CEF200010860BFF35C +:100220004F8FBFF36F8F40F20000C0F2F0004EF628 +:100230008851CEF200010860BFF34F8FBFF36F8F7C +:100240004FF00000E1EE100A4EF63C71CEF20001D4 +:100250000860062080F31488BFF36F8F03F0B4FDAD +:1002600003F046FE4FF055301F491B4A91423CBFF8 +:1002700041F8040BFAE71D49184A91423CBF41F886 +:10028000040BFAE71A491B4A1B4B9A423EBF51F82E +:10029000040B42F8040BF8E700201849184A914271 +:1002A0003CBF41F8040BFAE703F092FD03F06EFE49 +:1002B000144C154DAC4203DA54F8041B8847F9E797 +:1002C00000F042F8114C124DAC4203DA54F8041B12 +:1002D0008847F9E703F07ABD0007002000230020DB +:1002E0000000000808ED00E00001002000070020E9 +:1002F000584C000800230020802300208023002089 +:10030000BC4F0020E0010008E4010008E4010008FF +:10031000E40100082DE9F04F2DED108AC1F80CD052 +:10032000C3689D46BDEC108ABDE8F08F002383F3BF +:1003300011882846A047002003F0B0F9FEE703F03B +:1003400039F900DFFEE70000F8B500F043FE03F0E6 +:10035000D5FC074603F024FD0646C0BB274B9F4251 +:1003600035D001339F4235D0254B27F0FF029A420A +:1003700033D1F8B200F03AFC354642F2107400F086 +:100380003BFC08B10024254601F00EF948B30320D8 +:1003900000F03AF80024254636B11A4B9F4203D0AC +:1003A00003F0F6FC00242546002003F0B1FC0DB15B +:1003B00000F040F800F08CFC02F022F80546ACB9E1 +:1003C00000F0CEFC4FF47A7003F06EF9F7E7354693 +:1003D0000024D4E704460125D1E705464FF47A749A +:1003E000CDE7B4F57A7F08BF0125D5E702F008F81C +:1003F000431BA342E4D900F01DF8DDE7010007B07C +:10040000000008B0263A09B0084B187003280CD831 +:10041000DFE800F008050208022000F037BE0220E5 +:1004200000F02CBE024B00225A607047802300204F +:100430008423002010B501F0B7F830B1204B03221F +:100440001A70204B00225A6010BD1F4B1F4A1C46D9 +:1004500019680131F8D004339342F9D162681C4B1A +:100460009A42F1D91B4B9B6803F1006303F580337B +:100470009A42E9D203F060FC03F072FC002000F025 +:10048000C3FD0220FFF7C0FF134B1A6C00221A6451 +:10049000196E1A66196E596C5A64596E5A665B6EFB +:1004A00072B64FF0E0233021C3F8084DD4E9003292 +:1004B00081F311889D4683F308881047C4E700BF85 +:1004C0008023002084230020000001082000010870 +:1004D000FFFF00080023002000380240094A13688B +:1004E00049F2690099B21B0C00FB01331360064B03 +:1004F000186844F2506182B2000C01FB02001860DF +:1005000080B27047182300201423002010B500216A +:100510001022044600F0D6FD034B03CB206061603F +:100520001868A06010BD00BF107AFF1F2DE9F041D0 +:10053000ADF54E7D0DF134086CAC40F275120746F6 +:100540000D460EA80021C8F8001000F0BBFD4FF4C6 +:10055000C4720021204600F0B5FD01F051FF274B89 +:100560004FF47A72B0FBF2F0186093E807000223B0 +:1005700084E807000DF5E9702382FFF7C7FF41F219 +:1005800004431F49238407A804F072FA172384F850 +:1005900032310DF2E32207AB0DF12C0C1E4603CED7 +:1005A000664510605160334602F10802F6D13068AA +:1005B0001060B188B3799371918020464146012241 +:1005C00000F0CCFD00230393AB7E029305F11903E9 +:1005D000019380B20123CDE904800093E97E05A355 +:1005E000D3E90023384602F0D3FA0DF54E7DBDE87D +:1005F000F08100BF9E6AC421818A46EE8C230020D0 +:10060000804A00082DE9F0412C4C237ADAB080466C +:100610000D465BBB27A9284600F0B0FE0746002820 +:1006200042D19DF89D60C82E3ED801464FF4A66287 +:10063000204600F047FD4FF48073C4F8F8314FF4C2 +:100640000073C4F80C334FF44073C4F820343246BE +:100650000DF19E0104F1090000F022FD26449DF8F1 +:100660009C30777223720BB9EB7E237281220021BA +:1006700006AC27A800F026FD0122214627A800F09D +:10068000B9FE00230393AB7E029305F1190380B2F8 +:1006900001932823CDE904400093E97E05A3D3E923 +:1006A0000023404602F074FA5AB0BDE8F08100BF62 +:1006B000AFF3008026417272DF25D7B7B044002027 +:1006C000F0B5254E4FF48A7505FB0065F1B096F83C +:1006D000D83085F8DC300024D822214685F8E8405F +:1006E0003AA800F0EFFC06F1090000F0E3FCD5F8B1 +:1006F000E4308DF8F000C2B206AF06F109010DF149 +:10070000F100CDE93A3400F0CBFC394601223AA899 +:1007100000F09CFE80B2CDE9047008230127CDE9EA +:10072000023706F1D803019330230093317A0B4846 +:1007300007A3D3E9002302F02BFAA04206DD01F063 +:100740005FFEC5F8E000384671B0F0BD2046FBE71B +:1007500078F6339F93CACD8DB0440020A433002097 +:100760002DE9F0411D4D1E4E1E4F86B0284602F069 +:100770003BFA034658B30024CDE90344ADF81440D6 +:10078000027B8DF8142099684068029403AA03C282 +:100790001B68DFF8548043F00043029301F032FEFF +:1007A000821941F10003009402A9384601F0DAF8F9 +:1007B000A04205DD284602F01BFA88F80040D5E784 +:1007C00098F80030072B05D8013388F8003006B0C0 +:1007D000BDE8F081014802F00BFAF8E7A4330020ED +:1007E00040420F00D8330020E549002070B50D4687 +:1007F00014461E4602F028F950B9022E10D1012CE1 +:100800000ED112A3D3E90023C5E90023012007E09C +:10081000282C10D005D8012C09D0052C0FD0002091 +:1008200070BD302CFBD10BA3D3E90023ECE70BA365 +:10083000D3E90023E8E70BA3D3E90023E4E70BA304 +:10084000D3E90023E0E700BFAFF30080401DA12003 +:1008500026812A0B78F6339F93CACD8D9E6AC421D8 +:10086000818A46EE26417272DF25D7B7F017304AEB +:1008700039059E5638B505460E4C0021013500F06D +:10088000E5FBA4F82C55B4F82C0500F0C7FB78B1B3 +:10089000B4F82C0500F0D2FB014648B9B4F82C0599 +:1008A00000F0D4FBB4F82C350133A4F82C35EAE77A +:1008B00038BD00BFB044002010B50A4B0A4A1A6088 +:1008C00003F5805393F860203AB9DC6D2CB12046D3 +:1008D00000F0E8FE204604F00BF8BDE810400348A5 +:1008E00000F0E0BED8330020D44A000820440020A5 +:1008F0002DE9F04F8FB000AF05460C4602F0A4F88A +:10090000002849D1237E022B1BD1E38A012B18D169 +:1009100001F076FD0646FFF7E1FD03464FF4C8708F +:10092000DFF8C482B3FBF0F206F5167602FB103353 +:1009300016FA83F3C8F80030E37E33B9A34B0022E4 +:100940001A703C37BD46BDE8F08F07F12401204600 +:1009500000F0D2FC0028F4D107F11400FFF7D6FD17 +:1009600097F8264007F11401224607F1270004F00A +:1009700009F80028E2D10F2C08D8944B1C70D8F845 +:100980000030A3F51673C8F80030DAE797F82410A2 +:10099000284602F051F8D4E7E38A282B2BD010D850 +:1009A000012B23D0052BCCD1BFF34F8F8849894B26 +:1009B000CA6802F4E0621343CB60BFF34F8F00BFFD +:1009C000FDE7302BBDD1844EE17E327A9142B8D121 +:1009D000607E3146002291F8DC50854200F0A5800F +:1009E0000132042A01F58A71F5D1AAE72146284689 +:1009F000FFF79CFDA5E721462846FFF703FEA0E789 +:100A0000B2F8EC507B6005F103094FEA99094FEA0F +:100A10008902D11DC908A8EBC1039D46EB46002100 +:100A2000584600F04FFB04F1EE012A463144584687 +:100A300000F036FB7B6813B9012000F0E5FA96F868 +:100A4000D20000F0EBFA044630B9307200F006FB39 +:100A5000204600F0D9FAB1E0D6F8D4203AB996F899 +:100A6000D200B6F82C25824201D8FFF703FFD6F852 +:100A7000D4202A44944208D296F8D200B6F82C2505 +:100A80000130824201D8FFF7F5FE70685FFA89F203 +:100A9000594600F01FFB08B9C54679E0726896F820 +:100AA000D2002A447260D6F8D42005EB0209C6F8B9 +:100AB000D49000F0B3FA814509D396F8D220D6F845 +:100AC000D4000132001B86F8D220C6F8D400FF2DD6 +:100AD0000FD80024347200F0C1FA204600F094FAD6 +:100AE00000F062FD3D4B188108B9FFF7A3FCC54635 +:100AF00027E7BB6896F8D9000AFB0362FB68D2F8C7 +:100B0000E41082F8E83001F58061C2F8E030C2F804 +:100B1000E410FFF7D5FDFFF723FE96F8D920013248 +:100B200002F0030286F8D920B6E74FF48A7A0AFB6E +:100B300002F505F1EA013144204600F0B3FCF8600B +:100B400000287FF4FEAE3544012285F8E82001F04C +:100B500057FCD5F8E020D6ED007ADFED216A801A47 +:100B6000192838BF192040F6B832904228BF1046E5 +:100B7000B8EE677A07EE900AF8EEE77A67EEA67AA3 +:100B8000DFED186AE7EE267AFCEEE77AC6ED007A2A +:100B900096F8D930BB60BA6873680AFB02F4321960 +:100BA00092F8E81059B1D2F8E4108B42E8463FF4CD +:100BB00027AF002182F8E810C2F8E010C54673683C +:100BC000064A9B0A01331381BBE600BF9D33002018 +:100BD00000ED00E00400FA05B04400208C23002062 +:100BE000CDCCCC3D6666663FA0330020014B18702B +:100BF000704700BF9823002030B54FF000542B4BB6 +:100C000022689A4285B007D003F0D4F8044620BB8E +:100C10000024204605B030BD254B627D25481A7062 +:100C2000237D03724FF48073C0F8F8314FF40073E2 +:100C3000C0F80C3300254FF44073C0F820341E492F +:100C4000C0F8E450C922093000F02AFA2046E02218 +:100C5000294600F037FA0124DBE7184A184D136CD7 +:100C600043F000731364AA6D164B9A42D0D12B6ED9 +:100C7000013B7E2BCCD8144A07CA01AB83E807009E +:100C80001846032100F05EFC6B6D83424FF00003B9 +:100C9000BED12A6D8A4201BFAB65054B2A6E1A7020 +:100CA00003BF0A4BEA6D1A601C46B2E79AAD44C511 +:100CB00098230020B0440020160000200038024095 +:100CC000006600405041A0B058660040102300204C +:100CD00037B51A4D00F068FC02236B71184B288160 +:100CE00019681848012201F027FA00230193164BD6 +:100CF000164900931648174B4FF4805201F074FECA +:100D0000154B197811B1124801F096FE01F078FBED +:100D10000446FFF7E3FB4FF4C873B0FBF3F202FBAA +:100D2000130304F5167010FA83F00C4B186003F0EF +:100D300037F808B10F232B8103B030BD8C2300207E +:100D400010230020D8330020ED0700089C2300204A +:100D5000A4330020F108000898230020A0330020CD +:100D60002DE9F04F2DED028B0FF23829D9E90089DA +:100D7000834C93B00BAE9FED7E8BFFF7F1FC814F60 +:100D8000DFF828A200230A93ADF834300B93736088 +:100D90004FF0000B5B468DED008B01250DF11D0220 +:100DA00007A938468DF81C508DF81DB001F072F976 +:100DB0009DF81C30002B40F0A580204601F044FE39 +:100DC0000646002845D1704F01F01AFB3B68984257 +:100DD0003FD301F015FB8246FFF780FB4FF4C87349 +:100DE000B0FBF3F202FB13030AF5167010FA83F05E +:100DF0003860664F97F800B0CBF1100ABBF1000FD6 +:100E000014BF33462B465FFA8AFA0EA88DF82830B5 +:100E1000FFF77CFBBAF1060F28BF4FF0060A0EABB6 +:100E200003EB0B0152460DF1290000F039F90AAB32 +:100E30000393182302930AF10102554BD2B2CDE974 +:100E40000053049220464CA3D3E9002301F042FE54 +:100E50003E7001F0D5FA4F4A4F4D1368C31AB3F5EF +:100E60007A7F2ED3106001F0CDFA02460B46204661 +:100E700001F0C8FE204601F0E7FD10B32B7A474E83 +:100E8000002B14BF03230223737101F0B9FA0EAFD4 +:100E90004FF47A730122B0FBF3F0394630603046EC +:100EA00000F002FA182302933D4B019380B240F206 +:100EB0005513CDE90370009342464B46204601F09E +:100EC00009FE2B7A93B101F09BFA002607464FF4F6 +:100ED0008A7A95F8D900304400F003000AFB0053E9 +:100EE00093F8E82092B30136042EF2D1C82002F024 +:100EF000DBFB2B7A002B7FF43DAF13B0BDEC028BF4 +:100F0000BDE8F08FDAF8143083F02003CAF814300B +:100F1000594610220EA800F0D5F80DF11E0308AABC +:100F20000AA9384600F01EFE96E803000FAB83E8DE +:100F300003009DF834308DF844300A9B0E930EA9BF +:100F4000DDE90823204602F031F821E7D3F8E0205C +:100F500042B12B68FA2B38BFFA23BA1A0533B2EB29 +:100F6000430FC0D3FFF7ACFB0028BCD1BEE700BFE6 +:100F70000000000000000000401DA12026812A0B77 +:100F8000A4330020D8330020A03300209D3300205C +:100F90009C330020E0490020B04400208C23002036 +:100FA000E4490020F1C6A7C1D068080F0000024044 +:100FB00008B5054800F072FEBDE80840034A044940 +:100FC000002003F08FBC00BFD8330020204A00204F +:100FD000B908000870B502F03BFD094E094D30809C +:100FE000002428683388834208D902F02BFD2B683F +:100FF00004440133B4F5803F2B60F2D370BD00BFD1 +:10100000144A0020E849002002F0D2BD00F100603F +:10101000920000F5803002F061BD0000054B1A68B7 +:10102000054B1B889B1A834202D9104402F00ABD6B +:1010300000207047E8490020144A0020024B1B683A +:10104000184402F007BD00BFE8490020024B1B68AE +:10105000184402F017BD00BFE8490020064991F886 +:10106000243033B10023086A81F824300822FFF7C6 +:10107000CDBF0120704700BFEC490020022802BF0D +:10108000014B20229A61704700000240022802BFF3 +:10109000024B4FF400129A61704700BF00000240FB +:1010A00010B50023934203D0CC5CC4540133F9E75C +:1010B00010BD000003460246D01A12F9011B002998 +:1010C000FAD1704702440346934202D003F8011B51 +:1010D000FAE770472DE9F8431F4D144695F8242090 +:1010E0000746884652BBDFF870909CB395F82430D1 +:1010F0002BB92022FF2148462F62FFF7E3FF95F826 +:101100002400C0F10802A24228BF2246D6B24146BE +:10111000920005EB8000FFF7C3FF95F82430A41B75 +:101120001E44F6B2082E17449044E4B285F82460B9 +:10113000DBD1FFF793FF0028D7D108E02B6A03EB40 +:1011400082038342CFD0FFF789FF0028CBD1002054 +:10115000BDE8F8830120FBE7EC4900202DE9F047CA +:101160000D46044600219046284640F27912FFF7CA +:10117000A9FF234620220021284601F0B9FE231DA5 +:1011800002222021284601F0B3FE631D0322222102 +:10119000284601F0ADFEA31D03222521284601F0BB +:1011A000A7FE04F1080310222821284601F0A0FE22 +:1011B00004F1100308223821284601F099FE04F1B9 +:1011C000110308224021284601F092FE04F1120387 +:1011D00008224821284601F08BFE04F11403202246 +:1011E0005021284601F084FE04F1180340227021AA +:1011F000284601F07DFE04F120030822B021284694 +:1012000001F076FE04F121030822B821284601F0FE +:101210006FFE04F12207C0263B46314608222846CD +:10122000083601F065FEB6F5A07F07F10107F3D19E +:1012300004F1320308223146284601F059FE002706 +:1012400004F1330A94F832304FEAC7099F4209F596 +:10125000A47615D3B8F1000F08D1314604F599737F +:101260000722284601F044FE09F24F16274694F85B +:1012700032213B1B93420CD3F01DC008BDE8F08720 +:101280000AEB070308223146284601F031FE0137F8 +:10129000D8E707F2331331460822284601F028FE2A +:1012A00008360137E3E7000013B50446084600217D +:1012B00001602346C0F803102022019001F018FEBF +:1012C0000198231D0222202101F012FE0198631DC6 +:1012D0000322222101F00CFE0198A31D03222521E7 +:1012E00001F006FE019804F108031022282101F004 +:1012F000FFFD072002B010BDF7B50023047F009169 +:101300000E4607221946054601F0B6FC731C0093F1 +:10131000012200230721284601F0AEFCC4B9B31C0A +:101320000093052223460821284601F0A5FC0D2440 +:101330003746B278BB1B934211D32B7FA88A073460 +:10134000E408BBB9844294BF0020012003B0F0BD83 +:10135000AB8ADB00083BDB08B3700824E8E7FB1C22 +:101360000093214600230822284601F085FC08341A +:101370000137DEE7201A18BF0120E7E7F7B50023A1 +:10138000047F00910E4608221946054601F074FCC0 +:10139000731CC4B90822009311462346284601F065 +:1013A0006BFC1024012372785F1C013B934211D324 +:1013B0002B7FA88A0734E408BBB9844294BF00207D +:1013C000012003B0F0BDAB8ADB00083BDB08737083 +:1013D0000824E7E7F3190093214600230822284652 +:1013E00001F04AFC08343B46DDE7201A18BF012013 +:1013F000E7E70000F8B50E460546144600218122B5 +:101400003046FFF75FFE2B4608220021304601F0F0 +:101410006FFD7CB96B1C07220821304601F068FD86 +:101420000F2401236A785F1C013B934204D3E01D23 +:10143000C008F8BD0824F4E7EB192146082230461D +:1014400001F056FD08343B46ECE70000F8B50E46C7 +:10145000054614460021CE223046FFF733FE2B46C8 +:1014600028220021304601F043FD7CB905F1080334 +:1014700008222821304601F03BFD30242F462A7AED +:101480007B1B934204D3E01DC008F8BD2824F5E778 +:1014900007F1090321460822304601F029FD0834EE +:1014A0000137ECE7F7B5047F00910E4601231022C7 +:1014B0000021054601F0E0FBC4B9B31C00930922EA +:1014C00023461021284601F0D7FB1924374672889D +:1014D000BB1B9A4211D82B7FA88A0734E408BBB9FA +:1014E000844294BF0020012003B0F0BDAB8ADB0032 +:1014F000103BDB0873801024E8E73B1D0093214676 +:1015000000230822284601F0B7FB08340137DEE744 +:10151000201A18BF0120E7E730B5094D0A4491426F +:101520000DD011F8013B5840082340F30004013B63 +:101530002C4013F0FF0384EA5000F6D1EFE730BDF2 +:101540002083B8EDF7B54FF0FF33DFF854C0DFF874 +:1015500054E000EB81011A4688421CD050F8044B3D +:10156000019401AF042417F8015B82EA05620825A3 +:10157000DB18164605F1FF355241002EBCBF83EA49 +:101580000C0382EA0E0215F0FF05F1D1013C14F0C4 +:10159000FF04E8D1E0E7D843D14303B0F0BD00BF7A +:1015A0009336EAA9EBE1F042F7B5384A1068516882 +:1015B0006B4603C36A4636493648082303F0F2F9FE +:1015C0000446002833D10A25334A106851686B4617 +:1015D00003C36A4631492F48082303F0E3F9044660 +:1015E000002849D00369B3F5E02F45D8B0F866105C +:1015F00040F2144291423FD1294A024402F15C0177 +:101600008B4239D35C3B234900209E1AFFF784FFAD +:101610003246074604F164010020FFF77DFFA3680E +:101620009F4229D1E368984208BF002524E003695E +:10163000B3F5E02F27D8418B40F21442914220D1DC +:10164000174A024402F110018B4218D3103B114992 +:1016500000209D1AFFF760FF2A46064604F1180194 +:101660000020FFF759FFA3689E4202D1E368984229 +:1016700001D00D25A8E70025284603B0F0BD1025B0 +:10168000A2E70C25A0E70B259EE700BF984A0008BB +:10169000DCFF060000000108A14A000890FF0600D8 +:1016A0000800FFF710B5037C044613B9006803F087 +:1016B00061F9204610BD00000023BFF35B8FC360BB +:1016C000BFF35B8FBFF35B8F8360BFF35B8F7047AC +:1016D000BFF35B8F0068BFF35B8F704770B5054643 +:1016E0000C30FFF7F5FF05F1080604463046FFF71A +:1016F000EFFFA04206D930466D68FFF7E9FF2544A9 +:10170000281A70BD3046FFF7E3FF201AF9E7000002 +:1017100070B50546406898B105F10800FFF7D8FF9D +:1017200005F10C0604463046FFF7D2FF84423046EE +:1017300094BF6D680025FFF7CBFF013C2C44201AB5 +:1017400070BD000038B50C460546FFF7C7FFA04244 +:1017500010D305F10800FFF7BBFF04446868B4FB31 +:10176000F0F100FB1144BFF35B8F0120AC60BFF3CD +:101770005B8F38BD0020FCE72DE9F0411446074699 +:101780000D46FFF7C5FF844228BF0446D4B1B846D2 +:1017900058F80C6B4046FFF79BFF304428604046EA +:1017A0007E68FFF795FF331A9C4203D86C600120D6 +:1017B000BDE8F0816B60A41B3B68AB602044E8602F +:1017C0000220F5E72046F3E738B50C460546FFF75B +:1017D0009FFFA04210D305F10C00FFF779FF0444EE +:1017E0006868B4FBF0F100FB1144BFF35B8F01208C +:1017F000EC60BFF35B8F38BD0020FCE72DE9FF41B3 +:10180000884669460746FFF7B7FF6C4606B204EB09 +:10181000C6060025B44209D06268206808EB0501BD +:10182000FFF73EFC636808341D44F3E72946384659 +:10183000FFF7CAFF284604B0BDE8F081F8B50546B9 +:101840000C300F46FFF744FF05F10806044630460A +:10185000FFF73EFFA042304688BF6C68FFF738FFB5 +:10186000201A386020B130462C68FFF731FF204441 +:10187000F8BD000073B5144606460D46FFF72EFF6F +:10188000844228BF04460190DCB101A93046FFF72D +:10189000D5FF019B33B93268C5E90233C5E900249D +:1018A00001200CE09C4238BF0194286001986860D8 +:1018B0008442F5D93368AB60241AEC60022002B090 +:1018C00070BD2046FBE700002DE9FF410F46694649 +:1018D000FFF7D0FF6C4600B204EBC0050026AC4217 +:1018E00009D0D4F8048054F8081BB8194246FFF711 +:1018F000D7FB4644F3E7304604B0BDE8F081000072 +:1019000038B50546FFF7E0FF044601462846FFF7D5 +:1019100019FF204638BD000010B4026854681A460A +:1019200023465DF8044B184700207047002070479D +:1019300070470000002070470E20704700F580506F +:1019400090F8C800C0F340007047000000F58050D8 +:1019500090F9D0007047000000F58050C0F8CC101E +:1019600001207047F7B50C68BDF8207014F00054E2 +:1019700070D10D7B082D6DD8302585F31188456910 +:10198000AE6876010CD4AC68240108D4AC6814F0BD +:1019900080545DD184F31188204603B0F0BD01244A +:1019A0000E6804F1180C002EB8BFF6004FEA0C1CAC +:1019B000B4BF46F00406760545F80C600E680FFAD1 +:1019C00084FC16F0804F18BF05EB0C1E05EB0C1CB9 +:1019D0001EBFDEF8806146F00206CEF880610E7B05 +:1019E000CCF8846105EB04158E68C5F88C614E68EF +:1019F000C5F88861DCF8805145F00105CCF88051CC +:101A000000EB441641F268052E4405EB44150544ED +:101A1000C6E9002308350E4601F10C0C56F804EB1C +:101A200045F804EB6645F9D1843436882E8000EB06 +:101A3000441407F00305267926F00B06354325717B +:101A4000002484F31188009700F0FCFC0120A4E737 +:101A50000224A5E74FF0FF309FE7000013B500F523 +:101A600080540191E06DFFF753FE1F280AD90199B8 +:101A7000E06D2022FFF7C2FEA0F12003584258413A +:101A800002B010BD0020FBE708B5302383F31188B6 +:101A900000F58050C06DFFF70FFE002383F311881F +:101AA00008BD0000002202608281426082607047AF +:101AB00010B500220023C0E900230023044603815F +:101AC0000C30FFF7EFFF204610BD0000F0B50546D3 +:101AD00000F580500C4690F8C83013F0040FC3F3A3 +:101AE000800108BF114661F3820304F1840680F887 +:101AF000C83005EB461389B01B79D8072ED57AB3C9 +:101B000019072DD46846FFF7D3FF05EB441303F5FF +:101B1000835303F1180703AA103318685968144651 +:101B200003C40833BB422246F7D1186820609B8863 +:101B3000A380DDE90E23CDE900230123ADF80830B1 +:101B40002B686946DB6B2846984705EB46152B79D1 +:101B50001A075CBF43F008032B7101E0002AF4D19F +:101B600009B0F0BD2DE9F0479A4688B0074688468F +:101B70009146302383F3118807F580546846FFF7B8 +:101B800097FFE06DFFF7AAFD1F282AD9E06D2022FC +:101B90006946FFF7B5FE202823D103AD444605ABC7 +:101BA0002E4603CE9E4220606160354604F1080453 +:101BB000F6D130682060B388A380DDE90023C9E94D +:101BC0000023BDF80830AAF80030002383F3118801 +:101BD00053464A464146384608B0BDE8F04700F053 +:101BE0001FBC002080F3118808B0BDE8F08700001A +:101BF0002DE9F84F0023C0E90133254B044640F896 +:101C0000183B0F46FFF74EFF04F12800FFF750FF87 +:101C100004F1480804F5825546460835304620361A +:101C2000FFF746FFAE42F9D104F580554FF48053DB +:101C30004FF00009C5E91339C5F848800123EE6566 +:101C400004F5875804F58456C5F8549085F8583043 +:101C500085F86030083608F108084FF0000A4FF0A8 +:101C6000000B46E908ABA6F11800FFF71BFF203672 +:101C700046F8289C4645F4D185F8D07017B1054840 +:101C800000F0B8FB044B63612046BDE8F88F00BF4D +:101C9000D44A0008AC4A00080064004010B5044B68 +:101CA000197804464A1C1A70FFF7A2FF204610BD9F +:101CB0001C4A00202DE9F047002950D0294B2A4F1B +:101CC000B7FBF1F599428CBF0A231123581EB5FBCF +:101CD000F3FC03FB1C53C4B22BB102280346F5D816 +:101CE0000020BDE8F0870CF1FF36B6F5806FF7D223 +:101CF000C4EBC40E0EF103034FEAE309C3F3C703B9 +:101D0000A4EB030809F1010A4FF47A755FFA88F031 +:101D100009FB05555AFA88F8B5FBF8F5B5F5617F6A +:101D2000C1BF0EF1FF33C3F3C703E01AC0B25C1C9E +:101D300050FA84F40CFB04F4B7FBF4F4A142CFD1C5 +:101D4000013BDBB20F2BCBD80138C0B20728C7D874 +:101D50000021107116809170D3700120C1E70846F0 +:101D6000BFE700BF3F420F0040787D0170B50546D8 +:101D70000E464FF47A746B695B6803F00103B3425B +:101D800007D04FF47A7001F08FFC013CF3D120466C +:101D900070BD0120FCE7000030B54269936913F083 +:101DA000700F16D000230B4C936103F1840200EBFB +:101DB000421211794D0709D5890707D5416954F8B1 +:101DC00023508D60117941F0040111710133032B0F +:101DD000EBD130BDC04A000873B51D4643691646B5 +:101DE0009A68D207044609D59A6801219960C2F31E +:101DF0004002CDE900650021FFF768FE63699A683B +:101E0000D1050BD59A684FF480719960C2F34022D6 +:101E1000CDE9006501212046FFF758FE63699A6805 +:101E2000D2030BD59A684FF480319960C2F34042D7 +:101E3000CDE9006502212046FFF748FE04F58053F6 +:101E4000D3F8CC0010B103681B699847204602B054 +:101E5000BDE87040FFF7A0BFF8B504464669002909 +:101E600072D106F10C073868800770D006EB0115B7 +:101E70003868D5F8B00110F0040FD5F8B0011ABFDA +:101E8000C00840F00040400DA061D5F8B0C11CF082 +:101E9000020F1CBF40F08040A061D5F8B40106EBF2 +:101EA000011100F00F0084F82400D1F8B801207768 +:101EB000D1F8B801000A6077D1F8B801000CA0771A +:101EC000D1F8B801000EE077D1F8BC0184F8200009 +:101ED000D1F8BC01000A84F82100D1F8BC01000C43 +:101EE00084F82200D1F8BC11090E84F8231038219F +:101EF000396004F1340004F1180104F1240551F8AB +:101F0000046B40F8046BA942F9D109880180C4E947 +:101F10000A2321460023238651F8283B2046DB6B09 +:101F2000984704F5805393F8C820D3F8CC0042F0CA +:101F3000040283F8C82010B103681B699847204643 +:101F4000BDE8F840FFF728BF06F110078BE7F8BDA2 +:101F500010B5044600F056FA02460B4652EA030159 +:101F600002D0013A63F100030449086820B1214618 +:101F7000BDE81040FFF770BF10BD00BF184A002039 +:101F8000F0B5302181F31188DFF848C000F58351A6 +:101F90000831002404F1840500EB45152E797707FC +:101FA0000ED4F6060CD5D1E9007697429E4107D2B1 +:101FB00046695CF82470B7602E7946F004062E71ED +:101FC0000134032C01F12001E4D1002383F31188B3 +:101FD000F0BD00BFC04A000808B5302383F3118864 +:101FE000FFF7DAFE002383F3118808BDF8B54369D3 +:101FF0000546986800F0E050B0F1E05F0F4621D050 +:10200000F8B1302383F3118805F58354103400268A +:1020100006F1840305EB43131B791A0706D5013635 +:10202000032E04F12004F3D1012007E05B07F6D46E +:102030002146384600F040FA0028F0D1002383F30F +:102040001188F8BD0120FCE708B5302383F311881F +:1020500000F58050C06DFFF741FB002383F311882A +:1020600043090CBF0120002008BD0000F8B51D4643 +:10207000002313700F4606461446FFF7E5FF80F075 +:102080000100387025B129463046FFF7AFFF2070B8 +:10209000F8BD00002DE9B8410C4615461F468046A4 +:1020A00000F0B0F90B462178024609B9287850B102 +:1020B0004046FFF765FFFFF78FFF3B462A46214664 +:1020C000FFF7D4FF0120BDE8B881000070B53026CD +:1020D00086F31188174B1A6C42F000721A641A6A60 +:1020E00042F000721A621A6A22F000721A62002329 +:1020F00083F3118800F5805494F8C83013F001057B +:1021000016D1A9B186F311880321132001F0C8F973 +:102110000321142001F0C4F90321152001F0C0F9B6 +:1021200094F8C83043F0010384F8C83085F311886F +:1021300070BD00BF003802402DE9F04700F5805522 +:1021400088B095F8D030012B04468846164600F238 +:102150008180814F57F823200AB947F82300D7F828 +:1021600000A0C4F80C802674BAF1000F64D095F872 +:10217000D030012B70D001212046FFF7A7FF30237C +:1021800083F311886269136823F0020313606269A4 +:10219000136843F001031360636900275F6187F3ED +:1021A000118801212046FFF7E1FD002800F095800D +:1021B000E86DFFF781FA04F58359BA4609F1080979 +:1021C000202200216846FEF77DFF02A8FFF76AFC87 +:1021D000CDF818A06A4609EB07030DF1180E9446D6 +:1021E000BCE80300F44518605960624603F1080337 +:1021F000F5D1DCF80000186020379CF804201A7133 +:10220000602FDDD195F8C8306FF38203002785F881 +:10221000C8306A4641462046ADF80070ADF80270FD +:102220008DF80470FFF746FD636948BB4FF4004228 +:102230001A6008B0BDE8F08741F2D80002F05AFBFE +:10224000814610B15146FFF7D3FCC7F80090B9F1B1 +:10225000000F8CD10020ECE7386803681B6B9847AF +:102260000146002887D13868FFF730FF38680368D7 +:1022700032465B684146984700287FF47CAFE9E727 +:1022800061221A609DF802309DF803201B0612049B +:1022900002F4702203F040731343BDF80020C2F330 +:1022A000090213439DF804201205022E02F4E002F5 +:1022B0000CBF4FF000410021134362690B43D3610F +:1022C000636913225A616269136823F00103136082 +:1022D00039462046FFF74AFD08B96369A6E795F835 +:1022E000D03093BB6169D1F8002242F00102C1F8FD +:1022F00000226169D1F8002222F47C5222F00E0201 +:10230000C1F800226169D1F8002242F46062C1F88C +:1023100000226269C2F814326269C2F8043262694A +:1023200041F6FF71C2F80C126269C2F8403262696C +:10233000C2F8443263690122C3F81C226269D2F8F0 +:10234000003223F00103C2F8003295F8C83043F0A0 +:10235000020385F8C8306CE7184A002008B500F081 +:1023600051F850EA0103024602D0421E61F1000119 +:10237000044B186810B10B46FFF72EFDBDE808406E +:1023800001F064B8184A002008B50020FFF7E0FD0E +:10239000BDE8084001F05AB808B50120FFF7D8FDA4 +:1023A000BDE8084001F052B800B59BB0EFF30981D9 +:1023B00068226846FEF774FEEFF30583014B9B6BC2 +:1023C000FEE700BF00ED00E008B5FFF7EDFF0000FD +:1023D00000B59BB0EFF3098168226846FEF760FE06 +:1023E000EFF30583014B5B6BFEE700BF00ED00E000 +:1023F000FEE700000FB408B5029801F005F9FEE70A +:1024000001F01ABC01F0FCBB13B56C4684E8060071 +:10241000031D94E8030083E80500012002B010BD0D +:1024200073B58568019155B11B885B0707D4D0E966 +:1024300000369B6B9847019AC1B23046A8470120ED +:1024400002B070BDF0B5866889B005460C465EB135 +:10245000BDF838305B070AD4D0E900379B6B98474A +:102460002246C1B23846B047012009B0F0BD002273 +:102470000023CDE900230023ADF808300A4603AB62 +:1024800001F10806106851681C4603C40832B242C4 +:102490002346F7D1106820609288A280FFF7B2FF30 +:1024A0000423ADF808302B68CDE90001DB6B6946E9 +:1024B00028469847D8E7000030B503680968DD0F63 +:1024C000B5EBD17F23F0604421F060424FEAD17038 +:1024D0000BD0002BB8BFA40C0029B8BF920C9442BB +:1024E00002D034BF0120002030BD944205D1C1F399 +:1024F0008070C3F380738342F6D194422CBF0020D6 +:102500000120F1E72DE9F041456A15B94162BDE8C6 +:10251000F0814B6823F06047C3F38A464FEAD37ECD +:10252000C3F3807816EA230638BF3E46AC462B46F6 +:102530005A68BEEBD27F22F060440AD0002A18DA33 +:10254000A40CB44217D19D420FD10D60DEE71346B3 +:10255000EEE7A74207D102F08044C2F38072424501 +:102560000BD054B1EFE708D2EDE7CCF800100B60C8 +:10257000CDE7B44201D0B442E5D81A689C46002A9F +:10258000E5D11960C3E700002DE9F047089D01F08F +:1025900007044FEAD508224405F0070500EBD100F7 +:1025A0004FF47F49944201D1BDE8F08704F007075A +:1025B00005F0070A57453E4638BF5646C6F108069D +:1025C000111B8E4228BF0E46E10808EBD50E415C78 +:1025D00013F80EC0B94029FA06F721FA0AF1FFB242 +:1025E0008CEA010147FA0AF739408CEA010C03F83A +:1025F0000EC034443544D5E780EA0120082341F277 +:10260000210201B24000002980B203F1FF33B8BFBC +:10261000504013F0FF03F4D17047000038B50C466A +:102620008D18A54200D138BD14F8011BFFF7E4FF57 +:10263000F7E7000042684AB1136843604389818923 +:1026400001339BB29942438138BF83811046704762 +:1026500070B588B0202204460D4668460021FEF77A +:1026600031FD20460495FFF7E5FF024658B16B4661 +:10267000054608AE1C4603CCB44228606960234678 +:1026800005F10805F6D1104608B070BD082817D925 +:1026900009280CD00A280CD00B280CD00C280CD000 +:1026A0000D280CD00E2814BF4020302070470C207D +:1026B0007047102070471420704718207047202062 +:1026C00070470000082817D90C280CD910280CD9FD +:1026D00014280CD918280CD920280CD930288CBFE4 +:1026E0000F200E207047092070470A2070470B20EA +:1026F00070470C2070470D20704700002DE9F8430B +:10270000078C072F04461ED9D0E9029800254FF602 +:10271000FF73C5F12006A5F1200029FA05F108FA9A +:1027200006F628FA00F031430143C9B21846FFF714 +:1027300063FF0835402D0346EBD1E1693A46BDE819 +:10274000F843FFF76BBF4FF6FF70BDE8F88300005A +:1027500010B54B6823B9CA8A63F30902CA8210BD57 +:1027600004691A681C600361C38A013BC3824A6022 +:10277000EFE700002DE9F84F1D46CB8A0F46C3F363 +:1027800009010529814692460B4630D00020AAB2A5 +:1027900007F11A049EB2042E1FFA80F80FD8904554 +:1027A00003F1010306D3FB8A0A4462F30903FB82A7 +:1027B00001201AE01AF80060E6540130EAE790457B +:1027C000F1D2A1F1050B1C237C68BBFBF3F203FBE8 +:1027D00012BB1FFA8BF6002C45D14846FFF72AFFA3 +:1027E000044638B978606FF00200BDE8F88F4FF00A +:1027F0000008E6E7002606607860ADB24FF0000BF7 +:10280000454510D90AEB0803221D13F8011B915509 +:10281000B1B208F101081B291FFA88F82BD04545F1 +:1028200006F10106F1D8FB8AC3F30902154465F3EA +:102830000903BCE7013292B21C462368002BF9D190 +:102840006B1F0B441C21B3FBF1F301339BB29A4283 +:10285000D3D2BBF1000FD0D14846FFF7EBFE20B931 +:10286000C4F800B0BFE70122E7E7C0F800B05E4659 +:1028700020600446C1E74545D5D94846FFF7DAFE52 +:1028800008B92060AFE7C0F800B000262060044619 +:10289000B6E700002DE9F04F2DED028B1C4683B00A +:1028A0005B69019207468846002B00F09A80238CD2 +:1028B0002BB1E269002A00F09480072B35D807F18C +:1028C0000C00FFF7B7FE054638B96FF00205284641 +:1028D00003B0BDEC028BBDE8F08F14220021FEF79F +:1028E000F1FB228CE16905F10800FEF7D9FB208C91 +:1028F000013080B2FFF7E6FEFFF7C8FE013880B274 +:102900002084013028746369228C1B782A4403F0E8 +:102910001F0363F03F0348F00041137238466960BB +:102920002946FFF7EFFD0125D1E700F10C034FF039 +:10293000000908EE103A4FF0800A4E464D4618EE58 +:10294000100AFFF777FE83460028BED0142200212C +:10295000FEF7B8FB002E3AD1019BABF808300222FB +:102960000BF1080E1FFA82FC0CF10100BCF1060FFE +:10297000218C80B201D88E422BD3FFF7A3FEFFF744 +:1029800085FE62691278013802F01F028E4208BF8C +:102990004FF0400A42EA49121BFA80F14AEA020A61 +:1029A000013048F0004281F808A08BF81000CBF805 +:1029B000042059463846FFF7A5FD238C0135B34264 +:1029C0002DB289F001094FF0000AB8D17FE700224B +:1029D000C6E7E169895D0EF802100136B6B2013230 +:1029E000C0E76FF0010572E7F8B515460E463022D4 +:1029F000002104461F46FEF765FB069B6360B5F5A4 +:102A0000001F079BA76034BF6A094FF6FF72A362DD +:102A100097B2E66104F1100000239A4206D8002321 +:102A20000360A782E3822383E360F8BD066001337D +:102A300030462036F1E7000003781BB94BB2002B7B +:102A4000C8BF01707047000000787047F8B50C46A9 +:102A5000C969074611B9238C002B37D1257E1F2D5C +:102A600034D8387828BB228C072A2CD8268A36F00E +:102A700003032BD14FF6FF70FFF7D0FD20F00100CC +:102A80003102400441EA0561400C41EA40254FF61D +:102A9000FF72234629463846FFF7FCFE002807DD73 +:102AA000626913780133DBB21F2B88BF00231370D8 +:102AB000F8BD218A2D0645EA012505432046FFF78A +:102AC0001DFE0246E5E76FF00300F1E76FF001003D +:102AD000EEE7000070B58AB00446164600212822B1 +:102AE00068461D46FEF7EEFABDF83830ADF81030F6 +:102AF0000F9B05939DF840308DF81830119B07937C +:102B00006946BDF84830ADF820302046CDE9026571 +:102B1000FFF79CFF0AB070BD2DE9F041D36905466F +:102B20000C4616460BB9138C5BBB377E1F2F28D87B +:102B300095F80080B8F1000F26D03046FFF7DEFD93 +:102B40003378210241EAC33141EA0801338A41EA7C +:102B5000076141EA03410246334641F080012846BD +:102B6000FFF798FE00280ADD3378012B07D1726940 +:102B700013780133DBB21F2B88BF00231370BDE82D +:102B8000F0816FF00100FAE76FF00300F7E7000053 +:102B9000F0B58BB004460D46174600212822684642 +:102BA0001E46FEF78FFA9DF84C305A1E5342534191 +:102BB0008DF800309DF84030ADF81030119B059332 +:102BC0009DF848308DF81830149B07936A46BDF87D +:102BD0005430ADF8203029462046CDE90276FFF783 +:102BE0009BFF0BB0F0BD0000406A00B1043070479D +:102BF000436A1A68426202691A600361C38A013B30 +:102C0000C38270472DE9F041D0F82080194E144658 +:102C10001D464146002709B9BDE8F081D1E90223EC +:102C2000A21A65EB0303964277EB03031ED2036AF5 +:102C30008B420DD1FFF78CFD036A1B6803620369A9 +:102C40000B60C38A0161016A013BC3828846E2E7E7 +:102C5000FFF77EFD0B68C8F8003003690B60C38A7C +:102C60000161013BC382D8F80010D4E788460968A7 +:102C7000D1E700BF80841E002DE9F04F8BB00D46D8 +:102C8000DDF8509014469B468046002800F01981DC +:102C9000B9F1000F00F01581531E3F2B00F2118196 +:102CA000012A03D1BBF1000F40F00B810023CDE9D5 +:102CB0000833B8F81430B5EBC30F4FEAC30703D39A +:102CC00000200BB0BDE8F08F2B199F42D8F80C30D4 +:102CD0003ABF7F1BFFB227461BB9D8F81030002B34 +:102CE0007AD0272D4ED8C5F12806B7424FF0000301 +:102CF0002CBFF6B23E4600932946D8F8080008AB30 +:102D00003246FFF741FCA7EB060A35445FFA8AFA20 +:102D1000B8F8143003F10053053BDB000493D8F8F6 +:102D20000C3003932821039B13B1BAF1000F2CD16F +:102D3000D8F8100040B1BAF1000F05D0009608ABEA +:102D40005246691AFFF720FC38B2002FB8D0660748 +:102D50000AD00AAB03EBD401624211F8083C02F03E +:102D60000702134101F8083C082C3CD9102C40F212 +:102D7000B580202C40F2B780BBF1000F00F09C80A2 +:102D8000082334E0BA460026C2E7049BE02B28BFA4 +:102D9000E02306930B44AB42059314D95A1B0398C6 +:102DA0000096924534BF5246D2B2691A08AB04303D +:102DB0000792FFF7E9FB079A1644AAEB020A1544AB +:102DC000F6B25FFA8AFA049B069A05999B1A049355 +:102DD000039B1B680393A6E70093D8F8080008AB91 +:102DE0003A462946AEE7BBF1000F13D00123B4EBFE +:102DF000C30F6CD0082C12D89DF82030621E23FA25 +:102E000002F2D50706D54FF0FF3202FA04F423434D +:102E10008DF820309DF8203089F8003051E7102CD3 +:102E200012D8BDF82030621E23FA02F2D10706D56F +:102E30004FF0FF3202FA04F42343ADF82030BDF81E +:102E40002030A9F800303CE7202C0FD80899631EE9 +:102E500021FA03F3DA0705D54FF0FF3202FA04F442 +:102E60000C430894089BC9F800302AE7402C2BD06B +:102E7000DDE90865611EC4F12102A4F1210326FAEF +:102E800001F105FA02F225FA03F311431943CB07C6 +:102E900012D50122A4F12003C4F1200102FA03F3A8 +:102EA00022FA01F1A240524243EA010363EB4303D9 +:102EB00032432B43CDE90823DDE90823C9E9002388 +:102EC000FFE66FF00100FCE66FF00800F9E6082C61 +:102ED000A0D9102CB3D9202CEED8C3E7BBF1000F3A +:102EE000ADD0022383E7BBF1000FBBD004237EE704 +:102EF00030B5012A144638BF0124402C85B028BFC4 +:102F000040240025012ACDE9025518D81B788DF8F8 +:102F1000083063070AD004AB03EBD405624215F80E +:102F2000083C02F00702934005F8083C0091034674 +:102F30002246002102A8FFF727FB05B030BD082A72 +:102F4000E4D9102A03D81B88ADF80830E1E7202A1D +:102F50008DBFD3E900231B680293CDE90223D8E794 +:102F600010B5CB681BB98B600B618B8210BD0469F7 +:102F70001A681C600361C38A013BC382CA60F0E720 +:102F800003064CBFC0F3C0300220704708B50246AC +:102F9000FFF7F6FF022806D15306C2F30F2001D136 +:102FA00000F0030008BDC2F30740FBE72DE9F04F36 +:102FB00093B0CDE903230A6804461046FFF7E0FF0B +:102FC000022814BFC2F306260026002A0D468246B8 +:102FD00080F2F28112F0C04940F0EE81097B0029B5 +:102FE00000F0EA81022803D02378B34240F0E78161 +:102FF000C2F304630693104602F07F030593FFF7C4 +:10300000C5FF059B29444FEA834848EA0A4848EA35 +:103010004668CE7800230022CDE90823F3098346D1 +:1030200048EA0008029367D0059B00930246676850 +:10303000534608A92046B847002800F0C381276AF4 +:103040004FB9414604F10C00FFF702FB074690B967 +:103050006FF0020054E03B6998450DD03F68002FA7 +:10306000F9D1414604F10C00FFF7F2FA07460028B7 +:10307000EED0236A3B60276297F817C006F01F085E +:10308000CCF3840CACEB08001FFA80FE0028B8BF1C +:103090000EF12000A8EB0C031FFA83FED7E90221F2 +:1030A000B8BF00B2002B0793BEBF0EF120031BB2C6 +:1030B000079352EA010338D0039BDFF824E39A1AFE +:1030C000049B4FF0000C63EB010196457CEB010380 +:1030D0002BD36B7B97F81AE0734519D1029B002B19 +:1030E00078D0012821DC7868F8B9DFF8F0C294457F +:1030F00070EB010316D337E0276A27B96FF00C0095 +:1031000013B0BDE8F08F3B699845B5D03F68F4E750 +:10311000B24890427CEB010301D30020F0E7029B10 +:10312000002BFAD0079B0F2B17DCFA7DB30002F0BF +:10313000030203F07C031343FB7539462046FFF777 +:1031400007FB6B7BBB76029B3BB9FB7DC3F3840221 +:10315000013262F38603FB75D0E76A7BBB7E9A423D +:10316000DBD1029B002B35D0B309022B32D0039B5D +:10317000BB60049BFB60142200210DA8FDF7A2FF99 +:10318000039B0A93049B0B932B1D0C932B7BADF895 +:103190003EB0013BDBB2ADF83C30069B8DF84230CF +:1031A000059B8DF8433094F82C308DF840A083F0C7 +:1031B00001038DF844308DF84180A3680AA92046A8 +:1031C0009847FB7DC3F38403013303F01F039B0285 +:1031D000FB82A2E7FB7DC6F34012B2EBD31F40F0A7 +:1031E000F480C3F38403434540F0F280029A2B7BC2 +:1031F000B609002A4DD0F2075DD4032B40F2EB80D4 +:10320000039BBB60049BFB602B7BAE1D033BDBB2CF +:103210003246394604F10C00FFF7ACFA00280CDA0C +:1032200039462046FFF794FAFB7DC3F3840301334C +:1032300003F01F039B02FB820AE7DDE90884AB88E9 +:103240003B834FF6FF73C9F12000A9F1200228FA51 +:1032500009F104FA00F0014324FA02F2114318467E +:10326000C9B2FFF7C9F909F10809B9F1400F0346DE +:10327000E9D1B8822A7B033AD2B23146FFF7CEF9C0 +:10328000FB7DB882DA43C2F3C01262F3C713FB7549 +:1032900043E786B92E1D013BDBB23246394604F1C5 +:1032A0000C00FFF767FA0028BADB2A7BB88A013ADC +:1032B000D2B23146E2E7F98AC1F30901013B0429A0 +:1032C000DAB25BD8281D002307F11B069A4208D901 +:1032D00010F801CB06F801C0013101330529DBB23A +:1032E000F4D103990A9104990B91934207F11B01C0 +:1032F0000C9138BF043379680D9134BF55FA83F3CC +:1033000000230E93FB8AADF83EB0C3F309031A44C1 +:10331000069B8DF84230059B8DF8433094F82C3095 +:10332000ADF83C2083F001038DF8443000238DF884 +:1033300040A08DF841807B602A7BB88A013A291D24 +:10334000FFF76CF93B8BB882834203D1A3680AA9CB +:103350002046984720460AA9FFF702FEFB7DBA8A5D +:10336000C3F38403013303F01F039B02FB823B8BF7 +:103370009A420CBF00206FF01000C1E67B68002B62 +:10338000AFD0052001E01C3033461E68002EFAD174 +:10339000091A081D2E1D184401EB090CBCF11B0F66 +:1033A0005FFA89F39DD89A429BD916F8013B00F841 +:1033B000013B09F10109EFE76FF00900A0E66FF0AA +:1033C0000A009DE66FF00B009AE66FF00D0097E69D +:1033D0006FF00E0094E66FF00F0091E640420F0090 +:1033E00080841E00EFF3098305494A6B22F0010235 +:1033F0004A63683383F30988002383F31188704795 +:1034000000EF00E0302080F3118862B60C4B0D4ACB +:10341000D96821F4E0610904090C0A43DA60D3F8A1 +:10342000FC20094942F08072C3F8FC200A6842F08F +:1034300001020A602022DA7783F82200704700BF79 +:1034400000ED00E00003FA05001000E010B53023A5 +:1034500083F311880E4B5B6813F4006314D0F1EE14 +:10346000103AEFF30984683C4FF08073E361094B35 +:10347000DB6B236684F3098800F090F810B1064BEB +:10348000A36110BD054BFBE783F31188F9E700BF8B +:1034900000ED00E000EF00E03F03000842030008F9 +:1034A00000F1604303F561430901C9B283F80013D9 +:1034B000012200F01F039A4043099B0003F160437F +:1034C00003F56143C3F880211A6070470023037538 +:1034D000826803691B6899689142FBD25A6803604D +:1034E000426010605860704700230375826803696A +:1034F0001B6899689142FBD85A680360426010606B +:103500005860704708B50846302383F311880B7D57 +:10351000032B05D0042B0DD02BB983F3118808BDE4 +:103520008B6900221A604FF0FF338361FFF7CEFFF3 +:103530000023F2E7D1E9003213605A60F3E700009C +:10354000FFF7C4BF054BD9680875186802681A6090 +:10355000536001220275D860FCF7DCBE284A0020C7 +:1035600030B50C4BDD684B1C87B004460FD02B46A2 +:10357000094A684600F046F92046FFF7E3FF009B42 +:1035800013B1684600F048F9A86907B030BDFFF7ED +:10359000D9FFF9E7284A002005350008044B1A68CE +:1035A000DB6890689B68984294BF002001207047B8 +:1035B000284A0020084B10B51C68D86822681A6099 +:1035C000536001222275DC60FFF78EFF0146204622 +:1035D000BDE81040FCF79EBE284A002038B5074CD5 +:1035E00007490848012300252370656000F028FC86 +:1035F0000223237085F3118838BD00BF904C002052 +:10360000184B0008284A002008B572B6044B18650C +:1036100000F0E2FA00F08EFB024B03221A70FEE784 +:10362000284A0020904C002000F02CB98B60022327 +:1036300008618B82084670478368A3F1840243F8CF +:10364000142C026943F8442C426943F8402C094A7F +:1036500043F8242CC26843F8182C022203F80C2CDF +:10366000002203F80B2C044A43F8102CA3F120008D +:10367000704700BF2D030008284A002008B5FFF757 +:10368000DBFFBDE80840FFF75BBF0000024BDB68D3 +:1036900098610F20FFF756BF284A0020302383F39C +:1036A0001188FFF7F3BF000008B50146302383F30C +:1036B00011880820FFF754FF002383F3118808BD09 +:1036C000064BDB6839B1426818605A60136043608A +:1036D0000420FFF745BF4FF0FF307047284A002015 +:1036E0000368984206D01A680260506099611846D3 +:1036F000FFF726BF7047000010B503689C68A24220 +:103700000CD85C688A600B604C60216059609968D5 +:103710008A1A9A604FF0FF33836010BD1B68121B3A +:10372000ECE700000A2938BF0A2170B504460D46AF +:103730000A26601900F07EFB00F06AFB041BA5421C +:1037400003D8751C2E460446F3E70A2E04D9BDE8BB +:103750007040012000F0B4BB70BD0000F8B5144B00 +:103760000D46D96103F1100141600A2A196982608E +:1037700038BF0A22016048601861A818144600F09A +:103780004BFB0A2700F044FB431BA342064606D32B +:103790007C1C281900F04EFB27463546F2E70A2F1D +:1037A00004D9BDE8F840012000F08ABBF8BD00BF95 +:1037B000284A0020F8B506460D4600F029FB0F4ABE +:1037C000134653F8107F9F4206D12A4601463046E1 +:1037D000BDE8F840FFF7C2BFD169BB68441A2C1995 +:1037E00028BF2C46A34202D92946FFF79BFF224659 +:1037F00031460348BDE8F840FFF77EBF284A002065 +:10380000384A002010B4C0E9032300235DF8044BBC +:103810004361FFF7CFBF000010B5194C23699842F0 +:103820000DD0D0E90032816813605A609A680A446A +:103830009A60002303604FF0FF33A36110BD23465D +:10384000026843F8102F53600022026022699A42F6 +:1038500003D1BDE8104000F0E7BA936881680B44DB +:10386000936000F0D5FA2269E1699268441AA24295 +:10387000E4D91144BDE81040091AFFF753BF00BF57 +:10388000284A00202DE9F047DFF8BC8008F1100736 +:103890002C4ED8F8105000F0BBFAD8F81C40AA689B +:1038A000031B9A423ED81444D5E900324FF0000978 +:1038B000C8F81C4013605A60C5F80090D8F8103062 +:1038C000B34201D100F0B0FA89F31188D5E9033190 +:1038D00028469847302383F311886B69002BD8D092 +:1038E00000F096FA6A69A0EB04094A4582460DD2B7 +:1038F000022000F0E5FA0022D8F81030B34208D1D7 +:1039000051462846BDE8F047FFF728BF121A224467 +:10391000F2E712EB090938BF4A4629463846FFF755 +:10392000EBFEB5E7D8F81030B34208D01444211AA2 +:10393000C8F81C00A960BDE8F047FFF7F3BEBDE87A +:10394000F08700BF384A0020284A002038B500F030 +:103950005FFA054AD2E90845031B181945F1000131 +:10396000C2E9080138BD00BF284A00200020704786 +:10397000FEE70000704700004FF0FF307047000086 +:10398000BFF34F8F024AD368DB03FCD4704700BFFC +:10399000003C024008B5094B1B7873B9FFF7F0FFF4 +:1039A000074B1A69002ABFBF064A5A6002F18832E3 +:1039B0005A601A6822F480621A6008BD984C002090 +:1039C000003C02402301674508B50B4B1B7893B9B7 +:1039D000FFF7D6FF094B1A6942F000421A611A68D4 +:1039E00042F480521A601A6822F480521A601A68EF +:1039F00042F480621A6008BD984C0020003C0240EE +:103A00000728F0B516D80C4C0C4923787BB90C4D1F +:103A10000E4608234FF0006255F8047B46F8042B4D +:103A2000013B13F0FF033A44F6D10123237051F810 +:103A30002000F0BD0020FCE7BC4C00209C4C002086 +:103A4000244B0008014B53F820007047244B00081A +:103A500008207047072810B5044601D9002010BD82 +:103A6000FFF7CEFF064B53F824301844C21A0BB9A7 +:103A70000120F4E712680132F0D1043BF6E700BF01 +:103A8000244B0008072810B5044621D8FFF778FF1B +:103A9000FFF780FF0F4AF323D360C300DBB243F488 +:103AA000007343F002031361136943F4803313611D +:103AB000FFF766FFFFF7A4FF074B53F8241000F051 +:103AC00035F9FFF781FF2046BDE81040FFF7C2BF80 +:103AD000002010BD003C0240244B0008F8B512F055 +:103AE0000103144642D185182E4A954257D82E4BD1 +:103AF0001B6813F0010352D02C4DFFF74BFFF3234B +:103B0000EB60FFF73DFF40F20127032C15D824F0AE +:103B100001046618254C401A40F20117B14223698E +:103B200000EB010524D123F001032361FFF74CFFD3 +:103B30000120F8BD043C0430E7E78307E7D12B6997 +:103B400023F440732B612B693B432B6151F8046BC9 +:103B50000660BFF34F8FFFF713FF03689E42E9D063 +:103B60002B6923F001032B61FFF72EFF0020E0E714 +:103B700023F44073236123693B4323610B882B802B +:103B8000BFF34F8FFFF7FCFE2D8831F8023BADB23B +:103B9000AB42C3D0236923F001032361E4E7184655 +:103BA000C7E700BF0000080800380240003C0240A0 +:103BB000084908B50B7828B11BB9FFF7EBFE0123C4 +:103BC0000B7008BD002BFCD0BDE808400870FFF763 +:103BD000FBBE00BF984C00200149024800F0A8B885 +:103BE00000FF0300000100200846114600F0A4BEBB +:103BF000012000F0A1BE0000084600F0BBBE00009E +:103C000038B5EFF311859DB9EFF30584C4F30804CB +:103C1000302334B183F31188FFF798FE85F31188C0 +:103C200038BD83F31188FFF791FE84F3118838BD06 +:103C3000BDE83840FFF78ABE38B5FFF7E1FF114C09 +:103C4000114AC00840EA4170A0FB025EC908A0FB0F +:103C5000040C1CEB050CA1FB04404FF000035B417E +:103C6000A1FB02121CEB040C43EB000011EB0E0154 +:103C700042F10002411842F10000090941EA0070D6 +:103C800038BD00BFCFF753E3A59BC42010B5024455 +:103C9000064BD2B2904200D110BD441C00B253F882 +:103CA000200041F8040BE0B2F4E700BF50280040C8 +:103CB0000F4B30B51C6F240407D41C6F44F4007400 +:103CC0001C671C6F44F400441C670A4C236843F4CF +:103CD000807323600244084BD2B2904200D130BDC1 +:103CE000441C00B251F8045B43F82050E0B2F4E702 +:103CF00000380240007000405028004007B5012203 +:103D000001A90020FFF7C2FF019803B05DF804FB92 +:103D100013B50446FFF7F2FFA04205D0012201A926 +:103D200000200194FFF7C4FF02B010BD70470000EF +:103D30007047000070470000074B45F255521A606B +:103D400002225A6040F6FF729A604CF6CC421A602A +:103D5000024B01221A70704700300040C44C002012 +:103D6000034B1B781BB1034B4AF6AA221A6070471B +:103D7000C44C002000300040034B1A681AB9034AB3 +:103D8000D2F874281A607047C04C002000300240FE +:103D9000024B4FF08072C3F8742870470030024025 +:103DA00008B5FFF7E9FF024B1868C0F3407008BD83 +:103DB000C04C002008B5FFF7DFFF024B1868C0F3C6 +:103DC000007008BDC04C002070470000FEE70000F6 +:103DD0000A4B0B480B4A90420BD30B4BDA1C121ABE +:103DE000C11E22F003028B4238BF00220021FDF7E2 +:103DF00069B953F8041B40F8041BECE7D84C0008E1 +:103E0000BC4F0020BC4F0020BC4F002000F0CAB8BF +:103E10004FF08043586A70474FF080430022586348 +:103E20001A610222DA6070474FF080430022DA60A4 +:103E3000704700004FF0804358637047FEE7000072 +:103E400070B51B4B01630025044686B0586085623F +:103E50000E46FFF7D7FA04F11003C4E904334FF01C +:103E6000FF33C4E90635C4E90044A560E562FFF705 +:103E7000CFFF2B460246C4E9082304F134010D4A62 +:103E8000256580232046FFF7D1FB0123E0600A4A25 +:103E90000375009272680192B268CDE90223074B64 +:103EA0006846CDE90435FFF7E9FB06B070BD00BFF9 +:103EB000904C0020444B0008494B00083D3E000850 +:103EC000024AD36A1843D062704700BF284A0020D4 +:103ED0004B6843608B688360CB68C3600B69436148 +:103EE0004B6903628B6943620B6803607047000093 +:103EF00008B5234B23481A6942F0FF021A611A6978 +:103F000022F0FF021A611A691A6B42F0FF021A636B +:103F10001A6D42F0FF021A651B4A1B6D1146FFF72E +:103F2000D7FF02F11C0100F58060FFF7D1FF02F11D +:103F3000380100F58060FFF7CBFF02F1540100F576 +:103F40008060FFF7C5FF02F1700100F58060FFF7A8 +:103F5000BFFF02F18C0100F58060FFF7B9FF02F1AD +:103F6000A80100F58060FFF7B3FF02F1C40100F57E +:103F70008060FFF7ADFFBDE8084000F08DB800BFDE +:103F80000038024000000240504B000808B500F025 +:103F900019FAFFF723FBBDE80840FFF7EDBE00006C +:103FA000704700000F4B1A6C42F001021A641A6E3F +:103FB00042F001021A660C4A1B6E936843F001033B +:103FC00093604FF0804331229A624FF0FF32DA6201 +:103FD00000229A615A63DA605A6001225A611A60BB +:103FE000704700BF00380240002004E04FF08042DC +:103FF00008B51169D3680B40D9B2C9439B07116159 +:1040000007D5302383F31188FFF70EFB002383F3DA +:10401000118808BD1E4B1A6962F0FF021A611A6905 +:10402000D2B21A614FF0FF301A695A695861002103 +:104030005A6959615A691A6A62F080521A621A6A98 +:1040400002F080521A621A6A5A6A58625A6A5962AF +:104050005A6A1A6C42F080521A641A6E42F0805208 +:104060001A661A6E0B4A106840F480701060186F60 +:1040700000F44070B0F5007F1EBF4FF48030186729 +:104080001967536823F40073536000F073B900BFDD +:1040900000380240007000403B4B3C4A1A643C4AE6 +:1040A0004FF4404111601A6842F001021A601A6828 +:1040B0009007FCD59A6822F003029A60324B9A6806 +:1040C00012F00C02FBD1196801F0F90119609A6035 +:1040D0001A6842F480321A601A689103FCD55A6F4C +:1040E00042F001025A67284B5A6F9207FCD5294AC1 +:1040F0005A601A6842F080721A60254A5368580460 +:10410000FCD5214B1A689101FCD5234AC3F88420C1 +:104110001A6842F080621A601A681201FCD51F4AC0 +:104120009A600322C3F88C204FF00062C3F89420F9 +:104130001B4B1A681B4B9A421B4B21D11B4A11681F +:104140001B4A91421CD140F203121A60164A1368AE +:1041500003F00F03032BFAD10B4B9A6842F00202D3 +:104160009A609A6802F00C02082AFAD15A6C42F45A +:1041700080425A645A6E42F480425A665B6E7047BF +:1041800040F20372E1E700BF003802400004001073 +:104190000070004008194002103000240094883854 +:1041A000002004E011640020003C024000ED00E02B +:1041B00041C20F41074A08B5536903F00103536137 +:1041C00023B1054A13680BB150689847BDE8084011 +:1041D000FFF73CB9003C0140C84C0020074A08B535 +:1041E000536903F00203536123B1054A93680BB18D +:1041F000D0689847BDE80840FFF728B9003C014067 +:10420000C84C0020074A08B5536903F00403536102 +:1042100023B1054A13690BB150699847BDE80840BE +:10422000FFF714B9003C0140C84C0020074A08B50C +:10423000536903F00803536123B1054A93690BB135 +:10424000D0699847BDE80840FFF700B9003C01403D +:10425000C84C0020074A08B5536903F010035361A6 +:1042600023B1054A136A0BB1506A9847BDE808406C +:10427000FFF7ECB8003C0140C84C0020164B10B5CD +:104280005C6904F478725A61A30604D5134A936AF0 +:104290000BB1D06A9847600604D5104A136B0BB176 +:1042A000506B9847210604D50C4A936B0BB1D06B29 +:1042B0009847E20504D5094A136C0BB1506C984736 +:1042C000A30504D5054A936C0BB1D06C9847BDE8A3 +:1042D0001040FFF7BBB800BF003C0140C84C0020B5 +:1042E000194B10B55C6904F47C425A61620504D52F +:1042F000164A136D0BB1506D9847230504D5134A28 +:10430000936D0BB1D06D9847E00404D50F4A136E3E +:104310000BB1506E9847A10404D50C4A936E0BB1B3 +:10432000D06E9847620404D5084A136F0BB1506FE2 +:104330009847230404D5054A936F0BB1D06F984773 +:10434000BDE81040FFF782B8003C0140C84C002097 +:1043500008B5034800F0E8F8BDE80840FFF776B874 +:10436000484D002008B5FFF741FEBDE80840FFF7C3 +:104370006DB80000062108B50846FFF791F8062140 +:104380000720FFF78DF806210820FFF789F806219E +:104390000920FFF785F806210A20FFF781F806219A +:1043A0001720FFF77DF806212820FFF779F807216D +:1043B0001C20FFF775F8BDE808400C214720FFF7E7 +:1043C0006FB8000008B5FFF725FE00F07BF800F09D +:1043D0003DF8FFF7E5FDBDE80840FFF717BD000019 +:1043E000026843681143016003B118477047000039 +:1043F000143000F0C5B900004FF0FF33143000F066 +:10440000BFB90000383000F03BBA00004FF0FF3376 +:10441000383000F035BA0000143000F08BB90000DD +:104420004FF0FF31143000F085B90000383000F053 +:10443000E5B900004FF0FF32383000F0DFB900007E +:10444000012914BF6FF013000020704700F058B826 +:1044500037B515460E4A026000224260C0E90222CA +:104460000122044602740B46009000F15C014FF4F7 +:104470008072143000F034F900942B464FF48072AF +:1044800004F5AE7104F1380000F0ACF903B030BDB2 +:10449000304C000838B5C36904460D461BB90421E9 +:1044A0000844FFF79DFF294604F1140000F026F9A7 +:1044B000002806DA201D4FF40061BDE83840FFF700 +:1044C0008FBF38BD0023054A19460133102BC2E9BE +:1044D000001102F10802F8D1704700BFC84C00205B +:1044E000026843681143016003B118477047000038 +:1044F000024AD36843F0C003D36070470014014000 +:1045000010B5054C054A00212046FFF7A1FF044ADB +:10451000044BC4E9972310BD484D0020F144000826 +:104520000014014080F0FA022DE9F041D0F85C62FD +:10453000F7683368DA0504469DB20DD5302383F35E +:1045400011884FF480610430FFF7CAFF6FF4807365 +:104550003360002383F31188302383F3118804F13F +:10456000040815F02F033AD183F31188380615D5C6 +:10457000290613D5302383F3118804F1380000F0A5 +:1045800065F900284EDA0821201DFFF7A9FF4FF634 +:104590007F733B40F360002383F311887A0616D5BE +:1045A0006B0614D5302383F31188D4E913239A4280 +:1045B0000AD1236C43B127F040073F041021201D8E +:1045C0003F0CFFF78DFFF760002383F31188D4F8C9 +:1045D0006822D36843B3BDE8F041106918472B0740 +:1045E00014D015F0080F0CBF00214FF48071E807BC +:1045F00048BF41F02001AA0748BF41F040016B07C6 +:1046000048BF41F080014046FFF76AFFAD0673687E +:1046100005D594F8641220461940FFF73BFF356832 +:10462000ADB29EE77060B6E7BDE8F081F8B515461B +:1046300082680669AA420B46816938BF8568761A86 +:10464000B54204460BD218462A46FCF729FDA36959 +:104650002B44A361A3685B1BA3602846F8BD0CD95B +:1046600018463246FCF71CFDAF1BE1683A46304461 +:10467000FCF716FDE3683B44EBE718462A46FCF7D7 +:104680000FFDE368E5E7000083689342F7B5154640 +:10469000044638BF8568D0E90460361AB5420BD2AB +:1046A0002A46FCF7FDFC63692B446361A368284636 +:1046B0005B1BA36003B0F0BD0DD932460191FCF73E +:1046C000EFFC0199E068AF1B3A463144FCF7E8FC87 +:1046D000E3683B44E9E72A46FCF7E2FCE368E4E7E9 +:1046E00010B50A440024C361029B8460C0E9000045 +:1046F000C0E90511C1600261036210BD08B5D0E9CF +:104700000532934201D1826882B9826801328260A7 +:104710005A1C42611970D0E904329A4224BFC3681E +:1047200043610021FEF7DCFF002008BD4FF0FF30A1 +:10473000FBE7000070B5302304460E4683F3118872 +:10474000A568A5B1A368A269013BA360531CA3613E +:1047500015782269934224BFE368A361E3690BB132 +:1047600020469847002383F31188284607E0314606 +:104770002046FEF7A5FF0028E2DA85F3118870BD18 +:104780002DE9F74F04460E4617469846D0F81C9080 +:104790004FF0300A8AF311884FF0000B154665B1CF +:1047A0002A4631462046FFF741FF034660B941469D +:1047B0002046FEF785FF0028F1D0002383F31188FF +:1047C000781B03B0BDE8F08FB9F1000F03D0019062 +:1047D0002046C847019B8BF31188ED1A1E448AF3CB +:1047E0001188DCE7C0E90511C160C3611144009B79 +:1047F0008260C0E90000016103627047F8B50446B9 +:104800000D461646302383F31188A768A7B1A36825 +:10481000013BA36063695A1C62611D70D4E90432D4 +:104820009A4224BFE3686361E3690BB1204698476D +:10483000002080F3118807E031462046FEF740FF54 +:104840000028E2DA87F31188F8BD0000D0E90523DB +:104850009A4210B501D182687AB9826801328260C9 +:104860005A1C82611C7803699A4224BFC368836121 +:104870000021FEF735FF204610BD4FF0FF30FBE76B +:104880002DE9F74F04460E4617469846D0F81C907F +:104890004FF0300A8AF311884FF0000B154665B1CE +:1048A0002A4631462046FFF7EFFE034660B94146EF +:1048B0002046FEF705FF0028F1D0002383F311887E +:1048C000781B03B0BDE8F08FB9F1000F03D0019061 +:1048D0002046C847019B8BF31188ED1A1E448AF3CA +:1048E0001188DCE70B460146184600F02DB80000A1 +:1048F00000F040B8012838BF012010B5044620461A +:1049000000F030F830B900F007F808B900F00CF802 +:104910008047F4E710BD0000024B1868BFF35B8FBF +:10492000704700BFB44F002008B5062000F084F89F +:104930000120FFF71DF80000024B0A4601461868E7 +:10494000FFF752B91C23002010B5054C13462CB1BB +:104950000A4601460220AFF3008010BD2046FCE766 +:1049600000000000024B01461868FFF741B900BF84 +:104970001C230020024B01461868FFF73DB900BF19 +:104980001C23002010B501390244904201D10020BF +:1049900005E0037811F8014FA34201D0181B10BDA8 +:1049A0000130F2E72DE9F041A3B1C91A17780144AB +:1049B000044603F1FF3C8C42204601D9002009E067 +:1049C0000578BD4204F10104F5D10CEB0405D618BD +:1049D000A54201D1BDE8F08115F8018D16F801ED71 +:1049E000F045F5D0E7E700001F2938B504460D462D +:1049F00004D9162303604FF0FF3038BD426C12B16A +:104A000052F821304BB9204600F030F82A460146D2 +:104A10002046BDE8384000F017B8012B0AD0591CD9 +:104A200003D1162303600120E7E7002442F8254064 +:104A3000284698470020E0E7024B01461868FFF738 +:104A4000D3BF00BF1C23002038B5074D0023044608 +:104A5000084611462B60FEF78FFF431C02D12B68DE +:104A600003B1236038BD00BFB84F0020FEF77EBF02 +:104A7000034611F8012B03F8012B002AF9D17047E6 +:104A80006F72672E6172647570696C6F742E426903 +:104A9000726443414E64790040A2E4F16468910677 +:104AA0000041A3E5F26569920700000042616420BD +:104AB00043414E496661636520696E6465782E00E6 +:104AC0008000000000800000000080000000000066 +:104AD000000000001919000839210008952000087D +:104AE0005919000865190008651B000829190008F4 +:104AF000391900082D190008351900083119000866 +:104B0000891A00083D190008092400084D190008F9 +:104B10005D1A000863300000144B0008804A002032 +:104B2000904C0020004000000040000000400000C9 +:104B30000040000000000100000002000000020030 +:104B4000000002006D61696E0069646C6500000020 +:104B50000004802A00000000AAAAAAAA000040259A +:104B6000DFFF0000000000000080080010000A00C5 +:104B7000000000009AAAAAAA00000000FBFF0000A3 +:104B8000000000008800000000000000000000009D +:104B9000AAAAAAAA00000000FFFF0000000000006F +:104BA000000000000000000000000000AAAAAAAA5D +:104BB00000000000FFFF00000000000000000000F7 +:104BC0000000000000000000AAAAAAAA000000003D +:104BD000FFFF0000000000000000000000000000D7 +:104BE00000000000AAAAAAAA00000000FFFF00001F +:104BF00000000000000000000000000000000000B5 +:104C0000AAAAAAAA00000000FFFF000000000000FE +:104C10000000000000000000000000000A0000008A +:104C20000000000003000000000000000000000081 +:104C3000000000000D440008F94300083544000856 +:104C4000214400082D4400081944000805440008C8 +:104C5000F143000841440008140400000000000073 +:104C6000000007000000000040420F00FE2A010083 +:104C7000D2040000202300200000000000000000FB +:104C80000000000000000000000000000000000024 +:104C90000000000000000000000000000000000014 +:104CA0000000000000000000000000000000000004 +:104CB00000000000000000000000000000000000F4 +:104CC00000000000000000000000000000000000E4 +:084CD0000000000000000000DC :00000001FF diff --git a/Tools/bootloaders/C-RTK2-HP_bl.bin b/Tools/bootloaders/C-RTK2-HP_bl.bin index 54d5d3b04c4d42..184444acda64d5 100755 Binary files a/Tools/bootloaders/C-RTK2-HP_bl.bin and b/Tools/bootloaders/C-RTK2-HP_bl.bin differ diff --git a/Tools/bootloaders/CUAV_GPS_bl.bin b/Tools/bootloaders/CUAV_GPS_bl.bin index ba018a0af70560..ab7b6d90b77033 100755 Binary files a/Tools/bootloaders/CUAV_GPS_bl.bin and b/Tools/bootloaders/CUAV_GPS_bl.bin differ diff --git a/Tools/bootloaders/CUAV_GPS_bl.elf b/Tools/bootloaders/CUAV_GPS_bl.elf index e07dbb7f30c867..09c376bbafc864 100755 Binary files a/Tools/bootloaders/CUAV_GPS_bl.elf and b/Tools/bootloaders/CUAV_GPS_bl.elf differ diff --git a/Tools/bootloaders/CUAV_GPS_bl.hex b/Tools/bootloaders/CUAV_GPS_bl.hex index 3ffd8f8b5699b2..6a5a98d0633ec8 100644 --- a/Tools/bootloaders/CUAV_GPS_bl.hex +++ b/Tools/bootloaders/CUAV_GPS_bl.hex @@ -1,1289 +1,1238 @@ :020000040800F2 -:1000000000070020F5040008F1260008A9260008D2 -:10001000D1260008A9260008C9260008F704000810 -:10002000F7040008F7040008F7040008E5360008A4 -:10003000F7040008F7040008F7040008F7040008B4 -:10004000F7040008F7040008F7040008F7040008A4 -:10005000F7040008F7040008F144000819450008F7 -:10006000414500086945000891450008F70400086B -:10007000F7040008F7040008F7040008F704000874 -:10008000F7040008F7040008F70400085D260008DC -:100090008926000899260008F7040008B9450008D9 -:1000A000F7040008F7040008F7040008F704000844 -:1000B000B5460008F7040008F7040008F704000834 -:1000C000F7040008F7040008F7040008F704000824 -:1000D000F70400088D460008A1460008F704000850 -:1000E0001D460008F7040008F7040008F70400089C -:1000F000F7040008F7040008F7040008F7040008F4 -:10010000F7040008F7040008F7040008F7040008E3 -:10011000F7040008F7040008F7040008F7040008D3 -:10012000F7040008F7040008F7040008F7040008C3 -:10013000F7040008F7040008F7040008F7040008B3 -:10014000F7040008F7040008F7040008F7040008A3 -:10015000F7040008F7040008F7040008F704000893 -:10016000F7040008F7040008F7040008F704000883 -:10017000F7040008F7040008F7040008F704000873 -:10018000F7040008F7040008F7040008F704000863 -:10019000F7040008F7040008F7040008F704000853 -:1001A000F7040008F7040008F7040008F704000843 -:1001B000F7040008F7040008F7040008F704000833 -:1001C000F7040008F7040008F7040008F704000823 -:1001D000F7040008F7040008F7040008F704000813 -:1001E000CD12000800000000000000000000000028 -:1001F00053B94AB9002908BF00281CBF4FF0FF318E -:100200004FF0FF3000F074B9ADF1080C6DE904CE89 -:1002100000F006F8DDF804E0DDE9022304B07047E1 -:100220002DE9F047089D04468E46002B4DD18A42A9 -:10023000944669D9B2FA82F252B101FA02F3C2F1DC -:10024000200120FA01F10CFA02FC41EA030E94406D -:100250004FEA1C48210CBEFBF8F61FFA8CF708FB8E -:1002600016E341EA034306FB07F199420AD91CEB66 -:10027000030306F1FF3080F01F81994240F21C8198 -:10028000023E63445B1AA4B2B3FBF8F008FB1033E0 -:1002900044EA034400FB07F7A7420AD91CEB040415 -:1002A00000F1FF3380F00A81A74240F207816444E5 -:1002B000023840EA0640E41B00261DB1D44000236A -:1002C000C5E900433146BDE8F0878B4209D9002DCE -:1002D00000F0EF800026C5E9000130463146BDE858 -:1002E000F087B3FA83F6002E4AD18B4202D38242C2 -:1002F00000F2F980841A61EB030301209E46002D71 -:10030000E0D0C5E9004EDDE702B9FFDEB2FA82F2C5 -:10031000002A40F09280A1EB0C014FEA1C471FFA23 -:100320008CFE0126200CB1FBF7F307FB131140EA0A -:1003300001410EFB03F0884208D91CEB010103F1D7 -:10034000FF3802D2884200F2CB804346091AA4B299 -:10035000B1FBF7F007FB101144EA01440EFB00FE6D -:10036000A64508D91CEB040400F1FF3102D2A645D2 -:1003700000F2BB800846A4EB0E0440EA03409CE771 -:10038000C6F12007B34022FA07FC4CEA030C20FA1E -:1003900007F401FA06F31C43F9404FEA1C4900FA3E -:1003A00006F3B1FBF9F8200C1FFA8CFE09FB1811BB -:1003B00040EA014108FB0EF0884202FA06F20BD92E -:1003C0001CEB010108F1FF3A80F08880884240F27E -:1003D0008580A8F102086144091AA4B2B1FBF9F0C2 -:1003E00009FB101144EA014100FB0EFE8E4508D9BD -:1003F0001CEB010100F1FF346CD28E456AD9023842 -:10040000614440EA0840A0FB0294A1EB0E01A14226 -:10041000C846A64656D353D05DB1B3EB080261EB94 -:100420000E0101FA07F722FA06F3F1401F43C5E96E -:10043000007100263146BDE8F087C2F12003D840A4 -:100440000CFA02FC21FA03F3914001434FEA1C47E6 -:100450001FFA8CFEB3FBF7F007FB10360B0C43EAD8 -:10046000064300FB0EF69E4204FA02F408D91CEB88 -:10047000030300F1FF382FD29E422DD90238634486 -:100480009B1B89B2B3FBF7F607FB163341EA034126 -:1004900006FB0EF38B4208D91CEB010106F1FF3875 -:1004A00016D28B4214D9023E6144C91A46EA00466C -:1004B00038E72E46284605E70646E3E61846F8E6FE -:1004C0004B45A9D2B9EB020864EB0C0E0138A3E747 -:1004D0004646EAE7204694E74046D1E7D0467BE728 -:1004E000023B614432E7304609E76444023842E7A0 -:1004F000704700BF02E000F000F8FEE772B6374830 -:1005000080F30888364880F3098836483649086001 -:1005100040F20000CCF200004EF63471CEF2000141 -:100520000860BFF34F8FBFF36F8F40F20000C0F23F -:10053000F0004EF68851CEF200010860BFF34F8FF5 -:10054000BFF36F8F4FF00000E1EE100A4EF63C71E2 -:10055000CEF200010860062080F31488BFF36F8F8D -:1005600003F0D0FD03F062FE4FF055301F491B4AE7 -:1005700091423CBF41F8040BFAE71D49184A9142E9 -:100580003CBF41F8040BFAE71A491B4A1B4B9A423D -:100590003EBF51F8040B42F8040BF8E7002018495D -:1005A000184A91423CBF41F8040BFAE703F0AEFD54 -:1005B00003F08AFE144C154DAC4203DA54F8041BC8 -:1005C0008847F9E700F042F8114C124DAC4203DACB -:1005D00054F8041B8847F9E703F096BD0007002094 -:1005E000002300200000000808ED00E000010020CA -:1005F00000070020F04F0008002300208023002087 -:100600008023002030520020E0010008E4010008AF -:10061000E4010008E40100082DE9F04F2DED108AF7 -:10062000C1F80CD0C3689D46BDEC108ABDE8F08FC0 -:10063000002383F311882846A047002003F0D4F953 -:10064000FEE703F037F900DFFEE70000F8B500F041 -:100650004FFE03F0F1FC074603F040FD054600287D -:100660003FD12C4B9F423CD001339F423CD02A4B80 -:1006700027F0FF029A423AD1F8B200F045FC2E462C -:1006800042F2107400F046FC08B10024264601F046 -:100690001DF980B3032000F045F80024264635B14B -:1006A0001E4B9F4203D003F011FD0024264600207C -:1006B00003F0CCFC1A4B1B691B0722D40EB100F0CF -:1006C00047F800F093FC00F015FE02F019F805461B -:1006D000CCB102F015F8401BA04214D900F038F854 -:1006E000F3E72E460024CDE704460126CAE7064676 -:1006F0004FF47A74C6E7002CD1D04FF47A740126F7 -:10070000CDE70024DDE700F0B9FC4FF47A7003F088 -:1007100071F9DDE7010007B0000008B0263A09B022 -:1007200000040240084B187003280CD8DFE800F0E2 -:1007300008050208022000F03BBE022000F02EBE99 -:10074000024B00225A60704780230020842300203F -:1007500010B501F0BBF830B1204B03221A70204BCA -:1007600000225A6010BD1F4B1F4A1C4619680131F8 -:10077000F8D004339342F9D162681C4B9A42F1D904 -:100780001B4B9B6803F1006303F580339A42E9D267 -:1007900003F070FC03F082FC002000F0C5FD022095 -:1007A000FFF7C0FF134B1A6C00221A64196E1A6609 -:1007B000196E596C5A64596E5A665B6E72B64FF078 -:1007C000E0233021C3F8084DD4E9003281F31188C9 -:1007D0009D4683F308881047C4E700BF80230020AC -:1007E000842300200000010820000108FFFF00080A -:1007F0000023002000380240094A136849F26900CA -:1008000099B21B0C00FB01331360064B186844F2CD -:10081000506182B2000C01FB0200186080B2704788 -:10082000182300201423002010B5002110220446B4 -:1008300000F0DAFD034B03CB206061601868A06014 -:1008400010BD00BF107AFF1F2DE9F041ADF54E7DC0 -:100850000DF134086CAC40F2751207460D460EA837 -:100860000021C8F8001000F0BFFD4FF4C472002151 -:10087000204600F0B9FD01F043FF274B4FF47A7298 -:10088000B0FBF2F0186093E80700022384E8070049 -:100890000DF5E9702382FFF7C7FF4EF603131F49DA -:1008A000238407A804F0AAFA162384F832310DF243 -:1008B000E32207AB0DF12C0C1E4603CE66451060FB -:1008C0005160334602F10802F6D130681060B388F7 -:1008D000938041460122204600F0D2FD002303937D -:1008E000AB7E029305F11903019380B20123CDE998 -:1008F00004800093E97E06A3D3E90023384602F082 -:10090000C7FA0DF54E7DBDE8F08100BFAFF3008062 -:100910009E6AC421818A46EE8C2300200C4E00087A -:100920002DE9F0412C4C237ADAB080460D465BBBB2 -:1009300027A9284600F0B4FE0746002842D19DF8BA -:100940009D60C82E3ED801464FF4A662204600F0B6 -:100950004BFD4FF48073C4F8F8314FF40073C4F8C2 -:100960000C334FF44073C4F8203432460DF19E012D -:1009700004F1090000F026FD26449DF89C307772B2 -:1009800023720BB9EB7E23728122002106AC27A8CB -:1009900000F02AFD0122214627A800F0BDFE002319 -:1009A0000393AB7E029305F1190380B201932823D0 -:1009B000CDE904400093E97E05A3D3E90023404636 -:1009C00002F066FA5AB0BDE8F08100BFAFF30080D4 -:1009D00026417272DF25D7B7A8440020F0B5254E16 -:1009E0004FF48A7505FB0065F1B096F8D83085F8AC -:1009F000DC300024D822214685F8E8403AA800F0EF -:100A0000F3FC06F1090000F0E7FCD5F8E4308DF8BE -:100A1000F000C2B206AF06F109010DF1F100CDE917 -:100A20003A3400F0CFFC394601223AA800F0A0FE8B -:100A300080B2CDE9047008230127CDE9023706F121 -:100A4000D803019330230093317A0B4807A3D3E9ED -:100A5000002302F01DFAA04206DD01F051FEC5F8A8 -:100A6000E000384671B0F0BD2046FBE778F6339FD2 -:100A700093CACD8DA8440020A43300202DE9F04175 -:100A80001D4D1E4E1E4F86B0284602F02DFA03461D -:100A900058B30024CDE90344ADF81440027B8DF82F -:100AA000142099684068029403AA03C21B68DFF807 -:100AB000548043F00043029301F024FE821941F177 -:100AC0000003009402A9384601F0E6F8A04205DDD3 -:100AD000284602F00DFA88F80040D5E798F8003073 -:100AE000072B05D8013388F8003006B0BDE8F08147 -:100AF000014802F0FDF9F8E7A433002040420F005E -:100B0000D8330020DD49002070B50D4614461E463E -:100B100002F01AF950B9022E10D1012C0ED112A3F5 -:100B2000D3E90023C5E90023012007E0282C10D0D9 -:100B300005D8012C09D0052C0FD0002070BD302C19 -:100B4000FBD10BA3D3E90023ECE70BA3D3E90023EC -:100B5000E8E70BA3D3E90023E4E70BA3D3E90023E1 -:100B6000E0E700BFAFF30080401DA12026812A0BE3 -:100B700078F6339F93CACD8D9E6AC421818A46EE52 -:100B800026417272DF25D7B7F017304A39059E56D5 -:100B900038B505460E4C0021013500F0E7FBA4F8FE -:100BA0002C55B4F82C0500F0C9FB78B1B4F82C052D -:100BB00000F0D4FB014648B9B4F82C0500F0D6FB90 -:100BC000B4F82C350133A4F82C35EAE738BD00BF62 -:100BD000A844002010B50A4B0A4A1A6003F5805356 -:100BE00093F860203AB9DC6D2CB1204600F0ECFEA1 -:100BF000204604F043F8BDE81040034800F0E4BE8E -:100C0000D8330020604E0008204400202DE9F04F2A -:100C10008FB000AF05460C4602F096F8002849D187 -:100C2000237E022B1BD1E38A012B18D101F068FD32 -:100C30000646FFF7E1FD03464FF4C870DFF8C482B3 -:100C4000B3FBF0F206F5167602FB103316FA83F3C7 -:100C5000C8F80030E37E33B9A34B00221A703C374A -:100C6000BD46BDE8F08F07F12401204600F0D6FC18 -:100C70000028F4D107F11400FFF7D6FD97F82640BD -:100C800007F11401224607F1270004F041F800287B -:100C9000E2D10F2C08D8944B1C70D8F80030A3F583 -:100CA0001673C8F80030DAE797F82410284602F0E7 -:100CB00043F8D4E7E38A282B2BD010D8012B23D07C -:100CC000052BCCD1BFF34F8F8849894BCA6802F4FA -:100CD000E0621343CB60BFF34F8F00BFFDE7302BC3 -:100CE000BDD1844EE17E327A9142B8D1607E3146E8 -:100CF000002291F8DC50854200F0A5800132042AE0 -:100D000001F58A71F5D1AAE721462846FFF79CFD37 -:100D1000A5E721462846FFF703FEA0E7B2F8EC500E -:100D20007B6005F103094FEA99094FEA8902D11D59 -:100D3000C908A8EBC1039D46EB460021584600F0C8 -:100D400053FB04F1EE012A463144584600F03AFBC9 -:100D50007B6813B9012000F0E7FA96F8D20000F0A2 -:100D6000EDFA044630B9307200F008FB204600F07E -:100D7000DBFAB1E0D6F8D4203AB996F8D200B6F84A -:100D80002C25824201D8FFF703FFD6F8D4202A444D -:100D9000944208D296F8D200B6F82C25013082424F -:100DA00001D8FFF7F5FE70685FFA89F2594600F046 -:100DB00023FB08B9C54679E0726896F8D2002A4448 -:100DC0007260D6F8D42005EB0209C6F8D49000F082 -:100DD000B5FA814509D396F8D220D6F8D40001326D -:100DE000001B86F8D220C6F8D400FF2D0FD80024AF -:100DF000347200F0C3FA204600F096FA00F066FD67 -:100E00003D4B188108B9FFF7A3FCC54627E7BB682F -:100E100096F8D9000AFB0362FB68D2F8E41082F866 -:100E2000E83001F58061C2F8E030C2F8E410FFF765 -:100E3000D5FDFFF723FE96F8D920013202F0030218 -:100E400086F8D920B6E74FF48A7A0AFB02F505F155 -:100E5000EA013144204600F0B7FCF86000287FF436 -:100E6000FEAE3544012285F8E82001F049FCD5F8B2 -:100E7000E020D6ED007ADFED216A801A192838BF0C -:100E8000192040F6B832904228BF1046B8EE677A73 -:100E900007EE900AF8EEE77A67EEA67ADFED186AB9 -:100EA000E7EE267AFCEEE77AC6ED007A96F8D930BE -:100EB000BB60BA6873680AFB02F4321992F8E81052 -:100EC00059B1D2F8E4108B42E8463FF427AF002135 -:100ED00082F8E810C2F8E010C5467368064A9B0A1B -:100EE00001331381BBE600BF9D33002000ED00E01D -:100EF0000400FA05A84400208C230020CDCCCC3D72 -:100F00006666663FA0330020014B1870704700BF33 -:100F10009823002030B54FF000542B4B22689A42A2 -:100F200085B007D003F0E4F8044620BB0024204637 -:100F300005B030BD254B627D25481A70237D0372B4 -:100F40004FF48073C0F8F8314FF40073C0F80C33DD -:100F500000254FF44073C0F820341E49C0F8E45017 -:100F6000C922093000F02EFA2046E022294600F07E -:100F70003BFA0124DBE7184A184D136C43F0007369 -:100F80001364AA6D164B9A42D0D12B6E013B7E2B77 -:100F9000CCD8144A07CA01AB83E8070018460321DE -:100FA00000F062FC6B6D83424FF00003BED12A6DEE -:100FB0008A4201BFAB65054B2A6E1A7003BF0A4B0C -:100FC000EA6D1A601C46B2E79AAD44C5982300202A -:100FD000A8440020160000200038024000660040AF -:100FE0005041A0B0586600401023002037B51A4D7C -:100FF00000F06CFC02236B71184B288119681848AB -:10100000012201F01BFA00230193164B16490093AD -:101010001648174B4FF4805201F066FE154B1978B5 -:1010200011B1124801F088FE01F06AFB0446FFF797 -:10103000E3FB4FF4C873B0FBF3F202FB130304F5B8 -:10104000167010FA83F00C4B186003F047F808B1E3 -:101050000F232B8103B030BD8C23002010230020F0 -:10106000D8330020090B00089C230020A433002063 -:101070000D0C000898230020A03300202DE9F04F2C -:101080002DED028B0FF23829D9E90089834C93B0FA -:101090000BAE9FED7E8BFFF7F1FC814FDFF828A2AE -:1010A00000230A93ADF834300B9373604FF0000BBC -:1010B0005B468DED008B01250DF11D0207A9384619 -:1010C0008DF81C508DF81DB001F068F99DF81C30AA -:1010D000002B40F0A580204601F036FE0646002891 -:1010E00045D1704F01F00CFB3B6898423FD301F0B3 -:1010F00007FB8246FFF780FB4FF4C873B0FBF3F2A7 -:1011000002FB13030AF5167010FA83F03860664F7D -:1011100097F800B0CBF1100ABBF1000F14BF3346B3 -:101120002B465FFA8AFA0EA88DF82830FFF77CFB71 -:10113000BAF1060F28BF4FF0060A0EAB03EB0B0106 -:1011400052460DF1290000F03DF90AAB0393182334 -:1011500002930AF10102554BD2B2CDE90053049239 -:1011600020464CA3D3E9002301F034FE3E7001F089 -:10117000C7FA4F4A4F4D1368C31AB3F57A7F2ED37F -:10118000106001F0BFFA02460B46204601F0BAFE9D -:10119000204601F0D9FD10B32B7A474E002B14BF27 -:1011A00003230223737101F0ABFA0EAF4FF47A738D -:1011B0000122B0FBF3F039463060304600F006FA09 -:1011C000182302933D4B019380B240F25513CDE9B1 -:1011D0000370009342464B46204601F0FBFD2B7AFC -:1011E00093B101F08DFA002607464FF48A7A95F8FC -:1011F000D900304400F003000AFB005393F8E820C4 -:1012000092B30136042EF2D1C82002F0F3FB2B7A00 -:10121000002B7FF43DAF13B0BDEC028BBDE8F08F27 -:10122000DAF8143083F48053CAF814305946102287 -:101230000EA800F0D9F80DF11E0308AA0AA9384635 -:1012400000F028FE96E803000FAB83E803009DF84A -:1012500034308DF844300A9B0E930EA9DDE9082343 -:10126000204602F023F821E7D3F8E02042B12B68B2 -:10127000FA2B38BFFA23BA1A0533B2EB430FC0D3A7 -:10128000FFF7ACFB0028BCD1BEE700BF00000000A8 -:1012900000000000401DA12026812A0BA43300205D -:1012A000D8330020A03300209D3300209C33002041 -:1012B000D8490020A84400208C230020DC490020CD -:1012C000F1C6A7C1D068080F0004024008B5054860 -:1012D00000F07AFEBDE80840034A0449002003F00C -:1012E000C7BC00BFD8330020184A0020D50B000827 -:1012F0007047000070B502F041FD094E094D308085 -:10130000002428683388834208D902F031FD2B6815 -:1013100004440133B4F5803F2B60F2D370BD00BFAD -:101320000C4A0020E049002002F0D8BD00F1006026 -:10133000920000F5803002F067BD0000054B1A688E -:10134000054B1B889B1A834202D9104402F010BD42 -:1013500000207047E04900200C4A0020024B1B6827 -:10136000184402F00DBD00BFE0490020024B1B688D -:10137000184402F01DBD00BFE0490020064991F865 -:10138000243033B10023086A81F824300822FFF7A3 -:10139000CDBF0120704700BFE4490020022802BFF2 -:1013A000024B4FF480529A61704700BF0004024024 -:1013B000022802BF024B4FF080529A61704700BF73 -:1013C0000004024010B50023934203D0CC5CC45407 -:1013D0000133F9E710BD000003460246D01A12F9A6 -:1013E000011B0029FAD1704702440346934202D000 -:1013F00003F8011BFAE770472DE9F8431F4D144627 -:1014000095F824200746884652BBDFF870909CB3BD -:1014100095F824302BB92022FF2148462F62FFF790 -:10142000E3FF95F82400C0F10802A24228BF22463B -:10143000D6B24146920005EB8000FFF7C3FF95F856 -:101440002430A41B1E44F6B2082E17449044E4B284 -:1014500085F82460DBD1FFF791FF0028D7D108E0A1 -:101460002B6A03EB82038342CFD0FFF787FF00286C -:10147000CBD10020BDE8F8830120FBE7E449002040 -:101480002DE9F0470D46044600219046284640F2DB -:101490007912FFF7A9FF234620220021284601F0F8 -:1014A000A7FE231D02222021284601F0A1FE631D74 -:1014B00003222221284601F09BFEA31D03222521A1 -:1014C000284601F095FE04F1080310222821284641 -:1014D00001F08EFE04F1100308223821284601F0A5 -:1014E00087FE04F1110308224021284601F080FE06 -:1014F00004F1120308224821284601F079FE04F184 -:10150000140320225021284601F072FE04F1180332 -:1015100040227021284601F06BFE04F120030822CE -:10152000B021284601F064FE04F121030822B8210D -:10153000284601F05DFE04F12207C0263B463146F5 -:1015400008222846083601F053FEB6F5A07F07F1C1 -:101550000107F3D104F1320308223146284601F095 -:1015600047FE002704F1330A94F832304FEAC709E6 -:101570009F4209F5A47615D3B8F1000F08D1314682 -:1015800004F599730722284601F032FE09F24F163E -:10159000274694F832213B1B93420CD3F01DC00820 -:1015A000BDE8F0870AEB070308223146284601F020 -:1015B0001FFE0137D8E707F23313314608222846C9 -:1015C00001F016FE08360137E3E7000013B50446C4 -:1015D0000846002101602346C0F803102022019034 -:1015E00001F006FE0198231D0222202101F000FED9 -:1015F0000198631D0322222101F0FAFD0198A31D29 -:101600000322252101F0F4FD019804F108031022C2 -:10161000282101F0EDFD072002B010BDF7B5002331 -:10162000047F00910E4607221946054601F0A4FCEE -:10163000731C0093012200230721284601F09CFC23 -:10164000C4B9B31C0093052223460821284601F0A3 -:1016500093FC0D243746B278BB1B934211D32B7FEA -:10166000A88A0734E408BBB9844294BF0020012053 -:1016700003B0F0BDAB8ADB00083BDB08B370082485 -:10168000E8E7FB1C0093214600230822284601F0CE -:1016900073FC08340137DEE7201A18BF0120E7E7A2 -:1016A000F7B50023047F00910E460822194605462F -:1016B00001F062FC731CC4B9082200931146234652 -:1016C000284601F059FC1024012372785F1C013B6D -:1016D000934211D32B7FA88A0734E408BBB9844214 -:1016E00094BF0020012003B0F0BDAB8ADB00083BB3 -:1016F000DB0873700824E7E7F31900932146002301 -:101700000822284601F038FC08343B46DDE7201A61 -:1017100018BF0120E7E70000F8B50E46054614465D -:10172000002181223046FFF75FFE2B460822002170 -:10173000304601F05DFD7CB96B1C07220821304664 -:1017400001F056FD0F2401236A785F1C013B934290 -:1017500004D3E01DC008F8BD0824F4E7EB192146C6 -:101760000822304601F044FD08343B46ECE7000017 -:10177000F8B50E46054614460021CE223046FFF746 -:1017800033FE2B4628220021304601F031FD7CB982 -:1017900005F1080308222821304601F029FD3024F4 -:1017A0002F462A7A7B1B934204D3E01DC008F8BD64 -:1017B0002824F5E707F1090321460822304601F005 -:1017C00017FD08340137ECE7F7B5047F00910E46AA -:1017D000012310220021054601F0CEFBC4B9B31C41 -:1017E0000093092223461021284601F0C5FB192445 -:1017F00037467288BB1B9A4211D82B7FA88A0734C0 -:10180000E408BBB9844294BF0020012003B0F0BDBE -:10181000AB8ADB00103BDB0873801024E8E73B1D3C -:101820000093214600230822284601F0A5FB083436 -:101830000137DEE7201A18BF0120E7E730B5094D70 -:101840000A4491420DD011F8013B5840082340F35F -:101850000004013B2C4013F0FF0384EA5000F6D152 -:10186000EFE730BD2083B8EDF7B54FF0FF33DFF879 -:1018700054C0DFF854E000EB81011A4688421CD0C6 -:1018800050F8044B019401AF042417F8015B82EA7D -:1018900005620825DB18164605F1FF355241002E7A -:1018A000BCBF83EA0C0382EA0E0215F0FF05F1D1FA -:1018B000013C14F0FF04E8D1E0E7D843D14303B082 -:1018C000F0BD00BF9336EAA9EBE1F042F7B5384A24 -:1018D000106851686B4603C36A4636493648082388 -:1018E00003F026FA0446002833D10A25334A10684B -:1018F00051686B4603C36A4631492F48082303F0F9 -:1019000017FA0446002849D00369B3F5E02F45D8FB -:10191000B0F8661040F2E93291423FD1294A0244C0 -:1019200002F15C018B4239D35C3B234900209E1AB3 -:10193000FFF784FF3246074604F164010020FFF7F9 -:101940007DFFA3689F4229D1E368984208BF002524 -:1019500024E00369B3F5E02F27D8418B40F2E93248 -:10196000914220D1174A024402F110018B4218D350 -:10197000103B114900209D1AFFF760FF2A460646DA -:1019800004F118010020FFF759FFA3689E4202D11D -:10199000E368984201D00D25A8E70025284603B04A -:1019A000F0BD1025A2E70C25A0E70B259EE700BFA0 -:1019B000244E0008DCFF0600000001082D4E000840 -:1019C00090FF06000800FFF710B5037C044613B92A -:1019D000006803F095F9204610BD00000023BFF316 -:1019E0005B8FC360BFF35B8FBFF35B8F8360BFF31D -:1019F0005B8F7047BFF35B8F0068BFF35B8F7047EF -:101A000070B505460C30FFF7F5FF05F108060446F2 -:101A10003046FFF7EFFFA04206D930466D68FFF76A -:101A2000E9FF2544281A70BD3046FFF7E3FF201A6E -:101A3000F9E7000070B50546406898B105F1080067 -:101A4000FFF7D8FF05F10C0604463046FFF7D2FF3A -:101A50008442304694BF6D680025FFF7CBFF013C00 -:101A60002C44201A70BD000038B50C460546FFF71F -:101A7000C7FFA04210D305F10800FFF7BBFF0444E5 -:101A80006868B4FBF0F100FB1144BFF35B8F0120E9 -:101A9000AC60BFF35B8F38BD0020FCE72DE9F0415F -:101AA000144607460D46FFF7C5FF844228BF04468B -:101AB000D4B1B84658F80C6B4046FFF79BFF304452 -:101AC000286040467E68FFF795FF331A9C4203D892 -:101AD0006C600120BDE8F0816B60A41B3B68AB60CB -:101AE0002044E8600220F5E72046F3E738B50C46CD -:101AF0000546FFF79FFFA04210D305F10C00FFF74A -:101B000079FF04446868B4FBF0F100FB1144BFF3B3 -:101B10005B8F0120EC60BFF35B8F38BD0020FCE7DA -:101B20002DE9FF41884669460746FFF7B7FF6C4637 -:101B300006B204EBC6060025B44209D062682068EC -:101B400008EB0501FFF73EFC636808341D44F3E72A -:101B500029463846FFF7CAFF284604B0BDE8F081A1 -:101B6000F8B505460C300F46FFF744FF05F10806AF -:101B700004463046FFF73EFFA042304688BF6C68FF -:101B8000FFF738FF201A386020B130462C68FFF785 -:101B900031FF2044F8BD000073B5144606460D46DB -:101BA000FFF72EFF844228BF04460190DCB101A953 -:101BB0003046FFF7D5FF019B33B93268C5E90233E0 -:101BC000C5E9002401200CE09C4238BF0194286044 -:101BD000019868608442F5D93368AB60241AEC60E0 -:101BE000022002B070BD2046FBE700002DE9FF4156 -:101BF0000F466946FFF7D0FF6C4600B204EBC00504 -:101C00000026AC4209D0D4F8048054F8081BB81957 -:101C10004246FFF7D7FB4644F3E7304604B0BDE841 -:101C2000F081000038B50546FFF7E0FF04460146A5 -:101C30002846FFF719FF204638BD0000302383F304 -:101C4000118862B670470000002383F3118862B6E2 -:101C50007047000010B4026854681A4623465DF8C5 -:101C6000044B184701207047002070470020704740 -:101C700070470000002070470E20704700F580502C -:101C800090F8C800C0F340007047000000F5805095 -:101C900090F9C90070470000F7B50C68BDF82070D6 -:101CA00014F000541E466FD10B7B082B6CD8FFF745 -:101CB000C5FF4569AB685B010CD4AB681B0108D458 -:101CC000AC6814F080545DD1FFF7BEFF204603B02E -:101CD000F0BD01240B6804F1180C002BB8BFDB0029 -:101CE0004FEA0C1CB4BF43F004035B0545F80C300D -:101CF0000B680FFA84FC13F0804F18BF05EB0C1E25 -:101D000005EB0C1C1EBFDEF8803143F00203CEF859 -:101D100080310B7BCCF8843105EB04158B68C5F85A -:101D20008C314B68C5F88831DCF8803143F0010311 -:101D3000CCF8803100EB441541F268031D4403EBFD -:101D400044130344C5E9002608330D4601F10C0C89 -:101D500055F804EB43F804EB6545F9D184342D883C -:101D60001D8000EB441407F00303257925F00B05D3 -:101D70002B432371FFF768FF0097334600F0E2FC26 -:101D80000120A4E70224A5E74FF0FF309FE7000001 -:101D900013B500F580540191E06DFFF74BFE1F284D -:101DA0000AD90199E06D2022FFF7BAFEA0F12003C5 -:101DB0005842584102B010BD0020FBE708B500F5BD -:101DC0008050FFF73BFFC06DFFF708FEBDE80840FD -:101DD000FFF73ABF00220260828142608260704752 -:101DE00010B500220023C0E900230023044603812C -:101DF0000C30FFF7EFFF204610BD0000F0B50546A0 -:101E000000F580500C4690F8C83013F0040FC3F36F -:101E1000800108BF114661F3820304F1840680F853 -:101E2000C83005EB461389B01B79D8072ED57AB395 -:101E300019072DD46846FFF7D3FF05EB441303F5CC -:101E4000835303F1180703AA10331868596814461E -:101E500003C40833BB422246F7D1186820609B8830 -:101E6000A380DDE90E23CDE900230123ADF808307E -:101E70002B686946DB6B2846984705EB46152B799E -:101E80001A075CBF43F008032B7101E0002AF4D16C -:101E900009B0F0BD2DE9F047074688B007F580543A -:101EA00068469A468846FFF7C9FE9146FFF798FFB5 -:101EB000E06DFFF7A5FD1F2829D9E06D20226946B6 -:101EC000FFF7B0FE202822D103AD444605AB2E46D5 -:101ED00003CE9E4220606160354604F10804F6D1CD -:101EE00030682060B388A380DDE90023C9E90023BE -:101EF000BDF80830AAF80030FFF7A6FE4A46534660 -:101F00004146384608B0BDE8F04700F009BCFFF78D -:101F10009BFE002008B0BDE8F08700002DE9F84FD7 -:101F20000023C0E90133254B044640F8183B0F4617 -:101F3000FFF750FF04F12800FFF752FF04F14808B3 -:101F400004F582554646083530462036FFF748FFEF -:101F5000AE42F9D104F580554FF480534FF000099B -:101F6000C5E91339C5F848800123EE6504F58758A3 -:101F700004F58456C5F8549085F8583085F86030DB -:101F8000083608F108084FF0000A4FF0000B46E948 -:101F900008ABA6F11800FFF71DFF203646F8289C75 -:101FA0004645F4D185F8C97017B1054800F0A2FB89 -:101FB000044B63612046BDE8F88F00BF604E000807 -:101FC000384E00080064004010B5044B19780446F0 -:101FD0004A1C1A70FFF7A2FF204610BD144A0020C9 -:101FE0002DE9F047002950D0294B2A4FB7FBF1F5D6 -:101FF00099428CBF0A231123581EB5FBF3FC03FB47 -:102000001C53C4B22BB102280346F5D80020BDE80A -:10201000F0870CF1FF36B6F5806FF7D2C4EBC40E33 -:102020000EF103034FEAE309C3F3C703A4EB03086C -:1020300009F1010A4FF47A755FFA88F009FB05553A -:102040005AFA88F8B5FBF8F5B5F5617FC1BF0EF116 -:10205000FF33C3F3C703E01AC0B25C1C50FA84F428 -:102060000CFB04F4B7FBF4F4A142CFD1013BDBB28B -:102070000F2BCBD80138C0B20728C7D80021107168 -:1020800016809170D3700120C1E70846BFE700BFFA -:102090003F420F0040787D0170B505460E464FF473 -:1020A0007A746B695B6803F00103B34207D04FF4A5 -:1020B0007A7001F09FFC013CF3D1204670BD0120F5 -:1020C000FCE7000030B54269936913F0700F16D039 -:1020D00000230B4C936103F1840200EB421211794F -:1020E0004D0709D5890707D5416954F823508D60FC -:1020F000117941F0040111710133032BEBD130BD93 -:102100004C4E000873B51D46436916469A68D207BF -:10211000044609D59A6801219960C2F34002CDE9CD -:1021200000650021FFF76AFE63699A68D1050BD547 -:102130009A684FF480719960C2F34022CDE900653E -:1021400001212046FFF75AFE63699A68D2030BD536 -:102150009A684FF480319960C2F34042CDE900653E -:1021600002212046FFF74AFE204602B0BDE870403B -:10217000FFF7A8BFF8B50446466900296CD106F1FF -:102180000C07386880076AD006EB01153868D5F867 -:10219000B00110F0040FD5F8B0011ABFC00840F02C -:1021A0000040400DA061D5F8B0C11CF0020F1CBF6B -:1021B00040F08040A061D5F8B40106EB011100F0B9 -:1021C0000F0084F82400D1F8B8012077D1F8B801C5 -:1021D000000A6077D1F8B801000CA077D1F8B801F7 -:1021E000000EE077D1F8BC0184F82000D1F8BC01E2 -:1021F000000A84F82100D1F8BC01000C84F8220008 -:10220000D1F8BC11090E84F823103821396004F18B -:10221000340004F1180104F1240551F8046B40F86E -:10222000046BA942F9D109880180C4E90A23214637 -:102230000023238651F8283B2046DB6B984704F5A2 -:102240008052204692F8C83043F0040382F8C83028 -:10225000BDE8F840FFF736BF06F1100791E7F8BD7B -:1022600010B5044600F04EFA02460B4652EA03014E -:1022700002D0013A63F100030449086820B1214605 -:10228000BDE81040FFF776BF10BD00BF104A002028 -:10229000F8B500F583511E46FFF7D0FCDFF844C0C7 -:1022A0000831002404F1840500EB45152B795F0704 -:1022B0000ED4DB060CD5D1E900739742B34107D2A7 -:1022C00043695CF824709F602B7943F004032B7101 -:1022D0000134032C01F12001E4D1BDE8F840FFF7FF -:1022E000B3BC00BF4C4E000808B5FFF7A7FCFFF7D2 -:1022F000E9FEBDE80840FFF7A7BC0000F8B5436958 -:102300000546986800F0E050B0F1E05F0F461FD03E -:10231000E8B1FFF793FC05F583541034002606F16D -:10232000840305EB43131B791A0706D50136032EE8 -:1023300004F12004F3D1012007E05B07F6D4214625 -:10234000384600F039FA0028F0D1FFF77DFCF8BDDF -:102350000120FCE700F5805008B5FFF76FFCC06D69 -:10236000FFF74EFBFFF770FC43090CBF0120002074 -:1023700008BD0000F8B51D46002313700F46064641 -:102380001446FFF7E7FF80F00100387025B12946B9 -:102390003046FFF7B3FF2070F8BD00002DE9B841CB -:1023A0000C4615461F46804600F0ACF90B462178D6 -:1023B000024609B9287850B14046FFF769FFFFF798 -:1023C00093FF3B462A462146FFF7D4FF0120BDE894 -:1023D000B881000010B5FFF731FC174B1A6C42F0C2 -:1023E00000721A641A6A42F000721A621A6A00F5E0 -:1023F000805422F000721A62FFF726FC94F8C8306D -:10240000DB0718D4B9B103211320FFF717FC01F043 -:10241000C7F90321142001F0C3F90321152001F0AD -:10242000BFF994F8C83043F0010384F8C830BDE820 -:102430001040FFF709BC10BD003802402DE9F047FD -:1024400000F5805588B095F8C930012B04468846C0 -:1024500016467FD8804F57F823200AB947F8230043 -:10246000D7F800A0C4F80C802674BAF1000F63D02E -:1024700095F8C930012B6FD001212046FFF7AAFF44 -:10248000FFF7DCFB6269136823F0020313606269E3 -:10249000136843F001031360636900275F61012142 -:1024A0002046FFF7D1FBFFF7F7FD002800F09580ED -:1024B000E86DFFF793FA04F58359BA4609F1080964 -:1024C000202200216846FEF78FFF02A8FFF782FC5A -:1024D000CDF818A06A4609EB07030DF1180E9446D3 -:1024E000BCE80300F44518605960624603F1080334 -:1024F000F5D1DCF80000186020379CF804201A7130 -:10250000602FDDD195F8C8306FF38203002785F87E -:10251000C8306A4641462046ADF80070ADF80270FA -:102520008DF80470FFF75CFD636948BB4FF400420F -:102530001A6008B0BDE8F08741F2D00002F0A0FBBD -:10254000814610B15146FFF7E9FCC7F80090B9F198 -:10255000000F8DD10020ECE7386803681B6B9847AB -:102560000146002888D13868FFF734FF38680368CF -:1025700032465B684146984700287FF47DAFE9E723 -:1025800061221A609DF802309DF803201B06120498 -:1025900002F4702203F040731343BDF80020C2F32D -:1025A000090213439DF804201205022E02F4E002F2 -:1025B0000CBF4FF000410021134362690B43D3610C -:1025C000636913225A616269136823F0010313607F -:1025D00039462046FFF760FD08B96369A6E795F81C -:1025E000C93093BB6169D1F8002242F00102C1F801 -:1025F00000226169D1F8002222F47C5222F00E02FE -:10260000C1F800226169D1F8002242F46062C1F889 -:1026100000226269C2F814326269C2F80432626947 -:1026200041F6FF71C2F80C126269C2F84032626969 -:10263000C2F8443263690122C3F81C226269D2F8ED -:10264000003223F00103C2F8003295F8C83043F09D -:10265000020385F8C8306CE7104A002008B500F086 -:1026600051F850EA0103024602D0421E61F1000116 -:10267000044B186810B10B46FFF744FDBDE8084055 -:1026800001F064B8104A002008B50020FFF7E8FD0B -:10269000BDE8084001F05AB808B50120FFF7E0FD99 -:1026A000BDE8084001F052B800B59BB0EFF30981D6 -:1026B00068226846FEF786FEEFF30583014B9B6BAD -:1026C000FEE700BF00ED00E008B5FFF7EDFF0000FA -:1026D00000B59BB0EFF3098168226846FEF772FEF1 -:1026E000EFF30583014B5B6BFEE700BF00ED00E0FD -:1026F000FEE700000FB408B5029801F011F9FEE7FB -:1027000001F038BC01F010BC13B56C4684E806003B -:10271000031D94E8030083E80500012002B010BD0A -:1027200073B58568019155B11B885B0707D4D0E963 -:1027300000369B6B9847019AC1B23046A8470120EA -:1027400002B070BDF0B5866889B005460C465EB132 -:10275000BDF838305B070AD4D0E900379B6B984747 -:102760002246C1B23846B047012009B0F0BD002270 -:102770000023CDE900230023ADF808300A4603AB5F -:1027800001F10806106851681C4603C40832B242C1 -:102790002346F7D1106820609288A280FFF7B2FF2D -:1027A0000423ADF808302B68CDE90001DB6B6946E6 -:1027B00028469847D8E7000030B503680968DD0F60 -:1027C000B5EBD17F23F0604421F060424FEAD17035 -:1027D0000BD0002BB8BFA40C0029B8BF920C9442B8 -:1027E00002D034BF0120002030BD944205D1C1F396 -:1027F0008070C3F380738342F6D194422CBF0020D3 -:102800000120F1E72DE9F041456A15B94162BDE8C3 -:10281000F0814B6823F06047C3F38A464FEAD37ECA -:10282000C3F3807816EA230638BF3E46AC462B46F3 -:102830005A68BEEBD27F22F060440AD0002A18DA30 -:10284000A40CB44217D19D420FD10D60DEE71346B0 -:10285000EEE7A74207D102F08044C2F380724245FE -:102860000BD054B1EFE708D2EDE7CCF800100B60C5 -:10287000CDE7B44201D0B442E5D81A689C46002A9C -:10288000E5D11960C3E700002DE9F047089D01F08C -:1028900007044FEAD508224405F0070500EBD100F4 -:1028A0004FF47F49944201D1BDE8F08704F0070757 -:1028B00005F0070A57453E4638BF5646C6F108069A -:1028C000111B8E4228BF0E46E10808EBD50E415C75 -:1028D00013F80EC0B94029FA06F721FA0AF1FFB23F -:1028E0008CEA010147FA0AF739408CEA010C03F837 -:1028F0000EC034443544D5E780EA0120082341F274 -:10290000210201B24000002980B203F1FF33B8BFB9 -:10291000504013F0FF03F4D17047000038B50C4667 -:102920008D18A54200D138BD14F8011BFFF7E4FF54 -:10293000F7E7000042684AB1136843604389818920 -:1029400001339BB29942438138BF8381104670475F -:1029500070B588B0202204460D4668460021FEF777 -:1029600043FD20460495FFF7E5FF024658B16B464C -:10297000054608AE1C4603CCB44228606960234675 -:1029800005F10805F6D1104608B070BD082817D922 -:1029900009280CD00A280CD00B280CD00C280CD0FD -:1029A0000D280CD00E2814BF4020302070470C207A -:1029B000704710207047142070471820704720205F -:1029C00070470000082817D90C280CD910280CD9FA -:1029D00014280CD918280CD920280CD930288CBFE1 -:1029E0000F200E207047092070470A2070470B20E7 -:1029F00070470C2070470D20704700002DE9F84308 -:102A0000078C072F04461ED9D0E9029800254FF6FF -:102A1000FF73C5F12006A5F1200029FA05F108FA97 -:102A200006F628FA00F031430143C9B21846FFF711 -:102A300063FF0835402D0346EBD1E1693A46BDE816 -:102A4000F843FFF76BBF4FF6FF70BDE8F883000057 -:102A500010B54B6823B9CA8A63F30902CA8210BD54 -:102A600004691A681C600361C38A013BC3824A601F -:102A7000EFE700002DE9F84F1D46CB8A0F46C3F360 -:102A800009010529814692460B4630D00020AAB2A2 -:102A900007F11A049EB2042E1FFA80F80FD8904551 -:102AA00003F1010306D3FB8A0A4462F30903FB82A4 -:102AB00001201AE01AF80060E6540130EAE7904578 -:102AC000F1D2A1F1050B1C237C68BBFBF3F203FBE5 -:102AD00012BB1FFA8BF6002C45D14846FFF72AFFA0 -:102AE000044638B978606FF00200BDE8F88F4FF007 -:102AF0000008E6E7002606607860ADB24FF0000BF4 -:102B0000454510D90AEB0803221D13F8011B915506 -:102B1000B1B208F101081B291FFA88F82BD04545EE -:102B200006F10106F1D8FB8AC3F30902154465F3E7 -:102B30000903BCE7013292B21C462368002BF9D18D -:102B40006B1F0B441C21B3FBF1F301339BB29A4280 -:102B5000D3D2BBF1000FD0D14846FFF7EBFE20B92E -:102B6000C4F800B0BFE70122E7E7C0F800B05E4656 -:102B700020600446C1E74545D5D94846FFF7DAFE4F -:102B800008B92060AFE7C0F800B000262060044616 -:102B9000B6E700002DE9F04F2DED028B1C4683B007 -:102BA0005B69019207468846002B00F09A80238CCF -:102BB0002BB1E269002A00F09480072B35D807F189 -:102BC0000C00FFF7B7FE054638B96FF0020528463E -:102BD00003B0BDEC028BBDE8F08F14220021FEF79C -:102BE00003FC228CE16905F10800FEF7EBFB208C69 -:102BF000013080B2FFF7E6FEFFF7C8FE013880B271 -:102C00002084013028746369228C1B782A4403F0E5 -:102C10001F0363F03F0348F00041137238466960B8 -:102C20002946FFF7EFFD0125D1E700F10C034FF036 -:102C3000000908EE103A4FF0800A4E464D4618EE55 -:102C4000100AFFF777FE83460028BED01422002129 -:102C5000FEF7CAFB002E3AD1019BABF808300222E6 -:102C60000BF1080E1FFA82FC0CF10100BCF1060FFB -:102C7000218C80B201D88E422BD3FFF7A3FEFFF741 -:102C800085FE62691278013802F01F028E4208BF89 -:102C90004FF0400A42EA49121BFA80F14AEA020A5E -:102CA000013048F0004281F808A08BF81000CBF802 -:102CB000042059463846FFF7A5FD238C0135B34261 -:102CC0002DB289F001094FF0000AB8D17FE7002248 -:102CD000C6E7E169895D0EF802100136B6B201322D -:102CE000C0E76FF0010572E7F8B515460E463022D1 -:102CF000002104461F46FEF777FB069B6360B5F58F -:102D0000001F079BA76034BF6A094FF6FF72A362DA -:102D100097B2E66104F1100000239A4206D800231E -:102D20000360A782E3822383E360F8BD066001337A -:102D300030462036F1E7000003781BB94BB2002B78 -:102D4000C8BF01707047000000787047F8B50C46A6 -:102D5000C969074611B9238C002B37D1257E1F2D59 -:102D600034D8387828BB228C072A2CD8268A36F00B -:102D700003032BD14FF6FF70FFF7D0FD20F00100C9 -:102D80003102400441EA0561400C41EA40254FF61A -:102D9000FF72234629463846FFF7FCFE002807DD70 -:102DA000626913780133DBB21F2B88BF00231370D5 -:102DB000F8BD218A2D0645EA012505432046FFF787 -:102DC0001DFE0246E5E76FF00300F1E76FF001003A -:102DD000EEE7000070B58AB00446164600212822AE -:102DE00068461D46FEF700FBBDF83830ADF81030E0 -:102DF0000F9B05939DF840308DF81830119B079379 -:102E00006946BDF84830ADF820302046CDE902656E -:102E1000FFF79CFF0AB070BD2DE9F041D36905466C -:102E20000C4616460BB9138C5BBB377E1F2F28D878 -:102E300095F80080B8F1000F26D03046FFF7DEFD90 -:102E40003378210241EAC33141EA0801338A41EA79 -:102E5000076141EA03410246334641F080012846BA -:102E6000FFF798FE00280ADD3378012B07D172693D -:102E700013780133DBB21F2B88BF00231370BDE82A -:102E8000F0816FF00100FAE76FF00300F7E7000050 -:102E9000F0B58BB004460D4617460021282268463F -:102EA0001E46FEF7A1FA9DF84C305A1E534253417C -:102EB0008DF800309DF84030ADF81030119B05932F -:102EC0009DF848308DF81830149B07936A46BDF87A -:102ED0005430ADF8203029462046CDE90276FFF780 -:102EE0009BFF0BB0F0BD0000406A00B1043070479A -:102EF000436A1A68426202691A600361C38A013B2D -:102F0000C38270472DE9F041D0F82080194E144655 -:102F10001D464146002709B9BDE8F081D1E90223E9 -:102F2000A21A65EB0303964277EB03031ED2036AF2 -:102F30008B420DD1FFF78CFD036A1B6803620369A6 -:102F40000B60C38A0161016A013BC3828846E2E7E4 -:102F5000FFF77EFD0B68C8F8003003690B60C38A79 -:102F60000161013BC382D8F80010D4E788460968A4 -:102F7000D1E700BF80841E002DE9F04F8BB00D46D5 -:102F8000DDF8509014469B468046002800F01981D9 -:102F9000B9F1000F00F01581531E3F2B00F2118193 -:102FA000012A03D1BBF1000F40F00B810023CDE9D2 -:102FB0000833B8F81430B5EBC30F4FEAC30703D397 -:102FC00000200BB0BDE8F08F2B199F42D8F80C30D1 -:102FD0003ABF7F1BFFB227461BB9D8F81030002B31 -:102FE0007AD0272D4ED8C5F12806B7424FF00003FE -:102FF0002CBFF6B23E4600932946D8F8080008AB2D -:103000003246FFF741FCA7EB060A35445FFA8AFA1D -:10301000B8F8143003F10053053BDB000493D8F8F3 -:103020000C3003932821039B13B1BAF1000F2CD16C -:10303000D8F8100040B1BAF1000F05D0009608ABE7 -:103040005246691AFFF720FC38B2002FB8D0660745 -:103050000AD00AAB03EBD401624211F8083C02F03B -:103060000702134101F8083C082C3CD9102C40F20F -:10307000B580202C40F2B780BBF1000F00F09C809F -:10308000082334E0BA460026C2E7049BE02B28BFA1 -:10309000E02306930B44AB42059314D95A1B0398C3 -:1030A0000096924534BF5246D2B2691A08AB04303A -:1030B0000792FFF7E9FB079A1644AAEB020A1544A8 -:1030C000F6B25FFA8AFA049B069A05999B1A049352 -:1030D000039B1B680393A6E70093D8F8080008AB8E -:1030E0003A462946AEE7BBF1000F13D00123B4EBFB -:1030F000C30F6CD0082C12D89DF82030621E23FA22 -:1031000002F2D50706D54FF0FF3202FA04F423434A -:103110008DF820309DF8203089F8003051E7102CD0 -:1031200012D8BDF82030621E23FA02F2D10706D56C -:103130004FF0FF3202FA04F42343ADF82030BDF81B -:103140002030A9F800303CE7202C0FD80899631EE6 -:1031500021FA03F3DA0705D54FF0FF3202FA04F43F -:103160000C430894089BC9F800302AE7402C2BD068 -:10317000DDE90865611EC4F12102A4F1210326FAEC -:1031800001F105FA02F225FA03F311431943CB07C3 -:1031900012D50122A4F12003C4F1200102FA03F3A5 -:1031A00022FA01F1A240524243EA010363EB4303D6 -:1031B00032432B43CDE90823DDE90823C9E9002385 -:1031C000FFE66FF00100FCE66FF00800F9E6082C5E -:1031D000A0D9102CB3D9202CEED8C3E7BBF1000F37 -:1031E000ADD0022383E7BBF1000FBBD004237EE701 -:1031F00030B5012A144638BF0124402C85B028BFC1 -:1032000040240025012ACDE9025518D81B788DF8F5 -:10321000083063070AD004AB03EBD405624215F80B -:10322000083C02F00702934005F8083C0091034671 -:103230002246002102A8FFF727FB05B030BD082A6F -:10324000E4D9102A03D81B88ADF80830E1E7202A1A -:103250008DBFD3E900231B680293CDE90223D8E791 -:1032600010B5CB681BB98B600B618B8210BD0469F4 -:103270001A681C600361C38A013BC382CA60F0E71D -:1032800003064CBFC0F3C0300220704708B50246A9 -:10329000FFF7F6FF022806D15306C2F30F2001D133 -:1032A00000F0030008BDC2F30740FBE72DE9F04F33 -:1032B00093B0CDE903230A6804461046FFF7E0FF08 -:1032C000022814BFC2F306260026002A0D468246B5 -:1032D00080F2F28112F0C04940F0EE81097B0029B2 -:1032E00000F0EA81022803D02378B34240F0E7815E -:1032F000C2F304630693104602F07F030593FFF7C1 -:10330000C5FF059B29444FEA834848EA0A4848EA32 -:103310004668CE7800230022CDE90823F3098346CE -:1033200048EA0008029367D0059B0093024667684D -:10333000534608A92046B847002800F0C381276AF1 -:103340004FB9414604F10C00FFF702FB074690B964 -:103350006FF0020054E03B6998450DD03F68002FA4 -:10336000F9D1414604F10C00FFF7F2FA07460028B4 -:10337000EED0236A3B60276297F817C006F01F085B -:10338000CCF3840CACEB08001FFA80FE0028B8BF19 -:103390000EF12000A8EB0C031FFA83FED7E90221EF -:1033A000B8BF00B2002B0793BEBF0EF120031BB2C3 -:1033B000079352EA010338D0039BDFF824E39A1AFB -:1033C000049B4FF0000C63EB010196457CEB01037D -:1033D0002BD36B7B97F81AE0734519D1029B002B16 -:1033E00078D0012821DC7868F8B9DFF8F0C294457C -:1033F00070EB010316D337E0276A27B96FF00C0092 -:1034000013B0BDE8F08F3B699845B5D03F68F4E74D -:10341000B24890427CEB010301D30020F0E7029B0D -:10342000002BFAD0079B0F2B17DCFA7DB30002F0BC -:10343000030203F07C031343FB7539462046FFF774 -:1034400007FB6B7BBB76029B3BB9FB7DC3F384021E -:10345000013262F38603FB75D0E76A7BBB7E9A423A -:10346000DBD1029B002B35D0B309022B32D0039B5A -:10347000BB60049BFB60142200210DA8FDF7B4FF84 -:10348000039B0A93049B0B932B1D0C932B7BADF892 -:103490003EB0013BDBB2ADF83C30069B8DF84230CC -:1034A000059B8DF8433094F82C308DF840A083F0C4 -:1034B00001038DF844308DF84180A3680AA92046A5 -:1034C0009847FB7DC3F38403013303F01F039B0282 -:1034D000FB82A2E7FB7DC6F34012B2EBD31F40F0A4 -:1034E000F480C3F38403434540F0F280029A2B7BBF -:1034F000B609002A4DD0F2075DD4032B40F2EB80D1 -:10350000039BBB60049BFB602B7BAE1D033BDBB2CC -:103510003246394604F10C00FFF7ACFA00280CDA09 -:1035200039462046FFF794FAFB7DC3F38403013349 -:1035300003F01F039B02FB820AE7DDE90884AB88E6 -:103540003B834FF6FF73C9F12000A9F1200228FA4E -:1035500009F104FA00F0014324FA02F2114318467B -:10356000C9B2FFF7C9F909F10809B9F1400F0346DB -:10357000E9D1B8822A7B033AD2B23146FFF7CEF9BD -:10358000FB7DB882DA43C2F3C01262F3C713FB7546 -:1035900043E786B92E1D013BDBB23246394604F1C2 -:1035A0000C00FFF767FA0028BADB2A7BB88A013AD9 -:1035B000D2B23146E2E7F98AC1F30901013B04299D -:1035C000DAB25BD8281D002307F11B069A4208D9FE -:1035D00010F801CB06F801C0013101330529DBB237 -:1035E000F4D103990A9104990B91934207F11B01BD -:1035F0000C9138BF043379680D9134BF55FA83F3C9 -:1036000000230E93FB8AADF83EB0C3F309031A44BE -:10361000069B8DF84230059B8DF8433094F82C3092 -:10362000ADF83C2083F001038DF8443000238DF881 -:1036300040A08DF841807B602A7BB88A013A291D21 -:10364000FFF76CF93B8BB882834203D1A3680AA9C8 -:103650002046984720460AA9FFF702FEFB7DBA8A5A -:10366000C3F38403013303F01F039B02FB823B8BF4 -:103670009A420CBF00206FF01000C1E67B68002B5F -:10368000AFD0052001E01C3033461E68002EFAD171 -:10369000091A081D2E1D184401EB090CBCF11B0F63 -:1036A0005FFA89F39DD89A429BD916F8013B00F83E -:1036B000013B09F10109EFE76FF00900A0E66FF0A7 -:1036C0000A009DE66FF00B009AE66FF00D0097E69A -:1036D0006FF00E0094E66FF00F0091E640420F008D -:1036E00080841E00EFF3098305494A6B22F0010232 -:1036F0004A63683383F30988002383F31188704792 -:1037000000EF00E0302080F3118862B60C4B0D4AC8 -:10371000D96821F4E0610904090C0A43DA60D3F89E -:10372000FC20094942F08072C3F8FC200A6842F08C -:1037300001020A602022DA7783F82200704700BF76 -:1037400000ED00E00003FA05001000E010B53023A2 -:1037500083F311880E4B5B6813F4006314D0F1EE11 -:10376000103AEFF30984683C4FF08073E361094B32 -:10377000DB6B236684F3098800F090F810B1064BE8 -:10378000A36110BD054BFBE783F31188F9E700BF88 -:1037900000ED00E000EF00E04306000846060008E8 -:1037A00000F1604303F561430901C9B283F80013D6 -:1037B000012200F01F039A4043099B0003F160437C -:1037C00003F56143C3F880211A6070470023037535 -:1037D000826803691B6899689142FBD25A6803604A -:1037E0004260106058607047002303758268036967 -:1037F0001B6899689142FBD85A6803604260106068 -:103800005860704708B50846302383F311880B7D54 -:10381000032B05D0042B0DD02BB983F3118808BDE1 -:103820008B6900221A604FF0FF338361FFF7CEFFF0 -:103830000023F2E7D1E9003213605A60F3E7000099 -:10384000FFF7C4BF054BD9680875186802681A608D -:10385000536001220275D860FCF7DEBE204A0020CA -:1038600030B50C4BDD684B1C87B004460FD02B469F -:10387000094A684600F06CF92046FFF7E3FF009B19 -:1038800013B1684600F06EF9A86907B030BDFFF7C4 -:10389000D9FFF9E7204A002005380008044B1A68D0 -:1038A000DB6890689B68984294BF002001207047B5 -:1038B000204A0020084B10B51C68D86822681A609E -:1038C000536001222275DC60FFF78EFF014620461F -:1038D000BDE81040FCF7A0BE204A0020044B1A6847 -:1038E000DB6892689B689A4201D9FFF7E3BF704793 -:1038F000204A002038B5074C074908480123002515 -:103900002370656000F03AFC0223237085F3118870 -:1039100038BD00BF884C0020A44E0008204A00207B -:1039200008B572B6044B186500F0ECFA00F0A0FB85 -:10393000024B03221A70FEE7204A0020884C002028 -:1039400000F046B9EFF3118020B9EFF30583302280 -:1039500082F311887047000010B530B9EFF3058489 -:10396000C4F3080414B180F3118810BDFFF7B6FF4B -:1039700084F31188F9E700008B60022308618B82D1 -:10398000084670478368A3F1840243F8142C026947 -:1039900043F8442C426943F8402C094A43F8242C4C -:1039A000C26843F8182C022203F80C2C002203F8FA -:1039B0000B2C044A43F8102CA3F12000704700BFE1 -:1039C00031060008204A002008B5FFF7DBFFBDE8FC -:1039D0000840FFF735BF0000024BDB6898610F20FD -:1039E000FFF730BF204A0020302383F31188FFF710 -:1039F000F3BF000008B50146302383F31188082087 -:103A0000FFF72EFF002383F3118808BD064BDB6808 -:103A100039B1426818605A60136043600420FFF7B0 -:103A20001FBF4FF0FF307047204A002003689842C4 -:103A300006D01A680260506099611846FFF700BF0F -:103A40007047000010B503689C68A2420CD85C68FF -:103A50008A600B604C602160596099688A1A9A608C -:103A60004FF0FF33836010BD1B68121BECE70000B2 -:103A70000A2938BF0A2170B504460D460A26601986 -:103A800000F076FB00F062FB041BA54203D8751C16 -:103A90002E460446F3E70A2E04D9BDE87040012003 -:103AA00000F0ACBB70BD0000F8B5144B0D46D961F9 -:103AB00003F1100141600A2A1969826038BF0A22A5 -:103AC000016048601861A818144600F043FB0A27FB -:103AD00000F03CFB431BA342064606D37C1C28197E -:103AE00000F046FB27463546F2E70A2F04D9BDE829 -:103AF000F840012000F082BBF8BD00BF204A002042 -:103B0000F8B506460D4600F021FB0F4A134653F860 -:103B1000107F9F4206D12A4601463046BDE8F84054 -:103B2000FFF7C2BFD169BB68441A2C1928BF2C46C5 -:103B3000A34202D92946FFF79BFF2246314603489C -:103B4000BDE8F840FFF77EBF204A0020304A002041 -:103B500010B4C0E9032300235DF8044B4361FFF771 -:103B6000CFBF000010B5194C236998420DD0D0E9A1 -:103B70000032816813605A609A680A449A60002390 -:103B800003604FF0FF33A36110BD2346026843F882 -:103B9000102F53600022026022699A4203D1BDE8CF -:103BA000104000F0DFBA936881680B44936000F026 -:103BB000CDFA2269E1699268441AA242E4D911441B -:103BC000BDE81040091AFFF753BF00BF204A00208C -:103BD0002DE9F047DFF8BC8008F110072C4ED8F82B -:103BE000105000F0B3FAD8F81C40AA68031B9A42A0 -:103BF0003ED81444D5E900324FF00009C8F81C4003 -:103C000013605A60C5F80090D8F81030B34201D163 -:103C100000F0A8FA89F31188D5E9033128469847BE -:103C2000302383F311886B69002BD8D000F08EFA13 -:103C30006A69A0EB04094A4582460DD2022000F0D1 -:103C4000DDFA0022D8F81030B34208D15146284698 -:103C5000BDE8F047FFF728BF121A2244F2E712EB43 -:103C6000090938BF4A4629463846FFF7EBFEB5E753 -:103C7000D8F81030B34208D01444211AC8F81C00F8 -:103C8000A960BDE8F047FFF7F3BEBDE8F08700BFCD -:103C9000304A0020204A002000207047FEE7000044 -:103CA000704700004FF0FF3070470000BFF34F8FA8 -:103CB000024AD368DB03FCD4704700BF003C0240DB -:103CC00008B5094B1B7873B9FFF7F0FF074B1A696A -:103CD000002ABFBF064A5A6002F188325A601A6849 -:103CE00022F480621A6008BD904C0020003C024023 -:103CF0002301674508B50B4B1B7893B9FFF7D6FF37 -:103D0000094B1A6942F000421A611A6842F4805263 -:103D10001A601A6822F480521A601A6842F48062AB -:103D20001A6008BD904C0020003C02400728F0B506 -:103D300016D80C4C0C4923787BB90C4D0E46082341 -:103D40004FF0006255F8047B46F8042B013B13F05A -:103D5000FF033A44F6D10123237051F82000F0BD4F -:103D60000020FCE7B44C0020944C0020B04E00082A -:103D7000014B53F820007047B04E000808207047F0 -:103D8000072810B5044601D9002010BDFFF7CEFF6B -:103D9000064B53F824301844C21A0BB90120F4E73B -:103DA00012680132F0D1043BF6E700BFB04E0008C4 -:103DB000072810B5044621D8FFF778FFFFF780FFEA -:103DC0000F4AF323D360C300DBB243F4007343F024 -:103DD00002031361136943F480331361FFF766FF35 -:103DE000FFF7A4FF074B53F8241000F03DF9FFF74D -:103DF00081FF2046BDE81040FFF7C2BF002010BD84 -:103E0000003C0240B04E0008F8B512F00103144621 -:103E100042D185182E4A954257D82E4B1B6813F075 -:103E2000010352D02C4DFFF74BFFF323EB60FFF75C -:103E30003DFF40F20127032C15D824F00104661839 -:103E4000254C401A40F20117B142236900EB0105ED -:103E500024D123F001032361FFF74CFF0120F8BDBB -:103E6000043C0430E7E78307E7D12B6923F4407370 -:103E70002B612B693B432B6151F8046B0660BFF348 -:103E80004F8FFFF713FF03689E42E9D02B6923F0A1 -:103E900001032B61FFF72EFF0020E0E723F44073BE -:103EA000236123693B4323610B882B80BFF34F8F32 -:103EB000FFF7FCFE2D8831F8023BADB2AB42C3D018 -:103EC000236923F001032361E4E71846C7E700BF35 -:103ED0000000080800380240003C0240084908B5CC -:103EE0000B7828B11BB9FFF7EBFE01230B7008BD5F -:103EF000002BFCD0BDE808400870FFF7FBBE00BFF8 -:103F0000904C00204FF480214FF0005000F0AEB8EC -:103F10000846114600F0D6BE012000F0D3BE0000D6 -:103F2000084600F0EDBE000070B582B0FFF70AFD54 -:103F30000E4E054600F00AF93268904237BF0C4A2F -:103F40000B49516814682EBFD1E90041013151601D -:103F50000419034641F10001284601913360FFF73F -:103F6000FBFC0199204602B070BD00BFB84C002098 -:103F7000C04C002070B582B0FFF7E4FC104E05463F -:103F800000F0E4F83268904237BF0E4A0D4951689C -:103F900014682EBFD1E9004101315160041941F18B -:103FA00000010346284601913360FFF7D5FC0199D3 -:103FB0004FF47A7200232046FCF71AF902B070BD64 -:103FC000B84C0020C04C002010B50244064BD2B2C1 -:103FD000904200D110BD441C00B253F8200041F8BB -:103FE000040BE0B2F4E700BF502800400F4B30B59F -:103FF0001C6F240407D41C6F44F400741C671C6FEE -:1040000044F400441C670A4C236843F48073236023 -:104010000244084BD2B2904200D130BD441C00B2E1 -:1040200051F8045B43F82050E0B2F4E70038024056 -:10403000007000405028004007B5012201A900206F -:10404000FFF7C2FF019803B05DF804FB13B5044607 -:10405000FFF7F2FFA04205D0012201A90020019440 -:10406000FFF7C4FF02B010BD7047000070470000AA -:1040700070470000074B45F255521A6002225A6001 -:1040800040F6FF729A604CF6CC421A60024B012255 -:104090001A70704700300040CC4C0020034B1B7856 -:1040A0001BB1034B4AF6AA221A607047CC4C002081 -:1040B00000300040034B1A681AB9034AD2F874283A -:1040C0001A607047C84C002000300240024B4FF08D -:1040D0008072C3F8742870470030024008B5FFF7BB -:1040E000E9FF024B1868C0F3407008BDC84C0020BF -:1040F00008B5FFF7DFFF024B1868C0F3007008BD7A -:10410000C84C002070470000FEE700000A4B0B4837 -:104110000B4A90420BD30B4BDA1C121AC11E22F031 -:1041200003028B4238BF00220021FDF75DB953F82E -:10413000041B40F8041BECE77050000830520020CC -:10414000305200203052002000F0CAB84FF08043B7 -:10415000586A70474FF08043002258631A61022268 -:10416000DA6070474FF080430022DA607047000049 -:104170004FF0804358637047FEE7000070B51B4B5B -:1041800001630025044686B0586085620E46FFF73D -:10419000B9FA04F11003C4E904334FF0FF33C4E962 -:1041A0000635C4E90044A560E562FFF7CFFF2B4662 -:1041B0000246C4E9082304F134010D4A2565802331 -:1041C0002046FFF7D9FB0123E0600A4A03750092FD -:1041D00072680192B268CDE90223074B6846CDE9C7 -:1041E0000435FFF7F1FB06B070BD00BF884C00201E -:1041F000D04E0008D54E000879410008024AD36A23 -:104200001843D062704700BF204A00204B684360CB -:104210008B688360CB68C3600B6943614B69036241 -:104220008B6943620B6803607047000008B5234B3D -:1042300023481A6942F0FF021A611A6922F0FF024C -:104240001A611A691A6B42F0FF021A631A6D42F082 -:10425000FF021A651B4A1B6D1146FFF7D7FF02F1DB -:104260001C0100F58060FFF7D1FF02F1380100F575 -:104270008060FFF7CBFF02F1540100F58060FFF78B -:10428000C5FF02F1700100F58060FFF7BFFF02F18A -:104290008C0100F58060FFF7B9FF02F1A80100F57D -:1042A0008060FFF7B3FF02F1C40100F58060FFF703 -:1042B000ADFFBDE8084000F08DB800BF00380240F7 -:1042C00000000240DC4E000808B500F027FAFFF7B6 -:1042D00011FBBDE80840FFF7EDBE0000704700008D -:1042E0000F4B1A6C42F001021A641A6E42F001027E -:1042F0001A660C4A1B6E936843F0010393604FF0FB -:10430000804331229A624FF0FF32DA6200229A61D2 -:104310005A63DA605A6001225A611A60704700BF1E -:1043200000380240002004E04FF0804208B51169D7 -:10433000D3680B40D9B2C9439B07116107D530231D -:1043400083F31188FFF7FCFA002383F3118808BD7B -:104350001E4B1A6962F0FF021A611A69D2B21A6121 -:104360004FF0FF301A695A69586100215A69596142 -:104370005A691A6A62F080521A621A6A02F080520E -:104380001A621A6A5A6A58625A6A59625A6A1A6CE6 -:1043900042F080521A641A6E42F080521A661A6E07 -:1043A0000B4A106840F480701060186F00F4407081 -:1043B000B0F5007F1EBF4FF480301867196753684F -:1043C00023F40073536000F07DB900BF0038024051 -:1043D000007000403B4B3C4A1A643C4A4FF4404159 -:1043E00011601A6842F001021A601A689007FCD541 -:1043F0009A6822F003029A60324B9A6812F00C021B -:10440000FBD1196801F0F90119609A601A6842F449 -:1044100080321A601A689103FCD55A6F42F001028B -:104420005A67284B5A6F9207FCD5294A5A601A6876 -:1044300042F080721A60254A53685804FCD5214B1B -:104440001A689101FCD5234AC3F884201A6842F007 -:1044500080621A601A681201FCD51F4A9A60032212 -:10446000C3F88C204FF00062C3F894201B4B1A68ED -:104470001B4B9A421B4B21D11B4A11681B4A91428C -:104480001CD140F203121A60164A136803F00F039E -:10449000032BFAD10B4B9A6842F002029A609A6899 -:1044A00002F00C02082AFAD15A6C42F480425A6493 -:1044B0005A6E42F480425A665B6E704740F2037255 -:1044C000E1E700BF00380240000400100070004027 -:1044D000081940021030002400948838002004E0BD -:1044E00011640020003C024000ED00E041C20F4199 -:1044F000074A08B5536903F00103536123B1054A24 -:1045000013680BB150689847BDE80840FFF71EB923 -:10451000003C0140D04C0020074A08B5536903F025 -:104520000203536123B1054A93680BB1D0689847E1 -:10453000BDE80840FFF70AB9003C0140D04C00201C -:10454000074A08B5536903F00403536123B1054AD0 -:1045500013690BB150699847BDE80840FFF7F6B8FA -:10456000003C0140D04C0020074A08B5536903F0D5 -:104570000803536123B1054A93690BB1D069984789 -:10458000BDE80840FFF7E2B8003C0140D04C0020F5 -:10459000074A08B5536903F01003536123B1054A74 -:1045A000136A0BB1506A9847BDE80840FFF7CEB8D0 -:1045B000003C0140D04C0020164B10B55C6904F45F -:1045C00078725A61A30604D5134A936A0BB1D06A74 -:1045D0009847600604D5104A136B0BB1506B98478F -:1045E000210604D50C4A936B0BB1D06B9847E205BA -:1045F00004D5094A136C0BB1506C9847A30504D538 -:10460000054A936C0BB1D06C9847BDE81040FFF79A -:104610009DB800BF003C0140D04C0020194B10B5A4 -:104620005C6904F47C425A61620504D5164A136D34 -:104630000BB1506D9847230504D5134A936D0BB108 -:10464000D06D9847E00404D50F4A136E0BB1506E3D -:104650009847A10404D50C4A936E0BB1D06E9847CD -:10466000620404D5084A136F0BB1506F98472304B6 -:1046700004D5054A936F0BB1D06F9847BDE8104041 -:10468000FFF764B8003C0140D04C002008B5034857 -:1046900000F010F9BDE80840FFF758B8504D002071 -:1046A00008B5034800F006F9BDE80840FFF74EB82A -:1046B000BC4F002008B5FFF737FEBDE80840FFF704 -:1046C00045B80000062108B50846FFF769F806213D -:1046D0000720FFF765F806210820FFF761F806219B -:1046E0000920FFF75DF806210A20FFF759F8062197 -:1046F0001720FFF755F806212820FFF751F807216A -:104700001C20FFF74DF80C212520FFF749F8BDE8E4 -:1047100008400C212620FFF743B8000008B5FFF73A -:1047200017FE00F07BF800F03DF8FFF7D7FDBDE87D -:104730000840FFF709BD00000268436811430160AB -:1047400003B1184770470000143000F0DFB90000D3 -:104750004FF0FF33143000F0D9B90000383000F0CA -:1047600055BA00004FF0FF33383000F04FBA000068 -:10477000143000F0A5B900004FF0FF31143000F004 -:104780009FB90000383000F0FFB900004FF0FF3251 -:10479000383000F0F9B90000012914BF6FF01300A0 -:1047A0000020704700F060B837B515460E4A026029 -:1047B00000224260C0E902220122044602740B4634 -:1047C000009000F15C014FF48072143000F04EF95B -:1047D00000942B464FF4807204F5AE7104F138005A -:1047E00000F0C6F903B030BDBC4F000838B5C3694E -:1047F00004460D461BB904210844FFF79DFF2946D6 -:1048000004F1140000F040F9002806DA201D4FF4EE -:104810000061BDE83840FFF78FBF38BD0023054A6F -:1048200019460133102BC2E9001102F10802F8D138 -:10483000704700BFD04C00200268436811430160FC -:1048400003B1184770470000024AD36843F0C00321 -:10485000D360704700100140024AD36843F0C003A0 -:10486000D36070470044004010B50A4C0A4A204605 -:104870000021FFF799FF094B094AC4E99723094C26 -:10488000094A00212046FFF78FFF0849084BC4E979 -:10489000971310BD504D00204948000880F0FA02DF -:1048A00000100140BC4F002059480008004400405F -:1048B00040787D012DE9F041D0F85C62F7683368FB -:1048C000DA0504469DB20DD5302383F311884FF4E9 -:1048D00080610430FFF7B0FF6FF480733360002312 -:1048E00083F31188302383F3118804F1040815F051 -:1048F0002F033AD183F31188380615D5290613D52D -:10490000302383F3118804F1380000F065F90028A2 -:104910004EDA0821201DFFF78FFF4FF67F733B40D3 -:10492000F360002383F311887A0616D56B0614D53D -:10493000302383F31188D4E913239A420AD1236CDC -:1049400043B127F040073F041021201D3F0CFFF723 -:1049500073FFF760002383F31188D4F86822D368CB -:1049600043B3BDE8F041106918472B0714D015F088 -:10497000080F0CBF00214FF48071E80748BF41F0D9 -:104980002001AA0748BF41F040016B0748BF41F032 -:1049900080014046FFF750FFAD06736805D594F8D7 -:1049A000641220461940FFF721FF3568ADB29EE73B -:1049B0007060B6E7BDE8F081F8B515468268066913 -:1049C000AA420B46816938BF8568761AB54204460B -:1049D0000BD218462A46FCF7F5FCA3692B44A361C9 -:1049E000A3685B1BA3602846F8BD0CD91846324665 -:1049F000FCF7E8FCAF1BE1683A463044FCF7E2FC08 -:104A0000E3683B44EBE718462A46FCF7DBFCE36827 -:104A1000E5E7000083689342F7B51546044638BFC2 -:104A20008568D0E90460361AB5420BD22A46FCF7F5 -:104A3000C9FC63692B446361A36828465B1BA360C0 -:104A400003B0F0BD0DD932460191FCF7BBFC0199D2 -:104A5000E068AF1B3A463144FCF7B4FCE3683B44E2 -:104A6000E9E72A46FCF7AEFCE368E4E710B50A4440 -:104A70000024C361029B8460C0E90000C0E9051105 -:104A8000C1600261036210BD08B5D0E905329342EE -:104A900001D1826882B98268013282605A1C426107 -:104AA0001970D0E904329A4224BFC36843610021DF -:104AB000FEF7BCFF002008BD4FF0FF30FBE7000011 -:104AC00070B5302304460E4683F31188A568A5B15E -:104AD000A368A269013BA360531CA36115782269F6 -:104AE000934224BFE368A361E3690BB12046984772 -:104AF000002383F31188284607E031462046FEF75D -:104B000085FF0028E2DA85F3118870BD2DE9F74FA3 -:104B100004460E4617469846D0F81C904FF0300ACF -:104B20008AF311884FF0000B154665B12A463146CD -:104B30002046FFF741FF034660B941462046FEF795 -:104B400065FF0028F1D0002383F31188781B03B0A0 -:104B5000BDE8F08FB9F1000F03D001902046C8479F -:104B6000019B8BF31188ED1A1E448AF31188DCE750 -:104B7000C0E90511C160C3611144009B8260C0E9B6 -:104B80000000016103627047F8B504460D46164601 -:104B9000302383F31188A768A7B1A368013BA36002 -:104BA00063695A1C62611D70D4E904329A4224BFC1 -:104BB000E3686361E3690BB120469847002080F306 -:104BC000118807E031462046FEF720FF0028E2DA90 -:104BD00087F31188F8BD0000D0E905239A4210B58B -:104BE00001D182687AB98268013282605A1C82617E -:104BF0001C7803699A4224BFC36883610021FEF7D1 -:104C000015FF204610BD4FF0FF30FBE72DE9F74FB1 -:104C100004460E4617469846D0F81C904FF0300ACE -:104C20008AF311884FF0000B154665B12A463146CC -:104C30002046FFF7EFFE034660B941462046FEF7E7 -:104C4000E5FE0028F1D0002383F31188781B03B020 -:104C5000BDE8F08FB9F1000F03D001902046C8479E -:104C6000019B8BF31188ED1A1E448AF31188DCE74F -:104C70000B460146184600F02DB8000000F040B881 -:104C8000012838BF012010B50446204600F030F856 -:104C900030B900F007F808B900F00CF88047F4E7E5 -:104CA00010BD0000024B1868BFF35B8F704700BF58 -:104CB0002852002008B5062000F084F80120FEF7F5 -:104CC000EDFF0000024B0A4601461868FFF720B9C5 -:104CD0001C23002010B5054C13462CB10A46014692 -:104CE0000220AFF3008010BD2046FCE7000000006A -:104CF000024B01461868FFF70FB900BF1C230020C4 -:104D0000024B01461868FFF70BB900BF1C230020B7 -:104D100010B501390244904201D1002005E003782A -:104D200011F8014FA34201D0181B10BD0130F2E76A -:104D30002DE9F041A3B1C91A17780144044603F1E3 -:104D4000FF3C8C42204601D9002009E00578BD4295 -:104D500004F10104F5D10CEB0405D618A54201D1EC -:104D6000BDE8F08115F8018D16F801EDF045F5D09C -:104D7000E7E700001F2938B504460D4604D916237D -:104D800003604FF0FF3038BD426C12B152F8213051 -:104D90004BB9204600F030F82A4601462046BDE8CF -:104DA000384000F017B8012B0AD0591C03D1162344 -:104DB00003600120E7E7002442F825402846984791 -:104DC0000020E0E7024B01461868FFF7D3BF00BFA1 -:104DD0001C23002038B5074D002304460846114621 -:104DE0002B60FEF75FFF431C02D12B6803B12360E9 -:104DF00038BD00BF2C520020FEF74EBF034611F80D -:104E0000012B03F8012B002AF9D170476F72672E2E -:104E10006172647570696C6F742E435541565F47BB -:104E20005053000040A2E4F1646891060041A3E5FC -:104E3000F2656992070000004261642043414E49D7 -:104E40006661636520696E6465782E0080000000ED -:104E50000080000000008000000000000000000052 -:104E6000551C00083D2400089D230008651C00080F -:104E7000991C0008951E0008691C0008791C000890 -:104E80006D1C0008751C0008711C0008BD1D000881 -:104E90007D1C0008092700088D1C0008911D0008D2 -:104EA00063300000A04E0008784A0020884C0020A3 -:104EB00000400000004000000040000000400000F2 -:104EC00000000100000002000000020000000200DB -:104ED0006D61696E0069646C65000000A0011028B6 -:104EE00000000000AAAAAAAA50011024FFFF000097 -:104EF000007700000000000000A40A01000000008C -:104F0000AAA6AAAA80500000DFEF000000000077E8 -:104F1000880000000000000000000000AAAAAAAA61 -:104F200000000000FFFF0000000000000000000083 -:104F30000000000000000000AAAAAAAA00000000C9 -:104F4000FFFF000000000000000000000000000063 -:104F500000000000AAAAAAAA00000000FFFF0000AB -:104F60000000000000000000000000000000000041 -:104F7000AAAAAAAA00000000FFFF0000000000008B -:104F8000000000000000000000000000AAAAAAAA79 -:104F900000000000FFFF0000000000000000000013 -:104FA00000000000000000000A00000000000000F7 -:104FB00003000000000000000000000000000000EE -:104FC00065470008514700088D47000879470008E9 -:104FD00085470008714700085D47000849470008F9 -:104FE000994700083CB2FF7F01000000000000006C -:104FF000E9030000000000000000070000000000BE -:1050000040420F00FE2A0100D204000020230020AD -:105010000000000000000000000000000000000090 -:105020000000000000000000000000000000000080 -:105030000000000000000000000000000000000070 -:105040000000000000000000000000000000000060 -:105050000000000000000000000000000000000050 -:105060000000000000000000000000000000000040 +:1000000000070020F101000809240008C1230008AE +:10001000E9230008C1230008E1230008F3010008D8 +:10002000F3010008F3010008F3010008FD330008A4 +:10003000F3010008F3010008F3010008F3010008D0 +:10004000F3010008F3010008F3010008F3010008C0 +:10005000F3010008F3010008CD410008F541000854 +:100060001D420008454200086D420008F3010008E7 +:10007000F3010008F3010008F3010008F301000890 +:10008000F3010008F3010008F301000875230008DC +:10009000A1230008B1230008F301000895420008DD +:1000A000F3010008F3010008F3010008F301000860 +:1000B00091430008F3010008F3010008F301000870 +:1000C000F3010008F3010008F3010008F301000840 +:1000D000F3010008694300087D430008F3010008AC +:1000E000F9420008F3010008F3010008F3010008D9 +:1000F000F3010008F3010008F3010008F301000810 +:10010000F3010008F3010008F3010008F3010008FF +:10011000F3010008F3010008F3010008F3010008EF +:10012000F3010008F3010008F3010008F3010008DF +:10013000F3010008F3010008F3010008F3010008CF +:10014000F3010008F3010008F3010008F3010008BF +:10015000F3010008F3010008F3010008F3010008AF +:10016000F3010008F3010008F3010008F30100089F +:10017000F3010008F3010008F3010008F30100088F +:10018000F3010008F3010008F3010008F30100087F +:10019000F3010008F3010008F3010008F30100086F +:1001A000F3010008F3010008F3010008F30100085F +:1001B000F3010008F3010008F3010008F30100084F +:1001C000F3010008F3010008F3010008F30100083F +:1001D000F3010008F3010008F3010008F30100082F +:1001E000C50F000800000000000000000000000033 +:1001F00002E000F000F8FEE772B6374880F30888A6 +:10020000364880F3098836483649086040F20000D5 +:10021000CCF200004EF63471CEF200010860BFF35C +:100220004F8FBFF36F8F40F20000C0F2F0004EF628 +:100230008851CEF200010860BFF34F8FBFF36F8F7C +:100240004FF00000E1EE100A4EF63C71CEF20001D4 +:100250000860062080F31488BFF36F8F03F0C0FDA1 +:1002600003F052FE4FF055301F491B4A91423CBFEC +:1002700041F8040BFAE71D49184A91423CBF41F886 +:10028000040BFAE71A491B4A1B4B9A423EBF51F82E +:10029000040B42F8040BF8E700201849184A914271 +:1002A0003CBF41F8040BFAE703F09EFD03F07AFE31 +:1002B000144C154DAC4203DA54F8041B8847F9E797 +:1002C00000F042F8114C124DAC4203DA54F8041B12 +:1002D0008847F9E703F086BD0007002000230020CF +:1002E0000000000808ED00E00001002000070020E9 +:1002F000C04C000800230020802300208023002021 +:1003000028520020E0010008E4010008E401000890 +:10031000E40100082DE9F04F2DED108AC1F80CD052 +:10032000C3689D46BDEC108ABDE8F08F002383F3BF +:1003300011882846A047002003F0BCF9FEE703F02F +:1003400045F900DFFEE70000F8B500F04DFE03F0D0 +:10035000E1FC074603F030FD064600283DD12B4B5B +:100360009F423AD001339F423AD0294B27F0FF02F7 +:100370009A4238D1F8B200F043FC354642F210748C +:1003800000F044FC08B10024254601F019F970B3CF +:10039000032000F043F80024254636B11D4B9F4250 +:1003A00003D003F001FD00242546002003F0BCFC2F +:1003B000194B1B691B071FD40DB100F045F800F065 +:1003C00091FC02F029F80546C4B102F025F8401B63 +:1003D000A04213D900F038F8F3E735460024CFE700 +:1003E00004460125CCE705464FF47A74C8E7B4F516 +:1003F0007A7F08BF0125D0E70024E0E700F0BAFCCF +:100400004FF47A7003F05CF9DEE700BF010007B03B +:10041000000008B0263A09B000040240084B1870EA +:1004200003280CD8DFE800F008050208022000F0DD +:1004300039BE022000F02CBE024B00225A607047E9 +:10044000802300208423002010B501F0B9F830B1DA +:10045000204B03221A70204B00225A6010BD1F4B04 +:100460001F4A1C4619680131F8D004339342F9D170 +:1004700062681C4B9A42F1D91B4B9B6803F10063E5 +:1004800003F580339A42E9D203F062FC03F074FC76 +:10049000002000F0C3FD0220FFF7C0FF134B1A6CD1 +:1004A00000221A64196E1A66196E596C5A64596ED4 +:1004B0005A665B6E72B64FF0E0233021C3F8084DE8 +:1004C000D4E9003281F311889D4683F308881047F0 +:1004D000C4E700BF8023002084230020000001081F +:1004E00020000108FFFF0008002300200038024020 +:1004F000094A136849F2690099B21B0C00FB0133E9 +:100500001360064B186844F2506182B2000C01FB84 +:100510000200186080B270471823002014230020C6 +:1005200010B500211022044600F0D8FD034B03CB88 +:10053000206061601868A06010BD00BF107AFF1FC6 +:100540002DE9F041ADF54E7D0DF134086CAC40F273 +:10055000751207460D460EA80021C8F8001000F0DD +:10056000BDFD4FF4C4720021204600F0B7FD01F03C +:1005700053FF274B4FF47A72B0FBF2F0186093E808 +:100580000700022384E807000DF5E9702382FFF7D6 +:10059000C7FF4EF603131F49238407A804F09CFAF3 +:1005A000162384F832310DF2E32207AB0DF12C0C47 +:1005B0001E4603CE664510605160334602F10802C4 +:1005C000F6D130681060B3889380414601222046FE +:1005D00000F0D0FD00230393AB7E029305F11903D5 +:1005E000019380B20123CDE904800093E97E06A344 +:1005F000D3E90023384602F0D7FA0DF54E7DBDE869 +:10060000F08100BFAFF300809E6AC421818A46EE6C +:100610008C230020E84A00082DE9F0412C4C237A75 +:10062000DAB080460D465BBB27A9284600F0B2FE33 +:100630000746002842D19DF89D60C82E3ED801464D +:100640004FF4A662204600F049FD4FF48073C4F8D1 +:10065000F8314FF40073C4F80C334FF44073C4F80E +:10066000203432460DF19E0104F1090000F024FD12 +:1006700026449DF89C30777223720BB9EB7E23726F +:100680008122002106AC27A800F028FD0122214686 +:1006900027A800F0BBFE00230393AB7E029305F175 +:1006A000190380B201932823CDE904400093E97E29 +:1006B00005A3D3E90023404602F076FA5AB0BDE81C +:1006C000F08100BFAFF3008026417272DF25D7B7FB +:1006D000B0440020F0B5254E4FF48A7505FB006547 +:1006E000F1B096F8D83085F8DC300024D8222146C5 +:1006F00085F8E8403AA800F0F1FC06F1090000F0A6 +:10070000E5FCD5F8E4308DF8F000C2B206AF06F192 +:1007100009010DF1F100CDE93A3400F0CDFC394684 +:1007200001223AA800F09EFE80B2CDE904700823B1 +:100730000127CDE9023706F1D80301933023009356 +:10074000317A0B4807A3D3E9002302F02DFAA04227 +:1007500006DD01F061FEC5F8E000384671B0F0BD7D +:100760002046FBE778F6339F93CACD8DB044002036 +:10077000A43300202DE9F0411D4D1E4E1E4F86B0C2 +:10078000284602F03DFA034658B30024CDE903445D +:10079000ADF81440027B8DF81420996840680294EB +:1007A00003AA03C21B68DFF8548043F0004302939E +:1007B00001F034FE821941F10003009402A9384689 +:1007C00001F0DCF8A04205DD284602F01DFA88F8A9 +:1007D0000040D5E798F80030072B05D8013388F89A +:1007E000003006B0BDE8F081014802F00DFAF8E7EC +:1007F000A433002040420F00D8330020E5490020F8 +:1008000070B50D4614461E4602F02AF950B9022E64 +:1008100010D1012C0ED112A3D3E90023C5E9002386 +:10082000012007E0282C10D005D8012C09D0052C78 +:100830000FD0002070BD302CFBD10BA3D3E90023D7 +:10084000ECE70BA3D3E90023E8E70BA3D3E90023EC +:10085000E4E70BA3D3E90023E0E700BFAFF3008098 +:10086000401DA12026812A0B78F6339F93CACD8D97 +:100870009E6AC421818A46EE26417272DF25D7B76F +:10088000F017304A39059E5638B505460E4C002102 +:10089000013500F0E5FBA4F82C55B4F82C0500F068 +:1008A000C7FB78B1B4F82C0500F0D2FB014648B97B +:1008B000B4F82C0500F0D4FBB4F82C350133A4F8BF +:1008C0002C35EAE738BD00BFB044002010B50A4B14 +:1008D0000A4A1A6003F5805393F860203AB9DC6D38 +:1008E0002CB1204600F0EAFE204604F035F8BDE8C1 +:1008F0001040034800F0E2BED83300203C4B000813 +:10090000204400202DE9F04F8FB000AF05460C4683 +:1009100002F0A6F8002849D1237E022B1BD1E38ADE +:10092000012B18D101F078FD0646FFF7E1FD0346E3 +:100930004FF4C870DFF8C482B3FBF0F206F5167608 +:1009400002FB103316FA83F3C8F80030E37E33B9A4 +:10095000A34B00221A703C37BD46BDE8F08F07F16B +:100960002401204600F0D4FC0028F4D107F1140043 +:10097000FFF7D6FD97F8264007F11401224607F14C +:10098000270004F033F80028E2D10F2C08D8944B4C +:100990001C70D8F80030A3F51673C8F80030DAE7F9 +:1009A00097F82410284602F053F8D4E7E38A282B5E +:1009B0002BD010D8012B23D0052BCCD1BFF34F8FD8 +:1009C0008849894BCA6802F4E0621343CB60BFF3E5 +:1009D0004F8F00BFFDE7302BBDD1844EE17E327AD0 +:1009E0009142B8D1607E3146002291F8DC508542B8 +:1009F00000F0A5800132042A01F58A71F5D1AAE739 +:100A000021462846FFF79CFDA5E721462846FFF72B +:100A100003FEA0E7B2F8EC507B6005F103094FEA52 +:100A200099094FEA8902D11DC908A8EBC1039D4667 +:100A3000EB460021584600F051FB04F1EE012A4636 +:100A40003144584600F038FB7B6813B9012000F0B0 +:100A5000E5FA96F8D20000F0EBFA044630B93072AD +:100A600000F006FB204600F0D9FAB1E0D6F8D42019 +:100A70003AB996F8D200B6F82C25824201D8FFF791 +:100A800003FFD6F8D4202A44944208D296F8D20024 +:100A9000B6F82C250130824201D8FFF7F5FE7068C8 +:100AA0005FFA89F2594600F021FB08B9C54679E0A2 +:100AB000726896F8D2002A447260D6F8D42005EB0A +:100AC0000209C6F8D49000F0B3FA814509D396F82C +:100AD000D220D6F8D4000132001B86F8D220C6F806 +:100AE000D400FF2D0FD80024347200F0C1FA204644 +:100AF00000F094FA00F064FD3D4B188108B9FFF74F +:100B0000A3FCC54627E7BB6896F8D9000AFB036239 +:100B1000FB68D2F8E41082F8E83001F58061C2F891 +:100B2000E030C2F8E410FFF7D5FDFFF723FE96F89A +:100B3000D920013202F0030286F8D920B6E74FF43B +:100B40008A7A0AFB02F505F1EA013144204600F0F9 +:100B5000B5FCF86000287FF4FEAE3544012285F82C +:100B6000E82001F059FCD5F8E020D6ED007ADFED61 +:100B7000216A801A192838BF192040F6B8329042ED +:100B800028BF1046B8EE677A07EE900AF8EEE77ACB +:100B900067EEA67ADFED186AE7EE267AFCEEE77AD2 +:100BA000C6ED007A96F8D930BB60BA6873680AFB64 +:100BB00002F4321992F8E81059B1D2F8E4108B42DD +:100BC000E8463FF427AF002182F8E810C2F8E010B1 +:100BD000C5467368064A9B0A01331381BBE600BF12 +:100BE0009D33002000ED00E00400FA05B044002031 +:100BF0008C230020CDCCCC3D6666663FA033002020 +:100C0000014B1870704700BF9823002030B54FF09B +:100C100000542B4B22689A4285B007D003F0D6F8D7 +:100C2000044620BB0024204605B030BD254B627D24 +:100C300025481A70237D03724FF48073C0F8F83191 +:100C40004FF40073C0F80C3300254FF44073C0F824 +:100C500020341E49C0F8E450C922093000F02CFAB3 +:100C60002046E022294600F039FA0124DBE7184A41 +:100C7000184D136C43F000731364AA6D164B9A421F +:100C8000D0D12B6E013B7E2BCCD8144A07CA01ABC6 +:100C900083E807001846032100F060FC6B6D834277 +:100CA0004FF00003BED12A6D8A4201BFAB65054BF0 +:100CB0002A6E1A7003BF0A4BEA6D1A601C46B2E72F +:100CC0009AAD44C598230020B044002016000020AF +:100CD00000380240006600405041A0B05866004015 +:100CE0001023002037B51A4D00F06AFC02236B7107 +:100CF000184B288119681848012201F029FA0023AD +:100D00000193164B164900931648174B4FF4805227 +:100D100001F076FE154B197811B1124801F098FEDA +:100D200001F07AFB0446FFF7E3FB4FF4C873B0FB16 +:100D3000F3F202FB130304F5167010FA83F00C4B68 +:100D4000186003F039F808B10F232B8103B030BDD0 +:100D50008C23002010230020D83300200108000835 +:100D60009C230020A43300200509000898230020BC +:100D7000A03300202DE9F04F2DED028B0FF2382922 +:100D8000D9E90089834C93B00BAE9FED7E8BFFF7C2 +:100D9000F1FC814FDFF828A200230A93ADF834302C +:100DA0000B9373604FF0000B5B468DED008B0125BC +:100DB0000DF11D0207A938468DF81C508DF81DB0A5 +:100DC00001F074F99DF81C30002B40F0A5802046FE +:100DD00001F046FE0646002845D1704F01F01CFB8D +:100DE0003B6898423FD301F017FB8246FFF780FB38 +:100DF0004FF4C873B0FBF3F202FB13030AF516704D +:100E000010FA83F03860664F97F800B0CBF1100A03 +:100E1000BBF1000F14BF33462B465FFA8AFA0EA8C7 +:100E20008DF82830FFF77CFBBAF1060F28BF4FF092 +:100E3000060A0EAB03EB0B0152460DF1290000F040 +:100E40003BF90AAB0393182302930AF10102554BB5 +:100E5000D2B2CDE90053049220464CA3D3E900233B +:100E600001F044FE3E7001F0D7FA4F4A4F4D13682F +:100E7000C31AB3F57A7F2ED3106001F0CFFA024681 +:100E80000B46204601F0CAFE204601F0E9FD10B3F2 +:100E90002B7A474E002B14BF03230223737101F0FA +:100EA000BBFA0EAF4FF47A730122B0FBF3F0394670 +:100EB0003060304600F004FA182302933D4B019352 +:100EC00080B240F25513CDE90370009342464B4681 +:100ED000204601F00BFE2B7A93B101F09DFA00261B +:100EE00007464FF48A7A95F8D900304400F00300A1 +:100EF0000AFB005393F8E82092B30136042EF2D196 +:100F0000C82002F0DDFB2B7A002B7FF43DAF13B03D +:100F1000BDEC028BBDE8F08FDAF8143083F4805317 +:100F2000CAF81430594610220EA800F0D7F80DF177 +:100F30001E0308AA0AA9384600F020FE96E803001E +:100F40000FAB83E803009DF834308DF844300A9BE2 +:100F50000E930EA9DDE90823204602F033F821E7BD +:100F6000D3F8E02042B12B68FA2B38BFFA23BA1A23 +:100F70000533B2EB430FC0D3FFF7ACFB0028BCD165 +:100F8000BEE700BF0000000000000000401DA120DF +:100F900026812A0BA4330020D8330020A033002060 +:100FA0009D3300209C330020E0490020B044002005 +:100FB0008C230020E4490020F1C6A7C1D068080FA7 +:100FC0000004024008B5054800F074FEBDE8084082 +:100FD000034A0449002003F0B9BC00BFD833002005 +:100FE000204A0020CD08000870B502F03DFD094EF2 +:100FF000094D3080002428683388834208D902F0E4 +:101000002DFD2B6804440133B4F5803F2B60F2D3EF +:1010100070BD00BF144A0020E849002002F0D4BD92 +:1010200000F10060920000F5803002F063BD000026 +:10103000054B1A68054B1B889B1A834202D9104442 +:1010400002F00CBD00207047E8490020144A00203F +:10105000024B1B68184402F009BD00BFE84900209C +:10106000024B1B68184402F019BD00BFE84900207C +:10107000064991F8243033B10023086A81F82430FE +:101080000822FFF7CDBF0120704700BFEC490020C8 +:10109000022802BF024B4FF480529A61704700BF92 +:1010A00000040240022802BF024B4FF080529A61B6 +:1010B000704700BF0004024010B50023934203D0E4 +:1010C000CC5CC4540133F9E710BD0000034602466E +:1010D000D01A12F9011B0029FAD1704702440346C5 +:1010E000934202D003F8011BFAE770472DE9F84359 +:1010F0001F4D144695F824200746884652BBDFF85A +:1011000070909CB395F824302BB92022FF214846DB +:101110002F62FFF7E3FF95F82400C0F10802A24216 +:1011200028BF2246D6B24146920005EB8000FFF769 +:10113000C3FF95F82430A41B1E44F6B2082E1744B2 +:101140009044E4B285F82460DBD1FFF791FF0028DA +:10115000D7D108E02B6A03EB82038342CFD0FFF79D +:1011600087FF0028CBD10020BDE8F8830120FBE7F2 +:10117000EC4900202DE9F0470D4604460021904639 +:10118000284640F27912FFF7A9FF234620220021CA +:10119000284601F0B9FE231D02222021284601F035 +:1011A000B3FE631D03222221284601F0ADFEA31DDC +:1011B00003222521284601F0A7FE04F1080310228E +:1011C0002821284601F0A0FE04F11003082238214E +:1011D000284601F099FE04F1110308224021284617 +:1011E00001F092FE04F1120308224821284601F082 +:1011F0008BFE04F1140320225021284601F084FEC6 +:1012000004F1180340227021284601F07DFE04F10C +:1012100020030822B021284601F076FE04F12103C4 +:101220000822B821284601F06FFE04F12207C026EB +:101230003B46314608222846083601F065FEB6F5E1 +:10124000A07F07F10107F3D104F1320308223146F0 +:10125000284601F059FE002704F1330A94F8323091 +:101260004FEAC7099F4209F5A47615D3B8F1000FDC +:1012700008D1314604F599730722284601F044FE4F +:1012800009F24F16274694F832213B1B93420CD3A8 +:10129000F01DC008BDE8F0870AEB070308223146BD +:1012A000284601F031FE0137D8E707F23313314603 +:1012B0000822284601F028FE08360137E3E700003F +:1012C00013B504460846002101602346C0F8031008 +:1012D0002022019001F018FE0198231D02222021F6 +:1012E00001F012FE0198631D0322222101F00CFE81 +:1012F0000198A31D0322252101F006FE019804F1A7 +:1013000008031022282101F0FFFD072002B010BDC4 +:10131000F7B50023047F00910E46072219460546C3 +:1013200001F0B6FC731C009301220023072128461C +:1013300001F0AEFCC4B9B31C00930522234608217A +:10134000284601F0A5FC0D243746B278BB1B93421A +:1013500011D32B7FA88A0734E408BBB9844294BF19 +:101360000020012003B0F0BDAB8ADB00083BDB08A6 +:10137000B3700824E8E7FB1C0093214600230822F1 +:10138000284601F085FC08340137DEE7201A18BF33 +:101390000120E7E7F7B50023047F00910E460822FD +:1013A0001946054601F074FC731CC4B90822009369 +:1013B00011462346284601F06BFC10240123727865 +:1013C0005F1C013B934211D32B7FA88A0734E408AA +:1013D000BBB9844294BF0020012003B0F0BDAB8AAA +:1013E000DB00083BDB0873700824E7E7F319009380 +:1013F000214600230822284601F04AFC08343B46D7 +:10140000DDE7201A18BF0120E7E70000F8B50E4617 +:1014100005461446002181223046FFF75FFE2B4629 +:1014200008220021304601F06FFD7CB96B1C0722B9 +:101430000821304601F068FD0F2401236A785F1C03 +:10144000013B934204D3E01DC008F8BD0824F4E733 +:10145000EB1921460822304601F056FD08343B4680 +:10146000ECE70000F8B50E46054614460021CE22F2 +:101470003046FFF733FE2B4628220021304601F08C +:1014800043FD7CB905F1080308222821304601F00C +:101490003BFD30242F462A7A7B1B934204D3E01D68 +:1014A000C008F8BD2824F5E707F109032146082202 +:1014B000304601F029FD08340137ECE7F7B5047F29 +:1014C00000910E46012310220021054601F0E0FBA9 +:1014D000C4B9B31C0093092223461021284601F009 +:1014E000D7FB192437467288BB1B9A4211D82B7F31 +:1014F000A88A0734E408BBB9844294BF00200120C5 +:1015000003B0F0BDAB8ADB00103BDB087380102416 +:10151000E8E73B1D0093214600230822284601F0FE +:10152000B7FB08340137DEE7201A18BF0120E7E7D0 +:1015300030B5094D0A4491420DD011F8013B584095 +:10154000082340F30004013B2C4013F0FF0384EA1E +:101550005000F6D1EFE730BD2083B8EDF7B54FF07E +:10156000FF33DFF854C0DFF854E000EB81011A4686 +:1015700088421CD050F8044B019401AF042417F8A2 +:10158000015B82EA05620825DB18164605F1FF3586 +:101590005241002EBCBF83EA0C0382EA0E0215F012 +:1015A000FF05F1D1013C14F0FF04E8D1E0E7D84396 +:1015B000D14303B0F0BD00BF9336EAA9EBE1F0429E +:1015C000F7B5384A106851686B4603C36A46364916 +:1015D0003648082303F01AFA0446002833D10A25B6 +:1015E000334A106851686B4603C36A4631492F4835 +:1015F000082303F00BFA0446002849D00369B3F529 +:10160000E02F45D8B0F8661040F2E93291423FD160 +:10161000294A024402F15C018B4239D35C3B2349E5 +:1016200000209E1AFFF784FF3246074604F164014A +:101630000020FFF77DFFA3689F4229D1E36898420D +:1016400008BF002524E00369B3F5E02F27D8418BBC +:1016500040F2E932914220D1174A024402F11001CE +:101660008B4218D3103B114900209D1AFFF760FFF1 +:101670002A46064604F118010020FFF759FFA36827 +:101680009E4202D1E368984201D00D25A8E70025CB +:10169000284603B0F0BD1025A2E70C25A0E70B25D6 +:1016A0009EE700BF004B0008DCFF060000000108B9 +:1016B000094B000890FF06000800FFF710B5037CF7 +:1016C000044613B9006803F089F9204610BD0000F4 +:1016D0000023BFF35B8FC360BFF35B8FBFF35B8FF0 +:1016E0008360BFF35B8F7047BFF35B8F0068BFF30E +:1016F0005B8F704770B505460C30FFF7F5FF05F1BD +:10170000080604463046FFF7EFFFA04206D93046F0 +:101710006D68FFF7E9FF2544281A70BD3046FFF7D2 +:10172000E3FF201AF9E7000070B50546406898B15C +:1017300005F10800FFF7D8FF05F10C060446304616 +:10174000FFF7D2FF8442304694BF6D680025FFF753 +:10175000CBFF013C2C44201A70BD000038B50C466C +:101760000546FFF7C7FFA04210D305F10800FFF7B9 +:10177000BBFF04446868B4FBF0F100FB1144BFF305 +:101780005B8F0120AC60BFF35B8F38BD0020FCE7AE +:101790002DE9F041144607460D46FFF7C5FF844288 +:1017A00028BF0446D4B1B84658F80C6B4046FFF742 +:1017B0009BFF3044286040467E68FFF795FF331A50 +:1017C0009C4203D86C600120BDE8F0816B60A41BD3 +:1017D0003B68AB602044E8600220F5E72046F3E771 +:1017E00038B50C460546FFF79FFFA04210D305F120 +:1017F0000C00FFF779FF04446868B4FBF0F100FBCC +:101800001144BFF35B8F0120EC60BFF35B8F38BDE9 +:101810000020FCE72DE9FF41884669460746FFF7AF +:10182000B7FF6C4606B204EBC6060025B44209D0E9 +:101830006268206808EB0501FFF73EFC6368083426 +:101840001D44F3E729463846FFF7CAFF284604B08F +:10185000BDE8F081F8B505460C300F46FFF744FFB0 +:1018600005F1080604463046FFF73EFFA042304629 +:1018700088BF6C68FFF738FF201A386020B1304607 +:101880002C68FFF731FF2044F8BD000073B5144603 +:1018900006460D46FFF72EFF844228BF04460190FE +:1018A000DCB101A93046FFF7D5FF019B33B932689F +:1018B000C5E90233C5E9002401200CE09C4238BF91 +:1018C00001942860019868608442F5D93368AB6060 +:1018D000241AEC60022002B070BD2046FBE7000035 +:1018E0002DE9FF410F466946FFF7D0FF6C4600B275 +:1018F00004EBC0050026AC4209D0D4F8048054F8AB +:10190000081BB8194246FFF7D7FB4644F3E73046B9 +:1019100004B0BDE8F081000038B50546FFF7E0FFF0 +:10192000044601462846FFF719FF204638BD00004F +:1019300010B4026854681A4623465DF8044B1847F1 +:10194000002070470020704770470000002070475B +:101950000E20704700F5805090F8C800C0F340009A +:101960007047000000F5805090F9D00070470000EB +:1019700000F58050C0F8CC1001207047F7B50C6816 +:10198000BDF8207014F0005470D10D7B082D6DD877 +:10199000302585F311884569AE6876010CD4AC68B2 +:1019A000240108D4AC6814F080545DD184F311880C +:1019B000204603B0F0BD01240E6804F1180C002E7F +:1019C000B8BFF6004FEA0C1CB4BF46F0040676051B +:1019D00045F80C600E680FFA84FC16F0804F18BFB3 +:1019E00005EB0C1E05EB0C1C1EBFDEF8806146F0FB +:1019F0000206CEF880610E7BCCF8846105EB0415FD +:101A00008E68C5F88C614E68C5F88861DCF8805135 +:101A100045F00105CCF8805100EB441641F2680511 +:101A20002E4405EB44150544C6E9002308350E464F +:101A300001F10C0C56F804EB45F804EB6645F9D1BE +:101A4000843436882E8000EB441407F00305267991 +:101A500026F00B0635432571002484F31188009786 +:101A600000F0FCFC0120A4E70224A5E74FF0FF30C2 +:101A70009FE7000013B500F580540191E06DFFF77A +:101A800053FE1F280AD90199E06D2022FFF7C2FEFC +:101A9000A0F120035842584102B010BD0020FBE7DE +:101AA00008B5302383F3118800F58050C06DFFF72F +:101AB0000FFE002383F3118808BD0000002202609E +:101AC000828142608260704710B500220023C0E925 +:101AD00000230023044603810C30FFF7EFFF20466C +:101AE00010BD0000F0B5054600F580500C4690F89A +:101AF000C83013F0040FC3F3800108BF114661F32F +:101B0000820304F1840680F8C83005EB461389B0DF +:101B10001B79D8072ED57AB319072DD46846FFF75D +:101B2000D3FF05EB441303F5835303F1180703AA0E +:101B3000103318685968144603C40833BB42224660 +:101B4000F7D1186820609B88A380DDE90E23CDE9DA +:101B500000230123ADF808302B686946DB6B28466B +:101B6000984705EB46152B791A075CBF43F008032D +:101B70002B7101E0002AF4D109B0F0BD2DE9F04746 +:101B80009A4688B0074688469146302383F31188E9 +:101B900007F580546846FFF797FFE06DFFF7AAFD51 +:101BA0001F282AD9E06D20226946FFF7B5FE2028BC +:101BB00023D103AD444605AB2E4603CE9E422060A2 +:101BC0006160354604F10804F6D130682060B388BE +:101BD000A380DDE90023C9E90023BDF80830AAF895 +:101BE0000030002383F3118853464A464146384665 +:101BF00008B0BDE8F04700F01FBC002080F311885A +:101C000008B0BDE8F08700002DE9F84F0023C0E9D7 +:101C10000133254B044640F8183B0F46FFF74EFFB3 +:101C200004F12800FFF750FF04F1480804F582553D +:101C30004646083530462036FFF746FFAE42F9D11A +:101C400004F580554FF480534FF00009C5E913396E +:101C5000C5F848800123EE6504F5875804F58456DD +:101C6000C5F8549085F8583085F86030083608F18A +:101C700008084FF0000A4FF0000B46E908ABA6F148 +:101C80001800FFF71BFF203646F8289C4645F4D184 +:101C900085F8D07017B1054800F0B8FB044B6361BC +:101CA0002046BDE8F88F00BF3C4B0008144B0008ED +:101CB0000064004010B5044B197804464A1C1A70A1 +:101CC000FFF7A2FF204610BD1C4A00202DE9F04777 +:101CD000002950D0294B2A4FB7FBF1F599428CBF10 +:101CE0000A231123581EB5FBF3FC03FB1C53C4B29B +:101CF0002BB102280346F5D80020BDE8F0870CF18F +:101D0000FF36B6F5806FF7D2C4EBC40E0EF10303B5 +:101D10004FEAE309C3F3C703A4EB030809F1010A7F +:101D20004FF47A755FFA88F009FB05555AFA88F87E +:101D3000B5FBF8F5B5F5617FC1BF0EF1FF33C3F315 +:101D4000C703E01AC0B25C1C50FA84F40CFB04F424 +:101D5000B7FBF4F4A142CFD1013BDBB20F2BCBD8C0 +:101D60000138C0B20728C7D80021107116809170C1 +:101D7000D3700120C1E70846BFE700BF3F420F0014 +:101D800040787D0170B505460E464FF47A746B6954 +:101D90005B6803F00103B34207D04FF47A7001F09F +:101DA0008FFC013CF3D1204670BD0120FCE7000010 +:101DB00030B54269936913F0700F16D000230B4CB5 +:101DC000936103F1840200EB421211794D0709D5AA +:101DD000890707D5416954F823508D60117941F086 +:101DE000040111710133032BEBD130BD284B0008E6 +:101DF00073B51D46436916469A68D207044609D54D +:101E00009A6801219960C2F34002CDE90065002182 +:101E1000FFF768FE63699A68D1050BD59A684FF49D +:101E200080719960C2F34022CDE90065012120460E +:101E3000FFF758FE63699A68D2030BD59A684FF48E +:101E400080319960C2F34042CDE90065022120460D +:101E5000FFF748FE04F58053D3F8CC0010B10368B7 +:101E60001B699847204602B0BDE87040FFF7A0BF4D +:101E7000F8B504464669002972D106F10C073868A6 +:101E8000800770D006EB01153868D5F8B00110F066 +:101E9000040FD5F8B0011ABFC00840F00040400D53 +:101EA000A061D5F8B0C11CF0020F1CBF40F080400B +:101EB000A061D5F8B40106EB011100F00F0084F821 +:101EC0002400D1F8B8012077D1F8B801000A607772 +:101ED000D1F8B801000CA077D1F8B801000EE07776 +:101EE000D1F8BC0184F82000D1F8BC01000A84F8C4 +:101EF0002100D1F8BC01000C84F82200D1F8BC11FB +:101F0000090E84F823103821396004F1340004F1FB +:101F1000180104F1240551F8046B40F8046BA94240 +:101F2000F9D109880180C4E90A23214600232386C8 +:101F300051F8283B2046DB6B984704F5805393F813 +:101F4000C820D3F8CC0042F0040283F8C82010B1B6 +:101F500003681B6998472046BDE8F840FFF728BF93 +:101F600006F110078BE7F8BD10B5044600F056FAED +:101F700002460B4652EA030102D0013A63F1000324 +:101F80000449086820B12146BDE81040FFF770BF42 +:101F900010BD00BF184A0020F0B5302181F3118830 +:101FA000DFF848C000F583510831002404F18405AE +:101FB00000EB45152E7977070ED4F6060CD5D1E93E +:101FC000007697429E4107D246695CF82470B7605C +:101FD0002E7946F004062E710134032C01F1200104 +:101FE000E4D1002383F31188F0BD00BF284B000823 +:101FF00008B5302383F31188FFF7DAFE002383F35B +:10200000118808BDF8B543690546986800F0E050AE +:10201000B0F1E05F0F4621D0F8B1302383F311888F +:1020200005F583541034002606F1840305EB4313B1 +:102030001B791A0706D50136032E04F12004F3D1CB +:10204000012007E05B07F6D42146384600F040FA4D +:102050000028F0D1002383F31188F8BD0120FCE7AC +:1020600008B5302383F3118800F58050C06DFFF769 +:1020700041FB002383F3118843090CBF012000209A +:1020800008BD0000F8B51D46002313700F46064634 +:102090001446FFF7E5FF80F00100387025B12946AE +:1020A0003046FFF7AFFF2070F8BD00002DE9B841C2 +:1020B0000C4615461F46804600F0B0F90B462178C5 +:1020C000024609B9287850B14046FFF765FFFFF78F +:1020D0008FFF3B462A462146FFF7D4FF0120BDE88B +:1020E000B881000070B5302686F31188174B1A6C42 +:1020F00042F000721A641A6A42F000721A621A6A96 +:1021000022F000721A62002383F3118800F58054D4 +:1021100094F8C83013F0010516D1A9B186F31188DF +:102120000321132001F0C8F90321142001F0C4F9A0 +:102130000321152001F0C0F994F8C83043F00103E1 +:1021400084F8C83085F3118870BD00BF00380240A4 +:102150002DE9F04700F5805588B095F8D030012B77 +:1021600004468846164600F28180814F57F82320A6 +:102170000AB947F82300D7F800A0C4F80C802674E9 +:10218000BAF1000F64D095F8D030012B70D0012146 +:102190002046FFF7A7FF302383F311886269136895 +:1021A00023F0020313606269136843F001031360B4 +:1021B000636900275F6187F3118801212046FFF7DB +:1021C000E1FD002800F09580E86DFFF781FA04F545 +:1021D0008359BA4609F10809202200216846FEF712 +:1021E0007DFF02A8FFF76AFCCDF818A06A4609EB4C +:1021F00007030DF1180E9446BCE80300F44518607F +:102200005960624603F10803F5D1DCF8000018605C +:1022100020379CF804201A71602FDDD195F8C83062 +:102220006FF38203002785F8C8306A46414620468E +:10223000ADF80070ADF802708DF80470FFF746FD40 +:10224000636948BB4FF400421A6008B0BDE8F087EC +:1022500041F2D80002F082FB814610B15146FFF7EF +:10226000D3FCC7F80090B9F1000F8CD10020ECE747 +:10227000386803681B6B98470146002887D1386887 +:10228000FFF730FF3868036832465B68414698477D +:1022900000287FF47CAFE9E761221A609DF80230E4 +:1022A0009DF803201B06120402F4702203F0407311 +:1022B0001343BDF80020C2F3090213439DF8042024 +:1022C0001205022E02F4E0020CBF4FF00041002183 +:1022D000134362690B43D361636913225A616269D4 +:1022E000136823F00103136039462046FFF74AFDC7 +:1022F00008B96369A6E795F8D03093BB6169D1F856 +:10230000002242F00102C1F800226169D1F80022E6 +:1023100022F47C5222F00E02C1F800226169D1F849 +:10232000002242F46062C1F800226269C2F81432ED +:102330006269C2F80432626941F6FF71C2F80C1298 +:102340006269C2F840326269C2F8443263690122AC +:10235000C3F81C226269D2F8003223F00103C2F8EC +:10236000003295F8C83043F0020385F8C8306CE7B6 +:10237000184A002008B500F051F850EA010302465F +:1023800002D0421E61F10001044B186810B10B46E7 +:10239000FFF72EFDBDE8084001F064B8184A0020A0 +:1023A00008B50020FFF7E0FDBDE8084001F05AB88D +:1023B00008B50120FFF7D8FDBDE8084001F052B88C +:1023C00000B59BB0EFF3098168226846FEF774FE02 +:1023D000EFF30583014B9B6BFEE700BF00ED00E0D0 +:1023E00008B5FFF7EDFF000000B59BB0EFF30981E2 +:1023F00068226846FEF760FEEFF30583014B5B6BD6 +:10240000FEE700BF00ED00E0FEE700000FB408B5F6 +:10241000029801F005F9FEE701F01ABC01F0FCBBDF +:1024200013B56C4684E80600031D94E8030083E8B6 +:102430000500012002B010BD73B58568019155B14A +:102440001B885B0707D4D0E900369B6B9847019A3D +:10245000C1B23046A847012002B070BDF0B5866811 +:1024600089B005460C465EB1BDF838305B070AD42A +:10247000D0E900379B6B98472246C1B23846B04737 +:10248000012009B0F0BD00220023CDE90023002384 +:10249000ADF808300A4603AB01F108061068516830 +:1024A0001C4603C40832B2422346F7D110682060AC +:1024B0009288A280FFF7B2FF0423ADF808302B68A2 +:1024C000CDE90001DB6B694628469847D8E7000054 +:1024D00030B503680968DD0FB5EBD17F23F06044A8 +:1024E00021F060424FEAD1700BD0002BB8BFA40C92 +:1024F0000029B8BF920C944202D034BF01200020C2 +:1025000030BD944205D1C1F38070C3F38073834220 +:10251000F6D194422CBF00200120F1E72DE9F041D3 +:10252000456A15B94162BDE8F0814B6823F0604708 +:10253000C3F38A464FEAD37EC3F3807816EA2306B4 +:1025400038BF3E46AC462B465A68BEEBD27F22F0DF +:1025500060440AD0002A18DAA40CB44217D19D4274 +:102560000FD10D60DEE71346EEE7A74207D102F078 +:102570008044C2F3807242450BD054B1EFE708D2D9 +:10258000EDE7CCF800100B60CDE7B44201D0B442C7 +:10259000E5D81A689C46002AE5D11960C3E7000017 +:1025A0002DE9F047089D01F007044FEAD5082244C1 +:1025B00005F0070500EBD1004FF47F49944201D1AB +:1025C000BDE8F08704F0070705F0070A57453E46C7 +:1025D00038BF5646C6F10806111B8E4228BF0E466C +:1025E000E10808EBD50E415C13F80EC0B94029FA9A +:1025F00006F721FA0AF1FFB28CEA010147FA0AF75D +:1026000039408CEA010C03F80EC034443544D5E758 +:1026100080EA0120082341F2210201B24000002992 +:1026200080B203F1FF33B8BF504013F0FF03F4D181 +:102630007047000038B50C468D18A54200D138BD52 +:1026400014F8011BFFF7E4FFF7E7000042684AB106 +:10265000136843604389818901339BB29942438166 +:1026600038BF83811046704770B588B02022044679 +:102670000D4668460021FEF731FD20460495FFF720 +:10268000E5FF024658B16B46054608AE1C4603CC32 +:10269000B44228606960234605F10805F6D110466A +:1026A00008B070BD082817D909280CD00A280CD00A +:1026B0000B280CD00C280CD00D280CD00E2814BFE1 +:1026C0004020302070470C207047102070471420A5 +:1026D000704718207047202070470000082817D93D +:1026E0000C280CD910280CD914280CD918280CD96E +:1026F00020280CD930288CBF0F200E2070470920CD +:1027000070470A2070470B2070470C2070470D203F +:10271000704700002DE9F843078C072F04461ED9A7 +:10272000D0E9029800254FF6FF73C5F12006A5F108 +:10273000200029FA05F108FA06F628FA00F03143DC +:102740000143C9B21846FFF763FF0835402D034621 +:10275000EBD1E1693A46BDE8F843FFF76BBF4FF6AE +:10276000FF70BDE8F883000010B54B6823B9CA8A32 +:1027700063F30902CA8210BD04691A681C60036110 +:10278000C38A013BC3824A60EFE700002DE9F84F9E +:102790001D46CB8A0F46C3F309010529814692469F +:1027A0000B4630D00020AAB207F11A049EB2042EC4 +:1027B0001FFA80F80FD8904503F1010306D3FB8A76 +:1027C0000A4462F30903FB8201201AE01AF8006050 +:1027D000E6540130EAE79045F1D2A1F1050B1C2344 +:1027E0007C68BBFBF3F203FB12BB1FFA8BF6002CD9 +:1027F00045D14846FFF72AFF044638B978606FF0A4 +:102800000200BDE8F88F4FF00008E6E700260660FA +:102810007860ADB24FF0000B454510D90AEB0803C4 +:10282000221D13F8011B9155B1B208F101081B29B3 +:102830001FFA88F82BD0454506F10106F1D8FB8A2E +:10284000C3F30902154465F30903BCE7013292B2F0 +:102850001C462368002BF9D16B1F0B441C21B3FBD2 +:10286000F1F301339BB29A42D3D2BBF1000FD0D126 +:102870004846FFF7EBFE20B9C4F800B0BFE70122DD +:10288000E7E7C0F800B05E4620600446C1E7454572 +:10289000D5D94846FFF7DAFE08B92060AFE7C0F89F +:1028A00000B0002620600446B6E700002DE9F04F96 +:1028B0002DED028B1C4683B05B690192074688466A +:1028C000002B00F09A80238C2BB1E269002A00F0E3 +:1028D0009480072B35D807F10C00FFF7B7FE0546AB +:1028E00038B96FF00205284603B0BDEC028BBDE895 +:1028F000F08F14220021FEF7F1FB228CE16905F133 +:102900000800FEF7D9FB208C013080B2FFF7E6FE0D +:10291000FFF7C8FE013880B2208401302874636953 +:10292000228C1B782A4403F01F0363F03F0348F016 +:1029300000411372384669602946FFF7EFFD012513 +:10294000D1E700F10C034FF0000908EE103A4FF008 +:10295000800A4E464D4618EE100AFFF777FE834672 +:102960000028BED014220021FEF7B8FB002E3AD179 +:10297000019BABF8083002220BF1080E1FFA82FC13 +:102980000CF10100BCF1060F218C80B201D88E42FF +:102990002BD3FFF7A3FEFFF785FE6269127801389B +:1029A00002F01F028E4208BF4FF0400A42EA49126D +:1029B0001BFA80F14AEA020A013048F0004281F82D +:1029C00008A08BF81000CBF8042059463846FFF7D2 +:1029D000A5FD238C0135B3422DB289F001094FF0DA +:1029E000000AB8D17FE70022C6E7E169895D0EF8E9 +:1029F00002100136B6B20132C0E76FF0010572E78E +:102A0000F8B515460E463022002104461F46FEF753 +:102A100065FB069B6360B5F5001F079BA76034BF8D +:102A20006A094FF6FF72A36297B2E66104F11000E3 +:102A300000239A4206D800230360A782E3822383FF +:102A4000E360F8BD0660013330462036F1E7000050 +:102A500003781BB94BB2002BC8BF01707047000050 +:102A600000787047F8B50C46C969074611B9238C40 +:102A7000002B37D1257E1F2D34D8387828BB228CE7 +:102A8000072A2CD8268A36F003032BD14FF6FF7085 +:102A9000FFF7D0FD20F001003102400441EA05615A +:102AA000400C41EA40254FF6FF722346294638463E +:102AB000FFF7FCFE002807DD626913780133DBB203 +:102AC0001F2B88BF00231370F8BD218A2D0645EA0D +:102AD000012505432046FFF71DFE0246E5E76FF09E +:102AE0000300F1E76FF00100EEE7000070B58AB077 +:102AF000044616460021282268461D46FEF7EEFAD7 +:102B0000BDF83830ADF810300F9B05939DF840307C +:102B10008DF81830119B07936946BDF84830ADF821 +:102B200020302046CDE90265FFF79CFF0AB070BD5A +:102B30002DE9F041D36905460C4616460BB9138CB6 +:102B40005BBB377E1F2F28D895F80080B8F1000FA7 +:102B500026D03046FFF7DEFD3378210241EAC3314B +:102B600041EA0801338A41EA076141EA034102462A +:102B7000334641F080012846FFF798FE00280ADD21 +:102B80003378012B07D1726913780133DBB21F2B25 +:102B900088BF00231370BDE8F0816FF00100FAE7F1 +:102BA0006FF00300F7E70000F0B58BB004460D4668 +:102BB00017460021282268461E46FEF78FFA9DF828 +:102BC0004C305A1E534253418DF800309DF840302E +:102BD000ADF81030119B05939DF848308DF81830F2 +:102BE000149B07936A46BDF85430ADF8203029464F +:102BF0002046CDE90276FFF79BFF0BB0F0BD000049 +:102C0000406A00B104307047436A1A684262026940 +:102C10001A600361C38A013BC38270472DE9F0410A +:102C2000D0F82080194E14461D464146002709B9A8 +:102C3000BDE8F081D1E90223A21A65EB03039642B5 +:102C400077EB03031ED2036A8B420DD1FFF78CFD95 +:102C5000036A1B68036203690B60C38A0161016A2E +:102C6000013BC3828846E2E7FFF77EFD0B68C8F8A8 +:102C7000003003690B60C38A0161013BC382D8F84D +:102C80000010D4E788460968D1E700BF80841E00A1 +:102C90002DE9F04F8BB00D46DDF8509014469B4661 +:102CA0008046002800F01981B9F1000F00F015816D +:102CB000531E3F2B00F21181012A03D1BBF1000FFB +:102CC00040F00B810023CDE90833B8F81430B5EBA0 +:102CD000C30F4FEAC30703D300200BB0BDE8F08F4A +:102CE0002B199F42D8F80C303ABF7F1BFFB2274602 +:102CF0001BB9D8F81030002B7AD0272D4ED8C5F14B +:102D00002806B7424FF000032CBFF6B23E460093B0 +:102D10002946D8F8080008AB3246FFF741FCA7EB7C +:102D2000060A35445FFA8AFAB8F8143003F1005302 +:102D3000053BDB000493D8F80C3003932821039B58 +:102D400013B1BAF1000F2CD1D8F8100040B1BAF18C +:102D5000000F05D0009608AB5246691AFFF720FC19 +:102D600038B2002FB8D066070AD00AAB03EBD40103 +:102D7000624211F8083C02F00702134101F8083CD6 +:102D8000082C3CD9102C40F2B580202C40F2B780A2 +:102D9000BBF1000F00F09C80082334E0BA46002607 +:102DA000C2E7049BE02B28BFE02306930B44AB4211 +:102DB000059314D95A1B03980096924534BF524686 +:102DC000D2B2691A08AB04300792FFF7E9FB079A01 +:102DD0001644AAEB020A1544F6B25FFA8AFA049B7B +:102DE000069A05999B1A0493039B1B680393A6E715 +:102DF0000093D8F8080008AB3A462946AEE7BBF185 +:102E0000000F13D00123B4EBC30F6CD0082C12D8E1 +:102E10009DF82030621E23FA02F2D50706D54FF046 +:102E2000FF3202FA04F423438DF820309DF820305D +:102E300089F8003051E7102C12D8BDF82030621EFE +:102E400023FA02F2D10706D54FF0FF3202FA04F45A +:102E50002343ADF82030BDF82030A9F800303CE71E +:102E6000202C0FD80899631E21FA03F3DA0705D541 +:102E70004FF0FF3202FA04F40C430894089BC9F89F +:102E800000302AE7402C2BD0DDE90865611EC4F133 +:102E90002102A4F1210326FA01F105FA02F225FA32 +:102EA00003F311431943CB0712D50122A4F12003E8 +:102EB000C4F1200102FA03F322FA01F1A2405242C6 +:102EC00043EA010363EB430332432B43CDE9082379 +:102ED000DDE90823C9E90023FFE66FF00100FCE605 +:102EE0006FF00800F9E6082CA0D9102CB3D9202CDB +:102EF000EED8C3E7BBF1000FADD0022383E7BBF1EF +:102F0000000FBBD004237EE730B5012A144638BF3A +:102F10000124402C85B028BF40240025012ACDE99A +:102F2000025518D81B788DF8083063070AD004AB17 +:102F300003EBD405624215F8083C02F00702934007 +:102F400005F8083C009103462246002102A8FFF73D +:102F500027FB05B030BD082AE4D9102A03D81B8806 +:102F6000ADF80830E1E7202A8DBFD3E900231B68C4 +:102F70000293CDE90223D8E710B5CB681BB98B606B +:102F80000B618B8210BD04691A681C600361C38ADF +:102F9000013BC382CA60F0E703064CBFC0F3C030F8 +:102FA0000220704708B50246FFF7F6FF022806D157 +:102FB0005306C2F30F2001D100F0030008BDC2F395 +:102FC0000740FBE72DE9F04F93B0CDE903230A68F2 +:102FD00004461046FFF7E0FF022814BFC2F306269E +:102FE0000026002A0D46824680F2F28112F0C04986 +:102FF00040F0EE81097B002900F0EA81022803D02D +:103000002378B34240F0E781C2F30463069310468D +:1030100002F07F030593FFF7C5FF059B29444FEAA4 +:10302000834848EA0A4848EA4668CE7800230022E6 +:10303000CDE90823F309834648EA0008029367D0E4 +:10304000059B009302466768534608A92046B84787 +:10305000002800F0C381276A4FB9414604F10C00F3 +:10306000FFF702FB074690B96FF0020054E03B699E +:1030700098450DD03F68002FF9D1414604F10C006E +:10308000FFF7F2FA07460028EED0236A3B6027627A +:1030900097F817C006F01F08CCF3840CACEB0800BF +:1030A0001FFA80FE0028B8BF0EF12000A8EB0C0329 +:1030B0001FFA83FED7E90221B8BF00B2002B0793A5 +:1030C000BEBF0EF120031BB2079352EA010338D0B2 +:1030D000039BDFF824E39A1A049B4FF0000C63EB88 +:1030E000010196457CEB01032BD36B7B97F81AE02B +:1030F000734519D1029B002B78D0012821DC786818 +:10310000F8B9DFF8F0C2944570EB010316D337E04D +:10311000276A27B96FF00C0013B0BDE8F08F3B6948 +:103120009845B5D03F68F4E7B24890427CEB010384 +:1031300001D30020F0E7029B002BFAD0079B0F2B56 +:1031400017DCFA7DB30002F0030203F07C031343A3 +:10315000FB7539462046FFF707FB6B7BBB76029B6E +:103160003BB9FB7DC3F38402013262F38603FB7536 +:10317000D0E76A7BBB7E9A42DBD1029B002B35D025 +:10318000B309022B32D0039BBB60049BFB6014226B +:1031900000210DA8FDF7A2FF039B0A93049B0B934C +:1031A0002B1D0C932B7BADF83EB0013BDBB2ADF891 +:1031B0003C30069B8DF84230059B8DF8433094F8E7 +:1031C0002C308DF840A083F001038DF844308DF849 +:1031D0004180A3680AA920469847FB7DC3F3840376 +:1031E000013303F01F039B02FB82A2E7FB7DC6F3C2 +:1031F0004012B2EBD31F40F0F480C3F38403434585 +:1032000040F0F280029A2B7BB609002A4DD0F207DB +:103210005DD4032B40F2EB80039BBB60049BFB60FF +:103220002B7BAE1D033BDBB23246394604F10C006A +:10323000FFF7ACFA00280CDA39462046FFF794FA7B +:10324000FB7DC3F38403013303F01F039B02FB8266 +:103250000AE7DDE90884AB883B834FF6FF73C9F1C9 +:103260002000A9F1200228FA09F104FA00F0014334 +:1032700024FA02F211431846C9B2FFF7C9F909F15D +:103280000809B9F1400F0346E9D1B8822A7B033A15 +:10329000D2B23146FFF7CEF9FB7DB882DA43C2F3F2 +:1032A000C01262F3C713FB7543E786B92E1D013BBD +:1032B000DBB23246394604F10C00FFF767FA00280A +:1032C000BADB2A7BB88A013AD2B23146E2E7F98A00 +:1032D000C1F30901013B0429DAB25BD8281D0023A0 +:1032E00007F11B069A4208D910F801CB06F801C075 +:1032F000013101330529DBB2F4D103990A91049914 +:103300000B91934207F11B010C9138BF043379688C +:103310000D9134BF55FA83F300230E93FB8AADF869 +:103320003EB0C3F309031A44069B8DF84230059B57 +:103330008DF8433094F82C30ADF83C2083F0010335 +:103340008DF8443000238DF840A08DF841807B60DB +:103350002A7BB88A013A291DFFF76CF93B8BB882AA +:10336000834203D1A3680AA92046984720460AA9A8 +:10337000FFF702FEFB7DBA8AC3F38403013303F037 +:103380001F039B02FB823B8B9A420CBF00206FF015 +:103390001000C1E67B68002BAFD0052001E01C3097 +:1033A00033461E68002EFAD1091A081D2E1D184436 +:1033B00001EB090CBCF11B0F5FFA89F39DD89A420F +:1033C0009BD916F8013B00F8013B09F10109EFE731 +:1033D0006FF00900A0E66FF00A009DE66FF00B00A9 +:1033E0009AE66FF00D0097E66FF00E0094E66FF02E +:1033F0000F0091E640420F0080841E00EFF3098326 +:1034000005494A6B22F001024A63683383F3098855 +:10341000002383F31188704700EF00E0302080F331 +:10342000118862B60C4B0D4AD96821F4E061090499 +:10343000090C0A43DA60D3F8FC20094942F0807293 +:10344000C3F8FC200A6842F001020A602022DA7701 +:1034500083F82200704700BF00ED00E00003FA058A +:10346000001000E010B5302383F311880E4B5B6829 +:1034700013F4006314D0F1EE103AEFF30984683CC2 +:103480004FF08073E361094BDB6B236684F309889B +:1034900000F090F810B1064BA36110BD054BFBE79F +:1034A00083F31188F9E700BF00ED00E000EF00E0D2 +:1034B0003F0300084203000800F1604303F5614345 +:1034C0000901C9B283F80013012200F01F039A40DA +:1034D00043099B0003F1604303F56143C3F8802176 +:1034E0001A60704700230375826803691B68996836 +:1034F0009142FBD25A680360426010605860704786 +:1035000000230375826803691B6899689142FBD8A0 +:103510005A680360426010605860704708B50846FA +:10352000302383F311880B7D032B05D0042B0DD0A2 +:103530002BB983F3118808BD8B6900221A604FF004 +:10354000FF338361FFF7CEFF0023F2E7D1E90032BA +:1035500013605A60F3E70000FFF7C4BF054BD9685A +:103560000875186802681A60536001220275D860F5 +:10357000FCF7D0BE284A002030B50C4BDD684B1C50 +:1035800087B004460FD02B46094A684600F046F93A +:103590002046FFF7E3FF009B13B1684600F048F9AF +:1035A000A86907B030BDFFF7D9FFF9E7284A002026 +:1035B0001D350008044B1A68DB6890689B689842C8 +:1035C00094BF002001207047284A0020084B10B506 +:1035D0001C68D86822681A60536001222275DC607A +:1035E000FFF78EFF01462046BDE81040FCF792BE73 +:1035F000284A002038B5074C074908480123002510 +:103600002370656000F028FC0223237085F3118885 +:1036100038BD00BF904C0020804B0008284A002095 +:1036200008B572B6044B186500F0E2FA00F08EFBA4 +:10363000024B03221A70FEE7284A0020904C00201B +:1036400000F02CB98B60022308618B82084670471A +:103650008368A3F1840243F8142C026943F8442CD4 +:10366000426943F8402C094A43F8242CC26843F8C5 +:10367000182C022203F80C2C002203F80B2C044A0D +:1036800043F8102CA3F12000704700BF2D03000861 +:10369000284A002008B5FFF7DBFFBDE80840FFF728 +:1036A0005BBF0000024BDB6898610F20FFF756BF3D +:1036B000284A0020302383F31188FFF7F3BF00006E +:1036C00008B50146302383F311880820FFF754FF23 +:1036D000002383F3118808BD064BDB6839B14268CB +:1036E00018605A60136043600420FFF745BF4FF035 +:1036F000FF307047284A00200368984206D01A68B5 +:103700000260506099611846FFF726BF70470000BD +:1037100010B503689C68A2420CD85C688A600B6094 +:103720004C602160596099688A1A9A604FF0FF33A3 +:10373000836010BD1B68121BECE700000A2938BF2C +:103740000A2170B504460D460A26601900F07EFB7A +:1037500000F06AFB041BA54203D8751C2E460446E4 +:10376000F3E70A2E04D9BDE87040012000F0B4BB95 +:1037700070BD0000F8B5144B0D46D96103F110017E +:1037800041600A2A1969826038BF0A2201604860D4 +:103790001861A818144600F04BFB0A2700F044FB00 +:1037A000431BA342064606D37C1C281900F04EFB9F +:1037B00027463546F2E70A2F04D9BDE8F840012034 +:1037C00000F08ABBF8BD00BF284A0020F8B50646C5 +:1037D0000D4600F029FB0F4A134653F8107F9F4215 +:1037E00006D12A4601463046BDE8F840FFF7C2BF81 +:1037F000D169BB68441A2C1928BF2C46A34202D9B0 +:103800002946FFF79BFF224631460348BDE8F840B2 +:10381000FFF77EBF284A0020384A002010B4C0E9D4 +:10382000032300235DF8044B4361FFF7CFBF000083 +:1038300010B5194C236998420DD0D0E90032816847 +:1038400013605A609A680A449A60002303604FF03C +:10385000FF33A36110BD2346026843F8102F536065 +:103860000022026022699A4203D1BDE8104000F0B4 +:10387000E7BA936881680B44936000F0D5FA226937 +:10388000E1699268441AA242E4D91144BDE81040AB +:10389000091AFFF753BF00BF284A00202DE9F0475F +:1038A000DFF8BC8008F110072C4ED8F8105000F05B +:1038B000BBFAD8F81C40AA68031B9A423ED81444AD +:1038C000D5E900324FF00009C8F81C4013605A6077 +:1038D000C5F80090D8F81030B34201D100F0B0FA2A +:1038E00089F31188D5E9033128469847302383F3BB +:1038F00011886B69002BD8D000F096FA6A69A0EBAA +:1039000004094A4582460DD2022000F0E5FA002261 +:10391000D8F81030B34208D151462846BDE8F047E8 +:10392000FFF728BF121A2244F2E712EB090938BF49 +:103930004A4629463846FFF7EBFEB5E7D8F810307F +:10394000B34208D01444211AC8F81C00A960BDE88D +:10395000F047FFF7F3BEBDE8F08700BF384A00200C +:10396000284A002038B500F05FFA054AD2E9084538 +:10397000031B181945F10001C2E9080138BD00BF59 +:10398000284A002000207047FEE700007047000032 +:103990004FF0FF3070470000BFF34F8F024AD368EB +:1039A000DB03FCD4704700BF003C024008B5094B64 +:1039B0001B7873B9FFF7F0FF074B1A69002ABFBFE6 +:1039C000064A5A6002F188325A601A6822F480620C +:1039D0001A6008BD984C0020003C02402301674556 +:1039E00008B50B4B1B7893B9FFF7D6FF094B1A6943 +:1039F00042F000421A611A6842F480521A601A6852 +:103A000022F480521A601A6842F480621A6008BD7B +:103A1000984C0020003C02400728F0B516D80C4C0A +:103A20000C4923787BB90C4D0E4608234FF00062F9 +:103A300055F8047B46F8042B013B13F0FF033A448E +:103A4000F6D10123237051F82000F0BD0020FCE7DF +:103A5000BC4C00209C4C00208C4B0008014B53F8C0 +:103A6000200070478C4B000808207047072810B5CD +:103A7000044601D9002010BDFFF7CEFF064B53F8D6 +:103A800024301844C21A0BB90120F4E7126801323D +:103A9000F0D1043BF6E700BF8C4B0008072810B5B7 +:103AA000044621D8FFF778FFFFF780FF0F4AF32382 +:103AB000D360C300DBB243F4007343F0020313612D +:103AC000136943F480331361FFF766FFFFF7A4FF28 +:103AD000074B53F8241000F035F9FFF781FF20461B +:103AE000BDE81040FFF7C2BF002010BD003C0240FF +:103AF0008C4B0008F8B512F00103144642D185182A +:103B00002E4A954257D82E4B1B6813F0010352D012 +:103B10002C4DFFF74BFFF323EB60FFF73DFF40F227 +:103B20000127032C15D824F001046618254C401AEF +:103B300040F20117B142236900EB010524D123F0C3 +:103B400001032361FFF74CFF0120F8BD043C043062 +:103B5000E7E78307E7D12B6923F440732B612B69D7 +:103B60003B432B6151F8046B0660BFF34F8FFFF7A7 +:103B700013FF03689E42E9D02B6923F001032B61F8 +:103B8000FFF72EFF0020E0E723F440732361236951 +:103B90003B4323610B882B80BFF34F8FFFF7FCFE65 +:103BA0002D8831F8023BADB2AB42C3D0236923F07C +:103BB00001032361E4E71846C7E700BF00000808D7 +:103BC00000380240003C0240084908B50B7828B193 +:103BD0001BB9FFF7EBFE01230B7008BD002BFCD0D7 +:103BE000BDE808400870FFF7FBBE00BF984C0020FE +:103BF0000149024800F0A8B800FF030000010020BE +:103C00000846114600F0CCBE012000F0C9BE0000FD +:103C1000084600F0E3BE000038B5EFF311859DB90A +:103C2000EFF30584C4F30804302334B183F311881F +:103C3000FFF798FE85F3118838BD83F31188FFF7ED +:103C400091FE84F3118838BDBDE83840FFF78ABE85 +:103C500038B5FFF7E1FF114C114AC00840EA417046 +:103C6000A0FB025EC908A0FB040C1CEB050CA1FB29 +:103C700004404FF000035B41A1FB02121CEB040C5B +:103C800043EB000011EB0E0142F10002411842F13A +:103C90000000090941EA007038BD00BFCFF753E3C7 +:103CA000A59BC42010B50244064BD2B2904200D16D +:103CB00010BD441C00B253F8200041F8040BE0B2E0 +:103CC000F4E700BF502800400F4B30B51C6F2404B0 +:103CD00007D41C6F44F400741C671C6F44F4004448 +:103CE0001C670A4C236843F4807323600244084B2A +:103CF000D2B2904200D130BD441C00B251F8045BF6 +:103D000043F82050E0B2F4E7003802400070004071 +:103D10005028004007B5012201A90020FFF7C2FF8B +:103D2000019803B05DF804FB13B50446FFF7F2FFFA +:103D3000A04205D0012201A900200194FFF7C4FF91 +:103D400002B010BD704700007047000070470000CF +:103D5000074B45F255521A6002225A6040F6FF7234 +:103D60009A604CF6CC421A60024B01221A707047DE +:103D700000300040C44C0020034B1B781BB1034BA8 +:103D80004AF6AA221A607047C44C00200030004056 +:103D9000034B1A681AB9034AD2F874281A6070479C +:103DA000C04C002000300240024B4FF08072C3F83C +:103DB000742870470030024008B5FFF7E9FF024B56 +:103DC0001868C0F3407008BDC04C002008B5FFF76C +:103DD000DFFF024B1868C0F3007008BDC04C002024 +:103DE00070470000FEE700000A4B0B480B4A904268 +:103DF0000BD30B4BDA1C121AC11E22F003028B42AA +:103E000038BF00220021FDF769B953F8041B40F8C0 +:103E1000041BECE7404D00082852002028520020E7 +:103E20002852002000F0CAB84FF08043586A70470B +:103E30004FF08043002258631A610222DA60704713 +:103E40004FF080430022DA60704700004FF080435B +:103E500058637047FEE7000070B51B4B01630025F7 +:103E6000044686B0586085620E46FFF7D7FA04F123 +:103E70001003C4E904334FF0FF33C4E90635C4E945 +:103E80000044A560E562FFF7CFFF2B460246C4E978 +:103E9000082304F134010D4A256580232046FFF7ED +:103EA000D1FB0123E0600A4A037500927268019217 +:103EB000B268CDE90223074B6846CDE90435FFF728 +:103EC000E9FB06B070BD00BF904C0020AC4B000871 +:103ED000B14B0008553E0008024AD36A1843D0622D +:103EE000704700BF284A00204B6843608B6883609E +:103EF000CB68C3600B6943614B6903628B694362A2 +:103F00000B6803607047000008B5234B23481A690B +:103F100042F0FF021A611A6922F0FF021A611A695F +:103F20001A6B42F0FF021A631A6D42F0FF021A6523 +:103F30001B4A1B6D1146FFF7D7FF02F11C0100F56C +:103F40008060FFF7D1FF02F1380100F58060FFF7D4 +:103F5000CBFF02F1540100F58060FFF7C5FF02F1CD +:103F6000700100F58060FFF7BFFF02F18C0100F5E2 +:103F70008060FFF7B9FF02F1A80100F58060FFF74C +:103F8000B3FF02F1C40100F58060FFF7ADFFBDE8AB +:103F9000084000F08DB800BF003802400000024029 +:103FA000B84B000808B500F027FAFFF723FBBDE87F +:103FB0000840FFF7EDBE0000704700000F4B1A6C81 +:103FC00042F001021A641A6E42F001021A660C4AAB +:103FD0001B6E936843F0010393604FF080433122DE +:103FE0009A624FF0FF32DA6200229A615A63DA6015 +:103FF0005A6001225A611A60704700BF00380240BF +:10400000002004E04FF0804208B51169D3680B40EE +:10401000D9B2C9439B07116107D5302383F31188B7 +:10402000FFF70EFB002383F3118808BD1E4B1A69AE +:1040300062F0FF021A611A69D2B21A614FF0FF30C2 +:104040001A695A69586100215A6959615A691A6A8C +:1040500062F080521A621A6A02F080521A621A6A78 +:104060005A6A58625A6A59625A6A1A6C42F0805205 +:104070001A641A6E42F080521A661A6E0B4A106861 +:1040800040F480701060186F00F44070B0F5007F4D +:104090001EBF4FF4803018671967536823F400730C +:1040A000536000F07DB900BF00380240007000404E +:1040B0003B4B3C4A1A643C4A4FF4404111601A6839 +:1040C00042F001021A601A689007FCD59A6822F043 +:1040D00003029A60324B9A6812F00C02FBD1196805 +:1040E00001F0F90119609A601A6842F480321A608E +:1040F0001A689103FCD55A6F42F001025A67284BA7 +:104100005A6F9207FCD5294A5A601A6842F08072A9 +:104110001A60254A53685804FCD5214B1A6891014E +:10412000FCD5234AC3F884201A6842F080621A60E2 +:104130001A681201FCD51F4A9A600322C3F88C202A +:104140004FF00062C3F894201B4B1A681B4B9A4235 +:104150001B4B21D11B4A11681B4A91421CD140F2D2 +:1041600003121A60164A136803F00F03032BFAD1E7 +:104170000B4B9A6842F002029A609A6802F00C02B5 +:10418000082AFAD15A6C42F480425A645A6E42F4B8 +:1041900080425A665B6E704740F20372E1E700BFEF +:1041A000003802400004001000700040081940026E +:1041B0001030002400948838002004E011640020AE +:1041C000003C024000ED00E041C20F41074A08B543 +:1041D000536903F00103536123B1054A13680BB11E +:1041E00050689847BDE80840FFF73CB9003C0140E3 +:1041F000C84C0020074A08B5536903F00203536115 +:1042000023B1054A93680BB1D0689847BDE80840D0 +:10421000FFF728B9003C0140C84C0020074A08B508 +:10422000536903F00403536123B1054A13690BB1C9 +:1042300050699847BDE80840FFF714B9003C0140B9 +:10424000C84C0020074A08B5536903F008035361BE +:1042500023B1054A93690BB1D0699847BDE808407E +:10426000FFF700B9003C0140C84C0020074A08B5E0 +:10427000536903F01003536123B1054A136A0BB16C +:10428000506A9847BDE80840FFF7ECB8003C014091 +:10429000C84C0020164B10B55C6904F478725A6162 +:1042A000A30604D5134A936A0BB1D06A98476006F7 +:1042B00004D5104A136B0BB1506B9847210604D5F7 +:1042C0000C4A936B0BB1D06B9847E20504D5094AB1 +:1042D000136C0BB1506C9847A30504D5054A936C39 +:1042E0000BB1D06C9847BDE81040FFF7BBB800BFDA +:1042F000003C0140C84C0020194B10B55C6904F427 +:104300007C425A61620504D5164A136D0BB1506D9B +:104310009847230504D5134A936D0BB1D06D984788 +:10432000E00404D50F4A136E0BB1506E9847A104F8 +:1043300004D50C4A936E0BB1D06E9847620404D535 +:10434000084A136F0BB1506F9847230404D5054AF0 +:10435000936F0BB1D06F9847BDE81040FFF782B85C +:10436000003C0140C84C002008B5034800F010F99B +:10437000BDE80840FFF776B8484D002008B503486F +:1043800000F006F9BDE80840FFF76CB8B44F002014 +:1043900008B5FFF737FEBDE80840FFF763B8000037 +:1043A000062108B50846FFF787F806210720FFF722 +:1043B00083F806210820FFF77FF806210920FFF780 +:1043C0007BF806210A20FFF777F806211720FFF770 +:1043D00073F806212820FFF76FF807211C20FFF74C +:1043E0006BF80C212520FFF767F8BDE808400C2189 +:1043F0002620FFF761B8000008B5FFF717FE00F0B0 +:104400007BF800F03DF8FFF7D7FDBDE80840FFF767 +:1044100009BD0000026843681143016003B11847F9 +:1044200070470000143000F0DFB900004FF0FF3398 +:10443000143000F0D9B90000383000F055BA00004F +:104440004FF0FF33383000F04FBA0000143000F066 +:10445000A5B900004FF0FF31143000F09FB9000003 +:10446000383000F0FFB900004FF0FF32383000F074 +:10447000F9B90000012914BF6FF013000020704744 +:1044800000F060B837B515460E4A0260002242605F +:10449000C0E902220122044602740B46009000F19A +:1044A0005C014FF48072143000F04EF900942B46FA +:1044B0004FF4807204F5AE7104F1380000F0C6F9D3 +:1044C00003B030BD984C000838B5C36904460D46AA +:1044D0001BB904210844FFF79DFF294604F114008D +:1044E00000F040F9002806DA201D4FF40061BDE815 +:1044F0003840FFF78FBF38BD0023054A1946013306 +:10450000102BC2E9001102F10802F8D1704700BF78 +:10451000C84C0020026843681143016003B118478A +:1045200070470000024AD36843F0C003D36070476D +:1045300000100140024AD36843F0C003D3607047C3 +:104540000044004010B50A4C0A4A20460021FFF7FB +:1045500099FF094B094AC4E99723094C094A0021EC +:104560002046FFF78FFF0849084BC4E9971310BD99 +:10457000484D00202545000880F0FA020010014057 +:10458000B44F0020354500080044004040787D01CC +:104590002DE9F041D0F85C62F7683368DA0504462B +:1045A0009DB20DD5302383F311884FF48061043020 +:1045B000FFF7B0FF6FF480733360002383F311883B +:1045C000302383F3118804F1040815F02F033AD146 +:1045D00083F31188380615D5290613D5302383F3C4 +:1045E000118804F1380000F065F900284EDA08213E +:1045F000201DFFF78FFF4FF67F733B40F3600023D2 +:1046000083F311887A0616D56B0614D5302383F30D +:104610001188D4E913239A420AD1236C43B127F0BD +:1046200040073F041021201D3F0CFFF773FFF76088 +:10463000002383F31188D4F86822D36843B3BDE81C +:10464000F041106918472B0714D015F0080F0CBF64 +:1046500000214FF48071E80748BF41F02001AA070C +:1046600048BF41F040016B0748BF41F08001404620 +:10467000FFF750FFAD06736805D594F86412204625 +:104680001940FFF721FF3568ADB29EE77060B6E7CD +:10469000BDE8F081F8B5154682680669AA420B4666 +:1046A000816938BF8568761AB54204460BD2184630 +:1046B0002A46FCF701FDA3692B44A361A3685B1B99 +:1046C000A3602846F8BD0CD918463246FCF7F4FC26 +:1046D000AF1BE1683A463044FCF7EEFCE3683B442C +:1046E000EBE718462A46FCF7E7FCE368E5E700003D +:1046F00083689342F7B51546044638BF8568D0E90C +:104700000460361AB5420BD22A46FCF7D5FC636921 +:104710002B446361A36828465B1BA36003B0F0BD14 +:104720000DD932460191FCF7C7FC0199E068AF1B37 +:104730003A463144FCF7C0FCE3683B44E9E72A46CB +:10474000FCF7BAFCE368E4E710B50A440024C3614F +:10475000029B8460C0E90000C0E90511C1600261EC +:10476000036210BD08B5D0E90532934201D18268D9 +:1047700082B98268013282605A1C42611970D0E9A4 +:1047800004329A4224BFC36843610021FEF7B4FF9C +:10479000002008BD4FF0FF30FBE7000070B530236C +:1047A00004460E4683F31188A568A5B1A368A269E3 +:1047B000013BA360531CA36115782269934224BF77 +:1047C000E368A361E3690BB120469847002383F3B4 +:1047D0001188284607E031462046FEF77DFF002875 +:1047E000E2DA85F3118870BD2DE9F74F04460E46D5 +:1047F00017469846D0F81C904FF0300A8AF311887B +:104800004FF0000B154665B12A4631462046FFF7AA +:1048100041FF034660B941462046FEF75DFF002890 +:10482000F1D0002383F31188781B03B0BDE8F08F2B +:10483000B9F1000F03D001902046C847019B8BF3CC +:104840001188ED1A1E448AF31188DCE7C0E90511CE +:10485000C160C3611144009B8260C0E90000016136 +:1048600003627047F8B504460D461646302383F3BD +:104870001188A768A7B1A368013BA36063695A1CAC +:1048800062611D70D4E904329A4224BFE368636117 +:10489000E3690BB120469847002080F3118807E0B8 +:1048A00031462046FEF718FF0028E2DA87F3118828 +:1048B000F8BD0000D0E905239A4210B501D1826805 +:1048C0007AB98268013282605A1C82611C7803695D +:1048D0009A4224BFC36883610021FEF70DFF204682 +:1048E00010BD4FF0FF30FBE72DE9F74F04460E46B1 +:1048F00017469846D0F81C904FF0300A8AF311887A +:104900004FF0000B154665B12A4631462046FFF7A9 +:10491000EFFE034660B941462046FEF7DDFE002863 +:10492000F1D0002383F31188781B03B0BDE8F08F2A +:10493000B9F1000F03D001902046C847019B8BF3CB +:104940001188ED1A1E448AF31188DCE70B460146F4 +:10495000184600F02DB8000000F040B8012838BF1C +:10496000012010B50446204600F030F830B900F0C0 +:1049700007F808B900F00CF88047F4E710BD000014 +:10498000024B1868BFF35B8F704700BF20520020B6 +:1049900008B5062000F084F80120FEF7F5FF0000BE +:1049A000024B0A4601461868FFF72AB91C2300206B +:1049B00010B5054C13462CB10A4601460220AFF350 +:1049C000008010BD2046FCE700000000024B0146BD +:1049D0001868FFF719B900BF1C230020024B0146DD +:1049E0001868FFF715B900BF1C23002010B5013966 +:1049F0000244904201D1002005E0037811F8014FF4 +:104A0000A34201D0181B10BD0130F2E72DE9F0419F +:104A1000A3B1C91A17780144044603F1FF3C8C4244 +:104A2000204601D9002009E00578BD4204F10104C7 +:104A3000F5D10CEB0405D618A54201D1BDE8F081F3 +:104A400015F8018D16F801EDF045F5D0E7E7000007 +:104A50001F2938B504460D4604D9162303604FF0CC +:104A6000FF3038BD426C12B152F821304BB92046AC +:104A700000F030F82A4601462046BDE8384000F0F4 +:104A800017B8012B0AD0591C03D11623036001204B +:104A9000E7E7002442F82540284698470020E0E751 +:104AA000024B01461868FFF7D3BF00BF1C2300204C +:104AB00038B5074D00230446084611462B60FEF723 +:104AC00067FF431C02D12B6803B1236038BD00BFD0 +:104AD00024520020FEF756BF034611F8012B03F8BD +:104AE000012B002AF9D170476F72672E61726475CD +:104AF00070696C6F742E435541565F4750530000E8 +:104B000040A2E4F1646891060041A3E5F265699270 +:104B1000070000004261642043414E4966616365BD +:104B200020696E6465782E0080000000008000001F +:104B300000008000000000000000000031190008A3 +:104B400051210008AD200008711900087D190008E6 +:104B50007D1B00084119000851190008451900087B +:104B60004D19000849190008A11A00085519000834 +:104B70002124000865190008751A00086330000038 +:104B80007C4B0008804A0020904C00200040000030 +:104B90000040000000400000004000000000010054 +:104BA0000000020000000200000002006D61696E5A +:104BB0000069646C65000000A0011028000000007E +:104BC000AAAAAAAA50011024FFFF00000077000043 +:104BD0000000000000A40A0100000000AAA6AAAA82 +:104BE00080500000DFEF0000000000778800000028 +:104BF0000000000000000000AAAAAAAA000000000D +:104C0000FFFF0000000000000000000000000000A6 +:104C100000000000AAAAAAAA00000000FFFF0000EE +:104C20000000000000000000000000000000000084 +:104C3000AAAAAAAA00000000FFFF000000000000CE +:104C4000000000000000000000000000AAAAAAAABC +:104C500000000000FFFF0000000000000000000056 +:104C60000000000000000000AAAAAAAA000000009C +:104C7000FFFF000000000000000000000000000036 +:104C8000000000000A000000000000000300000017 +:104C90000000000000000000000000004144000887 +:104CA0002D44000869440008554400086144000888 +:104CB0004D440008394400082544000875440008A4 +:104CC000E9030000000000000000070000000000F1 +:104CD00040420F00FE2A0100D204000020230020E1 +:104CE00000000000000000000000000000000000C4 +:104CF00000000000000000000000000000000000B4 +:104D000000000000000000000000000000000000A3 +:104D10000000000000000000000000000000000093 +:104D20000000000000000000000000000000000083 +:104D30000000000000000000000000000000000073 :00000001FF diff --git a/Tools/bootloaders/CarbonixF405_bl.bin b/Tools/bootloaders/CarbonixF405_bl.bin index bbf4a40fcc0d73..bcbd76629c30b0 100755 Binary files a/Tools/bootloaders/CarbonixF405_bl.bin and b/Tools/bootloaders/CarbonixF405_bl.bin differ diff --git a/Tools/bootloaders/CarbonixL496_bl.bin b/Tools/bootloaders/CarbonixL496_bl.bin index 47736493150d3c..73aab00f2af6d8 100755 Binary files a/Tools/bootloaders/CarbonixL496_bl.bin and b/Tools/bootloaders/CarbonixL496_bl.bin differ diff --git a/Tools/bootloaders/CubeOrange-periph-heavy_bl.bin b/Tools/bootloaders/CubeOrange-periph-heavy_bl.bin index c912c780818ced..cd09e9be90ed95 100755 Binary files a/Tools/bootloaders/CubeOrange-periph-heavy_bl.bin and b/Tools/bootloaders/CubeOrange-periph-heavy_bl.bin differ diff --git a/Tools/bootloaders/CubeOrange-periph-heavy_bl.hex b/Tools/bootloaders/CubeOrange-periph-heavy_bl.hex index 6b527aec21bde3..d7433019f9d1c4 100644 --- a/Tools/bootloaders/CubeOrange-periph-heavy_bl.hex +++ b/Tools/bootloaders/CubeOrange-periph-heavy_bl.hex @@ -1,2014 +1,2073 @@ :020000040800F2 -:1000000000060020F50500086135000819350008D4 -:10001000413500081935000839350008F705000892 -:10002000F7050008F7050008F70500084545000832 -:10003000F7050008F7050008F7050008F7050008B0 -:10004000F7050008F7050008F7050008F7050008A0 -:10005000F7050008F70500086975000895750008A0 -:10006000C1750008ED75000819760008F70500084D -:10007000F7050008F7050008F7050008F705000870 -:10008000F7050008F7050008F7050008C93400085F -:10009000F1340008DD340008053500084576000815 -:1000A000F7050008F7050008F7050008F705000840 -:1000B000F7050008F7050008F7050008F705000830 -:1000C000F7050008F7050008F7050008F705000820 -:1000D000F7050008F7050008F7050008F705000810 -:1000E000A9760008F7050008F7050008F7050008DD -:1000F000F7050008F7050008F7050008F7050008F0 -:10010000F7050008F705000831770008F705000833 -:10011000F7050008F7050008F7050008F7050008CF -:10012000F7050008F7050008F7050008F7050008BF -:10013000F7050008F7050008F7050008F7050008AF -:10014000F7050008F7050008F7050008F70500089F -:10015000F7050008F7050008F7050008F70500088F -:10016000F7050008F7050008F7050008F70500087F -:10017000F7050008F16B0008F7050008F70500080F -:10018000F7050008F70500081D770008F7050008C7 -:10019000F7050008F7050008F7050008F70500084F -:1001A000F7050008F7050008F7050008F70500083F -:1001B000F7050008F7050008F7050008F70500082F -:1001C000F7050008F7050008F7050008F70500081F -:1001D000F7050008DD6B0008F7050008F7050008C3 -:1001E000F7050008F7050008F7050008F7050008FF -:1001F000F7050008F7050008F7050008F7050008EF -:10020000F7050008F7050008F7050008F7050008DE -:10021000F7050008F7050008F7050008F7050008CE -:10022000F7050008F7050008F7050008F7050008BE -:10023000F7050008F7050008F7050008F7050008AE -:10024000F7050008F7050008F7050008F70500089E -:10025000F7050008F7050008F7050008F70500088E -:10026000F7050008F7050008F7050008F70500087E -:10027000F7050008F7050008F7050008F70500086E -:10028000F7050008F7050008F7050008F70500085E -:10029000F7050008F7050008F7050008F70500084E -:1002A000F7050008F7050008F7050008F70500083E -:1002B000F7050008F7050008F7050008F70500082E -:1002C000F7050008F7050008F7050008F70500081E -:1002D000F7050008F7050008F7050008F70500080E -:1002E000111A0008000000000000000000000000DB -:1002F00053B94AB9002908BF00281CBF4FF0FF318D -:100300004FF0FF3000F074B9ADF1080C6DE904CE88 -:1003100000F006F8DDF804E0DDE9022304B07047E0 -:100320002DE9F047089D04468E46002B4DD18A42A8 -:10033000944669D9B2FA82F252B101FA02F3C2F1DB -:10034000200120FA01F10CFA02FC41EA030E94406C -:100350004FEA1C48210CBEFBF8F61FFA8CF708FB8D -:1003600016E341EA034306FB07F199420AD91CEB65 -:10037000030306F1FF3080F01F81994240F21C8197 -:10038000023E63445B1AA4B2B3FBF8F008FB1033DF -:1003900044EA034400FB07F7A7420AD91CEB040414 -:1003A00000F1FF3380F00A81A74240F207816444E4 -:1003B000023840EA0640E41B00261DB1D440002369 -:1003C000C5E900433146BDE8F0878B4209D9002DCD -:1003D00000F0EF800026C5E9000130463146BDE857 -:1003E000F087B3FA83F6002E4AD18B4202D38242C1 -:1003F00000F2F980841A61EB030301209E46002D70 -:10040000E0D0C5E9004EDDE702B9FFDEB2FA82F2C4 -:10041000002A40F09280A1EB0C014FEA1C471FFA22 -:100420008CFE0126200CB1FBF7F307FB131140EA09 -:1004300001410EFB03F0884208D91CEB010103F1D6 -:10044000FF3802D2884200F2CB804346091AA4B298 -:10045000B1FBF7F007FB101144EA01440EFB00FE6C -:10046000A64508D91CEB040400F1FF3102D2A645D1 -:1004700000F2BB800846A4EB0E0440EA03409CE770 -:10048000C6F12007B34022FA07FC4CEA030C20FA1D -:1004900007F401FA06F31C43F9404FEA1C4900FA3D -:1004A00006F3B1FBF9F8200C1FFA8CFE09FB1811BA -:1004B00040EA014108FB0EF0884202FA06F20BD92D -:1004C0001CEB010108F1FF3A80F08880884240F27D -:1004D0008580A8F102086144091AA4B2B1FBF9F0C1 -:1004E00009FB101144EA014100FB0EFE8E4508D9BC -:1004F0001CEB010100F1FF346CD28E456AD9023841 -:10050000614440EA0840A0FB0294A1EB0E01A14225 -:10051000C846A64656D353D05DB1B3EB080261EB93 -:100520000E0101FA07F722FA06F3F1401F43C5E96D -:10053000007100263146BDE8F087C2F12003D840A3 -:100540000CFA02FC21FA03F3914001434FEA1C47E5 -:100550001FFA8CFEB3FBF7F007FB10360B0C43EAD7 -:10056000064300FB0EF69E4204FA02F408D91CEB87 -:10057000030300F1FF382FD29E422DD90238634485 -:100580009B1B89B2B3FBF7F607FB163341EA034125 -:1005900006FB0EF38B4208D91CEB010106F1FF3874 -:1005A00016D28B4214D9023E6144C91A46EA00466B -:1005B00038E72E46284605E70646E3E61846F8E6FD -:1005C0004B45A9D2B9EB020864EB0C0E0138A3E746 -:1005D0004646EAE7204694E74046D1E7D0467BE727 -:1005E000023B614432E7304609E76444023842E79F -:1005F000704700BF02E000F000F8FEE772B637482F -:1006000080F30888364880F3098836483649086000 -:1006100040F20000CCF200004EF63471CEF2000140 -:100620000860BFF34F8FBFF36F8F40F20000C0F23E -:10063000F0004EF68851CEF200010860BFF34F8FF4 -:10064000BFF36F8F4FF00000E1EE100A4EF63C71E1 -:10065000CEF200010860062080F31488BFF36F8F8C -:1006600005F032FD06F040FD4FF055301F491B4AA2 -:1006700091423CBF41F8040BFAE71D49184A9142E8 -:100680003CBF41F8040BFAE71A491B4A1B4B9A423C -:100690003EBF51F8040B42F8040BF8E7002018495C -:1006A000184A91423CBF41F8040BFAE705F04AFDB5 -:1006B00006F09EFD144C154DAC4203DA54F8041BB1 -:1006C0008847F9E700F042F8114C124DAC4203DACA -:1006D00054F8041B8847F9E705F032BD00060020F6 -:1006E000002200200000000808ED00E000000020CB -:1006F00000060020E87C000800220020D022002014 -:10070000D022002030870020E0020008E402000828 -:10071000E4020008E40200082DE9F04F2DED108AF4 -:10072000C1F80CD0D0F80CD0BDEC108ABDE8F08F29 -:10073000002383F311882846A047002004F0AAFF75 -:10074000FEE704F003FF00DFFEE70000F8B501F06C -:1007500075F905F03DFC074605F0ACFC0546B8BB55 -:10076000204B9F4234D001339F4234D027F0FF0208 -:100770001D4B9A4232D12E4642F21074F8B200F06C -:1007800093FF00F097FF08B10024264601F04CFDCE -:1007900020B10024032000F07BF8264635B1134B2E -:1007A0009F4203D0002405F07DFC2646002005F082 -:1007B00019FC0EB100F082F801F0E2FA00F0AEFF91 -:1007C00001F0B8F9204600F029F900F077F8F9E7D0 -:1007D0002E460024D5E704460126D2E7064641F21C -:1007E0008834CEE7010007B0000008B0263A09B00F -:1007F00008B501F06BF9A0F120035842584108BD3B -:1008000007B541F21203022101A8ADF8043001F04E -:100810007BF903B05DF804FB38B5302383F311880E -:10082000174803680BB105F001F80023154A4FF48F -:100830007A71134804F0F0FF002383F31188124CFF -:10084000236813B12368013B2360636813B16368B5 -:10085000013B63600D4D2B7833B963687BB902208F -:1008600001F010FA322363602B78032B07D1636801 -:100870002BB9022001F006FA4FF47A73636038BD99 -:10088000D022002019080008F0230020E8220020D0 -:10089000084B187003280CD8DFE800F008050208A0 -:1008A000022001F0EDB9022001F0E8B9024B00226C -:1008B0005A607047E8220020F0230020F8B501F0CC -:1008C000B3FC30B14D4B03221A7000224C4B5A60DE -:1008D000F8BD4C4B4C4A1C4619680131F8D0043322 -:1008E0009342F9D16268494B9A42F1D9484B9B68CF -:1008F00003F1006303F500339A42E9D205F0A6FB49 -:1009000005F0B8FB002001F02FF90220FFF7C0FF2F -:10091000404B0021D3F8E820C3F8E810D3F81021A9 -:10092000C3F81011D3F81021D3F8EC20C3F8EC1061 -:10093000D3F81421C3F81411D3F81421D3F8F020FC -:10094000C3F8F010D3F81821C3F81811D3F8182100 -:10095000D3F8802042F00072C3F88020D3F88020C2 -:1009600022F00072C3F88020D3F8803072B64FF0C6 -:10097000E023C3F8084DD4E90004BFF34F8FBFF361 -:100980006F8F254AC2F88410BFF34F8F536923F449 -:1009900080335361BFF34F8FD2F8803043F6E07657 -:1009A000C3F3C905C3F34E335B0103EA060C2946C2 -:1009B0004CEA81770139C2F87472F9D2203B13F105 -:1009C000200FF2D1BFF34F8FBFF36F8FBFF34F8F65 -:1009D000BFF36F8F536923F4003353610023C2F8D0 -:1009E0005032BFF34F8FBFF36F8F302383F31188E3 -:1009F000854680F3088820476AE700BFE822002088 -:100A0000F02300200000020820000208FFFF010878 -:100A1000002200200044025800ED00E02DE9F04FD4 -:100A200093B0B74B2022FF2100900AA89D6801F0E7 -:100A300051F9B44A1378A3B90121B3481170036086 -:100A4000302383F3118803680BB104F0EFFE002319 -:100A5000AE4A4FF47A71AC4804F0DEFE002383F313 -:100A60001188009B13B1AA4B009A1A60A94A137807 -:100A7000032B03D000231370A54A53604FF0000AE4 -:100A8000009CD3465646D146012001F0F9F824B126 -:100A90009F4B1B68002B00F02C82002001F016F801 -:100AA0000390039B002B01DA00F08CFE039B002BCC -:100AB000EDDB012001F0E2F8039B213B1F2BE3D883 -:100AC00001A252F823F000BF490B0008710B000887 -:100AD000050C0008890A0008890A0008890A00082C -:100AE000970C0008670E0008810D0008E30D000850 -:100AF0000B0E0008310E0008890A0008430E00089A -:100B0000890A0008B50E0008E90B0008890A0008E8 -:100B1000F90E0008550B0008E90B0008890A0008C7 -:100B2000E30D0008890A0008890A0008890A0008FC -:100B3000890A0008890A0008890A0008890A000849 -:100B4000890A0008050C00080220FFF751FE002862 -:100B500040F0F981009B022105A8BAF1000F08BFFF -:100B60001C4641F21233ADF8143000F0CDFF8BE794 -:100B70004FF47A7000F0AAFF071EEBDB0220FFF7AC -:100B800037FE0028E6D0013F052F00F2DE81DFE8C6 -:100B900007F0030A0D1013360523042105A8059359 -:100BA00000F0B2FF17E004215548F9E704215A4844 -:100BB000F6E704215948F3E74FF01C08404608F1D6 -:100BC000040800F0D3FF0421059005A800F09CFF65 -:100BD000B8F12C0FF2D101204FF0000900FA07F70D -:100BE00047EA0B0B5FFA8BFB01F0C0F826B10BF064 -:100BF0000B030B2B08BF0024FFF702FE44E7042180 -:100C00004748CDE7002EA5D00BF00B030B2BA1D14D -:100C10000220FFF7EDFD074600289BD001200026AB -:100C200000F0A2FF0220FFF733FE1FFA86F84046CD -:100C300000F0AAFF0446B0B1039940460136A1F185 -:100C400040025142514100F0B7FF0028EDD1BA46B1 -:100C5000044641F21213022105A83E46ADF81430B5 -:100C600000F052FF10E725460120FFF711FE244B4C -:100C70009B68AB4207D9284600F078FF013040F06E -:100C800067810435F3E70025224BBA463E461D70C6 -:100C90001F4B5D60A8E7002E3FF45CAF0BF00B0329 -:100CA0000B2B7FF457AF0220FFF7F2FD322000F04C -:100CB0000DFFB0F10008FFF64DAF18F003077FF409 -:100CC00049AF0F4A08EB0503926893423FF642AFE3 -:100CD000B8F5807F3FF73EAF124BB845019323DD57 -:100CE0004FF47A7000F0F2FE0390039A002AFFF6A8 -:100CF00031AF039A0137019B03F8012BEDE700BFE9 -:100D000000220020EC230020D02200201908000837 -:100D1000F0230020E82200200422002008220020E6 -:100D20000C220020EC220020C820FFF761FD0746BE -:100D300000283FF40FAF1F2D11D8C5F120020AABD8 -:100D400025F0030084494245184428BF42460192D9 -:100D500000F09AFF019AFF217F4800F0BBFF4FEAA5 -:100D6000A803C8F387027C492846019300F0BAFF24 -:100D7000064600283FF46DAF019B05EB830533E782 -:100D80000220FFF735FD00283FF4E4AE00F026FF17 -:100D900000283FF4DFAE0027B846704B9B68BB428B -:100DA00018D91F2F11D80A9B01330ED027F0030347 -:100DB00012AA134453F8203C05934046042205A987 -:100DC000043701F01BFA8046E7E7384600F0CEFE14 -:100DD0000590F2E7CDF81480042105A800F094FEF8 -:100DE00002E70023642104A8049300F083FE002896 -:100DF0007FF4B0AE0220FFF7FBFC00283FF4AAAE60 -:100E0000049800F0E1FE0590E6E70023642104A8C1 -:100E1000049300F06FFE00287FF49CAE0220FFF7E1 -:100E2000E7FC00283FF496AE049800F0CFFEEAE716 -:100E30000220FFF7DDFC00283FF48CAE00F0DEFE60 -:100E4000E1E70220FFF7D4FC00283FF483AE05A9B8 -:100E5000142000F0D9FE07460421049004A800F0F5 -:100E600053FE3946B9E7322000F030FE071EFFF688 -:100E700071AEBB077FF46EAE384A07EB0903926888 -:100E800093423FF667AE0220FFF7B2FC00283FF422 -:100E900061AE27F003074F44B9453FF4A5AE48467D -:100EA00009F1040900F062FE0421059005A800F094 -:100EB0002BFEF1E74FF47A70FFF79AFC00283FF41D -:100EC00049AE00F08BFE002844D00A9B01330BD0C2 -:100ED00008220AA9002000F005FF00283AD02022AD -:100EE000FF210AA800F0F6FEFFF78AFC1C4804F078 -:100EF000D7FB13B0BDE8F08F002E3FF42BAE0BF004 -:100F00000B030B2B7FF426AE0023642105A8059369 -:100F100000F0F0FD074600287FF41CAE0220FFF72A -:100F200067FC804600283FF415AEFFF769FC41F2EC -:100F3000883004F0B5FB059800F062FF46463C4659 -:100F400000F014FFA0E506464EE64FF0000901E66A -:100F5000BA467EE637467CE6EC22002000220020DE -:100F6000A0860100094A49F26900136899B21B0C76 -:100F700000FB013344F250611360054B186882B2E4 -:100F8000000C01FB0200186080B2704714220020A0 -:100F9000102200200021102210B5044600F09AFE15 -:100FA000034B03CB206061601868A06010BD00BFD8 -:100FB00000E8F11F2DE9F041ADF5527D0D4600210D -:100FC00040F2751270AC074612A8119100F082FE33 -:100FD0004FF4C4720021204600F07CFE0DF144085D -:100FE00002F0C6FA4FF47A72264BB0FBF2F01860AA -:100FF00093E80700022384E807000DF5F1702382CF -:10100000FFF7C8FF47F605031F4907A8238406F02A -:1010100033FC25230DF2F3220DF13C0C84F8323120 -:1010200007AB1E46083203CE664542F8080C42F86C -:10103000041C3346F5D130684146106020463379B0 -:101040001371012200F0FEFE002380B2E97E0393BB -:10105000AB7E029305F1190301930123009307A3CB -:10106000D3E90023CDE90480384602F03FFE0DF5B8 -:10107000527DBDE8F08100BFAFF300809E6AC421BD -:10108000818A46EEF8230020887800082DE9F04197 -:101090002C4CDAB080460D46237A5BBB27A9284644 -:1010A00000F0DEFF0746002842D19DF89D60C82E63 -:1010B0003ED801464FF4A662204600F00BFE4FF4E6 -:1010C000807332460DF19E01C4F8F8314FF400737D -:1010D00004F109002644C4F80C334FF44073C4F8FB -:1010E000203400F0D1FD9DF89C30777223720BB94B -:1010F000EB7E237206AC8122002127A800F0EAFDD6 -:101100000122214627A800F0E7FF002380B2E97EF4 -:101110000393AB7E029305F1190301932823CDE9D4 -:1011200004400093404605A3D3E9002302F0DEFD0E -:101130005AB0BDE8F08100BFAFF300802641727263 -:10114000DF25D7B7A05D0020F0B5254E4FF48A7596 -:10115000F1B0002405FB006596F8D830D82221466E -:1011600085F8DC303AA885F8E84006AF00F0B2FD1B -:1011700006F1090000F0A6FDD5F8E430C2B206F190 -:1011800009018DF8F0000DF1F100CDE93A3400F0DD -:101190007BFD394601223AA800F0CAFF082380B23D -:1011A000317ACDE9047001270E48CDE9023706F106 -:1011B000D80301933023009307A3D3E9002302F05F -:1011C00095FDA04206DD02F0D3F9C5F8E0003846EF -:1011D00071B0F0BD2046FBE778F6339F93CACD8D02 -:1011E000A05D0020103400202DE9F04F274F87B07C -:1011F000DFF8A480264E384602F0A4FD03460028FE -:101200003CD00024234DADF81440A1460294A246E0 -:10121000CDE90344027B8DF8142003AA9968406845 -:1012200003C21B6843F0004302932B6804F22C5462 -:10123000D3F810B002F09EF910EB0802CDF800A030 -:10124000284605F5A55541F1000302A9D84740F607 -:1012500058230028C8BF49F0010910359C42E4D149 -:10126000B9F1000F05D0384602F070FD86F800A0F5 -:10127000C1E73378072B04D80133337007B0BDE8DA -:10128000F08F024802F062FDF8E700BF1034002042 -:10129000D56200204034002040420F0070B50D465A -:1012A00014461E4602F07EFC50B9022E10D1012CCD -:1012B0000ED112A3D3E900230120C5E9002307E0E2 -:1012C000282C10D005D8012C09D0052C0FD00020D7 -:1012D00070BD302CFBD10BA3D3E90023ECE70BA3AB -:1012E000D3E90023E8E70BA3D3E90023E4E70BA34A -:1012F000D3E90023E0E700BFAFF30080401DA12049 -:1013000026812A0B78F6339F93CACD8D9E6AC4211D -:10131000818A46EE26417272DF25D7B7F017304A30 -:1013200039059E5638B505460E4C0021013500F0B2 -:1013300043FCA4F82C55B4F82C0500F025FC78B13A -:10134000B4F82C0500F030FC014648B9B4F82C057F -:1013500000F032FCB4F82C350133A4F82C35EAE760 -:1013600038BD00BFA05D0020F8B50E4C02260E4F20 -:10137000A4F5805343F8307C237E3BB965692DB1D9 -:10138000284600F0CBFF284606F02CFA2046A4F5AC -:10139000A55400F0C3FF012EA4F1100400D1F8BD44 -:1013A0000126E5E720590020507900082DE9F04F8B -:1013B0008FB005460C4600AF02F0F4FB002849D17F -:1013C000237E022B1BD1E38A012B18D102F0D0F827 -:1013D0000646FFF7C7FD03464FF4C87006F51676BC -:1013E000DFF8C082B3FBF0F202FB103316FA83F38E -:1013F000C8F80030E37E33B9A34B00221A703C37A3 -:10140000BD46BDE8F08F07F12401204600F0E6FD5F -:101410000028F4D107F11400FFF7BCFD97F826402F -:1014200007F1140107F12700224606F0F3F900281E -:10143000E2D10F2C08D8944B1C70D8F80030A3F5DB -:101440001673C8F80030DAE797F82410284602F03F -:10145000A1FBD4E7E38A282B2BD010D8012B23D073 -:10146000052BCCD1BFF34F8F8849894BCA6802F452 -:10147000E0621343CB60BFF34F8F00BFFDE7302B1B -:10148000BDD1844EE17E327A9142B8D1607E314640 -:10149000002291F8DC50854200F0A580013201F570 -:1014A0008A71042AF5D1AAE721462846FFF782FD72 -:1014B000A5E721462846FFF7E9FDA0E7B2F8EC5082 -:1014C0007B6005F103094FEA99094FEA8902D11DB2 -:1014D000C908A8EBC10300219D46EB46584600F021 -:1014E000F9FB04F1EE012A465846314400F0CCFBEA -:1014F0007B6813B9012000F037FB96F8D20000F0AA -:1015000043FB044630B9307200F068FB204600F01F -:101510002BFBB1E0D6F8D4203AB996F8D200B6F851 -:101520002C25824201D8FFF7FDFED6F8D4202A44AC -:10153000944208D296F8D200B6F82C2501308242A7 -:1015400001D8FFF7EFFE5FFA89F25946706800F0A4 -:10155000C9FB08B9C54679E0726896F8D2002A44FA -:101560007260D6F8D42005EB0209C6F8D49000F0DA -:101570000BFB814509D396F8D220D6F8D40001326E -:10158000001B86F8D220C6F8D400FF2D0FD8002407 -:10159000347200F023FB204600F0E6FA00F044FE2F -:1015A0003D4B188108B9FFF789F9C54627E7BB68A5 -:1015B00096F8D9000AFB0362FB68D2F8E41082F8BF -:1015C000E83001F58061C2F8E030C2F8E410FFF7BE -:1015D000BBFDFFF709FE96F8D920013202F00302A5 -:1015E00086F8D920B6E74FF48A7A20460AFB02F53E -:1015F00005F1EA01314400F0C7FDF86000287FF4EE -:10160000FEAE0122354485F8E82001F0B1FFD5F89F -:10161000E020D6ED007A801A40F6B832B8EE677A4C -:10162000DFED1E6A192838BF1920904228BF1046E6 -:1016300007EE900AF8EEE77A67EEA67ADFED186A11 -:10164000E7EE267AFCEEE77AC6ED007A96F8D93016 -:10165000BB60BA6873680AFB02F4321992F8E810AA -:1016600059B1D2F8E410E8468B423FF427AF00218D -:1016700082F8E810C2F8E010C5467368064A9B0A73 -:1016800001331381BBE600BF0934002000ED00E008 -:101690000400FA05A05D0020F8230020CDCCCC3D4D -:1016A0006666663F0C340020014B1870704700BF1F -:1016B0000424002038B54FF04054144B22689A425D -:1016C00021D1627D0025124B12481A70C922237D58 -:1016D0000930114900F8013C4FF48073C0F8DB5029 -:1016E000C0F8EF314FF40073C0F803334FF4407388 -:1016F000C0F8173400F0C8FAE0222946204600F06E -:10170000E9FA012038BD0020FCE700BF9AAD44C5CE -:1017100004240020A05D00201600003037B500F042 -:1017200083FD1F4C1F4D022301221F496B7123684B -:101730002881204604F580545B6898470122D4F83C -:10174000B03404F5966018495B6898470023174940 -:101750004FF480520193164B16480093164B02F03B -:10176000F1F9164B197811B1124802F013FA01F091 -:10177000FFFE0446FFF7F6FB4FF4C873B0FBF3F22D -:1017800002FB130304F5167010FA83F00C4B18607B -:1017900004F090FC08B10F232B8103B030BD00BFD3 -:1017A00040340020F823002040420F00082400208D -:1017B0009D12000810340020AD13000804240020FE -:1017C0000C3400202DE9F04F00252DED028B93B055 -:1017D0000DF12C084FF0010ADFF814B2FFF704FDF9 -:1017E0000A95ADF834500B95C8F804509FED798BED -:1017F00000267E4C374623680DF11D0207A92046BE -:101800008DF81CA08DF81D508DED008BD3F808903D -:101810000023C8479DF81C90B9F1000F1ED010227C -:1018200000210EA800F056FA236808AA0AA95F69E9 -:1018300020460DF11E03B8470FAB4F4698E8030052 -:1018400083E803009DF834300EA958468DF84430E3 -:101850000A9B0E93DDE9082302F056FC06F22C5693 -:1018600040F6582304F5A5549E4204F11004C2D159 -:10187000002FBDD15E4802F095F900283FD15D4EA2 -:1018800001F076FE3368984239D301F071FE0446C8 -:10189000FFF768FB4FF4C8738DF82870B0FBF3F2C4 -:1018A00002FB130304F5167010FA83F03060524EF9 -:1018B000377817B901238DF82830C7F110040EA826 -:1018C000FFF768FB0EABE4B20DF12900D919062C25 -:1018D00028BF06242246013400F0D6F90AABE4B250 -:1018E00043480393182304940293444B0193012328 -:1018F00000933AA3D3E9002302F09AF9357001F07E -:1019000037FE3F4A3F4C1368C31AB3F57A7F2FD393 -:10191000106001F02FFE02460B46354802F020FA17 -:10192000334802F03FF918B3237A0EAF364E002B3E -:1019300014BF03230223737101F01AFE4FF47A736C -:1019400001223946B0FBF3F03060304600F01EFB58 -:10195000182380B202932D4B019340F25513CDE929 -:101960000370009322481FA3D3E9002302F060F91B -:10197000237A93B101F0FCFD002607464FF48A78E4 -:1019800094F8D900304400F0030008FB004393F8BA -:10199000E82072B10136042EF2D1C82003F080FE97 -:1019A000237A002B7FF414AF13B0BDEC028BBDE89B -:1019B000F08FD3F8E02042B12368BA1AFA2B38BF6F -:1019C000FA230533B2EB430FE4D3FFF7BDFB002846 -:1019D000E0D1E2E70000000000000000401DA1206F -:1019E00026812A0BF1C6A7C1D068080F4034002019 -:1019F000103400200C34002009340020083400206A -:101A0000D0620020A05D0020F8230020D4620020D6 -:101A100008B5064801F0B6F8054801F0B3F8054AE4 -:101A200005490020BDE8084005F0D6BE403400203E -:101A3000F048002030630020691300087047000060 -:101A40002DE9F84F4FF47A7306460D46002402FB49 -:101A500003F7DFF85080DFF8509098F900305FFA14 -:101A600084FA5A1C01D0A34212D159F824002A4604 -:101A700031460368D3F820B03B46D847854207D1AA -:101A8000074B012083F800A0BDE8F88F0124E4E7AC -:101A9000002CFBD04FF4FA7003F002FE0020F3E7B5 -:101AA0001C630020182200201C22002070B5044670 -:101AB0004FF47A76412C254628BF412506FB05F0D8 -:101AC00003F0EEFD641BF5D170BD0000002307B5E7 -:101AD000024601210DF107008DF80730FFF7B0FF36 -:101AE00020B19DF8070003B05DF804FB4FF0FF3014 -:101AF000F9E700000A46042108B5FFF7A1FF80F0CE -:101B00000100C0B2404208BD074B0A4630B4197804 -:101B1000064B53F82140014623682046DD69044BFB -:101B2000AC4630BC604700BF1C6300201C22002074 -:101B3000A086010070B50A4E00240A4D04F0CEF8CC -:101B4000308028683388834208D904F0C3F82B68B2 -:101B500004440133B4F5003F2B60F2D370BD00BFE5 -:101B60001E630020D862002004F086B900F10060F6 -:101B700000F500300068704700F10060920000F549 -:101B8000003004F007B90000054B1A68054B1B88AC -:101B90009B1A834202D9104404F09CB8002070477D -:101BA000D86200201E630020024B1B68184404F01A -:101BB00097B800BFD8620020024B1B68184404F09D -:101BC000A1B800BFD86200200020704700F1FF508C -:101BD00000F58F10D0F8000870470000064991F812 -:101BE000243033B100230822086A81F82430FFF73B -:101BF000C3BF0120704700BFDC620020014B1868A2 -:101C0000704700BF0010005C194B013803220844E4 -:101C100070B51D68174BC5F30B042D0C1E88A6422A -:101C20000BD15C680A46013C824213460FD214F97C -:101C3000016F4EB102F8016BF6E7013A03F10803B8 -:101C4000ECD181420B4602D22C2203F8012B042452 -:101C5000094A1688AE4204D1984284BF967803F8A8 -:101C6000016B013C02F10402F3D1581A70BD00BFB0 -:101C70000010005C24220020DC780008704700007F -:101C80007047000070470000002310B5934203D056 -:101C9000CC5CC4540133F9E710BD0000013810B525 -:101CA00010F9013F3BB191F900409C4203D11AB1B8 -:101CB0000131013AF4E71AB191F90020981A10BDE8 -:101CC0001046FCE703460246D01A12F9011B002910 -:101CD000FAD1704702440346934202D003F8011B35 -:101CE000FAE770472DE9F8431F4D1446074688462A -:101CF00095F8242052BBDFF870909CB395F82430FF -:101D00002BB92022FF2148462F62FFF7E3FF95F809 -:101D100024004146C0F1080205EB8000A24228BF22 -:101D20002246D6B29200FFF7AFFF95F82430A41BED -:101D300017441E449044E4B2F6B2082E85F824609D -:101D4000DBD1FFF74BFF0028D7D108E02B6A03EB6C -:101D500082038342CFD0FFF741FF0028CBD1002080 -:101D6000BDE8F8830120FBE7DC620020024B1A7813 -:101D7000024B1A70704700BF1C630020182200201D -:101D800038B51A4C1A4D204602F0A8FF29462046C5 -:101D900002F0D0FF2D684FF47A70D5F89020D2F879 -:101DA000043843F00203C2F80438FFF77FFE1149FC -:101DB000284603F0CDF8D5F890200F4DD2F804381E -:101DC000286823F002030D49A042C2F804384FF4FA -:101DD000E1330B6001D002F0DFFE6868A04204D05E -:101DE0000649BDE8384002F0D7BE38BD106A002071 -:101DF0007C7A0008847A00081C22002004630020FA -:101E00000C4B70B50C4D04461E780C4B55F8262033 -:101E10009A420DD00A4B002118221846FFF75AFFAC -:101E20000460014655F82600BDE8704002F0B4BEDB -:101E300070BD00BF1C6300201C220020106A00201F -:101E4000046300202DE9F0470D460446002190462A -:101E5000284640F27912FFF73DFF23462022002159 -:101E6000284604F1220702F0F1F8231D0222202166 -:101E70002846C02602F0EAF8631D032222212846E4 -:101E800002F0E4F8A31D03222521284602F0DEF823 -:101E900004F1080310222821284602F0D7F804F1A3 -:101EA000100308223821284602F0D0F804F111036B -:101EB00008224021284602F0C9F804F11203082242 -:101EC0004821284602F0C2F804F1140320225021D0 -:101ED000284602F0BBF804F118034022702128467E -:101EE00002F0B4F804F120030822B021284602F0E1 -:101EF000ADF804F121030822B821284602F0A6F823 -:101F0000314608363B4608222846013702F09EF843 -:101F1000B6F5A07FF4D1002704F1330A04F13203AF -:101F200008223146284602F091F894F832304FEA00 -:101F3000C7099F4209F5A47615D3B8F1000F08D15F -:101F4000314609F24F1604F599730722284602F02C -:101F50007DF827463B1B94F8322193420CD3F01DA9 -:101F6000C008BDE8F0870AEB07030822314628467F -:101F7000013702F06BF8D8E707F233133146082235 -:101F800028460836013702F061F8E3E713B5044646 -:101F9000084600212022234601900160C0F803106A -:101FA00002F054F8231D01980222202102F04EF87D -:101FB000631D01980322222102F048F8A31D019815 -:101FC0000322252102F042F8019804F108031022AF -:101FD000282102F03BF8072002B010BD0023F7B51E -:101FE0000E46047F072200911946054601F0F2FED5 -:101FF000731C0122072100932846002301F0EAFE0A -:10200000C4B9B31C052208212846009323460D2499 -:1020100001F0E0FE3746BB1BB278934211D3073480 -:102020002B7FA88AE408BBB9844294BF002001201A -:1020300003B0F0BDAB8A0824DB00083BDB08B370BB -:10204000E8E7FB1C214608222846009300230834B9 -:10205000013701F0BFFEDEE7201A18BF0120E7E7D5 -:102060000023F7B50E46047F082200911946054665 -:1020700001F0B0FE731CC4B908220093234610245B -:102080001146284601F0A6FE01235F1C7278013B31 -:10209000934211D307342B7FA88AE408BBB984424A -:1020A00094BF0020012003B0F0BDAB8A0824DB0000 -:1020B000083BDB087370E7E7F3192146082228463E -:1020C0000093002301F086FE08343B46DDE7201A2A -:1020D00018BF0120E7E70000F8B50E460546144694 -:1020E000002181223046FFF7F5FD2B460822002112 -:1020F000304601F0ABFF7CB90F246B1C072208218E -:10210000304601F0A3FF01235F1C6A78013B934234 -:1021100004D3E01DC008F8BD0824F4E7EB192146FC -:102120000822304601F092FF08343B46ECE70000FD -:10213000F8B50E46054614460021CE223046FFF77C -:10214000C9FD2B4628220021304601F07FFF7CB9D3 -:10215000302405F1080308222821304601F076FFDB -:102160002F467B1B2A7A934204D3E01DC008F8BD9A -:102170002824F5E707F109032146082230460834F0 -:10218000013701F063FFECE7F7B5047F0E460091DD -:10219000012310220021054601F01CFEC4B9B31C26 -:1021A00009221021284600932346192401F012FE2B -:1021B00037467288BB1B9A4211D807342B7FA88AF6 -:1021C000E408BBB9844294BF0020012003B0F0BDF5 -:1021D000AB8A1024DB00103BDB087380E8E73B1D73 -:1021E000214608222846009300230834013701F0D5 -:1021F000F1FDDEE7201A18BF0120E7E730B50A44F9 -:10220000084D91420DD011F8013B5840082340F38E -:102210000004013B2C4013F0FF0384EA5000F6D188 -:10222000EFE730BD2083B8EDF7B5364A6B4610684E -:1022300051686A4603C308233349344805F0FAFA63 -:10224000044690BB0A25324A6B46106851686A46BC -:1022500003C308232F492D4805F0ECFA0446002853 -:1022600047D00369B3F5F01F43D8B0F86620B2F544 -:10227000AF6F3ED1284A024402F15C018B4238D351 -:102280005C3B224900209E1AFFF7B8FF04F164016D -:10229000074632460020FFF7B1FFA3689F4228D1CE -:1022A000E368984208BF002523E00369B3F5F01FF7 -:1022B00026D8428BB2F5AF6F20D1174A024402F103 -:1022C00010018B4218D3103B104900209D1AFFF7D4 -:1022D00095FF04F1180106462A460020FFF78EFFFD -:1022E000A3689E4202D1E368984201D00D25AAE777 -:1022F0000025284603B0F0BD1025A4E70C25A2E771 -:102300000B25A0E7EC780008DCFF1D0000000208A8 -:10231000F578000890FF1D000800FEF710B5037C5B -:10232000044613B9006805F06DFA204610BD0000A0 -:102330000023BFF35B8FC360BFF35B8FBFF35B8F83 -:102340008360BFF35B8F7047BFF35B8F0068BFF3A1 -:102350005B8F704770B505460C30FFF7F5FF0446FC -:1023600005F108063046FFF7EFFFA04206D96D6879 -:102370003046FFF7E9FF2544281A70BD3046FFF7C5 -:10238000E3FF201AF9E7000070B505464068A0B1E8 -:1023900005F10C0605F10800FFF7D6FF04463046AC -:1023A000FFF7D2FF844204F1FF34304694BF6D68DA -:1023B0000025FFF7C9FF2C44201A70BD38B50C4624 -:1023C0000546FFF7C7FFA04210D305F10800FFF74D -:1023D000BBFF04446868BFF35B8FB4FBF0F100FB04 -:1023E00011440120AC60BFF35B8F38BD0020FCE7D7 -:1023F0002DE9F041144607460D46FFF7C5FF84421C -:1024000028BF0446D4B1B84658F80C6B4046FFF7D5 -:102410009BFF3044286040467E68FFF795FF331AE3 -:102420009C4203D801206C60BDE8F081A41B6B6066 -:102430003B682044AB60E8600220F5E72046F3E704 -:1024400038B50C460546FFF79FFFA04210D305F1B3 -:102450000C00FFF779FF04446868BFF35B8FB4FB9F -:10246000F0F100FB11440120EC60BFF35B8F38BD3D -:102470000020FCE72DE9FF418846694607466C4687 -:10248000FFF7B6FF002506B204EBC606B4420AD039 -:10249000626808EB050120680834FFF7F5FB54F883 -:1024A000043C1D44F2E729463846FFF7C9FF284699 -:1024B00004B0BDE8F0810000F8B505460C300F46C9 -:1024C000FFF742FF05F1080604463046FFF73CFFE0 -:1024D000A042304688BF6C68FFF736FF201A38608C -:1024E00020B12C683046FFF72FFF2044F8BD0000D4 -:1024F00073B5144606460D46FFF72CFF8442019043 -:1025000028BF0446DCB101A93046FFF7D5FF019B87 -:1025100033B93268C5E90233C5E9002401200CE073 -:102520009C42286038BF0194019884426860F5D9C4 -:102530003368241A0220AB60EC6002B070BD204604 -:10254000FBE700002DE9FF410F4669466C46FFF7A7 -:10255000CFFF00B2002604EBC005AC4209D0D4F88E -:102560000480B81954F8081B42464644FFF78CFB18 -:10257000F3E7304604B0BDE8F081000038B5054609 -:10258000FFF7E0FF044601462846FFF717FF204605 -:1025900038BD0000302383F3118862B67047000015 -:1025A000002383F3118862B6704700000120704752 -:1025B0007047000010B41346026814680022A44655 -:1025C0005DF8044B6047000000F5805090F8590416 -:1025D0007047000000F5805090F8520470470000EA -:1025E00000F5805090F95804704700004E20704765 -:1025F00000F5805208B5FFF7CDFFD2F89834D2F835 -:1026000094041844D2F890341844D2F8783418441A -:10261000D2F888341844D2F884341844FFF7C0FF45 -:1026200008BD00002DE9F04F0C4600F5805185B043 -:102630001F4691F8523405469046BDF838909BB13C -:10264000D1F874340133C1F8743423689A0006D485 -:10265000237B082B0BD9627B0AB10F2B07D9D1F84A -:1026600078340133C1F878344FF0FF300FE0FFF7D2 -:1026700091FFEB6AD3F8C42012F4001A0AD0D1F803 -:102680007C3400200133C1F87C34FFF789FF05B0AA -:10269000BDE8F08F22684FF0480BD3F8C460002AE1 -:1026A0006B6AC6F30446B4BF42F0804292041BFB3F -:1026B000063BCBF8002023685B004FEA066344BF6B -:1026C00042F00052CBF80020227B43EA0243720121 -:1026D000CBF80430607B18B343F44013CBF80430DC -:1026E000D1F8A4340133C1F8A434AB1803F58353F3 -:1026F000197B41F020011973207B039200F094FFB5 -:102700000330039A80105FFA8AF30AF1010A8342C8 -:102710000DDA04EB83010BEB830349689960F2E760 -:10272000AB1803F58353197B60F34511E3E70121EF -:10273000EB6A04F10C00B140C3F8D010AB1821468D -:1027400003F58253C3E9048705EB461303F582536F -:10275000183351F804CB814243F804CBF9D10988EE -:102760002A442846198041F26803D65002F5805267 -:1027700009F0030392F86C1043F0100321F01F01DD -:102780000B43214682F86C304246FFF709FF3B4677 -:10279000CDF8009000F00EFF012078E72DE9F0471A -:1027A00000F58056044696F85254002D40F0018101 -:1027B000037C032B40F092802B4628462F465FFA7D -:1027C00083FC944510DA01EBCC0E51F83CC0BCF10F -:1027D000000F04DBDEF804C0BCF1000F02DB0137A0 -:1027E0000133ECE70130FBE7FFF7D4FEE36AF0B911 -:1027F000D3F8800040F00200C3F880004E23E06A66 -:10280000002F6ED1D0F8803043F00103C0F8803043 -:10281000694B6A4A1B6803F1805303F52C539B00F4 -:102820009342A36240F2AF80654800F09BFE4D28C2 -:1028300042D8DFF884814FEA004EDFF88891D8F85B -:1028400000C04EEA8C0EC3F884E00CF1805303F50F -:102850002C539B00636100EB0C03D4F82CC0C8F828 -:102860000030C0F14E03DCF8800040F03000CCF8BE -:1028700080004FF0000CD4F81480E6465FFA8CF02C -:102880008242BCDD01EBC00A51F83000002810DBA9 -:10289000DAF804A0BAF1000F0BDA09EA00400AF0F6 -:1028A0007F0A40EA0A0040F0084048F82E000EF186 -:1028B000010E0CF1010CE1E79A6922F001029A6124 -:1028C00000F056FE0646E36A9B69D90704D500F07E -:1028D0004FFE831BFA2BF6D9FFF762FE2846BDE8B0 -:1028E000F087B7EB530F3DD2DFF8CCE04FEA074C4F -:1028F000DEF800304CEA830CC0F888C003F1805049 -:1029000003EB4703002700F52C50CEF80030BC46FF -:102910008000A061E06AD0F8803043F00C03C0F87A -:102920008030D4F818E0FBB29A427FF771AF51F8CB -:10293000330001EBC3080028D8F8043001DB002B7A -:102940000EDB20F0604023F0604340F0005043F085 -:1029500000434EF83C000EEBCC000CF1010C436040 -:102960000137E0E7836923F00103836100F000FE93 -:102970000646E36A9B69DA07AED500F0F9FD831BD2 -:10298000FA2BF6D9A8E7E26A936923F00103936171 -:1029900000F0EEFD0746E36A9B69DB0705D500F012 -:1029A000E7FDC31BFA2BF6D996E7012586F85254AA -:1029B00092E7002592E700BF2C630020FCB50040A1 -:1029C000007900080000FF0713B500F5805401915D -:1029D000606CFFF7D9FC1F280AD920220199606C8E -:1029E000FFF748FDA0F120035842584102B010BD46 -:1029F0000020FBE700F5805008B5FFF7CBFD406CE9 -:102A0000FFF796FCBDE80840FFF7CABD0022026050 -:102A100082814260826070470022002310B5C0E9C5 -:102A20000023002304460C3020F8043CFFF7EEFF9F -:102A3000204610BD2DE9F047074688B09A468846E3 -:102A400007F5805468469146FFF7A4FDFFF7E4FFC1 -:102A5000606CFFF77FFC1F282DD920226946606C2F -:102A6000FFF78CFD202826D194F852341BB303AD18 -:102A7000444605AB2E46083403CE9E4244F8080C6B -:102A800044F8041C3546F5D130684146206038468C -:102A9000B388A380DDE90023C9E90023BDF808302D -:102AA0004A46AAF80030FFF77BFD534608B0BDE860 -:102AB000F04700F06DBD0020FFF772FD08B0BDE8E3 -:102AC000F08700002DE9F84F0023064600F58154F9 -:102AD000054688461034C0E90133274B46F8303BA1 -:102AE000374638462037FFF797FFA742F9D105F55B -:102AF00080544FF4805305F5A3594FF0000A266324 -:102B00000026676405F5835709F110094FF0000BA3 -:102B10001037E663C4E90D36012384F8403084F8A9 -:102B20004830A7F11800203747E910ABFFF76EFFD8 -:102B300047F8286C4F45F4D1B8F1010F84F8588458 -:102B4000A4F85A64A4F85C64A4F85E6484F8606431 -:102B5000A4F86264A4F86464A4F8666484F8686401 -:102B600002D9064800F0FEFC054B284653F82830F1 -:102B7000EB62BDE8F88F00BF5079000824790008A7 -:102B800040790008044B10B5197804464A1C1A70A5 -:102B9000FFF798FF204610BD296300202DE9F0477C -:102BA00000295FD0304F3148B7FBF1F581428CBF2F -:102BB0000A201120431EB5FBF0FC00FB1C50DCB2C8 -:102BC00020B1022B1846F5D8002037E00CF1FF3574 -:102BD000B5F5806F32D2C4EBC4094FF47A7009F1B5 -:102BE00003034FEAE308C3F3C70308F1010AA4EBA8 -:102BF000030E08FB00085FFA8EF65AFA8EFEB8FB49 -:102C0000FEFEBEF5617F1BDC1FFA8EF4581C56FADF -:102C100080F00CFB00FCB7FBFCFC6145D4D1013B10 -:102C2000DBB20F2BD0D8711E0020C9B2072905D8FE -:102C3000107101201480558053719171BDE8F087A7 -:102C400009F1FF334FEAE30EC3F3C7030EF10108A6 -:102C5000E41A0EFB0000E6B258FA84F4B0FBF4F478 -:102C6000A4B2D3E70846E9E700B4C4043F420F002A -:102C700038B540F27772C36A154CC3F8BC200722FE -:102C8000C36AC3F8C8202268C16A930043F4C02312 -:102C9000C1F8A03002F1805302F16C01C56A03F55E -:102CA0002C53EA3289009B00226041F0E061094A1E -:102CB000C361C5F8C01003F5D87103F56A734162AA -:102CC0009342836202D9044800F04CFC38BD00BF37 -:102CD0002C630020FCB50040007900082DE9F04F7E -:102CE00000F58055994689B0044695F858348A46CF -:102CF0009046022B04D90027384609B0BDE8F08F72 -:102D00009B4A52F8231009B942F823009949C4F8A4 -:102D10000CA00B7884F81090C3B9FFF73BFC964BDE -:102D2000D3F8EC2042F48072C3F8EC20D3F894205E -:102D300042F48072C3F89420D3F8942022F4807275 -:102D4000C3F8942001230B70FFF72AFC95F8513447 -:102D50006BB9FFF71FFC894A95F85834D35CEBB187 -:102D6000012B24D0012385F85134FFF719FCFFF71C -:102D700011FCE26A936923F01003936100F0F8FB01 -:102D80000746E36A9E6916F0080617D000F0F0FBCC -:102D9000C31BFA2BF5D9FFF703FCACE70321132083 -:102DA00001F044FD0321152001F040FDDAE7032185 -:102DB000142001F03BFD03211620F5E79A6942F04B -:102DC00001029A6100F0D4FB0746E36A9A69D007D2 -:102DD00005D400F0CDFBC31BFA2BF6D9DBE79A69CB -:102DE000002704F5825B42F002020BF1100B9A619E -:102DF000E36A5F65FFF7D4FB686CFFF799FA20225E -:102E000000216846FEF766FF02A8FFF7FFFD6A464D -:102E10000BEB06030DF1180E069794460833BCE839 -:102E20000300F44543F8080C43F8041C6246F4D14F -:102E3000DCF8000020361860B6F5806F9CF804209E -:102E40001A71DCD1002304F5A252514620461A32F1 -:102E500085F8503485F85334FFF7A0FE074690B943 -:102E6000E26A936923F00103936100F081FB054658 -:102E7000E36A9B69D9077FF53EAF00F079FB431BFE -:102E8000FA2BF5D937E795F85F6495F85E2436029A -:102E9000C5F86CA4E36A46EA426695F860241643D6 -:102EA000B5F85C2446EA0246DE61B8F1000F29D08D -:102EB00004F5A352414620460232FFF76FFE90B957 -:102EC000E26A936923F00103936100F051FB054628 -:102ED000E36A9B69DA077FF50EAF00F049FB431BFD -:102EE000FA2BF5D907E795F8683495F867141B01B4 -:102EF000C5F87084E26A43EA0123B5F8641443EA32 -:102F00000143D360E36A00262046C3F8BC60FFF7A4 -:102F1000AFFE85F859646FF04042E36A1A65184ABB -:102F2000E36A5A654FF00222E36A9A654FF0FF3276 -:102F3000E36AC3F8E0200322E36A9145DA653FF4CF -:102F4000DBAEE26A936923F00103936100F010FBAA -:102F50000646E36A9B69DB0705D500F009FB831B86 -:102F6000FA2BF6D9C7E6012385F85234C4E600BF30 -:102F700020630020286300200044025838790008AC -:102F8000550200022DE9F04F054689B0904699465A -:102F9000002741F2680A00F58056EB6AD3F8D83072 -:102FA000FB40D8074AD505EB47124FEA471B52446E -:102FB0001379190742D4D6F880340133C6F8803427 -:102FC00013799A0605EB0B0248BFD6F8A834524491 -:102FD00044BF0133C6F8A834137943F008031371D2 -:102FE000DB0723D596F8533403B305F582546846BE -:102FF000FFF712FD03AB18345C4404F1080C2068A1 -:10300000083454F8041C1A46644503C21346F6D12A -:103010002068694610602846A2889A800123ADF88E -:1030200008302B68CDE90089DB6B9847D6F854341B -:1030300023B1D6F89C340133C6F89C340137202FD5 -:10304000ABD109B0BDE8F08F2DE9F04F0F468DB040 -:10305000044600F08FFA82468946002F5BD1E36A6E -:10306000D3F8A02012F4FE0F03D100200DB0BDE86C -:10307000F08FD3F8A420920141BF04F58051D1F81C -:1030800094240132C1F89424D3F8A4205606ECD03D -:10309000D3F8A450E669C5F305254823E8464FF068 -:1030A000000B03FB05664046FFF7B0FC3268510099 -:1030B0004ABF22F06043C2F38A4343F000439200C8 -:1030C00048BF43F080430093736813F400131BBFA1 -:1030D000012304F580528DF80D308DF80D301EBFA0 -:1030E000D2F8AC340133C2F8AC34F38803F00F03E8 -:1030F0008DF80C309DF80C0000F096FA5FFA8BF317 -:10310000984225D9F2180CA90BF1010B127A0B4445 -:1031100003F82C2CEEE7012FA7D1E36AD3F8B020F7 -:1031200012F4FE0FA1D0D3F8B420950141BF04F5ED -:103130008051D1F894240132C1F89424D3F8B420FA -:10314000500692D0D3F8B450266AC5F30525A4E7FB -:10315000EFB9E36AC3F8A85004A807ADFFF75CFC19 -:1031600098E80F0007C52B800023204604A9ADF87E -:103170001830236804F58054DB6BCDE904A9984727 -:1031800058B1D4F88C340133C4F88C346EE7012F75 -:10319000E2D1E36AC3F8B850DEE7D4F890340120F6 -:1031A0000133C4F8903461E7F8B505460F4600F5E1 -:1031B0008054012639462846FFF746FF10B184F8AF -:1031C0005364F7E7D4F8543423B1D4F89C34013372 -:1031D000C4F89C34F8BD0000C36AF0B51A6C12F450 -:1031E0007F0F2BD01B6C00F5805441F268054FF027 -:1031F000010CC4F8A0340023471900EB43125E0110 -:103200002A44117911F0020F15D0490713D4B95986 -:10321000C66A0CFA01F1D6F8CCE011EA0E0F0AD01A -:10322000C6F8D410117941F004011171D4F8882442 -:103230000132C4F888240133202BDED1F0BD000018 -:103240002B4B70B51E561B5C012B30D8294D2A4ADA -:1032500055F8233052F8264013B349B3236D9A052D -:1032600010D54FF40073236500F084F950EA010291 -:103270000B4602D0013861F10003024655F82600E2 -:10328000FFF780FE236D9B012CD54FF0007255F89F -:103290002630226503F58053012283F8592421E06A -:1032A00001232365102323654FF48053236570BDEC -:1032B000236DDA0702D4236D5B0706D505230021B1 -:1032C00055F826002365FFF76FFF236DD80602D45B -:1032D000236D590606D55023012155F82600236594 -:1032E000FFF762FF55F82600BDE87040FFF774BF96 -:1032F0003C790008206300204079000808B5FFF7FA -:1033000049F9FFF769FFBDE80840FFF749B9000038 -:10331000C36AD3F8C00010F07C5005D0D3F8C400C5 -:1033200080F40010C0F340507047000000F580505A -:1033300008B5FFF72FF9406CFFF70CF8FFF730F9ED -:1033400043090CBF0120002008BD000000F5805398 -:1033500093F8592462B1C16A8A6922F001028A6134 -:10336000D3F898240132C3F89824002283F8592412 -:10337000704700002DE9F74300F58251984600257B -:10338000FFF708F9103141F2680E4FF0010900F51E -:10339000805C00EB4514744423795E071CD4DB0683 -:1033A0001AD58E69C36A09FA06F6D3F8CC703E4284 -:1033B00012D04F6801970F689742019F77EB08077B -:1033C0000AD2C3F8D460237943F004032371DCF8F4 -:1033D00084340133CCF8843401352031202DD8D108 -:1033E00003B0BDE8F043FFF7DBB80000F8B51E46B8 -:1033F00000230F46054613701446FFF797FF80F031 -:10340000010038701EB12846FFF782FF2070F8BD1A -:103410002DE9F04F85B099460D468046164691F845 -:1034200000B0DDE90EA302931378019300F0A2F837 -:103430002B7804460F4613B93378002B42D022462E -:103440003B464046FFF796FFFFF758FFFFF77EFF2A -:103450004B4632462946FFF7C9FF2B7833B1BBF103 -:10346000000F03D0012005B0BDE8F08F337813B111 -:10347000019B002BF6D108F5805303935445029B22 -:1034800077EB03031ED2039BD3F85404D0B1036837 -:10349000AAEB0401DB6889B298474B4632462946BD -:1034A0004046FFF7A3FF2B7813B1BBF1000FD9D132 -:1034B000337813B1019B002BD4D100F05BF80446A4 -:1034C0000F46DBE70020CEE7002108B50846FFF7EE -:1034D000B7FEBDE8084001F06DB8000008B5012155 -:1034E0000020FFF7ADFEBDE8084001F063B8000022 -:1034F00008B500210120FFF7A3FEBDE8084001F058 -:1035000059B80000012108B50846FFF799FEBDE84B -:10351000084001F04FB8000000B59BB0EFF30981FF -:1035200068226846FEF7B0FBEFF30583014B9B6B07 -:10353000FEE700BF00ED00E008B5FFF7EDFF00007B -:1035400000B59BB0EFF3098168226846FEF79CFB4B -:10355000EFF30583014B5B6BFEE700BF00ED00E07E -:10356000FEE700000FB408B5029802F025F8FEE768 -:1035700002F0CEBC02F0A6BC13B56C46031D84E875 -:10358000060094E8030083E80500012002B010BDA6 -:1035900073B58568019155B11B885B0707D4D0E9E5 -:1035A00000369B6B9847019AC1B23046A84701206C -:1035B00002B070BDF0B5866889B005460C465EB1B4 -:1035C000BDF838305B070AD4D0E900379B6B9847C9 -:1035D0002246C1B23846B047012009B0F0BD0022F2 -:1035E000002301F10806CDE9002300230A46ADF8C7 -:1035F000083003AB1068083252F8041C1C46B24273 -:1036000003C42346F6D1106820609288A280FFF799 -:10361000B1FF0423ADF808302B68CDE90001DB6B66 -:10362000694628469847D7E7082817D909280CD0B3 +:1000000000070020F1020008A1330008593300085E +:10001000813300085933000879330008F3020008DF +:10002000F3020008F3020008F30200088543000809 +:10003000F3020008F3020008F3020008F3020008CC +:10004000F3020008F3020008F3020008F3020008BC +:10005000F3020008F3020008017800082D78000878 +:100060005978000885780008B178000849440008EC +:10007000714400089D440008C9440008F544000884 +:100080001D45000849450008F3020008093300082F +:10009000313300081D33000845330008DD780008BF +:1000A000F3020008F3020008F3020008F30200085C +:1000B000F3020008F3020008F3020008F30200084C +:1000C000F3020008F3020008F3020008F30200083C +:1000D000F3020008F3020008F3020008F30200082C +:1000E00041790008F3020008F3020008F302000857 +:1000F000F3020008F3020008F30200087545000847 +:10010000F3020008F3020008C9790008F3020008AE +:10011000F3020008F3020008F3020008F3020008EB +:10012000A1450008C9450008F5450008214600081A +:100130004D460008F3020008F3020008F30200082D +:10014000F3020008F3020008F3020008F3020008BB +:1001500075460008A1460008CD460008F3020008D5 +:10016000F3020008F3020008F3020008F30200089B +:10017000F3020008816E0008F3020008F302000891 +:10018000F3020008F3020008B5790008F302000842 +:10019000F3020008F3020008F3020008F30200086B +:1001A000F3020008F3020008F3020008F30200085B +:1001B000F3020008F3020008F3020008F30200084B +:1001C000F3020008F3020008F3020008F30200083B +:1001D000F30200086D6E0008F3020008F302000845 +:1001E000F3020008F3020008F3020008F30200081B +:1001F000F3020008F3020008F3020008F30200080B +:10020000F3020008F3020008F3020008F3020008FA +:10021000F3020008F3020008F3020008F3020008EA +:10022000F3020008F3020008F3020008F3020008DA +:10023000F3020008F3020008F3020008F3020008CA +:10024000F3020008F3020008F3020008F3020008BA +:10025000F3020008F3020008F3020008F3020008AA +:10026000F3020008F3020008F3020008F30200089A +:10027000F3020008F3020008F3020008F30200088A +:10028000F3020008F3020008F3020008F30200087A +:10029000F3020008F3020008F3020008F30200086A +:1002A000F3020008F3020008F3020008F30200085A +:1002B000F3020008F3020008F3020008F30200084A +:1002C000F3020008F3020008F3020008F30200083A +:1002D000F3020008F3020008F3020008F30200082A +:1002E00021170008000000000000000000000000CE +:1002F00002E000F000F8FEE772B6374880F30888A5 +:10030000364880F3098836483649086040F20000D4 +:10031000CCF200004EF63471CEF200010860BFF35B +:100320004F8FBFF36F8F40F20000C0F2F0004EF627 +:100330008851CEF200010860BFF34F8FBFF36F8F7B +:100340004FF00000E1EE100A4EF63C71CEF20001D3 +:100350000860062080F31488BFF36F8F05F0FCFF60 +:1003600007F00AF84FF055301F491B4A91423CBF35 +:1003700041F8040BFAE71D49184A91423CBF41F885 +:10038000040BFAE71A491B4A1B4B9A423EBF51F82D +:10039000040B42F8040BF8E700201849184A914270 +:1003A0003CBF41F8040BFAE706F014F807F068F8D0 +:1003B000144C154DAC4203DA54F8041B8847F9E796 +:1003C00000F042F8114C124DAC4203DA54F8041B11 +:1003D0008847F9E705F0FCBF000700200023002054 +:1003E0000000000808ED00E00001002000070020E8 +:1003F0009880000800230020D0230020D023002074 +:10040000C8880020E0020008E4020008E4020008B6 +:10041000E40200082DE9F04F2DED108AC1F80CD050 +:10042000D0F80CD0BDEC108ABDE8F08F002383F328 +:1004300011882846A047002005F070FAFEE705F075 +:10044000EFF900DFFEE70000F8B501F0E9F901F08F +:100450007FFB05F005FF074605F074FF0546A8BBC6 +:100460001F4B9F4232D001339F4232D027F0FF0210 +:100470001C4B9A4230D12E4642F21074F8B200F072 +:100480009BFF00F09FFF08B10024264601F0A8FD65 +:1004900020B10024032000F079F8264635B1124B34 +:1004A0009F4203D0002405F045FF2646002005F0BA +:1004B000E1FE0EB100F080F801F0E8FA00F0B6FFBE +:1004C000204600F037F900F077F8F9E72E460024CF +:1004D000D7E704460126D4E7064641F28834D0E740 +:1004E000010007B0000008B0263A09B008B501F0D5 +:1004F00063F9A0F120035842584108BD07B541F205 +:100500001203022101A8ADF8043001F073F903B021 +:100510005DF804FB38B5302383F31188174803686E +:100520000BB105F0C7FA0023154A4FF47A7113484E +:1005300005F0B6FA002383F31188124C236813B137 +:100540002368013B2360636813B16368013B636008 +:100550000D4D2B7833B963687BB9022001F008FA9E +:10056000322363602B78032B07D163682BB90220F9 +:1005700001F0FEF94FF47A73636038BDD023002098 +:1005800015050008F0240020E8230020084B18700F +:1005900003280CD8DFE800F008050208022001F06B +:1005A000E5B9022001F0E0B9024B00225A60704721 +:1005B000E8230020F0240020F8B501F011FD30B14F +:1005C000544B03221A700022534B5A60F8BD534B10 +:1005D000534A1C4619680131F8D004339342F9D1CB +:1005E0006268504B9A42F1D94F4B9B6803F100630C +:1005F00003F500339A42E9D205F070FE05F082FE61 +:10060000002001F027F90220FFF7C0FF474B00212F +:10061000D3F8E820C3F8E810D3F81021C3F810117C +:10062000D3F81021D3F8EC20C3F8EC10D3F8142140 +:10063000C3F81411D3F81421D3F8F020C3F8F01044 +:10064000D3F81821C3F81811D3F81821D3F8802053 +:1006500042F00062C3F88020D3F8802022F00062CC +:10066000C3F88020D3F88020D3F8802042F00072B5 +:10067000C3F88020D3F8802022F00072C3F88020D5 +:10068000D3F8803072B64FF0E023C3F8084DD4E9B8 +:100690000004BFF34F8FBFF36F8F254AC2F8841059 +:1006A000BFF34F8F536923F480335361BFF34F8FF0 +:1006B000D2F8803043F6E076C3F3C905C3F34E3376 +:1006C0005B0103EA060C29464CEA81770139C2F83E +:1006D0007472F9D2203B13F1200FF2D1BFF34F8F88 +:1006E000BFF36F8FBFF34F8FBFF36F8F536923F447 +:1006F000003353610023C2F85032BFF34F8FBFF372 +:100700006F8F302383F31188854680F30888204754 +:100710005CE700BFE8230020F0240020000002086E +:1007200020000208FFFF01080023002000440258B7 +:1007300000ED00E02DE9F04F93B0B74B2022FF21F0 +:1007400000900AA89D6801F04BF9B44A1378A3B948 +:100750000121B34811700360302383F311880368CB +:100760000BB105F0A7F90023AE4A4FF47A71AC48FB +:1007700005F096F9002383F31188009B13B1AA4B6F +:10078000009A1A60A94A1378032B03D00023137030 +:10079000A54A53604FF0000A009CD3465646D14606 +:1007A000012001F0E3F824B19F4B1B68002B00F0FF +:1007B0002C82002001F000F80390039B002B01DA4B +:1007C00000F088FE039B002BEDDB012001F0CCF84C +:1007D000039B213B1F2BE3D801A252F823F000BF5B +:1007E00061080008890800081D090008A107000821 +:1007F000A1070008A1070008AF0900087F0B000847 +:10080000990A0008FB0A0008230B0008490B00089E +:10081000A10700085B0B0008A1070008CD0B00082A +:1008200001090008A1070008110C00086D08000864 +:1008300001090008A1070008FB0A0008A107000839 +:10084000A1070008A1070008A1070008A1070008E8 +:10085000A1070008A1070008A10700081D0900085A +:100860000220FFF743FE002840F0F981009B02219F +:1008700005A8BAF1000F08BF1C4641F21233ADF8CB +:10088000143000F0B7FF8BE74FF47A7000F094FF5C +:10089000071EEBDB0220FFF729FE0028E6D0013F10 +:1008A000052F00F2DE81DFE807F0030A0D10133692 +:1008B0000523042105A8059300F09CFF17E00421FF +:1008C0005548F9E704215A48F6E704215948F3E767 +:1008D0004FF01C08404608F1040800F0BDFF042159 +:1008E000059005A800F086FFB8F12C0FF2D1012089 +:1008F0004FF0000900FA07F747EA0B0B5FFA8BFB92 +:1009000001F0BAF826B10BF00B030B2B08BF002443 +:10091000FFF7F4FD44E704214748CDE7002EA5D0BA +:100920000BF00B030B2BA1D10220FFF7DFFD0746D5 +:1009300000289BD00120002600F08CFF0220FFF74A +:1009400025FE1FFA86F8404600F094FF0446B0B139 +:10095000039940460136A1F140025142514100F055 +:10096000A1FF0028EDD1BA46044641F2121302213C +:1009700005A83E46ADF8143000F03CFF10E72546D0 +:100980000120FFF703FE244B9B68AB4207D92846A2 +:1009900000F062FF013040F067810435F3E7002585 +:1009A000224BBA463E461D701F4B5D60A8E7002EE5 +:1009B0003FF45CAF0BF00B030B2B7FF457AF02201F +:1009C000FFF7E4FD322000F0F7FEB0F10008FFF67B +:1009D0004DAF18F003077FF449AF0F4A08EB05034A +:1009E000926893423FF642AFB8F5807F3FF73EAF43 +:1009F000124BB845019323DD4FF47A7000F0DCFE12 +:100A00000390039A002AFFF631AF039A0137019B46 +:100A100003F8012BEDE700BF00230020EC240020A9 +:100A2000D023002015050008F0240020E823002032 +:100A300004230020082300200C230020EC230020A6 +:100A4000C820FFF753FD074600283FF40FAF1F2DC6 +:100A500011D8C5F120020AAB25F0030084494245B4 +:100A6000184428BF4246019200F094FF019AFF21EA +:100A70007F4800F0B5FF4FEAA803C8F387027C491E +:100A80002846019300F0B4FF064600283FF46DAFFE +:100A9000019B05EB830533E70220FFF727FD0028C4 +:100AA0003FF4E4AE00F010FF00283FF4DFAE002773 +:100AB000B846704B9B68BB4218D91F2F11D80A9BB0 +:100AC00001330ED027F0030312AA134453F8203C3D +:100AD00005934046042205A9043701F06BFA8046CD +:100AE000E7E7384600F0B8FE0590F2E7CDF814804D +:100AF000042105A800F07EFE02E70023642104A87B +:100B0000049300F06DFE00287FF4B0AE0220FFF7E2 +:100B1000EDFC00283FF4AAAE049800F0CBFE05904F +:100B2000E6E70023642104A8049300F059FE00289E +:100B30007FF49CAE0220FFF7D9FC00283FF496AE6C +:100B4000049800F0B9FEEAE70220FFF7CFFC002886 +:100B50003FF48CAE00F0C8FEE1E70220FFF7C6FCD0 +:100B600000283FF483AE05A9142000F0C3FE074619 +:100B70000421049004A800F03DFE3946B9E7322074 +:100B800000F01AFE071EFFF671AEBB077FF46EAED3 +:100B9000384A07EB0903926893423FF667AE02209A +:100BA000FFF7A4FC00283FF461AE27F003074F4491 +:100BB000B9453FF4A5AE484609F1040900F04CFEE2 +:100BC0000421059005A800F015FEF1E74FF47A70B6 +:100BD000FFF78CFC00283FF449AE00F075FE0028BA +:100BE00044D00A9B01330BD008220AA9002000F050 +:100BF000FFFE00283AD02022FF210AA800F0F0FED4 +:100C0000FFF77CFC1C4804F08FFE13B0BDE8F08FAA +:100C1000002E3FF42BAE0BF00B030B2B7FF426AE14 +:100C20000023642105A8059300F0DAFD074600289B +:100C30007FF41CAE0220FFF759FC804600283FF4E9 +:100C400015AEFFF75BFC41F2883004F06DFE0598AD +:100C500000F05CFF46463C4600F00EFFA0E506466D +:100C60004EE64FF0000901E6BA467EE637467CE6DE +:100C7000EC23002000230020A0860100094A49F24D +:100C80006900136899B21B0C00FB013344F25061F8 +:100C90001360054B186882B2000C01FB020018605B +:100CA00080B270471423002010230020002110225E +:100CB00010B5044600F094FE034B03CB2060616046 +:100CC0001868A06010BD00BF00E8F11F2DE9F041D9 +:100CD000ADF5527D0D46002140F2751270AC07460D +:100CE00012A8119100F07CFE4FF4C472002120463E +:100CF00000F076FE0DF1440802F05AFB4FF47A72D0 +:100D0000264BB0FBF2F0186093E80700022384E85A +:100D100007000DF5F1702382FFF7C8FF47F60503C2 +:100D20001F4907A8238406F0F3FE25230DF2F322C2 +:100D30000DF13C0C84F8323107AB1E46083203CE6D +:100D4000664542F8080C42F8041C3346F5D1306879 +:100D500041461060204633791371012200F04EFFA6 +:100D6000002380B2E97E0393AB7E029305F1190361 +:100D700001930123009307A3D3E90023CDE9048065 +:100D8000384602F0D3FE0DF5527DBDE8F08100BF7C +:100D9000AFF300809E6AC421818A46EEF8240020C9 +:100DA000207B00082DE9F0412C4CDAB080460D463E +:100DB000237A5BBB27A9284601F02EF807460028B6 +:100DC00042D19DF89D60C82E3ED801464FF4A662E0 +:100DD000204600F005FE4FF4807332460DF19E016F +:100DE000C4F8F8314FF4007304F109002644C4F844 +:100DF0000C334FF44073C4F8203400F0CBFD9DF861 +:100E00009C30777223720BB9EB7E237206AC812281 +:100E1000002127A800F0E4FD0122214627A801F0C7 +:100E200037F8002380B2E97E0393AB7E029305F18D +:100E3000190301932823CDE904400093404605A3FC +:100E4000D3E9002302F072FE5AB0BDE8F08100BF82 +:100E5000AFF3008026417272DF25D7B7C05E002055 +:100E6000F0B5254E4FF48A75F1B0002405FB0065FE +:100E700096F8D830D822214685F8DC303AA885F893 +:100E8000E84006AF00F0ACFD06F1090000F0A0FD5F +:100E9000D5F8E430C2B206F109018DF8F0000DF189 +:100EA000F100CDE93A3400F075FD394601223AA847 +:100EB00001F01AF8082380B2317ACDE904700127D5 +:100EC0000E48CDE9023706F1D80301933023009391 +:100ED00007A3D3E9002302F029FEA04206DD02F0B9 +:100EE00067FAC5F8E000384671B0F0BD2046FBE770 +:100EF00078F6339F93CACD8DC05E00201035002058 +:100F00002DE9F04F264F87B0DFF8A080254E3846F8 +:100F100002F038FE034600283AD00024224DADF8F6 +:100F20001440A1460294A246CDE90344027B8DF809 +:100F3000142003AA9968406803C21B6843F0004369 +:100F400002932B6804F5A664D3F810B002F032FACD +:100F500010EB0802CDF800A0284605F5A65541F192 +:100F6000000302A9D8470028C8BF49F00109B4F519 +:100F7000266FE6D1B9F1000F05D0384602F006FE23 +:100F800086F800A0C3E73378072B04D80133337009 +:100F900007B0BDE8F08F024802F0F8FDF8E700BFA7 +:100FA00010350020F56300204035002040420F003E +:100FB00070B50D4614461E4602F014FD50B9022EBF +:100FC00010D1012C0ED112A3D3E900230120C5E9D1 +:100FD000002307E0282C10D005D8012C09D0052CBF +:100FE0000FD0002070BD302CFBD10BA3D3E9002320 +:100FF000ECE70BA3D3E90023E8E70BA3D3E9002335 +:10100000E4E70BA3D3E90023E0E700BFAFF30080E0 +:10101000401DA12026812A0B78F6339F93CACD8DDF +:101020009E6AC421818A46EE26417272DF25D7B7B7 +:10103000F017304A39059E5638B505460E4C00214A +:10104000013500F02FFCA4F82C55B4F82C0500F065 +:1010500011FC78B1B4F82C0500F01CFC014648B92D +:10106000B4F82C0500F01EFCB4F82C350133A4F8BC +:101070002C35EAE738BD00BFC05E0020F8B50D4C46 +:1010800002260D4FA4F5805343F8307C237E3BB9F4 +:1010900065692DB1284601F01DF8284606F0EEFCE2 +:1010A0002046A4F5A65401F015F8012E00D1F8BD94 +:1010B0000126E7E7305A0020E87B00082DE9F04FD1 +:1010C0008FB005460C4600AF02F08CFC002849D1D9 +:1010D000237E022B1BD1E38A012B18D102F068F981 +:1010E0000646FFF7CBFD03464FF4C87006F51676AB +:1010F000DFF8C082B3FBF0F202FB103316FA83F381 +:10110000C8F80030E37E33B9A34B00221A703C3795 +:10111000BD46BDE8F08F07F12401204600F03AFEFD +:101120000028F4D107F11400FFF7C0FD97F826401E +:1011300007F1140107F12700224606F0B7FC00284A +:10114000E2D10F2C08D8944B1C70D8F80030A3F5CE +:101150001673C8F80030DAE797F82410284602F032 +:1011600039FCD4E7E38A282B2BD010D8012B23D0CD +:10117000052BCCD1BFF34F8F8849894BCA6802F445 +:10118000E0621343CB60BFF34F8F00BFFDE7302B0E +:10119000BDD1844EE17E327A9142B8D1607E314633 +:1011A000002291F8DC50854200F0A580013201F563 +:1011B0008A71042AF5D1AAE721462846FFF786FD61 +:1011C000A5E721462846FFF7EDFDA0E7B2F8EC5071 +:1011D0007B6005F103094FEA99094FEA8902D11DA5 +:1011E000C908A8EBC10300219D46EB46584600F014 +:1011F000F7FB04F1EE012A465846314400F0CAFBE1 +:101200007B6813B9012000F025FB96F8D20000F0AE +:1012100031FB044630B9307200F056FB204600F036 +:1012200019FBB1E0D6F8D4203AB996F8D200B6F856 +:101230002C25824201D8FFF7FFFED6F8D4202A449D +:10124000944208D296F8D200B6F82C25013082429A +:1012500001D8FFF7F1FE5FFA89F25946706800F095 +:10126000C7FB08B9C54679E0726896F8D2002A44EF +:101270007260D6F8D42005EB0209C6F8D49000F0CD +:10128000F9FA814509D396F8D220D6F8D400013274 +:10129000001B86F8D220C6F8D400FF2D0FD80024FA +:1012A000347200F011FB204600F0D4FA00F098FEF2 +:1012B0003D4B188108B9FFF77FF9C54627E7BB68A2 +:1012C00096F8D9000AFB0362FB68D2F8E41082F8B2 +:1012D000E83001F58061C2F8E030C2F8E410FFF7B1 +:1012E000BFFDFFF70DFE96F8D920013202F0030290 +:1012F00086F8D920B6E74FF48A7A20460AFB02F531 +:1013000005F1EA01314400F01BFEF86000287FF48B +:10131000FEAE0122354485F8E82002F049F8D5F800 +:10132000E020D6ED007A801A40F6B832B8EE677A3F +:10133000DFED1E6A192838BF1920904228BF1046D9 +:1013400007EE900AF8EEE77A67EEA67ADFED186A04 +:10135000E7EE267AFCEEE77AC6ED007A96F8D93009 +:10136000BB60BA6873680AFB02F4321992F8E8109D +:1013700059B1D2F8E410E8468B423FF427AF002180 +:1013800082F8E810C2F8E010C5467368064A9B0A66 +:1013900001331381BBE600BF0935002000ED00E0FA +:1013A0000400FA05C05E0020F8240020CDCCCC3D1E +:1013B0006666663F0C350020014B1870704700BF11 +:1013C0000425002038B54FF00054144B22689A428F +:1013D00021D1627D0025124B12481A70C922237D4B +:1013E0000930114900F8013C4FF48073C0F8DB501C +:1013F000C0F8EF314FF40073C0F803334FF440737B +:10140000C0F8173400F0C6FAE0222946204600F062 +:10141000E7FA012038BD0020FCE700BF9AAD44C5C3 +:1014200004250020C05E00201600002037B500F023 +:10143000D7FD1F4C1F4D022301221F496B712368EA +:10144000288120465B68984704F5805301221A4999 +:10145000D3F8C03404F5A6505B68984700231749B9 +:101460004FF480520193164B16480093164B02F02E +:1014700089FA164B197811B1124802F0ABFA01F053 +:1014800097FF0446FFF7FAFB4FF4C873B0FBF3F283 +:1014900002FB130304F5167010FA83F00C4B18606E +:1014A00004F050FF08B10F232B8103B030BD00BF03 +:1014B00040350020F824002040420F00082500207D +:1014C000B10F000810350020BD10000804250020D1 +:1014D0000C3500202DE9F04F00242DED028B93B048 +:1014E0000DF12C084FF0010ADFF814B2FFF708FDE8 +:1014F0000A94ADF834400B94C8F804409FED798B02 +:1015000000267E4D37462B680DF11D0207A928469F +:101510008DF81CA08DF81D408DED008BD3F8089040 +:101520000023C8479DF81C90B9F1000F1ED010226F +:1015300000210EA800F054FA2B6808AA0AA95F69D6 +:1015400028460DF11E03B8470FAB4F4698E803003D +:1015500083E803009DF834300EA958468DF84430D6 +:101560000A9B0E93DDE9082302F0EEFC06F5A66661 +:1015700005F5A655B6F5266FC5D1002FC0D1604838 +:1015800002F030FA00283FD15E4E01F011FF3368BF +:10159000984239D301F00CFF0546FFF76FFB4FF47B +:1015A000C8738DF82870B0FBF3F202FB130305F546 +:1015B000167010FA83F03060534E377817B9012354 +:1015C0008DF82830C7F110050EA8FFF76FFB0EABA2 +:1015D000EDB20DF12900D919062D28BF06252A469E +:1015E000013500F0D7F90AABEDB245480393182353 +:1015F00004950293454B0193012300933BA3D3E948 +:10160000002302F035FA347001F0D2FE404A414D19 +:101610001368C31AB3F57A7F2FD3106001F0CAFEA6 +:1016200002460B46364802F0BBFA354802F0DAF9BA +:1016300018B32B7A0EAF384E002B14BF03230223AE +:10164000737101F0B5FE4FF47A7301223946B0FB95 +:10165000F3F03060304600F075FB182380B202933F +:101660002E4B019340F25513CDE9037000932448AB +:1016700020A3D3E9002302F0FBF92B7A93B101F008 +:1016800097FE002607464FF48A7895F8D900304433 +:1016900000F0030008FB005393F8E82072B1013614 +:1016A000042EF2D1C82004F03FF92B7A002B7FF4EE +:1016B00017AF13B0BDEC028BBDE8F08FD3F8E0207C +:1016C00042B12B68BA1AFA2B38BFFA230533B2EBB2 +:1016D000430FE4D3FFF7C4FB0028E0D1E2E700BFEB +:1016E000AFF300800000000000000000401DA120BA +:1016F00026812A0BF1C6A7C1D068080F403500200B +:10170000103500200C350020093500200835002058 +:10171000F0630020C05E0020F8240020F463002065 +:1017200010B5074C204601F007F904F5A65001F06A +:1017300003F9044A04490020BDE8104006F098B9B6 +:1017400040350020506400207D1000082DE9F84F3E +:101750004FF47A7306460D46002402FB03F7DFF8C8 +:101760005080DFF8509098F900305FFA84FA5A1CE4 +:1017700001D0A34212D159F824002A463146036809 +:10178000D3F820B03B46D847854207D1074B01200C +:1017900083F800A0BDE8F88F0124E4E7002CFBD01B +:1017A0004FF4FA7004F0C0F80020F3E73C64002026 +:1017B000182300201C230020002307B50246012126 +:1017C0000DF107008DF80730FFF7C0FF20B19DF83D +:1017D000070003B05DF804FB4FF0FF30F9E70000AD +:1017E0000A46042108B5FFF7B1FF80F00100C0B23E +:1017F000404208BD074B0A4630B41978064B53F8EF +:101800002140014623682046DD69044BAC4630BCCC +:10181000604700BF3C6400201C230020A08601001C +:1018200070B50A4E00240A4D04F0ACFB30802868E5 +:101830003388834208D904F0A1FB2B6804440133A8 +:10184000B4F5003F2B60F2D370BD00BF3E640020B2 +:10185000F863002004F064BC00F1006000F5003083 +:101860000068704700F10060920000F5003004F05D +:10187000E5BB0000054B1A68054B1B889B1A834289 +:1018800002D9104404F07ABB00207047F8630020AE +:101890003E640020024B1B68184404F075BB00BF77 +:1018A000F8630020024B1B68184404F07FBB00BFA4 +:1018B000F86300200020704700F1FF5000F58F1002 +:1018C000D0F8000870470000064991F8243033B181 +:1018D00000230822086A81F82430FFF7C3BF0120E3 +:1018E000704700BFFC630020014B1868704700BFC1 +:1018F0000010005C194B01380322084470B51D68C4 +:10190000174BC5F30B042D0C1E88A6420BD15C6847 +:101910000A46013C824213460FD214F9016F4EB1C0 +:1019200002F8016BF6E7013A03F10803ECD18142BA +:101930000B4602D22C2203F8012B0424094A1688F4 +:10194000AE4204D1984284BF967803F8016B013C03 +:1019500002F10402F3D1581A70BD00BF0010005C00 +:1019600024230020747B00087047000070470000AB +:101970007047000070B504464FF47A764CB1412CA4 +:10198000254628BF412506FB05F0641B03F0CCFF6C +:10199000F4E770BD002310B5934203D0CC5CC4546F +:1019A0000133F9E710BD0000013810B510F9013F0F +:1019B0003BB191F900409C4203D11AB10131013A87 +:1019C000F4E71AB191F90020981A10BD1046FCE70F +:1019D00003460246D01A12F9011B0029FAD17047BA +:1019E00002440346934202D003F8011BFAE7704712 +:1019F0002DE9F8431F4D14460746884695F82420E4 +:101A000052BBDFF870909CB395F824302BB920229C +:101A1000FF2148462F62FFF7E3FF95F82400414677 +:101A2000C0F1080205EB8000A24228BF2246D6B2D0 +:101A30009200FFF7AFFF95F82430A41B17441E4413 +:101A40009044E4B2F6B2082E85F82460DBD1FFF7AB +:101A50003BFF0028D7D108E02B6A03EB82038342C7 +:101A6000CFD0FFF731FF0028CBD10020BDE8F883AD +:101A70000120FBE7FC630020024B1A78024B1A702E +:101A8000704700BF3C6400201823002038B51A4C72 +:101A90001A4D204603F08CFA2946204603F0B4FA8A +:101AA0002D684FF47A70D5F89020D2F8043843F0BE +:101AB0000203C2F80438FFF75DFF1149284603F01E +:101AC000B1FBD5F890200F4DD2F80438286823F0E8 +:101AD00002030D49A042C2F804384FF4E1330B6011 +:101AE00001D003F0C3F96868A04204D00649BDE8FC +:101AF000384003F0BBB938BDB86B0020347E000815 +:101B00003C7E00081C230020246400200C4B70B590 +:101B10000C4D04461E780C4B55F826209A420DD0E9 +:101B20000A4B002118221846FFF75AFF04600146AD +:101B300055F82600BDE8704003F098B970BD00BFAD +:101B40003C6400201C230020B86B0020246400208B +:101B5000F0B5A1B071B600230120002480261A46FA +:101B6000194602F05BFE4FF4D067214A3D25136908 +:101B700023BBD2F810310BBB036804F100619960FC +:101B80000368C3F80CD003685E6003681F600168D7 +:101B90000B6843F001030B6001680B6823F01E0320 +:101BA0000B6001680B68DB07FCD4037B8034416861 +:101BB00005FA03F3B4F5001F0B60D8D102F06EFEF6 +:101BC000B4F5001F11D000240A4E0B4D012004F083 +:101BD000A7FA3388A34205D928682044013404F0C9 +:101BE000E5F9F6E7002004F09BFA61B621B0F0BDFC +:101BF000002000523E640020F86300202DE9F047E9 +:101C00000D46044600219046284640F27912FFF71F +:101C1000E7FE234620220021284604F1220702F095 +:101C200035F9231D022220212846C02602F02EF974 +:101C3000631D03222221284602F028F9A31D032256 +:101C40002521284602F022F904F108031022282158 +:101C5000284602F01BF904F1100308223821284617 +:101C600002F014F904F1110308224021284602F081 +:101C70000DF904F1120308224821284602F006F962 +:101C800004F1140320225021284602F0FFF804F149 +:101C9000180340227021284602F0F8F804F12003CE +:101CA0000822B021284602F0F1F804F121030822AD +:101CB000B821284602F0EAF8314608363B460822A9 +:101CC0002846013702F0E2F8B6F5A07FF4D10027EC +:101CD00004F1330A04F1320308223146284602F0A7 +:101CE000D5F894F832304FEAC7099F4209F5A47637 +:101CF00015D3B8F1000F08D1314609F24F1604F59B +:101D000099730722284602F0C1F827463B1B94F836 +:101D1000322193420CD3F01DC008BDE8F0870AEBD6 +:101D20000703082231462846013702F0AFF8D8E70A +:101D300007F233133146082228460836013702F0ED +:101D4000A5F8E3E713B50446084600212022234600 +:101D500001900160C0F8031002F098F8231D01986B +:101D60000222202102F092F8631D01980322222111 +:101D700002F08CF8A31D01980322252102F086F8B9 +:101D8000019804F108031022282102F07FF80720AF +:101D900002B010BD0023F7B50E46047F0722009164 +:101DA0001946054601F036FF731C012207210093F6 +:101DB0002846002301F02EFFC4B9B31C05220821D8 +:101DC0002846009323460D2401F024FF3746BB1B11 +:101DD000B278934211D307342B7FA88AE408BBB9A9 +:101DE000844294BF0020012003B0F0BDAB8A0824D8 +:101DF000DB00083BDB08B370E8E7FB1C2146082248 +:101E00002846009300230834013701F003FFDEE782 +:101E1000201A18BF0120E7E70023F7B50E46047F1C +:101E2000082200911946054601F0F4FE731CC4B95E +:101E300008220093234610241146284601F0EAFEAA +:101E400001235F1C7278013B934211D307342B7F2F +:101E5000A88AE408BBB9844294BF0020012003B0E3 +:101E6000F0BDAB8A0824DB00083BDB087370E7E7B2 +:101E7000F3192146082228460093002301F0CAFEE8 +:101E800008343B46DDE7201A18BF0120E7E70000D1 +:101E9000F8B50E4605461446002181223046FFF76C +:101EA0009FFD2B4608220021304601F0EFFF7CB950 +:101EB0000F246B1C07220821304601F0E7FF0123A5 +:101EC0005F1C6A78013B934204D3E01DC008F8BD53 +:101ED0000824F4E7EB1921460822304601F0D6FF2A +:101EE00008343B46ECE70000F8B50E4605461446BC +:101EF0000021CE223046FFF773FD2B462822002119 +:101F0000304601F0C3FF7CB9302405F108030822F4 +:101F10002821304601F0BAFF2F467B1B2A7A9342D4 +:101F200004D3E01DC008F8BD2824F5E707F1090334 +:101F30002146082230460834013701F0A7FFECE7BC +:101F4000F7B5047F0E4600910123102200210546BB +:101F500001F060FEC4B9B31C092210212846009389 +:101F60002346192401F056FE37467288BB1B9A425D +:101F700011D807342B7FA88AE408BBB9844294BFE8 +:101F80000020012003B0F0BDAB8A1024DB00103B21 +:101F9000DB087380E8E73B1D2146082228460093B2 +:101FA00000230834013701F035FEDEE7201A18BFA0 +:101FB0000120E7E730B50A44084D91420DD011F8F1 +:101FC000013B5840082340F30004013B2C4013F030 +:101FD000FF0384EA5000F6D1EFE730BD2083B8ED6F +:101FE000F7B5364A6B46106851686A4603C3082342 +:101FF0003349344805F06AFD044690BB0A25324A4D +:102000006B46106851686A4603C308232F492D4860 +:1020100005F05CFD0446002847D00369B3F5F01FC6 +:1020200043D8B0F86620B2F5AF6F3ED1284A0244DB +:1020300002F15C018B4238D35C3B224900209E1A9E +:10204000FFF7B8FF04F16401074632460020FFF7AE +:10205000B1FFA3689F4228D1E368984208BF0025DA +:1020600023E00369B3F5F01F26D8428BB2F5AF6FBA +:1020700020D1174A024402F110018B4218D3103BC1 +:10208000104900209D1AFFF795FF04F1180106463C +:102090002A460020FFF78EFFA3689E4202D1E36824 +:1020A000984201D00D25AAE70025284603B0F0BDCF +:1020B0001025A4E70C25A2E70B25A0E7847B0008E8 +:1020C000DCFF1D00000002088D7B000890FF1D0052 +:1020D0000800FEF710B5037C044613B9006805F04C +:1020E000DDFC204610BD00000023BFF35B8FC36002 +:1020F000BFF35B8FBFF35B8F8360BFF35B8F704772 +:10210000BFF35B8F0068BFF35B8F704770B5054608 +:102110000C30FFF7F5FF044605F108063046FFF7DF +:10212000EFFFA04206D96D683046FFF7E9FF25446E +:10213000281A70BD3046FFF7E3FF201AF9E70000C8 +:1021400070B505464068A0B105F10C0605F1080020 +:10215000FFF7D6FF04463046FFF7D2FF844204F172 +:10216000FF34304694BF6D680025FFF7C9FF2C444B +:10217000201A70BD38B50C460546FFF7C7FFA042D0 +:1021800010D305F10800FFF7BBFF04446868BFF3F4 +:102190005B8FB4FBF0F100FB11440120AC60BFF396 +:1021A0005B8F38BD0020FCE72DE9F041144607465F +:1021B0000D46FFF7C5FF844228BF0446D4B1B84698 +:1021C00058F80C6B4046FFF79BFF304428604046B0 +:1021D0007E68FFF795FF331A9C4203D801206C609C +:1021E000BDE8F081A41B6B603B682044AB60E860F5 +:1021F0000220F5E72046F3E738B50C460546FFF721 +:102200009FFFA04210D305F10C00FFF779FF0444B3 +:102210006868BFF35B8FB4FBF0F100FB1144012051 +:10222000EC60BFF35B8F38BD0020FCE72DE9FF4178 +:102230008846694607466C46FFF7B6FF002506B29A +:1022400004EBC606B4420AD0626808EB05012068B8 +:102250000834FFF79FFB54F8043C1D44F2E729467D +:102260003846FFF7C9FF284604B0BDE8F0810000FA +:10227000F8B505460C300F46FFF742FF05F108069A +:1022800004463046FFF73CFFA042304688BF6C68EA +:10229000FFF736FF201A386020B12C683046FFF770 +:1022A0002FFF2044F8BD000073B5144606460D46C6 +:1022B000FFF72CFF8442019028BF0446DCB101A93E +:1022C0003046FFF7D5FF019B33B93268C5E90233C9 +:1022D000C5E9002401200CE09C42286038BF01942D +:1022E000019884426860F5D93368241A0220AB60F3 +:1022F000EC6002B070BD2046FBE700002DE9FF4115 +:102300000F4669466C46FFF7CFFF00B2002604EB8C +:10231000C005AC4209D0D4F80480B81954F8081BA1 +:1023200042464644FFF736FBF3E7304604B0BDE8CB +:10233000F081000038B50546FFF7E0FF044601468E +:102340002846FFF717FF204638BD00007047000001 +:1023500010B41346026814680022A4465DF8044BCA +:102360006047000000F5805090F859047047000065 +:1023700000F5805090F852047047000000F580503E +:1023800090F95804704700004E207047302383F3C3 +:10239000118800F58052D2F89C34D2F89804184481 +:1023A000D2F894341844D2F87C341844D2F88C34DF +:1023B0001844D2F888341844002383F311887047F6 +:1023C00000F58050C0F85414012070472DE9F04FFB +:1023D0000C4600F5805185B01F4691F852340546F1 +:1023E0009046BDF838909BB1D1F878340133C1F8EC +:1023F00078342368980006D4237B082B0BD9627BA2 +:102400000AB10F2B07D9D1F87C340133C1F87C34E1 +:102410004FF0FF3010E0302383F31188EB6AD3F8DC +:10242000C42012F4001B0AD0D1F8803400200133FC +:10243000C1F8803480F3118805B0BDE8F08F2068C2 +:102440004822D3F8C4300028C3F3044A6B6AB4BFEF +:1024500040F08040800412FB0A334FEA4A161860AD +:10246000226852004FEA0A6244BF40F000501860F0 +:10247000207B42EA00425A60607B10B342F4401273 +:102480005A60D1F8B0240132C1F8B024AA1902F57B +:102490008352117B41F020011173207B039300F0E4 +:1024A000E3FF0330039B80105FFA8BF20BF1010B0B +:1024B00082420DDA04EB820103EB820249689160EB +:1024C000F2E7AA1902F58352117B60F34511E3E7A5 +:1024D0000122EB6A05EB4A1102FA0AF201F5825178 +:1024E000C3F8D020AB19183104F10C0203F5825364 +:1024F000C3E90487234653F8040B934241F8040BC5 +:10250000F9D11B882E440B8041F2680346F803A0E2 +:1025100006F5805609F0030396F86C2043F010038B +:1025200022F01F02134386F86C30002383F31188D6 +:1025300042463B4621462846CDF8009000F05AFF1F +:10254000012079E72DE9F04700F58056044696F81A +:102550005254002D40F00381037C032B40F0948003 +:1025600028462B462F465FFA80FC944510DA01EB93 +:10257000CC0E51F83CC0BCF1000F04DBDEF804C007 +:10258000BCF1000F02DB01370130ECE70133FBE760 +:10259000302080F31188E06AF3B9D0F8803043F03E +:1025A0000203C0F880304E23E06A002F6FD1D0F8CC +:1025B000803043F00103C0F880306A4B6A4A1B68E0 +:1025C00003F1805303F52C539B009342A36240F226 +:1025D000B080664800F0E6FE4D2B42D8DFF88481DB +:1025E0004FEA034EDFF88891D8F800C04EEA8C0E0F +:1025F000C0F884E00CF1805000F52C508000606140 +:1026000003EB0C00D4F82CC0C3F14E03C8F8000053 +:10261000DCF8800040F03000CCF880004FF0000C77 +:10262000D4F81480E6465FFA8CF08242BCDD01EB00 +:10263000C00A51F83000002810DBDAF804A0BAF123 +:10264000000F0BDA09EA00400AF07F0A40EA0A00AC +:1026500040F0084048F82E000EF1010E0CF1010C7C +:10266000E1E7836923F00103836100F0A1FE0646E0 +:10267000E36A9B69D90704D500F09AFE831BFA2B05 +:10268000F6D9002383F311882846BDE8F087B7EB1D +:10269000530F3DD2DFF8CCE04FEA074CDEF80030B4 +:1026A0004CEA830CC0F888C003F1805003EB470369 +:1026B000002700F52C50CEF80030BC468000A06109 +:1026C000E06AD0F8803043F00C03C0F88030D4F8D2 +:1026D00018E0FBB29A427FF770AF51F8330001EB7C +:1026E000C3080028D8F8043001DB002B0EDB20F0F3 +:1026F000604023F0604340F0005043F000434EF848 +:102700003C000EEBCC000CF1010C43600137E0E71C +:10271000836923F00103836100F04AFE0646E36A01 +:102720009B69DA07ADD500F043FE831BFA2BF6D97F +:10273000A7E7E26A936923F00103936100F038FE92 +:102740000746E36A9B69DB0705D500F031FEC31B32 +:10275000FA2BF6D995E7012586F8525491E7002522 +:1027600092E700BF4C640020FCB50040987B000855 +:102770000000FF0713B500F580540191606CFFF76E +:10278000DFFC1F280AD920220199606CFFF74EFD5B +:10279000A0F120035842584102B010BD0020FBE7D1 +:1027A00008B5302383F3118800F58050406CFFF7A3 +:1027B0009BFC002383F3118808BD00000022026007 +:1027C00082814260826070470022002310B5C0E918 +:1027D0000023002304460C3020F8043CFFF7EEFFF2 +:1027E000204610BD2DE9F0479A4688B00746884636 +:1027F0009146302383F3118807F580546846FFF72C +:10280000E3FF606CFFF782FC1F282ED92022694667 +:10281000606CFFF78FFD202827D194F8523423B342 +:1028200003AD444605AB2E46083403CE9E4244F821 +:10283000080C44F8041C3546F5D130682060B38894 +:10284000A380DDE90023C9E90023BDF80830AAF818 +:102850000030002383F3118853464A4641463846E8 +:1028600008B0BDE8F04700F0B3BD002080F3118848 +:1028700008B0BDE8F08700002DE9F84F00230646B8 +:1028800000F58154054688461034C0E90133274BD2 +:1028900046F8303B374638462037FFF795FFA742CA +:1028A000F9D105F580544FF4805305F5A3594FF045 +:1028B000000A26630026676405F5835709F11009AD +:1028C0004FF0000B1037E663C4E90D36012384F89E +:1028D000403084F84830A7F11800203747E910ABA2 +:1028E000FFF76CFF47F8286C4F45F4D1B8F1010FA2 +:1028F00084F85884A4F85A64A4F85C64A4F85E646C +:1029000084F86064A4F86264A4F86464A4F866645B +:1029100084F8686402D9064800F044FD054B284657 +:1029200053F82830EB62BDE8F88F00BFE87B000861 +:10293000BC7B0008D87B0008044B10B5197804460E +:102940004A1C1A70FFF798FF204610BD496400200A +:102950002DE9F04300295AD02E4E2F48B6FBF1F452 +:1029600081428CBF0A201120431EB4FBF0F700FB0C +:102970001740DDB220B1022B1846F5D8002032E016 +:102980007B1EB3F5806F2ED2C5EBC5084FF47A736A +:1029900008F103044FEAE40EC4F3C7040EF1010981 +:1029A000281B0EFB033E5FFA80FC59FA80F0BEFB49 +:1029B000F0F0B0F5617F18DC83B2601C5CFA80F047 +:1029C0007843B6FBF0F08142D8D1611E0F29D5D8EB +:1029D0000CF1FF310729D1D80120138057801071E5 +:1029E000547182F806C0BDE8F08308F1FF34E010AE +:1029F000C4F3C70400F1010E2D1B00FB03335FFA83 +:102A000085FC5EFA85F5B3FBF5F39BB2D5E7084686 +:102A1000E9E700BF00B4C4043F420F0030B50D4BDE +:102A200005200D4D1C786C438C420ED15978012045 +:102A3000518099785171D9789171197911715B79B7 +:102A400003EB83035B00138030BD013803F1060301 +:102A5000E8D1F9E7287C000840420F0038B540F281 +:102A60007772C36A154CC3F8BC200722C36AC3F847 +:102A7000C8202268C16A930043F4C023C1F8A03083 +:102A800002F1805302F16C01C56A03F52C53EA325E +:102A900089009B00226041F0E061094AC361C5F8EA +:102AA000C01003F5D87103F56A73416293428362E3 +:102AB00002D9044800F076FC38BD00BF4C64002009 +:102AC000FCB50040987B00082DE9F04F00F58055DB +:102AD0001F4689B0044695F8583489469046022B23 +:102AE00004D90026304609B0BDE8F08FA84A52F854 +:102AF000231009B942F82300A648C4F80C900178C5 +:102B00002774C9B9302383F31188A34BD3F8EC2081 +:102B100042F48072C3F8EC20D3F8942042F480721F +:102B2000C3F89420D3F8942022F48072C3F8942040 +:102B30000123037081F3118895F851347BB9302358 +:102B400083F31188954A95F85834D35C0BB3012B65 +:102B500028D0012385F85134002383F311883023D2 +:102B600083F31188E26A936923F01003936100F004 +:102B70001FFC8246E36A9E6916F0080619D000F031 +:102B800017FCA0EB0A03FA2BF4D9002686F3118870 +:102B9000A8E70321132001F09DFF0321152001F078 +:102BA00099FFD6E70321142001F094FF032116209A +:102BB000F5E79A6942F001029A6100F0F9FB82465A +:102BC000E36A9A69D00706D400F0F2FBA0EB0A038F +:102BD000FA2BF5D9D9E79A694FF0000A42F00202C0 +:102BE0009A61E36AC3F854A08AF3118804F5825B02 +:102BF000686CFFF779FA0BF1100B20220021684670 +:102C0000FEF7EEFE02A8FFF7D9FD6A460BEB0603BE +:102C10000DF1180ECDF818A094460833BCE8030057 +:102C2000F44543F8080C43F8041C6246F4D1DCF880 +:102C3000000020361860B6F5806F9CF804201A71E9 +:102C4000DBD1002304F5A252494620461A3285F80A +:102C5000503485F85334FFF77BFE064690B9E26A9C +:102C6000936923F00103936100F0A2FB0546E36A38 +:102C70009B69D9077FF535AF00F09AFB431BFA2B10 +:102C8000F5D92EE795F85E34C5F86C94591E95F881 +:102C90005F34E26A013B1B0243EA416395F860142A +:102CA00001390B43B5F85C14013943EA0143D361A0 +:102CB000B8F1000F36D004F5A35241462046023247 +:102CC000FFF7ACFE90B9E26A936923F001039361C8 +:102CD00000F06EFB0546E36A9B69DA077FF501AFFA +:102CE00000F066FB431BFA2BF5D9FAE695F867244A +:102CF000C5F87084511E95F86824E36A013A120100 +:102D000042EA012295F8661401390A43B5F86414C1 +:102D1000013942EA014242F40002DA604FF42062D3 +:102D2000E36A9A64E36A4FF000082046C3F8BC8067 +:102D3000FFF794FE85F859846FF04042E36A1A6504 +:102D4000174AE36A5A654FF00222E36A9A654FF028 +:102D5000FF32E36AC3F8E0200322E36A9742DA65B0 +:102D60003FF4C0AEE26A936923F00103936100F07F +:102D70001FFB0746E36A9B69DB0705D500F018FBDC +:102D8000C31BFA2BF6D9ACE6012385F85234A9E629 +:102D9000406400204864002000440258D07B0008B2 +:102DA000550200022DE9F04F054689B0904699463C +:102DB000002741F2680A00F58056EB6AD3F8D83054 +:102DC000FB40D80751D505EB47124FEA471B524449 +:102DD0001379190749D4D6F884340133C6F88434FA +:102DE00005F5A553C3E9008913799A0605EB0B0293 +:102DF00048BFD6F8B434524444BF0133C6F8B434A3 +:102E0000137943F008031371DB0723D596F8533485 +:102E100003B305F582546846FFF7D6FC03AB1834BC +:102E20005C4404F1080C2068083454F8041C1A4669 +:102E3000644503C21346F6D12068694610602846EF +:102E4000A2889A800123ADF808302B68CDE900896B +:102E5000DB6B9847D6F8A834D6F854040133C6F88B +:102E6000A83410B103681B6998470137202FA4D1FB +:102E700009B0BDE8F08F00002DE9F04F0F468DB08E +:102E8000044600F097FA82468946002F5BD1E36A38 +:102E9000D3F8A02012F4FE0F03D100200DB0BDE83E +:102EA000F08FD3F8A420920141BF04F58051D1F8EE +:102EB00098240132C1F89824D3F8A4205606ECD007 +:102EC000D3F8A450E669C5F305254823E8464FF03A +:102ED000000B03FB05664046FFF770FC32685100AB +:102EE0004ABF22F06043C2F38A4343F0004392009A +:102EF00048BF43F080430093736813F400131BBF73 +:102F0000012304F580528DF80D308DF80D301EBF71 +:102F1000D2F8B8340133C2F8B834F38803F00F03A1 +:102F20008DF80C309DF80C0000F09EFA5FFA8BF3E0 +:102F3000984225D9F2180CA90BF1010B127A0B4417 +:102F400003F82C2CEEE7012FA7D1E36AD3F8B020C9 +:102F500012F4FE0FA1D0D3F8B420950141BF04F5BF +:102F60008051D1F898240132C1F89824D3F8B420C4 +:102F7000500692D0D3F8B450266AC5F30525A4E7CD +:102F8000EFB9E36AC3F8A85004A807ADFFF71CFC2B +:102F900098E80F0007C52B800023204604A9ADF850 +:102FA0001830236804F58054DB6BCDE904A99847F9 +:102FB00058B1D4F890340133C4F890346EE7012F3F +:102FC000E2D1E36AC3F8B850DEE7D4F894340120C4 +:102FD0000133C4F8943461E72DE9F04105460F460A +:102FE00000F58054012639462846FFF745FF10B109 +:102FF00084F85364F7E7D4F8A834D4F854040133C0 +:10300000C4F8A83420B10368BDE8F0411B69184733 +:10301000BDE8F081C36AF0B51A6C12F47F0F2BD0B3 +:103020001B6C00F5805441F268054FF0010CC4F8A8 +:10303000AC340023471900EB43125E012A44117996 +:1030400011F0020F15D0490713D4B959C66A0CFA0A +:1030500001F1D6F8CCE011EA0E0F0AD0C6F8D41070 +:10306000117941F004011171D4F88C240132C4F8B3 +:103070008C240133202BDED1F0BD00002B4B70B52A +:103080001E561B5C012B30D8294D2A4A55F8233097 +:1030900052F8264013B349B3236D9A0510D54FF467 +:1030A0000073236500F086F950EA01020B4602D056 +:1030B000013861F10003024655F82600FFF772FE61 +:1030C000236D9B012CD54FF0007255F826302265F8 +:1030D00003F58053012283F8592421E0012323655D +:1030E000102323654FF48053236570BD236DDA07E9 +:1030F00002D4236D5B0706D50523002155F8260071 +:103100002365FFF769FF236DD80602D4236D5906A6 +:1031100006D55023012155F826002365FFF75CFFF3 +:1031200055F82600BDE87040FFF774BFD47B000857 +:1031300040640020D87B000808B5302383F3118851 +:10314000FFF768FF002383F3118808BDC36AD3F833 +:10315000C00010F07C5005D0D3F8C40080F40010FB +:10316000C0F340507047000008B5302383F3118846 +:1031700000F58050406CFEF7C9FF002383F31188EF +:1031800043090CBF0120002008BD000000F580535A +:1031900093F8592462B1C16A8A6922F001028A61F6 +:1031A000D3F89C240132C3F89C24002283F85924CC +:1031B000704700002DE9F743302181F3118800F5B5 +:1031C0008251002541F2680E4FF00108103100F5E0 +:1031D000805C00EB45147444267977071CD4F6060E +:1031E0001AD58E69D0F82C9008FA06F6D9F8CC706A +:1031F0003E4211D04F6801970F689742019F9F414F +:103200000AD2C9F8D460267946F004062671DCF8A3 +:1032100088440134CCF8884401352031202DD8D1A0 +:10322000002383F3118803B0BDE8F083F8B51E4690 +:1032300000230F46054613701446FFF795FF80F0F4 +:10324000010038701EB12846FFF780FF2070F8BDDE +:103250002DE9F04F85B099460D468046164691F807 +:1032600000B0DDE90EA302931378019300F0A2F8F9 +:103270002B7804460F4613B93378002B41D02246F1 +:103280003B464046FFF796FFFFF756FFFFF77EFFEE +:103290004B4632462946FFF7C9FF2B7833B1BBF1C5 +:1032A000000F03D0012005B0BDE8F08F337813B1D3 +:1032B000019B002BF6D108F5805303935445029BE4 +:1032C00077EB03031DD2039BD3F85404C8B1036802 +:1032D000AAEB04011B6898474B46324629464046F4 +:1032E000FFF7A4FF2B7813B1BBF1000FDAD13378CD +:1032F00013B1019B002BD5D100F05CF804460F46BA +:10330000DCE70020CFE70000002108B50846FFF702 +:10331000B5FEBDE8084001F06DB8000008B5012118 +:103320000020FFF7ABFEBDE8084001F063B80000E5 +:1033300008B500210120FFF7A1FEBDE8084001F01B +:1033400059B80000012108B50846FFF797FEBDE80F +:10335000084001F04FB8000000B59BB0EFF30981C1 +:1033600068226846FEF716FBEFF30583014B9B6B63 +:10337000FEE700BF00ED00E008B5FFF7EDFF00003D +:1033800000B59BB0EFF3098168226846FEF702FBA7 +:10339000EFF30583014B5B6BFEE700BF00ED00E040 +:1033A000FEE700000FB408B5029802F063FAFEE7EA +:1033B00002F0F8BE02F0DABE13B56C46031D84E8D5 +:1033C000060094E8030083E80500012002B010BD68 +:1033D00073B58568019155B11B885B0707D4D0E9A7 +:1033E00000369B6B9847019AC1B23046A84701202E +:1033F00002B070BDF0B5866889B005460C465EB176 +:10340000BDF838305B070AD4D0E900379B6B98478A +:103410002246C1B23846B047012009B0F0BD0022B3 +:10342000002301F10806CDE9002300230A46ADF888 +:10343000083003AB1068083252F8041C1C46B24234 +:1034400003C42346F6D1106820609288A280FFF75B +:10345000B1FF0423ADF808302B68CDE90001DB6B28 +:10346000694628469847D7E7082817D909280CD075 +:103470000A280CD00B280CD00C280CD00D280CD00E +:103480000E2814BF4020302070470C2070471020B9 +:1034900070471420704718207047202070470000A4 +:1034A0002DE9F041456A15B94162BDE8F0814B68EC +:1034B000AC4623F06047C3F38A464FEAD37EC3F39A +:1034C000807816EA230638BF3E462B465A68BEEB84 +:1034D000D27F22F060440AD0002A18DAA40CB44249 +:1034E00017D19D420FD10D60DEE71346EEE7A742EC +:1034F00007D102F08044C2F3807242450BD054B130 +:10350000EFE708D2EDE7CCF800100B60CDE7B4424E +:1035100001D0B442E5D81A689C46002AE5D119606A +:10352000C3E700002DE9F047089D01F0070400EB18 +:10353000D1004FF47F494FEAD508224405F0070532 +:10354000944201D1BDE8F08704F0070705F0070AAF +:10355000111B08EBD50E57453E4613F80EC038BF79 +:103560005646C6F108068E4228BF0E46E108415C69 +:1035700034443544B94029FA06F721FA0AF1FFB27A +:103580008CEA010147FA0AF739408CEA010C03F88A +:103590000EC0D5E780EA0120082341F2210201B2E2 +:1035A000013B4000002980B2B8BF504013F0FF0338 +:1035B000F5D1704738B50C468D18A54200D138BDFD +:1035C00014F8011BFFF7E6FFF7E7000042684AB175 +:1035D000136881894360438901339BB299424381D7 +:1035E00038BF83811046704770B588B004462022EA +:1035F0000D4668460021FEF7F3F920460495FFF7D3 +:10360000E5FF024660B16B46054608AE1C4608352C +:1036100003CCB44245F8080C45F8041C2346F5D108 +:10362000104608B070BD0000082817D909280CD032 :103630000A280CD00B280CD00C280CD00D280CD04C :103640000E2814BF4020302070470C2070471020F7 :1036500070471420704718207047202070470000E2 -:103660002DE9F041456A15B94162BDE8F0814B682A -:10367000AC4623F06047C3F38A464FEAD37EC3F3D8 -:10368000807816EA230638BF3E462B465A68BEEBC2 -:10369000D27F22F060440AD0002A18DAA40CB44287 -:1036A00017D19D420FD10D60DEE71346EEE7A7422A -:1036B00007D102F08044C2F3807242450BD054B16E -:1036C000EFE708D2EDE7CCF800100B60CDE7B4428D -:1036D00001D0B442E5D81A689C46002AE5D11960A9 -:1036E000C3E700002DE9F047089D01F0070400EB57 -:1036F000D1004FF47F494FEAD508224405F0070571 -:10370000944201D1BDE8F08704F0070705F0070AED -:10371000111B08EBD50E57453E4613F80EC038BFB7 -:103720005646C6F108068E4228BF0E46E108415CA7 -:1037300034443544B94029FA06F721FA0AF1FFB2B8 -:103740008CEA010147FA0AF739408CEA010C03F8C8 -:103750000EC0D5E780EA0120082341F2210201B220 -:10376000013B4000002980B2B8BF504013F0FF0376 -:10377000F5D1704738B50C468D18A54200D138BD3B -:1037800014F8011BFFF7E6FFF7E7000042684AB1B3 -:10379000136881894360438901339BB29942438115 -:1037A00038BF83811046704770B588B00446202228 -:1037B0000D4668460021FEF78DFA20460495FFF776 -:1037C000E5FF024660B16B46054608AE1C4608356B -:1037D00003CCB44245F8080C45F8041C2346F5D147 -:1037E000104608B070BD0000082817D909280CD071 -:1037F0000A280CD00B280CD00C280CD00D280CD08B -:103800000E2814BF4020302070470C207047102035 -:103810007047142070471820704720207047000020 -:10382000082817D90C280CD910280CD914280CD921 -:1038300018280CD920280CD930288CBF0F200E2036 -:103840007047092070470A2070470B2070470C20F2 -:1038500070470D20704700002DE9F843078C04469F -:10386000072F1ED900254FF6FF73D0E90298C5F146 -:103870002006A5F1200029FA05F1083508FA06F618 -:1038800028FA00F0314301431846C9B2FFF762FF3E -:10389000402D0346EBD13A46E169BDE8F843FFF716 -:1038A00069BF4FF6FF70BDE8F883000010B54B68A4 -:1038B00023B9CA8A63F30902CA8210BD04691A686F -:1038C0001C600361C38A013BC3824A60EFE70000CA -:1038D0002DE9F84F1D46CB8A0F468146C3F30901F7 -:1038E000924605290B4630D00020AAB207F11A04EF -:1038F0009EB21FFA80F8042E0FD8904503F1010301 -:1039000006D30A44FB8A62F309030120FB821AE012 -:103910001AF800600130E654EAE79045F1D2A1F1CF -:10392000050B1C237C68BBFBF3F203FB12BB1FFAE5 -:103930008BF6002C45D14846FFF728FF044638B9DE -:1039400078606FF00200BDE8F88F4FF00008E6E7FE -:10395000002606607860ADB24FF0000B454510D9E7 -:103960000AEB0803221D13F8011B08F10108915509 -:10397000B1B21FFA88F81B292BD0454506F1010684 -:10398000F1D8FB8AC3F30902154465F30903BCE7C8 -:1039900001321C4692B22368002BF9D16B1F0B44F5 -:1039A0001C21B3FBF1F301339BB29A42D3D2BBF19A -:1039B000000FD0D14846FFF7E9FE20B9C4F800B0A7 -:1039C000BFE70122E7E7C0F800B05E46206004468A -:1039D000C1E74545D5D94846FFF7D8FE08B920606C -:1039E000AFE7C0F800B0002620600446B6E700004C -:1039F0002DE9F04F1C46074688462DED028B83B01B -:103A00005B690192002B00F09A80238C2BB1E26954 -:103A1000002A00F09480072B35D807F10C00FFF73F -:103A2000B5FE054638B96FF00205284603B0BDEC77 -:103A3000028BBDE8F08F14220021FEF74BF9228C97 -:103A4000E16905F10800FEF71FF9208C48F00041FC -:103A5000013080B2FFF7E4FEFFF7C6FE013880B206 -:103A600020840130287438466369228C1B782A44EC -:103A700003F01F0363F03F03137269602946FFF7E9 -:103A8000EFFD0125D1E74FF0000900F10C034FF0E5 -:103A9000800A4E464D4608EE103A18EE100AFFF71F -:103AA00075FE83460028BED014220021FEF712F9CD -:103AB000002E3AD1019B0222ABF808300BF1080E20 -:103AC0001FFA82FC218C0CF10100BCF1060F80B2C0 -:103AD00001D88E422BD3FFF7A3FE8E4208BF4FF0D2 -:103AE000400AFFF781FE62690138013512781BFA3E -:103AF00080F1013002F01F022DB242EA491289F032 -:103B000001094AEA020A48F0004281F808A0594631 -:103B10008BF810003846CBF804204FF0000AFFF76E -:103B20009FFD238CB342B8D17FE70022C6E7E1694D -:103B3000895D01360EF80210B6B20132C0E76FF0AF -:103B4000010572E7F8B515460E46302200210446FD -:103B50001F46FEF7BFF8069BB5F5001FA760636020 -:103B600004F11000079B34BF6A094FF6FF72E6614B -:103B7000A362002397B29A4206D800230360A7826B -:103B8000E3822383E360F8BD0660013330462036CC -:103B9000F1E7000003781BB94BB2002BC8BF0170DE -:103BA0007047000000787047F8B50C46C9690746B1 -:103BB00011B9238C002B37D1257E1F2D34D83878AE -:103BC00028BB228C072A2CD8268A36F003032BD157 -:103BD0004FF6FF70FFF7CEFD20F0010031024FF6E7 -:103BE000FF72400441EA0561400C41EA402523464A -:103BF00029463846FFF7FCFE002807DD6269137886 -:103C00000133DBB21F2B88BF00231370F8BD218A5C -:103C10002D0645EA012505432046FFF71DFE024615 -:103C2000E5E76FF00300F1E76FF00100EEE7000059 -:103C300070B58AB0044616460021282268461D4603 -:103C4000FEF748F8BDF8383069462046ADF8103028 -:103C50000F9B05939DF840308DF81830119B07930A -:103C6000BDF84830CDE90265ADF82030FFF79CFF84 -:103C70000AB070BD2DE9F041D36905460C461646E1 -:103C80000BB9138C5BBB377E1F2F28D895F80080AB -:103C9000B8F1000F26D03046FFF7DEFD3378210261 -:103CA0000246284641EAC331338A41EA080141EA23 -:103CB000076141EA0341334641F08001FFF798FE76 -:103CC00000280ADD3378012B07D17269137801339C -:103CD000DBB21F2B88BF00231370BDE8F0816FF0AB -:103CE0000100FAE76FF00300F7E70000F0B58BB0D2 -:103CF00004460D4617460021282268461E46FDF759 -:103D0000E9FF9DF84C30294620465A1E5342534144 -:103D10006A468DF800309DF84030ADF81030119BA8 -:103D200005939DF848308DF81830149B0793BDF823 -:103D30005430CDE90276ADF82030FFF79BFF0BB091 -:103D4000F0BD0000406A00B104307047436A1A6851 -:103D5000426202691A600361C38A013BC3827047F1 -:103D60002DE9F041D0F8208014461D46184E4146FA -:103D7000002709B9BDE8F081D1E90223A21A65EB59 -:103D80000303964277EB03031ED2036A8B420DD1E5 -:103D9000FFF78CFD036A1B68036203690B60C38A2B -:103DA0000161013B016AC3828846E2E7FFF77EFDBD -:103DB0000B68C8F8003003690B60C38A0161013BDE -:103DC000C382D8F80010D4E788460968D1E700BF5D -:103DD00080841E002DE9F04F8BB00D4614469B46A3 -:103DE000DDF850908046002800F01881B9F1000FEE -:103DF00000F01481531E3F2B00F21081012A03D1E1 -:103E0000BBF1000F40F00A810023CDE90833B8F878 -:103E10001430B5EBC30F4FEAC30703D300200BB038 -:103E2000BDE8F08F2B199F42D8F80C3036BF7F1BAE -:103E30002746FFB21BB9D8F81030002B7AD0272DB7 -:103E40004DD8C5F1280600232946B742009308AB98 -:103E5000D8F808002CBFF6B23E46A7EB060A354458 -:103E600032465FFA8AFAFFF73DFCB8F81430282191 -:103E700003F10053053BDB000493D8F80C300393A7 -:103E8000039B13B1BAF1000F2CD1D8F8100040B148 -:103E9000BAF1000F05D008AB5246691A0096FFF739 -:103EA00021FC38B2002FB9D066070AD00AAB6242B3 -:103EB00003EBD40102F0070211F8083C134101F8AA -:103EC000083C082C3DD9102C40F2B580202C40F243 -:103ED000B780BBF1000F00F09C80082335E0BA46A4 -:103EE0000026C2E7049BE02B28BFE02306930B4487 -:103EF000AB42059315D95A1B0398691A009692454F -:103F000008AB00F1040034BF5246D2B20792FFF76B -:103F1000E9FB079A1644AAEB020A1544F6B25FFAC7 -:103F20008AFA049B069A05999B1A0493039B1B68C3 -:103F30000393A5E700933A4608AB2946D8F8080052 -:103F4000ADE7BBF1000F13D00123B4EBC30F6BD06F -:103F5000082C12D89DF82030621E23FA02F2D507F1 -:103F600006D54FF0FF3202FA04F423438DF82030D7 -:103F70009DF8203089F8003051E7102C12D8BDF898 -:103F80002030621E23FA02F2D10706D54FF0FF322D -:103F900002FA04F42343ADF82030BDF82030A9F82C -:103FA00000303CE7202C0FD80899631E21FA03F358 -:103FB000DA0705D54FF0FF3202FA04F40C430894F7 -:103FC000089BC9F800302AE7402C2AD0611EC4F1B2 -:103FD0002102A4F12103DDE9086526FA01F105FAC1 -:103FE00002F225FA03F311431943CB0711D501223D -:103FF000A4F12003C4F1200102FA03F322FA01F133 -:10400000A2400B43524263EB430332432B43CDE9BF -:104010000823DDE90823C9E9002300E76FF0010068 -:10402000FDE66FF00800FAE6082CA1D9102CB4D9EF -:10403000202CEED8C4E7BBF1000FAED0022384E7FA -:10404000BBF1000FBCD004237FE70000012A30B58C -:10405000144638BF012485B00025402C28BF4024D9 -:10406000012ACDE9025518D81B788DF8083063076E -:104070000AD004AB624203EBD40502F0070215F844 -:10408000083C934005F8083C034600912246002175 -:1040900002A8FFF727FB05B030BD082AE4D9102A93 -:1040A00003D81B88ADF80830E1E7202A95BF1B68CC -:1040B000D3E900230293CDE90223D8E710B5CB68FA -:1040C0001BB98B600B618B8210BD04691A681C6080 -:1040D0000361C38A013BC382CA60F0E703064CBF99 -:1040E000C0F3C0300220704708B50246FFF7F6FF64 -:1040F000022806D15306C2F30F2001D100F00300BD -:1041000008BDC2F30740FBE72DE9F04F93B004462A -:104110000D46CDE903230A681046FFF7DFFF0228AA -:10412000824614BFC2F306260026002A80F2F381DD -:1041300012F0C04940F0EF81097B002900F0EB81CB -:10414000022803D02378B34240F0E881C2F304632D -:1041500010462944069302F07F030593FFF7C4FF3E -:10416000059B002283464FEA8348002348EA0A4819 -:1041700048EA4668CE78CDE90823F30948EA000802 -:10418000029368D0059B024608A920460093534637 -:104190006768B847002800F0C481276A4FB94146D4 -:1041A00004F10C00FFF700FB074690B96FF0020026 -:1041B00055E03B6998450DD03F68002FF9D1414645 -:1041C00004F10C00FFF7F0FA07460028EED0236A4E -:1041D0003B60276297F817C006F01F08CCF3840CE9 -:1041E000ACEB0800A8EB0C031FFA80FE0028B8BF58 -:1041F0000EF120001FFA83FEB8BF00B2002B079318 -:10420000B8BF0EF12003D7E90221BCBF1BB2079350 -:1042100052EA010338D0039B4FF0000CDFF820E393 -:104220009A1A049B63EB010196457CEB01032BD3A7 -:104230006B7B97F81AE0734519D1029B002B78D05D -:10424000012821DC7868F8B9DFF8F0C2944570EBFA -:10425000010316D337E0276A27B96FF00C0013B0BB -:10426000BDE8F08F3B699845B4D03F68F4E7B348A8 -:1042700090427CEB010301D30020F0E7029B002B6E -:10428000FAD0079B0F2B17DCFA7DB3003946204686 -:1042900002F0030203F07C031343FB75FFF706FBF8 -:1042A0006B7BBB76029B3BB9FB7DC3F3840201327F -:1042B00062F38603FB75D0E76A7BBB7E9A42DBD153 -:1042C000029B002B35D0B309022B32D0039B142262 -:1042D00000210DA8BB60049BFB60FDF7FBFC039B6A -:1042E0000AA920460A93049BADF83EB00B932B1D00 -:1042F0008DF840A00C932B7B8DF84180013BDBB205 -:10430000ADF83C30069B8DF84230059B8DF843306C -:1043100094F82C3083F001038DF84430A36898475B -:10432000FB7DC3F38403013303F01F039B02FB8275 -:10433000A2E7FB7DC6F34012B2EBD31F40F0F4803E -:10434000C3F38403434540F0F280029AB6092B7B05 -:10435000002A4DD0F2075DD4032B40F2EB80039B83 -:10436000AE1D394604F10C00BB603246049BFB6075 -:104370002B7B033BDBB2FFF7ABFA00280CDA3946A4 -:104380002046FFF793FAFB7DC3F38403013303F068 -:104390001F039B02FB8209E7AB88DDE908843B83AE -:1043A0004FF6FF73C9F12000A9F1200228FA09F1A4 -:1043B00009F1080904FA00F024FA02F20143184650 -:1043C0001143C9B2FFF7C6F9B9F1400F0346E9D16D -:1043D000B88231462A7B033AD2B2FFF7CBF9FB7D94 -:1043E000B882DA43C2F3C01262F3C713FB7543E726 -:1043F00086B92E1D013B394604F10C00DBB2324672 -:10440000FFF766FA0028BADB2A7B3146B88A013A00 -:10441000D2B2E2E7F98A013BC1F30901DAB2042919 -:104420005BD8281D002307F11B069A4208D910F813 -:1044300001CB013306F801C00131DBB20529F4D10B -:10444000039993420A9138BF043304992CBF002387 -:1044500055FA83F30B9107F11B010C9179680E93C8 -:104460000D91291DFB8AADF83EB0C3F309038DF809 -:1044700040A08DF841801A44069B8DF84230059B80 -:10448000ADF83C208DF8433094F82C3083F00103D4 -:104490008DF844300023B88A7B602A7B013AFFF70D -:1044A00069F93B8BB882834203D1A3680AA92046ED -:1044B000984720460AA9FFF701FEFB7DBA8AC3F39D -:1044C0008403013303F01F039B02FB823B8B9A4260 -:1044D0000CBF00206FF01000C1E67B68002BAFD04E -:1044E000052001E01C3033461E68002EFAD1091A5F -:1044F0002E1D081D184401EB090C5FFA89F3BCF16D -:104500001B0F9DD89A429BD916F8013B09F101096E -:1045100000F8013BEFE76FF00900A0E66FF00A003A -:104520009DE66FF00B009AE66FF00D0097E66FF0D6 -:104530000E0094E66FF00F0091E600BF40420F00BE -:1045400080841E00EFF30983054968334A6B22F02B -:1045500001024A6383F30988002383F311887047BB -:1045600000EF00E0302080F3118862B60D4B0E4A58 -:10457000D96821F4E0610904090C0A430B49DA60A7 -:10458000D3F8FC2042F08072C3F8FC20084AC2F83D -:10459000B01F116841F0010111602022DA7783F821 -:1045A0002200704700ED00E00003FA0555CEACC5CF -:1045B000001000E0302310B583F311880E4B5B68C8 -:1045C00013F4006314D0F1EE103AEFF309844FF0C6 -:1045D0008073683CE361094BDB6B236684F30988D5 -:1045E00000F0A8FF10B1064BA36110BD054BFBE71F -:1045F00083F31188F9E700BF00ED00E000EF00E071 -:104600004307000846070008026843681143016039 -:1046100003B1184770470000024A136843F0C00313 -:10462000136070470078004013B50E4C204600F030 -:10463000A7FA04F1140000234FF400720A49009411 -:1046400000F064F9094B4FF40072094904F1380095 -:10465000009400F0DDF9074A074BC4E9172302B0C4 -:1046600010BD00BF34630020A0630020194600087D -:10467000A06500200078004000E1F505037C30B51E -:10468000244C002918BF0C46012B11D1224B984213 -:104690000ED1224BD3F8E82042F08042C3F8E82044 -:1046A000D3F8102142F08042C3F81021D3F8103122 -:1046B0002268036EC16D03EB52038466B3FBF2F311 -:1046C0006268150442BF23F0070503F0070343EABD -:1046D0004503CB60A36843F040034B60E36843F0BD -:1046E00001038B6042F4967343F001030B604FF0BB -:1046F000FF330B62510505D512F0102205D0B2F13F -:10470000805F04D080F8643030BD7F23FAE73F2318 -:10471000F8E700BF90790008346300200044025895 -:104720002DE9F047C66D05463768F4692107346204 -:104730001AD014F0080118BF4FF48071E20748BF87 -:1047400041F02001A3074FF0300348BF41F0400182 -:10475000600748BF41F0800183F31188281DFFF7EF -:1047600053FF002383F31188E2050AD5302383F336 -:1047700011884FF48061281DFFF746FF002383F363 -:1047800011884FF030094FF0000A14F0200838D19A -:104790003B0616D54FF0300905F1380A200610D532 -:1047A00089F31188504600F067F9002836DA0821AD -:1047B000281DFFF729FF27F080033360002383F3D0 -:1047C0001188790614D5620612D5302383F3118837 -:1047D000D5E913239A4208D12B6C33B127F0400757 -:1047E0001021281DFFF710FF3760002383F3118885 -:1047F000E30618D5AA6E1369ABB15069BDE8F0475E -:10480000184789F31188736A284695F8641019408F -:1048100000F0D0F98AF31188F469B6E7B06288F342 -:104820001188F469BAE7BDE8F0870000090100F1DA -:104830006043012203F56143C9B283F8001300F01D -:104840001F039A4043099B0003F1604303F5614352 -:10485000C3F880211A607047F8B51546826804468F -:104860000B46AA4200D28568A1692669761AB5422C -:104870000BD218462A46FDF707FAA3692B44A36119 -:104880002846A3685B1BA360F8BD0CD9AF1B184674 -:104890003246FDF7F9F93A46E1683044FDF7F4F99C -:1048A000E3683B44EBE718462A46FDF7EDF9E36879 -:1048B000E5E7000083689342F7B50446154600D249 -:1048C0008568D4E90460361AB5420BD22A46FDF752 -:1048D000DBF963692B4463612846A3685B1BA36013 -:1048E00003B0F0BD0DD93246AF1B0191FDF7CCF9F5 -:1048F00001993A46E0683144FDF7C6F9E3683B4464 -:10490000E9E72A46FDF7C0F9E368E4E710B50A4491 -:104910000024C361029B8460C16002610362C0E93C -:104920000000C0E9051110BD08B5D0E90532934279 -:1049300001D1826882B98268013282605A1C426168 -:1049400019700021D0E904329A4224BFC368436140 -:1049500000F0C2FE002008BD4FF0FF30FBE7000072 -:1049600070B5302304460E4683F31188A568A5B1BF -:10497000A368A269013BA360531CA3611578226957 -:10498000934224BFE368A361E3690BB120469847D3 -:10499000002383F31188284607E03146204600F0C3 -:1049A0008BFE0028E2DA85F3118870BD2DE9F74F00 -:1049B00004460E4617469846D0F81C904FF0300A31 -:1049C0008AF311884FF0000B154665B12A4631462F -:1049D0002046FFF741FF034660B94146204600F0FC -:1049E0006BFE0028F1D0002383F31188781B03B0FD -:1049F000BDE8F08FB9F1000F03D001902046C84701 -:104A0000019B8BF31188ED1A1E448AF31188DCE7B1 -:104A1000C160C361009B82600362C0E9051111445B -:104A2000C0E9000001617047F8B504460D4616461E -:104A3000302383F31188A768A7B1A368013BA36063 -:104A400063695A1C62611D70D4E904329A4224BF22 -:104A5000E3686361E3690BB120469847002080F367 -:104A6000118807E03146204600F026FE0028E2DAF1 -:104A700087F31188F8BD0000D0E9052310B59A42EC -:104A800001D182687AB982680021013282605A1CA1 -:104A900082611C7803699A4224BFC368836100F075 -:104AA0001BFE204610BD4FF0FF30FBE72DE9F74F0E -:104AB00004460E4617469846D0F81C904FF0300A30 -:104AC0008AF311884FF0000B154665B12A4631462E -:104AD0002046FFF7EFFE034660B94146204600F04E -:104AE000EBFD0028F1D0002383F31188781B03B07D -:104AF000BDE8F08FB9F1000F03D001902046C84700 -:104B0000019B8BF31188ED1A1E448AF31188DCE7B0 -:104B1000026843681143016003B118477047000001 -:104B20001430FFF743BF00004FF0FF331430FFF79E -:104B30003DBF00003830FFF7B9BF00004FF0FF3332 -:104B40003830FFF7B3BF00001430FFF709BF000093 -:104B50004FF0FF311430FFF703BF00003830FFF78C -:104B600063BF00004FF0FF323830FFF75DBF000039 -:104B7000012914BF6FF0130000207047FFF754BDE8 -:104B8000044B036000234360C0E902330123037434 -:104B9000704700BFA879000810B53023044683F39E -:104BA0001188FFF76BFD02230020237480F3118826 -:104BB00010BD000038B5C36904460D461BB9042179 -:104BC0000844FFF7A5FF294604F11400FFF7ACFEE7 -:104BD000002806DA201D4FF40061BDE83840FFF7D9 -:104BE00097BF38BD026843681143016003B118479D -:104BF0007047000013B5406B00F58054D4F8A4381A -:104C00001A681178042914D1017C022911D119796B -:104C1000012312898B4013420BD101A94C3002F0C1 -:104C200019F9D4F8A4480246019B2179206800F0C4 -:104C3000DFF902B010BD0000143002F09BB8000094 -:104C40004FF0FF33143002F095B800004C3002F002 -:104C50006DB900004FF0FF334C3002F067B900002F -:104C6000143002F069B800004FF0FF31143002F048 -:104C700063B800004C3002F039B900004FF0FF3249 -:104C80004C3002F033B900000020704710B500F539 -:104C90008054D4F8A4381A681178042917D1017CFB -:104CA000022914D15979012352898B4013420ED124 -:104CB000143001F0FBFF024648B1D4F8A4484FF489 -:104CC000407361792068BDE8104000F07FB910BDE5 -:104CD000406BFFF7DBBF0000704700007FB5124B51 -:104CE00001250426044603600023057400F18402B4 -:104CF00043602946C0E902330C4B02901430019303 -:104D00004FF44073009601F0ADFF094B04F6944256 -:104D1000294604F14C000294CDE900634FF440733E -:104D200002F074F804B070BDD0790008D14C0008CE -:104D3000F54B00080A68302383F311880B790B3395 -:104D400042F823004B79133342F823008B7913B1D7 -:104D50000B3342F8230000F58053C3F8A418022354 -:104D60000374002080F311887047000038B5037F7A -:104D7000044613B190F85430ABB90125201D02212F -:104D8000FFF730FF04F114006FF00101257700F008 -:104D9000AFFC04F14C0084F854506FF00101BDE801 -:104DA000384000F0A5BC38BD10B5012104460430E0 -:104DB000FFF718FF0023237784F8543010BD00005C -:104DC00038B504460025143001F064FF04F14C00AE -:104DD000257702F033F8201D84F854500121FFF7A5 -:104DE00001FF2046BDE83840FFF750BF90F8803003 -:104DF00003F06003202B06D190F881200023212AA4 -:104E000003D81F2A06D800207047222AFBD1C0E908 -:104E10001D3303E0034A426707228267C36701200C -:104E2000704700BF3C22002037B500F58055D5F80B -:104E3000A4381A68117804291AD1017C022917D1E3 -:104E40001979012312898B40134211D100F14C04CE -:104E5000204602F0B3F858B101A9204601F0FAFF4C -:104E6000D5F8A4480246019B2179206800F0C0F8DB -:104E700003B030BD01F10B03F0B550F8236085B0ED -:104E800004460D46FEB1302383F3118804EB8507F9 -:104E9000301D0821FFF7A6FEFB6806F14C005B6998 -:104EA0001B681BB1019001F0E3FF019803A901F019 -:104EB000D1FF024648B1039B2946204600F098F8EE -:104EC000002383F3118805B0F0BDFB685A691268AE -:104ED000002AF5D01B8A013B1340F1D104F1800276 -:104EE000EAE70000133138B550F82140ECB1302327 -:104EF00083F3118804F58053D3F8A42813685279FA -:104F000003EB8203DB689B695D6845B1042160188F -:104F1000FFF768FE294604F1140001F0D1FE204697 -:104F2000FFF7B4FE002383F3118838BD70470000FB -:104F300001F09EB901234022002110B5044600F87B -:104F4000303BFCF7C7FE0023C4E9013310BD00006D -:104F500010B53023044683F31188242241600021D8 -:104F60000C30FCF7B7FE204601F0A4F90223002024 -:104F7000237080F3118810BD70B500EB81030546E6 -:104F800050690E461446DA6018B110220021FCF771 -:104F9000A1FEA06918B110220021FCF79BFE31464A -:104FA0002846BDE8704001F08BBA000083682022DB -:104FB000002103F0011310B5044683601030FCF7A4 -:104FC00089FE2046BDE8104001F006BBF0B4012583 -:104FD00000EB810447898D40E4683D43A469458125 -:104FE00023600023A2606360F0BC01F023BB0000DB -:104FF000F0B4012500EB810407898D40E4683D434E -:105000006469058123600023A2606360F0BC01F045 -:1050100099BB000070B502230025044624220370CA -:105020002946C0F888500C3040F8045CFCF752FE6A -:10503000204684F8705001F0D7F963681B6823B1EB -:1050400029462046BDE87040184770BD0378052BFF -:1050500010B504460AD080F88C30052303704368ED -:105060001B680BB1042198470023A36010BD00000A -:105070000178052906D190F88C20436802701B68DE -:1050800003B118477047000070B590F870300446BF -:1050900013B1002380F8703004F18002204601F043 -:1050A000BFFA63689B68B3B994F8803013F0600569 -:1050B00035D00021204601F0B1FD0021204601F04D -:1050C000A1FD63681B6813B106212046984706239B -:1050D00084F8703070BD204698470028E4D0B4F8BA -:1050E0008630A26F9A4288BFA36794F98030A56F7B -:1050F000002B4FF0300380F20381002D00F0F2808E -:10510000092284F8702083F3118800212046D4E915 -:105110001D23FFF76DFF002383F31188DAE794F86E -:10512000812003F07F0343EA022340F202329342DC -:1051300000F0C58021D8B3F5807F48D00DD8012B71 -:105140003FD0022B00F09380002BB2D104F18802F3 -:1051500062670222A267E367C1E7B3F5817F00F0CF -:105160009B80B3F5407FA4D194F88230012BA0D16D -:10517000B4F8883043F0020332E0B3F5006F4DD04D -:1051800017D8B3F5A06F31D0A3F5C063012B90D829 -:105190006368204694F882205E6894F88310B4F81F -:1051A0008430B047002884D0436863670368A367EE -:1051B0001AE0B3F5106F36D040F6024293427FF406 -:1051C00078AF5C4B63670223A3670023C3E794F8BF -:1051D0008230012B7FF46DAFB4F8883023F00203E6 -:1051E000A4F88830C4E91D55E56778E7B4F8803045 -:1051F000B3F5A06F0ED194F88230204684F88A303F -:1052000001F050F963681B6813B1012120469847EB -:10521000032323700023C4E91D339CE704F18B03AF -:1052200063670123C3E72378042B10D1302383F372 -:1052300011882046FFF7BAFE85F3118803216368C1 -:1052400084F88B5021701B680BB12046984794F866 -:105250008230002BDED084F88B3004232370636807 -:105260001B68002BD6D0022120469847D2E794F83D -:10527000843020461D0603F00F010AD501F0C2F963 -:10528000012804D002287FF414AF2B4B9AE72B4B54 -:1052900098E701F0A9F9F3E794F88230002B7FF446 -:1052A00008AF94F8843013F00F01B3D01A062046EB -:1052B00002D501F0CBFCADE701F0BCFCAAE794F805 -:1052C0008230002B7FF4F5AE94F8843013F00F0198 -:1052D000A0D01B06204602D501F0A0FC9AE701F001 -:1052E00091FC97E7142284F8702083F311882B46F1 -:1052F0002A4629462046FFF769FE85F31188E9E62C -:105300005DB1152284F8702083F3118800212046B6 -:10531000D4E91D23FFF75AFEFDE60B2284F8702026 -:1053200083F311882B462A4629462046FFF760FE64 -:10533000E3E700BF007A0008F8790008FC7900086C -:1053400038B590F870300446002B3ED0063BDAB2F8 -:105350000F2A34D80F2B32D8DFE803F03731310869 -:10536000223231313131313131313737856FB0F857 -:1053700086309D4214D2C3681B8AB5FBF3F203FB4F -:1053800012556DB9302383F311882B462A462946DE -:10539000FFF72EFE85F311880A2384F870300EE0A3 -:1053A000142384F87030302383F3118800232046BF -:1053B0001A461946FFF70AFE002383F3118838BD09 -:1053C000C36F03B198470023E7E70021204601F0AF -:1053D00025FC0021204601F015FC63681B6813B111 -:1053E0000621204698470623D7E7000010B590F81D -:1053F00070300446142B29D017D8062B05D001D8BD -:105400001BB110BD093B022BFBD80021204601F047 -:1054100005FC0021204601F0F5FB63681B6813B111 -:10542000062120469847062319E0152BE9D10B23C6 -:1054300080F87030302383F3118800231A46194610 -:10544000FFF7D6FD002383F31188DAE7C3689B6971 -:105450005B68002BD5D1C36F03B19847002384F854 -:105460007030CEE700238268037503691B68996872 -:105470009142FBD25A6803604260106058607047E6 -:1054800000238268037503691B6899689142FBD801 -:105490005A680360426010605860704708B508465B -:1054A000302383F311880B7D032B05D0042B0DD003 -:1054B0002BB983F3118808BD8B6900221A604FF065 -:1054C000FF338361FFF7CEFF0023F2E7D1E900321B -:1054D00013605A60F3E70000FFF7C4BF054BD968BB -:1054E00008751868026853601A600122D860027556 -:1054F000FBF712B9A06700200C4B30B5DD684B1CE0 -:1055000087B004460FD02B46094A684600F084F95C -:105510002046FFF7E3FF009B13B1684600F086F9D1 -:10552000A86907B030BDFFF7D9FFF9E7A0670020F1 -:105530009D540008044B1A68DB6890689B68984289 -:1055400094BF002001207047A0670020084B10B5D1 -:105550001C68D868226853601A600122DC602275DA -:10556000FFF78EFF01462046BDE81040FBF7D4B898 -:10557000A0670020044B1A68DB6892689B689A4217 -:1055800001D9FFF7E3BF7047A067002038B5074C8B -:1055900001230025064907482370656001F04CFD92 -:1055A0000223237085F3118838BD00BF086A0020EC -:1055B000087A0008A067002008B572B6044B186589 -:1055C00000F06EFC00F040FD024B03221A70FEE773 -:1055D000A0670020086A002000F05EB9EFF3118098 -:1055E00020B9EFF30583302282F311887047000061 -:1055F00010B530B9EFF30584C4F3080414B180F397 -:10560000118810BDFFF7B6FF84F31188F9E7000099 -:10561000034A516853685B1A9842FBD8704700BF31 -:10562000001000E08B600223086108468B827047FF -:105630008368A3F1840243F8142C026943F8442CD4 -:10564000426943F8402C094A43F8242CC268A3F16C -:10565000200043F8182C022203F80C2C002203F837 -:105660000B2C034A43F8102C704700BF3107000889 -:10567000A067002008B5FFF7DBFFBDE80840FFF793 -:105680002BBF0000024BDB6898610F20FFF726BF9D -:10569000A0670020302383F31188FFF7F3BF0000D9 -:1056A00008B50146302383F311880820FFF724FF53 -:1056B000002383F3118808BD064BDB6839B14268CB -:1056C00018605A60136043600420FFF715BF4FF065 -:1056D000FF307047A06700200368984206D01A6820 -:1056E0000260506018469961FFF7F6BE70470000EF -:1056F00038B504460D462068844200D138BD0368A1 -:1057000023605C608561FFF7E7FEF4E7036810B58E -:105710009C68A2420CD85C688A600B604C60216077 -:10572000596099688A1A9A604FF0FF33836010BD00 -:10573000121B1B68ECE700000A2938BF0A2170B56C -:1057400004460D460A26601901F06EFC01F056FC75 -:10575000041BA54203D8751C04462E46F3E70A2E07 -:1057600004D90120BDE8704001F0A6BC70BD000066 -:10577000F8B5144B0D460A2A4FF00A07D96103F118 -:105780001001826038BF0A22416019691446016025 -:1057900048601861A81801F037FC01F02FFC431B8A -:1057A0000646A34206D37C1C28192746354601F03D -:1057B0003BFCF2E70A2F04D90120BDE8F84001F0D4 -:1057C0007BBCF8BDA0670020F8B506460D4601F089 -:1057D00015FC0F4A134653F8107F9F4206D12A4604 -:1057E00001463046BDE8F840FFF7C2BFD169BB684B -:1057F000441A2C1928BF2C46A34202D92946FFF788 -:105800009BFF224631460348BDE8F840FFF77EBFC4 -:10581000A0670020B0670020C0E90323002310B474 -:105820005DF8044B4361FFF7CFBF000010B5194C82 -:10583000236998420DD08168D0E9003213605A6024 -:105840009A680A449A60002303604FF0FF33A36113 -:1058500010BD0268234643F8102F536000220260F7 -:1058600022699A4203D1BDE8104001F0D7BB93688A -:1058700081680B44936001F0C1FB2269E169926881 -:10588000441AA242E4D91144BDE81040091AFFF7B6 -:1058900053BF00BFA06700202DE9F047DFF8BC80B0 -:1058A00008F110072C4ED8F8105001F0A7FBD8F8DB -:1058B0001C40AA68031B9A423ED814444FF00009CA -:1058C000D5E90032C8F81C4013605A60C5F8009052 -:1058D000D8F81030B34201D101F0A0FB89F3118850 -:1058E000D5E9033128469847302383F311886B6943 -:1058F000002BD8D001F082FB6A69A0EB0409824634 -:105900004A450DD2022001F0D7FB0022D8F8103012 -:10591000B34208D151462846BDE8F047FFF728BFFB -:10592000121A2244F2E712EB09092946384638BF19 -:105930004A46FFF7EBFEB5E7D8F81030B34208D07F -:105940001444C8F81C00211AA960BDE8F047FFF70D -:10595000F3BEBDE8F08700BFB0670020A06700205D -:1059600000207047FEE70000704700004FF0FF3056 -:105970007047000002290CD0032904D001290748F0 -:1059800018BF00207047032A05D8054800EBC20065 -:105990007047044870470020704700BFE07A000855 -:1059A0004C220020947A000870B59AB0054608464B -:1059B000144601A900F0C2F801A8FCF783F9431CC2 -:1059C0000022C6B25B001046C5E9003423700323F1 -:1059D000023404F8013C01ABD1B202348E4201D84A -:1059E0001AB070BD13F8011B013204F8010C04F861 -:1059F000021CF1E708B5302383F311880348FFF751 -:105A000013FA002383F3118808BD00BF106A002039 -:105A100090F8803003F01F02012A07D190F881200E -:105A20000B2A03D10023C0E91D3315E003F0600306 -:105A3000202B08D1B0F884302BB990F88120212A8E -:105A400003D81F2A04D8FFF7D1B9222AEBD0FAE7EE -:105A5000034A426707228267C3670120704700BF7D -:105A60004322002007B5052917D8DFE801F01916F1 -:105A700003191920302383F31188104A0121019062 -:105A8000FFF77AFA019802210D4AFFF775FA0D48DF -:105A9000FFF796F9002383F3118803B05DF804FB48 -:105AA000302383F311880748FFF760F9F2E73023CA -:105AB00083F311880348FFF777F9EBE7347A00089E -:105AC000587A0008106A002038B50C4D0C4C2A4654 -:105AD0000C4904F10800FFF767FF05F1CA0204F161 -:105AE00010000949FFF760FF05F5CA7204F11800BC -:105AF0000649BDE83840FFF757BF00BFE8820020E5 -:105B00004C220020147A00081E7A0008297A000826 -:105B100070B5044608460D46FCF7D4F8C6B22046D8 -:105B2000013403780BB9184670BD32462946FCF79C -:105B3000B5F80028F3D10120F6E700002DE9F04781 -:105B400005460C46FCF7BEF82C49C6B22846FFF7BE -:105B5000DFFF08B11036F6B229492846FFF7D8FF13 -:105B600008B11036F6B2632E0BD8DFF89080DFF85C -:105B70009090244FDFF898A02E7846B92670BDE8A3 -:105B8000F08729462046BDE8F04701F075BE252E76 -:105B900030D1072241462846FCF780F880B91A4BDD -:105BA000224603F1140153F8040B8B4242F8040B14 -:105BB000F9D1198807359B78173411809370DBE78A -:105BC000082249462846FCF769F898B9A21C0F4BF1 -:105BD000197802320909C95D02F8041C13F8011B87 -:105BE00001F00F015345C95D02F8031CF0D11834D0 -:105BF0000835C1E7013504F8016BBDE7007B0008FB -:105C0000297A0008087B00089678000800E8F11F50 -:105C10000CE8F11FBFF34F8F044B1A695107FCD1F9 -:105C2000D3F810215207F8D1704700BF002000526E -:105C300008B50D4B1B78ABB9FFF7ECFF0B4BDA68DF -:105C4000D10704D50A4A5A6002F188325A60D3F863 -:105C50000C21D20706D5064AC3F8042102F1883286 -:105C6000C3F8042108BD00BF468500200020005273 -:105C70002301674508B5114B1B78F3B9104B1A691E -:105C8000510703D5DA6842F04002DA60D3F81021F8 -:105C9000520705D5D3F80C2142F04002C3F80C217D -:105CA000FFF7B8FF064BDA6842F00102DA60D3F87A -:105CB0000C2142F00102C3F80C2108BD46850020EA -:105CC000002000520F289ABF00F580604004002099 -:105CD000704700004FF400307047000010207047FC -:105CE0000F2808B50BD8FFF7EDFF00F50033026869 -:105CF000013204D104308342F9D1012008BD0020D3 -:105D0000FCE700000F2838B505463FD8FFF782FFB3 -:105D10001F4CFFF78DFF4FF0FF3307286361C4F876 -:105D200014311DD82361FFF775FF030243F02403EC -:105D3000E360E36843F08003E36023695A07FCD41F -:105D40002846FFF767FFFFF7BDFF4FF4003100F073 -:105D500057F92846FFF78EFFBDE83840FFF7C0BF70 -:105D6000C4F81031FFF756FFA0F108031B0243F0FF -:105D70002403C4F80C31D4F80C3143F08003C4F888 -:105D80000C31D4F810315B07FBD4D9E7002038BDC3 -:105D9000002000522DE9F84F05460C46104645EA12 -:105DA0000203DE0602D00020BDE8F88F20F01F00BD -:105DB000DFF8BCB0DFF8BCA0FFF73AFF04EB000847 -:105DC000444503D10120FFF755FFEDE72022294686 -:105DD000204601F01FFD10B920352034F0E72B4696 -:105DE00005F120021F68791CDDD104339A42F9D1F4 -:105DF00005F178431B481C4EB3F5801F1B4B38BF81 -:105E0000184603F1F80332BFD946D1461E46FFF7C4 -:105E100001FF0760A5EB040C336804F11C0143F09B -:105E200002033360231FD9F8007017F00507FAD179 -:105E300053F8042F8B424CF80320F4D1BFF34F8F5B -:105E4000FFF7E8FE4FF0FF3320222146036028468B -:105E5000336823F00203336001F0DCFC0028BBD080 -:105E60003846B0E7142100520C2000521420005292 -:105E7000102000521021005210B5084C237828B190 -:105E80001BB9FFF7D5FE0123237010BD002BFCD0FA -:105E90002070BDE81040FFF7EDBE00BF4685002032 -:105EA00038B5054D00240334696855F80C0B00F033 -:105EB000B9F8122CF7D138BD1C7B0008084601F058 -:105EC000A1BC000070B5104E82B0FFF787FB0546FD -:105ED00001F094F8326803469042336037BF0B4AB2 -:105EE0000A495168146836BF0131D1E90041516057 -:105EF0000419284641F100010191FFF779FB204682 -:105F0000019902B070BD00BF488500205085002077 -:105F100070B5124E82B0FFF761FB054601F06EF8D6 -:105F2000326803469042336037BF0D4A0C495168CE -:105F3000146836BF0131D1E9004151600419284687 -:105F400041F100010191FFF753FB4FF47A720023F6 -:105F500020460199FAF7CCF902B070BD48850020BF -:105F6000508500200244074BD2B210B5904200D1B8 -:105F700010BD441C00B253F8200041F8040BE0B2FD -:105F8000F4E700BF504000580E4B30B51C6F24049E -:105F900005D41C6F1C671C6F44F400441C670A4C3A -:105FA00002442368D2B243F480732360074B9042CB -:105FB00000D130BD441C51F8045B00B243F82050BE -:105FC000E0B2F4E70044025800480258504000583C -:105FD00007B5012201A90020FFF7C4FF019803B013 -:105FE0005DF804FB13B50446FFF7F2FFA04205D0AD -:105FF000012201A900200194FFF7C6FF02B010BDE5 -:106000000144BFF34F8F064B884204D3BFF34F8F39 -:10601000BFF36F8F7047C3F85C022030F4E700BF16 -:1060200000ED00E00144BFF34F8F064B884204D3DC -:10603000BFF34F8FBFF36F8F7047C3F870022030EC -:10604000F4E700BF00ED00E070470000074B45F2A9 -:1060500055521A6002225A6040F6FF729A604CF65E -:10606000CC421A600122024B1A7070470048005857 -:106070005C850020034B1B781BB1034B4AF6AA2218 -:106080001A6070475C85002000480058034B1A686E -:106090001AB9034AD2F8D0241A60704758850020F4 -:1060A00000400258024B4FF48032C3F8D0247047AE -:1060B0000040025808B5FFF7E9FF024B1868C0F32B -:1060C000806008BD5885002070B5BFF34F8FBFF3C7 -:1060D0006F8F1A4A0021C2F85012BFF34F8FBFF3DF -:1060E0006F8F536943F400335361BFF34F8FBFF396 -:1060F0006F8FC2F88410BFF34F8FD2F8803043F611 -:10610000E074C3F3C900C3F34E335B0103EA040632 -:10611000014646EA81750139C2F86052F9D2203B46 -:1061200013F1200FF2D1BFF34F8F536943F4803343 -:106130005361BFF34F8FBFF36F8F70BD00ED00E071 -:10614000FEE70000214B2248224A70B5904237D327 -:10615000214BC11EDA1C121A22F003028B4238BFF7 -:1061600000220021FBF7B6FD1C4A0023C2F8843050 -:10617000BFF34F8FD2F8803043F6E074C3F3C90009 -:10618000C3F34E335B0103EA0406014646EA817518 -:106190000139C2F86C52F9D2203B13F1200FF2D131 -:1061A000BFF34F8FBFF36F8FBFF34F8FBFF36F8F6F -:1061B0000023C2F85032BFF34F8FBFF36F8F70BD13 -:1061C00053F8041B40F8041BC0E700BFB87D00086B -:1061D00030870020308700203087002000ED00E06D -:1061E000074BD3F8D81021EA0001C3F8D810D3F830 -:1061F000002122EA0002C3F80021D3F800317047E1 -:106200000044025870B5D0E9244300224FF0FF3516 -:106210009E6804EB42135101D3F80009002805DA07 -:10622000D3F8000940F08040C3F80009D3F8000B10 -:10623000002805DAD3F8000B40F08040C3F8000BCB -:10624000013263189642C3F80859C3F8085BE0D2DC -:106250004FF00113C4F81C3870BD0000890141F0F3 -:106260002001016103699B06FCD41220FFF7D0B91D -:1062700010B50A4C2046FEF75DFE094BC4F890307D -:10628000084BC4F89430084C2046FEF753FE074BE9 -:10629000C4F89030064BC4F8943010BD60850020DF -:1062A00000000840887B0008FC85002000000440B6 -:1062B000947B000870B503780546012B5CD1434BF5 -:1062C000D0F89040984258D1414B0E216520D3F828 -:1062D000D82042F00062C3F8D820D3F8002142F061 -:1062E0000062C3F80021D3F80021D3F8802042F0E7 -:1062F0000062C3F88020D3F8802022F00062C3F847 -:106300008020D3F88030FEF791FA324BE360324BB5 -:10631000C4F800380023D5F89060C4F8003EC023CC -:1063200023604FF40413A3633369002BFCDA0123C9 -:106330000C203361FFF76CF93369DB07FCD41220C2 -:10634000FFF766F93369002BFCDA00262846A660C1 -:10635000FFF758FF6B68C4F81068DB68C4F814686E -:10636000C4F81C6883BB1D4BA3614FF0FF3363610E -:10637000A36843F00103A36070BD194B9842C9D1D3 -:10638000134B4FF08060D3F8D82042F00072C3F86E -:10639000D820D3F8002142F00072C3F80021D3F8CE -:1063A0000021D3F8802042F00072C3F88020D3F897 -:1063B000802022F00072C3F88020D3F88030FFF7ED -:1063C0000FFF0E214D209EE7064BCDE76085002094 -:1063D000004402584014004003002002003C30C03A -:1063E000FC850020083C30C0F8B5D0F89040054648 -:1063F00000214FF000662046FFF730FFD5F89410DB -:1064000000234FF001128F684FF0FF30C4F834388A -:10641000C4F81C2804EB431201339F42C2F8006900 -:10642000C2F8006BC2F80809C2F8080BF2D20B6878 -:10643000D5F89020C5F8983063621023136116696F -:1064400016F01006FBD11220FFF7E2F8D4F800385E -:1064500023F4FE63C4F80038A36943F4402343F0F7 -:106460001003A3610923C4F81038C4F814380B4B87 -:10647000EB604FF0C043C4F8103B094BC4F8003B3D -:10648000C4F81069C4F80039D5F8983003F1100247 -:1064900043F48013C5F89820A362F8BD647B00081C -:1064A00040800010D0F8902090F88A10D2F8003880 -:1064B00023F4FE6343EA0113C2F80038704700007A -:1064C0002DE9F84300EB8103D0F890500C4680464C -:1064D000DA680FFA81F94801166806F00306731EA0 -:1064E000022B05EB41134FF0000194BFB604384E68 -:1064F000C3F8101B4FF0010104F1100398BF06F11F -:10650000805601FA03F3916998BF06F50046002909 -:106510003AD0578A04F15801374349016F50D5F8F2 -:106520001C180B430021C5F81C382B180127C3F891 -:106530001019A7405369611E9BB3138A928B9B0865 -:10654000012A88BF5343D8F89820981842EA034399 -:1065500001F140022146C8F89800284605EB820266 -:106560005360FFF77BFE08EB8900C3681B8A43EA90 -:10657000845348341E4364012E51D5F81C381F4300 -:10658000C5F81C78BDE8F88305EB4917D7F8001B60 -:1065900021F40041C7F8001BD5F81C1821EA0303B9 -:1065A000C0E704F13F030B4A2846214605EB83036D -:1065B0005A60FFF753FE05EB4910D0F8003923F479 -:1065C0000043C0F80039D5F81C3823EA0707D7E79D -:1065D0000080001000040002D0F894201268C0F877 -:1065E0009820FFF70FBE00005831D0F890304901D5 -:1065F0005B5813F4004004D013F4001F0CBF0220BA -:10660000012070474831D0F8903049015B5813F4AD -:10661000004004D013F4001F0CBF0220012070477B -:1066200000EB8101CB68196A0B6813604B685360FB -:106630007047000000EB810330B5DD68AA6913687C -:10664000D36019B9402B84BF402313606B8A146850 -:10665000D0F890201C4402EB4110013C09B2B4FB7D -:10666000F3F46343033323F0030343EAC44343F0E7 -:10667000C043C0F8103B2B6803F00303012B0ED17D -:10668000D2F8083802EB411013F4807FD0F8003BB9 -:1066900014BF43F0805343F00053C0F8003B02EBBB -:1066A0004112D2F8003B43F00443C2F8003B30BD36 -:1066B0002DE9F041D0F8906005460C4606EB4113F9 -:1066C000D3F8087B3A07C3F8087B08D5D6F8143806 -:1066D0001B0704D500EB8103DB685B689847FA076A -:1066E0001FD5D6F81438DB071BD505EB8403D96812 -:1066F000CCB98B69488A5A68B2FBF0F600FB1622C7 -:106700008AB91868DA6890420DD2121AC3E90024D7 -:10671000302383F3118821462846FFF78BFF84F34B -:106720001188BDE8F081012303FA04F26B8923EAA2 -:1067300002036B81CB68002BF3D021462846BDE8CD -:10674000F041184700EB81034A0170B5DD68D0F8CD -:1067500090306C692668E66056BB1A444FF40020FE -:10676000C2F810092A6802F00302012A0AB20ED107 -:10677000D3F8080803EB421410F4807FD4F8000922 -:1067800014BF40F0805040F00050C4F8000903EB03 -:106790004212D2F8000940F00440C2F80009012278 -:1067A000D3F8340802FA01F10143C3F8341870BD7C -:1067B00019B9402E84BF4020206020681A442E8AD8 -:1067C0008419013CB4FBF6F440EAC44040F00050A8 -:1067D000C6E700002DE9F843D0F8906005460C4666 -:1067E0004F0106EB4113D3F8088918F0010FC3F8E5 -:1067F00008891CD0D6F81038DB0718D500EB8103C8 -:10680000D3F80CC0DCF81430D3F800E0DA68964511 -:1068100030D2A2EB0E024FF000091A60C3F80490C8 -:10682000302383F31188FFF78DFF89F3118818F067 -:10683000800F1DD0D6F834380126A640334217D039 -:1068400005EB84030134D5F89050D3F80CC0E4B2C2 -:106850002F44DCF8142005EB0434D2F800E0516832 -:10686000714514D3D5F8343823EA0606C5F83468E0 -:10687000BDE8F883012303FA01F2038923EA020346 -:106880000381DCF80830002BD1D09847CFE7AEEB7E -:106890000103BCF81000834228BF0346D7F818094B -:1068A00080B2B3EB800FE3D89068A0F1040959F8E7 -:1068B000048FC4F80080A0EB09089844B8F1040FD5 -:1068C000F5D818440B4490605360C8E72DE9F84FA1 -:1068D000D0F8905004466E69AB691E4016F480589B -:1068E0006E6103D0BDE8F84FFEF794BB002E12DABC -:1068F000D5F8003E9B0705D0D5F8003E23F00303F2 -:10690000C5F8003ED5F80438204623F00103C5F849 -:106910000438FEF7ADFB370505D52046FFF772FCBE -:106920002046FEF793FBB0040CD5D5F8083813F0D9 -:10693000060FEB6823F470530CBF43F4105343F479 -:10694000A053EB6031071BD56368DB681BB9AB69EB -:1069500023F00803AB612378052B0CD1D5F8003E5A -:106960009A0705D0D5F8003E23F00303C5F8003E92 -:106970002046FEF77DFB6368DB680BB12046984735 -:10698000F30200F1BA80B70226D5D4F89090002720 -:106990004FF0010A09EB4712D2F8003B03F4402301 -:1069A000B3F5802F11D1D2F8003B002B0DDA6289AC -:1069B0000AFA07F322EA0303638104EB8703DB6827 -:1069C000DB6813B13946204698470137D4F8943034 -:1069D000FFB29B689F42DDD9F00619D5D4F890002C -:1069E000026AC2F30A1702F00F0302F4F012B2F5C2 -:1069F000802F00F0CA80B2F5402F09D104EB830349 -:106A0000002200F58050DB681B6A974240F0B0809E -:106A10003003D5F8185835D5E90303D500212046B1 -:106A2000FFF746FEAA0303D501212046FFF740FEEB -:106A30006B0303D502212046FFF73AFE2F0303D54F -:106A400003212046FFF734FEE80203D50421204647 -:106A5000FFF72EFEA90203D505212046FFF728FEE9 -:106A60006A0203D506212046FFF722FE2B0203D53A -:106A700007212046FFF71CFEEF0103D50821204621 -:106A8000FFF716FE700340F1A780E90703D5002148 -:106A90002046FFF79FFEAA0703D501212046FFF7F6 -:106AA00099FE6B0703D502212046FFF793FE2F07BF -:106AB00003D503212046FFF78DFEEE0603D5042102 -:106AC0002046FFF787FEA80603D505212046FFF7DD -:106AD00081FE690603D506212046FFF77BFE2A06C4 -:106AE00003D507212046FFF775FEEB0574D5204638 -:106AF0000821BDE8F84FFFF76DBED4F890904FF035 -:106B0000000B4FF0010AD4F894305FFA8BF79B68C2 -:106B10009F423FF638AF09EB4713D3F8002902F440 -:106B20004022B2F5802F20D1D3F80029002A1CDAA8 -:106B3000D3F8002942F09042C3F80029D3F8002985 -:106B4000002AFBDB3946D4F89000FFF787FB228947 -:106B50000AFA07F322EA0303238104EB8703DB68C5 -:106B60009B6813B13946204698470BF1010BCAE7E1 -:106B7000910701D1D0F80080072A02F101029CBFE1 -:106B800003F8018B4FEA18283FE704EB830300F575 -:106B90008050DA68D2F818C0DCF80820DCE9001C64 -:106BA000A1EB0C0C00218F4208D1DB689B699A682D -:106BB0003A449A605A683A445A6029E711F0030F40 -:106BC00001D1D0F800808C4501F1010184BF02F8A9 -:106BD000018B4FEA1828E6E7BDE8F88F08B50348AF -:106BE000FFF774FEBDE80840FDF7E4BC60850020B7 -:106BF00008B50348FFF76AFEBDE80840FDF7DABCB8 -:106C0000FC850020D0F8903003EB4111D1F8003B17 -:106C100043F40013C1F8003B70470000D0F89030F7 -:106C200003EB4111D1F8003943F40013C1F80039E6 -:106C300070470000D0F8903003EB4111D1F8003BD1 -:106C400023F40013C1F8003B70470000D0F89030E7 -:106C500003EB4111D1F8003923F40013C1F80039D6 -:106C60007047000030B50433039C0172002104FB1F -:106C70000325C160C0E90653049B0363059BC0E97B -:106C80000000C0E90422C0E90842C0E90A114363D8 -:106C900030BD00000022416AC260C0E90411C0E9B1 -:106CA0000A226FF00101FEF723BD0000D0E9043293 -:106CB000934201D1C2680AB9181D7047002070477D -:106CC000036919600021C2680132C260C2691344BD -:106CD00082699342036124BF436A0361FEF7FCBCEF -:106CE00038B504460D46E3683BB162690020131DC8 -:106CF0001268A3621344E36207E0237A33B929469A -:106D00002046FEF7D9FC0028EDDA38BD6FF001000F -:106D1000FBE70000C368C269013BC36043691344D9 -:106D200082699342436124BF436A436100238362C3 -:106D3000036B03B11847704770B53023044683F3E3 -:106D40001188866A3EB9FFF7CBFF054618B186F376 -:106D50001188284670BDA36AE26A13F8015B93426A -:106D6000A36202D32046FFF7D5FF002383F31188E7 -:106D7000EFE700002DE9F84F04460E461746984607 -:106D80004FF0300989F311880025AA46D4F828B0BD -:106D9000BBF1000F09D141462046FFF7A1FF20B10A -:106DA0008BF311882846BDE8F88FD4E90A12A7EBC7 -:106DB000050B521A934528BF9346BBF1400F1BD9D0 -:106DC000334601F1400251F8040B914243F8040BA1 -:106DD000F9D1A36A403640354033A362D4E90A238F -:106DE0009A4202D32046FFF795FF8AF31188BD42ED -:106DF000D8D289F31188C9E730465A46FAF744FFDA -:106E0000A36A5E445D445B44A362E7E710B5029C5D -:106E10000433017203FB0421C460C0E9061300239C -:106E2000C0E90A33039B0363049BC0E90000C0E987 -:106E30000422C0E90842436310BD0000026A6FF0FB -:106E40000101C260426AC0E904220022C0E90A22AC -:106E5000FEF74EBCD0E904239A4201D1C26822B9A0 -:106E6000184650F8043B0B60704700231846FAE7B9 -:106E7000C3680021C2690133C36043691344826956 -:106E80009342436124BF436A4361FEF725BC00007F -:106E900038B504460D46E3683BB1236900201A1D4E -:106EA000A262E2691344E36207E0237A33B9294618 -:106EB0002046FEF701FC0028EDDA38BD6FF0010036 -:106EC000FBE7000003691960C268013AC260C26949 -:106ED000134482699342036124BF436A0361002320 -:106EE0008362036B03B118477047000070B530230D -:106EF0000D460446114683F31188866A2EB9FFF7C2 -:106F0000C7FF10B186F3118870BDA36A1D70A36A14 -:106F1000E26A01339342A36204D3E1692046043953 -:106F2000FFF7D0FF002080F31188EDE72DE9F84F3F -:106F300004460D46904699464FF0300A8AF3118870 -:106F40000026B346A76A4FB949462046FFF7A0FF7F -:106F500020B187F311883046BDE8F88FD4E90A07DD -:106F60003A1AA8EB0607974228BF1746402F1BD9AD -:106F700005F1400355F8042B9D4240F8042BF9D14C -:106F8000A36A40364033A362D4E90A239A4204D369 -:106F9000E16920460439FFF795FF8BF311884645D8 -:106FA000D9D28AF31188CDE729463A46FAF76CFE22 -:106FB000A36A3D443E443B44A362E5E7D0E9042391 -:106FC0009A4217D1C3689BB1836A8BB1043B9B1A69 -:106FD0000ED01360C368013BC360C3691A44836960 -:106FE0009A42026124BF436A036100238362012342 -:106FF000184670470023FBE700F024B9014B586A9C -:10700000704700BF000C0040034B002258631A6118 -:107010000222DA60704700BF000C0040014B0022E2 -:10702000DA607047000C0040014B5863704700BFA6 -:10703000000C0040FEE7000070B51B4B0025044625 -:1070400086B058600E4685620163FDF78BFA04F145 -:107050001003A560E562C4E904334FF0FF33C4E9CF -:107060000044C4E90635FFF7C9FF2B46024604F188 -:1070700034012046C4E9082380230C4A2565FEF725 -:10708000D1FA01230A4AE0600092037568467268EB -:107090000192B268CDE90223064BCDE90435FEF733 -:1070A000E9FA06B070BD00BF086A0020A07B0008A6 -:1070B000A57B000835700008024AD36A1843D062E5 -:1070C000704700BFA06700204B6843608B688360F7 -:1070D000CB68C3600B6943614B6903628B69436290 -:1070E0000B6803607047000008B53C4B40F2FF712D -:1070F0003B48D3F888200A43C3F88820D3F8882077 -:1071000022F4FF6222F00702C3F88820D3F8882017 -:10711000D3F8E0200A43C3F8E020D3F808210A435B -:10712000C3F808212F4AD3F808311146FFF7CCFFE6 -:1071300000F5806002F11C01FFF7C6FF00F58060DA -:1071400002F13801FFF7C0FF00F5806002F1540141 -:10715000FFF7BAFF00F5806002F17001FFF7B4FF9E -:1071600000F5806002F18C01FFF7AEFF00F5806052 -:1071700002F1A801FFF7A8FF00F5806002F1C40149 -:10718000FFF7A2FF00F5806002F1E001FFF79CFF2E -:1071900000F5806002F1FC01FFF796FF02F58C71AB -:1071A00000F58060FFF790FF00F014F90E4BD3F864 -:1071B000902242F00102C3F89022D3F8942242F0C8 -:1071C0000102C3F894220522C3F898204FF06052C0 -:1071D000C3F89C20054AC3F8A02008BD004402580B -:1071E00000000258AC7B000800ED00E01F0008031F -:1071F00008B500F0D1FAFEF7C9F90F4BD3F8DC203F -:1072000042F04002C3F8DC20D3F8042122F040020F -:10721000C3F80421D3F80431084B1A6842F008027D -:107220001A601A6842F004021A60FEF72FFFBDE8E8 -:107230000840FEF749BC00BF00440258001802484D -:1072400070470000114BD3F8E82042F00802C3F861 -:10725000E820D3F8102142F00802C3F810210C4AAC -:10726000D3F81031D36B43F00803D363C722094B23 -:107270009A624FF0FF32DA6200229A615A63DA6052 -:107280005A6001225A611A60704700BF00440258D8 -:107290000010005C000C0040094A08B51169D36871 -:1072A0000B40D9B29B076FEA0101116107D530236A -:1072B00083F31188FEF790F9002383F3118808BD4A -:1072C000000C0040064BD3F8DC200243C3F8DC205E -:1072D000D3F804211043C3F80401D3F804317047F4 -:1072E000004402583A4B4FF0FF31D3F8802062F04F -:1072F0000042C3F88020D3F8802002F00042C3F897 -:107300008020D3F88020D3F88420C3F88410D3F8E9 -:1073100084200022C3F88420D3F88400D86F40F082 -:10732000FF4040F4FF0040F4DF4040F07F00D867AA -:10733000D86F20F0FF4020F4FF0020F4DF4020F061 -:107340007F00D867D86FD3F888006FEA40506FEAA3 -:107350005050C3F88800D3F88800C0F30A00C3F87F -:107360008800D3F88800D3F89000C3F89010D3F8C1 -:107370009000C3F89020D3F89000D3F89400C3F89D -:107380009410D3F89400C3F89420D3F89400D3F861 -:107390009800C3F89810D3F89800C3F89820D3F851 -:1073A0009800D3F88C00C3F88C10D3F88C00C3F885 -:1073B0008C20D3F88C00D3F89C00C3F89C10D3F831 -:1073C0009C10C3F89C20D3F89C3000F0B9B900BFE2 -:1073D0000044025808B50122534BC3F80821534B0F -:1073E000D3F8F42042F00202C3F8F420D3F81C21B1 -:1073F00042F00202C3F81C210222D3F81C314C4B8C -:10740000DA605A689104FCD54A4A1A6001229A60EF -:10741000494ADA6000221A614FF440429A61444BB3 -:107420009A699204FCD51A6842F480721A603F4B44 -:107430001A6F12F4407F04D04FF480321A67002292 -:107440001A671A6842F001021A60384B1A6850072E -:10745000FCD500221A611A6912F03802FBD1012111 -:1074600019604FF0804159605A67344ADA62344AF1 -:107470001A611A6842F480321A602C4B1A68910320 -:10748000FCD51A6842F480521A601A689204FCD53E -:107490002C4A2D499A6200225A63196301F57C0136 -:1074A000DA6301F5E77199635A64284A1A64284A35 -:1074B000DA621A6842F0A8521A601C4B1A6802F08D -:1074C0002852B2F1285FF9D148229A614FF48862BC -:1074D000DA6140221A621F4ADA641F4A1A651F4A9B -:1074E0005A651F4A9A6532231E4A1360136803F0D7 -:1074F0000F03022BFAD10D4A136943F00303136102 -:10750000136903F03803182BFAD14FF00050FFF73E -:10751000D9FE4FF08040FFF7D5FE4FF00040BDE8A8 -:107520000840FFF7CFBE00BF008000510044025862 -:107530000048025800C000F0020000010000FF01F6 -:10754000008890083220600063020901470E050898 -:10755000DD0BBF0120000020000001100910E00039 -:1075600000010110002000524FF0B04208B5D2F8DF -:10757000883003F00103C2F8883023B1044A13684D -:107580000BB150689847BDE80840FDF713B800BF3D -:10759000B08600204FF0B04208B5D2F8883003F032 -:1075A0000203C2F8883023B1044A93680BB1D06853 -:1075B0009847BDE80840FCF7FDBF00BFB08600203B -:1075C0004FF0B04208B5D2F8883003F00403C2F897 -:1075D000883023B1044A13690BB150699847BDE85C -:1075E0000840FCF7E7BF00BFB08600204FF0B04274 -:1075F00008B5D2F8883003F00803C2F8883023B108 -:10760000044A93690BB1D0699847BDE80840FCF77C -:10761000D1BF00BFB08600204FF0B04208B5D2F80D -:10762000883003F01003C2F8883023B1044A136A8B -:107630000BB1506A9847BDE80840FCF7BBBF00BFDC -:10764000B08600204FF0B04310B5D3F8884004F462 -:107650007872C3F88820A30604D5124A936A0BB146 -:10766000D06A9847600604D50E4A136B0BB1506B75 -:107670009847210604D50B4A936B0BB1D06B984702 -:10768000E20504D5074A136C0BB1506C9847A3056B -:1076900004D5044A936C0BB1D06C9847BDE81040F8 -:1076A000FCF788BFB08600204FF0B04310B5D3F888 -:1076B000884004F47C42C3F88820620504D5164A49 -:1076C000136D0BB1506D9847230504D5124A936D85 -:1076D0000BB1D06D9847E00404D50F4A136E0BB17F -:1076E000506E9847A10404D50B4A936E0BB1D06E2F -:1076F0009847620404D5084A136F0BB1506F98473E -:10770000230404D5044A936F0BB1D06F9847BDE8AA -:107710001040FCF74FBF00BFB086002008B50348FB -:10772000FCF7FEFFBDE80840FCF744BF34630020CF -:1077300008B5FFF7B1FDBDE80840FCF73BBF00000E -:10774000062108B50846FDF771F806210720FDF768 -:107750006DF806210820FDF769F806210920FDF7DC -:1077600065F806210A20FDF761F806211720FDF7CC -:107770005DF806212820FDF759F809217A20FDF748 -:1077800055F807213220FDF751F80C215220BDE8B1 -:107790000840FDF74BB8000008B5FFF7A3FD00F067 -:1077A0000DF8FDF7EBF9FDF7C3FBFDF795FAFFF7D1 -:1077B00047FDBDE80840FFF71FBC00000023054A55 -:1077C00019460133102BC2E9001102F10802F8D169 -:1077D000704700BFB08600200B460146184600F0F7 -:1077E00003B8000000F00EB810B5054C13462CB1DC -:1077F0000A4601460220AFF3008010BD2046FCE798 -:1078000000000000024B01461868FEF757BB00BF9E -:107810006C22002010B501390244904201D10020B1 -:1078200005E0037811F8014FA34201D0181B10BDE9 -:107830000130F2E72DE9F041A3B1C91A17780144EC -:10784000044603F1FF3C8C42204601D9002009E0A8 -:107850000578BD4204F10104F5D10CEB0405D618FE -:10786000A54201D1BDE8F08115F8018D16F801EDB2 -:10787000F045F5D0E7E70000034611F8012B03F8C7 -:10788000012B002AF9D170476F72672E61726475FF -:1078900070696C6F742E437562654F72616E6765B7 -:1078A0002D7065726970682D6865617679000000D9 -:1078B00053544D333248373F3F3F0053544D3332DA -:1078C000483733782F3732780053544D33324837A6 -:1078D00034332F3735332F373530000001105A003D -:1078E00003105900012058000320560040A2E4F183 -:1078F000646891060041A3E5F26569920700000003 -:1079000043414E464449666163653A204D65737351 -:107910006167652052414D204F766572666C6F77C6 -:10792000210000004261642043414E496661636565 -:1079300020696E6465782E00000100000001FF00E0 -:1079400000A0004000A40040000000000000000073 -:10795000DD2C0008B525000811340008AD2500080D -:1079600025260008352A00089D270008ED25000877 -:10797000F1250008C9250008B1250008F5290008EF -:10798000D525000879350008E1250008C929000837 -:107990000096000000000000000000000000000051 -:1079A0000000000000000000000000003D4B000847 -:1079B000294B0008654B0008514B00085D4B00083F -:1079C000494B0008354B0008214B0008714B00085B -:1079D00000000000554C0008414C00087D4C000898 -:1079E000694C0008754C0008614C00084D4C0008BB -:1079F000394C0008894C000800000000010000001C -:107A00000000000063300000047A0008F8670020DE -:107A1000086A00204172647550696C6F74002542D9 -:107A20004F415244252D424C002553455249414C6B -:107A3000250000000200000000000000754E000854 -:107A4000E54E000840004000B8820020C8820020B7 -:107A50000200000000000000030000000000000021 -:107A60002D4F00080000000010000000D882002008 -:107A70000000000001000000000000006085002000 -:107A800001010200655A000875590008115A0008E2 -:107A9000F5590008430000009C7A000809024300E1 -:107AA000020100C0320904000001020201000524A5 -:107AB000001001052401000104240202052406002F -:107AC00001070582030800FF09040100020A000003 -:107AD0000007050102400000070581024000000088 -:107AE00012000000E87A00081201100102000040B4 -:107AF00009124157000201020301000004030904B6 -:107B000025424F4152442500303132333435363727 -:107B1000383941424344454600000000000000203F -:107B20000000020002000000000100300000000020 -:107B3000080000000000002400000800040000000D -:107B40000004000000FC00000200000000000430FF -:107B50000080000008000000000000380000010064 -:107B60000100000000000000895000084153000897 -:107B7000ED530008400040009886002098860020C1 -:107B800001000000A88600208000000040010000E5 -:107B900008000000000100000010000008000000C4 -:107BA0006D61696E0069646C650000000000802AE8 -:107BB00000000000AAAAAAAA00000024FFFF0000FB -:107BC0000000000000A00A000021000200000000E8 -:107BD000AAAAAAAA00000000FFFF000000000009F6 -:107BE000000009001400005400000000AAAAAAAA7C -:107BF00014000054FFFF000000000000000000001F -:107C00000A40100000000000AAAA8AAA0040100042 -:107C1000FFFF00009900000000000000008102004A -:107C200000000000AAAAAAAA00410100FFFF00006C -:107C300000000070070000000000000000000000CD -:107C4000AAAAAAAA00000000FFFF0000000000008E -:107C5000000000000000000000000000AAAAAAAA7C -:107C600000000000FFFF0000000000000000000016 -:107C70000000000000000000AAAAAAAA000000005C -:107C8000FFFF0000000000000000000000000000F6 -:107C900000000000AAAAAAAA00000000FFFF00003E -:107CA00000000000000000000000000000000000D4 -:107CB000AAAAAAAA00000000FFFF0000000000001E -:107CC000000000000000000000000000AAAAAAAA0C -:107CD00000000000FFFF00000000000000000000A6 -:107CE0004086FF7F010000007805000000000000D2 -:107CF00000001E0000000000FE2A0100D204000067 -:107D0000FF000000106A0020346300200000000023 -:107D1000B078000883040000BB780008500400001D -:107D2000C9780008009600000000080096000000D6 -:107D30000008000004000000FC7A000800000000B9 -:107D40000000000000000000000000000000000033 -:107D50000000000070220020000000000000000071 -:107D60000000000000000000000000000000000013 -:107D70000000000000000000000000000000000003 -:107D800000000000000000000000000000000000F3 -:107D900000000000000000000000000000000000E3 -:107DA00000000000000000000000000000000000D3 -:087DB0000000000000000000CB +:10366000082817D90C280CD910280CD914280CD9E3 +:1036700018280CD920280CD930288CBF0F200E20F8 +:103680007047092070470A2070470B2070470C20B4 +:1036900070470D20704700002DE9F843078C044661 +:1036A000072F1ED900254FF6FF73D0E90298C5F108 +:1036B0002006A5F1200029FA05F1083508FA06F6DA +:1036C00028FA00F0314301431846C9B2FFF762FF00 +:1036D000402D0346EBD13A46E169BDE8F843FFF7D8 +:1036E00069BF4FF6FF70BDE8F883000010B54B6866 +:1036F00023B9CA8A63F30902CA8210BD04691A6831 +:103700001C600361C38A013BC3824A60EFE700008B +:103710002DE9F84F1D46CB8A0F468146C3F30901B8 +:10372000924605290B4630D00020AAB207F11A04B0 +:103730009EB21FFA80F8042E0FD8904503F10103C2 +:1037400006D30A44FB8A62F309030120FB821AE0D4 +:103750001AF800600130E654EAE79045F1D2A1F191 +:10376000050B1C237C68BBFBF3F203FB12BB1FFAA7 +:103770008BF6002C45D14846FFF728FF044638B9A0 +:1037800078606FF00200BDE8F88F4FF00008E6E7C0 +:10379000002606607860ADB24FF0000B454510D9A9 +:1037A0000AEB0803221D13F8011B08F101089155CB +:1037B000B1B21FFA88F81B292BD0454506F1010646 +:1037C000F1D8FB8AC3F30902154465F30903BCE78A +:1037D00001321C4692B22368002BF9D16B1F0B44B7 +:1037E0001C21B3FBF1F301339BB29A42D3D2BBF15C +:1037F000000FD0D14846FFF7E9FE20B9C4F800B069 +:10380000BFE70122E7E7C0F800B05E46206004464B +:10381000C1E74545D5D94846FFF7D8FE08B920602D +:10382000AFE7C0F800B0002620600446B6E700000D +:103830002DE9F04F1C46074688462DED028B83B0DC +:103840005B690192002B00F09A80238C2BB1E26916 +:10385000002A00F09480072B35D807F10C00FFF701 +:10386000B5FE054638B96FF00205284603B0BDEC39 +:10387000028BBDE8F08F14220021FEF7B1F8228CF4 +:10388000E16905F10800FEF785F8208C48F0004159 +:10389000013080B2FFF7E4FEFFF7C6FE013880B2C8 +:1038A00020840130287438466369228C1B782A44AE +:1038B00003F01F0363F03F03137269602946FFF7AB +:1038C000EFFD0125D1E74FF0000900F10C034FF0A7 +:1038D000800A4E464D4608EE103A18EE100AFFF7E1 +:1038E00075FE83460028BED014220021FEF778F82A +:1038F000002E3AD1019B0222ABF808300BF1080EE2 +:103900001FFA82FC218C0CF10100BCF1060F80B281 +:1039100001D88E422BD3FFF7A3FE8E4208BF4FF093 +:10392000400AFFF781FE62690138013512781BFAFF +:1039300080F1013002F01F022DB242EA491289F0F3 +:1039400001094AEA020A48F0004281F808A05946F3 +:103950008BF810003846CBF804204FF0000AFFF730 +:103960009FFD238CB342B8D17FE70022C6E7E1690F +:10397000895D01360EF80210B6B20132C0E76FF071 +:10398000010572E7F8B515460E46302200210446BF +:103990001F46FEF725F8069BB5F5001FA76063607C +:1039A00004F11000079B34BF6A094FF6FF72E6610D +:1039B000A362002397B29A4206D800230360A7822D +:1039C000E3822383E360F8BD06600133304620368E +:1039D000F1E7000003781BB94BB2002BC8BF0170A0 +:1039E0007047000000787047F8B50C46C969074673 +:1039F00011B9238C002B37D1257E1F2D34D8387870 +:103A000028BB228C072A2CD8268A36F003032BD118 +:103A10004FF6FF70FFF7CEFD20F0010031024FF6A8 +:103A2000FF72400441EA0561400C41EA402523460B +:103A300029463846FFF7FCFE002807DD6269137847 +:103A40000133DBB21F2B88BF00231370F8BD218A1E +:103A50002D0645EA012505432046FFF71DFE0246D7 +:103A6000E5E76FF00300F1E76FF00100EEE700001B +:103A700070B58AB0044616460021282268461D46C5 +:103A8000FDF7AEFFBDF8383069462046ADF810307E +:103A90000F9B05939DF840308DF81830119B0793CC +:103AA000BDF84830CDE90265ADF82030FFF79CFF46 +:103AB0000AB070BD2DE9F041D36905460C461646A3 +:103AC0000BB9138C5BBB377E1F2F28D895F800806D +:103AD000B8F1000F26D03046FFF7DEFD3378210223 +:103AE0000246284641EAC331338A41EA080141EAE5 +:103AF000076141EA0341334641F08001FFF798FE38 +:103B000000280ADD3378012B07D17269137801335D +:103B1000DBB21F2B88BF00231370BDE8F0816FF06C +:103B20000100FAE76FF00300F7E70000F0B58BB093 +:103B300004460D4617460021282268461E46FDF71A +:103B40004FFF9DF84C30294620465A1E53425341A0 +:103B50006A468DF800309DF84030ADF81030119B6A +:103B600005939DF848308DF81830149B0793BDF8E5 +:103B70005430CDE90276ADF82030FFF79BFF0BB053 +:103B8000F0BD0000406A00B104307047436A1A6813 +:103B9000426202691A600361C38A013BC3827047B3 +:103BA0002DE9F041D0F8208014461D46184E4146BC +:103BB000002709B9BDE8F081D1E90223A21A65EB1B +:103BC0000303964277EB03031ED2036A8B420DD1A7 +:103BD000FFF78CFD036A1B68036203690B60C38AED +:103BE0000161013B016AC3828846E2E7FFF77EFD7F +:103BF0000B68C8F8003003690B60C38A0161013BA0 +:103C0000C382D8F80010D4E788460968D1E700BF1E +:103C100080841E002DE9F04F8BB00D4614469B4664 +:103C2000DDF850908046002800F01881B9F1000FAF +:103C300000F01481531E3F2B00F21081012A03D1A2 +:103C4000BBF1000F40F00A810023CDE90833B8F83A +:103C50001430B5EBC30F4FEAC30703D300200BB0FA +:103C6000BDE8F08F2B199F42D8F80C3036BF7F1B70 +:103C70002746FFB21BB9D8F81030002B7AD0272D79 +:103C80004DD8C5F1280600232946B742009308AB5A +:103C9000D8F808002CBFF6B23E46A7EB060A35441A +:103CA00032465FFA8AFAFFF73DFCB8F81430282153 +:103CB00003F10053053BDB000493D8F80C30039369 +:103CC000039B13B1BAF1000F2CD1D8F8100040B10A +:103CD000BAF1000F05D008AB5246691A0096FFF7FB +:103CE00021FC38B2002FB9D066070AD00AAB624275 +:103CF00003EBD40102F0070211F8083C134101F86C +:103D0000083C082C3DD9102C40F2B580202C40F204 +:103D1000B780BBF1000F00F09C80082335E0BA4665 +:103D20000026C2E7049BE02B28BFE02306930B4448 +:103D3000AB42059315D95A1B0398691A0096924510 +:103D400008AB00F1040034BF5246D2B20792FFF72D +:103D5000E9FB079A1644AAEB020A1544F6B25FFA89 +:103D60008AFA049B069A05999B1A0493039B1B6885 +:103D70000393A5E700933A4608AB2946D8F8080014 +:103D8000ADE7BBF1000F13D00123B4EBC30F6BD031 +:103D9000082C12D89DF82030621E23FA02F2D507B3 +:103DA00006D54FF0FF3202FA04F423438DF8203099 +:103DB0009DF8203089F8003051E7102C12D8BDF85A +:103DC0002030621E23FA02F2D10706D54FF0FF32EF +:103DD00002FA04F42343ADF82030BDF82030A9F8EE +:103DE00000303CE7202C0FD80899631E21FA03F31A +:103DF000DA0705D54FF0FF3202FA04F40C430894B9 +:103E0000089BC9F800302AE7402C2AD0611EC4F173 +:103E10002102A4F12103DDE9086526FA01F105FA82 +:103E200002F225FA03F311431943CB0711D50122FE +:103E3000A4F12003C4F1200102FA03F322FA01F1F4 +:103E4000A2400B43524263EB430332432B43CDE981 +:103E50000823DDE90823C9E9002300E76FF001002A +:103E6000FDE66FF00800FAE6082CA1D9102CB4D9B1 +:103E7000202CEED8C4E7BBF1000FAED0022384E7BC +:103E8000BBF1000FBCD004237FE70000012A30B54E +:103E9000144638BF012485B00025402C28BF40249B +:103EA000012ACDE9025518D81B788DF80830630730 +:103EB0000AD004AB624203EBD40502F0070215F806 +:103EC000083C934005F8083C034600912246002137 +:103ED00002A8FFF727FB05B030BD082AE4D9102A55 +:103EE00003D81B88ADF80830E1E7202A95BF1B688E +:103EF000D3E900230293CDE90223D8E710B5CB68BC +:103F00001BB98B600B618B8210BD04691A681C6041 +:103F10000361C38A013BC382CA60F0E703064CBF5A +:103F2000C0F3C0300220704708B50246FFF7F6FF25 +:103F3000022806D15306C2F30F2001D100F003007E +:103F400008BDC2F30740FBE72DE9F04F93B00446EC +:103F50000D46CDE903230A681046FFF7DFFF02286C +:103F6000824614BFC2F306260026002A80F2F3819F +:103F700012F0C04940F0EF81097B002900F0EB818D +:103F8000022803D02378B34240F0E881C2F30463EF +:103F900010462944069302F07F030593FFF7C4FF00 +:103FA000059B002283464FEA8348002348EA0A48DB +:103FB00048EA4668CE78CDE90823F30948EA0008C4 +:103FC000029368D0059B024608A9204600935346F9 +:103FD0006768B847002800F0C481276A4FB9414696 +:103FE00004F10C00FFF700FB074690B96FF00200E8 +:103FF00055E03B6998450DD03F68002FF9D1414607 +:1040000004F10C00FFF7F0FA07460028EED0236A0F +:104010003B60276297F817C006F01F08CCF3840CAA +:10402000ACEB0800A8EB0C031FFA80FE0028B8BF19 +:104030000EF120001FFA83FEB8BF00B2002B0793D9 +:10404000B8BF0EF12003D7E90221BCBF1BB2079312 +:1040500052EA010338D0039B4FF0000CDFF820E355 +:104060009A1A049B63EB010196457CEB01032BD369 +:104070006B7B97F81AE0734519D1029B002B78D01F +:10408000012821DC7868F8B9DFF8F0C2944570EBBC +:10409000010316D337E0276A27B96FF00C0013B07D +:1040A000BDE8F08F3B699845B4D03F68F4E7B3486A +:1040B00090427CEB010301D30020F0E7029B002B30 +:1040C000FAD0079B0F2B17DCFA7DB3003946204648 +:1040D00002F0030203F07C031343FB75FFF706FBBA +:1040E0006B7BBB76029B3BB9FB7DC3F38402013241 +:1040F00062F38603FB75D0E76A7BBB7E9A42DBD115 +:10410000029B002B35D0B309022B32D0039B142223 +:1041100000210DA8BB60049BFB60FDF761FC039BC5 +:104120000AA920460A93049BADF83EB00B932B1DC1 +:104130008DF840A00C932B7B8DF84180013BDBB2C6 +:10414000ADF83C30069B8DF84230059B8DF843302E +:1041500094F82C3083F001038DF84430A36898471D +:10416000FB7DC3F38403013303F01F039B02FB8237 +:10417000A2E7FB7DC6F34012B2EBD31F40F0F48000 +:10418000C3F38403434540F0F280029AB6092B7BC7 +:10419000002A4DD0F2075DD4032B40F2EB80039B45 +:1041A000AE1D394604F10C00BB603246049BFB6037 +:1041B0002B7B033BDBB2FFF7ABFA00280CDA394666 +:1041C0002046FFF793FAFB7DC3F38403013303F02A +:1041D0001F039B02FB8209E7AB88DDE908843B8370 +:1041E0004FF6FF73C9F12000A9F1200228FA09F166 +:1041F00009F1080904FA00F024FA02F20143184612 +:104200001143C9B2FFF7C6F9B9F1400F0346E9D12E +:10421000B88231462A7B033AD2B2FFF7CBF9FB7D55 +:10422000B882DA43C2F3C01262F3C713FB7543E7E7 +:1042300086B92E1D013B394604F10C00DBB2324633 +:10424000FFF766FA0028BADB2A7B3146B88A013AC2 +:10425000D2B2E2E7F98A013BC1F30901DAB20429DB +:104260005BD8281D002307F11B069A4208D910F8D5 +:1042700001CB013306F801C00131DBB20529F4D1CD +:10428000039993420A9138BF043304992CBF002349 +:1042900055FA83F30B9107F11B010C9179680E938A +:1042A0000D91291DFB8AADF83EB0C3F309038DF8CB +:1042B00040A08DF841801A44069B8DF84230059B42 +:1042C000ADF83C208DF8433094F82C3083F0010396 +:1042D0008DF844300023B88A7B602A7B013AFFF7CF +:1042E00069F93B8BB882834203D1A3680AA92046AF +:1042F000984720460AA9FFF701FEFB7DBA8AC3F35F +:104300008403013303F01F039B02FB823B8B9A4221 +:104310000CBF00206FF01000C1E67B68002BAFD00F +:10432000052001E01C3033461E68002EFAD1091A20 +:104330002E1D081D184401EB090C5FFA89F3BCF12E +:104340001B0F9DD89A429BD916F8013B09F1010930 +:1043500000F8013BEFE76FF00900A0E66FF00A00FC +:104360009DE66FF00B009AE66FF00D0097E66FF098 +:104370000E0094E66FF00F0091E600BF40420F0080 +:1043800080841E00EFF30983054968334A6B22F0ED +:1043900001024A6383F30988002383F3118870477D +:1043A00000EF00E0302080F3118862B60D4B0E4A1A +:1043B000D96821F4E0610904090C0A430B49DA6069 +:1043C000D3F8FC2042F08072C3F8FC20084AC2F8FF +:1043D000B01F116841F0010111602022DA7783F8E3 +:1043E0002200704700ED00E00003FA0555CEACC591 +:1043F000001000E0302310B583F311880E4B5B688A +:1044000013F4006314D0F1EE103AEFF309844FF087 +:104410008073683CE361094BDB6B236684F3098896 +:1044200001F0F2F910B1064BA36110BD054BFBE79B +:1044300083F31188F9E700BF00ED00E000EF00E032 +:104440003F0400084204000808B5074B074A1968F2 +:1044500001F03D01996053680BB190689847BDE841 +:104460000840FFF7C7BF00BF0000024054640020AF +:1044700008B5084B1968890901F03D018A019A6065 +:10448000054AD3680BB110699847BDE80840FFF7AB +:10449000B1BF00BF000002405464002008B5084BC3 +:1044A0001968090C01F03D010A049A60054A536934 +:1044B0000BB190699847BDE80840FFF79BBF00BF6C +:1044C000000002405464002008B5084B1968890DAB +:1044D00001F03D018A059A60054AD3690BB1106A63 +:1044E0009847BDE80840FFF785BF00BF00000240C5 +:1044F0005464002008B5074B074A596801F03D0194 +:10450000D960536A0BB1906A9847BDE80840FFF73D +:1045100071BF00BF000002405464002008B5084B82 +:104520005968890901F03D018A01DA60054AD36AB8 +:104530000BB1106B9847BDE80840FFF75BBF00BFA9 +:10454000000002405464002008B5084B5968090C6B +:1045500001F03D010A04DA60054A536B0BB1906B20 +:104560009847BDE80840FFF745BF00BF0000024084 +:104570005464002008B5084B5968890D01F03D01CD +:104580008A05DA60054AD36B0BB1106C9847BDE819 +:104590000840FFF72FBF00BF000002405464002016 +:1045A00008B5074B074A196801F03D019960536C43 +:1045B0000BB1906C9847BDE80840FFF71BBF00BFE8 +:1045C000000402405464002008B5084B19688909AA +:1045D00001F03D018A019A60054AD36C0BB1106D60 +:1045E0009847BDE80840FFF705BF00BF0004024040 +:1045F0005464002008B5084B1968090C01F03D010E +:104600000A049A60054A536D0BB1906D9847BDE856 +:104610000840FFF7EFBE00BF0004024054640020D2 +:1046200008B5084B1968890D01F03D018A059A60AB +:10463000054AD36D0BB1106E9847BDE80840FFF7EF +:10464000D9BE00BF000402405464002008B5074BE7 +:10465000074A596801F03D01D960536E0BB1906E65 +:104660009847BDE80840FFF7C5BE00BF0004024000 +:104670005464002008B5084B5968890901F03D01D0 +:104680008A01DA60054AD36E0BB1106F9847BDE816 +:104690000840FFF7AFBE00BF000402405464002092 +:1046A00008B5084B5968090C01F03D010A04DA60AD +:1046B000054A536F0BB1906F9847BDE80840FFF76C +:1046C00099BE00BF000402405464002008B5084BA6 +:1046D0005968890D01F03D018A05DA60054AD36FFA +:1046E00013B1D2F880009847BDE80840FFF782BEBA +:1046F000000402405464002000230C4910B51A46FF +:104700000B4C0B6054F82300026001EB43000433B0 +:104710004260402BF6D1074A4FF0FF339360D360DD +:10472000C2F80834C2F80C3410BD00BF5464002035 +:10473000487C0008000002400F28F8B510D9102866 +:1047400010D0112811D0122808D10F240720DFF82B +:10475000C8E00126DEF80050A04208D9002653E048 +:104760000446F4E70F240020F1E70724FBE706FAEC +:1047700000F73D424AD1264C4FEA001C3D4304EB72 +:1047800000160EEBC000CEF80050C0E90123FBB2CA +:1047900073B12048D0F8D83043F00103C0F8D830C6 +:1047A000D0F8003143F00103C0F80031D0F80031F7 +:1047B00017F47F4F0ED01748D0F8D83043F00203DB +:1047C000C0F8D830D0F8003143F00203C0F800310F +:1047D000D0F8003154F80C00036823F01F03036085 +:1047E000056815F00105FBD104EB0C033D2493F89B +:1047F0000CC05F6804FA0CF43C602124056044613D +:1048000012B1987B00F066F93046F8BD0130A3E79D +:10481000487C0008004402585464002010B530243D +:1048200084F31188FFF788FF002383F3118810BDFC +:1048300010B50446807B00F063F901231549627BC3 +:1048400003FA02F20B6823EA0203DAB20B6072B9D0 +:10485000114AD2F8D81021F00101C2F8D810D2F8CC +:10486000001121F00101C2F80011D2F8002113F467 +:104870007F4F0ED1084BD3F8D82022F00202C3F8A4 +:10488000D820D3F8002122F00202C3F80021D3F887 +:10489000003110BD546400200044025808B5302394 +:1048A00083F31188FFF7C4FF002383F3118808BD49 +:1048B000026843681143016003B118477047000064 +:1048C000024A136843F0C003136070470078004049 +:1048D00013B50E4C204600F0BDFA04F1140000237D +:1048E0004FF400720A49009400F07AF9094B4FF432 +:1048F0000072094904F13800009400F0F3F9074A06 +:10490000074BC4E9172302B010BD00BFD8640020D4 +:1049100044650020C148000844670020007800403A +:1049200000E1F505037C30B5244C002918BF0C4686 +:10493000012B11D1224B98420ED1224BD3F8E82003 +:1049400042F08042C3F8E820D3F8102142F08042C0 +:10495000C3F81021D3F810312268036EC16D03EB48 +:1049600052038466B3FBF2F36268150442BF23F07E +:10497000070503F0070343EA4503CB60A36843F050 +:1049800040034B60E36843F001038B6042F496738D +:1049900043F001030B604FF0FF330B62510505D567 +:1049A00012F0102205D0B2F1805F04D080F864309C +:1049B00030BD7F23FAE73F23F8E700BF487D0008BA +:1049C000D8640020004402582DE9F047C66D054622 +:1049D0003768F469210734621AD014F0080118BF4F +:1049E0004FF48071E20748BF41F02001A3074FF068 +:1049F000300348BF41F04001600748BF41F08001EB +:104A000083F31188281DFFF753FF002383F31188D8 +:104A1000E2050AD5302383F311884FF48061281D05 +:104A2000FFF746FF002383F311884FF030094FF062 +:104A3000000A14F0200838D13B0616D54FF0300993 +:104A400005F1380A200610D589F31188504600F088 +:104A50007DF9002836DA0821281DFFF729FF27F005 +:104A600080033360002383F31188790614D562062E +:104A700012D5302383F31188D5E913239A4208D144 +:104A80002B6C33B127F040071021281DFFF710FFD2 +:104A90003760002383F31188E30618D5AA6E1369E3 +:104AA000ABB15069BDE8F047184789F31188736AC4 +:104AB000284695F86410194000F0E6F98AF3118849 +:104AC000F469B6E7B06288F31188F469BAE7BDE823 +:104AD000F0870000090100F16043012203F5614302 +:104AE000C9B283F8001300F01F039A4043099B00EA +:104AF00003F1604303F56143C3F880211A607047F6 +:104B000000F01F0301229A40430900F160409B001E +:104B100000F5614003F1604303F56143C3F8802071 +:104B2000C3F88021002380F800337047F8B515469C +:104B3000826804460B46AA4200D28568A1692669AC +:104B4000761AB5420BD218462A46FCF723FFA36912 +:104B50002B44A3612846A3685B1BA360F8BD0CD956 +:104B6000AF1B18463246FCF715FF3A46E168304461 +:104B7000FCF710FFE3683B44EBE718462A46FCF7D6 +:104B800009FFE368E5E7000083689342F7B5044650 +:104B9000154600D28568D4E90460361AB5420BD2B6 +:104BA0002A46FCF7F7FE63692B4463612846A36835 +:104BB0005B1BA36003B0F0BD0DD93246AF1B019162 +:104BC000FCF7E8FE01993A46E0683144FCF7E2FE62 +:104BD000E3683B44E9E72A46FCF7DCFEE368E4E7E8 +:104BE00010B50A440024C361029B8460C160026165 +:104BF0000362C0E90000C0E9051110BD08B5D0E9A5 +:104C00000532934201D1826882B9826801328260A2 +:104C10005A1C426119700021D0E904329A4224BF23 +:104C2000C368436100F09CFE002008BD4FF0FF30D8 +:104C3000FBE7000070B5302304460E4683F311886D +:104C4000A568A5B1A368A269013BA360531CA36139 +:104C500015782269934224BFE368A361E3690BB12D +:104C600020469847002383F31188284607E0314601 +:104C7000204600F065FE0028E2DA85F3118870BD59 +:104C80002DE9F74F04460E4617469846D0F81C907B +:104C90004FF0300A8AF311884FF0000B154665B1CA +:104CA0002A4631462046FFF741FF034660B9414698 +:104CB000204600F045FE0028F1D0002383F3118840 +:104CC000781B03B0BDE8F08FB9F1000F03D001905D +:104CD0002046C847019B8BF31188ED1A1E448AF3C6 +:104CE0001188DCE7C160C361009B82600362C0E998 +:104CF00005111144C0E9000001617047F8B5044690 +:104D00000D461646302383F31188A768A7B1A36820 +:104D1000013BA36063695A1C62611D70D4E90432CF +:104D20009A4224BFE3686361E3690BB12046984768 +:104D3000002080F3118807E03146204600F000FE95 +:104D40000028E2DA87F31188F8BD0000D0E90523D6 +:104D500010B59A4201D182687AB982680021013285 +:104D600082605A1C82611C7803699A4224BFC3681E +:104D7000836100F0F5FD204610BD4FF0FF30FBE7EA +:104D80002DE9F74F04460E4617469846D0F81C907A +:104D90004FF0300A8AF311884FF0000B154665B1C9 +:104DA0002A4631462046FFF7EFFE034660B94146EA +:104DB000204600F0C5FD0028F1D0002383F31188C0 +:104DC000781B03B0BDE8F08FB9F1000F03D001905C +:104DD0002046C847019B8BF31188ED1A1E448AF3C5 +:104DE0001188DCE7026843681143016003B118478A +:104DF000704700001430FFF743BF00004FF0FF334F +:104E00001430FFF73DBF00003830FFF7B9BF000096 +:104E10004FF0FF333830FFF7B3BF00001430FFF717 +:104E200009BF00004FF0FF311430FFF703BF00004F +:104E30003830FFF763BF00004FF0FF323830FFF724 +:104E40005DBF0000012914BF6FF013000020704700 +:104E5000FFF73EBD044B036000234360C0E902330B +:104E600001230374704700BF607D000810B5302334 +:104E7000044683F31188FFF755FD022300202374B5 +:104E800080F3118810BD000038B5C36904460D4693 +:104E90001BB904210844FFF7A5FF294604F11400BB +:104EA000FFF7ACFE002806DA201D4FF40061BDE8D4 +:104EB0003840FFF797BF38BD02684368114301606F +:104EC00003B118477047000013B5406B00F58054DC +:104ED000D4F8A4381A681178042914D1017C022965 +:104EE00011D11979012312898B4013420BD101A9E9 +:104EF0004C3002F0F7F8D4F8A4480246019B21791F +:104F0000206800F0DFF902B010BD0000143002F09C +:104F100079B800004FF0FF33143002F073B800008E +:104F20004C3002F04BB900004FF0FF334C3002F030 +:104F300045B90000143002F047B800004FF0FF31CF +:104F4000143002F041B800004C3002F017B90000F4 +:104F50004FF0FF324C3002F011B9000000207047D2 +:104F600010B500F58054D4F8A4381A6811780429D3 +:104F700017D1017C022914D15979012352898B4020 +:104F800013420ED1143001F0D9FF024648B1D4F8D3 +:104F9000A4484FF4407361792068BDE8104000F0E8 +:104FA0007FB910BD406BFFF7DBBF0000704700000A +:104FB0007FB5124B012504260446036000230574C7 +:104FC00000F1840243602946C0E902330C4B029091 +:104FD000143001934FF44073009601F08BFF094B9E +:104FE00004F69442294604F14C000294CDE9006392 +:104FF0004FF4407302F052F804B070BD887D000891 +:10500000A54F0008C94E00080A68302383F31188B1 +:105010000B790B3342F823004B79133342F823000A +:105020008B7913B10B3342F8230000F58053C3F89A +:10503000A41802230374002080F311887047000035 +:1050400038B5037F044613B190F85430ABB901254D +:10505000201D0221FFF730FF04F114006FF0010161 +:10506000257700F089FC04F14C0084F854506FF06F +:105070000101BDE8384000F07FBC38BD10B501210A +:1050800004460430FFF718FF0023237784F85430D8 +:1050900010BD000038B504460025143001F042FF71 +:1050A00004F14C00257702F011F8201D84F85450CB +:1050B0000121FFF701FF2046BDE83840FFF750BF50 +:1050C00090F8803003F06003202B06D190F8812007 +:1050D0000023212A03D81F2A06D800207047222A3D +:1050E000FBD1C0E91D3303E0034A42670722826710 +:1050F000C3670120704700BF3C23002037B500F58F +:105100008055D5F8A4381A68117804291AD1017C81 +:10511000022917D11979012312898B40134211D129 +:1051200000F14C04204602F091F858B101A9204644 +:1051300001F0D8FFD5F8A4480246019B21792068E8 +:1051400000F0C0F803B030BD01F10B03F0B550F82A +:10515000236085B004460D46FEB1302383F31188E9 +:1051600004EB8507301D0821FFF7A6FEFB6806F15A +:105170004C005B691B681BB1019001F0C1FF0198F5 +:1051800003A901F0AFFF024648B1039B2946204620 +:1051900000F098F8002383F3118805B0F0BDFB6898 +:1051A0005A691268002AF5D01B8A013B1340F1D1DD +:1051B00004F18002EAE70000133138B550F82140CD +:1051C000ECB1302383F3118804F58053D3F8A4287D +:1051D0001368527903EB8203DB689B695D6845B114 +:1051E00004216018FFF768FE294604F1140001F05D +:1051F000AFFE2046FFF7B4FE002383F3118838BDCD +:105200007047000001F07CB901234022002110B555 +:10521000044600F8303BFCF7E3FB0023C4E901330C +:1052200010BD000010B53023044683F311882422FA +:10523000416000210C30FCF7D3FB204601F082F9DD +:1052400002230020237080F3118810BD70B500EB9D +:105250008103054650690E461446DA6018B11022E3 +:105260000021FCF7BDFBA06918B110220021FCF75A +:10527000B7FB31462846BDE8704001F069BA00002E +:1052800083682022002103F0011310B504468360D7 +:105290001030FCF7A5FB2046BDE8104001F0E4BA51 +:1052A000F0B4012500EB810447898D40E4683D435B +:1052B000A469458123600023A2606360F0BC01F013 +:1052C00001BB0000F0B4012500EB810407898D408B +:1052D000E4683D436469058123600023A260636044 +:1052E000F0BC01F077BB000070B502230025044636 +:1052F000242203702946C0F888500C3040F8045C22 +:10530000FCF76EFB204684F8705001F0B5F9636835 +:105310001B6823B129462046BDE87040184770BD80 +:105320000378052B10B504460AD080F88C3005238D +:10533000037043681B680BB1042198470023A360E6 +:1053400010BD00000178052906D190F88C20436833 +:1053500002701B6803B118477047000070B590F8E1 +:105360007030044613B1002380F8703004F18002DD +:10537000204601F09DFA63689B68B3B994F88030C9 +:1053800013F0600535D00021204601F08FFD00218B +:10539000204601F07FFD63681B6813B1062120469B +:1053A0009847062384F8703070BD2046984700283F +:1053B000E4D0B4F88630A26F9A4288BFA36794F90C +:1053C0008030A56F002B4FF0300380F20381002D59 +:1053D00000F0F280092284F8702083F31188002104 +:1053E0002046D4E91D23FFF76DFF002383F31188C6 +:1053F000DAE794F8812003F07F0343EA022340F2C6 +:105400000232934200F0C58021D8B3F5807F48D0A6 +:105410000DD8012B3FD0022B00F09380002BB2D18E +:1054200004F1880262670222A267E367C1E7B3F56D +:10543000817F00F09B80B3F5407FA4D194F8823047 +:10544000012BA0D1B4F8883043F0020332E0B3F569 +:10545000006F4DD017D8B3F5A06F31D0A3F5C0635E +:10546000012B90D86368204694F882205E6894F8F7 +:105470008310B4F88430B047002884D04368636751 +:105480000368A3671AE0B3F5106F36D040F6024206 +:1054900093427FF478AF5C4B63670223A3670023DA +:1054A000C3E794F88230012B7FF46DAFB4F88830F5 +:1054B00023F00203A4F88830C4E91D55E56778E7B6 +:1054C000B4F88030B3F5A06F0ED194F88230204646 +:1054D00084F88A3001F02EF963681B6813B101214A +:1054E00020469847032323700023C4E91D339CE71B +:1054F00004F18B0363670123C3E72378042B10D1E6 +:10550000302383F311882046FFF7BAFE85F3118814 +:105510000321636884F88B5021701B680BB120460F +:10552000984794F88230002BDED084F88B30042327 +:10553000237063681B68002BD6D002212046984751 +:10554000D2E794F8843020461D0603F00F010AD5F7 +:1055500001F0A0F9012804D002287FF414AF2B4BEE +:105560009AE72B4B98E701F087F9F3E794F882303C +:10557000002B7FF408AF94F8843013F00F01B3D000 +:105580001A06204602D501F0A9FCADE701F09AFC0D +:10559000AAE794F88230002B7FF4F5AE94F88430BB +:1055A00013F00F01A0D01B06204602D501F07EFCAF +:1055B0009AE701F06FFC97E7142284F8702083F3D8 +:1055C00011882B462A4629462046FFF769FE85F3B7 +:1055D0001188E9E65DB1152284F8702083F3118803 +:1055E00000212046D4E91D23FFF75AFEFDE60B22D9 +:1055F00084F8702083F311882B462A4629462046DA +:10560000FFF760FEE3E700BFB87D0008B07D00084B +:10561000B47D000838B590F870300446002B3ED0B9 +:10562000063BDAB20F2A34D80F2B32D8DFE803F06A +:10563000373131082232313131313131313137377F +:10564000856FB0F886309D4214D2C3681B8AB5FBC3 +:10565000F3F203FB12556DB9302383F311882B4607 +:105660002A462946FFF72EFE85F311880A2384F87F +:1056700070300EE0142384F87030302383F31188E7 +:10568000002320461A461946FFF70AFE002383F33B +:10569000118838BDC36F03B198470023E7E70021A5 +:1056A000204601F003FC0021204601F0F3FB636873 +:1056B0001B6813B10621204698470623D7E7000050 +:1056C00010B590F870300446142B29D017D8062B4B +:1056D00005D001D81BB110BD093B022BFBD800211E +:1056E000204601F0E3FB0021204601F0D3FB636874 +:1056F0001B6813B1062120469847062319E0152B95 +:10570000E9D10B2380F87030302383F31188002314 +:105710001A461946FFF7D6FD002383F31188DAE70E +:10572000C3689B695B68002BD5D1C36F03B19847F1 +:10573000002384F87030CEE7002382680375036984 +:105740001B6899689142FBD25A68036042601060FE +:105750005860704700238268037503691B68996865 +:105760009142FBD85A6803604260106058607047ED +:1057700008B50846302383F311880B7D032B05D031 +:10578000042B0DD02BB983F3118808BD8B6900223F +:105790001A604FF0FF338361FFF7CEFF0023F2E77B +:1057A000D1E9003213605A60F3E70000FFF7C4BF8D +:1057B000054BD96808751868026853601A600122A1 +:1057C000D8600275FAF726BE486900200C4B30B548 +:1057D000DD684B1C87B004460FD02B46094A68464B +:1057E00000F05EF92046FFF7E3FF009B13B1684627 +:1057F00000F060F9A86907B030BDFFF7D9FFF9E7FD +:105800004869002071570008044B1A68DB689068EB +:105810009B68984294BF002001207047486900208F +:10582000084B10B51C68D868226853601A600122C2 +:10583000DC602275FFF78EFF01462046BDE8104070 +:10584000FAF7E8BD4869002038B5074C0123002568 +:10585000064907482370656001F036FD0223237076 +:1058600085F3118838BD00BFB06B0020C07D0008F3 +:105870004869002008B572B6044B186500F064FC56 +:1058800000F02AFD024B03221A70FEE7486900204F +:10589000B06B002000F044B9034A516853685B1AAA +:1058A0009842FBD8704700BF001000E08B600223D5 +:1058B000086108468B8270478368A3F1840243F82D +:1058C000142C026943F8442C426943F8402C094ADD +:1058D00043F8242CC268A3F1200043F8182C0222BC +:1058E00003F80C2C002203F80B2C034A43F8102C6D +:1058F000704700BF2D0400084869002008B5FFF775 +:10590000DBFFBDE80840FFF751BF0000024BDB683A +:1059100098610F20FFF74CBF48690020302383F3C4 +:105920001188FFF7F3BF000008B50146302383F369 +:1059300011880820FFF74AFF002383F3118808BD70 +:10594000064BDB6839B1426818605A6013604360E7 +:105950000420FFF73BBF4FF0FF307047486900203D +:105960000368984206D01A68026050601846996130 +:10597000FFF71CBF7047000038B504460D4620688D +:10598000844200D138BD036823605C608561FFF705 +:105990000DFFF4E7036810B59C68A2420CD85C6860 +:1059A0008A600B604C602160596099688A1A9A601D +:1059B0004FF0FF33836010BD121B1B68ECE7000043 +:1059C0000A2938BF0A2170B504460D460A26601917 +:1059D00001F072FC01F05AFC041BA54203D8751CAF +:1059E00004462E46F3E70A2E04D90120BDE8704094 +:1059F00001F0AABC70BD0000F8B5144B0D460A2A90 +:105A00004FF00A07D96103F11001826038BF0A2202 +:105A1000416019691446016048601861A81801F0D6 +:105A20003BFC01F033FC431B0646A34206D37C1C1F +:105A300028192746354601F03FFCF2E70A2F04D922 +:105A40000120BDE8F84001F07FBCF8BD48690020A6 +:105A5000F8B506460D4601F019FC0F4A134653F8F7 +:105A6000107F9F4206D12A4601463046BDE8F840E5 +:105A7000FFF7C2BFD169BB68441A2C1928BF2C4656 +:105A8000A34202D92946FFF79BFF2246314603482D +:105A9000BDE8F840FFF77EBF486900205869002044 +:105AA000C0E90323002310B45DF8044B4361FFF702 +:105AB000CFBF000010B5194C236998420DD0816802 +:105AC000D0E9003213605A609A680A449A60002351 +:105AD00003604FF0FF33A36110BD0268234643F813 +:105AE000102F53600022026022699A4203D1BDE860 +:105AF000104001F0DBBB936881680B44936001F0B8 +:105B0000C5FB2269E1699268441AA242E4D91144B2 +:105B1000BDE81040091AFFF753BF00BF48690020D5 +:105B20002DE9F047DFF8BC8008F110072C4ED8F8BB +:105B3000105001F0ABFBD8F81C40AA68031B9A4236 +:105B40003ED814444FF00009D5E90032C8F81C4093 +:105B500013605A60C5F80090D8F81030B34201D1F4 +:105B600001F0A4FB89F31188D5E903312846984751 +:105B7000302383F311886B69002BD8D001F086FBAA +:105B80006A69A0EB040982464A450DD2022001F061 +:105B9000DBFB0022D8F81030B34208D1514628462A +:105BA000BDE8F047FFF728BF121A2244F2E712EBD4 +:105BB00009092946384638BF4A46FFF7EBFEB5E7E4 +:105BC000D8F81030B34208D01444C8F81C00211A89 +:105BD000A960BDE8F047FFF7F3BEBDE8F08700BF5E +:105BE000586900204869002038B501F04FFB054A8C +:105BF000D2E90845031B181945F10001C2E9080163 +:105C000038BD00BF4869002000207047FEE7000053 +:105C1000704700004FF0FF307047000002290CD0A1 +:105C2000032904D00129074818BF00207047032A20 +:105C300005D8054800EBC2007047044870470020B3 +:105C4000704700BF987E00084C2300204C7E00085F +:105C500070B59AB005460846144601A900F0C2F88E +:105C600001A8FBF7B5FE431C0022C6B25B0010463C +:105C7000C5E9003423700323023404F8013C01AB6E +:105C8000D1B202348E4201D81AB070BD13F8011B94 +:105C9000013204F8010C04F8021CF1E708B53023C6 +:105CA00083F311880348FFF729FA002383F311884F +:105CB00008BD00BFB86B002090F8803003F01F02D1 +:105CC000012A07D190F881200B2A03D10023C0E9D3 +:105CD0001D3315E003F06003202B08D1B0F88430A9 +:105CE0002BB990F88120212A03D81F2A04D8FFF766 +:105CF000E7B9222AEBD0FAE7034A42670722826714 +:105D0000C3670120704700BF4323002007B5052962 +:105D100017D8DFE801F0191603191920302383F38F +:105D20001188104A01210190FFF790FA0198022191 +:105D30000D4AFFF78BFA0D48FFF7ACF9002383F308 +:105D4000118803B05DF804FB302383F31188074802 +:105D5000FFF776F9F2E7302383F311880348FFF762 +:105D60008DF9EBE7EC7D0008107E0008B86B002091 +:105D700038B50C4D0C4C2A460C4904F10800FFF7CD +:105D800067FF05F1CA0204F110000949FFF760FF3F +:105D900005F5CA7204F118000649BDE83840FFF75E +:105DA00057BF00BF908400204C230020CC7D00080A +:105DB000D67D0008E17D000870B5044608460D4612 +:105DC000FBF706FEC6B22046013403780BB918462D +:105DD00070BD32462946FBF7E7FD0028F3D10120CC +:105DE000F6E700002DE9F04705460C46FBF7F0FD0D +:105DF0002C49C6B22846FFF7DFFF08B11036F6B2CD +:105E000029492846FFF7D8FF08B11036F6B2632EAD +:105E10000BD8DFF89080DFF89090244FDFF898A03F +:105E20002E7846B92670BDE8F08729462046BDE8A1 +:105E3000F04701F06DBE252E30D10722414628469D +:105E4000FBF7B2FD80B91A4B224603F1140153F857 +:105E5000040B8B4242F8040BF9D1198807359B7863 +:105E6000173411809370DBE7082249462846FBF778 +:105E70009BFD98B9A21C0F4B197802320909C95D24 +:105E800002F8041C13F8011B01F00F015345C95D12 +:105E900002F8031CF0D118340835C1E7013504F8C5 +:105EA000016BBDE7B87E0008E17D0008C07E0008F8 +:105EB0002E7B000800E8F11F0CE8F11FBFF34F8FA5 +:105EC000044B1A695107FCD1D3F810215207F8D1BD +:105ED000704700BF0020005208B50D4B1B78ABB9CE +:105EE000FFF7ECFF0B4BDA68D10704D50A4A5A607A +:105EF00002F188325A60D3F80C21D20706D5064A3F +:105F0000C3F8042102F18832C3F8042108BD00BFA0 +:105F1000EE860020002000522301674508B5114B92 +:105F20001B78F3B9104B1A69510703D5DA6842F0B0 +:105F30004002DA60D3F81021520705D5D3F80C21BE +:105F400042F04002C3F80C21FFF7B8FF064BDA68B5 +:105F500042F00102DA60D3F80C2142F00102C3F8EA +:105F60000C2108BDEE860020002000520F289ABFA9 +:105F700000F5806040040020704700004FF40030BE +:105F800070470000102070470F2808B50BD8FFF7A6 +:105F9000EDFF00F500330268013204D10430834282 +:105FA000F9D1012008BD0020FCE700000F2838B51A +:105FB00005463FD8FFF782FF1F4CFFF78DFF4FF0DC +:105FC000FF3307286361C4F814311DD82361FFF73C +:105FD00075FF030243F02403E360E36843F08003AA +:105FE000E36023695A07FCD42846FFF767FFFFF7F1 +:105FF000BDFF4FF4003100F04BF92846FFF78EFF4C +:10600000BDE83840FFF7C0BFC4F81031FFF756FFB6 +:10601000A0F108031B0243F02403C4F80C31D4F8A8 +:106020000C3143F08003C4F80C31D4F810315B0715 +:10603000FBD4D9E7002038BD002000522DE9F84FED +:1060400005460C46104645EA0203DE0602D0002053 +:10605000BDE8F88F20F01F00DFF8BCB0DFF8BCA06F +:10606000FFF73AFF04EB0008444503D10120FFF796 +:1060700055FFEDE720222946204601F017FD10B913 +:1060800020352034F0E72B4605F120021F68791CEB +:10609000DDD104339A42F9D105F178431B481C4EF7 +:1060A000B3F5801F1B4B38BF184603F1F80332BF0E +:1060B000D946D1461E46FFF701FF0760A5EB040C49 +:1060C000336804F11C0143F002033360231FD9F845 +:1060D000007017F00507FAD153F8042F8B424CF8E3 +:1060E0000320F4D1BFF34F8FFFF7E8FE4FF0FF33EB +:1060F0002022214603602846336823F002033360E0 +:1061000001F0D4FC0028BBD03846B0E7142100527F +:106110000C20005214200052102000521021005276 +:1061200010B5084C237828B11BB9FFF7D5FE012321 +:10613000237010BD002BFCD02070BDE81040FFF78D +:10614000EDBE00BFEE86002038B5054D00240334B7 +:10615000696855F80C0B00F0ADF8122CF7D138BD7A +:10616000D47E0008084601F099BC000038B5EFF372 +:1061700011859DB9EFF30584C4F30804302334B1CD +:1061800083F31188FFF730FD85F3118838BD83F361 +:106190001188FFF729FD84F3118838BDBDE8384028 +:1061A000FFF722BD10B5FFF7E1FF104CC008104A01 +:1061B000002340EA4170C908A0FB04ECA0FB020EDA +:1061C0001CEB0000A1FB044CA1FB02125B41001977 +:1061D00043EB0C0011EB0E0142F10002411842F1B9 +:1061E0000000090941EA007010BD00BFCFF753E37A +:1061F000A59BC4200244074BD2B210B5904200D1F7 +:1062000010BD441C00B253F8200041F8040BE0B26A +:10621000F4E700BF504000580E4B30B51C6F24040B +:1062200005D41C6F1C671C6F44F400441C670A4CA7 +:1062300002442368D2B243F480732360074B904238 +:1062400000D130BD441C51F8045B00B243F820502B +:10625000E0B2F4E7004402580048025850400058A9 +:1062600007B5012201A90020FFF7C4FF019803B080 +:106270005DF804FB13B50446FFF7F2FFA04205D01A +:10628000012201A900200194FFF7C6FF02B010BD52 +:106290000144BFF34F8F064B884204D3BFF34F8FA7 +:1062A000BFF36F8F7047C3F85C022030F4E700BF84 +:1062B00000ED00E00144BFF34F8F064B884204D34A +:1062C000BFF34F8FBFF36F8F7047C3F8700220305A +:1062D000F4E700BF00ED00E070470000074B45F217 +:1062E00055521A6002225A6040F6FF729A604CF6CC +:1062F000CC421A600122024B1A70704700480058C5 +:10630000F4860020034B1B781BB1034B4AF6AA22EC +:106310001A607047F486002000480058034B1A6842 +:106320001AB9034AD2F8D0241A607047F0860020C8 +:1063300000400258024B4FF48032C3F8D02470471B +:106340000040025808B5FFF7E9FF024B1868C0F398 +:10635000806008BDF086002070B5BFF34F8FBFF39B +:106360006F8F1A4A0021C2F85012BFF34F8FBFF34C +:106370006F8F536943F400335361BFF34F8FBFF303 +:106380006F8FC2F88410BFF34F8FD2F8803043F67E +:10639000E074C3F3C900C3F34E335B0103EA0406A0 +:1063A000014646EA81750139C2F86052F9D2203BB4 +:1063B00013F1200FF2D1BFF34F8F536943F48033B1 +:1063C0005361BFF34F8FBFF36F8F70BD00ED00E0DF +:1063D000FEE70000214B2248224A70B5904237D395 +:1063E000214BC11EDA1C121A22F003028B4238BF65 +:1063F00000220021FBF7F4FA1C4A0023C2F8843083 +:10640000BFF34F8FD2F8803043F6E074C3F3C90076 +:10641000C3F34E335B0103EA0406014646EA817585 +:106420000139C2F86C52F9D2203B13F1200FF2D19E +:10643000BFF34F8FBFF36F8FBFF34F8FBFF36F8FDC +:106440000023C2F85032BFF34F8FBFF36F8F70BD80 +:1064500053F8041B40F8041BC0E700BF6881000824 +:10646000C8880020C8880020C888002000ED00E00F +:10647000074BD3F8D81021EA0001C3F8D810D3F89D +:10648000002122EA0002C3F80021D3F8003170474E +:106490000044025870B5D0E9244300224FF0FF3584 +:1064A0009E6804EB42135101D3F80009002805DA75 +:1064B000D3F8000940F08040C3F80009D3F8000B7E +:1064C000002805DAD3F8000B40F08040C3F8000B39 +:1064D000013263189642C3F80859C3F8085BE0D24A +:1064E0004FF00113C4F81C3870BD0000890141F061 +:1064F0002001016103699B06FCD41220FFF7CCB98F +:1065000010B50A4C2046FEF77FFE094BC4F89030C8 +:10651000084BC4F89430084C2046FEF775FE074B34 +:10652000C4F89030064BC4F8943010BDF8860020B3 +:1065300000000840407F00089487002000000440CD +:106540004C7F000870B503780546012B5CD1434BA6 +:10655000D0F89040984258D1414B0E216520D3F895 +:10656000D82042F00062C3F8D820D3F8002142F0CE +:106570000062C3F80021D3F80021D3F8802042F054 +:106580000062C3F88020D3F8802022F00062C3F8B4 +:106590008020D3F88030FEF79DFA324BE360324B17 +:1065A000C4F800380023D5F89060C4F8003EC0233A +:1065B00023604FF40413A3633369002BFCDA012337 +:1065C0000C203361FFF768F93369DB07FCD4122034 +:1065D000FFF762F93369002BFCDA00262846A66033 +:1065E000FFF758FF6B68C4F81068DB68C4F81468DC +:1065F000C4F81C6883BB1D4BA3614FF0FF3363617C +:10660000A36843F00103A36070BD194B9842C9D140 +:10661000134B4FF08060D3F8D82042F00072C3F8DB +:10662000D820D3F8002142F00072C3F80021D3F83B +:106630000021D3F8802042F00072C3F88020D3F804 +:10664000802022F00072C3F88020D3F88030FFF75A +:106650000FFF0E214D209EE7064BCDE7F886002068 +:10666000004402584014004003002002003C30C0A7 +:1066700094870020083C30C0F8B5D0F8904005461B +:1066800000214FF000662046FFF730FFD5F8941048 +:1066900000234FF001128F684FF0FF30C4F83438F8 +:1066A000C4F81C2804EB431201339F42C2F800696E +:1066B000C2F8006BC2F80809C2F8080BF2D20B68E6 +:1066C000D5F89020C5F898306362102313611669DD +:1066D00016F01006FBD11220FFF7DEF8D4F80038D0 +:1066E00023F4FE63C4F80038A36943F4402343F065 +:1066F0001003A3610923C4F81038C4F814380B4BF5 +:10670000EB604FF0C043C4F8103B094BC4F8003BAA +:10671000C4F81069C4F80039D5F8983003F11002B4 +:1067200043F48013C5F89820A362F8BD1C7F0008CD +:1067300040800010D0F8902090F88A10D2F80038ED +:1067400023F4FE6343EA0113C2F8003870470000E7 +:106750002DE9F84300EB8103D0F890500C468046B9 +:10676000DA680FFA81F94801166806F00306731E0D +:10677000022B05EB41134FF0000194BFB604384ED5 +:10678000C3F8101B4FF0010104F1100398BF06F18C +:10679000805601FA03F3916998BF06F50046002977 +:1067A0003AD0578A04F15801374349016F50D5F860 +:1067B0001C180B430021C5F81C382B180127C3F8FF +:1067C0001019A7405369611E9BB3138A928B9B08D3 +:1067D000012A88BF5343D8F89820981842EA034307 +:1067E00001F140022146C8F89800284605EB8202D4 +:1067F0005360FFF77BFE08EB8900C3681B8A43EAFE +:10680000845348341E4364012E51D5F81C381F436D +:10681000C5F81C78BDE8F88305EB4917D7F8001BCD +:1068200021F40041C7F8001BD5F81C1821EA030326 +:10683000C0E704F13F030B4A2846214605EB8303DA +:106840005A60FFF753FE05EB4910D0F8003923F4E6 +:106850000043C0F80039D5F81C3823EA0707D7E70A +:106860000080001000040002D0F894201268C0F8E4 +:106870009820FFF70FBE00005831D0F89030490142 +:106880005B5813F4004004D013F4001F0CBF022027 +:10689000012070474831D0F8903049015B5813F41B +:1068A000004004D013F4001F0CBF022001207047E9 +:1068B00000EB8101CB68196A0B6813604B68536069 +:1068C0007047000000EB810330B5DD68AA691368EA +:1068D000D36019B9402B84BF402313606B8A1468BE +:1068E000D0F890201C4402EB4110013C09B2B4FBEB +:1068F000F3F46343033323F0030343EAC44343F055 +:10690000C043C0F8103B2B6803F00303012B0ED1EA +:10691000D2F8083802EB411013F4807FD0F8003B26 +:1069200014BF43F0805343F00053C0F8003B02EB28 +:106930004112D2F8003B43F00443C2F8003B30BDA3 +:106940002DE9F041D0F8906005460C4606EB411366 +:10695000D3F8087B3A07C3F8087B08D5D6F8143873 +:106960001B0704D500EB8103DB685B689847FA07D7 +:106970001FD5D6F81438DB071BD505EB8403D9687F +:10698000CCB98B69488A5A68B2FBF0F600FB162234 +:106990008AB91868DA6890420DD2121AC3E9002445 +:1069A000302383F3118821462846FFF78BFF84F3B9 +:1069B0001188BDE8F081012303FA04F26B8923EA10 +:1069C00002036B81CB68002BF3D021462846BDE83B +:1069D000F041184700EB81034A0170B5DD68D0F83B +:1069E00090306C692668E66056BB1A444FF400206C +:1069F000C2F810092A6802F00302012A0AB20ED175 +:106A0000D3F8080803EB421410F4807FD4F800098F +:106A100014BF40F0805040F00050C4F8000903EB70 +:106A20004212D2F8000940F00440C2F800090122E5 +:106A3000D3F8340802FA01F10143C3F8341870BDE9 +:106A400019B9402E84BF4020206020681A442E8A45 +:106A50008419013CB4FBF6F440EAC44040F0005015 +:106A6000C6E700002DE9F843D0F8906005460C46D3 +:106A70004F0106EB4113D3F8088918F0010FC3F852 +:106A800008891CD0D6F81038DB0718D500EB810335 +:106A9000D3F80CC0DCF81430D3F800E0DA6896457F +:106AA00030D2A2EB0E024FF000091A60C3F8049036 +:106AB000302383F31188FFF78DFF89F3118818F0D5 +:106AC000800F1DD0D6F834380126A640334217D0A7 +:106AD00005EB84030134D5F89050D3F80CC0E4B230 +:106AE0002F44DCF8142005EB0434D2F800E05168A0 +:106AF000714514D3D5F8343823EA0606C5F834684E +:106B0000BDE8F883012303FA01F2038923EA0203B3 +:106B10000381DCF80830002BD1D09847CFE7AEEBEB +:106B20000103BCF81000834228BF0346D7F81809B8 +:106B300080B2B3EB800FE3D89068A0F1040959F854 +:106B4000048FC4F80080A0EB09089844B8F1040F42 +:106B5000F5D818440B4490605360C8E72DE9F84F0E +:106B6000D0F8905004466E69AB691E4016F4805808 +:106B70006E6103D0BDE8F84FFEF7B6BB002E12DA07 +:106B8000D5F8003E9B0705D0D5F8003E23F003035F +:106B9000C5F8003ED5F80438204623F00103C5F8B7 +:106BA0000438FEF7CFFB370505D52046FFF772FC0A +:106BB0002046FEF7B5FBB0040CD5D5F8083813F025 +:106BC000060FEB6823F470530CBF43F4105343F4E7 +:106BD000A053EB6031071BD56368DB681BB9AB6959 +:106BE00023F00803AB612378052B0CD1D5F8003EC8 +:106BF0009A0705D0D5F8003E23F00303C5F8003E00 +:106C00002046FEF79FFB6368DB680BB12046984780 +:106C1000F30200F1BA80B70226D5D4F8909000278D +:106C20004FF0010A09EB4712D2F8003B03F440236E +:106C3000B3F5802F11D1D2F8003B002B0DDA628919 +:106C40000AFA07F322EA0303638104EB8703DB6894 +:106C5000DB6813B13946204698470137D4F89430A1 +:106C6000FFB29B689F42DDD9F00619D5D4F8900099 +:106C7000026AC2F30A1702F00F0302F4F012B2F52F +:106C8000802F00F0CA80B2F5402F09D104EB8303B6 +:106C9000002200F58050DB681B6A974240F0B0800C +:106CA0003003D5F8185835D5E90303D5002120461F +:106CB000FFF746FEAA0303D501212046FFF740FE59 +:106CC0006B0303D502212046FFF73AFE2F0303D5BD +:106CD00003212046FFF734FEE80203D504212046B5 +:106CE000FFF72EFEA90203D505212046FFF728FE57 +:106CF0006A0203D506212046FFF722FE2B0203D5A8 +:106D000007212046FFF71CFEEF0103D5082120468E +:106D1000FFF716FE700340F1A780E90703D50021B5 +:106D20002046FFF79FFEAA0703D501212046FFF763 +:106D300099FE6B0703D502212046FFF793FE2F072C +:106D400003D503212046FFF78DFEEE0603D504216F +:106D50002046FFF787FEA80603D505212046FFF74A +:106D600081FE690603D506212046FFF77BFE2A0631 +:106D700003D507212046FFF775FEEB0574D52046A5 +:106D80000821BDE8F84FFFF76DBED4F890904FF0A2 +:106D9000000B4FF0010AD4F894305FFA8BF79B6830 +:106DA0009F423FF638AF09EB4713D3F8002902F4AE +:106DB0004022B2F5802F20D1D3F80029002A1CDA16 +:106DC000D3F8002942F09042C3F80029D3F80029F3 +:106DD000002AFBDB3946D4F89000FFF787FB2289B5 +:106DE0000AFA07F322EA0303238104EB8703DB6833 +:106DF0009B6813B13946204698470BF1010BCAE74F +:106E0000910701D1D0F80080072A02F101029CBF4E +:106E100003F8018B4FEA18283FE704EB830300F5E2 +:106E20008050DA68D2F818C0DCF80820DCE9001CD1 +:106E3000A1EB0C0C00218F4208D1DB689B699A689A +:106E40003A449A605A683A445A6029E711F0030FAD +:106E500001D1D0F800808C4501F1010184BF02F816 +:106E6000018B4FEA1828E6E7BDE8F88F08B503481C +:106E7000FFF774FEBDE80840FDF7BCBAF8860020B5 +:106E800008B50348FFF76AFEBDE80840FDF7B2BA4F +:106E900094870020D0F8903003EB4111D1F8003BEB +:106EA00043F40013C1F8003B70470000D0F8903065 +:106EB00003EB4111D1F8003943F40013C1F8003954 +:106EC00070470000D0F8903003EB4111D1F8003B3F +:106ED00023F40013C1F8003B70470000D0F8903055 +:106EE00003EB4111D1F8003923F40013C1F8003944 +:106EF0007047000030B50433039C0172002104FB8D +:106F00000325C160C0E90653049B0363059BC0E9E8 +:106F10000000C0E90422C0E90842C0E90A11436345 +:106F200030BD00000022416AC260C0E90411C0E91E +:106F30000A226FF00101FEF71FBD0000D0E9043204 +:106F4000934201D1C2680AB9181D704700207047EA +:106F5000036919600021C2680132C260C26913442A +:106F600082699342036124BF436A0361FEF7F8BC60 +:106F700038B504460D46E3683BB162690020131D35 +:106F80001268A3621344E36207E0237A33B9294607 +:106F90002046FEF7D5FC0028EDDA38BD6FF0010081 +:106FA000FBE70000C368C269013BC3604369134447 +:106FB00082699342436124BF436A43610023836231 +:106FC000036B03B11847704770B53023044683F351 +:106FD0001188866A3EB9FFF7CBFF054618B186F3E4 +:106FE0001188284670BDA36AE26A13F8015B9342D8 +:106FF000A36202D32046FFF7D5FF002383F3118855 +:10700000EFE700002DE9F84F04460E461746984674 +:107010004FF0300989F311880025AA46D4F828B02A +:10702000BBF1000F09D141462046FFF7A1FF20B177 +:107030008BF311882846BDE8F88FD4E90A12A7EB34 +:10704000050B521A934528BF9346BBF1400F1BD93D +:10705000334601F1400251F8040B914243F8040B0E +:10706000F9D1A36A403640354033A362D4E90A23FC +:107070009A4202D32046FFF795FF8AF31188BD425A +:10708000D8D289F31188C9E730465A46FAF782FC0C +:10709000A36A5E445D445B44A362E7E710B5029CCB +:1070A0000433017203FB0421C460C0E9061300230A +:1070B000C0E90A33039B0363049BC0E90000C0E9F5 +:1070C0000422C0E90842436310BD0000026A6FF069 +:1070D0000101C260426AC0E904220022C0E90A221A +:1070E000FEF74ABCD0E904239A4201D1C26822B912 +:1070F000184650F8043B0B60704700231846FAE727 +:10710000C3680021C2690133C360436913448269C3 +:107110009342436124BF436A4361FEF721BC0000F0 +:1071200038B504460D46E3683BB1236900201A1DBB +:10713000A262E2691344E36207E0237A33B9294685 +:107140002046FEF7FDFB0028EDDA38BD6FF00100A8 +:10715000FBE7000003691960C268013AC260C269B6 +:10716000134482699342036124BF436A036100238D +:107170008362036B03B118477047000070B530237A +:107180000D460446114683F31188866A2EB9FFF72F +:10719000C7FF10B186F3118870BDA36A1D70A36A82 +:1071A000E26A01339342A36204D3E16920460439C1 +:1071B000FFF7D0FF002080F31188EDE72DE9F84FAD +:1071C00004460D46904699464FF0300A8AF31188DE +:1071D0000026B346A76A4FB949462046FFF7A0FFED +:1071E00020B187F311883046BDE8F88FD4E90A074B +:1071F0003A1AA8EB0607974228BF1746402F1BD91B +:1072000005F1400355F8042B9D4240F8042BF9D1B9 +:10721000A36A40364033A362D4E90A239A4204D3D6 +:10722000E16920460439FFF795FF8BF31188464545 +:10723000D9D28AF31188CDE729463A46FAF7AAFB54 +:10724000A36A3D443E443B44A362E5E7D0E90423FE +:107250009A4217D1C3689BB1836A8BB1043B9B1AD6 +:107260000ED01360C368013BC360C3691A448369CD +:107270009A42026124BF436A0361002383620123AF +:10728000184670470023FBE700F024B9014B586A09 +:10729000704700BF000C0040034B002258631A6186 +:1072A0000222DA60704700BF000C0040014B002250 +:1072B000DA607047000C0040014B5863704700BF14 +:1072C000000C0040FEE7000070B51B4B0025044693 +:1072D00086B058600E4685620163FDF763F804F1DD +:1072E0001003A560E562C4E904334FF0FF33C4E93D +:1072F0000044C4E90635FFF7C9FF2B46024604F1F6 +:1073000034012046C4E9082380230C4A2565FEF792 +:10731000CDFA01230A4AE06000920375684672685C +:107320000192B268CDE90223064BCDE90435FEF7A0 +:10733000E5FA06B070BD00BFB06B0020587F0008B2 +:107340005D7F0008C5720008024AD36A1843D06204 +:10735000704700BF486900204B6843608B688360BA +:10736000CB68C3600B6943614B6903628B694362FD +:107370000B6803607047000008B53C4B40F2FF719A +:107380003B48D3F888200A43C3F88820D3F88820E4 +:1073900022F4FF6222F00702C3F88820D3F8882085 +:1073A000D3F8E0200A43C3F8E020D3F808210A43C9 +:1073B000C3F808212F4AD3F808311146FFF7CCFF54 +:1073C00000F5806002F11C01FFF7C6FF00F5806048 +:1073D00002F13801FFF7C0FF00F5806002F15401AF +:1073E000FFF7BAFF00F5806002F17001FFF7B4FF0C +:1073F00000F5806002F18C01FFF7AEFF00F58060C0 +:1074000002F1A801FFF7A8FF00F5806002F1C401B6 +:10741000FFF7A2FF00F5806002F1E001FFF79CFF9B +:1074200000F5806002F1FC01FFF796FF02F58C7118 +:1074300000F58060FFF790FF00F018F90E4BD3F8CD +:10744000902242F00102C3F89022D3F8942242F035 +:107450000102C3F894220522C3F898204FF060522D +:10746000C3F89C20054AC3F8A02008BD0044025878 +:1074700000000258647F000800ED00E01F000803D0 +:1074800008B500F0D5FAFEF7DFF90F4BD3F8DC2092 +:1074900042F04002C3F8DC20D3F8042122F040027D +:1074A000C3F80421D3F80431084B1A6842F00802EB +:1074B0001A601A6842F004021A60FEF72FFFBDE856 +:1074C0000840FEF755BC00BF0044025800180248AF +:1074D00070470000114BD3F8E82042F00802C3F8CF +:1074E000E820D3F8102142F00802C3F810210C4A1A +:1074F000D3F81031D36B43F00803D363C722094B91 +:107500009A624FF0FF32DA6200229A615A63DA60BF +:107510005A6001225A611A60704700BF0044025845 +:107520000010005C000C0040094A08B51169D368DE +:107530000B40D9B29B076FEA0101116107D53023D7 +:1075400083F31188FEF7A6F9002383F3118808BDA1 +:10755000000C0040064BD3F8DC200243C3F8DC20CB +:10756000D3F804211043C3F80401D3F80431704761 +:107570000044025808B53C4B4FF0FF31D3F880204F +:1075800062F00042C3F88020D3F8802002F000426D +:10759000C3F88020D3F88020D3F88420C3F8841067 +:1075A000D3F884200022C3F88420D3F88400D86F55 +:1075B00040F0FF4040F4FF0040F4DF4040F07F0027 +:1075C000D867D86F20F0FF4020F4FF0020F4DF40A0 +:1075D00020F07F00D867D86FD3F888006FEA40505A +:1075E0006FEA5050C3F88800D3F88800C0F30A004F +:1075F000C3F88800D3F88800D3F89000C3F890103F +:10760000D3F89000C3F89020D3F89000D3F89400FA +:10761000C3F89410D3F89400C3F89420D3F89400DE +:10762000D3F89800C3F89810D3F89800C3F89820BE +:10763000D3F89800D3F88C00C3F88C10D3F88C00E2 +:10764000C3F88C20D3F88C00D3F89C00C3F89C10AE +:10765000D3F89C10C3F89C20D3F89C30FDF74CF86D +:10766000BDE8084000F0B8B90044025808B501224E +:10767000534BC3F80821534BD3F8F42042F00202D5 +:10768000C3F8F420D3F81C2142F00202C3F81C21F5 +:107690000222D3F81C314C4BDA605A689104FCD5B5 +:1076A0004A4A1A6001229A60494ADA6000221A6145 +:1076B0004FF440429A61444B9A699204FCD51A688F +:1076C00042F480721A603F4B1A6F12F4407F04D06C +:1076D0004FF480321A6700221A671A6842F00102DA +:1076E0001A60384B1A685007FCD500221A611A69D3 +:1076F00012F03802FBD1012119604FF0804159602E +:107700005A67344ADA62344A1A611A6842F480329B +:107710001A602C4B1A689103FCD51A6842F4805207 +:107720001A601A689204FCD52C4A2D499A620022EC +:107730005A63196301F57C01DA6301F5E771996316 +:107740005A64284A1A64284ADA621A6842F0A8522F +:107750001A601C4B1A6802F02852B2F1285FF9D166 +:1077600048229A614FF48862DA6140221A621F4A05 +:10777000DA641F4A1A651F4A5A651F4A9A653223FE +:107780001E4A1360136803F00F03022BFAD10D4A4F +:10779000136943F003031361136903F03803182BD3 +:1077A000FAD14FF00050FFF7D5FE4FF08040FFF7C1 +:1077B000D1FE4FF00040BDE80840FFF7CBBE00BF50 +:1077C00000800051004402580048025800C000F0F8 +:1077D000020000010000FF010088900832206000D4 +:1077E00063020901470E0508DD0BBF0120000020E0 +:1077F000000001100910E0000001011000200052FB +:107800004FF0B04208B5D2F8883003F00103C2F857 +:10781000883023B1044A13680BB150689847BDE81B +:107820000840FCF7E7BD00BF488800204FF0B04299 +:1078300008B5D2F8883003F00203C2F8883023B1CB +:10784000044A93680BB1D0689847BDE80840FCF73C +:10785000D1BD00BF488800204FF0B04208B5D2F833 +:10786000883003F00403C2F8883023B1044A136956 +:107870000BB150699847BDE80840FCF7BBBD00BF9D +:10788000488800204FF0B04208B5D2F8883003F0A5 +:107890000803C2F8883023B1044A93690BB1D06958 +:1078A0009847BDE80840FCF7A5BD00BF4888002008 +:1078B0004FF0B04208B5D2F8883003F01003C2F898 +:1078C000883023B1044A136A0BB1506A9847BDE867 +:1078D0000840FCF78FBD00BF488800204FF0B04340 +:1078E00010B5D3F8884004F47872C3F88820A30652 +:1078F00004D5124A936A0BB1D06A9847600604D542 +:107900000E4A136B0BB1506B9847210604D50B4AF6 +:10791000936B0BB1D06B9847E20504D5074A136C03 +:107920000BB1506C9847A30504D5044A936C0BB176 +:10793000D06C9847BDE81040FCF75CBD488800203B +:107940004FF0B04310B5D3F8884004F47C42C3F83C +:107950008820620504D5164A136D0BB1506D984707 +:10796000230504D5124A936D0BB1D06D9847E004FE +:1079700004D50F4A136E0BB1506E9847A10404D57D +:107980000B4A936E0BB1D06E9847620404D5084A37 +:10799000136F0BB1506F9847230404D5044A936FBB +:1079A0000BB1D06F9847BDE81040FCF723BD00BF76 +:1079B0004888002008B50348FDF706F8BDE80840F0 +:1079C000FCF718BDD864002008B5FFF7ADFDBDE891 +:1079D0000840FCF70FBD0000062108B50846FDF77A +:1079E00079F806210720FDF775F806210820FDF734 +:1079F00071F806210920FDF76DF806210A20FDF730 +:107A000069F806211720FDF765F806212820FDF703 +:107A100061F809217A20FDF75DF807213220FDF792 +:107A200059F80C215220BDE80840FDF753B800007A +:107A300008B5FFF79FFD00F00DF8FDF709FAFDF717 +:107A4000E1FBFDF7B3FAFFF743FDBDE80840FFF7A0 +:107A50001BBC00000023054A19460133102BC2E964 +:107A6000001102F10802F8D1704700BF48880020D9 +:107A70000B460146184600F003B8000000F00EB8AF +:107A800010B5054C13462CB10A4601460220AFF34F +:107A9000008010BD2046FCE700000000024B0146BC +:107AA0001868FEF75FBB00BF6C23002010B50139DA +:107AB0000244904201D1002005E0037811F8014F03 +:107AC000A34201D0181B10BD0130F2E72DE9F041AF +:107AD000A3B1C91A17780144044603F1FF3C8C4254 +:107AE000204601D9002009E00578BD4204F10104D7 +:107AF000F5D10CEB0405D618A54201D1BDE8F08103 +:107B000015F8018D16F801EDF045F5D0E7E7000016 +:107B1000034611F8012B03F8012B002AF9D1704715 +:107B20006F72672E6172647570696C6F742E437525 +:107B300062654F72616E67652D7065726970682D40 +:107B4000686561767900000053544D333248373F01 +:107B50003F3F0053544D3332483733782F37327814 +:107B60000053544D3332483734332F3735332F37A2 +:107B70003530000001105A00031059000120580050 +:107B80000320560040A2E4F1646891060041A3E599 +:107B9000F26569920700000043414E464449666120 +:107BA00063653A204D6573736167652052414D20CE +:107BB0004F766572666C6F77210000004261642029 +:107BC00043414E496661636520696E6465782E00A5 +:107BD000000100000001FF0000A0004000A40040E0 +:107BE0000000000000000000C92A0008512300081E +:107BF00051320008C1230008CD230008E527000802 +:107C000045250008892300088D2300086523000806 +:107C10004D230008A127000871230008B93300088C +:107C20007D2300087527000801040E05054B02029C +:107C30000E05054B04010E05054B05010B04044B15 +:107C4000080106030346000010000240080002403D +:107C50000008024000000B0028000240080002401B +:107C60000408024006010C004000024008000240E7 +:107C70000808024010020D005800024008000240AF +:107C80000C08024016030E00700002400C00024077 +:107C90001008024000040F00880002400C0002405F +:107CA0001408024006051000A00002400C0002402B +:107CB0001808024010061100B80002400C000240F3 +:107CC0001C08024016072F0010040240080402405E +:107CD000200802400008380028040240080402403E +:107CE000240802400609390040040240080402400A +:107CF00028080240100A3A005804024008040240D2 +:107D00002C080240160B3B00700402400C04024099 +:107D100030080240000C3C00880402400C04024081 +:107D200034080240060D4400A00402400C04024046 +:107D300038080240100E4500B80402400C0402400E +:107D40003C080240160F46000096000000000000AC +:107D50000000000000000000000000000000000023 +:107D600000000000114E0008FD4D0008394E0008CB +:107D7000254E0008314E00081D4E0008094E00082F +:107D8000F54D0008454E000800000000294F00088E +:107D9000154F0008514F00083D4F0008494F00089B +:107DA000354F0008214F00080D4F00085D4F0008B7 +:107DB000000000000100000000000000633000002F +:107DC000BC7D0008A0690020B06B00204172647582 +:107DD00050696C6F740025424F415244252D424C2E +:107DE000002553455249414C250000000200000087 +:107DF0000000000049510008B9510008400040004F +:107E00006084002070840020020000000000000058 +:107E10000300000000000000015200080000000004 +:107E2000100000008084002000000000010000001D +:107E300000000000F8860020010102000D5D00082E +:107E40001D5C0008B95C00089D5C00084300000050 +:107E5000547E000809024300020100C032090400F8 +:107E600000010202010005240010010524010001A7 +:107E7000042402020524060001070582030800FF0E +:107E800009040100020A0000000705010240000089 +:107E9000070581024000000012000000A07E0008DB +:107EA00012011001020000400912415700020102B4 +:107EB000030100000403090425424F4152442500F8 +:107EC0003031323334353637383941424344454610 +:107ED000000000000001002000FF0100020000007F +:107EE0000000003000000400080000000000002432 +:107EF00000000800040000000004000000FC000076 +:107F000002000000000004300080000008000000B3 +:107F10000000003800000100010000000000000027 +:107F20005D53000815560008C15600084000400087 +:107F300030880020308800200100000040880020A8 +:107F40008000000040010000080000000001000067 +:107F500000100000080000006D61696E0069646C2B +:107F6000650000000000802A00000000AAAAAAAA5A +:107F700000000024FFFF00000000000000A00A0035 +:107F80000021000200000000AAAAAAAA0000000026 +:107F9000FFFF000000000009000009001400005469 +:107FA00000000000AAAAAAAA14000054FFFF0000C3 +:107FB00000000000000000000A4010000000000067 +:107FC000AAAA8AAA00401000FFFF00009900000042 +:107FD000000000000081020000000000AAAAAAAA76 +:107FE00000410100FFFF00000000007007000000DA +:107FF0000000000000000000AAAAAAAA00000000D9 +:10800000FFFF000000000000000000000000000072 +:1080100000000000AAAAAAAA00000000FFFF0000BA +:108020000000000000000000000000000000000050 +:10803000AAAAAAAA00000000FFFF0000000000009A +:10804000000000000000000000000000AAAAAAAA88 +:1080500000000000FFFF0000000000000000000022 +:108060000000000000000000AAAAAAAA0000000068 +:10807000FFFF000000000000000000000000000002 +:1080800000000000AAAAAAAA00000000FFFF00004A +:108090000000000000000000780500000000000063 +:1080A00000001E0000000000FE2A0100D2040000B3 +:1080B000FF000000B86B0020D86400200000000022 +:1080C000487B000883040000537B00085004000034 +:1080D000617B000800960000000008009600000088 +:1080E0000008000004000000B47E0008000000004A +:1080F0000000000000000000000000000000000080 +:1081000000000000702300200000000000000000BC +:10811000000000000000000000000000000000005F +:10812000000000000000000000000000000000004F +:10813000000000000000000000000000000000003F +:10814000000000000000000000000000000000002F +:10815000000000000000000000000000000000001F +:08816000000000000000000017 :00000001FF diff --git a/Tools/bootloaders/CubeOrange-periph_bl.bin b/Tools/bootloaders/CubeOrange-periph_bl.bin index e0358397d22ef9..a470da6051a965 100755 Binary files a/Tools/bootloaders/CubeOrange-periph_bl.bin and b/Tools/bootloaders/CubeOrange-periph_bl.bin differ diff --git a/Tools/bootloaders/CubeOrange-periph_bl.hex b/Tools/bootloaders/CubeOrange-periph_bl.hex index c1a27f91483174..c5edc232014275 100644 --- a/Tools/bootloaders/CubeOrange-periph_bl.hex +++ b/Tools/bootloaders/CubeOrange-periph_bl.hex @@ -1,2013 +1,2072 @@ :020000040800F2 -:1000000000060020F50500086135000819350008D4 -:10001000413500081935000839350008F705000892 -:10002000F7050008F7050008F70500084545000832 -:10003000F7050008F7050008F7050008F7050008B0 -:10004000F7050008F7050008F7050008F7050008A0 -:10005000F7050008F70500086575000891750008A8 -:10006000BD750008E975000815760008F705000859 -:10007000F7050008F7050008F7050008F705000870 -:10008000F7050008F7050008F7050008C93400085F -:10009000F1340008DD340008053500084176000819 -:1000A000F7050008F7050008F7050008F705000840 -:1000B000F7050008F7050008F7050008F705000830 -:1000C000F7050008F7050008F7050008F705000820 -:1000D000F7050008F7050008F7050008F705000810 -:1000E000A5760008F7050008F7050008F7050008E1 -:1000F000F7050008F7050008F7050008F7050008F0 -:10010000F7050008F70500082D770008F705000837 -:10011000F7050008F7050008F7050008F7050008CF -:10012000F7050008F7050008F7050008F7050008BF -:10013000F7050008F7050008F7050008F7050008AF -:10014000F7050008F7050008F7050008F70500089F -:10015000F7050008F7050008F7050008F70500088F -:10016000F7050008F7050008F7050008F70500087F -:10017000F7050008ED6B0008F7050008F705000813 -:10018000F7050008F705000819770008F7050008CB -:10019000F7050008F7050008F7050008F70500084F -:1001A000F7050008F7050008F7050008F70500083F -:1001B000F7050008F7050008F7050008F70500082F -:1001C000F7050008F7050008F7050008F70500081F -:1001D000F7050008D96B0008F7050008F7050008C7 -:1001E000F7050008F7050008F7050008F7050008FF -:1001F000F7050008F7050008F7050008F7050008EF -:10020000F7050008F7050008F7050008F7050008DE -:10021000F7050008F7050008F7050008F7050008CE -:10022000F7050008F7050008F7050008F7050008BE -:10023000F7050008F7050008F7050008F7050008AE -:10024000F7050008F7050008F7050008F70500089E -:10025000F7050008F7050008F7050008F70500088E -:10026000F7050008F7050008F7050008F70500087E -:10027000F7050008F7050008F7050008F70500086E -:10028000F7050008F7050008F7050008F70500085E -:10029000F7050008F7050008F7050008F70500084E -:1002A000F7050008F7050008F7050008F70500083E -:1002B000F7050008F7050008F7050008F70500082E -:1002C000F7050008F7050008F7050008F70500081E -:1002D000F7050008F7050008F7050008F70500080E -:1002E000111A0008000000000000000000000000DB -:1002F00053B94AB9002908BF00281CBF4FF0FF318D -:100300004FF0FF3000F074B9ADF1080C6DE904CE88 -:1003100000F006F8DDF804E0DDE9022304B07047E0 -:100320002DE9F047089D04468E46002B4DD18A42A8 -:10033000944669D9B2FA82F252B101FA02F3C2F1DB -:10034000200120FA01F10CFA02FC41EA030E94406C -:100350004FEA1C48210CBEFBF8F61FFA8CF708FB8D -:1003600016E341EA034306FB07F199420AD91CEB65 -:10037000030306F1FF3080F01F81994240F21C8197 -:10038000023E63445B1AA4B2B3FBF8F008FB1033DF -:1003900044EA034400FB07F7A7420AD91CEB040414 -:1003A00000F1FF3380F00A81A74240F207816444E4 -:1003B000023840EA0640E41B00261DB1D440002369 -:1003C000C5E900433146BDE8F0878B4209D9002DCD -:1003D00000F0EF800026C5E9000130463146BDE857 -:1003E000F087B3FA83F6002E4AD18B4202D38242C1 -:1003F00000F2F980841A61EB030301209E46002D70 -:10040000E0D0C5E9004EDDE702B9FFDEB2FA82F2C4 -:10041000002A40F09280A1EB0C014FEA1C471FFA22 -:100420008CFE0126200CB1FBF7F307FB131140EA09 -:1004300001410EFB03F0884208D91CEB010103F1D6 -:10044000FF3802D2884200F2CB804346091AA4B298 -:10045000B1FBF7F007FB101144EA01440EFB00FE6C -:10046000A64508D91CEB040400F1FF3102D2A645D1 -:1004700000F2BB800846A4EB0E0440EA03409CE770 -:10048000C6F12007B34022FA07FC4CEA030C20FA1D -:1004900007F401FA06F31C43F9404FEA1C4900FA3D -:1004A00006F3B1FBF9F8200C1FFA8CFE09FB1811BA -:1004B00040EA014108FB0EF0884202FA06F20BD92D -:1004C0001CEB010108F1FF3A80F08880884240F27D -:1004D0008580A8F102086144091AA4B2B1FBF9F0C1 -:1004E00009FB101144EA014100FB0EFE8E4508D9BC -:1004F0001CEB010100F1FF346CD28E456AD9023841 -:10050000614440EA0840A0FB0294A1EB0E01A14225 -:10051000C846A64656D353D05DB1B3EB080261EB93 -:100520000E0101FA07F722FA06F3F1401F43C5E96D -:10053000007100263146BDE8F087C2F12003D840A3 -:100540000CFA02FC21FA03F3914001434FEA1C47E5 -:100550001FFA8CFEB3FBF7F007FB10360B0C43EAD7 -:10056000064300FB0EF69E4204FA02F408D91CEB87 -:10057000030300F1FF382FD29E422DD90238634485 -:100580009B1B89B2B3FBF7F607FB163341EA034125 -:1005900006FB0EF38B4208D91CEB010106F1FF3874 -:1005A00016D28B4214D9023E6144C91A46EA00466B -:1005B00038E72E46284605E70646E3E61846F8E6FD -:1005C0004B45A9D2B9EB020864EB0C0E0138A3E746 -:1005D0004646EAE7204694E74046D1E7D0467BE727 -:1005E000023B614432E7304609E76444023842E79F -:1005F000704700BF02E000F000F8FEE772B637482F -:1006000080F30888364880F3098836483649086000 -:1006100040F20000CCF200004EF63471CEF2000140 -:100620000860BFF34F8FBFF36F8F40F20000C0F23E -:10063000F0004EF68851CEF200010860BFF34F8FF4 -:10064000BFF36F8F4FF00000E1EE100A4EF63C71E1 -:10065000CEF200010860062080F31488BFF36F8F8C -:1006600005F030FD06F03EFD4FF055301F491B4AA6 -:1006700091423CBF41F8040BFAE71D49184A9142E8 -:100680003CBF41F8040BFAE71A491B4A1B4B9A423C -:100690003EBF51F8040B42F8040BF8E7002018495C -:1006A000184A91423CBF41F8040BFAE705F048FDB7 -:1006B00006F09CFD144C154DAC4203DA54F8041BB3 -:1006C0008847F9E700F042F8114C124DAC4203DACA -:1006D00054F8041B8847F9E705F030BD00060020F8 -:1006E000002200200000000808ED00E000000020CB -:1006F00000060020E07C000800220020D02200201C -:10070000D022002030870020E0020008E402000828 -:10071000E4020008E40200082DE9F04F2DED108AF4 -:10072000C1F80CD0D0F80CD0BDEC108ABDE8F08F29 -:10073000002383F311882846A047002004F0AAFF75 -:10074000FEE704F003FF00DFFEE70000F8B501F06C -:1007500075F905F03BFC074605F0AAFC0546B8BB59 -:10076000204B9F4234D001339F4234D027F0FF0208 -:100770001D4B9A4232D12E4642F21074F8B200F06C -:1007800093FF00F097FF08B10024264601F04CFDCE -:1007900020B10024032000F07BF8264635B1134B2E -:1007A0009F4203D0002405F07BFC2646002005F084 -:1007B00017FC0EB100F082F801F0E2FA00F0AEFF93 -:1007C00001F0B8F9204600F029F900F077F8F9E7D0 -:1007D0002E460024D5E704460126D2E7064641F21C -:1007E0008834CEE7010007B0000008B0263A09B00F -:1007F00008B501F06BF9A0F120035842584108BD3B -:1008000007B541F21203022101A8ADF8043001F04E -:100810007BF903B05DF804FB38B5302383F311880E -:10082000174803680BB105F001F80023154A4FF48F -:100830007A71134804F0F0FF002383F31188124CFF -:10084000236813B12368013B2360636813B16368B5 -:10085000013B63600D4D2B7833B963687BB902208F -:1008600001F010FA322363602B78032B07D1636801 -:100870002BB9022001F006FA4FF47A73636038BD99 -:10088000D022002019080008F0230020E8220020D0 -:10089000084B187003280CD8DFE800F008050208A0 -:1008A000022001F0EDB9022001F0E8B9024B00226C -:1008B0005A607047E8220020F0230020F8B501F0CC -:1008C000B3FC30B14D4B03221A7000224C4B5A60DE -:1008D000F8BD4C4B4C4A1C4619680131F8D0043322 -:1008E0009342F9D16268494B9A42F1D9484B9B68CF -:1008F00003F1006303F500339A42E9D205F0A4FB4B -:1009000005F0B6FB002001F02FF90220FFF7C0FF31 -:10091000404B0021D3F8E820C3F8E810D3F81021A9 -:10092000C3F81011D3F81021D3F8EC20C3F8EC1061 -:10093000D3F81421C3F81411D3F81421D3F8F020FC -:10094000C3F8F010D3F81821C3F81811D3F8182100 -:10095000D3F8802042F00072C3F88020D3F88020C2 -:1009600022F00072C3F88020D3F8803072B64FF0C6 -:10097000E023C3F8084DD4E90004BFF34F8FBFF361 -:100980006F8F254AC2F88410BFF34F8F536923F449 -:1009900080335361BFF34F8FD2F8803043F6E07657 -:1009A000C3F3C905C3F34E335B0103EA060C2946C2 -:1009B0004CEA81770139C2F87472F9D2203B13F105 -:1009C000200FF2D1BFF34F8FBFF36F8FBFF34F8F65 -:1009D000BFF36F8F536923F4003353610023C2F8D0 -:1009E0005032BFF34F8FBFF36F8F302383F31188E3 -:1009F000854680F3088820476AE700BFE822002088 -:100A0000F02300200000020820000208FFFF010878 -:100A1000002200200044025800ED00E02DE9F04FD4 -:100A200093B0B74B2022FF2100900AA89D6801F0E7 -:100A300051F9B44A1378A3B90121B3481170036086 -:100A4000302383F3118803680BB104F0EFFE002319 -:100A5000AE4A4FF47A71AC4804F0DEFE002383F313 -:100A60001188009B13B1AA4B009A1A60A94A137807 -:100A7000032B03D000231370A54A53604FF0000AE4 -:100A8000009CD3465646D146012001F0F9F824B126 -:100A90009F4B1B68002B00F02C82002001F016F801 -:100AA0000390039B002B01DA00F08CFE039B002BCC -:100AB000EDDB012001F0E2F8039B213B1F2BE3D883 -:100AC00001A252F823F000BF490B0008710B000887 -:100AD000050C0008890A0008890A0008890A00082C -:100AE000970C0008670E0008810D0008E30D000850 -:100AF0000B0E0008310E0008890A0008430E00089A -:100B0000890A0008B50E0008E90B0008890A0008E8 -:100B1000F90E0008550B0008E90B0008890A0008C7 -:100B2000E30D0008890A0008890A0008890A0008FC -:100B3000890A0008890A0008890A0008890A000849 -:100B4000890A0008050C00080220FFF751FE002862 -:100B500040F0F981009B022105A8BAF1000F08BFFF -:100B60001C4641F21233ADF8143000F0CDFF8BE794 -:100B70004FF47A7000F0AAFF071EEBDB0220FFF7AC -:100B800037FE0028E6D0013F052F00F2DE81DFE8C6 -:100B900007F0030A0D1013360523042105A8059359 -:100BA00000F0B2FF17E004215548F9E704215A4844 -:100BB000F6E704215948F3E74FF01C08404608F1D6 -:100BC000040800F0D3FF0421059005A800F09CFF65 -:100BD000B8F12C0FF2D101204FF0000900FA07F70D -:100BE00047EA0B0B5FFA8BFB01F0C0F826B10BF064 -:100BF0000B030B2B08BF0024FFF702FE44E7042180 -:100C00004748CDE7002EA5D00BF00B030B2BA1D14D -:100C10000220FFF7EDFD074600289BD001200026AB -:100C200000F0A2FF0220FFF733FE1FFA86F84046CD -:100C300000F0AAFF0446B0B1039940460136A1F185 -:100C400040025142514100F0B7FF0028EDD1BA46B1 -:100C5000044641F21213022105A83E46ADF81430B5 -:100C600000F052FF10E725460120FFF711FE244B4C -:100C70009B68AB4207D9284600F078FF013040F06E -:100C800067810435F3E70025224BBA463E461D70C6 -:100C90001F4B5D60A8E7002E3FF45CAF0BF00B0329 -:100CA0000B2B7FF457AF0220FFF7F2FD322000F04C -:100CB0000DFFB0F10008FFF64DAF18F003077FF409 -:100CC00049AF0F4A08EB0503926893423FF642AFE3 -:100CD000B8F5807F3FF73EAF124BB845019323DD57 -:100CE0004FF47A7000F0F2FE0390039A002AFFF6A8 -:100CF00031AF039A0137019B03F8012BEDE700BFE9 -:100D000000220020EC230020D02200201908000837 -:100D1000F0230020E82200200422002008220020E6 -:100D20000C220020EC220020C820FFF761FD0746BE -:100D300000283FF40FAF1F2D11D8C5F120020AABD8 -:100D400025F0030084494245184428BF42460192D9 -:100D500000F09AFF019AFF217F4800F0BBFF4FEAA5 -:100D6000A803C8F387027C492846019300F0BAFF24 -:100D7000064600283FF46DAF019B05EB830533E782 -:100D80000220FFF735FD00283FF4E4AE00F026FF17 -:100D900000283FF4DFAE0027B846704B9B68BB428B -:100DA00018D91F2F11D80A9B01330ED027F0030347 -:100DB00012AA134453F8203C05934046042205A987 -:100DC000043701F01BFA8046E7E7384600F0CEFE14 -:100DD0000590F2E7CDF81480042105A800F094FEF8 -:100DE00002E70023642104A8049300F083FE002896 -:100DF0007FF4B0AE0220FFF7FBFC00283FF4AAAE60 -:100E0000049800F0E1FE0590E6E70023642104A8C1 -:100E1000049300F06FFE00287FF49CAE0220FFF7E1 -:100E2000E7FC00283FF496AE049800F0CFFEEAE716 -:100E30000220FFF7DDFC00283FF48CAE00F0DEFE60 -:100E4000E1E70220FFF7D4FC00283FF483AE05A9B8 -:100E5000142000F0D9FE07460421049004A800F0F5 -:100E600053FE3946B9E7322000F030FE071EFFF688 -:100E700071AEBB077FF46EAE384A07EB0903926888 -:100E800093423FF667AE0220FFF7B2FC00283FF422 -:100E900061AE27F003074F44B9453FF4A5AE48467D -:100EA00009F1040900F062FE0421059005A800F094 -:100EB0002BFEF1E74FF47A70FFF79AFC00283FF41D -:100EC00049AE00F08BFE002844D00A9B01330BD0C2 -:100ED00008220AA9002000F005FF00283AD02022AD -:100EE000FF210AA800F0F6FEFFF78AFC1C4804F078 -:100EF000D7FB13B0BDE8F08F002E3FF42BAE0BF004 -:100F00000B030B2B7FF426AE0023642105A8059369 -:100F100000F0F0FD074600287FF41CAE0220FFF72A -:100F200067FC804600283FF415AEFFF769FC41F2EC -:100F3000883004F0B5FB059800F062FF46463C4659 -:100F400000F014FFA0E506464EE64FF0000901E66A -:100F5000BA467EE637467CE6EC22002000220020DE -:100F6000A0860100094A49F26900136899B21B0C76 -:100F700000FB013344F250611360054B186882B2E4 -:100F8000000C01FB0200186080B2704714220020A0 -:100F9000102200200021102210B5044600F09AFE15 -:100FA000034B03CB206061601868A06010BD00BFD8 -:100FB00000E8F11F2DE9F041ADF5507D0D4600210F -:100FC00040F275126EAC074610A80F9100F082FE39 -:100FD0004FF4C4720021204600F07CFE0DF13C0865 -:100FE00002F0C6FA4FF47A72264BB0FBF2F01860AA -:100FF00093E80700022384E807000DF5ED702382D3 -:10100000FFF7C8FF47F605031F4907A8238406F02A -:1010100031FC1F230DF2EB220DF1340C84F8323138 -:1010200007AB1E46083203CE664542F8080C42F86C -:10103000041C3346F5D1306810602046B188B3797E -:10104000918041469371012200F0FCFE002380B2A2 -:10105000E97E0393AB7E029305F11903019301230B -:10106000009306A3D3E90023CDE90480384602F0BB -:101070003DFE0DF5507DBDE8F08100BF9E6AC421A4 -:10108000818A46EEF8230020847800082DE9F0419B -:101090002C4CDAB080460D46237A5BBB27A9284644 -:1010A00000F0DEFF0746002842D19DF89D60C82E63 -:1010B0003ED801464FF4A662204600F00BFE4FF4E6 -:1010C000807332460DF19E01C4F8F8314FF400737D -:1010D00004F109002644C4F80C334FF44073C4F8FB -:1010E000203400F0D1FD9DF89C30777223720BB94B -:1010F000EB7E237206AC8122002127A800F0EAFDD6 -:101100000122214627A800F0E7FF002380B2E97EF4 -:101110000393AB7E029305F1190301932823CDE9D4 -:1011200004400093404605A3D3E9002302F0DEFD0E -:101130005AB0BDE8F08100BFAFF300802641727263 -:10114000DF25D7B7A05D0020F0B5254E4FF48A7596 -:10115000F1B0002405FB006596F8D830D82221466E -:1011600085F8DC303AA885F8E84006AF00F0B2FD1B -:1011700006F1090000F0A6FDD5F8E430C2B206F190 -:1011800009018DF8F0000DF1F100CDE93A3400F0DD -:101190007BFD394601223AA800F0CAFF082380B23D -:1011A000317ACDE9047001270E48CDE9023706F106 -:1011B000D80301933023009307A3D3E9002302F05F -:1011C00095FDA04206DD02F0D3F9C5F8E0003846EF -:1011D00071B0F0BD2046FBE778F6339F93CACD8D02 -:1011E000A05D0020103400202DE9F04F274F87B07C -:1011F000DFF8A480264E384602F0A4FD03460028FE -:101200003CD00024234DADF81440A1460294A246E0 -:10121000CDE90344027B8DF8142003AA9968406845 -:1012200003C21B6843F0004302932B6804F22C5462 -:10123000D3F810B002F09EF910EB0802CDF800A030 -:10124000284605F5A55541F1000302A9D84740F607 -:1012500058230028C8BF49F0010910359C42E4D149 -:10126000B9F1000F05D0384602F070FD86F800A0F5 -:10127000C1E73378072B04D80133337007B0BDE8DA -:10128000F08F024802F062FDF8E700BF1034002042 -:10129000D56200204034002040420F0070B50D465A -:1012A00014461E4602F07EFC50B9022E10D1012CCD -:1012B0000ED112A3D3E900230120C5E9002307E0E2 -:1012C000282C10D005D8012C09D0052C0FD00020D7 -:1012D00070BD302CFBD10BA3D3E90023ECE70BA3AB -:1012E000D3E90023E8E70BA3D3E90023E4E70BA34A -:1012F000D3E90023E0E700BFAFF30080401DA12049 -:1013000026812A0B78F6339F93CACD8D9E6AC4211D -:10131000818A46EE26417272DF25D7B7F017304A30 -:1013200039059E5638B505460E4C0021013500F0B2 -:1013300043FCA4F82C55B4F82C0500F025FC78B13A -:10134000B4F82C0500F030FC014648B9B4F82C057F -:1013500000F032FCB4F82C350133A4F82C35EAE760 -:1013600038BD00BFA05D0020F8B50E4C02260E4F20 -:10137000A4F5805343F8307C237E3BB965692DB1D9 -:10138000284600F0CBFF284606F02AFA2046A4F5AE -:10139000A55400F0C3FF012EA4F1100400D1F8BD44 -:1013A0000126E5E720590020447900082DE9F04F97 -:1013B0008FB005460C4600AF02F0F4FB002849D17F -:1013C000237E022B1BD1E38A012B18D102F0D0F827 -:1013D0000646FFF7C7FD03464FF4C87006F51676BC -:1013E000DFF8C082B3FBF0F202FB103316FA83F38E -:1013F000C8F80030E37E33B9A34B00221A703C37A3 -:10140000BD46BDE8F08F07F12401204600F0E6FD5F -:101410000028F4D107F11400FFF7BCFD97F826402F -:1014200007F1140107F12700224606F0F1F9002820 -:10143000E2D10F2C08D8944B1C70D8F80030A3F5DB -:101440001673C8F80030DAE797F82410284602F03F -:10145000A1FBD4E7E38A282B2BD010D8012B23D073 -:10146000052BCCD1BFF34F8F8849894BCA6802F452 -:10147000E0621343CB60BFF34F8F00BFFDE7302B1B -:10148000BDD1844EE17E327A9142B8D1607E314640 -:10149000002291F8DC50854200F0A580013201F570 -:1014A0008A71042AF5D1AAE721462846FFF782FD72 -:1014B000A5E721462846FFF7E9FDA0E7B2F8EC5082 -:1014C0007B6005F103094FEA99094FEA8902D11DB2 -:1014D000C908A8EBC10300219D46EB46584600F021 -:1014E000F9FB04F1EE012A465846314400F0CCFBEA -:1014F0007B6813B9012000F037FB96F8D20000F0AA -:1015000043FB044630B9307200F068FB204600F01F -:101510002BFBB1E0D6F8D4203AB996F8D200B6F851 -:101520002C25824201D8FFF7FDFED6F8D4202A44AC -:10153000944208D296F8D200B6F82C2501308242A7 -:1015400001D8FFF7EFFE5FFA89F25946706800F0A4 -:10155000C9FB08B9C54679E0726896F8D2002A44FA -:101560007260D6F8D42005EB0209C6F8D49000F0DA -:101570000BFB814509D396F8D220D6F8D40001326E -:10158000001B86F8D220C6F8D400FF2D0FD8002407 -:10159000347200F023FB204600F0E6FA00F044FE2F -:1015A0003D4B188108B9FFF789F9C54627E7BB68A5 -:1015B00096F8D9000AFB0362FB68D2F8E41082F8BF -:1015C000E83001F58061C2F8E030C2F8E410FFF7BE -:1015D000BBFDFFF709FE96F8D920013202F00302A5 -:1015E00086F8D920B6E74FF48A7A20460AFB02F53E -:1015F00005F1EA01314400F0C7FDF86000287FF4EE -:10160000FEAE0122354485F8E82001F0B1FFD5F89F -:10161000E020D6ED007A801A40F6B832B8EE677A4C -:10162000DFED1E6A192838BF1920904228BF1046E6 -:1016300007EE900AF8EEE77A67EEA67ADFED186A11 -:10164000E7EE267AFCEEE77AC6ED007A96F8D93016 -:10165000BB60BA6873680AFB02F4321992F8E810AA -:1016600059B1D2F8E410E8468B423FF427AF00218D -:1016700082F8E810C2F8E010C5467368064A9B0A73 -:1016800001331381BBE600BF0934002000ED00E008 -:101690000400FA05A05D0020F8230020CDCCCC3D4D -:1016A0006666663F0C340020014B1870704700BF1F -:1016B0000424002038B54FF04054144B22689A425D -:1016C00021D1627D0025124B12481A70C922237D58 -:1016D0000930114900F8013C4FF48073C0F8DB5029 -:1016E000C0F8EF314FF40073C0F803334FF4407388 -:1016F000C0F8173400F0C8FAE0222946204600F06E -:10170000E9FA012038BD0020FCE700BF9AAD44C5CE -:1017100004240020A05D00201600003037B500F042 -:1017200083FD1F4C1F4D022301221F496B7123684B -:101730002881204604F580545B6898470122D4F83C -:10174000B03404F5966018495B6898470023174940 -:101750004FF480520193164B16480093164B02F03B -:10176000F1F9164B197811B1124802F013FA01F091 -:10177000FFFE0446FFF7F6FB4FF4C873B0FBF3F22D -:1017800002FB130304F5167010FA83F00C4B18607B -:1017900004F08EFC08B10F232B8103B030BD00BFD5 -:1017A00040340020F823002040420F00082400208D -:1017B0009D12000810340020AD13000804240020FE -:1017C0000C3400202DE9F04F00252DED028B93B055 -:1017D0000DF12C084FF0010ADFF814B2FFF704FDF9 -:1017E0000A95ADF834500B95C8F804509FED798BED -:1017F00000267E4C374623680DF11D0207A92046BE -:101800008DF81CA08DF81D508DED008BD3F808903D -:101810000023C8479DF81C90B9F1000F1ED010227C -:1018200000210EA800F056FA236808AA0AA95F69E9 -:1018300020460DF11E03B8470FAB4F4698E8030052 -:1018400083E803009DF834300EA958468DF84430E3 -:101850000A9B0E93DDE9082302F056FC06F22C5693 -:1018600040F6582304F5A5549E4204F11004C2D159 -:10187000002FBDD15E4802F095F900283FD15D4EA2 -:1018800001F076FE3368984239D301F071FE0446C8 -:10189000FFF768FB4FF4C8738DF82870B0FBF3F2C4 -:1018A00002FB130304F5167010FA83F03060524EF9 -:1018B000377817B901238DF82830C7F110040EA826 -:1018C000FFF768FB0EABE4B20DF12900D919062C25 -:1018D00028BF06242246013400F0D6F90AABE4B250 -:1018E00043480393182304940293444B0193012328 -:1018F00000933AA3D3E9002302F09AF9357001F07E -:1019000037FE3F4A3F4C1368C31AB3F57A7F2FD393 -:10191000106001F02FFE02460B46354802F020FA17 -:10192000334802F03FF918B3237A0EAF364E002B3E -:1019300014BF03230223737101F01AFE4FF47A736C -:1019400001223946B0FBF3F03060304600F01EFB58 -:10195000182380B202932D4B019340F25513CDE929 -:101960000370009322481FA3D3E9002302F060F91B -:10197000237A93B101F0FCFD002607464FF48A78E4 -:1019800094F8D900304400F0030008FB004393F8BA -:10199000E82072B10136042EF2D1C82003F080FE97 -:1019A000237A002B7FF414AF13B0BDEC028BBDE89B -:1019B000F08FD3F8E02042B12368BA1AFA2B38BF6F -:1019C000FA230533B2EB430FE4D3FFF7BDFB002846 -:1019D000E0D1E2E70000000000000000401DA1206F -:1019E00026812A0BF1C6A7C1D068080F4034002019 -:1019F000103400200C34002009340020083400206A -:101A0000D0620020A05D0020F8230020D4620020D6 -:101A100008B5064801F0B6F8054801F0B3F8054AE4 -:101A200005490020BDE8084005F0D4BE4034002040 -:101A3000F048002030630020691300087047000060 -:101A40002DE9F84F4FF47A7306460D46002402FB49 -:101A500003F7DFF85080DFF8509098F900305FFA14 -:101A600084FA5A1C01D0A34212D159F824002A4604 -:101A700031460368D3F820B03B46D847854207D1AA -:101A8000074B012083F800A0BDE8F88F0124E4E7AC -:101A9000002CFBD04FF4FA7003F002FE0020F3E7B5 -:101AA0001C630020182200201C22002070B5044670 -:101AB0004FF47A76412C254628BF412506FB05F0D8 -:101AC00003F0EEFD641BF5D170BD0000002307B5E7 -:101AD000024601210DF107008DF80730FFF7B0FF36 -:101AE00020B19DF8070003B05DF804FB4FF0FF3014 -:101AF000F9E700000A46042108B5FFF7A1FF80F0CE -:101B00000100C0B2404208BD074B0A4630B4197804 -:101B1000064B53F82140014623682046DD69044BFB -:101B2000AC4630BC604700BF1C6300201C22002074 -:101B3000A086010070B50A4E00240A4D04F0CCF8CE -:101B4000308028683388834208D904F0C1F82B68B4 -:101B500004440133B4F5003F2B60F2D370BD00BFE5 -:101B60001E630020D862002004F084B900F10060F8 -:101B700000F500300068704700F10060920000F549 -:101B8000003004F005B90000054B1A68054B1B88AE -:101B90009B1A834202D9104404F09AB8002070477F -:101BA000D86200201E630020024B1B68184404F01A -:101BB00095B800BFD8620020024B1B68184404F09F -:101BC0009FB800BFD86200200020704700F1FF508E -:101BD00000F58F10D0F8000870470000064991F812 -:101BE000243033B100230822086A81F82430FFF73B -:101BF000C3BF0120704700BFDC620020014B1868A2 -:101C0000704700BF0010005C194B013803220844E4 -:101C100070B51D68174BC5F30B042D0C1E88A6422A -:101C20000BD15C680A46013C824213460FD214F97C -:101C3000016F4EB102F8016BF6E7013A03F10803B8 -:101C4000ECD181420B4602D22C2203F8012B042452 -:101C5000094A1688AE4204D1984284BF967803F8A8 -:101C6000016B013C02F10402F3D1581A70BD00BFB0 -:101C70000010005C24220020D0780008704700008B -:101C80007047000070470000002310B5934203D056 -:101C9000CC5CC4540133F9E710BD0000013810B525 -:101CA00010F9013F3BB191F900409C4203D11AB1B8 -:101CB0000131013AF4E71AB191F90020981A10BDE8 -:101CC0001046FCE703460246D01A12F9011B002910 -:101CD000FAD1704702440346934202D003F8011B35 -:101CE000FAE770472DE9F8431F4D1446074688462A -:101CF00095F8242052BBDFF870909CB395F82430FF -:101D00002BB92022FF2148462F62FFF7E3FF95F809 -:101D100024004146C0F1080205EB8000A24228BF22 -:101D20002246D6B29200FFF7AFFF95F82430A41BED -:101D300017441E449044E4B2F6B2082E85F824609D -:101D4000DBD1FFF74BFF0028D7D108E02B6A03EB6C -:101D500082038342CFD0FFF741FF0028CBD1002080 -:101D6000BDE8F8830120FBE7DC620020024B1A7813 -:101D7000024B1A70704700BF1C630020182200201D -:101D800038B51A4C1A4D204602F0A8FF29462046C5 -:101D900002F0D0FF2D684FF47A70D5F89020D2F879 -:101DA000043843F00203C2F80438FFF77FFE1149FC -:101DB000284603F0CDF8D5F890200F4DD2F804381E -:101DC000286823F002030D49A042C2F804384FF4FA -:101DD000E1330B6001D002F0DFFE6868A04204D05E -:101DE0000649BDE8384002F0D7BE38BD106A002071 -:101DF000707A0008787A00081C2200200463002012 -:101E00000C4B70B50C4D04461E780C4B55F8262033 -:101E10009A420DD00A4B002118221846FFF75AFFAC -:101E20000460014655F82600BDE8704002F0B4BEDB -:101E300070BD00BF1C6300201C220020106A00201F -:101E4000046300202DE9F0470D460446002190462A -:101E5000284640F27912FFF73DFF23462022002159 -:101E6000284604F1220702F0F1F8231D0222202166 -:101E70002846C02602F0EAF8631D032222212846E4 -:101E800002F0E4F8A31D03222521284602F0DEF823 -:101E900004F1080310222821284602F0D7F804F1A3 -:101EA000100308223821284602F0D0F804F111036B -:101EB00008224021284602F0C9F804F11203082242 -:101EC0004821284602F0C2F804F1140320225021D0 -:101ED000284602F0BBF804F118034022702128467E -:101EE00002F0B4F804F120030822B021284602F0E1 -:101EF000ADF804F121030822B821284602F0A6F823 -:101F0000314608363B4608222846013702F09EF843 -:101F1000B6F5A07FF4D1002704F1330A04F13203AF -:101F200008223146284602F091F894F832304FEA00 -:101F3000C7099F4209F5A47615D3B8F1000F08D15F -:101F4000314609F24F1604F599730722284602F02C -:101F50007DF827463B1B94F8322193420CD3F01DA9 -:101F6000C008BDE8F0870AEB07030822314628467F -:101F7000013702F06BF8D8E707F233133146082235 -:101F800028460836013702F061F8E3E713B5044646 -:101F9000084600212022234601900160C0F803106A -:101FA00002F054F8231D01980222202102F04EF87D -:101FB000631D01980322222102F048F8A31D019815 -:101FC0000322252102F042F8019804F108031022AF -:101FD000282102F03BF8072002B010BD0023F7B51E -:101FE0000E46047F072200911946054601F0F2FED5 -:101FF000731C0122072100932846002301F0EAFE0A -:10200000C4B9B31C052208212846009323460D2499 -:1020100001F0E0FE3746BB1BB278934211D3073480 -:102020002B7FA88AE408BBB9844294BF002001201A -:1020300003B0F0BDAB8A0824DB00083BDB08B370BB -:10204000E8E7FB1C214608222846009300230834B9 -:10205000013701F0BFFEDEE7201A18BF0120E7E7D5 -:102060000023F7B50E46047F082200911946054665 -:1020700001F0B0FE731CC4B908220093234610245B -:102080001146284601F0A6FE01235F1C7278013B31 -:10209000934211D307342B7FA88AE408BBB984424A -:1020A00094BF0020012003B0F0BDAB8A0824DB0000 -:1020B000083BDB087370E7E7F3192146082228463E -:1020C0000093002301F086FE08343B46DDE7201A2A -:1020D00018BF0120E7E70000F8B50E460546144694 -:1020E000002181223046FFF7F5FD2B460822002112 -:1020F000304601F0ABFF7CB90F246B1C072208218E -:10210000304601F0A3FF01235F1C6A78013B934234 -:1021100004D3E01DC008F8BD0824F4E7EB192146FC -:102120000822304601F092FF08343B46ECE70000FD -:10213000F8B50E46054614460021CE223046FFF77C -:10214000C9FD2B4628220021304601F07FFF7CB9D3 -:10215000302405F1080308222821304601F076FFDB -:102160002F467B1B2A7A934204D3E01DC008F8BD9A -:102170002824F5E707F109032146082230460834F0 -:10218000013701F063FFECE7F7B5047F0E460091DD -:10219000012310220021054601F01CFEC4B9B31C26 -:1021A00009221021284600932346192401F012FE2B -:1021B00037467288BB1B9A4211D807342B7FA88AF6 -:1021C000E408BBB9844294BF0020012003B0F0BDF5 -:1021D000AB8A1024DB00103BDB087380E8E73B1D73 -:1021E000214608222846009300230834013701F0D5 -:1021F000F1FDDEE7201A18BF0120E7E730B50A44F9 -:10220000084D91420DD011F8013B5840082340F38E -:102210000004013B2C4013F0FF0384EA5000F6D188 -:10222000EFE730BD2083B8EDF7B5364A6B4610684E -:1022300051686A4603C308233349344805F0F8FA65 -:10224000044690BB0A25324A6B46106851686A46BC -:1022500003C308232F492D4805F0EAFA0446002855 -:1022600047D00369B3F5F01F43D8B0F86620B2F544 -:10227000AF6F3ED1284A024402F15C018B4238D351 -:102280005C3B224900209E1AFFF7B8FF04F164016D -:10229000074632460020FFF7B1FFA3689F4228D1CE -:1022A000E368984208BF002523E00369B3F5F01FF7 -:1022B00026D8428BB2F5AF6F20D1174A024402F103 -:1022C00010018B4218D3103B104900209D1AFFF7D4 -:1022D00095FF04F1180106462A460020FFF78EFFFD -:1022E000A3689E4202D1E368984201D00D25AAE777 -:1022F0000025284603B0F0BD1025A4E70C25A2E771 -:102300000B25A0E7E0780008DCFF1D0000000208B4 -:10231000E978000890FF1D000800FEF710B5037C67 -:10232000044613B9006805F06BFA204610BD0000A2 -:102330000023BFF35B8FC360BFF35B8FBFF35B8F83 -:102340008360BFF35B8F7047BFF35B8F0068BFF3A1 -:102350005B8F704770B505460C30FFF7F5FF0446FC -:1023600005F108063046FFF7EFFFA04206D96D6879 -:102370003046FFF7E9FF2544281A70BD3046FFF7C5 -:10238000E3FF201AF9E7000070B505464068A0B1E8 -:1023900005F10C0605F10800FFF7D6FF04463046AC -:1023A000FFF7D2FF844204F1FF34304694BF6D68DA -:1023B0000025FFF7C9FF2C44201A70BD38B50C4624 -:1023C0000546FFF7C7FFA04210D305F10800FFF74D -:1023D000BBFF04446868BFF35B8FB4FBF0F100FB04 -:1023E00011440120AC60BFF35B8F38BD0020FCE7D7 -:1023F0002DE9F041144607460D46FFF7C5FF84421C -:1024000028BF0446D4B1B84658F80C6B4046FFF7D5 -:102410009BFF3044286040467E68FFF795FF331AE3 -:102420009C4203D801206C60BDE8F081A41B6B6066 -:102430003B682044AB60E8600220F5E72046F3E704 -:1024400038B50C460546FFF79FFFA04210D305F1B3 -:102450000C00FFF779FF04446868BFF35B8FB4FB9F -:10246000F0F100FB11440120EC60BFF35B8F38BD3D -:102470000020FCE72DE9FF418846694607466C4687 -:10248000FFF7B6FF002506B204EBC606B4420AD039 -:10249000626808EB050120680834FFF7F5FB54F883 -:1024A000043C1D44F2E729463846FFF7C9FF284699 -:1024B00004B0BDE8F0810000F8B505460C300F46C9 -:1024C000FFF742FF05F1080604463046FFF73CFFE0 -:1024D000A042304688BF6C68FFF736FF201A38608C -:1024E00020B12C683046FFF72FFF2044F8BD0000D4 -:1024F00073B5144606460D46FFF72CFF8442019043 -:1025000028BF0446DCB101A93046FFF7D5FF019B87 -:1025100033B93268C5E90233C5E9002401200CE073 -:102520009C42286038BF0194019884426860F5D9C4 -:102530003368241A0220AB60EC6002B070BD204604 -:10254000FBE700002DE9FF410F4669466C46FFF7A7 -:10255000CFFF00B2002604EBC005AC4209D0D4F88E -:102560000480B81954F8081B42464644FFF78CFB18 -:10257000F3E7304604B0BDE8F081000038B5054609 -:10258000FFF7E0FF044601462846FFF717FF204605 -:1025900038BD0000302383F3118862B67047000015 -:1025A000002383F3118862B6704700000120704752 -:1025B0007047000010B41346026814680022A44655 -:1025C0005DF8044B6047000000F5805090F8590416 -:1025D0007047000000F5805090F8520470470000EA -:1025E00000F5805090F95804704700004E20704765 -:1025F00000F5805208B5FFF7CDFFD2F89834D2F835 -:1026000094041844D2F890341844D2F8783418441A -:10261000D2F888341844D2F884341844FFF7C0FF45 -:1026200008BD00002DE9F04F0C4600F5805185B043 -:102630001F4691F8523405469046BDF838909BB13C -:10264000D1F874340133C1F8743423689A0006D485 -:10265000237B082B0BD9627B0AB10F2B07D9D1F84A -:1026600078340133C1F878344FF0FF300FE0FFF7D2 -:1026700091FFEB6AD3F8C42012F4001A0AD0D1F803 -:102680007C3400200133C1F87C34FFF789FF05B0AA -:10269000BDE8F08F22684FF0480BD3F8C460002AE1 -:1026A0006B6AC6F30446B4BF42F0804292041BFB3F -:1026B000063BCBF8002023685B004FEA066344BF6B -:1026C00042F00052CBF80020227B43EA0243720121 -:1026D000CBF80430607B18B343F44013CBF80430DC -:1026E000D1F8A4340133C1F8A434AB1803F58353F3 -:1026F000197B41F020011973207B039200F094FFB5 -:102700000330039A80105FFA8AF30AF1010A8342C8 -:102710000DDA04EB83010BEB830349689960F2E760 -:10272000AB1803F58353197B60F34511E3E70121EF -:10273000EB6A04F10C00B140C3F8D010AB1821468D -:1027400003F58253C3E9048705EB461303F582536F -:10275000183351F804CB814243F804CBF9D10988EE -:102760002A442846198041F26803D65002F5805267 -:1027700009F0030392F86C1043F0100321F01F01DD -:102780000B43214682F86C304246FFF709FF3B4677 -:10279000CDF8009000F00EFF012078E72DE9F0471A -:1027A00000F58056044696F85254002D40F0018101 -:1027B000037C032B40F092802B4628462F465FFA7D -:1027C00083FC944510DA01EBCC0E51F83CC0BCF10F -:1027D000000F04DBDEF804C0BCF1000F02DB0137A0 -:1027E0000133ECE70130FBE7FFF7D4FEE36AF0B911 -:1027F000D3F8800040F00200C3F880004E23E06A66 -:10280000002F6ED1D0F8803043F00103C0F8803043 -:10281000694B6A4A1B6803F1805303F52C539B00F4 -:102820009342A36240F2AF80654800F09BFE4D28C2 -:1028300042D8DFF884814FEA004EDFF88891D8F85B -:1028400000C04EEA8C0EC3F884E00CF1805303F50F -:102850002C539B00636100EB0C03D4F82CC0C8F828 -:102860000030C0F14E03DCF8800040F03000CCF8BE -:1028700080004FF0000CD4F81480E6465FFA8CF02C -:102880008242BCDD01EBC00A51F83000002810DBA9 -:10289000DAF804A0BAF1000F0BDA09EA00400AF0F6 -:1028A0007F0A40EA0A0040F0084048F82E000EF186 -:1028B000010E0CF1010CE1E79A6922F001029A6124 -:1028C00000F056FE0646E36A9B69D90704D500F07E -:1028D0004FFE831BFA2BF6D9FFF762FE2846BDE8B0 -:1028E000F087B7EB530F3DD2DFF8CCE04FEA074C4F -:1028F000DEF800304CEA830CC0F888C003F1805049 -:1029000003EB4703002700F52C50CEF80030BC46FF -:102910008000A061E06AD0F8803043F00C03C0F87A -:102920008030D4F818E0FBB29A427FF771AF51F8CB -:10293000330001EBC3080028D8F8043001DB002B7A -:102940000EDB20F0604023F0604340F0005043F085 -:1029500000434EF83C000EEBCC000CF1010C436040 -:102960000137E0E7836923F00103836100F000FE93 -:102970000646E36A9B69DA07AED500F0F9FD831BD2 -:10298000FA2BF6D9A8E7E26A936923F00103936171 -:1029900000F0EEFD0746E36A9B69DB0705D500F012 -:1029A000E7FDC31BFA2BF6D996E7012586F85254AA -:1029B00092E7002592E700BF2C630020FCB50040A1 -:1029C000F47800080000FF0713B500F5805401916A -:1029D000606CFFF7D9FC1F280AD920220199606C8E -:1029E000FFF748FDA0F120035842584102B010BD46 -:1029F0000020FBE700F5805008B5FFF7CBFD406CE9 -:102A0000FFF796FCBDE80840FFF7CABD0022026050 -:102A100082814260826070470022002310B5C0E9C5 -:102A20000023002304460C3020F8043CFFF7EEFF9F -:102A3000204610BD2DE9F047074688B09A468846E3 -:102A400007F5805468469146FFF7A4FDFFF7E4FFC1 -:102A5000606CFFF77FFC1F282DD920226946606C2F -:102A6000FFF78CFD202826D194F852341BB303AD18 -:102A7000444605AB2E46083403CE9E4244F8080C6B -:102A800044F8041C3546F5D130684146206038468C -:102A9000B388A380DDE90023C9E90023BDF808302D -:102AA0004A46AAF80030FFF77BFD534608B0BDE860 -:102AB000F04700F06DBD0020FFF772FD08B0BDE8E3 -:102AC000F08700002DE9F84F0023064600F58154F9 -:102AD000054688461034C0E90133274B46F8303BA1 -:102AE000374638462037FFF797FFA742F9D105F55B -:102AF00080544FF4805305F5A3594FF0000A266324 -:102B00000026676405F5835709F110094FF0000BA3 -:102B10001037E663C4E90D36012384F8403084F8A9 -:102B20004830A7F11800203747E910ABFFF76EFFD8 -:102B300047F8286C4F45F4D1B8F1010F84F8588458 -:102B4000A4F85A64A4F85C64A4F85E6484F8606431 -:102B5000A4F86264A4F86464A4F8666484F8686401 -:102B600002D9064800F0FEFC054B284653F82830F1 -:102B7000EB62BDE8F88F00BF4479000818790008BF -:102B800034790008044B10B5197804464A1C1A70B1 -:102B9000FFF798FF204610BD296300202DE9F0477C -:102BA00000295FD0304F3148B7FBF1F581428CBF2F -:102BB0000A201120431EB5FBF0FC00FB1C50DCB2C8 -:102BC00020B1022B1846F5D8002037E00CF1FF3574 -:102BD000B5F5806F32D2C4EBC4094FF47A7009F1B5 -:102BE00003034FEAE308C3F3C70308F1010AA4EBA8 -:102BF000030E08FB00085FFA8EF65AFA8EFEB8FB49 -:102C0000FEFEBEF5617F1BDC1FFA8EF4581C56FADF -:102C100080F00CFB00FCB7FBFCFC6145D4D1013B10 -:102C2000DBB20F2BD0D8711E0020C9B2072905D8FE -:102C3000107101201480558053719171BDE8F087A7 -:102C400009F1FF334FEAE30EC3F3C7030EF10108A6 -:102C5000E41A0EFB0000E6B258FA84F4B0FBF4F478 -:102C6000A4B2D3E70846E9E700B4C4043F420F002A -:102C700038B540F27772C36A154CC3F8BC200722FE -:102C8000C36AC3F8C8202268C16A930043F4C02312 -:102C9000C1F8A03002F1805302F16C01C56A03F55E -:102CA0002C53EA3289009B00226041F0E061094A1E -:102CB000C361C5F8C01003F5D87103F56A734162AA -:102CC0009342836202D9044800F04CFC38BD00BF37 -:102CD0002C630020FCB50040F47800082DE9F04F8B -:102CE00000F58055994689B0044695F858348A46CF -:102CF0009046022B04D90027384609B0BDE8F08F72 -:102D00009B4A52F8231009B942F823009949C4F8A4 -:102D10000CA00B7884F81090C3B9FFF73BFC964BDE -:102D2000D3F8EC2042F48072C3F8EC20D3F894205E -:102D300042F48072C3F89420D3F8942022F4807275 -:102D4000C3F8942001230B70FFF72AFC95F8513447 -:102D50006BB9FFF71FFC894A95F85834D35CEBB187 -:102D6000012B24D0012385F85134FFF719FCFFF71C -:102D700011FCE26A936923F01003936100F0F8FB01 -:102D80000746E36A9E6916F0080617D000F0F0FBCC -:102D9000C31BFA2BF5D9FFF703FCACE70321132083 -:102DA00001F044FD0321152001F040FDDAE7032185 -:102DB000142001F03BFD03211620F5E79A6942F04B -:102DC00001029A6100F0D4FB0746E36A9A69D007D2 -:102DD00005D400F0CDFBC31BFA2BF6D9DBE79A69CB -:102DE000002704F5825B42F002020BF1100B9A619E -:102DF000E36A5F65FFF7D4FB686CFFF799FA20225E -:102E000000216846FEF766FF02A8FFF7FFFD6A464D -:102E10000BEB06030DF1180E069794460833BCE839 -:102E20000300F44543F8080C43F8041C6246F4D14F -:102E3000DCF8000020361860B6F5806F9CF804209E -:102E40001A71DCD1002304F5A252514620461A32F1 -:102E500085F8503485F85334FFF7A0FE074690B943 -:102E6000E26A936923F00103936100F081FB054658 -:102E7000E36A9B69D9077FF53EAF00F079FB431BFE -:102E8000FA2BF5D937E795F85F6495F85E2436029A -:102E9000C5F86CA4E36A46EA426695F860241643D6 -:102EA000B5F85C2446EA0246DE61B8F1000F29D08D -:102EB00004F5A352414620460232FFF76FFE90B957 -:102EC000E26A936923F00103936100F051FB054628 -:102ED000E36A9B69DA077FF50EAF00F049FB431BFD -:102EE000FA2BF5D907E795F8683495F867141B01B4 -:102EF000C5F87084E26A43EA0123B5F8641443EA32 -:102F00000143D360E36A00262046C3F8BC60FFF7A4 -:102F1000AFFE85F859646FF04042E36A1A65184ABB -:102F2000E36A5A654FF00222E36A9A654FF0FF3276 -:102F3000E36AC3F8E0200322E36A9145DA653FF4CF -:102F4000DBAEE26A936923F00103936100F010FBAA -:102F50000646E36A9B69DB0705D500F009FB831B86 -:102F6000FA2BF6D9C7E6012385F85234C4E600BF30 -:102F70002063002028630020004402582C790008B8 -:102F8000550200022DE9F04F054689B0904699465A -:102F9000002741F2680A00F58056EB6AD3F8D83072 -:102FA000FB40D8074AD505EB47124FEA471B52446E -:102FB0001379190742D4D6F880340133C6F8803427 -:102FC00013799A0605EB0B0248BFD6F8A834524491 -:102FD00044BF0133C6F8A834137943F008031371D2 -:102FE000DB0723D596F8533403B305F582546846BE -:102FF000FFF712FD03AB18345C4404F1080C2068A1 -:10300000083454F8041C1A46644503C21346F6D12A -:103010002068694610602846A2889A800123ADF88E -:1030200008302B68CDE90089DB6B9847D6F854341B -:1030300023B1D6F89C340133C6F89C340137202FD5 -:10304000ABD109B0BDE8F08F2DE9F04F0F468DB040 -:10305000044600F08FFA82468946002F5BD1E36A6E -:10306000D3F8A02012F4FE0F03D100200DB0BDE86C -:10307000F08FD3F8A420920141BF04F58051D1F81C -:1030800094240132C1F89424D3F8A4205606ECD03D -:10309000D3F8A450E669C5F305254823E8464FF068 -:1030A000000B03FB05664046FFF7B0FC3268510099 -:1030B0004ABF22F06043C2F38A4343F000439200C8 -:1030C00048BF43F080430093736813F400131BBFA1 -:1030D000012304F580528DF80D308DF80D301EBFA0 -:1030E000D2F8AC340133C2F8AC34F38803F00F03E8 -:1030F0008DF80C309DF80C0000F096FA5FFA8BF317 -:10310000984225D9F2180CA90BF1010B127A0B4445 -:1031100003F82C2CEEE7012FA7D1E36AD3F8B020F7 -:1031200012F4FE0FA1D0D3F8B420950141BF04F5ED -:103130008051D1F894240132C1F89424D3F8B420FA -:10314000500692D0D3F8B450266AC5F30525A4E7FB -:10315000EFB9E36AC3F8A85004A807ADFFF75CFC19 -:1031600098E80F0007C52B800023204604A9ADF87E -:103170001830236804F58054DB6BCDE904A9984727 -:1031800058B1D4F88C340133C4F88C346EE7012F75 -:10319000E2D1E36AC3F8B850DEE7D4F890340120F6 -:1031A0000133C4F8903461E7F8B505460F4600F5E1 -:1031B0008054012639462846FFF746FF10B184F8AF -:1031C0005364F7E7D4F8543423B1D4F89C34013372 -:1031D000C4F89C34F8BD0000C36AF0B51A6C12F450 -:1031E0007F0F2BD01B6C00F5805441F268054FF027 -:1031F000010CC4F8A0340023471900EB43125E0110 -:103200002A44117911F0020F15D0490713D4B95986 -:10321000C66A0CFA01F1D6F8CCE011EA0E0F0AD01A -:10322000C6F8D410117941F004011171D4F8882442 -:103230000132C4F888240133202BDED1F0BD000018 -:103240002B4B70B51E561B5C012B30D8294D2A4ADA -:1032500055F8233052F8264013B349B3236D9A052D -:1032600010D54FF40073236500F084F950EA010291 -:103270000B4602D0013861F10003024655F82600E2 -:10328000FFF780FE236D9B012CD54FF0007255F89F -:103290002630226503F58053012283F8592421E06A -:1032A00001232365102323654FF48053236570BDEC -:1032B000236DDA0702D4236D5B0706D505230021B1 -:1032C00055F826002365FFF76FFF236DD80602D45B -:1032D000236D590606D55023012155F82600236594 -:1032E000FFF762FF55F82600BDE87040FFF774BF96 -:1032F00030790008206300203479000808B5FFF712 -:1033000049F9FFF769FFBDE80840FFF749B9000038 -:10331000C36AD3F8C00010F07C5005D0D3F8C400C5 -:1033200080F40010C0F340507047000000F580505A -:1033300008B5FFF72FF9406CFFF70CF8FFF730F9ED -:1033400043090CBF0120002008BD000000F5805398 -:1033500093F8592462B1C16A8A6922F001028A6134 -:10336000D3F898240132C3F89824002283F8592412 -:10337000704700002DE9F74300F58251984600257B -:10338000FFF708F9103141F2680E4FF0010900F51E -:10339000805C00EB4514744423795E071CD4DB0683 -:1033A0001AD58E69C36A09FA06F6D3F8CC703E4284 -:1033B00012D04F6801970F689742019F77EB08077B -:1033C0000AD2C3F8D460237943F004032371DCF8F4 -:1033D00084340133CCF8843401352031202DD8D108 -:1033E00003B0BDE8F043FFF7DBB80000F8B51E46B8 -:1033F00000230F46054613701446FFF797FF80F031 -:10340000010038701EB12846FFF782FF2070F8BD1A -:103410002DE9F04F85B099460D468046164691F845 -:1034200000B0DDE90EA302931378019300F0A2F837 -:103430002B7804460F4613B93378002B42D022462E -:103440003B464046FFF796FFFFF758FFFFF77EFF2A -:103450004B4632462946FFF7C9FF2B7833B1BBF103 -:10346000000F03D0012005B0BDE8F08F337813B111 -:10347000019B002BF6D108F5805303935445029B22 -:1034800077EB03031ED2039BD3F85404D0B1036837 -:10349000AAEB0401DB6889B298474B4632462946BD -:1034A0004046FFF7A3FF2B7813B1BBF1000FD9D132 -:1034B000337813B1019B002BD4D100F05BF80446A4 -:1034C0000F46DBE70020CEE7002108B50846FFF7EE -:1034D000B7FEBDE8084001F06DB8000008B5012155 -:1034E0000020FFF7ADFEBDE8084001F063B8000022 -:1034F00008B500210120FFF7A3FEBDE8084001F058 -:1035000059B80000012108B50846FFF799FEBDE84B -:10351000084001F04FB8000000B59BB0EFF30981FF -:1035200068226846FEF7B0FBEFF30583014B9B6B07 -:10353000FEE700BF00ED00E008B5FFF7EDFF00007B -:1035400000B59BB0EFF3098168226846FEF79CFB4B -:10355000EFF30583014B5B6BFEE700BF00ED00E07E -:10356000FEE700000FB408B5029802F025F8FEE768 -:1035700002F0CCBC02F0A4BC13B56C46031D84E879 -:10358000060094E8030083E80500012002B010BDA6 -:1035900073B58568019155B11B885B0707D4D0E9E5 -:1035A00000369B6B9847019AC1B23046A84701206C -:1035B00002B070BDF0B5866889B005460C465EB1B4 -:1035C000BDF838305B070AD4D0E900379B6B9847C9 -:1035D0002246C1B23846B047012009B0F0BD0022F2 -:1035E000002301F10806CDE9002300230A46ADF8C7 -:1035F000083003AB1068083252F8041C1C46B24273 -:1036000003C42346F6D1106820609288A280FFF799 -:10361000B1FF0423ADF808302B68CDE90001DB6B66 -:10362000694628469847D7E7082817D909280CD0B3 +:1000000000070020F1020008A1330008593300085E +:10001000813300085933000879330008F3020008DF +:10002000F3020008F3020008F30200088543000809 +:10003000F3020008F3020008F3020008F3020008CC +:10004000F3020008F3020008F3020008F3020008BC +:10005000F3020008F3020008FD7700082978000881 +:100060005578000881780008AD78000849440008F8 +:10007000714400089D440008C9440008F544000884 +:100080001D45000849450008F3020008093300082F +:10009000313300081D33000845330008D9780008C3 +:1000A000F3020008F3020008F3020008F30200085C +:1000B000F3020008F3020008F3020008F30200084C +:1000C000F3020008F3020008F3020008F30200083C +:1000D000F3020008F3020008F3020008F30200082C +:1000E0003D790008F3020008F3020008F30200085B +:1000F000F3020008F3020008F30200087545000847 +:10010000F3020008F3020008C5790008F3020008B2 +:10011000F3020008F3020008F3020008F3020008EB +:10012000A1450008C9450008F5450008214600081A +:100130004D460008F3020008F3020008F30200082D +:10014000F3020008F3020008F3020008F3020008BB +:1001500075460008A1460008CD460008F3020008D5 +:10016000F3020008F3020008F3020008F30200089B +:10017000F30200087D6E0008F3020008F302000895 +:10018000F3020008F3020008B1790008F302000846 +:10019000F3020008F3020008F3020008F30200086B +:1001A000F3020008F3020008F3020008F30200085B +:1001B000F3020008F3020008F3020008F30200084B +:1001C000F3020008F3020008F3020008F30200083B +:1001D000F3020008696E0008F3020008F302000849 +:1001E000F3020008F3020008F3020008F30200081B +:1001F000F3020008F3020008F3020008F30200080B +:10020000F3020008F3020008F3020008F3020008FA +:10021000F3020008F3020008F3020008F3020008EA +:10022000F3020008F3020008F3020008F3020008DA +:10023000F3020008F3020008F3020008F3020008CA +:10024000F3020008F3020008F3020008F3020008BA +:10025000F3020008F3020008F3020008F3020008AA +:10026000F3020008F3020008F3020008F30200089A +:10027000F3020008F3020008F3020008F30200088A +:10028000F3020008F3020008F3020008F30200087A +:10029000F3020008F3020008F3020008F30200086A +:1002A000F3020008F3020008F3020008F30200085A +:1002B000F3020008F3020008F3020008F30200084A +:1002C000F3020008F3020008F3020008F30200083A +:1002D000F3020008F3020008F3020008F30200082A +:1002E00021170008000000000000000000000000CE +:1002F00002E000F000F8FEE772B6374880F30888A5 +:10030000364880F3098836483649086040F20000D4 +:10031000CCF200004EF63471CEF200010860BFF35B +:100320004F8FBFF36F8F40F20000C0F2F0004EF627 +:100330008851CEF200010860BFF34F8FBFF36F8F7B +:100340004FF00000E1EE100A4EF63C71CEF20001D3 +:100350000860062080F31488BFF36F8F05F0FAFF62 +:1003600007F008F84FF055301F491B4A91423CBF37 +:1003700041F8040BFAE71D49184A91423CBF41F885 +:10038000040BFAE71A491B4A1B4B9A423EBF51F82D +:10039000040B42F8040BF8E700201849184A914270 +:1003A0003CBF41F8040BFAE706F012F807F066F8D4 +:1003B000144C154DAC4203DA54F8041B8847F9E796 +:1003C00000F042F8114C124DAC4203DA54F8041B11 +:1003D0008847F9E705F0FABF000700200023002056 +:1003E0000000000808ED00E00001002000070020E8 +:1003F0009080000800230020D0230020D02300207C +:10040000C8880020E0020008E4020008E4020008B6 +:10041000E40200082DE9F04F2DED108AC1F80CD050 +:10042000D0F80CD0BDEC108ABDE8F08F002383F328 +:1004300011882846A047002005F070FAFEE705F075 +:10044000EFF900DFFEE70000F8B501F0E9F901F08F +:100450007FFB05F003FF074605F072FF0546A8BBCA +:100460001F4B9F4232D001339F4232D027F0FF0210 +:100470001C4B9A4230D12E4642F21074F8B200F072 +:100480009BFF00F09FFF08B10024264601F0A8FD65 +:1004900020B10024032000F079F8264635B1124B34 +:1004A0009F4203D0002405F043FF2646002005F0BC +:1004B000DFFE0EB100F080F801F0E8FA00F0B6FFC0 +:1004C000204600F037F900F077F8F9E72E460024CF +:1004D000D7E704460126D4E7064641F28834D0E740 +:1004E000010007B0000008B0263A09B008B501F0D5 +:1004F00063F9A0F120035842584108BD07B541F205 +:100500001203022101A8ADF8043001F073F903B021 +:100510005DF804FB38B5302383F31188174803686E +:100520000BB105F0C7FA0023154A4FF47A7113484E +:1005300005F0B6FA002383F31188124C236813B137 +:100540002368013B2360636813B16368013B636008 +:100550000D4D2B7833B963687BB9022001F008FA9E +:10056000322363602B78032B07D163682BB90220F9 +:1005700001F0FEF94FF47A73636038BDD023002098 +:1005800015050008F0240020E8230020084B18700F +:1005900003280CD8DFE800F008050208022001F06B +:1005A000E5B9022001F0E0B9024B00225A60704721 +:1005B000E8230020F0240020F8B501F011FD30B14F +:1005C000544B03221A700022534B5A60F8BD534B10 +:1005D000534A1C4619680131F8D004339342F9D1CB +:1005E0006268504B9A42F1D94F4B9B6803F100630C +:1005F00003F500339A42E9D205F06EFE05F080FE65 +:10060000002001F027F90220FFF7C0FF474B00212F +:10061000D3F8E820C3F8E810D3F81021C3F810117C +:10062000D3F81021D3F8EC20C3F8EC10D3F8142140 +:10063000C3F81411D3F81421D3F8F020C3F8F01044 +:10064000D3F81821C3F81811D3F81821D3F8802053 +:1006500042F00062C3F88020D3F8802022F00062CC +:10066000C3F88020D3F88020D3F8802042F00072B5 +:10067000C3F88020D3F8802022F00072C3F88020D5 +:10068000D3F8803072B64FF0E023C3F8084DD4E9B8 +:100690000004BFF34F8FBFF36F8F254AC2F8841059 +:1006A000BFF34F8F536923F480335361BFF34F8FF0 +:1006B000D2F8803043F6E076C3F3C905C3F34E3376 +:1006C0005B0103EA060C29464CEA81770139C2F83E +:1006D0007472F9D2203B13F1200FF2D1BFF34F8F88 +:1006E000BFF36F8FBFF34F8FBFF36F8F536923F447 +:1006F000003353610023C2F85032BFF34F8FBFF372 +:100700006F8F302383F31188854680F30888204754 +:100710005CE700BFE8230020F0240020000002086E +:1007200020000208FFFF01080023002000440258B7 +:1007300000ED00E02DE9F04F93B0B74B2022FF21F0 +:1007400000900AA89D6801F04BF9B44A1378A3B948 +:100750000121B34811700360302383F311880368CB +:100760000BB105F0A7F90023AE4A4FF47A71AC48FB +:1007700005F096F9002383F31188009B13B1AA4B6F +:10078000009A1A60A94A1378032B03D00023137030 +:10079000A54A53604FF0000A009CD3465646D14606 +:1007A000012001F0E3F824B19F4B1B68002B00F0FF +:1007B0002C82002001F000F80390039B002B01DA4B +:1007C00000F088FE039B002BEDDB012001F0CCF84C +:1007D000039B213B1F2BE3D801A252F823F000BF5B +:1007E00061080008890800081D090008A107000821 +:1007F000A1070008A1070008AF0900087F0B000847 +:10080000990A0008FB0A0008230B0008490B00089E +:10081000A10700085B0B0008A1070008CD0B00082A +:1008200001090008A1070008110C00086D08000864 +:1008300001090008A1070008FB0A0008A107000839 +:10084000A1070008A1070008A1070008A1070008E8 +:10085000A1070008A1070008A10700081D0900085A +:100860000220FFF743FE002840F0F981009B02219F +:1008700005A8BAF1000F08BF1C4641F21233ADF8CB +:10088000143000F0B7FF8BE74FF47A7000F094FF5C +:10089000071EEBDB0220FFF729FE0028E6D0013F10 +:1008A000052F00F2DE81DFE807F0030A0D10133692 +:1008B0000523042105A8059300F09CFF17E00421FF +:1008C0005548F9E704215A48F6E704215948F3E767 +:1008D0004FF01C08404608F1040800F0BDFF042159 +:1008E000059005A800F086FFB8F12C0FF2D1012089 +:1008F0004FF0000900FA07F747EA0B0B5FFA8BFB92 +:1009000001F0BAF826B10BF00B030B2B08BF002443 +:10091000FFF7F4FD44E704214748CDE7002EA5D0BA +:100920000BF00B030B2BA1D10220FFF7DFFD0746D5 +:1009300000289BD00120002600F08CFF0220FFF74A +:1009400025FE1FFA86F8404600F094FF0446B0B139 +:10095000039940460136A1F140025142514100F055 +:10096000A1FF0028EDD1BA46044641F2121302213C +:1009700005A83E46ADF8143000F03CFF10E72546D0 +:100980000120FFF703FE244B9B68AB4207D92846A2 +:1009900000F062FF013040F067810435F3E7002585 +:1009A000224BBA463E461D701F4B5D60A8E7002EE5 +:1009B0003FF45CAF0BF00B030B2B7FF457AF02201F +:1009C000FFF7E4FD322000F0F7FEB0F10008FFF67B +:1009D0004DAF18F003077FF449AF0F4A08EB05034A +:1009E000926893423FF642AFB8F5807F3FF73EAF43 +:1009F000124BB845019323DD4FF47A7000F0DCFE12 +:100A00000390039A002AFFF631AF039A0137019B46 +:100A100003F8012BEDE700BF00230020EC240020A9 +:100A2000D023002015050008F0240020E823002032 +:100A300004230020082300200C230020EC230020A6 +:100A4000C820FFF753FD074600283FF40FAF1F2DC6 +:100A500011D8C5F120020AAB25F0030084494245B4 +:100A6000184428BF4246019200F094FF019AFF21EA +:100A70007F4800F0B5FF4FEAA803C8F387027C491E +:100A80002846019300F0B4FF064600283FF46DAFFE +:100A9000019B05EB830533E70220FFF727FD0028C4 +:100AA0003FF4E4AE00F010FF00283FF4DFAE002773 +:100AB000B846704B9B68BB4218D91F2F11D80A9BB0 +:100AC00001330ED027F0030312AA134453F8203C3D +:100AD00005934046042205A9043701F06BFA8046CD +:100AE000E7E7384600F0B8FE0590F2E7CDF814804D +:100AF000042105A800F07EFE02E70023642104A87B +:100B0000049300F06DFE00287FF4B0AE0220FFF7E2 +:100B1000EDFC00283FF4AAAE049800F0CBFE05904F +:100B2000E6E70023642104A8049300F059FE00289E +:100B30007FF49CAE0220FFF7D9FC00283FF496AE6C +:100B4000049800F0B9FEEAE70220FFF7CFFC002886 +:100B50003FF48CAE00F0C8FEE1E70220FFF7C6FCD0 +:100B600000283FF483AE05A9142000F0C3FE074619 +:100B70000421049004A800F03DFE3946B9E7322074 +:100B800000F01AFE071EFFF671AEBB077FF46EAED3 +:100B9000384A07EB0903926893423FF667AE02209A +:100BA000FFF7A4FC00283FF461AE27F003074F4491 +:100BB000B9453FF4A5AE484609F1040900F04CFEE2 +:100BC0000421059005A800F015FEF1E74FF47A70B6 +:100BD000FFF78CFC00283FF449AE00F075FE0028BA +:100BE00044D00A9B01330BD008220AA9002000F050 +:100BF000FFFE00283AD02022FF210AA800F0F0FED4 +:100C0000FFF77CFC1C4804F08FFE13B0BDE8F08FAA +:100C1000002E3FF42BAE0BF00B030B2B7FF426AE14 +:100C20000023642105A8059300F0DAFD074600289B +:100C30007FF41CAE0220FFF759FC804600283FF4E9 +:100C400015AEFFF75BFC41F2883004F06DFE0598AD +:100C500000F05CFF46463C4600F00EFFA0E506466D +:100C60004EE64FF0000901E6BA467EE637467CE6DE +:100C7000EC23002000230020A0860100094A49F24D +:100C80006900136899B21B0C00FB013344F25061F8 +:100C90001360054B186882B2000C01FB020018605B +:100CA00080B270471423002010230020002110225E +:100CB00010B5044600F094FE034B03CB2060616046 +:100CC0001868A06010BD00BF00E8F11F2DE9F041D9 +:100CD000ADF5507D0D46002140F275126EAC074611 +:100CE00010A80F9100F07CFE4FF4C4720021204642 +:100CF00000F076FE0DF13C0802F05AFB4FF47A72D8 +:100D0000264BB0FBF2F0186093E80700022384E85A +:100D100007000DF5ED702382FFF7C8FF47F60503C6 +:100D20001F4907A8238406F0F1FE1F230DF2EB22D2 +:100D30000DF1340C84F8323107AB1E46083203CE75 +:100D4000664542F8080C42F8041C3346F5D1306879 +:100D500010602046B188B379918041469371012299 +:100D600000F04CFF002380B2E97E0393AB7E029338 +:100D700005F1190301930123009306A3D3E900238E +:100D8000CDE90480384602F0D1FE0DF5507DBDE876 +:100D9000F08100BF9E6AC421818A46EEF8240020BB +:100DA0001C7B00082DE9F0412C4CDAB080460D4642 +:100DB000237A5BBB27A9284601F02EF807460028B6 +:100DC00042D19DF89D60C82E3ED801464FF4A662E0 +:100DD000204600F005FE4FF4807332460DF19E016F +:100DE000C4F8F8314FF4007304F109002644C4F844 +:100DF0000C334FF44073C4F8203400F0CBFD9DF861 +:100E00009C30777223720BB9EB7E237206AC812281 +:100E1000002127A800F0E4FD0122214627A801F0C7 +:100E200037F8002380B2E97E0393AB7E029305F18D +:100E3000190301932823CDE904400093404605A3FC +:100E4000D3E9002302F072FE5AB0BDE8F08100BF82 +:100E5000AFF3008026417272DF25D7B7C05E002055 +:100E6000F0B5254E4FF48A75F1B0002405FB0065FE +:100E700096F8D830D822214685F8DC303AA885F893 +:100E8000E84006AF00F0ACFD06F1090000F0A0FD5F +:100E9000D5F8E430C2B206F109018DF8F0000DF189 +:100EA000F100CDE93A3400F075FD394601223AA847 +:100EB00001F01AF8082380B2317ACDE904700127D5 +:100EC0000E48CDE9023706F1D80301933023009391 +:100ED00007A3D3E9002302F029FEA04206DD02F0B9 +:100EE00067FAC5F8E000384671B0F0BD2046FBE770 +:100EF00078F6339F93CACD8DC05E00201035002058 +:100F00002DE9F04F264F87B0DFF8A080254E3846F8 +:100F100002F038FE034600283AD00024224DADF8F6 +:100F20001440A1460294A246CDE90344027B8DF809 +:100F3000142003AA9968406803C21B6843F0004369 +:100F400002932B6804F5A664D3F810B002F032FACD +:100F500010EB0802CDF800A0284605F5A65541F192 +:100F6000000302A9D8470028C8BF49F00109B4F519 +:100F7000266FE6D1B9F1000F05D0384602F006FE23 +:100F800086F800A0C3E73378072B04D80133337009 +:100F900007B0BDE8F08F024802F0F8FDF8E700BFA7 +:100FA00010350020F56300204035002040420F003E +:100FB00070B50D4614461E4602F014FD50B9022EBF +:100FC00010D1012C0ED112A3D3E900230120C5E9D1 +:100FD000002307E0282C10D005D8012C09D0052CBF +:100FE0000FD0002070BD302CFBD10BA3D3E9002320 +:100FF000ECE70BA3D3E90023E8E70BA3D3E9002335 +:10100000E4E70BA3D3E90023E0E700BFAFF30080E0 +:10101000401DA12026812A0B78F6339F93CACD8DDF +:101020009E6AC421818A46EE26417272DF25D7B7B7 +:10103000F017304A39059E5638B505460E4C00214A +:10104000013500F02FFCA4F82C55B4F82C0500F065 +:1010500011FC78B1B4F82C0500F01CFC014648B92D +:10106000B4F82C0500F01EFCB4F82C350133A4F8BC +:101070002C35EAE738BD00BFC05E0020F8B50D4C46 +:1010800002260D4FA4F5805343F8307C237E3BB9F4 +:1010900065692DB1284601F01DF8284606F0ECFCE4 +:1010A0002046A4F5A65401F015F8012E00D1F8BD94 +:1010B0000126E7E7305A0020DC7B00082DE9F04FDD +:1010C0008FB005460C4600AF02F08CFC002849D1D9 +:1010D000237E022B1BD1E38A012B18D102F068F981 +:1010E0000646FFF7CBFD03464FF4C87006F51676AB +:1010F000DFF8C082B3FBF0F202FB103316FA83F381 +:10110000C8F80030E37E33B9A34B00221A703C3795 +:10111000BD46BDE8F08F07F12401204600F03AFEFD +:101120000028F4D107F11400FFF7C0FD97F826401E +:1011300007F1140107F12700224606F0B5FC00284C +:10114000E2D10F2C08D8944B1C70D8F80030A3F5CE +:101150001673C8F80030DAE797F82410284602F032 +:1011600039FCD4E7E38A282B2BD010D8012B23D0CD +:10117000052BCCD1BFF34F8F8849894BCA6802F445 +:10118000E0621343CB60BFF34F8F00BFFDE7302B0E +:10119000BDD1844EE17E327A9142B8D1607E314633 +:1011A000002291F8DC50854200F0A580013201F563 +:1011B0008A71042AF5D1AAE721462846FFF786FD61 +:1011C000A5E721462846FFF7EDFDA0E7B2F8EC5071 +:1011D0007B6005F103094FEA99094FEA8902D11DA5 +:1011E000C908A8EBC10300219D46EB46584600F014 +:1011F000F7FB04F1EE012A465846314400F0CAFBE1 +:101200007B6813B9012000F025FB96F8D20000F0AE +:1012100031FB044630B9307200F056FB204600F036 +:1012200019FBB1E0D6F8D4203AB996F8D200B6F856 +:101230002C25824201D8FFF7FFFED6F8D4202A449D +:10124000944208D296F8D200B6F82C25013082429A +:1012500001D8FFF7F1FE5FFA89F25946706800F095 +:10126000C7FB08B9C54679E0726896F8D2002A44EF +:101270007260D6F8D42005EB0209C6F8D49000F0CD +:10128000F9FA814509D396F8D220D6F8D400013274 +:10129000001B86F8D220C6F8D400FF2D0FD80024FA +:1012A000347200F011FB204600F0D4FA00F098FEF2 +:1012B0003D4B188108B9FFF77FF9C54627E7BB68A2 +:1012C00096F8D9000AFB0362FB68D2F8E41082F8B2 +:1012D000E83001F58061C2F8E030C2F8E410FFF7B1 +:1012E000BFFDFFF70DFE96F8D920013202F0030290 +:1012F00086F8D920B6E74FF48A7A20460AFB02F531 +:1013000005F1EA01314400F01BFEF86000287FF48B +:10131000FEAE0122354485F8E82002F049F8D5F800 +:10132000E020D6ED007A801A40F6B832B8EE677A3F +:10133000DFED1E6A192838BF1920904228BF1046D9 +:1013400007EE900AF8EEE77A67EEA67ADFED186A04 +:10135000E7EE267AFCEEE77AC6ED007A96F8D93009 +:10136000BB60BA6873680AFB02F4321992F8E8109D +:1013700059B1D2F8E410E8468B423FF427AF002180 +:1013800082F8E810C2F8E010C5467368064A9B0A66 +:1013900001331381BBE600BF0935002000ED00E0FA +:1013A0000400FA05C05E0020F8240020CDCCCC3D1E +:1013B0006666663F0C350020014B1870704700BF11 +:1013C0000425002038B54FF00054144B22689A428F +:1013D00021D1627D0025124B12481A70C922237D4B +:1013E0000930114900F8013C4FF48073C0F8DB501C +:1013F000C0F8EF314FF40073C0F803334FF440737B +:10140000C0F8173400F0C6FAE0222946204600F062 +:10141000E7FA012038BD0020FCE700BF9AAD44C5C3 +:1014200004250020C05E00201600002037B500F023 +:10143000D7FD1F4C1F4D022301221F496B712368EA +:10144000288120465B68984704F5805301221A4999 +:10145000D3F8C03404F5A6505B68984700231749B9 +:101460004FF480520193164B16480093164B02F02E +:1014700089FA164B197811B1124802F0ABFA01F053 +:1014800097FF0446FFF7FAFB4FF4C873B0FBF3F283 +:1014900002FB130304F5167010FA83F00C4B18606E +:1014A00004F04EFF08B10F232B8103B030BD00BF05 +:1014B00040350020F824002040420F00082500207D +:1014C000B10F000810350020BD10000804250020D1 +:1014D0000C3500202DE9F04F00242DED028B93B048 +:1014E0000DF12C084FF0010ADFF814B2FFF708FDE8 +:1014F0000A94ADF834400B94C8F804409FED798B02 +:1015000000267E4D37462B680DF11D0207A928469F +:101510008DF81CA08DF81D408DED008BD3F8089040 +:101520000023C8479DF81C90B9F1000F1ED010226F +:1015300000210EA800F054FA2B6808AA0AA95F69D6 +:1015400028460DF11E03B8470FAB4F4698E803003D +:1015500083E803009DF834300EA958468DF84430D6 +:101560000A9B0E93DDE9082302F0EEFC06F5A66661 +:1015700005F5A655B6F5266FC5D1002FC0D1604838 +:1015800002F030FA00283FD15E4E01F011FF3368BF +:10159000984239D301F00CFF0546FFF76FFB4FF47B +:1015A000C8738DF82870B0FBF3F202FB130305F546 +:1015B000167010FA83F03060534E377817B9012354 +:1015C0008DF82830C7F110050EA8FFF76FFB0EABA2 +:1015D000EDB20DF12900D919062D28BF06252A469E +:1015E000013500F0D7F90AABEDB245480393182353 +:1015F00004950293454B0193012300933BA3D3E948 +:10160000002302F035FA347001F0D2FE404A414D19 +:101610001368C31AB3F57A7F2FD3106001F0CAFEA6 +:1016200002460B46364802F0BBFA354802F0DAF9BA +:1016300018B32B7A0EAF384E002B14BF03230223AE +:10164000737101F0B5FE4FF47A7301223946B0FB95 +:10165000F3F03060304600F075FB182380B202933F +:101660002E4B019340F25513CDE9037000932448AB +:1016700020A3D3E9002302F0FBF92B7A93B101F008 +:1016800097FE002607464FF48A7895F8D900304433 +:1016900000F0030008FB005393F8E82072B1013614 +:1016A000042EF2D1C82004F03FF92B7A002B7FF4EE +:1016B00017AF13B0BDEC028BBDE8F08FD3F8E0207C +:1016C00042B12B68BA1AFA2B38BFFA230533B2EBB2 +:1016D000430FE4D3FFF7C4FB0028E0D1E2E700BFEB +:1016E000AFF300800000000000000000401DA120BA +:1016F00026812A0BF1C6A7C1D068080F403500200B +:10170000103500200C350020093500200835002058 +:10171000F0630020C05E0020F8240020F463002065 +:1017200010B5074C204601F007F904F5A65001F06A +:1017300003F9044A04490020BDE8104006F096B9B8 +:1017400040350020506400207D1000082DE9F84F3E +:101750004FF47A7306460D46002402FB03F7DFF8C8 +:101760005080DFF8509098F900305FFA84FA5A1CE4 +:1017700001D0A34212D159F824002A463146036809 +:10178000D3F820B03B46D847854207D1074B01200C +:1017900083F800A0BDE8F88F0124E4E7002CFBD01B +:1017A0004FF4FA7004F0C0F80020F3E73C64002026 +:1017B000182300201C230020002307B50246012126 +:1017C0000DF107008DF80730FFF7C0FF20B19DF83D +:1017D000070003B05DF804FB4FF0FF30F9E70000AD +:1017E0000A46042108B5FFF7B1FF80F00100C0B23E +:1017F000404208BD074B0A4630B41978064B53F8EF +:101800002140014623682046DD69044BAC4630BCCC +:10181000604700BF3C6400201C230020A08601001C +:1018200070B50A4E00240A4D04F0AAFB30802868E7 +:101830003388834208D904F09FFB2B6804440133AA +:10184000B4F5003F2B60F2D370BD00BF3E640020B2 +:10185000F863002004F062BC00F1006000F5003085 +:101860000068704700F10060920000F5003004F05D +:10187000E3BB0000054B1A68054B1B889B1A83428B +:1018800002D9104404F078BB00207047F8630020B0 +:101890003E640020024B1B68184404F073BB00BF79 +:1018A000F8630020024B1B68184404F07DBB00BFA6 +:1018B000F86300200020704700F1FF5000F58F1002 +:1018C000D0F8000870470000064991F8243033B181 +:1018D00000230822086A81F82430FFF7C3BF0120E3 +:1018E000704700BFFC630020014B1868704700BFC1 +:1018F0000010005C194B01380322084470B51D68C4 +:10190000174BC5F30B042D0C1E88A6420BD15C6847 +:101910000A46013C824213460FD214F9016F4EB1C0 +:1019200002F8016BF6E7013A03F10803ECD18142BA +:101930000B4602D22C2203F8012B0424094A1688F4 +:10194000AE4204D1984284BF967803F8016B013C03 +:1019500002F10402F3D1581A70BD00BF0010005C00 +:1019600024230020687B00087047000070470000B7 +:101970007047000070B504464FF47A764CB1412CA4 +:10198000254628BF412506FB05F0641B03F0CCFF6C +:10199000F4E770BD002310B5934203D0CC5CC4546F +:1019A0000133F9E710BD0000013810B510F9013F0F +:1019B0003BB191F900409C4203D11AB10131013A87 +:1019C000F4E71AB191F90020981A10BD1046FCE70F +:1019D00003460246D01A12F9011B0029FAD17047BA +:1019E00002440346934202D003F8011BFAE7704712 +:1019F0002DE9F8431F4D14460746884695F82420E4 +:101A000052BBDFF870909CB395F824302BB920229C +:101A1000FF2148462F62FFF7E3FF95F82400414677 +:101A2000C0F1080205EB8000A24228BF2246D6B2D0 +:101A30009200FFF7AFFF95F82430A41B17441E4413 +:101A40009044E4B2F6B2082E85F82460DBD1FFF7AB +:101A50003BFF0028D7D108E02B6A03EB82038342C7 +:101A6000CFD0FFF731FF0028CBD10020BDE8F883AD +:101A70000120FBE7FC630020024B1A78024B1A702E +:101A8000704700BF3C6400201823002038B51A4C72 +:101A90001A4D204603F08CFA2946204603F0B4FA8A +:101AA0002D684FF47A70D5F89020D2F8043843F0BE +:101AB0000203C2F80438FFF75DFF1149284603F01E +:101AC000B1FBD5F890200F4DD2F80438286823F0E8 +:101AD00002030D49A042C2F804384FF4E1330B6011 +:101AE00001D003F0C3F96868A04204D00649BDE8FC +:101AF000384003F0BBB938BDB86B0020287E000821 +:101B0000307E00081C230020246400200C4B70B59C +:101B10000C4D04461E780C4B55F826209A420DD0E9 +:101B20000A4B002118221846FFF75AFF04600146AD +:101B300055F82600BDE8704003F098B970BD00BFAD +:101B40003C6400201C230020B86B0020246400208B +:101B5000F0B5A1B071B600230120002480261A46FA +:101B6000194602F05BFE4FF4D067214A3D25136908 +:101B700023BBD2F810310BBB036804F100619960FC +:101B80000368C3F80CD003685E6003681F600168D7 +:101B90000B6843F001030B6001680B6823F01E0320 +:101BA0000B6001680B68DB07FCD4037B8034416861 +:101BB00005FA03F3B4F5001F0B60D8D102F06EFEF6 +:101BC000B4F5001F11D000240A4E0B4D012004F083 +:101BD000A5FA3388A34205D928682044013404F0CB +:101BE000E3F9F6E7002004F099FA61B621B0F0BD00 +:101BF000002000523E640020F86300202DE9F047E9 +:101C00000D46044600219046284640F27912FFF71F +:101C1000E7FE234620220021284604F1220702F095 +:101C200035F9231D022220212846C02602F02EF974 +:101C3000631D03222221284602F028F9A31D032256 +:101C40002521284602F022F904F108031022282158 +:101C5000284602F01BF904F1100308223821284617 +:101C600002F014F904F1110308224021284602F081 +:101C70000DF904F1120308224821284602F006F962 +:101C800004F1140320225021284602F0FFF804F149 +:101C9000180340227021284602F0F8F804F12003CE +:101CA0000822B021284602F0F1F804F121030822AD +:101CB000B821284602F0EAF8314608363B460822A9 +:101CC0002846013702F0E2F8B6F5A07FF4D10027EC +:101CD00004F1330A04F1320308223146284602F0A7 +:101CE000D5F894F832304FEAC7099F4209F5A47637 +:101CF00015D3B8F1000F08D1314609F24F1604F59B +:101D000099730722284602F0C1F827463B1B94F836 +:101D1000322193420CD3F01DC008BDE8F0870AEBD6 +:101D20000703082231462846013702F0AFF8D8E70A +:101D300007F233133146082228460836013702F0ED +:101D4000A5F8E3E713B50446084600212022234600 +:101D500001900160C0F8031002F098F8231D01986B +:101D60000222202102F092F8631D01980322222111 +:101D700002F08CF8A31D01980322252102F086F8B9 +:101D8000019804F108031022282102F07FF80720AF +:101D900002B010BD0023F7B50E46047F0722009164 +:101DA0001946054601F036FF731C012207210093F6 +:101DB0002846002301F02EFFC4B9B31C05220821D8 +:101DC0002846009323460D2401F024FF3746BB1B11 +:101DD000B278934211D307342B7FA88AE408BBB9A9 +:101DE000844294BF0020012003B0F0BDAB8A0824D8 +:101DF000DB00083BDB08B370E8E7FB1C2146082248 +:101E00002846009300230834013701F003FFDEE782 +:101E1000201A18BF0120E7E70023F7B50E46047F1C +:101E2000082200911946054601F0F4FE731CC4B95E +:101E300008220093234610241146284601F0EAFEAA +:101E400001235F1C7278013B934211D307342B7F2F +:101E5000A88AE408BBB9844294BF0020012003B0E3 +:101E6000F0BDAB8A0824DB00083BDB087370E7E7B2 +:101E7000F3192146082228460093002301F0CAFEE8 +:101E800008343B46DDE7201A18BF0120E7E70000D1 +:101E9000F8B50E4605461446002181223046FFF76C +:101EA0009FFD2B4608220021304601F0EFFF7CB950 +:101EB0000F246B1C07220821304601F0E7FF0123A5 +:101EC0005F1C6A78013B934204D3E01DC008F8BD53 +:101ED0000824F4E7EB1921460822304601F0D6FF2A +:101EE00008343B46ECE70000F8B50E4605461446BC +:101EF0000021CE223046FFF773FD2B462822002119 +:101F0000304601F0C3FF7CB9302405F108030822F4 +:101F10002821304601F0BAFF2F467B1B2A7A9342D4 +:101F200004D3E01DC008F8BD2824F5E707F1090334 +:101F30002146082230460834013701F0A7FFECE7BC +:101F4000F7B5047F0E4600910123102200210546BB +:101F500001F060FEC4B9B31C092210212846009389 +:101F60002346192401F056FE37467288BB1B9A425D +:101F700011D807342B7FA88AE408BBB9844294BFE8 +:101F80000020012003B0F0BDAB8A1024DB00103B21 +:101F9000DB087380E8E73B1D2146082228460093B2 +:101FA00000230834013701F035FEDEE7201A18BFA0 +:101FB0000120E7E730B50A44084D91420DD011F8F1 +:101FC000013B5840082340F30004013B2C4013F030 +:101FD000FF0384EA5000F6D1EFE730BD2083B8ED6F +:101FE000F7B5364A6B46106851686A4603C3082342 +:101FF0003349344805F068FD044690BB0A25324A4F +:102000006B46106851686A4603C308232F492D4860 +:1020100005F05AFD0446002847D00369B3F5F01FC8 +:1020200043D8B0F86620B2F5AF6F3ED1284A0244DB +:1020300002F15C018B4238D35C3B224900209E1A9E +:10204000FFF7B8FF04F16401074632460020FFF7AE +:10205000B1FFA3689F4228D1E368984208BF0025DA +:1020600023E00369B3F5F01F26D8428BB2F5AF6FBA +:1020700020D1174A024402F110018B4218D3103BC1 +:10208000104900209D1AFFF795FF04F1180106463C +:102090002A460020FFF78EFFA3689E4202D1E36824 +:1020A000984201D00D25AAE70025284603B0F0BDCF +:1020B0001025A4E70C25A2E70B25A0E7787B0008F4 +:1020C000DCFF1D0000000208817B000890FF1D005E +:1020D0000800FEF710B5037C044613B9006805F04C +:1020E000DBFC204610BD00000023BFF35B8FC36004 +:1020F000BFF35B8FBFF35B8F8360BFF35B8F704772 +:10210000BFF35B8F0068BFF35B8F704770B5054608 +:102110000C30FFF7F5FF044605F108063046FFF7DF +:10212000EFFFA04206D96D683046FFF7E9FF25446E +:10213000281A70BD3046FFF7E3FF201AF9E70000C8 +:1021400070B505464068A0B105F10C0605F1080020 +:10215000FFF7D6FF04463046FFF7D2FF844204F172 +:10216000FF34304694BF6D680025FFF7C9FF2C444B +:10217000201A70BD38B50C460546FFF7C7FFA042D0 +:1021800010D305F10800FFF7BBFF04446868BFF3F4 +:102190005B8FB4FBF0F100FB11440120AC60BFF396 +:1021A0005B8F38BD0020FCE72DE9F041144607465F +:1021B0000D46FFF7C5FF844228BF0446D4B1B84698 +:1021C00058F80C6B4046FFF79BFF304428604046B0 +:1021D0007E68FFF795FF331A9C4203D801206C609C +:1021E000BDE8F081A41B6B603B682044AB60E860F5 +:1021F0000220F5E72046F3E738B50C460546FFF721 +:102200009FFFA04210D305F10C00FFF779FF0444B3 +:102210006868BFF35B8FB4FBF0F100FB1144012051 +:10222000EC60BFF35B8F38BD0020FCE72DE9FF4178 +:102230008846694607466C46FFF7B6FF002506B29A +:1022400004EBC606B4420AD0626808EB05012068B8 +:102250000834FFF79FFB54F8043C1D44F2E729467D +:102260003846FFF7C9FF284604B0BDE8F0810000FA +:10227000F8B505460C300F46FFF742FF05F108069A +:1022800004463046FFF73CFFA042304688BF6C68EA +:10229000FFF736FF201A386020B12C683046FFF770 +:1022A0002FFF2044F8BD000073B5144606460D46C6 +:1022B000FFF72CFF8442019028BF0446DCB101A93E +:1022C0003046FFF7D5FF019B33B93268C5E90233C9 +:1022D000C5E9002401200CE09C42286038BF01942D +:1022E000019884426860F5D93368241A0220AB60F3 +:1022F000EC6002B070BD2046FBE700002DE9FF4115 +:102300000F4669466C46FFF7CFFF00B2002604EB8C +:10231000C005AC4209D0D4F80480B81954F8081BA1 +:1023200042464644FFF736FBF3E7304604B0BDE8CB +:10233000F081000038B50546FFF7E0FF044601468E +:102340002846FFF717FF204638BD00007047000001 +:1023500010B41346026814680022A4465DF8044BCA +:102360006047000000F5805090F859047047000065 +:1023700000F5805090F852047047000000F580503E +:1023800090F95804704700004E207047302383F3C3 +:10239000118800F58052D2F89C34D2F89804184481 +:1023A000D2F894341844D2F87C341844D2F88C34DF +:1023B0001844D2F888341844002383F311887047F6 +:1023C00000F58050C0F85414012070472DE9F04FFB +:1023D0000C4600F5805185B01F4691F852340546F1 +:1023E0009046BDF838909BB1D1F878340133C1F8EC +:1023F00078342368980006D4237B082B0BD9627BA2 +:102400000AB10F2B07D9D1F87C340133C1F87C34E1 +:102410004FF0FF3010E0302383F31188EB6AD3F8DC +:10242000C42012F4001B0AD0D1F8803400200133FC +:10243000C1F8803480F3118805B0BDE8F08F2068C2 +:102440004822D3F8C4300028C3F3044A6B6AB4BFEF +:1024500040F08040800412FB0A334FEA4A161860AD +:10246000226852004FEA0A6244BF40F000501860F0 +:10247000207B42EA00425A60607B10B342F4401273 +:102480005A60D1F8B0240132C1F8B024AA1902F57B +:102490008352117B41F020011173207B039300F0E4 +:1024A000E3FF0330039B80105FFA8BF20BF1010B0B +:1024B00082420DDA04EB820103EB820249689160EB +:1024C000F2E7AA1902F58352117B60F34511E3E7A5 +:1024D0000122EB6A05EB4A1102FA0AF201F5825178 +:1024E000C3F8D020AB19183104F10C0203F5825364 +:1024F000C3E90487234653F8040B934241F8040BC5 +:10250000F9D11B882E440B8041F2680346F803A0E2 +:1025100006F5805609F0030396F86C2043F010038B +:1025200022F01F02134386F86C30002383F31188D6 +:1025300042463B4621462846CDF8009000F05AFF1F +:10254000012079E72DE9F04700F58056044696F81A +:102550005254002D40F00381037C032B40F0948003 +:1025600028462B462F465FFA80FC944510DA01EB93 +:10257000CC0E51F83CC0BCF1000F04DBDEF804C007 +:10258000BCF1000F02DB01370130ECE70133FBE760 +:10259000302080F31188E06AF3B9D0F8803043F03E +:1025A0000203C0F880304E23E06A002F6FD1D0F8CC +:1025B000803043F00103C0F880306A4B6A4A1B68E0 +:1025C00003F1805303F52C539B009342A36240F226 +:1025D000B080664800F0E6FE4D2B42D8DFF88481DB +:1025E0004FEA034EDFF88891D8F800C04EEA8C0E0F +:1025F000C0F884E00CF1805000F52C508000606140 +:1026000003EB0C00D4F82CC0C3F14E03C8F8000053 +:10261000DCF8800040F03000CCF880004FF0000C77 +:10262000D4F81480E6465FFA8CF08242BCDD01EB00 +:10263000C00A51F83000002810DBDAF804A0BAF123 +:10264000000F0BDA09EA00400AF07F0A40EA0A00AC +:1026500040F0084048F82E000EF1010E0CF1010C7C +:10266000E1E7836923F00103836100F0A1FE0646E0 +:10267000E36A9B69D90704D500F09AFE831BFA2B05 +:10268000F6D9002383F311882846BDE8F087B7EB1D +:10269000530F3DD2DFF8CCE04FEA074CDEF80030B4 +:1026A0004CEA830CC0F888C003F1805003EB470369 +:1026B000002700F52C50CEF80030BC468000A06109 +:1026C000E06AD0F8803043F00C03C0F88030D4F8D2 +:1026D00018E0FBB29A427FF770AF51F8330001EB7C +:1026E000C3080028D8F8043001DB002B0EDB20F0F3 +:1026F000604023F0604340F0005043F000434EF848 +:102700003C000EEBCC000CF1010C43600137E0E71C +:10271000836923F00103836100F04AFE0646E36A01 +:102720009B69DA07ADD500F043FE831BFA2BF6D97F +:10273000A7E7E26A936923F00103936100F038FE92 +:102740000746E36A9B69DB0705D500F031FEC31B32 +:10275000FA2BF6D995E7012586F8525491E7002522 +:1027600092E700BF4C640020FCB500408C7B000861 +:102770000000FF0713B500F580540191606CFFF76E +:10278000DFFC1F280AD920220199606CFFF74EFD5B +:10279000A0F120035842584102B010BD0020FBE7D1 +:1027A00008B5302383F3118800F58050406CFFF7A3 +:1027B0009BFC002383F3118808BD00000022026007 +:1027C00082814260826070470022002310B5C0E918 +:1027D0000023002304460C3020F8043CFFF7EEFFF2 +:1027E000204610BD2DE9F0479A4688B00746884636 +:1027F0009146302383F3118807F580546846FFF72C +:10280000E3FF606CFFF782FC1F282ED92022694667 +:10281000606CFFF78FFD202827D194F8523423B342 +:1028200003AD444605AB2E46083403CE9E4244F821 +:10283000080C44F8041C3546F5D130682060B38894 +:10284000A380DDE90023C9E90023BDF80830AAF818 +:102850000030002383F3118853464A4641463846E8 +:1028600008B0BDE8F04700F0B3BD002080F3118848 +:1028700008B0BDE8F08700002DE9F84F00230646B8 +:1028800000F58154054688461034C0E90133274BD2 +:1028900046F8303B374638462037FFF795FFA742CA +:1028A000F9D105F580544FF4805305F5A3594FF045 +:1028B000000A26630026676405F5835709F11009AD +:1028C0004FF0000B1037E663C4E90D36012384F89E +:1028D000403084F84830A7F11800203747E910ABA2 +:1028E000FFF76CFF47F8286C4F45F4D1B8F1010FA2 +:1028F00084F85884A4F85A64A4F85C64A4F85E646C +:1029000084F86064A4F86264A4F86464A4F866645B +:1029100084F8686402D9064800F044FD054B284657 +:1029200053F82830EB62BDE8F88F00BFDC7B00086D +:10293000B07B0008CC7B0008044B10B51978044626 +:102940004A1C1A70FFF798FF204610BD496400200A +:102950002DE9F04300295AD02E4E2F48B6FBF1F452 +:1029600081428CBF0A201120431EB4FBF0F700FB0C +:102970001740DDB220B1022B1846F5D8002032E016 +:102980007B1EB3F5806F2ED2C5EBC5084FF47A736A +:1029900008F103044FEAE40EC4F3C7040EF1010981 +:1029A000281B0EFB033E5FFA80FC59FA80F0BEFB49 +:1029B000F0F0B0F5617F18DC83B2601C5CFA80F047 +:1029C0007843B6FBF0F08142D8D1611E0F29D5D8EB +:1029D0000CF1FF310729D1D80120138057801071E5 +:1029E000547182F806C0BDE8F08308F1FF34E010AE +:1029F000C4F3C70400F1010E2D1B00FB03335FFA83 +:102A000085FC5EFA85F5B3FBF5F39BB2D5E7084686 +:102A1000E9E700BF00B4C4043F420F0030B50D4BDE +:102A200005200D4D1C786C438C420ED15978012045 +:102A3000518099785171D9789171197911715B79B7 +:102A400003EB83035B00138030BD013803F1060301 +:102A5000E8D1F9E71C7C000840420F0038B540F28D +:102A60007772C36A154CC3F8BC200722C36AC3F847 +:102A7000C8202268C16A930043F4C023C1F8A03083 +:102A800002F1805302F16C01C56A03F52C53EA325E +:102A900089009B00226041F0E061094AC361C5F8EA +:102AA000C01003F5D87103F56A73416293428362E3 +:102AB00002D9044800F076FC38BD00BF4C64002009 +:102AC000FCB500408C7B00082DE9F04F00F58055E7 +:102AD0001F4689B0044695F8583489469046022B23 +:102AE00004D90026304609B0BDE8F08FA84A52F854 +:102AF000231009B942F82300A648C4F80C900178C5 +:102B00002774C9B9302383F31188A34BD3F8EC2081 +:102B100042F48072C3F8EC20D3F8942042F480721F +:102B2000C3F89420D3F8942022F48072C3F8942040 +:102B30000123037081F3118895F851347BB9302358 +:102B400083F31188954A95F85834D35C0BB3012B65 +:102B500028D0012385F85134002383F311883023D2 +:102B600083F31188E26A936923F01003936100F004 +:102B70001FFC8246E36A9E6916F0080619D000F031 +:102B800017FCA0EB0A03FA2BF4D9002686F3118870 +:102B9000A8E70321132001F09DFF0321152001F078 +:102BA00099FFD6E70321142001F094FF032116209A +:102BB000F5E79A6942F001029A6100F0F9FB82465A +:102BC000E36A9A69D00706D400F0F2FBA0EB0A038F +:102BD000FA2BF5D9D9E79A694FF0000A42F00202C0 +:102BE0009A61E36AC3F854A08AF3118804F5825B02 +:102BF000686CFFF779FA0BF1100B20220021684670 +:102C0000FEF7EEFE02A8FFF7D9FD6A460BEB0603BE +:102C10000DF1180ECDF818A094460833BCE8030057 +:102C2000F44543F8080C43F8041C6246F4D1DCF880 +:102C3000000020361860B6F5806F9CF804201A71E9 +:102C4000DBD1002304F5A252494620461A3285F80A +:102C5000503485F85334FFF77BFE064690B9E26A9C +:102C6000936923F00103936100F0A2FB0546E36A38 +:102C70009B69D9077FF535AF00F09AFB431BFA2B10 +:102C8000F5D92EE795F85E34C5F86C94591E95F881 +:102C90005F34E26A013B1B0243EA416395F860142A +:102CA00001390B43B5F85C14013943EA0143D361A0 +:102CB000B8F1000F36D004F5A35241462046023247 +:102CC000FFF7ACFE90B9E26A936923F001039361C8 +:102CD00000F06EFB0546E36A9B69DA077FF501AFFA +:102CE00000F066FB431BFA2BF5D9FAE695F867244A +:102CF000C5F87084511E95F86824E36A013A120100 +:102D000042EA012295F8661401390A43B5F86414C1 +:102D1000013942EA014242F40002DA604FF42062D3 +:102D2000E36A9A64E36A4FF000082046C3F8BC8067 +:102D3000FFF794FE85F859846FF04042E36A1A6504 +:102D4000174AE36A5A654FF00222E36A9A654FF028 +:102D5000FF32E36AC3F8E0200322E36A9742DA65B0 +:102D60003FF4C0AEE26A936923F00103936100F07F +:102D70001FFB0746E36A9B69DB0705D500F018FBDC +:102D8000C31BFA2BF6D9ACE6012385F85234A9E629 +:102D9000406400204864002000440258C47B0008BE +:102DA000550200022DE9F04F054689B0904699463C +:102DB000002741F2680A00F58056EB6AD3F8D83054 +:102DC000FB40D80751D505EB47124FEA471B524449 +:102DD0001379190749D4D6F884340133C6F88434FA +:102DE00005F5A553C3E9008913799A0605EB0B0293 +:102DF00048BFD6F8B434524444BF0133C6F8B434A3 +:102E0000137943F008031371DB0723D596F8533485 +:102E100003B305F582546846FFF7D6FC03AB1834BC +:102E20005C4404F1080C2068083454F8041C1A4669 +:102E3000644503C21346F6D12068694610602846EF +:102E4000A2889A800123ADF808302B68CDE900896B +:102E5000DB6B9847D6F8A834D6F854040133C6F88B +:102E6000A83410B103681B6998470137202FA4D1FB +:102E700009B0BDE8F08F00002DE9F04F0F468DB08E +:102E8000044600F097FA82468946002F5BD1E36A38 +:102E9000D3F8A02012F4FE0F03D100200DB0BDE83E +:102EA000F08FD3F8A420920141BF04F58051D1F8EE +:102EB00098240132C1F89824D3F8A4205606ECD007 +:102EC000D3F8A450E669C5F305254823E8464FF03A +:102ED000000B03FB05664046FFF770FC32685100AB +:102EE0004ABF22F06043C2F38A4343F0004392009A +:102EF00048BF43F080430093736813F400131BBF73 +:102F0000012304F580528DF80D308DF80D301EBF71 +:102F1000D2F8B8340133C2F8B834F38803F00F03A1 +:102F20008DF80C309DF80C0000F09EFA5FFA8BF3E0 +:102F3000984225D9F2180CA90BF1010B127A0B4417 +:102F400003F82C2CEEE7012FA7D1E36AD3F8B020C9 +:102F500012F4FE0FA1D0D3F8B420950141BF04F5BF +:102F60008051D1F898240132C1F89824D3F8B420C4 +:102F7000500692D0D3F8B450266AC5F30525A4E7CD +:102F8000EFB9E36AC3F8A85004A807ADFFF71CFC2B +:102F900098E80F0007C52B800023204604A9ADF850 +:102FA0001830236804F58054DB6BCDE904A99847F9 +:102FB00058B1D4F890340133C4F890346EE7012F3F +:102FC000E2D1E36AC3F8B850DEE7D4F894340120C4 +:102FD0000133C4F8943461E72DE9F04105460F460A +:102FE00000F58054012639462846FFF745FF10B109 +:102FF00084F85364F7E7D4F8A834D4F854040133C0 +:10300000C4F8A83420B10368BDE8F0411B69184733 +:10301000BDE8F081C36AF0B51A6C12F47F0F2BD0B3 +:103020001B6C00F5805441F268054FF0010CC4F8A8 +:10303000AC340023471900EB43125E012A44117996 +:1030400011F0020F15D0490713D4B959C66A0CFA0A +:1030500001F1D6F8CCE011EA0E0F0AD0C6F8D41070 +:10306000117941F004011171D4F88C240132C4F8B3 +:103070008C240133202BDED1F0BD00002B4B70B52A +:103080001E561B5C012B30D8294D2A4A55F8233097 +:1030900052F8264013B349B3236D9A0510D54FF467 +:1030A0000073236500F086F950EA01020B4602D056 +:1030B000013861F10003024655F82600FFF772FE61 +:1030C000236D9B012CD54FF0007255F826302265F8 +:1030D00003F58053012283F8592421E0012323655D +:1030E000102323654FF48053236570BD236DDA07E9 +:1030F00002D4236D5B0706D50523002155F8260071 +:103100002365FFF769FF236DD80602D4236D5906A6 +:1031100006D55023012155F826002365FFF75CFFF3 +:1031200055F82600BDE87040FFF774BFC87B000863 +:1031300040640020CC7B000808B5302383F311885D +:10314000FFF768FF002383F3118808BDC36AD3F833 +:10315000C00010F07C5005D0D3F8C40080F40010FB +:10316000C0F340507047000008B5302383F3118846 +:1031700000F58050406CFEF7C9FF002383F31188EF +:1031800043090CBF0120002008BD000000F580535A +:1031900093F8592462B1C16A8A6922F001028A61F6 +:1031A000D3F89C240132C3F89C24002283F85924CC +:1031B000704700002DE9F743302181F3118800F5B5 +:1031C0008251002541F2680E4FF00108103100F5E0 +:1031D000805C00EB45147444267977071CD4F6060E +:1031E0001AD58E69D0F82C9008FA06F6D9F8CC706A +:1031F0003E4211D04F6801970F689742019F9F414F +:103200000AD2C9F8D460267946F004062671DCF8A3 +:1032100088440134CCF8884401352031202DD8D1A0 +:10322000002383F3118803B0BDE8F083F8B51E4690 +:1032300000230F46054613701446FFF795FF80F0F4 +:10324000010038701EB12846FFF780FF2070F8BDDE +:103250002DE9F04F85B099460D468046164691F807 +:1032600000B0DDE90EA302931378019300F0A2F8F9 +:103270002B7804460F4613B93378002B41D02246F1 +:103280003B464046FFF796FFFFF756FFFFF77EFFEE +:103290004B4632462946FFF7C9FF2B7833B1BBF1C5 +:1032A000000F03D0012005B0BDE8F08F337813B1D3 +:1032B000019B002BF6D108F5805303935445029BE4 +:1032C00077EB03031DD2039BD3F85404C8B1036802 +:1032D000AAEB04011B6898474B46324629464046F4 +:1032E000FFF7A4FF2B7813B1BBF1000FDAD13378CD +:1032F00013B1019B002BD5D100F05CF804460F46BA +:10330000DCE70020CFE70000002108B50846FFF702 +:10331000B5FEBDE8084001F06DB8000008B5012118 +:103320000020FFF7ABFEBDE8084001F063B80000E5 +:1033300008B500210120FFF7A1FEBDE8084001F01B +:1033400059B80000012108B50846FFF797FEBDE80F +:10335000084001F04FB8000000B59BB0EFF30981C1 +:1033600068226846FEF716FBEFF30583014B9B6B63 +:10337000FEE700BF00ED00E008B5FFF7EDFF00003D +:1033800000B59BB0EFF3098168226846FEF702FBA7 +:10339000EFF30583014B5B6BFEE700BF00ED00E040 +:1033A000FEE700000FB408B5029802F063FAFEE7EA +:1033B00002F0F6BE02F0D8BE13B56C46031D84E8D9 +:1033C000060094E8030083E80500012002B010BD68 +:1033D00073B58568019155B11B885B0707D4D0E9A7 +:1033E00000369B6B9847019AC1B23046A84701202E +:1033F00002B070BDF0B5866889B005460C465EB176 +:10340000BDF838305B070AD4D0E900379B6B98478A +:103410002246C1B23846B047012009B0F0BD0022B3 +:10342000002301F10806CDE9002300230A46ADF888 +:10343000083003AB1068083252F8041C1C46B24234 +:1034400003C42346F6D1106820609288A280FFF75B +:10345000B1FF0423ADF808302B68CDE90001DB6B28 +:10346000694628469847D7E7082817D909280CD075 +:103470000A280CD00B280CD00C280CD00D280CD00E +:103480000E2814BF4020302070470C2070471020B9 +:1034900070471420704718207047202070470000A4 +:1034A0002DE9F041456A15B94162BDE8F0814B68EC +:1034B000AC4623F06047C3F38A464FEAD37EC3F39A +:1034C000807816EA230638BF3E462B465A68BEEB84 +:1034D000D27F22F060440AD0002A18DAA40CB44249 +:1034E00017D19D420FD10D60DEE71346EEE7A742EC +:1034F00007D102F08044C2F3807242450BD054B130 +:10350000EFE708D2EDE7CCF800100B60CDE7B4424E +:1035100001D0B442E5D81A689C46002AE5D119606A +:10352000C3E700002DE9F047089D01F0070400EB18 +:10353000D1004FF47F494FEAD508224405F0070532 +:10354000944201D1BDE8F08704F0070705F0070AAF +:10355000111B08EBD50E57453E4613F80EC038BF79 +:103560005646C6F108068E4228BF0E46E108415C69 +:1035700034443544B94029FA06F721FA0AF1FFB27A +:103580008CEA010147FA0AF739408CEA010C03F88A +:103590000EC0D5E780EA0120082341F2210201B2E2 +:1035A000013B4000002980B2B8BF504013F0FF0338 +:1035B000F5D1704738B50C468D18A54200D138BDFD +:1035C00014F8011BFFF7E6FFF7E7000042684AB175 +:1035D000136881894360438901339BB299424381D7 +:1035E00038BF83811046704770B588B004462022EA +:1035F0000D4668460021FEF7F3F920460495FFF7D3 +:10360000E5FF024660B16B46054608AE1C4608352C +:1036100003CCB44245F8080C45F8041C2346F5D108 +:10362000104608B070BD0000082817D909280CD032 :103630000A280CD00B280CD00C280CD00D280CD04C :103640000E2814BF4020302070470C2070471020F7 :1036500070471420704718207047202070470000E2 -:103660002DE9F041456A15B94162BDE8F0814B682A -:10367000AC4623F06047C3F38A464FEAD37EC3F3D8 -:10368000807816EA230638BF3E462B465A68BEEBC2 -:10369000D27F22F060440AD0002A18DAA40CB44287 -:1036A00017D19D420FD10D60DEE71346EEE7A7422A -:1036B00007D102F08044C2F3807242450BD054B16E -:1036C000EFE708D2EDE7CCF800100B60CDE7B4428D -:1036D00001D0B442E5D81A689C46002AE5D11960A9 -:1036E000C3E700002DE9F047089D01F0070400EB57 -:1036F000D1004FF47F494FEAD508224405F0070571 -:10370000944201D1BDE8F08704F0070705F0070AED -:10371000111B08EBD50E57453E4613F80EC038BFB7 -:103720005646C6F108068E4228BF0E46E108415CA7 -:1037300034443544B94029FA06F721FA0AF1FFB2B8 -:103740008CEA010147FA0AF739408CEA010C03F8C8 -:103750000EC0D5E780EA0120082341F2210201B220 -:10376000013B4000002980B2B8BF504013F0FF0376 -:10377000F5D1704738B50C468D18A54200D138BD3B -:1037800014F8011BFFF7E6FFF7E7000042684AB1B3 -:10379000136881894360438901339BB29942438115 -:1037A00038BF83811046704770B588B00446202228 -:1037B0000D4668460021FEF78DFA20460495FFF776 -:1037C000E5FF024660B16B46054608AE1C4608356B -:1037D00003CCB44245F8080C45F8041C2346F5D147 -:1037E000104608B070BD0000082817D909280CD071 -:1037F0000A280CD00B280CD00C280CD00D280CD08B -:103800000E2814BF4020302070470C207047102035 -:103810007047142070471820704720207047000020 -:10382000082817D90C280CD910280CD914280CD921 -:1038300018280CD920280CD930288CBF0F200E2036 -:103840007047092070470A2070470B2070470C20F2 -:1038500070470D20704700002DE9F843078C04469F -:10386000072F1ED900254FF6FF73D0E90298C5F146 -:103870002006A5F1200029FA05F1083508FA06F618 -:1038800028FA00F0314301431846C9B2FFF762FF3E -:10389000402D0346EBD13A46E169BDE8F843FFF716 -:1038A00069BF4FF6FF70BDE8F883000010B54B68A4 -:1038B00023B9CA8A63F30902CA8210BD04691A686F -:1038C0001C600361C38A013BC3824A60EFE70000CA -:1038D0002DE9F84F1D46CB8A0F468146C3F30901F7 -:1038E000924605290B4630D00020AAB207F11A04EF -:1038F0009EB21FFA80F8042E0FD8904503F1010301 -:1039000006D30A44FB8A62F309030120FB821AE012 -:103910001AF800600130E654EAE79045F1D2A1F1CF -:10392000050B1C237C68BBFBF3F203FB12BB1FFAE5 -:103930008BF6002C45D14846FFF728FF044638B9DE -:1039400078606FF00200BDE8F88F4FF00008E6E7FE -:10395000002606607860ADB24FF0000B454510D9E7 -:103960000AEB0803221D13F8011B08F10108915509 -:10397000B1B21FFA88F81B292BD0454506F1010684 -:10398000F1D8FB8AC3F30902154465F30903BCE7C8 -:1039900001321C4692B22368002BF9D16B1F0B44F5 -:1039A0001C21B3FBF1F301339BB29A42D3D2BBF19A -:1039B000000FD0D14846FFF7E9FE20B9C4F800B0A7 -:1039C000BFE70122E7E7C0F800B05E46206004468A -:1039D000C1E74545D5D94846FFF7D8FE08B920606C -:1039E000AFE7C0F800B0002620600446B6E700004C -:1039F0002DE9F04F1C46074688462DED028B83B01B -:103A00005B690192002B00F09A80238C2BB1E26954 -:103A1000002A00F09480072B35D807F10C00FFF73F -:103A2000B5FE054638B96FF00205284603B0BDEC77 -:103A3000028BBDE8F08F14220021FEF74BF9228C97 -:103A4000E16905F10800FEF71FF9208C48F00041FC -:103A5000013080B2FFF7E4FEFFF7C6FE013880B206 -:103A600020840130287438466369228C1B782A44EC -:103A700003F01F0363F03F03137269602946FFF7E9 -:103A8000EFFD0125D1E74FF0000900F10C034FF0E5 -:103A9000800A4E464D4608EE103A18EE100AFFF71F -:103AA00075FE83460028BED014220021FEF712F9CD -:103AB000002E3AD1019B0222ABF808300BF1080E20 -:103AC0001FFA82FC218C0CF10100BCF1060F80B2C0 -:103AD00001D88E422BD3FFF7A3FE8E4208BF4FF0D2 -:103AE000400AFFF781FE62690138013512781BFA3E -:103AF00080F1013002F01F022DB242EA491289F032 -:103B000001094AEA020A48F0004281F808A0594631 -:103B10008BF810003846CBF804204FF0000AFFF76E -:103B20009FFD238CB342B8D17FE70022C6E7E1694D -:103B3000895D01360EF80210B6B20132C0E76FF0AF -:103B4000010572E7F8B515460E46302200210446FD -:103B50001F46FEF7BFF8069BB5F5001FA760636020 -:103B600004F11000079B34BF6A094FF6FF72E6614B -:103B7000A362002397B29A4206D800230360A7826B -:103B8000E3822383E360F8BD0660013330462036CC -:103B9000F1E7000003781BB94BB2002BC8BF0170DE -:103BA0007047000000787047F8B50C46C9690746B1 -:103BB00011B9238C002B37D1257E1F2D34D83878AE -:103BC00028BB228C072A2CD8268A36F003032BD157 -:103BD0004FF6FF70FFF7CEFD20F0010031024FF6E7 -:103BE000FF72400441EA0561400C41EA402523464A -:103BF00029463846FFF7FCFE002807DD6269137886 -:103C00000133DBB21F2B88BF00231370F8BD218A5C -:103C10002D0645EA012505432046FFF71DFE024615 -:103C2000E5E76FF00300F1E76FF00100EEE7000059 -:103C300070B58AB0044616460021282268461D4603 -:103C4000FEF748F8BDF8383069462046ADF8103028 -:103C50000F9B05939DF840308DF81830119B07930A -:103C6000BDF84830CDE90265ADF82030FFF79CFF84 -:103C70000AB070BD2DE9F041D36905460C461646E1 -:103C80000BB9138C5BBB377E1F2F28D895F80080AB -:103C9000B8F1000F26D03046FFF7DEFD3378210261 -:103CA0000246284641EAC331338A41EA080141EA23 -:103CB000076141EA0341334641F08001FFF798FE76 -:103CC00000280ADD3378012B07D17269137801339C -:103CD000DBB21F2B88BF00231370BDE8F0816FF0AB -:103CE0000100FAE76FF00300F7E70000F0B58BB0D2 -:103CF00004460D4617460021282268461E46FDF759 -:103D0000E9FF9DF84C30294620465A1E5342534144 -:103D10006A468DF800309DF84030ADF81030119BA8 -:103D200005939DF848308DF81830149B0793BDF823 -:103D30005430CDE90276ADF82030FFF79BFF0BB091 -:103D4000F0BD0000406A00B104307047436A1A6851 -:103D5000426202691A600361C38A013BC3827047F1 -:103D60002DE9F041D0F8208014461D46184E4146FA -:103D7000002709B9BDE8F081D1E90223A21A65EB59 -:103D80000303964277EB03031ED2036A8B420DD1E5 -:103D9000FFF78CFD036A1B68036203690B60C38A2B -:103DA0000161013B016AC3828846E2E7FFF77EFDBD -:103DB0000B68C8F8003003690B60C38A0161013BDE -:103DC000C382D8F80010D4E788460968D1E700BF5D -:103DD00080841E002DE9F04F8BB00D4614469B46A3 -:103DE000DDF850908046002800F01881B9F1000FEE -:103DF00000F01481531E3F2B00F21081012A03D1E1 -:103E0000BBF1000F40F00A810023CDE90833B8F878 -:103E10001430B5EBC30F4FEAC30703D300200BB038 -:103E2000BDE8F08F2B199F42D8F80C3036BF7F1BAE -:103E30002746FFB21BB9D8F81030002B7AD0272DB7 -:103E40004DD8C5F1280600232946B742009308AB98 -:103E5000D8F808002CBFF6B23E46A7EB060A354458 -:103E600032465FFA8AFAFFF73DFCB8F81430282191 -:103E700003F10053053BDB000493D8F80C300393A7 -:103E8000039B13B1BAF1000F2CD1D8F8100040B148 -:103E9000BAF1000F05D008AB5246691A0096FFF739 -:103EA00021FC38B2002FB9D066070AD00AAB6242B3 -:103EB00003EBD40102F0070211F8083C134101F8AA -:103EC000083C082C3DD9102C40F2B580202C40F243 -:103ED000B780BBF1000F00F09C80082335E0BA46A4 -:103EE0000026C2E7049BE02B28BFE02306930B4487 -:103EF000AB42059315D95A1B0398691A009692454F -:103F000008AB00F1040034BF5246D2B20792FFF76B -:103F1000E9FB079A1644AAEB020A1544F6B25FFAC7 -:103F20008AFA049B069A05999B1A0493039B1B68C3 -:103F30000393A5E700933A4608AB2946D8F8080052 -:103F4000ADE7BBF1000F13D00123B4EBC30F6BD06F -:103F5000082C12D89DF82030621E23FA02F2D507F1 -:103F600006D54FF0FF3202FA04F423438DF82030D7 -:103F70009DF8203089F8003051E7102C12D8BDF898 -:103F80002030621E23FA02F2D10706D54FF0FF322D -:103F900002FA04F42343ADF82030BDF82030A9F82C -:103FA00000303CE7202C0FD80899631E21FA03F358 -:103FB000DA0705D54FF0FF3202FA04F40C430894F7 -:103FC000089BC9F800302AE7402C2AD0611EC4F1B2 -:103FD0002102A4F12103DDE9086526FA01F105FAC1 -:103FE00002F225FA03F311431943CB0711D501223D -:103FF000A4F12003C4F1200102FA03F322FA01F133 -:10400000A2400B43524263EB430332432B43CDE9BF -:104010000823DDE90823C9E9002300E76FF0010068 -:10402000FDE66FF00800FAE6082CA1D9102CB4D9EF -:10403000202CEED8C4E7BBF1000FAED0022384E7FA -:10404000BBF1000FBCD004237FE70000012A30B58C -:10405000144638BF012485B00025402C28BF4024D9 -:10406000012ACDE9025518D81B788DF8083063076E -:104070000AD004AB624203EBD40502F0070215F844 -:10408000083C934005F8083C034600912246002175 -:1040900002A8FFF727FB05B030BD082AE4D9102A93 -:1040A00003D81B88ADF80830E1E7202A95BF1B68CC -:1040B000D3E900230293CDE90223D8E710B5CB68FA -:1040C0001BB98B600B618B8210BD04691A681C6080 -:1040D0000361C38A013BC382CA60F0E703064CBF99 -:1040E000C0F3C0300220704708B50246FFF7F6FF64 -:1040F000022806D15306C2F30F2001D100F00300BD -:1041000008BDC2F30740FBE72DE9F04F93B004462A -:104110000D46CDE903230A681046FFF7DFFF0228AA -:10412000824614BFC2F306260026002A80F2F381DD -:1041300012F0C04940F0EF81097B002900F0EB81CB -:10414000022803D02378B34240F0E881C2F304632D -:1041500010462944069302F07F030593FFF7C4FF3E -:10416000059B002283464FEA8348002348EA0A4819 -:1041700048EA4668CE78CDE90823F30948EA000802 -:10418000029368D0059B024608A920460093534637 -:104190006768B847002800F0C481276A4FB94146D4 -:1041A00004F10C00FFF700FB074690B96FF0020026 -:1041B00055E03B6998450DD03F68002FF9D1414645 -:1041C00004F10C00FFF7F0FA07460028EED0236A4E -:1041D0003B60276297F817C006F01F08CCF3840CE9 -:1041E000ACEB0800A8EB0C031FFA80FE0028B8BF58 -:1041F0000EF120001FFA83FEB8BF00B2002B079318 -:10420000B8BF0EF12003D7E90221BCBF1BB2079350 -:1042100052EA010338D0039B4FF0000CDFF820E393 -:104220009A1A049B63EB010196457CEB01032BD3A7 -:104230006B7B97F81AE0734519D1029B002B78D05D -:10424000012821DC7868F8B9DFF8F0C2944570EBFA -:10425000010316D337E0276A27B96FF00C0013B0BB -:10426000BDE8F08F3B699845B4D03F68F4E7B348A8 -:1042700090427CEB010301D30020F0E7029B002B6E -:10428000FAD0079B0F2B17DCFA7DB3003946204686 -:1042900002F0030203F07C031343FB75FFF706FBF8 -:1042A0006B7BBB76029B3BB9FB7DC3F3840201327F -:1042B00062F38603FB75D0E76A7BBB7E9A42DBD153 -:1042C000029B002B35D0B309022B32D0039B142262 -:1042D00000210DA8BB60049BFB60FDF7FBFC039B6A -:1042E0000AA920460A93049BADF83EB00B932B1D00 -:1042F0008DF840A00C932B7B8DF84180013BDBB205 -:10430000ADF83C30069B8DF84230059B8DF843306C -:1043100094F82C3083F001038DF84430A36898475B -:10432000FB7DC3F38403013303F01F039B02FB8275 -:10433000A2E7FB7DC6F34012B2EBD31F40F0F4803E -:10434000C3F38403434540F0F280029AB6092B7B05 -:10435000002A4DD0F2075DD4032B40F2EB80039B83 -:10436000AE1D394604F10C00BB603246049BFB6075 -:104370002B7B033BDBB2FFF7ABFA00280CDA3946A4 -:104380002046FFF793FAFB7DC3F38403013303F068 -:104390001F039B02FB8209E7AB88DDE908843B83AE -:1043A0004FF6FF73C9F12000A9F1200228FA09F1A4 -:1043B00009F1080904FA00F024FA02F20143184650 -:1043C0001143C9B2FFF7C6F9B9F1400F0346E9D16D -:1043D000B88231462A7B033AD2B2FFF7CBF9FB7D94 -:1043E000B882DA43C2F3C01262F3C713FB7543E726 -:1043F00086B92E1D013B394604F10C00DBB2324672 -:10440000FFF766FA0028BADB2A7B3146B88A013A00 -:10441000D2B2E2E7F98A013BC1F30901DAB2042919 -:104420005BD8281D002307F11B069A4208D910F813 -:1044300001CB013306F801C00131DBB20529F4D10B -:10444000039993420A9138BF043304992CBF002387 -:1044500055FA83F30B9107F11B010C9179680E93C8 -:104460000D91291DFB8AADF83EB0C3F309038DF809 -:1044700040A08DF841801A44069B8DF84230059B80 -:10448000ADF83C208DF8433094F82C3083F00103D4 -:104490008DF844300023B88A7B602A7B013AFFF70D -:1044A00069F93B8BB882834203D1A3680AA92046ED -:1044B000984720460AA9FFF701FEFB7DBA8AC3F39D -:1044C0008403013303F01F039B02FB823B8B9A4260 -:1044D0000CBF00206FF01000C1E67B68002BAFD04E -:1044E000052001E01C3033461E68002EFAD1091A5F -:1044F0002E1D081D184401EB090C5FFA89F3BCF16D -:104500001B0F9DD89A429BD916F8013B09F101096E -:1045100000F8013BEFE76FF00900A0E66FF00A003A -:104520009DE66FF00B009AE66FF00D0097E66FF0D6 -:104530000E0094E66FF00F0091E600BF40420F00BE -:1045400080841E00EFF30983054968334A6B22F02B -:1045500001024A6383F30988002383F311887047BB -:1045600000EF00E0302080F3118862B60D4B0E4A58 -:10457000D96821F4E0610904090C0A430B49DA60A7 -:10458000D3F8FC2042F08072C3F8FC20084AC2F83D -:10459000B01F116841F0010111602022DA7783F821 -:1045A0002200704700ED00E00003FA0555CEACC5CF -:1045B000001000E0302310B583F311880E4B5B68C8 -:1045C00013F4006314D0F1EE103AEFF309844FF0C6 -:1045D0008073683CE361094BDB6B236684F30988D5 -:1045E00000F0A8FF10B1064BA36110BD054BFBE71F -:1045F00083F31188F9E700BF00ED00E000EF00E071 -:104600004307000846070008026843681143016039 -:1046100003B1184770470000024A136843F0C00313 -:10462000136070470078004013B50E4C204600F030 -:10463000A7FA04F1140000234FF400720A49009411 -:1046400000F064F9094B4FF40072094904F1380095 -:10465000009400F0DDF9074A074BC4E9172302B0C4 -:1046600010BD00BF34630020A0630020194600087D -:10467000A06500200078004000E1F505037C30B51E -:10468000244C002918BF0C46012B11D1224B984213 -:104690000ED1224BD3F8E82042F08042C3F8E82044 -:1046A000D3F8102142F08042C3F81021D3F8103122 -:1046B0002268036EC16D03EB52038466B3FBF2F311 -:1046C0006268150442BF23F0070503F0070343EABD -:1046D0004503CB60A36843F040034B60E36843F0BD -:1046E00001038B6042F4967343F001030B604FF0BB -:1046F000FF330B62510505D512F0102205D0B2F13F -:10470000805F04D080F8643030BD7F23FAE73F2318 -:10471000F8E700BF847900083463002000440258A1 -:104720002DE9F047C66D05463768F4692107346204 -:104730001AD014F0080118BF4FF48071E20748BF87 -:1047400041F02001A3074FF0300348BF41F0400182 -:10475000600748BF41F0800183F31188281DFFF7EF -:1047600053FF002383F31188E2050AD5302383F336 -:1047700011884FF48061281DFFF746FF002383F363 -:1047800011884FF030094FF0000A14F0200838D19A -:104790003B0616D54FF0300905F1380A200610D532 -:1047A00089F31188504600F067F9002836DA0821AD -:1047B000281DFFF729FF27F080033360002383F3D0 -:1047C0001188790614D5620612D5302383F3118837 -:1047D000D5E913239A4208D12B6C33B127F0400757 -:1047E0001021281DFFF710FF3760002383F3118885 -:1047F000E30618D5AA6E1369ABB15069BDE8F0475E -:10480000184789F31188736A284695F8641019408F -:1048100000F0D0F98AF31188F469B6E7B06288F342 -:104820001188F469BAE7BDE8F0870000090100F1DA -:104830006043012203F56143C9B283F8001300F01D -:104840001F039A4043099B0003F1604303F5614352 -:10485000C3F880211A607047F8B51546826804468F -:104860000B46AA4200D28568A1692669761AB5422C -:104870000BD218462A46FDF707FAA3692B44A36119 -:104880002846A3685B1BA360F8BD0CD9AF1B184674 -:104890003246FDF7F9F93A46E1683044FDF7F4F99C -:1048A000E3683B44EBE718462A46FDF7EDF9E36879 -:1048B000E5E7000083689342F7B50446154600D249 -:1048C0008568D4E90460361AB5420BD22A46FDF752 -:1048D000DBF963692B4463612846A3685B1BA36013 -:1048E00003B0F0BD0DD93246AF1B0191FDF7CCF9F5 -:1048F00001993A46E0683144FDF7C6F9E3683B4464 -:10490000E9E72A46FDF7C0F9E368E4E710B50A4491 -:104910000024C361029B8460C16002610362C0E93C -:104920000000C0E9051110BD08B5D0E90532934279 -:1049300001D1826882B98268013282605A1C426168 -:1049400019700021D0E904329A4224BFC368436140 -:1049500000F0C2FE002008BD4FF0FF30FBE7000072 -:1049600070B5302304460E4683F31188A568A5B1BF -:10497000A368A269013BA360531CA3611578226957 -:10498000934224BFE368A361E3690BB120469847D3 -:10499000002383F31188284607E03146204600F0C3 -:1049A0008BFE0028E2DA85F3118870BD2DE9F74F00 -:1049B00004460E4617469846D0F81C904FF0300A31 -:1049C0008AF311884FF0000B154665B12A4631462F -:1049D0002046FFF741FF034660B94146204600F0FC -:1049E0006BFE0028F1D0002383F31188781B03B0FD -:1049F000BDE8F08FB9F1000F03D001902046C84701 -:104A0000019B8BF31188ED1A1E448AF31188DCE7B1 -:104A1000C160C361009B82600362C0E9051111445B -:104A2000C0E9000001617047F8B504460D4616461E -:104A3000302383F31188A768A7B1A368013BA36063 -:104A400063695A1C62611D70D4E904329A4224BF22 -:104A5000E3686361E3690BB120469847002080F367 -:104A6000118807E03146204600F026FE0028E2DAF1 -:104A700087F31188F8BD0000D0E9052310B59A42EC -:104A800001D182687AB982680021013282605A1CA1 -:104A900082611C7803699A4224BFC368836100F075 -:104AA0001BFE204610BD4FF0FF30FBE72DE9F74F0E -:104AB00004460E4617469846D0F81C904FF0300A30 -:104AC0008AF311884FF0000B154665B12A4631462E -:104AD0002046FFF7EFFE034660B94146204600F04E -:104AE000EBFD0028F1D0002383F31188781B03B07D -:104AF000BDE8F08FB9F1000F03D001902046C84700 -:104B0000019B8BF31188ED1A1E448AF31188DCE7B0 -:104B1000026843681143016003B118477047000001 -:104B20001430FFF743BF00004FF0FF331430FFF79E -:104B30003DBF00003830FFF7B9BF00004FF0FF3332 -:104B40003830FFF7B3BF00001430FFF709BF000093 -:104B50004FF0FF311430FFF703BF00003830FFF78C -:104B600063BF00004FF0FF323830FFF75DBF000039 -:104B7000012914BF6FF0130000207047FFF754BDE8 -:104B8000044B036000234360C0E902330123037434 -:104B9000704700BF9C79000810B53023044683F3AA -:104BA0001188FFF76BFD02230020237480F3118826 -:104BB00010BD000038B5C36904460D461BB9042179 -:104BC0000844FFF7A5FF294604F11400FFF7ACFEE7 -:104BD000002806DA201D4FF40061BDE83840FFF7D9 -:104BE00097BF38BD026843681143016003B118479D -:104BF0007047000013B5406B00F58054D4F8A4381A -:104C00001A681178042914D1017C022911D119796B -:104C1000012312898B4013420BD101A94C3002F0C1 -:104C200017F9D4F8A4480246019B2179206800F0C6 -:104C3000DFF902B010BD0000143002F099B8000096 -:104C40004FF0FF33143002F093B800004C3002F004 -:104C50006BB900004FF0FF334C3002F065B9000033 -:104C6000143002F067B800004FF0FF31143002F04A -:104C700061B800004C3002F037B900004FF0FF324D -:104C80004C3002F031B900000020704710B500F53B -:104C90008054D4F8A4381A681178042917D1017CFB -:104CA000022914D15979012352898B4013420ED124 -:104CB000143001F0F9FF024648B1D4F8A4484FF48B -:104CC000407361792068BDE8104000F07FB910BDE5 -:104CD000406BFFF7DBBF0000704700007FB5124B51 -:104CE00001250426044603600023057400F18402B4 -:104CF00043602946C0E902330C4B02901430019303 -:104D00004FF44073009601F0ABFF094B04F6944258 -:104D1000294604F14C000294CDE900634FF440733E -:104D200002F072F804B070BDC4790008D14C0008DC -:104D3000F54B00080A68302383F311880B790B3395 -:104D400042F823004B79133342F823008B7913B1D7 -:104D50000B3342F8230000F58053C3F8A418022354 -:104D60000374002080F311887047000038B5037F7A -:104D7000044613B190F85430ABB90125201D02212F -:104D8000FFF730FF04F114006FF00101257700F008 -:104D9000AFFC04F14C0084F854506FF00101BDE801 -:104DA000384000F0A5BC38BD10B5012104460430E0 -:104DB000FFF718FF0023237784F8543010BD00005C -:104DC00038B504460025143001F062FF04F14C00B0 -:104DD000257702F031F8201D84F854500121FFF7A7 -:104DE00001FF2046BDE83840FFF750BF90F8803003 -:104DF00003F06003202B06D190F881200023212AA4 -:104E000003D81F2A06D800207047222AFBD1C0E908 -:104E10001D3303E0034A426707228267C36701200C -:104E2000704700BF3C22002037B500F58055D5F80B -:104E3000A4381A68117804291AD1017C022917D1E3 -:104E40001979012312898B40134211D100F14C04CE -:104E5000204602F0B1F858B101A9204601F0F8FF50 -:104E6000D5F8A4480246019B2179206800F0C0F8DB -:104E700003B030BD01F10B03F0B550F8236085B0ED -:104E800004460D46FEB1302383F3118804EB8507F9 -:104E9000301D0821FFF7A6FEFB6806F14C005B6998 -:104EA0001B681BB1019001F0E1FF019803A901F01B -:104EB000CFFF024648B1039B2946204600F098F8F0 -:104EC000002383F3118805B0F0BDFB685A691268AE -:104ED000002AF5D01B8A013B1340F1D104F1800276 -:104EE000EAE70000133138B550F82140ECB1302327 -:104EF00083F3118804F58053D3F8A42813685279FA -:104F000003EB8203DB689B695D6845B1042160188F -:104F1000FFF768FE294604F1140001F0CFFE204699 -:104F2000FFF7B4FE002383F3118838BD70470000FB -:104F300001F09CB901234022002110B5044600F87D -:104F4000303BFCF7C7FE0023C4E9013310BD00006D -:104F500010B53023044683F31188242241600021D8 -:104F60000C30FCF7B7FE204601F0A2F90223002026 -:104F7000237080F3118810BD70B500EB81030546E6 -:104F800050690E461446DA6018B110220021FCF771 -:104F9000A1FEA06918B110220021FCF79BFE31464A -:104FA0002846BDE8704001F089BA000083682022DD -:104FB000002103F0011310B5044683601030FCF7A4 -:104FC00089FE2046BDE8104001F004BBF0B4012585 -:104FD00000EB810447898D40E4683D43A469458125 -:104FE00023600023A2606360F0BC01F021BB0000DD -:104FF000F0B4012500EB810407898D40E4683D434E -:105000006469058123600023A2606360F0BC01F045 -:1050100097BB000070B502230025044624220370CC -:105020002946C0F888500C3040F8045CFCF752FE6A -:10503000204684F8705001F0D5F963681B6823B1ED -:1050400029462046BDE87040184770BD0378052BFF -:1050500010B504460AD080F88C30052303704368ED -:105060001B680BB1042198470023A36010BD00000A -:105070000178052906D190F88C20436802701B68DE -:1050800003B118477047000070B590F870300446BF -:1050900013B1002380F8703004F18002204601F043 -:1050A000BDFA63689B68B3B994F8803013F060056B -:1050B00035D00021204601F0AFFD0021204601F04F -:1050C0009FFD63681B6813B106212046984706239D -:1050D00084F8703070BD204698470028E4D0B4F8BA -:1050E0008630A26F9A4288BFA36794F98030A56F7B -:1050F000002B4FF0300380F20381002D00F0F2808E -:10510000092284F8702083F3118800212046D4E915 -:105110001D23FFF76DFF002383F31188DAE794F86E -:10512000812003F07F0343EA022340F202329342DC -:1051300000F0C58021D8B3F5807F48D00DD8012B71 -:105140003FD0022B00F09380002BB2D104F18802F3 -:1051500062670222A267E367C1E7B3F5817F00F0CF -:105160009B80B3F5407FA4D194F88230012BA0D16D -:10517000B4F8883043F0020332E0B3F5006F4DD04D -:1051800017D8B3F5A06F31D0A3F5C063012B90D829 -:105190006368204694F882205E6894F88310B4F81F -:1051A0008430B047002884D0436863670368A367EE -:1051B0001AE0B3F5106F36D040F6024293427FF406 -:1051C00078AF5C4B63670223A3670023C3E794F8BF -:1051D0008230012B7FF46DAFB4F8883023F00203E6 -:1051E000A4F88830C4E91D55E56778E7B4F8803045 -:1051F000B3F5A06F0ED194F88230204684F88A303F -:1052000001F04EF963681B6813B1012120469847ED -:10521000032323700023C4E91D339CE704F18B03AF -:1052200063670123C3E72378042B10D1302383F372 -:1052300011882046FFF7BAFE85F3118803216368C1 -:1052400084F88B5021701B680BB12046984794F866 -:105250008230002BDED084F88B3004232370636807 -:105260001B68002BD6D0022120469847D2E794F83D -:10527000843020461D0603F00F010AD501F0C0F965 -:10528000012804D002287FF414AF2B4B9AE72B4B54 -:1052900098E701F0A7F9F3E794F88230002B7FF448 -:1052A00008AF94F8843013F00F01B3D01A062046EB -:1052B00002D501F0C9FCADE701F0BAFCAAE794F809 -:1052C0008230002B7FF4F5AE94F8843013F00F0198 -:1052D000A0D01B06204602D501F09EFC9AE701F003 -:1052E0008FFC97E7142284F8702083F311882B46F3 -:1052F0002A4629462046FFF769FE85F31188E9E62C -:105300005DB1152284F8702083F3118800212046B6 -:10531000D4E91D23FFF75AFEFDE60B2284F8702026 -:1053200083F311882B462A4629462046FFF760FE64 -:10533000E3E700BFF4790008EC790008F079000891 -:1053400038B590F870300446002B3ED0063BDAB2F8 -:105350000F2A34D80F2B32D8DFE803F03731310869 -:10536000223231313131313131313737856FB0F857 -:1053700086309D4214D2C3681B8AB5FBF3F203FB4F -:1053800012556DB9302383F311882B462A462946DE -:10539000FFF72EFE85F311880A2384F870300EE0A3 -:1053A000142384F87030302383F3118800232046BF -:1053B0001A461946FFF70AFE002383F3118838BD09 -:1053C000C36F03B198470023E7E70021204601F0AF -:1053D00023FC0021204601F013FC63681B6813B115 -:1053E0000621204698470623D7E7000010B590F81D -:1053F00070300446142B29D017D8062B05D001D8BD -:105400001BB110BD093B022BFBD80021204601F047 -:1054100003FC0021204601F0F3FB63681B6813B115 -:10542000062120469847062319E0152BE9D10B23C6 -:1054300080F87030302383F3118800231A46194610 -:10544000FFF7D6FD002383F31188DAE7C3689B6971 -:105450005B68002BD5D1C36F03B19847002384F854 -:105460007030CEE700238268037503691B68996872 -:105470009142FBD25A6803604260106058607047E6 -:1054800000238268037503691B6899689142FBD801 -:105490005A680360426010605860704708B508465B -:1054A000302383F311880B7D032B05D0042B0DD003 -:1054B0002BB983F3118808BD8B6900221A604FF065 -:1054C000FF338361FFF7CEFF0023F2E7D1E900321B -:1054D00013605A60F3E70000FFF7C4BF054BD968BB -:1054E00008751868026853601A600122D860027556 -:1054F000FBF712B9A06700200C4B30B5DD684B1CE0 -:1055000087B004460FD02B46094A684600F084F95C -:105510002046FFF7E3FF009B13B1684600F086F9D1 -:10552000A86907B030BDFFF7D9FFF9E7A0670020F1 -:105530009D540008044B1A68DB6890689B68984289 -:1055400094BF002001207047A0670020084B10B5D1 -:105550001C68D868226853601A600122DC602275DA -:10556000FFF78EFF01462046BDE81040FBF7D4B898 -:10557000A0670020044B1A68DB6892689B689A4217 -:1055800001D9FFF7E3BF7047A067002038B5074C8B -:1055900001230025064907482370656001F04AFD94 -:1055A0000223237085F3118838BD00BF086A0020EC -:1055B000FC790008A067002008B572B6044B186596 -:1055C00000F06CFC00F03EFD024B03221A70FEE777 -:1055D000A0670020086A002000F05EB9EFF3118098 -:1055E00020B9EFF30583302282F311887047000061 -:1055F00010B530B9EFF30584C4F3080414B180F397 -:10560000118810BDFFF7B6FF84F31188F9E7000099 -:10561000034A516853685B1A9842FBD8704700BF31 -:10562000001000E08B600223086108468B827047FF -:105630008368A3F1840243F8142C026943F8442CD4 -:10564000426943F8402C094A43F8242CC268A3F16C -:10565000200043F8182C022203F80C2C002203F837 -:105660000B2C034A43F8102C704700BF3107000889 -:10567000A067002008B5FFF7DBFFBDE80840FFF793 -:105680002BBF0000024BDB6898610F20FFF726BF9D -:10569000A0670020302383F31188FFF7F3BF0000D9 -:1056A00008B50146302383F311880820FFF724FF53 -:1056B000002383F3118808BD064BDB6839B14268CB -:1056C00018605A60136043600420FFF715BF4FF065 -:1056D000FF307047A06700200368984206D01A6820 -:1056E0000260506018469961FFF7F6BE70470000EF -:1056F00038B504460D462068844200D138BD0368A1 -:1057000023605C608561FFF7E7FEF4E7036810B58E -:105710009C68A2420CD85C688A600B604C60216077 -:10572000596099688A1A9A604FF0FF33836010BD00 -:10573000121B1B68ECE700000A2938BF0A2170B56C -:1057400004460D460A26601901F06CFC01F054FC79 -:10575000041BA54203D8751C04462E46F3E70A2E07 -:1057600004D90120BDE8704001F0A4BC70BD000068 -:10577000F8B5144B0D460A2A4FF00A07D96103F118 -:105780001001826038BF0A22416019691446016025 -:1057900048601861A81801F035FC01F02DFC431B8E -:1057A0000646A34206D37C1C28192746354601F03D -:1057B00039FCF2E70A2F04D90120BDE8F84001F0D6 -:1057C00079BCF8BDA0670020F8B506460D4601F08B -:1057D00013FC0F4A134653F8107F9F4206D12A4606 -:1057E00001463046BDE8F840FFF7C2BFD169BB684B -:1057F000441A2C1928BF2C46A34202D92946FFF788 -:105800009BFF224631460348BDE8F840FFF77EBFC4 -:10581000A0670020B0670020C0E90323002310B474 -:105820005DF8044B4361FFF7CFBF000010B5194C82 -:10583000236998420DD08168D0E9003213605A6024 -:105840009A680A449A60002303604FF0FF33A36113 -:1058500010BD0268234643F8102F536000220260F7 -:1058600022699A4203D1BDE8104001F0D5BB93688C -:1058700081680B44936001F0BFFB2269E169926883 -:10588000441AA242E4D91144BDE81040091AFFF7B6 -:1058900053BF00BFA06700202DE9F047DFF8BC80B0 -:1058A00008F110072C4ED8F8105001F0A5FBD8F8DD -:1058B0001C40AA68031B9A423ED814444FF00009CA -:1058C000D5E90032C8F81C4013605A60C5F8009052 -:1058D000D8F81030B34201D101F09EFB89F3118852 -:1058E000D5E9033128469847302383F311886B6943 -:1058F000002BD8D001F080FB6A69A0EB0409824636 -:105900004A450DD2022001F0D5FB0022D8F8103014 -:10591000B34208D151462846BDE8F047FFF728BFFB -:10592000121A2244F2E712EB09092946384638BF19 -:105930004A46FFF7EBFEB5E7D8F81030B34208D07F -:105940001444C8F81C00211AA960BDE8F047FFF70D -:10595000F3BEBDE8F08700BFB0670020A06700205D -:1059600000207047FEE70000704700004FF0FF3056 -:105970007047000002290CD0032904D001290748F0 -:1059800018BF00207047032A05D8054800EBC20065 -:105990007047044870470020704700BFD47A000861 -:1059A0004C220020887A000870B59AB00546084657 -:1059B000144601A900F0C2F801A8FCF783F9431CC2 -:1059C0000022C6B25B001046C5E9003423700323F1 -:1059D000023404F8013C01ABD1B202348E4201D84A -:1059E0001AB070BD13F8011B013204F8010C04F861 -:1059F000021CF1E708B5302383F311880348FFF751 -:105A000013FA002383F3118808BD00BF106A002039 -:105A100090F8803003F01F02012A07D190F881200E -:105A20000B2A03D10023C0E91D3315E003F0600306 -:105A3000202B08D1B0F884302BB990F88120212A8E -:105A400003D81F2A04D8FFF7D1B9222AEBD0FAE7EE -:105A5000034A426707228267C3670120704700BF7D -:105A60004322002007B5052917D8DFE801F01916F1 -:105A700003191920302383F31188104A0121019062 -:105A8000FFF77AFA019802210D4AFFF775FA0D48DF -:105A9000FFF796F9002383F3118803B05DF804FB48 -:105AA000302383F311880748FFF760F9F2E73023CA -:105AB00083F311880348FFF777F9EBE7287A0008AA -:105AC0004C7A0008106A002038B50C4D0C4C2A4660 -:105AD0000C4904F10800FFF767FF05F1CA0204F161 -:105AE00010000949FFF760FF05F5CA7204F11800BC -:105AF0000649BDE83840FFF757BF00BFE8820020E5 -:105B00004C220020087A0008127A00081D7A00084A -:105B100070B5044608460D46FCF7D4F8C6B22046D8 -:105B2000013403780BB9184670BD32462946FCF79C -:105B3000B5F80028F3D10120F6E700002DE9F04781 -:105B400005460C46FCF7BEF82B49C6B22846FFF7BF -:105B5000DFFF08B10A36F6B228492846FFF7D8FF1A -:105B600008B11036F6B2632E0BD8DFF88C80DFF860 -:105B70008C90234FDFF894A02E7846B92670BDE8AC -:105B8000F08729462046BDE8F04701F073BE252E78 -:105B90002ED1072241462846FCF780F870B9194BF0 -:105BA000224603F1100153F8040B8B4242F8040B18 -:105BB000F9D11B78073511341370DDE70822494607 -:105BC0002846FCF76BF898B9A21C0F4B19780232E3 -:105BD0000909C95D02F8041C13F8011B01F00F014B -:105BE0005345C95D02F8031CF0D118340835C3E7EA -:105BF000013504F8016BBFE7F47A00081D7A00084C -:105C0000FC7A00089278000800E8F11F0CE8F11F08 -:105C1000BFF34F8F044B1A695107FCD1D3F8102101 -:105C20005207F8D1704700BF0020005208B50D4B55 -:105C30001B78ABB9FFF7ECFF0B4BDA68D10704D543 -:105C40000A4A5A6002F188325A60D3F80C21D2070E -:105C500006D5064AC3F8042102F18832C3F80421AC -:105C600008BD00BF46850020002000522301674583 -:105C700008B5114B1B78F3B9104B1A69510703D5BE -:105C8000DA6842F04002DA60D3F81021520705D5F5 -:105C9000D3F80C2142F04002C3F80C21FFF7B8FF03 -:105CA000064BDA6842F00102DA60D3F80C2142F0C8 -:105CB0000102C3F80C2108BD4685002000200052D7 -:105CC0000F289ABF00F58060400400207047000054 -:105CD0004FF4003070470000102070470F2808B5BF -:105CE0000BD8FFF7EDFF00F500330268013204D155 -:105CF00004308342F9D1012008BD0020FCE70000F8 -:105D00000F2838B505463FD8FFF782FF1F4CFFF735 -:105D10008DFF4FF0FF3307286361C4F814311DD89D -:105D20002361FFF775FF030243F02403E360E36898 -:105D300043F08003E36023695A07FCD42846FFF749 -:105D400067FFFFF7BDFF4FF4003100F057F9284619 -:105D5000FFF78EFFBDE83840FFF7C0BFC4F8103131 -:105D6000FFF756FFA0F108031B0243F02403C4F819 -:105D70000C31D4F80C3143F08003C4F80C31D4F862 -:105D800010315B07FBD4D9E7002038BD002000525A -:105D90002DE9F84F05460C46104645EA0203DE069B -:105DA00002D00020BDE8F88F20F01F00DFF8BCB063 -:105DB000DFF8BCA0FFF73AFF04EB0008444503D12D -:105DC0000120FFF755FFEDE720222946204601F08C -:105DD0001FFD10B920352034F0E72B4605F12002D5 -:105DE0001F68791CDDD104339A42F9D105F178435B -:105DF0001B481C4EB3F5801F1B4B38BF184603F1E0 -:105E0000F80332BFD946D1461E46FFF701FF0760AF -:105E1000A5EB040C336804F11C0143F0020333606A -:105E2000231FD9F8007017F00507FAD153F8042F93 -:105E30008B424CF80320F4D1BFF34F8FFFF7E8FEFD -:105E40004FF0FF332022214603602846336823F0B9 -:105E50000203336001F0DCFC0028BBD03846B0E719 -:105E6000142100520C200052142000521020005225 -:105E70001021005210B5084C237828B11BB9FFF748 -:105E8000D5FE0123237010BD002BFCD02070BDE88F -:105E90001040FFF7EDBE00BF4685002038B5054D28 -:105EA00000240334696855F80C0B00F0B9F8122C83 -:105EB000F7D138BD107B0008084601F0A1BC0000F6 -:105EC00070B5104E82B0FFF789FB054601F094F8DB -:105ED000326803469042336037BF0B4A0A49516823 -:105EE000146836BF0131D1E90041516004192846D8 -:105EF00041F100010191FFF77BFB2046019902B0BF -:105F000070BD00BF488500205085002070B5124E3E -:105F100082B0FFF763FB054601F06EF83268034676 -:105F20009042336037BF0D4A0C495168146836BF40 -:105F30000131D1E9004151600419284641F10001C5 -:105F40000191FFF755FB4FF47A7200232046019927 -:105F5000FAF7CEF902B070BD4885002050850020C8 -:105F60000244074BD2B210B5904200D110BD441C80 -:105F700000B253F8200041F8040BE0B2F4E700BF90 -:105F8000504000580E4B30B51C6F240405D41C6FD4 -:105F90001C671C6F44F400441C670A4C02442368CD -:105FA000D2B243F480732360074B904200D130BDDE -:105FB000441C51F8045B00B243F82050E0B2F4E70F -:105FC00000440258004802585040005807B50122CA -:105FD00001A90020FFF7C4FF019803B05DF804FB9E -:105FE00013B50446FFF7F2FFA04205D0012201A934 -:105FF00000200194FFF7C6FF02B010BD0144BFF3BB -:106000004F8F064B884204D3BFF34F8FBFF36F8F80 -:106010007047C3F85C022030F4E700BF00ED00E0F9 -:106020000144BFF34F8F064B884204D3BFF34F8F19 -:10603000BFF36F8F7047C3F870022030F4E700BFE2 -:1060400000ED00E070470000074B45F255521A6022 -:1060500002225A6040F6FF729A604CF6CC421A60F7 -:106060000122024B1A707047004800585C850020DE -:10607000034B1B781BB1034B4AF6AA221A607047E8 -:106080005C85002000480058034B1A681AB9034A7F -:10609000D2F8D0241A60704758850020004002587A -:1060A000024B4FF48032C3F8D024704700400258AE -:1060B00008B5FFF7E9FF024B1868C0F3806008BD20 -:1060C0005885002070B5BFF34F8FBFF36F8F1A4A0A -:1060D0000021C2F85012BFF34F8FBFF36F8F536987 -:1060E00043F400335361BFF34F8FBFF36F8FC2F898 -:1060F0008410BFF34F8FD2F8803043F6E074C3F3BF -:10610000C900C3F34E335B0103EA0406014646EAC5 -:1061100081750139C2F86052F9D2203B13F1200F8A -:10612000F2D1BFF34F8F536943F480335361BFF310 -:106130004F8FBFF36F8F70BD00ED00E0FEE70000F2 -:10614000214B2248224A70B5904237D3214BC11EC1 -:10615000DA1C121A22F003028B4238BF00220021FF -:10616000FBF7B8FD1C4A0023C2F88430BFF34F8F01 -:10617000D2F8803043F6E074C3F3C900C3F34E3362 -:106180005B0103EA0406014646EA81750139C2F85B -:106190006C52F9D2203B13F1200FF2D1BFF34F8F95 -:1061A000BFF36F8FBFF34F8FBFF36F8F0023C2F822 -:1061B0005032BFF34F8FBFF36F8F70BD53F8041B86 -:1061C00040F8041BC0E700BFB07D00083087002006 -:1061D000308700203087002000ED00E0074BD3F827 -:1061E000D81021EA0001C3F8D810D3F8002122EA20 -:1061F0000002C3F80021D3F8003170470044025870 -:1062000070B5D0E9244300224FF0FF359E6804EBBF -:1062100042135101D3F80009002805DAD3F8000928 -:1062200040F08040C3F80009D3F8000B002805DADD -:10623000D3F8000B40F08040C3F8000B0132631824 -:106240009642C3F80859C3F8085BE0D24FF0011337 -:10625000C4F81C3870BD0000890141F020010161C3 -:1062600003699B06FCD41220FFF7D2B910B50A4C83 -:106270002046FEF75FFE094BC4F89030084BC4F887 -:106280009430084C2046FEF755FE074BC4F890307A -:10629000064BC4F8943010BD608500200000084013 -:1062A0007C7B0008FC85002000000440887B0008FF -:1062B00070B503780546012B5CD1434BD0F8904074 -:1062C000984258D1414B0E216520D3F8D82042F096 -:1062D0000062C3F8D820D3F8002142F00062C3F86E -:1062E0000021D3F80021D3F8802042F00062C3F8E7 -:1062F0008020D3F8802022F00062C3F88020D3F8F9 -:106300008030FEF793FA324BE360324BC4F800382A -:106310000023D5F89060C4F8003EC02323604FF4FA -:106320000413A3633369002BFCDA01230C203361CF -:10633000FFF76EF93369DB07FCD41220FFF768F929 -:106340003369002BFCDA00262846A660FFF758FFC9 -:106350006B68C4F81068DB68C4F81468C4F81C687B -:1063600083BB1D4BA3614FF0FF336361A36843F010 -:106370000103A36070BD194B9842C9D1134B4FF074 -:106380008060D3F8D82042F00072C3F8D820D3F848 -:10639000002142F00072C3F80021D3F80021D3F8A5 -:1063A000802042F00072C3F88020D3F8802022F0D1 -:1063B0000072C3F88020D3F88030FFF70FFF0E2162 -:1063C0004D209EE7064BCDE7608500200044025833 -:1063D0004014004003002002003C30C0FC85002037 -:1063E000083C30C0F8B5D0F89040054600214FF089 -:1063F00000662046FFF730FFD5F8941000234FF0D9 -:1064000001128F684FF0FF30C4F83438C4F81C28EC -:1064100004EB431201339F42C2F80069C2F8006BDB -:10642000C2F80809C2F8080BF2D20B68D5F8902020 -:10643000C5F89830636210231361166916F01006D0 -:10644000FBD11220FFF7E4F8D4F8003823F4FE6300 -:10645000C4F80038A36943F4402343F01003A36158 -:106460000923C4F81038C4F814380B4BEB604FF014 -:10647000C043C4F8103B094BC4F8003BC4F8106992 -:10648000C4F80039D5F8983003F1100243F48013B2 -:10649000C5F89820A362F8BD587B00084080001022 -:1064A000D0F8902090F88A10D2F8003823F4FE63D8 -:1064B00043EA0113C2F80038704700002DE9F843A1 -:1064C00000EB8103D0F890500C468046DA680FFA52 -:1064D00081F94801166806F00306731E022B05EBCE -:1064E00041134FF0000194BFB604384EC3F8101B9F -:1064F0004FF0010104F1100398BF06F1805601FA34 -:1065000003F3916998BF06F5004600293AD0578AEF -:1065100004F15801374349016F50D5F81C180B435B -:106520000021C5F81C382B180127C3F81019A74003 -:106530005369611E9BB3138A928B9B08012A88BF03 -:106540005343D8F89820981842EA034301F14002D7 -:106550002146C8F89800284605EB82025360FFF7F1 -:106560007BFE08EB8900C3681B8A43EA84534834E6 -:106570001E4364012E51D5F81C381F43C5F81C7802 -:10658000BDE8F88305EB4917D7F8001B21F400415B -:10659000C7F8001BD5F81C1821EA0303C0E704F173 -:1065A0003F030B4A2846214605EB83035A60FFF759 -:1065B00053FE05EB4910D0F8003923F40043C0F82E -:1065C0000039D5F81C3823EA0707D7E70080001008 -:1065D00000040002D0F894201268C0F89820FFF759 -:1065E0000FBE00005831D0F8903049015B5813F4C9 -:1065F000004004D013F4001F0CBF0220012070479C -:106600004831D0F8903049015B5813F4004004D071 -:1066100013F4001F0CBF02200120704700EB810122 -:10662000CB68196A0B6813604B68536070470000B1 -:1066300000EB810330B5DD68AA691368D36019B92E -:10664000402B84BF402313606B8A1468D0F89020DD -:106650001C4402EB4110013C09B2B4FBF3F4634368 -:10666000033323F0030343EAC44343F0C043C0F8B9 -:10667000103B2B6803F00303012B0ED1D2F808382E -:1066800002EB411013F4807FD0F8003B14BF43F0BD -:10669000805343F00053C0F8003B02EB4112D2F8A4 -:1066A000003B43F00443C2F8003B30BD2DE9F0410C -:1066B000D0F8906005460C4606EB4113D3F8087BF2 -:1066C0003A07C3F8087B08D5D6F814381B0704D559 -:1066D00000EB8103DB685B689847FA071FD5D6F8A3 -:1066E0001438DB071BD505EB8403D968CCB98B695B -:1066F000488A5A68B2FBF0F600FB16228AB918687D -:10670000DA6890420DD2121AC3E90024302383F3D1 -:10671000118821462846FFF78BFF84F31188BDE8D6 -:10672000F081012303FA04F26B8923EA02036B81EF -:10673000CB68002BF3D021462846BDE8F04118472E -:1067400000EB81034A0170B5DD68D0F890306C69C8 -:106750002668E66056BB1A444FF40020C2F81009C0 -:106760002A6802F00302012A0AB20ED1D3F80808FF -:1067700003EB421410F4807FD4F8000914BF40F0FA -:10678000805040F00050C4F8000903EB4212D2F8E8 -:10679000000940F00440C2F800090122D3F834088F -:1067A00002FA01F10143C3F8341870BD19B9402E43 -:1067B00084BF4020206020681A442E8A8419013C3E -:1067C000B4FBF6F440EAC44040F00050C6E70000D5 -:1067D0002DE9F843D0F8906005460C464F0106EBD2 -:1067E0004113D3F8088918F0010FC3F808891CD0A9 -:1067F000D6F81038DB0718D500EB8103D3F80CC0AE -:10680000DCF81430D3F800E0DA68964530D2A2EB19 -:106810000E024FF000091A60C3F80490302383F38E -:106820001188FFF78DFF89F3118818F0800F1DD0B4 -:10683000D6F834380126A640334217D005EB84033E -:106840000134D5F89050D3F80CC0E4B22F44DCF8F2 -:10685000142005EB0434D2F800E05168714514D3DC -:10686000D5F8343823EA0606C5F83468BDE8F8835D -:10687000012303FA01F2038923EA02030381DCF80E -:106880000830002BD1D09847CFE7AEEB0103BCF81E -:106890001000834228BF0346D7F8180980B2B3EB33 -:1068A000800FE3D89068A0F1040959F8048FC4F868 -:1068B0000080A0EB09089844B8F1040FF5D81844FB -:1068C0000B4490605360C8E72DE9F84FD0F8905022 -:1068D00004466E69AB691E4016F480586E6103D0A1 -:1068E000BDE8F84FFEF796BB002E12DAD5F8003E51 -:1068F0009B0705D0D5F8003E23F00303C5F8003E02 -:10690000D5F80438204623F00103C5F80438FEF713 -:10691000AFFB370505D52046FFF772FC2046FEF792 -:1069200095FBB0040CD5D5F8083813F0060FEB68CA -:1069300023F470530CBF43F4105343F4A053EB60A3 -:1069400031071BD56368DB681BB9AB6923F008030B -:10695000AB612378052B0CD1D5F8003E9A0705D002 -:10696000D5F8003E23F00303C5F8003E2046FEF7AD -:106970007FFB6368DB680BB120469847F30200F1A8 -:10698000BA80B70226D5D4F8909000274FF0010ABC -:1069900009EB4712D2F8003B03F44023B3F5802FF4 -:1069A00011D1D2F8003B002B0DDA62890AFA07F305 -:1069B00022EA0303638104EB8703DB68DB6813B11E -:1069C0003946204698470137D4F89430FFB29B6887 -:1069D0009F42DDD9F00619D5D4F89000026AC2F3BF -:1069E0000A1702F00F0302F4F012B2F5802F00F044 -:1069F000CA80B2F5402F09D104EB8303002200F5D1 -:106A00008050DB681B6A974240F0B0803003D5F8B5 -:106A1000185835D5E90303D500212046FFF746FE77 -:106A2000AA0303D501212046FFF740FE6B0303D5DF -:106A300002212046FFF73AFE2F0303D5032120460B -:106A4000FFF734FEE80203D504212046FFF72EFEAF -:106A5000A90203D505212046FFF728FE6A0203D5C7 -:106A600006212046FFF722FE2B0203D507212046F0 -:106A7000FFF71CFEEF0103D508212046FFF716FEA5 -:106A8000700340F1A780E90703D500212046FFF7F6 -:106A90009FFEAA0703D501212046FFF799FE6B0749 -:106AA00003D502212046FFF793FE2F0703D50321CC -:106AB0002046FFF78DFEEE0603D504212046FFF7A2 -:106AC00087FEA80603D505212046FFF781FE69064B -:106AD00003D506212046FFF77BFE2A0603D50721B2 -:106AE0002046FFF775FEEB0574D520460821BDE86A -:106AF000F84FFFF76DBED4F890904FF0000B4FF0B9 -:106B0000010AD4F894305FFA8BF79B689F423FF6F6 -:106B100038AF09EB4713D3F8002902F44022B2F54D -:106B2000802F20D1D3F80029002A1CDAD3F80029BD -:106B300042F09042C3F80029D3F80029002AFBDB79 -:106B40003946D4F89000FFF787FB22890AFA07F349 -:106B500022EA0303238104EB8703DB689B6813B1FC -:106B60003946204698470BF1010BCAE7910701D13E -:106B7000D0F80080072A02F101029CBF03F8018BC4 -:106B80004FEA18283FE704EB830300F58050DA68EA -:106B9000D2F818C0DCF80820DCE9001CA1EB0C0CD2 -:106BA00000218F4208D1DB689B699A683A449A6059 -:106BB0005A683A445A6029E711F0030F01D1D0F81E -:106BC00000808C4501F1010184BF02F8018B4FEA7E -:106BD0001828E6E7BDE8F88F08B50348FFF774FE0C -:106BE000BDE80840FDF7E6BC6085002008B5034815 -:106BF000FFF76AFEBDE80840FDF7DCBCFC8500201D -:106C0000D0F8903003EB4111D1F8003B43F400136E -:106C1000C1F8003B70470000D0F8903003EB411101 -:106C2000D1F8003943F40013C1F80039704700006F -:106C3000D0F8903003EB4111D1F8003B23F400135E -:106C4000C1F8003B70470000D0F8903003EB4111D1 -:106C5000D1F8003923F40013C1F80039704700005F -:106C600030B50433039C0172002104FB0325C1608D -:106C7000C0E90653049B0363059BC0E90000C0E91B -:106C80000422C0E90842C0E90A11436330BD000094 -:106C90000022416AC260C0E90411C0E90A226FF013 -:106CA0000101FEF725BD0000D0E90432934201D175 -:106CB000C2680AB9181D704700207047036919603F -:106CC0000021C2680132C260C269134482699342E2 -:106CD000036124BF436A0361FEF7FEBC38B5044676 -:106CE0000D46E3683BB162690020131D1268A36280 -:106CF0001344E36207E0237A33B929462046FEF7BE -:106D0000DBFC0028EDDA38BD6FF00100FBE7000086 -:106D1000C368C269013BC3604369134482699342FB -:106D2000436124BF436A436100238362036B03B161 -:106D30001847704770B53023044683F31188866A7C -:106D40003EB9FFF7CBFF054618B186F311882846F8 -:106D500070BDA36AE26A13F8015B9342A36202D397 -:106D60002046FFF7D5FF002383F31188EFE70000EB -:106D70002DE9F84F04460E46174698464FF0300965 -:106D800089F311880025AA46D4F828B0BBF1000F7A -:106D900009D141462046FFF7A1FF20B18BF31188AE -:106DA0002846BDE8F88FD4E90A12A7EB050B521A62 -:106DB000934528BF9346BBF1400F1BD9334601F1E1 -:106DC000400251F8040B914243F8040BF9D1A36A35 -:106DD000403640354033A362D4E90A239A4202D3B5 -:106DE0002046FFF795FF8AF31188BD42D8D289F378 -:106DF0001188C9E730465A46FAF746FFA36A5E444F -:106E00005D445B44A362E7E710B5029C0433017262 -:106E100003FB0421C460C0E906130023C0E90A3360 -:106E2000039B0363049BC0E90000C0E90422C0E99E -:106E30000842436310BD0000026A6FF00101C260A6 -:106E4000426AC0E904220022C0E90A22FEF750BCCF -:106E5000D0E904239A4201D1C26822B9184650F8F9 -:106E6000043B0B60704700231846FAE7C368002113 -:106E7000C2690133C3604369134482699342436129 -:106E800024BF436A4361FEF727BC000038B50446BF -:106E90000D46E3683BB1236900201A1DA262E26936 -:106EA0001344E36207E0237A33B929462046FEF70C -:106EB00003FC0028EDDA38BD6FF00100FBE70000AD -:106EC00003691960C268013AC260C26913448269E9 -:106ED0009342036124BF436A036100238362036B0F -:106EE00003B118477047000070B530230D460446C3 -:106EF000114683F31188866A2EB9FFF7C7FF10B1D8 -:106F000086F3118870BDA36A1D70A36AE26A01331B -:106F10009342A36204D3E16920460439FFF7D0FF0E -:106F2000002080F31188EDE72DE9F84F04460D4667 -:106F3000904699464FF0300A8AF311880026B346EE -:106F4000A76A4FB949462046FFF7A0FF20B187F353 -:106F500011883046BDE8F88FD4E90A073A1AA8EB41 -:106F60000607974228BF1746402F1BD905F140035B -:106F700055F8042B9D4240F8042BF9D1A36A403602 -:106F80004033A362D4E90A239A4204D3E16920463C -:106F90000439FFF795FF8BF311884645D9D28AF360 -:106FA0001188CDE729463A46FAF76EFEA36A3D44BA -:106FB0003E443B44A362E5E7D0E904239A4217D15B -:106FC000C3689BB1836A8BB1043B9B1A0ED01360DC -:106FD000C368013BC360C3691A4483699A42026172 -:106FE00024BF436A0361002383620123184670476C -:106FF0000023FBE700F024B9014B586A704700BF3B -:10700000000C0040034B002258631A610222DA6030 -:10701000704700BF000C0040014B0022DA6070474F -:10702000000C0040014B5863704700BF000C00404B -:10703000FEE7000070B51B4B0025044686B0586083 -:107040000E4685620163FDF78DFA04F11003A56019 -:10705000E562C4E904334FF0FF33C4E90044C4E9F6 -:107060000635FFF7C9FF2B46024604F134012046DE -:10707000C4E9082380230C4A2565FEF7D3FA0123CF -:107080000A4AE06000920375684672680192B2682D -:10709000CDE90223064BCDE90435FEF7EBFA06B045 -:1070A00070BD00BF086A0020947B0008997B00082F -:1070B00031700008024AD36A1843D062704700BF9B -:1070C000A06700204B6843608B688360CB68C36017 -:1070D0000B6943614B6903628B6943620B68036010 -:1070E0007047000008B53C4B40F2FF713B48D3F8B5 -:1070F00088200A43C3F88820D3F8882022F4FF624E -:1071000022F00702C3F88820D3F88820D3F8E020C3 -:107110000A43C3F8E020D3F808210A43C3F8082142 -:107120002F4AD3F808311146FFF7CCFF00F58060F5 -:1071300002F11C01FFF7C6FF00F5806002F1380183 -:10714000FFF7C0FF00F5806002F15401FFF7BAFFBE -:1071500000F5806002F17001FFF7B4FF00F5806078 -:1071600002F18C01FFF7AEFF00F5806002F1A8018B -:10717000FFF7A8FF00F5806002F1C401FFF7A2FF4E -:1071800000F5806002F1E001FFF79CFF00F58060F0 -:1071900002F1FC01FFF796FF02F58C7100F58060AB -:1071A000FFF790FF00F014F90E4BD3F8902242F055 -:1071B0000102C3F89022D3F8942242F00102C3F8EE -:1071C00094220522C3F898204FF06052C3F89C2007 -:1071D000054AC3F8A02008BD004402580000025828 -:1071E000A07B000800ED00E01F00080308B500F0D8 -:1071F000D1FAFEF7CBF90F4BD3F8DC2042F0400276 -:10720000C3F8DC20D3F8042122F04002C3F80421A3 -:10721000D3F80431084B1A6842F008021A601A6861 -:1072200042F004021A60FEF72FFFBDE80840FEF7A7 -:107230004BBC00BF004402580018024870470000D1 -:10724000114BD3F8E82042F00802C3F8E820D3F845 -:10725000102142F00802C3F810210C4AD3F8103173 -:10726000D36B43F00803D363C722094B9A624FF0F4 -:10727000FF32DA6200229A615A63DA605A600122B0 -:107280005A611A60704700BF004402580010005C49 -:10729000000C0040094A08B51169D3680B40D9B207 -:1072A0009B076FEA0101116107D5302383F3118831 -:1072B000FEF792F9002383F3118808BD000C00400B -:1072C000064BD3F8DC200243C3F8DC20D3F80421BA -:1072D0001043C3F80401D3F8043170470044025846 -:1072E0003A4B4FF0FF31D3F8802062F00042C3F8F0 -:1072F0008020D3F8802002F00042C3F88020D3F829 -:107300008020D3F88420C3F88410D3F8842000228E -:10731000C3F88420D3F88400D86F40F0FF4040F4D5 -:10732000FF0040F4DF4040F07F00D867D86F20F0C6 -:10733000FF4020F4FF0020F4DF4020F07F00D867FA -:10734000D86FD3F888006FEA40506FEA5050C3F806 -:107350008800D3F88800C0F30A00C3F88800D3F887 -:107360008800D3F89000C3F89010D3F89000C3F8C9 -:107370009020D3F89000D3F89400C3F89410D3F879 -:107380009400C3F89420D3F89400D3F89800C3F87D -:107390009810D3F89800C3F89820D3F89800D3F841 -:1073A0008C00C3F88C10D3F88C00C3F88C20D3F871 -:1073B0008C00D3F89C00C3F89C10D3F89C10C3F841 -:1073C0009C20D3F89C3000F0B9B900BF00440258AB -:1073D00008B50122534BC3F80821534BD3F8F420CE -:1073E00042F00202C3F8F420D3F81C2142F002025A -:1073F000C3F81C210222D3F81C314C4BDA605A68C6 -:107400009104FCD54A4A1A6001229A60494ADA601E -:1074100000221A614FF440429A61444B9A699204E7 -:10742000FCD51A6842F480721A603F4B1A6F12F44E -:10743000407F04D04FF480321A6700221A671A681E -:1074400042F001021A60384B1A685007FCD500223E -:107450001A611A6912F03802FBD1012119604FF04C -:10746000804159605A67344ADA62344A1A611A68AC -:1074700042F480321A602C4B1A689103FCD51A68CA -:1074800042F480521A601A689204FCD52C4A2D49A5 -:107490009A6200225A63196301F57C01DA6301F5EF -:1074A000E77199635A64284A1A64284ADA621A68AA -:1074B00042F0A8521A601C4B1A6802F02852B2F12E -:1074C000285FF9D148229A614FF48862DA6140223C -:1074D0001A621F4ADA641F4A1A651F4A5A651F4A10 -:1074E0009A6532231E4A1360136803F00F03022BC0 -:1074F000FAD10D4A136943F003031361136903F0D2 -:107500003803182BFAD14FF00050FFF7D9FE4FF097 -:107510008040FFF7D5FE4FF00040BDE80840FFF780 -:10752000CFBE00BF008000510044025800480258FE -:1075300000C000F0020000010000FF010088900878 -:107540003220600063020901470E0508DD0BBF0110 -:1075500020000020000001100910E00000010110CF -:10756000002000524FF0B04208B5D2F8883003F046 -:107570000103C2F8883023B1044A13680BB1506884 -:107580009847BDE80840FDF715B800BFB086002059 -:107590004FF0B04208B5D2F8883003F00203C2F8C9 -:1075A000883023B1044A93680BB1D0689847BDE88E -:1075B0000840FCF7FFBF00BFB08600204FF0B0428C -:1075C00008B5D2F8883003F00403C2F8883023B13C -:1075D000044A13690BB150699847BDE80840FCF7AD -:1075E000E9BF00BFB08600204FF0B04208B5D2F826 -:1075F000883003F00803C2F8883023B1044A936945 -:107600000BB1D0699847BDE80840FCF7D3BF00BF75 -:10761000B08600204FF0B04208B5D2F8883003F0B1 -:107620001003C2F8883023B1044A136A0BB1506AC0 -:107630009847BDE80840FCF7BDBF00BFB0860020FA -:107640004FF0B04310B5D3F8884004F47872C3F813 -:107650008820A30604D5124A936A0BB1D06A9847D2 -:10766000600604D50E4A136B0BB1506B9847210688 -:1076700004D50B4A936B0BB1D06B9847E20504D548 -:10768000074A136C0BB1506C9847A30504D5044A04 -:10769000936C0BB1D06C9847BDE81040FCF78ABFE3 -:1076A000B08600204FF0B04310B5D3F8884004F402 -:1076B0007C42C3F88820620504D5164A136D0BB1CD -:1076C000506D9847230504D5124A936D0BB1D06DC8 -:1076D0009847E00404D50F4A136E0BB1506E9847DB -:1076E000A10404D50B4A936E0BB1D06E9847620487 -:1076F00004D5084A136F0BB1506F9847230404D583 -:10770000044A936F0BB1D06F9847BDE81040FCF767 -:1077100051BF00BFB086002008B50348FDF700F850 -:10772000BDE80840FCF746BF3463002008B5FFF70A -:10773000B1FDBDE80840FCF73DBF0000062108B5DB -:107740000846FDF773F806210720FDF76FF80621BC -:107750000820FDF76BF806210920FDF767F80621E0 -:107760000A20FDF763F806211720FDF75FF80621D0 -:107770002820FDF75BF809217A20FDF757F807214B -:107780003220FDF753F80C215220BDE80840FDF7E8 -:107790004DB8000008B5FFF7A3FD00F00DF8FDF7A8 -:1077A000EDF9FDF7C5FBFDF797FAFFF747FDBDE8DB -:1077B0000840FFF71FBC00000023054A19460133AB -:1077C000102BC2E9001102F10802F8D1704700BF86 -:1077D000B08600200B460146184600F003B80000B2 -:1077E00000F00EB810B5054C13462CB10A46014600 -:1077F0000220AFF3008010BD2046FCE7000000002F -:10780000024B01461868FEF757BB00BF6C220020F0 -:1078100010B501390244904201D1002005E00378FF -:1078200011F8014FA34201D0181B10BD0130F2E73F -:107830002DE9F041A3B1C91A17780144044603F1B8 -:10784000FF3C8C42204601D9002009E00578BD426A -:1078500004F10104F5D10CEB0405D618A54201D1C1 -:10786000BDE8F08115F8018D16F801EDF045F5D071 -:10787000E7E70000034611F8012B03F8012B002A6B -:10788000F9D170476F72672E6172647570696C6FA1 -:10789000742E437562654F72616E67652D706572F7 -:1078A0006970680053544D333248373F3F3F0053AF -:1078B000544D3332483733782F3732780053544D94 -:1078C0003332483734332F3735332F3735300000D4 -:1078D00001105A00031059000120580003205600DF -:1078E00040A2E4F1646891060041A3E5F265699263 -:1078F0000700000043414E464449666163653A20F3 -:107900004D6573736167652052414D204F766572F6 -:10791000666C6F77210000004261642043414E494C -:107920006661636520696E6465782E000001000061 -:107930000001FF0000A0004000A400400000000083 -:1079400000000000DD2C0008B525000811340008F7 -:10795000AD25000825260008352A00089D270008C7 -:10796000ED250008F1250008C9250008B12500080B -:10797000F5290008D525000879350008E12500081B -:10798000C929000800960000000000000000000067 -:1079900000000000000000000000000000000000E7 -:1079A0003D4B0008294B0008654B0008514B00086F -:1079B0005D4B0008494B0008354B0008214B00087F -:1079C000714B000800000000554C0008414C0008B5 -:1079D0007D4C0008694C0008754C0008614C00089B -:1079E0004D4C0008394C0008894C0008000000008C -:1079F000010000000000000063300000F87900087A -:107A0000F8670020086A00204172647550696C6F45 -:107A1000740025424F415244252D424C00255345C8 -:107A20005249414C25000000020000000000000007 -:107A3000754E0008E54E000840004000B882002066 -:107A4000C8820020020000000000000003000000C7 -:107A5000000000002D4F0008000000001000000092 -:107A6000D88200200000000001000000000000009B -:107A70006085002001010200655A00087559000860 -:107A8000115A0008F559000843000000907A0008D8 -:107A900009024300020100C0320904000001020291 -:107AA0000100052400100105240100010424020244 -:107AB0000524060001070582030800FF09040100F0 -:107AC000020A0000000705010240000007058102CC -:107AD0004000000012000000DC7A000812011001D2 -:107AE0000200004009124157000201020301000098 -:107AF0000403090425424F415244250030313233FA -:107B00003435363738394142434445460000000099 -:107B10000000002000000200020000000001003010 -:107B20000000000008000000000000240000080021 -:107B3000040000000004000000FC0000020000003F -:107B40000000043000800000080000000000003841 -:107B50000000010001000000000000008950000842 -:107B600041530008ED530008400040009886002073 -:107B70009886002001000000A886002080000000F8 -:107B8000400100000800000000010000001000009B -:107B9000080000006D61696E0069646C650000009A -:107BA0000000802A00000000AAAAAAAA000000245F -:107BB000FFFF00000000000000A00A0000210002FA -:107BC00000000000AAAAAAAA00000000FFFF00000F -:107BD000000000090000090014000054000000002B -:107BE000AAAAAAAA14000054FFFF00000000000087 -:107BF000000000000A40100000000000AAAA8AAAA3 -:107C000000401000FFFF000099000000000000008D -:107C10000081020000000000AAAAAAAA00410100F7 -:107C2000FFFF0000000000700700000000000000DF -:107C300000000000AAAAAAAA00000000FFFF00009E -:107C40000000000000000000000000000000000034 -:107C5000AAAAAAAA00000000FFFF0000000000007E -:107C6000000000000000000000000000AAAAAAAA6C -:107C700000000000FFFF0000000000000000000006 -:107C80000000000000000000AAAAAAAA000000004C -:107C9000FFFF0000000000000000000000000000E6 -:107CA00000000000AAAAAAAA00000000FFFF00002E -:107CB00000000000000000000000000000000000C4 -:107CC000AAAAAAAA00000000FFFF0000000000000E -:107CD000000000004C86FF7F010000000000000053 -:107CE000780500000000000000001E0000000000F9 -:107CF000FE2A0100D2040000FF000000106A0020EC -:107D00003463002000000000A47800088304000011 -:107D1000AF78000850040000BD780008009600000D -:107D200000000800960000000008000004000000A9 -:107D3000F07A0008000000000000000000000000D1 -:107D40000000000000000000000000007022002081 -:107D50000000000000000000000000000000000023 -:107D60000000000000000000000000000000000013 -:107D70000000000000000000000000000000000003 -:107D800000000000000000000000000000000000F3 -:107D900000000000000000000000000000000000E3 -:107DA00000000000000000000000000000000000D3 +:10366000082817D90C280CD910280CD914280CD9E3 +:1036700018280CD920280CD930288CBF0F200E20F8 +:103680007047092070470A2070470B2070470C20B4 +:1036900070470D20704700002DE9F843078C044661 +:1036A000072F1ED900254FF6FF73D0E90298C5F108 +:1036B0002006A5F1200029FA05F1083508FA06F6DA +:1036C00028FA00F0314301431846C9B2FFF762FF00 +:1036D000402D0346EBD13A46E169BDE8F843FFF7D8 +:1036E00069BF4FF6FF70BDE8F883000010B54B6866 +:1036F00023B9CA8A63F30902CA8210BD04691A6831 +:103700001C600361C38A013BC3824A60EFE700008B +:103710002DE9F84F1D46CB8A0F468146C3F30901B8 +:10372000924605290B4630D00020AAB207F11A04B0 +:103730009EB21FFA80F8042E0FD8904503F10103C2 +:1037400006D30A44FB8A62F309030120FB821AE0D4 +:103750001AF800600130E654EAE79045F1D2A1F191 +:10376000050B1C237C68BBFBF3F203FB12BB1FFAA7 +:103770008BF6002C45D14846FFF728FF044638B9A0 +:1037800078606FF00200BDE8F88F4FF00008E6E7C0 +:10379000002606607860ADB24FF0000B454510D9A9 +:1037A0000AEB0803221D13F8011B08F101089155CB +:1037B000B1B21FFA88F81B292BD0454506F1010646 +:1037C000F1D8FB8AC3F30902154465F30903BCE78A +:1037D00001321C4692B22368002BF9D16B1F0B44B7 +:1037E0001C21B3FBF1F301339BB29A42D3D2BBF15C +:1037F000000FD0D14846FFF7E9FE20B9C4F800B069 +:10380000BFE70122E7E7C0F800B05E46206004464B +:10381000C1E74545D5D94846FFF7D8FE08B920602D +:10382000AFE7C0F800B0002620600446B6E700000D +:103830002DE9F04F1C46074688462DED028B83B0DC +:103840005B690192002B00F09A80238C2BB1E26916 +:10385000002A00F09480072B35D807F10C00FFF701 +:10386000B5FE054638B96FF00205284603B0BDEC39 +:10387000028BBDE8F08F14220021FEF7B1F8228CF4 +:10388000E16905F10800FEF785F8208C48F0004159 +:10389000013080B2FFF7E4FEFFF7C6FE013880B2C8 +:1038A00020840130287438466369228C1B782A44AE +:1038B00003F01F0363F03F03137269602946FFF7AB +:1038C000EFFD0125D1E74FF0000900F10C034FF0A7 +:1038D000800A4E464D4608EE103A18EE100AFFF7E1 +:1038E00075FE83460028BED014220021FEF778F82A +:1038F000002E3AD1019B0222ABF808300BF1080EE2 +:103900001FFA82FC218C0CF10100BCF1060F80B281 +:1039100001D88E422BD3FFF7A3FE8E4208BF4FF093 +:10392000400AFFF781FE62690138013512781BFAFF +:1039300080F1013002F01F022DB242EA491289F0F3 +:1039400001094AEA020A48F0004281F808A05946F3 +:103950008BF810003846CBF804204FF0000AFFF730 +:103960009FFD238CB342B8D17FE70022C6E7E1690F +:10397000895D01360EF80210B6B20132C0E76FF071 +:10398000010572E7F8B515460E46302200210446BF +:103990001F46FEF725F8069BB5F5001FA76063607C +:1039A00004F11000079B34BF6A094FF6FF72E6610D +:1039B000A362002397B29A4206D800230360A7822D +:1039C000E3822383E360F8BD06600133304620368E +:1039D000F1E7000003781BB94BB2002BC8BF0170A0 +:1039E0007047000000787047F8B50C46C969074673 +:1039F00011B9238C002B37D1257E1F2D34D8387870 +:103A000028BB228C072A2CD8268A36F003032BD118 +:103A10004FF6FF70FFF7CEFD20F0010031024FF6A8 +:103A2000FF72400441EA0561400C41EA402523460B +:103A300029463846FFF7FCFE002807DD6269137847 +:103A40000133DBB21F2B88BF00231370F8BD218A1E +:103A50002D0645EA012505432046FFF71DFE0246D7 +:103A6000E5E76FF00300F1E76FF00100EEE700001B +:103A700070B58AB0044616460021282268461D46C5 +:103A8000FDF7AEFFBDF8383069462046ADF810307E +:103A90000F9B05939DF840308DF81830119B0793CC +:103AA000BDF84830CDE90265ADF82030FFF79CFF46 +:103AB0000AB070BD2DE9F041D36905460C461646A3 +:103AC0000BB9138C5BBB377E1F2F28D895F800806D +:103AD000B8F1000F26D03046FFF7DEFD3378210223 +:103AE0000246284641EAC331338A41EA080141EAE5 +:103AF000076141EA0341334641F08001FFF798FE38 +:103B000000280ADD3378012B07D17269137801335D +:103B1000DBB21F2B88BF00231370BDE8F0816FF06C +:103B20000100FAE76FF00300F7E70000F0B58BB093 +:103B300004460D4617460021282268461E46FDF71A +:103B40004FFF9DF84C30294620465A1E53425341A0 +:103B50006A468DF800309DF84030ADF81030119B6A +:103B600005939DF848308DF81830149B0793BDF8E5 +:103B70005430CDE90276ADF82030FFF79BFF0BB053 +:103B8000F0BD0000406A00B104307047436A1A6813 +:103B9000426202691A600361C38A013BC3827047B3 +:103BA0002DE9F041D0F8208014461D46184E4146BC +:103BB000002709B9BDE8F081D1E90223A21A65EB1B +:103BC0000303964277EB03031ED2036A8B420DD1A7 +:103BD000FFF78CFD036A1B68036203690B60C38AED +:103BE0000161013B016AC3828846E2E7FFF77EFD7F +:103BF0000B68C8F8003003690B60C38A0161013BA0 +:103C0000C382D8F80010D4E788460968D1E700BF1E +:103C100080841E002DE9F04F8BB00D4614469B4664 +:103C2000DDF850908046002800F01881B9F1000FAF +:103C300000F01481531E3F2B00F21081012A03D1A2 +:103C4000BBF1000F40F00A810023CDE90833B8F83A +:103C50001430B5EBC30F4FEAC30703D300200BB0FA +:103C6000BDE8F08F2B199F42D8F80C3036BF7F1B70 +:103C70002746FFB21BB9D8F81030002B7AD0272D79 +:103C80004DD8C5F1280600232946B742009308AB5A +:103C9000D8F808002CBFF6B23E46A7EB060A35441A +:103CA00032465FFA8AFAFFF73DFCB8F81430282153 +:103CB00003F10053053BDB000493D8F80C30039369 +:103CC000039B13B1BAF1000F2CD1D8F8100040B10A +:103CD000BAF1000F05D008AB5246691A0096FFF7FB +:103CE00021FC38B2002FB9D066070AD00AAB624275 +:103CF00003EBD40102F0070211F8083C134101F86C +:103D0000083C082C3DD9102C40F2B580202C40F204 +:103D1000B780BBF1000F00F09C80082335E0BA4665 +:103D20000026C2E7049BE02B28BFE02306930B4448 +:103D3000AB42059315D95A1B0398691A0096924510 +:103D400008AB00F1040034BF5246D2B20792FFF72D +:103D5000E9FB079A1644AAEB020A1544F6B25FFA89 +:103D60008AFA049B069A05999B1A0493039B1B6885 +:103D70000393A5E700933A4608AB2946D8F8080014 +:103D8000ADE7BBF1000F13D00123B4EBC30F6BD031 +:103D9000082C12D89DF82030621E23FA02F2D507B3 +:103DA00006D54FF0FF3202FA04F423438DF8203099 +:103DB0009DF8203089F8003051E7102C12D8BDF85A +:103DC0002030621E23FA02F2D10706D54FF0FF32EF +:103DD00002FA04F42343ADF82030BDF82030A9F8EE +:103DE00000303CE7202C0FD80899631E21FA03F31A +:103DF000DA0705D54FF0FF3202FA04F40C430894B9 +:103E0000089BC9F800302AE7402C2AD0611EC4F173 +:103E10002102A4F12103DDE9086526FA01F105FA82 +:103E200002F225FA03F311431943CB0711D50122FE +:103E3000A4F12003C4F1200102FA03F322FA01F1F4 +:103E4000A2400B43524263EB430332432B43CDE981 +:103E50000823DDE90823C9E9002300E76FF001002A +:103E6000FDE66FF00800FAE6082CA1D9102CB4D9B1 +:103E7000202CEED8C4E7BBF1000FAED0022384E7BC +:103E8000BBF1000FBCD004237FE70000012A30B54E +:103E9000144638BF012485B00025402C28BF40249B +:103EA000012ACDE9025518D81B788DF80830630730 +:103EB0000AD004AB624203EBD40502F0070215F806 +:103EC000083C934005F8083C034600912246002137 +:103ED00002A8FFF727FB05B030BD082AE4D9102A55 +:103EE00003D81B88ADF80830E1E7202A95BF1B688E +:103EF000D3E900230293CDE90223D8E710B5CB68BC +:103F00001BB98B600B618B8210BD04691A681C6041 +:103F10000361C38A013BC382CA60F0E703064CBF5A +:103F2000C0F3C0300220704708B50246FFF7F6FF25 +:103F3000022806D15306C2F30F2001D100F003007E +:103F400008BDC2F30740FBE72DE9F04F93B00446EC +:103F50000D46CDE903230A681046FFF7DFFF02286C +:103F6000824614BFC2F306260026002A80F2F3819F +:103F700012F0C04940F0EF81097B002900F0EB818D +:103F8000022803D02378B34240F0E881C2F30463EF +:103F900010462944069302F07F030593FFF7C4FF00 +:103FA000059B002283464FEA8348002348EA0A48DB +:103FB00048EA4668CE78CDE90823F30948EA0008C4 +:103FC000029368D0059B024608A9204600935346F9 +:103FD0006768B847002800F0C481276A4FB9414696 +:103FE00004F10C00FFF700FB074690B96FF00200E8 +:103FF00055E03B6998450DD03F68002FF9D1414607 +:1040000004F10C00FFF7F0FA07460028EED0236A0F +:104010003B60276297F817C006F01F08CCF3840CAA +:10402000ACEB0800A8EB0C031FFA80FE0028B8BF19 +:104030000EF120001FFA83FEB8BF00B2002B0793D9 +:10404000B8BF0EF12003D7E90221BCBF1BB2079312 +:1040500052EA010338D0039B4FF0000CDFF820E355 +:104060009A1A049B63EB010196457CEB01032BD369 +:104070006B7B97F81AE0734519D1029B002B78D01F +:10408000012821DC7868F8B9DFF8F0C2944570EBBC +:10409000010316D337E0276A27B96FF00C0013B07D +:1040A000BDE8F08F3B699845B4D03F68F4E7B3486A +:1040B00090427CEB010301D30020F0E7029B002B30 +:1040C000FAD0079B0F2B17DCFA7DB3003946204648 +:1040D00002F0030203F07C031343FB75FFF706FBBA +:1040E0006B7BBB76029B3BB9FB7DC3F38402013241 +:1040F00062F38603FB75D0E76A7BBB7E9A42DBD115 +:10410000029B002B35D0B309022B32D0039B142223 +:1041100000210DA8BB60049BFB60FDF761FC039BC5 +:104120000AA920460A93049BADF83EB00B932B1DC1 +:104130008DF840A00C932B7B8DF84180013BDBB2C6 +:10414000ADF83C30069B8DF84230059B8DF843302E +:1041500094F82C3083F001038DF84430A36898471D +:10416000FB7DC3F38403013303F01F039B02FB8237 +:10417000A2E7FB7DC6F34012B2EBD31F40F0F48000 +:10418000C3F38403434540F0F280029AB6092B7BC7 +:10419000002A4DD0F2075DD4032B40F2EB80039B45 +:1041A000AE1D394604F10C00BB603246049BFB6037 +:1041B0002B7B033BDBB2FFF7ABFA00280CDA394666 +:1041C0002046FFF793FAFB7DC3F38403013303F02A +:1041D0001F039B02FB8209E7AB88DDE908843B8370 +:1041E0004FF6FF73C9F12000A9F1200228FA09F166 +:1041F00009F1080904FA00F024FA02F20143184612 +:104200001143C9B2FFF7C6F9B9F1400F0346E9D12E +:10421000B88231462A7B033AD2B2FFF7CBF9FB7D55 +:10422000B882DA43C2F3C01262F3C713FB7543E7E7 +:1042300086B92E1D013B394604F10C00DBB2324633 +:10424000FFF766FA0028BADB2A7B3146B88A013AC2 +:10425000D2B2E2E7F98A013BC1F30901DAB20429DB +:104260005BD8281D002307F11B069A4208D910F8D5 +:1042700001CB013306F801C00131DBB20529F4D1CD +:10428000039993420A9138BF043304992CBF002349 +:1042900055FA83F30B9107F11B010C9179680E938A +:1042A0000D91291DFB8AADF83EB0C3F309038DF8CB +:1042B00040A08DF841801A44069B8DF84230059B42 +:1042C000ADF83C208DF8433094F82C3083F0010396 +:1042D0008DF844300023B88A7B602A7B013AFFF7CF +:1042E00069F93B8BB882834203D1A3680AA92046AF +:1042F000984720460AA9FFF701FEFB7DBA8AC3F35F +:104300008403013303F01F039B02FB823B8B9A4221 +:104310000CBF00206FF01000C1E67B68002BAFD00F +:10432000052001E01C3033461E68002EFAD1091A20 +:104330002E1D081D184401EB090C5FFA89F3BCF12E +:104340001B0F9DD89A429BD916F8013B09F1010930 +:1043500000F8013BEFE76FF00900A0E66FF00A00FC +:104360009DE66FF00B009AE66FF00D0097E66FF098 +:104370000E0094E66FF00F0091E600BF40420F0080 +:1043800080841E00EFF30983054968334A6B22F0ED +:1043900001024A6383F30988002383F3118870477D +:1043A00000EF00E0302080F3118862B60D4B0E4A1A +:1043B000D96821F4E0610904090C0A430B49DA6069 +:1043C000D3F8FC2042F08072C3F8FC20084AC2F8FF +:1043D000B01F116841F0010111602022DA7783F8E3 +:1043E0002200704700ED00E00003FA0555CEACC591 +:1043F000001000E0302310B583F311880E4B5B688A +:1044000013F4006314D0F1EE103AEFF309844FF087 +:104410008073683CE361094BDB6B236684F3098896 +:1044200001F0F2F910B1064BA36110BD054BFBE79B +:1044300083F31188F9E700BF00ED00E000EF00E032 +:104440003F0400084204000808B5074B074A1968F2 +:1044500001F03D01996053680BB190689847BDE841 +:104460000840FFF7C7BF00BF0000024054640020AF +:1044700008B5084B1968890901F03D018A019A6065 +:10448000054AD3680BB110699847BDE80840FFF7AB +:10449000B1BF00BF000002405464002008B5084BC3 +:1044A0001968090C01F03D010A049A60054A536934 +:1044B0000BB190699847BDE80840FFF79BBF00BF6C +:1044C000000002405464002008B5084B1968890DAB +:1044D00001F03D018A059A60054AD3690BB1106A63 +:1044E0009847BDE80840FFF785BF00BF00000240C5 +:1044F0005464002008B5074B074A596801F03D0194 +:10450000D960536A0BB1906A9847BDE80840FFF73D +:1045100071BF00BF000002405464002008B5084B82 +:104520005968890901F03D018A01DA60054AD36AB8 +:104530000BB1106B9847BDE80840FFF75BBF00BFA9 +:10454000000002405464002008B5084B5968090C6B +:1045500001F03D010A04DA60054A536B0BB1906B20 +:104560009847BDE80840FFF745BF00BF0000024084 +:104570005464002008B5084B5968890D01F03D01CD +:104580008A05DA60054AD36B0BB1106C9847BDE819 +:104590000840FFF72FBF00BF000002405464002016 +:1045A00008B5074B074A196801F03D019960536C43 +:1045B0000BB1906C9847BDE80840FFF71BBF00BFE8 +:1045C000000402405464002008B5084B19688909AA +:1045D00001F03D018A019A60054AD36C0BB1106D60 +:1045E0009847BDE80840FFF705BF00BF0004024040 +:1045F0005464002008B5084B1968090C01F03D010E +:104600000A049A60054A536D0BB1906D9847BDE856 +:104610000840FFF7EFBE00BF0004024054640020D2 +:1046200008B5084B1968890D01F03D018A059A60AB +:10463000054AD36D0BB1106E9847BDE80840FFF7EF +:10464000D9BE00BF000402405464002008B5074BE7 +:10465000074A596801F03D01D960536E0BB1906E65 +:104660009847BDE80840FFF7C5BE00BF0004024000 +:104670005464002008B5084B5968890901F03D01D0 +:104680008A01DA60054AD36E0BB1106F9847BDE816 +:104690000840FFF7AFBE00BF000402405464002092 +:1046A00008B5084B5968090C01F03D010A04DA60AD +:1046B000054A536F0BB1906F9847BDE80840FFF76C +:1046C00099BE00BF000402405464002008B5084BA6 +:1046D0005968890D01F03D018A05DA60054AD36FFA +:1046E00013B1D2F880009847BDE80840FFF782BEBA +:1046F000000402405464002000230C4910B51A46FF +:104700000B4C0B6054F82300026001EB43000433B0 +:104710004260402BF6D1074A4FF0FF339360D360DD +:10472000C2F80834C2F80C3410BD00BF5464002035 +:104730003C7C0008000002400F28F8B510D9102872 +:1047400010D0112811D0122808D10F240720DFF82B +:10475000C8E00126DEF80050A04208D9002653E048 +:104760000446F4E70F240020F1E70724FBE706FAEC +:1047700000F73D424AD1264C4FEA001C3D4304EB72 +:1047800000160EEBC000CEF80050C0E90123FBB2CA +:1047900073B12048D0F8D83043F00103C0F8D830C6 +:1047A000D0F8003143F00103C0F80031D0F80031F7 +:1047B00017F47F4F0ED01748D0F8D83043F00203DB +:1047C000C0F8D830D0F8003143F00203C0F800310F +:1047D000D0F8003154F80C00036823F01F03036085 +:1047E000056815F00105FBD104EB0C033D2493F89B +:1047F0000CC05F6804FA0CF43C602124056044613D +:1048000012B1987B00F066F93046F8BD0130A3E79D +:104810003C7C0008004402585464002010B5302449 +:1048200084F31188FFF788FF002383F3118810BDFC +:1048300010B50446807B00F063F901231549627BC3 +:1048400003FA02F20B6823EA0203DAB20B6072B9D0 +:10485000114AD2F8D81021F00101C2F8D810D2F8CC +:10486000001121F00101C2F80011D2F8002113F467 +:104870007F4F0ED1084BD3F8D82022F00202C3F8A4 +:10488000D820D3F8002122F00202C3F80021D3F887 +:10489000003110BD546400200044025808B5302394 +:1048A00083F31188FFF7C4FF002383F3118808BD49 +:1048B000026843681143016003B118477047000064 +:1048C000024A136843F0C003136070470078004049 +:1048D00013B50E4C204600F0BDFA04F1140000237D +:1048E0004FF400720A49009400F07AF9094B4FF432 +:1048F0000072094904F13800009400F0F3F9074A06 +:10490000074BC4E9172302B010BD00BFD8640020D4 +:1049100044650020C148000844670020007800403A +:1049200000E1F505037C30B5244C002918BF0C4686 +:10493000012B11D1224B98420ED1224BD3F8E82003 +:1049400042F08042C3F8E820D3F8102142F08042C0 +:10495000C3F81021D3F810312268036EC16D03EB48 +:1049600052038466B3FBF2F36268150442BF23F07E +:10497000070503F0070343EA4503CB60A36843F050 +:1049800040034B60E36843F001038B6042F496738D +:1049900043F001030B604FF0FF330B62510505D567 +:1049A00012F0102205D0B2F1805F04D080F864309C +:1049B00030BD7F23FAE73F23F8E700BF3C7D0008C6 +:1049C000D8640020004402582DE9F047C66D054622 +:1049D0003768F469210734621AD014F0080118BF4F +:1049E0004FF48071E20748BF41F02001A3074FF068 +:1049F000300348BF41F04001600748BF41F08001EB +:104A000083F31188281DFFF753FF002383F31188D8 +:104A1000E2050AD5302383F311884FF48061281D05 +:104A2000FFF746FF002383F311884FF030094FF062 +:104A3000000A14F0200838D13B0616D54FF0300993 +:104A400005F1380A200610D589F31188504600F088 +:104A50007DF9002836DA0821281DFFF729FF27F005 +:104A600080033360002383F31188790614D562062E +:104A700012D5302383F31188D5E913239A4208D144 +:104A80002B6C33B127F040071021281DFFF710FFD2 +:104A90003760002383F31188E30618D5AA6E1369E3 +:104AA000ABB15069BDE8F047184789F31188736AC4 +:104AB000284695F86410194000F0E6F98AF3118849 +:104AC000F469B6E7B06288F31188F469BAE7BDE823 +:104AD000F0870000090100F16043012203F5614302 +:104AE000C9B283F8001300F01F039A4043099B00EA +:104AF00003F1604303F56143C3F880211A607047F6 +:104B000000F01F0301229A40430900F160409B001E +:104B100000F5614003F1604303F56143C3F8802071 +:104B2000C3F88021002380F800337047F8B515469C +:104B3000826804460B46AA4200D28568A1692669AC +:104B4000761AB5420BD218462A46FCF723FFA36912 +:104B50002B44A3612846A3685B1BA360F8BD0CD956 +:104B6000AF1B18463246FCF715FF3A46E168304461 +:104B7000FCF710FFE3683B44EBE718462A46FCF7D6 +:104B800009FFE368E5E7000083689342F7B5044650 +:104B9000154600D28568D4E90460361AB5420BD2B6 +:104BA0002A46FCF7F7FE63692B4463612846A36835 +:104BB0005B1BA36003B0F0BD0DD93246AF1B019162 +:104BC000FCF7E8FE01993A46E0683144FCF7E2FE62 +:104BD000E3683B44E9E72A46FCF7DCFEE368E4E7E8 +:104BE00010B50A440024C361029B8460C160026165 +:104BF0000362C0E90000C0E9051110BD08B5D0E9A5 +:104C00000532934201D1826882B9826801328260A2 +:104C10005A1C426119700021D0E904329A4224BF23 +:104C2000C368436100F09CFE002008BD4FF0FF30D8 +:104C3000FBE7000070B5302304460E4683F311886D +:104C4000A568A5B1A368A269013BA360531CA36139 +:104C500015782269934224BFE368A361E3690BB12D +:104C600020469847002383F31188284607E0314601 +:104C7000204600F065FE0028E2DA85F3118870BD59 +:104C80002DE9F74F04460E4617469846D0F81C907B +:104C90004FF0300A8AF311884FF0000B154665B1CA +:104CA0002A4631462046FFF741FF034660B9414698 +:104CB000204600F045FE0028F1D0002383F3118840 +:104CC000781B03B0BDE8F08FB9F1000F03D001905D +:104CD0002046C847019B8BF31188ED1A1E448AF3C6 +:104CE0001188DCE7C160C361009B82600362C0E998 +:104CF00005111144C0E9000001617047F8B5044690 +:104D00000D461646302383F31188A768A7B1A36820 +:104D1000013BA36063695A1C62611D70D4E90432CF +:104D20009A4224BFE3686361E3690BB12046984768 +:104D3000002080F3118807E03146204600F000FE95 +:104D40000028E2DA87F31188F8BD0000D0E90523D6 +:104D500010B59A4201D182687AB982680021013285 +:104D600082605A1C82611C7803699A4224BFC3681E +:104D7000836100F0F5FD204610BD4FF0FF30FBE7EA +:104D80002DE9F74F04460E4617469846D0F81C907A +:104D90004FF0300A8AF311884FF0000B154665B1C9 +:104DA0002A4631462046FFF7EFFE034660B94146EA +:104DB000204600F0C5FD0028F1D0002383F31188C0 +:104DC000781B03B0BDE8F08FB9F1000F03D001905C +:104DD0002046C847019B8BF31188ED1A1E448AF3C5 +:104DE0001188DCE7026843681143016003B118478A +:104DF000704700001430FFF743BF00004FF0FF334F +:104E00001430FFF73DBF00003830FFF7B9BF000096 +:104E10004FF0FF333830FFF7B3BF00001430FFF717 +:104E200009BF00004FF0FF311430FFF703BF00004F +:104E30003830FFF763BF00004FF0FF323830FFF724 +:104E40005DBF0000012914BF6FF013000020704700 +:104E5000FFF73EBD044B036000234360C0E902330B +:104E600001230374704700BF547D000810B5302340 +:104E7000044683F31188FFF755FD022300202374B5 +:104E800080F3118810BD000038B5C36904460D4693 +:104E90001BB904210844FFF7A5FF294604F11400BB +:104EA000FFF7ACFE002806DA201D4FF40061BDE8D4 +:104EB0003840FFF797BF38BD02684368114301606F +:104EC00003B118477047000013B5406B00F58054DC +:104ED000D4F8A4381A681178042914D1017C022965 +:104EE00011D11979012312898B4013420BD101A9E9 +:104EF0004C3002F0F5F8D4F8A4480246019B217921 +:104F0000206800F0DFF902B010BD0000143002F09C +:104F100077B800004FF0FF33143002F071B8000092 +:104F20004C3002F049B900004FF0FF334C3002F032 +:104F300043B90000143002F045B800004FF0FF31D3 +:104F4000143002F03FB800004C3002F015B90000F8 +:104F50004FF0FF324C3002F00FB9000000207047D4 +:104F600010B500F58054D4F8A4381A6811780429D3 +:104F700017D1017C022914D15979012352898B4020 +:104F800013420ED1143001F0D7FF024648B1D4F8D5 +:104F9000A4484FF4407361792068BDE8104000F0E8 +:104FA0007FB910BD406BFFF7DBBF0000704700000A +:104FB0007FB5124B012504260446036000230574C7 +:104FC00000F1840243602946C0E902330C4B029091 +:104FD000143001934FF44073009601F089FF094BA0 +:104FE00004F69442294604F14C000294CDE9006392 +:104FF0004FF4407302F050F804B070BD7C7D00089F +:10500000A54F0008C94E00080A68302383F31188B1 +:105010000B790B3342F823004B79133342F823000A +:105020008B7913B10B3342F8230000F58053C3F89A +:10503000A41802230374002080F311887047000035 +:1050400038B5037F044613B190F85430ABB901254D +:10505000201D0221FFF730FF04F114006FF0010161 +:10506000257700F089FC04F14C0084F854506FF06F +:105070000101BDE8384000F07FBC38BD10B501210A +:1050800004460430FFF718FF0023237784F85430D8 +:1050900010BD000038B504460025143001F040FF73 +:1050A00004F14C00257702F00FF8201D84F85450CD +:1050B0000121FFF701FF2046BDE83840FFF750BF50 +:1050C00090F8803003F06003202B06D190F8812007 +:1050D0000023212A03D81F2A06D800207047222A3D +:1050E000FBD1C0E91D3303E0034A42670722826710 +:1050F000C3670120704700BF3C23002037B500F58F +:105100008055D5F8A4381A68117804291AD1017C81 +:10511000022917D11979012312898B40134211D129 +:1051200000F14C04204602F08FF858B101A9204646 +:1051300001F0D6FFD5F8A4480246019B21792068EA +:1051400000F0C0F803B030BD01F10B03F0B550F82A +:10515000236085B004460D46FEB1302383F31188E9 +:1051600004EB8507301D0821FFF7A6FEFB6806F15A +:105170004C005B691B681BB1019001F0BFFF0198F7 +:1051800003A901F0ADFF024648B1039B2946204622 +:1051900000F098F8002383F3118805B0F0BDFB6898 +:1051A0005A691268002AF5D01B8A013B1340F1D1DD +:1051B00004F18002EAE70000133138B550F82140CD +:1051C000ECB1302383F3118804F58053D3F8A4287D +:1051D0001368527903EB8203DB689B695D6845B114 +:1051E00004216018FFF768FE294604F1140001F05D +:1051F000ADFE2046FFF7B4FE002383F3118838BDCF +:105200007047000001F07AB901234022002110B557 +:10521000044600F8303BFCF7E3FB0023C4E901330C +:1052200010BD000010B53023044683F311882422FA +:10523000416000210C30FCF7D3FB204601F080F9DF +:1052400002230020237080F3118810BD70B500EB9D +:105250008103054650690E461446DA6018B11022E3 +:105260000021FCF7BDFBA06918B110220021FCF75A +:10527000B7FB31462846BDE8704001F067BA000030 +:1052800083682022002103F0011310B504468360D7 +:105290001030FCF7A5FB2046BDE8104001F0E2BA53 +:1052A000F0B4012500EB810447898D40E4683D435B +:1052B000A469458123600023A2606360F0BC01F013 +:1052C000FFBA0000F0B4012500EB810407898D408E +:1052D000E4683D436469058123600023A260636044 +:1052E000F0BC01F075BB000070B502230025044638 +:1052F000242203702946C0F888500C3040F8045C22 +:10530000FCF76EFB204684F8705001F0B3F9636837 +:105310001B6823B129462046BDE87040184770BD80 +:105320000378052B10B504460AD080F88C3005238D +:10533000037043681B680BB1042198470023A360E6 +:1053400010BD00000178052906D190F88C20436833 +:1053500002701B6803B118477047000070B590F8E1 +:105360007030044613B1002380F8703004F18002DD +:10537000204601F09BFA63689B68B3B994F88030CB +:1053800013F0600535D00021204601F08DFD00218D +:10539000204601F07DFD63681B6813B1062120469D +:1053A0009847062384F8703070BD2046984700283F +:1053B000E4D0B4F88630A26F9A4288BFA36794F90C +:1053C0008030A56F002B4FF0300380F20381002D59 +:1053D00000F0F280092284F8702083F31188002104 +:1053E0002046D4E91D23FFF76DFF002383F31188C6 +:1053F000DAE794F8812003F07F0343EA022340F2C6 +:105400000232934200F0C58021D8B3F5807F48D0A6 +:105410000DD8012B3FD0022B00F09380002BB2D18E +:1054200004F1880262670222A267E367C1E7B3F56D +:10543000817F00F09B80B3F5407FA4D194F8823047 +:10544000012BA0D1B4F8883043F0020332E0B3F569 +:10545000006F4DD017D8B3F5A06F31D0A3F5C0635E +:10546000012B90D86368204694F882205E6894F8F7 +:105470008310B4F88430B047002884D04368636751 +:105480000368A3671AE0B3F5106F36D040F6024206 +:1054900093427FF478AF5C4B63670223A3670023DA +:1054A000C3E794F88230012B7FF46DAFB4F88830F5 +:1054B00023F00203A4F88830C4E91D55E56778E7B6 +:1054C000B4F88030B3F5A06F0ED194F88230204646 +:1054D00084F88A3001F02CF963681B6813B101214C +:1054E00020469847032323700023C4E91D339CE71B +:1054F00004F18B0363670123C3E72378042B10D1E6 +:10550000302383F311882046FFF7BAFE85F3118814 +:105510000321636884F88B5021701B680BB120460F +:10552000984794F88230002BDED084F88B30042327 +:10553000237063681B68002BD6D002212046984751 +:10554000D2E794F8843020461D0603F00F010AD5F7 +:1055500001F09EF9012804D002287FF414AF2B4BF0 +:105560009AE72B4B98E701F085F9F3E794F882303E +:10557000002B7FF408AF94F8843013F00F01B3D000 +:105580001A06204602D501F0A7FCADE701F098FC11 +:10559000AAE794F88230002B7FF4F5AE94F88430BB +:1055A00013F00F01A0D01B06204602D501F07CFCB1 +:1055B0009AE701F06DFC97E7142284F8702083F3DA +:1055C00011882B462A4629462046FFF769FE85F3B7 +:1055D0001188E9E65DB1152284F8702083F3118803 +:1055E00000212046D4E91D23FFF75AFEFDE60B22D9 +:1055F00084F8702083F311882B462A4629462046DA +:10560000FFF760FEE3E700BFAC7D0008A47D000863 +:10561000A87D000838B590F870300446002B3ED0C5 +:10562000063BDAB20F2A34D80F2B32D8DFE803F06A +:10563000373131082232313131313131313137377F +:10564000856FB0F886309D4214D2C3681B8AB5FBC3 +:10565000F3F203FB12556DB9302383F311882B4607 +:105660002A462946FFF72EFE85F311880A2384F87F +:1056700070300EE0142384F87030302383F31188E7 +:10568000002320461A461946FFF70AFE002383F33B +:10569000118838BDC36F03B198470023E7E70021A5 +:1056A000204601F001FC0021204601F0F1FB636877 +:1056B0001B6813B10621204698470623D7E7000050 +:1056C00010B590F870300446142B29D017D8062B4B +:1056D00005D001D81BB110BD093B022BFBD800211E +:1056E000204601F0E1FB0021204601F0D1FB636878 +:1056F0001B6813B1062120469847062319E0152B95 +:10570000E9D10B2380F87030302383F31188002314 +:105710001A461946FFF7D6FD002383F31188DAE70E +:10572000C3689B695B68002BD5D1C36F03B19847F1 +:10573000002384F87030CEE7002382680375036984 +:105740001B6899689142FBD25A68036042601060FE +:105750005860704700238268037503691B68996865 +:105760009142FBD85A6803604260106058607047ED +:1057700008B50846302383F311880B7D032B05D031 +:10578000042B0DD02BB983F3118808BD8B6900223F +:105790001A604FF0FF338361FFF7CEFF0023F2E77B +:1057A000D1E9003213605A60F3E70000FFF7C4BF8D +:1057B000054BD96808751868026853601A600122A1 +:1057C000D8600275FAF726BE486900200C4B30B548 +:1057D000DD684B1C87B004460FD02B46094A68464B +:1057E00000F05EF92046FFF7E3FF009B13B1684627 +:1057F00000F060F9A86907B030BDFFF7D9FFF9E7FD +:105800004869002071570008044B1A68DB689068EB +:105810009B68984294BF002001207047486900208F +:10582000084B10B51C68D868226853601A600122C2 +:10583000DC602275FFF78EFF01462046BDE8104070 +:10584000FAF7E8BD4869002038B5074C0123002568 +:10585000064907482370656001F034FD0223237078 +:1058600085F3118838BD00BFB06B0020B47D0008FF +:105870004869002008B572B6044B186500F062FC58 +:1058800000F028FD024B03221A70FEE74869002051 +:10589000B06B002000F044B9034A516853685B1AAA +:1058A0009842FBD8704700BF001000E08B600223D5 +:1058B000086108468B8270478368A3F1840243F82D +:1058C000142C026943F8442C426943F8402C094ADD +:1058D00043F8242CC268A3F1200043F8182C0222BC +:1058E00003F80C2C002203F80B2C034A43F8102C6D +:1058F000704700BF2D0400084869002008B5FFF775 +:10590000DBFFBDE80840FFF751BF0000024BDB683A +:1059100098610F20FFF74CBF48690020302383F3C4 +:105920001188FFF7F3BF000008B50146302383F369 +:1059300011880820FFF74AFF002383F3118808BD70 +:10594000064BDB6839B1426818605A6013604360E7 +:105950000420FFF73BBF4FF0FF307047486900203D +:105960000368984206D01A68026050601846996130 +:10597000FFF71CBF7047000038B504460D4620688D +:10598000844200D138BD036823605C608561FFF705 +:105990000DFFF4E7036810B59C68A2420CD85C6860 +:1059A0008A600B604C602160596099688A1A9A601D +:1059B0004FF0FF33836010BD121B1B68ECE7000043 +:1059C0000A2938BF0A2170B504460D460A26601917 +:1059D00001F070FC01F058FC041BA54203D8751CB3 +:1059E00004462E46F3E70A2E04D90120BDE8704094 +:1059F00001F0A8BC70BD0000F8B5144B0D460A2A92 +:105A00004FF00A07D96103F11001826038BF0A2202 +:105A1000416019691446016048601861A81801F0D6 +:105A200039FC01F031FC431B0646A34206D37C1C23 +:105A300028192746354601F03DFCF2E70A2F04D924 +:105A40000120BDE8F84001F07DBCF8BD48690020A8 +:105A5000F8B506460D4601F017FC0F4A134653F8F9 +:105A6000107F9F4206D12A4601463046BDE8F840E5 +:105A7000FFF7C2BFD169BB68441A2C1928BF2C4656 +:105A8000A34202D92946FFF79BFF2246314603482D +:105A9000BDE8F840FFF77EBF486900205869002044 +:105AA000C0E90323002310B45DF8044B4361FFF702 +:105AB000CFBF000010B5194C236998420DD0816802 +:105AC000D0E9003213605A609A680A449A60002351 +:105AD00003604FF0FF33A36110BD0268234643F813 +:105AE000102F53600022026022699A4203D1BDE860 +:105AF000104001F0D9BB936881680B44936001F0BA +:105B0000C3FB2269E1699268441AA242E4D91144B4 +:105B1000BDE81040091AFFF753BF00BF48690020D5 +:105B20002DE9F047DFF8BC8008F110072C4ED8F8BB +:105B3000105001F0A9FBD8F81C40AA68031B9A4238 +:105B40003ED814444FF00009D5E90032C8F81C4093 +:105B500013605A60C5F80090D8F81030B34201D1F4 +:105B600001F0A2FB89F31188D5E903312846984753 +:105B7000302383F311886B69002BD8D001F084FBAC +:105B80006A69A0EB040982464A450DD2022001F061 +:105B9000D9FB0022D8F81030B34208D1514628462C +:105BA000BDE8F047FFF728BF121A2244F2E712EBD4 +:105BB00009092946384638BF4A46FFF7EBFEB5E7E4 +:105BC000D8F81030B34208D01444C8F81C00211A89 +:105BD000A960BDE8F047FFF7F3BEBDE8F08700BF5E +:105BE000586900204869002038B501F04DFB054A8E +:105BF000D2E90845031B181945F10001C2E9080163 +:105C000038BD00BF4869002000207047FEE7000053 +:105C1000704700004FF0FF307047000002290CD0A1 +:105C2000032904D00129074818BF00207047032A20 +:105C300005D8054800EBC2007047044870470020B3 +:105C4000704700BF8C7E00084C230020407E000877 +:105C500070B59AB005460846144601A900F0C2F88E +:105C600001A8FBF7B5FE431C0022C6B25B0010463C +:105C7000C5E9003423700323023404F8013C01AB6E +:105C8000D1B202348E4201D81AB070BD13F8011B94 +:105C9000013204F8010C04F8021CF1E708B53023C6 +:105CA00083F311880348FFF729FA002383F311884F +:105CB00008BD00BFB86B002090F8803003F01F02D1 +:105CC000012A07D190F881200B2A03D10023C0E9D3 +:105CD0001D3315E003F06003202B08D1B0F88430A9 +:105CE0002BB990F88120212A03D81F2A04D8FFF766 +:105CF000E7B9222AEBD0FAE7034A42670722826714 +:105D0000C3670120704700BF4323002007B5052962 +:105D100017D8DFE801F0191603191920302383F38F +:105D20001188104A01210190FFF790FA0198022191 +:105D30000D4AFFF78BFA0D48FFF7ACF9002383F308 +:105D4000118803B05DF804FB302383F31188074802 +:105D5000FFF776F9F2E7302383F311880348FFF762 +:105D60008DF9EBE7E07D0008047E0008B86B0020A9 +:105D700038B50C4D0C4C2A460C4904F10800FFF7CD +:105D800067FF05F1CA0204F110000949FFF760FF3F +:105D900005F5CA7204F118000649BDE83840FFF75E +:105DA00057BF00BF908400204C230020C07D000816 +:105DB000CA7D0008D57D000870B5044608460D462A +:105DC000FBF706FEC6B22046013403780BB918462D +:105DD00070BD32462946FBF7E7FD0028F3D10120CC +:105DE000F6E700002DE9F04705460C46FBF7F0FD0D +:105DF0002B49C6B22846FFF7DFFF08B10A36F6B2D4 +:105E000028492846FFF7D8FF08B11036F6B2632EAE +:105E10000BD8DFF88C80DFF88C90234FDFF894A04C +:105E20002E7846B92670BDE8F08729462046BDE8A1 +:105E3000F04701F06BBE252E2ED1072241462846A1 +:105E4000FBF7B2FD70B9194B224603F1100153F86C +:105E5000040B8B4242F8040BF9D11B78073511343F +:105E60001370DDE7082249462846FBF79DFD98B9E7 +:105E7000A21C0F4B197802320909C95D02F8041CF3 +:105E800013F8011B01F00F015345C95D02F8031C13 +:105E9000F0D118340835C3E7013504F8016BBFE7CA +:105EA000AC7E0008D57D0008B47E00082A7B00087F +:105EB00000E8F11F0CE8F11FBFF34F8F044B1A6984 +:105EC0005107FCD1D3F810215207F8D1704700BF19 +:105ED0000020005208B50D4B1B78ABB9FFF7ECFF63 +:105EE0000B4BDA68D10704D50A4A5A6002F18832AE +:105EF0005A60D3F80C21D20706D5064AC3F804210C +:105F000002F18832C3F8042108BD00BFEE860020EC +:105F1000002000522301674508B5114B1B78F3B9E7 +:105F2000104B1A69510703D5DA6842F04002DA6073 +:105F3000D3F81021520705D5D3F80C2142F04002C6 +:105F4000C3F80C21FFF7B8FF064BDA6842F00102F4 +:105F5000DA60D3F80C2142F00102C3F80C2108BD2D +:105F6000EE860020002000520F289ABF00F58060C6 +:105F700040040020704700004FF4003070470000DC +:105F8000102070470F2808B50BD8FFF7EDFF00F57C +:105F900000330268013204D104308342F9D1012078 +:105FA00008BD0020FCE700000F2838B505463FD8A3 +:105FB000FFF782FF1F4CFFF78DFF4FF0FF330728DD +:105FC0006361C4F814311DD82361FFF775FF030224 +:105FD00043F02403E360E36843F08003E360236954 +:105FE0005A07FCD42846FFF767FFFFF7BDFF4FF4C1 +:105FF000003100F04BF92846FFF78EFFBDE838402E +:10600000FFF7C0BFC4F81031FFF756FFA0F1080337 +:106010001B0243F02403C4F80C31D4F80C3143F0D4 +:106020008003C4F80C31D4F810315B07FBD4D9E7F6 +:10603000002038BD002000522DE9F84F05460C46DF +:10604000104645EA0203DE0602D00020BDE8F88FC4 +:1060500020F01F00DFF8BCB0DFF8BCA0FFF73AFF6C +:1060600004EB0008444503D10120FFF755FFEDE79D +:1060700020222946204601F017FD10B92035203492 +:10608000F0E72B4605F120021F68791CDDD10433AF +:106090009A42F9D105F178431B481C4EB3F5801F95 +:1060A0001B4B38BF184603F1F80332BFD946D1461F +:1060B0001E46FFF701FF0760A5EB040C336804F1EF +:1060C0001C0143F002033360231FD9F8007017F05E +:1060D0000507FAD153F8042F8B424CF80320F4D172 +:1060E000BFF34F8FFFF7E8FE4FF0FF33202221462A +:1060F00003602846336823F00203336001F0D4FCC8 +:106100000028BBD03846B0E7142100520C200052C2 +:1061100014200052102000521021005210B5084CDB +:10612000237828B11BB9FFF7D5FE0123237010BDDA +:10613000002BFCD02070BDE81040FFF7EDBE00BF83 +:10614000EE86002038B5054D00240334696855F803 +:106150000C0B00F0ADF8122CF7D138BDC87E00084A +:10616000084601F099BC000038B5EFF311859DB9E0 +:10617000EFF30584C4F30804302334B183F31188AA +:10618000FFF732FD85F3118838BD83F31188FFF7DF +:106190002BFD84F3118838BDBDE83840FFF724BDDE +:1061A00010B5FFF7E1FF104CC008104A002340EA89 +:1061B0004170C908A0FB04ECA0FB020E1CEB000020 +:1061C000A1FB044CA1FB02125B41001943EB0C0044 +:1061D00011EB0E0142F10002411842F100000909E1 +:1061E00041EA007010BD00BFCFF753E3A59BC42068 +:1061F0000244074BD2B210B5904200D110BD441CEE +:1062000000B253F8200041F8040BE0B2F4E700BFFD +:10621000504000580E4B30B51C6F240405D41C6F41 +:106220001C671C6F44F400441C670A4C024423683A +:10623000D2B243F480732360074B904200D130BD4B +:10624000441C51F8045B00B243F82050E0B2F4E77C +:1062500000440258004802585040005807B5012237 +:1062600001A90020FFF7C4FF019803B05DF804FB0B +:1062700013B50446FFF7F2FFA04205D0012201A9A1 +:1062800000200194FFF7C6FF02B010BD0144BFF328 +:106290004F8F064B884204D3BFF34F8FBFF36F8FEE +:1062A0007047C3F85C022030F4E700BF00ED00E067 +:1062B0000144BFF34F8F064B884204D3BFF34F8F87 +:1062C000BFF36F8F7047C3F870022030F4E700BF50 +:1062D00000ED00E070470000074B45F255521A6090 +:1062E00002225A6040F6FF729A604CF6CC421A6065 +:1062F0000122024B1A70704700480058F4860020B3 +:10630000034B1B781BB1034B4AF6AA221A60704755 +:10631000F486002000480058034B1A681AB9034A53 +:10632000D2F8D0241A607047F0860020004002584E +:10633000024B4FF48032C3F8D0247047004002581B +:1063400008B5FFF7E9FF024B1868C0F3806008BD8D +:10635000F086002070B5BFF34F8FBFF36F8F1A4ADE +:106360000021C2F85012BFF34F8FBFF36F8F5369F4 +:1063700043F400335361BFF34F8FBFF36F8FC2F805 +:106380008410BFF34F8FD2F8803043F6E074C3F32C +:10639000C900C3F34E335B0103EA0406014646EA33 +:1063A00081750139C2F86052F9D2203B13F1200FF8 +:1063B000F2D1BFF34F8F536943F480335361BFF37E +:1063C0004F8FBFF36F8F70BD00ED00E0FEE7000060 +:1063D000214B2248224A70B5904237D3214BC11E2F +:1063E000DA1C121A22F003028B4238BF002200216D +:1063F000FBF7F6FA1C4A0023C2F88430BFF34F8F34 +:10640000D2F8803043F6E074C3F3C900C3F34E33CF +:106410005B0103EA0406014646EA81750139C2F8C8 +:106420006C52F9D2203B13F1200FF2D1BFF34F8F02 +:10643000BFF36F8FBFF34F8FBFF36F8F0023C2F88F +:106440005032BFF34F8FBFF36F8F70BD53F8041BF3 +:1064500040F8041BC0E700BF60810008C888002026 +:10646000C8880020C888002000ED00E0074BD3F862 +:10647000D81021EA0001C3F8D810D3F8002122EA8D +:106480000002C3F80021D3F80031704700440258DD +:1064900070B5D0E9244300224FF0FF359E6804EB2D +:1064A00042135101D3F80009002805DAD3F8000996 +:1064B00040F08040C3F80009D3F8000B002805DA4B +:1064C000D3F8000B40F08040C3F8000B0132631892 +:1064D0009642C3F80859C3F8085BE0D24FF00113A5 +:1064E000C4F81C3870BD0000890141F02001016131 +:1064F00003699B06FCD41220FFF7CEB910B50A4CF5 +:106500002046FEF781FE094BC4F89030084BC4F8D2 +:106510009430084C2046FEF777FE074BC4F89030C5 +:10652000064BC4F8943010BDF886002000000840E7 +:10653000347F00089487002000000440407F00085A +:1065400070B503780546012B5CD1434BD0F89040E1 +:10655000984258D1414B0E216520D3F8D82042F003 +:106560000062C3F8D820D3F8002142F00062C3F8DB +:106570000021D3F80021D3F8802042F00062C3F854 +:106580008020D3F8802022F00062C3F88020D3F866 +:106590008030FEF79FFA324BE360324BC4F800388C +:1065A0000023D5F89060C4F8003EC02323604FF468 +:1065B0000413A3633369002BFCDA01230C2033613D +:1065C000FFF76AF93369DB07FCD41220FFF764F99F +:1065D0003369002BFCDA00262846A660FFF758FF37 +:1065E0006B68C4F81068DB68C4F81468C4F81C68E9 +:1065F00083BB1D4BA3614FF0FF336361A36843F07E +:106600000103A36070BD194B9842C9D1134B4FF0E1 +:106610008060D3F8D82042F00072C3F8D820D3F8B5 +:10662000002142F00072C3F80021D3F80021D3F812 +:10663000802042F00072C3F88020D3F8802022F03E +:106640000072C3F88020D3F88030FFF70FFF0E21CF +:106650004D209EE7064BCDE7F88600200044025807 +:106660004014004003002002003C30C0948700200A +:10667000083C30C0F8B5D0F89040054600214FF0F6 +:1066800000662046FFF730FFD5F8941000234FF046 +:1066900001128F684FF0FF30C4F83438C4F81C285A +:1066A00004EB431201339F42C2F80069C2F8006B49 +:1066B000C2F80809C2F8080BF2D20B68D5F890208E +:1066C000C5F89830636210231361166916F010063E +:1066D000FBD11220FFF7E0F8D4F8003823F4FE6372 +:1066E000C4F80038A36943F4402343F01003A361C6 +:1066F0000923C4F81038C4F814380B4BEB604FF082 +:10670000C043C4F8103B094BC4F8003BC4F81069FF +:10671000C4F80039D5F8983003F1100243F480131F +:10672000C5F89820A362F8BD107F000840800010D3 +:10673000D0F8902090F88A10D2F8003823F4FE6345 +:1067400043EA0113C2F80038704700002DE9F8430E +:1067500000EB8103D0F890500C468046DA680FFABF +:1067600081F94801166806F00306731E022B05EB3B +:1067700041134FF0000194BFB604384EC3F8101B0C +:106780004FF0010104F1100398BF06F1805601FAA1 +:1067900003F3916998BF06F5004600293AD0578A5D +:1067A00004F15801374349016F50D5F81C180B43C9 +:1067B0000021C5F81C382B180127C3F81019A74071 +:1067C0005369611E9BB3138A928B9B08012A88BF71 +:1067D0005343D8F89820981842EA034301F1400245 +:1067E0002146C8F89800284605EB82025360FFF75F +:1067F0007BFE08EB8900C3681B8A43EA8453483454 +:106800001E4364012E51D5F81C381F43C5F81C786F +:10681000BDE8F88305EB4917D7F8001B21F40041C8 +:10682000C7F8001BD5F81C1821EA0303C0E704F1E0 +:106830003F030B4A2846214605EB83035A60FFF7C6 +:1068400053FE05EB4910D0F8003923F40043C0F89B +:106850000039D5F81C3823EA0707D7E70080001075 +:1068600000040002D0F894201268C0F89820FFF7C6 +:106870000FBE00005831D0F8903049015B5813F436 +:10688000004004D013F4001F0CBF02200120704709 +:106890004831D0F8903049015B5813F4004004D0DF +:1068A00013F4001F0CBF02200120704700EB810190 +:1068B000CB68196A0B6813604B685360704700001F +:1068C00000EB810330B5DD68AA691368D36019B99C +:1068D000402B84BF402313606B8A1468D0F890204B +:1068E0001C4402EB4110013C09B2B4FBF3F46343D6 +:1068F000033323F0030343EAC44343F0C043C0F827 +:10690000103B2B6803F00303012B0ED1D2F808389B +:1069100002EB411013F4807FD0F8003B14BF43F02A +:10692000805343F00053C0F8003B02EB4112D2F811 +:10693000003B43F00443C2F8003B30BD2DE9F04179 +:10694000D0F8906005460C4606EB4113D3F8087B5F +:106950003A07C3F8087B08D5D6F814381B0704D5C6 +:1069600000EB8103DB685B689847FA071FD5D6F810 +:106970001438DB071BD505EB8403D968CCB98B69C8 +:10698000488A5A68B2FBF0F600FB16228AB91868EA +:10699000DA6890420DD2121AC3E90024302383F33F +:1069A000118821462846FFF78BFF84F31188BDE844 +:1069B000F081012303FA04F26B8923EA02036B815D +:1069C000CB68002BF3D021462846BDE8F04118479C +:1069D00000EB81034A0170B5DD68D0F890306C6936 +:1069E0002668E66056BB1A444FF40020C2F810092E +:1069F0002A6802F00302012A0AB20ED1D3F808086D +:106A000003EB421410F4807FD4F8000914BF40F067 +:106A1000805040F00050C4F8000903EB4212D2F855 +:106A2000000940F00440C2F800090122D3F83408FC +:106A300002FA01F10143C3F8341870BD19B9402EB0 +:106A400084BF4020206020681A442E8A8419013CAB +:106A5000B4FBF6F440EAC44040F00050C6E7000042 +:106A60002DE9F843D0F8906005460C464F0106EB3F +:106A70004113D3F8088918F0010FC3F808891CD016 +:106A8000D6F81038DB0718D500EB8103D3F80CC01B +:106A9000DCF81430D3F800E0DA68964530D2A2EB87 +:106AA0000E024FF000091A60C3F80490302383F3FC +:106AB0001188FFF78DFF89F3118818F0800F1DD022 +:106AC000D6F834380126A640334217D005EB8403AC +:106AD0000134D5F89050D3F80CC0E4B22F44DCF860 +:106AE000142005EB0434D2F800E05168714514D34A +:106AF000D5F8343823EA0606C5F83468BDE8F883CB +:106B0000012303FA01F2038923EA02030381DCF87B +:106B10000830002BD1D09847CFE7AEEB0103BCF88B +:106B20001000834228BF0346D7F8180980B2B3EBA0 +:106B3000800FE3D89068A0F1040959F8048FC4F8D5 +:106B40000080A0EB09089844B8F1040FF5D8184468 +:106B50000B4490605360C8E72DE9F84FD0F890508F +:106B600004466E69AB691E4016F480586E6103D00E +:106B7000BDE8F84FFEF7B8BB002E12DAD5F8003E9C +:106B80009B0705D0D5F8003E23F00303C5F8003E6F +:106B9000D5F80438204623F00103C5F80438FEF781 +:106BA000D1FB370505D52046FFF772FC2046FEF7DE +:106BB000B7FBB0040CD5D5F8083813F0060FEB6816 +:106BC00023F470530CBF43F4105343F4A053EB6011 +:106BD00031071BD56368DB681BB9AB6923F0080379 +:106BE000AB612378052B0CD1D5F8003E9A0705D070 +:106BF000D5F8003E23F00303C5F8003E2046FEF71B +:106C0000A1FB6368DB680BB120469847F30200F1F3 +:106C1000BA80B70226D5D4F8909000274FF0010A29 +:106C200009EB4712D2F8003B03F44023B3F5802F61 +:106C300011D1D2F8003B002B0DDA62890AFA07F372 +:106C400022EA0303638104EB8703DB68DB6813B18B +:106C50003946204698470137D4F89430FFB29B68F4 +:106C60009F42DDD9F00619D5D4F89000026AC2F32C +:106C70000A1702F00F0302F4F012B2F5802F00F0B1 +:106C8000CA80B2F5402F09D104EB8303002200F53E +:106C90008050DB681B6A974240F0B0803003D5F823 +:106CA000185835D5E90303D500212046FFF746FEE5 +:106CB000AA0303D501212046FFF740FE6B0303D54D +:106CC00002212046FFF73AFE2F0303D50321204679 +:106CD000FFF734FEE80203D504212046FFF72EFE1D +:106CE000A90203D505212046FFF728FE6A0203D535 +:106CF00006212046FFF722FE2B0203D5072120465E +:106D0000FFF71CFEEF0103D508212046FFF716FE12 +:106D1000700340F1A780E90703D500212046FFF763 +:106D20009FFEAA0703D501212046FFF799FE6B07B6 +:106D300003D502212046FFF793FE2F0703D5032139 +:106D40002046FFF78DFEEE0603D504212046FFF70F +:106D500087FEA80603D505212046FFF781FE6906B8 +:106D600003D506212046FFF77BFE2A0603D507211F +:106D70002046FFF775FEEB0574D520460821BDE8D7 +:106D8000F84FFFF76DBED4F890904FF0000B4FF026 +:106D9000010AD4F894305FFA8BF79B689F423FF664 +:106DA00038AF09EB4713D3F8002902F44022B2F5BB +:106DB000802F20D1D3F80029002A1CDAD3F800292B +:106DC00042F09042C3F80029D3F80029002AFBDBE7 +:106DD0003946D4F89000FFF787FB22890AFA07F3B7 +:106DE00022EA0303238104EB8703DB689B6813B16A +:106DF0003946204698470BF1010BCAE7910701D1AC +:106E0000D0F80080072A02F101029CBF03F8018B31 +:106E10004FEA18283FE704EB830300F58050DA6857 +:106E2000D2F818C0DCF80820DCE9001CA1EB0C0C3F +:106E300000218F4208D1DB689B699A683A449A60C6 +:106E40005A683A445A6029E711F0030F01D1D0F88B +:106E500000808C4501F1010184BF02F8018B4FEAEB +:106E60001828E6E7BDE8F88F08B50348FFF774FE79 +:106E7000BDE80840FDF7BEBAF886002008B5034813 +:106E8000FFF76AFEBDE80840FDF7B4BA948700201A +:106E9000D0F8903003EB4111D1F8003B43F40013DC +:106EA000C1F8003B70470000D0F8903003EB41116F +:106EB000D1F8003943F40013C1F8003970470000DD +:106EC000D0F8903003EB4111D1F8003B23F40013CC +:106ED000C1F8003B70470000D0F8903003EB41113F +:106EE000D1F8003923F40013C1F8003970470000CD +:106EF00030B50433039C0172002104FB0325C160FB +:106F0000C0E90653049B0363059BC0E90000C0E988 +:106F10000422C0E90842C0E90A11436330BD000001 +:106F20000022416AC260C0E90411C0E90A226FF080 +:106F30000101FEF721BD0000D0E90432934201D1E6 +:106F4000C2680AB9181D70470020704703691960AC +:106F50000021C2680132C260C2691344826993424F +:106F6000036124BF436A0361FEF7FABC38B50446E7 +:106F70000D46E3683BB162690020131D1268A362ED +:106F80001344E36207E0237A33B929462046FEF72B +:106F9000D7FC0028EDDA38BD6FF00100FBE70000F8 +:106FA000C368C269013BC360436913448269934269 +:106FB000436124BF436A436100238362036B03B1CF +:106FC0001847704770B53023044683F31188866AEA +:106FD0003EB9FFF7CBFF054618B186F31188284666 +:106FE00070BDA36AE26A13F8015B9342A36202D305 +:106FF0002046FFF7D5FF002383F31188EFE7000059 +:107000002DE9F84F04460E46174698464FF03009D2 +:1070100089F311880025AA46D4F828B0BBF1000FE7 +:1070200009D141462046FFF7A1FF20B18BF311881B +:107030002846BDE8F88FD4E90A12A7EB050B521ACF +:10704000934528BF9346BBF1400F1BD9334601F14E +:10705000400251F8040B914243F8040BF9D1A36AA2 +:10706000403640354033A362D4E90A239A4202D322 +:107070002046FFF795FF8AF31188BD42D8D289F3E5 +:107080001188C9E730465A46FAF784FCA36A5E4481 +:107090005D445B44A362E7E710B5029C04330172D0 +:1070A00003FB0421C460C0E906130023C0E90A33CE +:1070B000039B0363049BC0E90000C0E90422C0E90C +:1070C0000842436310BD0000026A6FF00101C26014 +:1070D000426AC0E904220022C0E90A22FEF74CBC41 +:1070E000D0E904239A4201D1C26822B9184650F867 +:1070F000043B0B60704700231846FAE7C368002181 +:10710000C2690133C3604369134482699342436196 +:1071100024BF436A4361FEF723BC000038B5044630 +:107120000D46E3683BB1236900201A1DA262E269A3 +:107130001344E36207E0237A33B929462046FEF779 +:10714000FFFB0028EDDA38BD6FF00100FBE700001F +:1071500003691960C268013AC260C2691344826956 +:107160009342036124BF436A036100238362036B7C +:1071700003B118477047000070B530230D46044630 +:10718000114683F31188866A2EB9FFF7C7FF10B145 +:1071900086F3118870BDA36A1D70A36AE26A013389 +:1071A0009342A36204D3E16920460439FFF7D0FF7C +:1071B000002080F31188EDE72DE9F84F04460D46D5 +:1071C000904699464FF0300A8AF311880026B3465C +:1071D000A76A4FB949462046FFF7A0FF20B187F3C1 +:1071E00011883046BDE8F88FD4E90A073A1AA8EBAF +:1071F0000607974228BF1746402F1BD905F14003C9 +:1072000055F8042B9D4240F8042BF9D1A36A40366F +:107210004033A362D4E90A239A4204D3E1692046A9 +:107220000439FFF795FF8BF311884645D9D28AF3CD +:107230001188CDE729463A46FAF7ACFBA36A3D44EC +:107240003E443B44A362E5E7D0E904239A4217D1C8 +:10725000C3689BB1836A8BB1043B9B1A0ED0136049 +:10726000C368013BC360C3691A4483699A420261DF +:1072700024BF436A036100238362012318467047D9 +:107280000023FBE700F024B9014B586A704700BFA8 +:10729000000C0040034B002258631A610222DA609E +:1072A000704700BF000C0040014B0022DA607047BD +:1072B000000C0040014B5863704700BF000C0040B9 +:1072C000FEE7000070B51B4B0025044686B05860F1 +:1072D0000E4685620163FDF765F804F11003A560B1 +:1072E000E562C4E904334FF0FF33C4E90044C4E964 +:1072F0000635FFF7C9FF2B46024604F1340120464C +:10730000C4E9082380230C4A2565FEF7CFFA012340 +:107310000A4AE06000920375684672680192B2689A +:10732000CDE90223064BCDE90435FEF7E7FA06B0B6 +:1073300070BD00BFB06B00204C7F0008517F00087B +:10734000C1720008024AD36A1843D062704700BF76 +:10735000486900204B6843608B688360CB68C360DA +:107360000B6943614B6903628B6943620B6803607D +:107370007047000008B53C4B40F2FF713B48D3F822 +:1073800088200A43C3F88820D3F8882022F4FF62BB +:1073900022F00702C3F88820D3F88820D3F8E02031 +:1073A0000A43C3F8E020D3F808210A43C3F80821B0 +:1073B0002F4AD3F808311146FFF7CCFF00F5806063 +:1073C00002F11C01FFF7C6FF00F5806002F13801F1 +:1073D000FFF7C0FF00F5806002F15401FFF7BAFF2C +:1073E00000F5806002F17001FFF7B4FF00F58060E6 +:1073F00002F18C01FFF7AEFF00F5806002F1A801F9 +:10740000FFF7A8FF00F5806002F1C401FFF7A2FFBB +:1074100000F5806002F1E001FFF79CFF00F580605D +:1074200002F1FC01FFF796FF02F58C7100F5806018 +:10743000FFF790FF00F018F90E4BD3F8902242F0BE +:107440000102C3F89022D3F8942242F00102C3F85B +:1074500094220522C3F898204FF06052C3F89C2074 +:10746000054AC3F8A02008BD004402580000025895 +:10747000587F000800ED00E01F00080308B500F089 +:10748000D5FAFEF7E1F90F4BD3F8DC2042F04002C9 +:10749000C3F8DC20D3F8042122F04002C3F8042111 +:1074A000D3F80431084B1A6842F008021A601A68CF +:1074B00042F004021A60FEF72FFFBDE80840FEF715 +:1074C00057BC00BF00440258001802487047000033 +:1074D000114BD3F8E82042F00802C3F8E820D3F8B3 +:1074E000102142F00802C3F810210C4AD3F81031E1 +:1074F000D36B43F00803D363C722094B9A624FF062 +:10750000FF32DA6200229A615A63DA605A6001221D +:107510005A611A60704700BF004402580010005CB6 +:10752000000C0040094A08B51169D3680B40D9B274 +:107530009B076FEA0101116107D5302383F311889E +:10754000FEF7A8F9002383F3118808BD000C004062 +:10755000064BD3F8DC200243C3F8DC20D3F8042127 +:107560001043C3F80401D3F80431704700440258B3 +:1075700008B53C4B4FF0FF31D3F8802062F0004259 +:10758000C3F88020D3F8802002F00042C3F88020A6 +:10759000D3F88020D3F88420C3F88410D3F8842053 +:1075A0000022C3F88420D3F88400D86F40F0FF4055 +:1075B00040F4FF0040F4DF4040F07F00D867D86F10 +:1075C00020F0FF4020F4FF0020F4DF4020F07F0097 +:1075D000D867D86FD3F888006FEA40506FEA5050F0 +:1075E000C3F88800D3F88800C0F30A00C3F8880005 +:1075F000D3F88800D3F89000C3F89010D3F8900027 +:10760000C3F89020D3F89000D3F89400C3F89410F6 +:10761000D3F89400C3F89420D3F89400D3F89800DA +:10762000C3F89810D3F89800C3F89820D3F89800BE +:10763000D3F88C00C3F88C10D3F88C00C3F88C20DE +:10764000D3F88C00D3F89C00C3F89C10D3F89C109E +:10765000C3F89C20D3F89C30FDF74EF8BDE80840F5 +:1076600000F0B8B90044025808B50122534BC3F8E2 +:107670000821534BD3F8F42042F00202C3F8F4205F +:10768000D3F81C2142F00202C3F81C210222D3F8D5 +:107690001C314C4BDA605A689104FCD54A4A1A6096 +:1076A00001229A60494ADA6000221A614FF440428E +:1076B0009A61444B9A699204FCD51A6842F480722C +:1076C0001A603F4B1A6F12F4407F04D04FF480329F +:1076D0001A6700221A671A6842F001021A60384BD2 +:1076E0001A685007FCD500221A611A6912F0380294 +:1076F000FBD1012119604FF0804159605A67344A2B +:10770000DA62344A1A611A6842F480321A602C4BE9 +:107710001A689103FCD51A6842F480521A601A68FC +:107720009204FCD52C4A2D499A6200225A631963AF +:1077300001F57C01DA6301F5E77199635A64284A1F +:107740001A64284ADA621A6842F0A8521A601C4B7E +:107750001A6802F02852B2F1285FF9D148229A61E2 +:107760004FF48862DA6140221A621F4ADA641F4AC3 +:107770001A651F4A5A651F4A9A6532231E4A1360CA +:10778000136803F00F03022BFAD10D4A136943F07B +:1077900003031361136903F03803182BFAD14FF078 +:1077A0000050FFF7D5FE4FF08040FFF7D1FE4FF0BD +:1077B0000040BDE80840FFF7CBBE00BF008000518D +:1077C000004402580048025800C000F002000001C6 +:1077D0000000FF0100889008322060006302090168 +:1077E000470E0508DD0BBF0120000020000001103E +:1077F0000910E00000010110002000524FF0B042DB +:1078000008B5D2F8883003F00103C2F8883023B1FC +:10781000044A13680BB150689847BDE80840FCF76C +:10782000E9BD00BF488800204FF0B04208B5D2F84B +:10783000883003F00203C2F8883023B1044A936809 +:107840000BB1D0689847BDE80840FCF7D3BD00BF36 +:10785000488800204FF0B04208B5D2F8883003F0D5 +:107860000403C2F8883023B1044A13690BB150698C +:107870009847BDE80840FCF7BDBD00BF4888002020 +:107880004FF0B04208B5D2F8883003F00803C2F8D0 +:10789000883023B1044A93690BB1D0699847BDE899 +:1078A0000840FCF7A7BD00BF488800204FF0B04259 +:1078B00008B5D2F8883003F01003C2F8883023B13D +:1078C000044A136A0BB1506A9847BDE80840FCF7B8 +:1078D00091BD00BF488800204FF0B04310B5D3F8E9 +:1078E000884004F47872C3F88820A30604D5124AAD +:1078F000936A0BB1D06A9847600604D50E4A136BA1 +:107900000BB1506B9847210604D50B4A936B0BB112 +:10791000D06B9847E20504D5074A136C0BB1506C45 +:107920009847A30504D5044A936C0BB1D06C9847D3 +:10793000BDE81040FCF75EBD488800204FF0B04322 +:1079400010B5D3F8884004F47C42C3F8882062055F +:1079500004D5164A136D0BB1506D9847230504D515 +:10796000124A936D0BB1D06D9847E00404D50F4ACD +:10797000136E0BB1506E9847A10404D50B4A936E59 +:107980000BB1D06E9847620404D5084A136F0BB14F +:10799000506F9847230404D5044A936F0BB1D06FFE +:1079A0009847BDE81040FCF725BD00BF488800207F +:1079B00008B50348FDF708F8BDE80840FCF71ABD14 +:1079C000D864002008B5FFF7ADFDBDE80840FCF71E +:1079D00011BD0000062108B50846FDF77BF8062119 +:1079E0000720FDF777F806210820FDF773F8062138 +:1079F0000920FDF76FF806210A20FDF76BF8062134 +:107A00001720FDF767F806212820FDF763F8092104 +:107A10007A20FDF75FF807213220FDF75BF80C2193 +:107A20005220BDE80840FDF755B8000008B5FFF743 +:107A30009FFD00F00DF8FDF70BFAFDF7E3FBFDF7F6 +:107A4000B5FAFFF743FDBDE80840FFF71BBC000097 +:107A50000023054A19460133102BC2E9001102F137 +:107A60000802F8D1704700BF488800200B46014645 +:107A7000184600F003B8000000F00EB810B5054C31 +:107A800013462CB10A4601460220AFF3008010BD18 +:107A90002046FCE700000000024B01461868FEF794 +:107AA0005FBB00BF6C23002010B501390244904237 +:107AB00001D1002005E0037811F8014FA34201D065 +:107AC000181B10BD0130F2E72DE9F041A3B1C91A2E +:107AD00017780144044603F1FF3C8C42204601D94B +:107AE000002009E00578BD4204F10104F5D10CEB5A +:107AF0000405D618A54201D1BDE8F08115F8018D25 +:107B000016F801EDF045F5D0E7E70000034611F85F +:107B1000012B03F8012B002AF9D170476F72672EF1 +:107B20006172647570696C6F742E437562654F7213 +:107B3000616E67652D7065726970680053544D33CE +:107B40003248373F3F3F0053544D33324837337844 +:107B50002F3732780053544D3332483734332F3770 +:107B600035332F373530000001105A00031059000B +:107B7000012058000320560040A2E4F164689106F9 +:107B80000041A3E5F26569920700000043414E46BB +:107B90004449666163653A204D657373616765208A +:107BA00052414D204F766572666C6F772100000060 +:107BB0004261642043414E496661636520696E6499 +:107BC00065782E00000100000001FF0000A00040C9 +:107BD00000A400400000000000000000C92A0008C6 +:107BE0005123000851320008C1230008CD230008AA +:107BF000E527000845250008892300088D23000893 +:107C0000652300084D230008A12700087123000800 +:107C1000B93300087D2300087527000801040E050C +:107C2000054B02020E05054B04010E05054B05012F +:107C30000B04044B08010603034600001000024039 +:107C4000080002400008024000000B00280002402B +:107C5000080002400408024006010C0040000240F7 +:107C6000080002400808024010020D0058000240BF +:107C7000080002400C08024016030E00700002408B +:107C80000C0002401008024000040F00880002406F +:107C90000C0002401408024006051000A00002403B +:107CA0000C0002401808024010061100B800024003 +:107CB0000C0002401C08024016072F00100402406E +:107CC000080402402008024000083800280402404E +:107CD000080402402408024006093900400402401A +:107CE0000804024028080240100A3A0058040240E2 +:107CF000080402402C080240160B3B0070040240AE +:107D00000C04024030080240000C3C008804024091 +:107D10000C04024034080240060D4400A004024056 +:107D20000C04024038080240100E4500B80402401E +:107D30000C0402403C080240160F4600009600006A +:107D40000000000000000000000000000000000033 +:107D50000000000000000000114E0008FD4D00086A +:107D6000394E0008254E0008314E00081D4E00080F +:107D7000094E0008F54D0008454E000800000000BF +:107D8000294F0008154F0008514F00083D4F0008CB +:107D9000494F0008354F0008214F00080D4F0008DB +:107DA0005D4F00080000000001000000000000001E +:107DB00063300000B07D0008A0690020B06B002097 +:107DC0004172647550696C6F740025424F41524492 +:107DD000252D424C002553455249414C25000000B9 +:107DE000020000000000000049510008B9510008DD +:107DF00040004000608400207084002002000000E9 +:107E00000000000003000000000000000152000814 +:107E1000000000001000000080840020000000002E +:107E20000100000000000000F886002001010200AF +:107E30000D5D00081D5C0008B95C00089D5C000831 +:107E400043000000487E000809024300020100C010 +:107E5000320904000001020201000524001001059E +:107E60002401000104240202052406000107058202 +:107E7000030800FF09040100020A000000070501D1 +:107E800002400000070581024000000012000000CF +:107E9000947E0008120110010200004009124157AF +:107EA00000020102030100000403090425424F41BE +:107EB0005244250030313233343536373839414277 +:107EC00043444546000000000001002000FF01007F +:107ED0000200000000000030000004000800000064 +:107EE000000000240000080004000000000400005E +:107EF00000FC0000020000000000043000800000D0 +:107F0000080000000000003800000100010000002F +:107F1000000000005D53000815560008C156000817 +:107F20004000400030880020308800200100000020 +:107F30004088002080000000400100000800000090 +:107F40000001000000100000080000006D61696E73 +:107F50000069646C650000000000802A00000000D9 +:107F6000AAAAAAAA00000024FFFF00000000000047 +:107F700000A00A000021000200000000AAAAAAAA8C +:107F800000000000FFFF00000000000900000900E1 +:107F90001400005400000000AAAAAAAA1400005469 +:107FA000FFFF000000000000000000000A40100079 +:107FB00000000000AAAA8AAA00401000FFFF0000EB +:107FC0009900000000000000008102000000000095 +:107FD000AAAAAAAA00410100FFFF00000000007049 +:107FE000070000000000000000000000AAAAAAAAE2 +:107FF00000000000FFFF0000000000000000000083 +:108000000000000000000000AAAAAAAA00000000C8 +:10801000FFFF000000000000000000000000000062 +:1080200000000000AAAAAAAA00000000FFFF0000AA +:108030000000000000000000000000000000000040 +:10804000AAAAAAAA00000000FFFF0000000000008A +:10805000000000000000000000000000AAAAAAAA78 +:1080600000000000FFFF0000000000000000000012 +:108070000000000000000000AAAAAAAA0000000058 +:10808000FFFF0000000000000000000000000000F2 +:10809000780500000000000000001E000000000045 +:1080A000FE2A0100D2040000FF000000B86B00208F +:1080B000D8640020000000003C7B0008830400001E +:1080C000477B000850040000557B00080096000024 +:1080D00000000800960000000008000004000000F6 +:1080E000A87E000800000000000000000000000062 +:1080F00000000000000000000000000070230020CD +:10810000000000000000000000000000000000006F +:10811000000000000000000000000000000000005F +:10812000000000000000000000000000000000004F +:10813000000000000000000000000000000000003F +:10814000000000000000000000000000000000002F +:10815000000000000000000000000000000000001F :00000001FF diff --git a/Tools/bootloaders/CubePilot-CANMod_bl.bin b/Tools/bootloaders/CubePilot-CANMod_bl.bin index 8530e9ba2f9d57..164019d4b6aa9d 100755 Binary files a/Tools/bootloaders/CubePilot-CANMod_bl.bin and b/Tools/bootloaders/CubePilot-CANMod_bl.bin differ diff --git a/Tools/bootloaders/CubePilot-CANMod_bl.hex b/Tools/bootloaders/CubePilot-CANMod_bl.hex index e8bf2bd2d4d8ea..79443030873fff 100644 --- a/Tools/bootloaders/CubePilot-CANMod_bl.hex +++ b/Tools/bootloaders/CubePilot-CANMod_bl.hex @@ -1,1996 +1,2053 @@ :020000040800F2 -:1000000000060020F5050008B53400086D3400082E -:10001000953400086D3400088D340008F705000899 -:10002000F7050008F7050008F705000899440008DF -:10003000F7050008F7050008F7050008F7050008B0 -:10004000F7050008F7050008F7050008F7050008A0 -:10005000F7050008F70500086974000895740008A2 -:10006000C1740008ED74000819750008F705000850 -:10007000F7050008F7050008F7050008F705000870 -:10008000F7050008F7050008F70500084D340008DB -:10009000F70500085D340008F705000845750008FD -:1000A000F7050008F7050008F7050008F705000840 -:1000B000F7050008F7050008F7050008F705000830 -:1000C000F7050008F7050008F7050008F705000820 -:1000D000F7050008F7050008F7050008F705000810 -:1000E000A9750008F7050008F7050008F7050008DE -:1000F000F7050008F7050008F7050008F7050008F0 -:10010000F7050008F705000831760008F705000834 -:10011000F7050008F7050008F7050008F7050008CF -:10012000F7050008F7050008F7050008F7050008BF -:10013000F7050008F7050008F7050008F7050008AF -:10014000F7050008F7050008F7050008F70500089F -:10015000F7050008F7050008F7050008F70500088F -:10016000F7050008F7050008F7050008F70500087F -:10017000F70500081D6B0008F7050008F7050008E3 -:10018000F7050008F70500081D760008F7050008C8 -:10019000F7050008F7050008F7050008F70500084F -:1001A000F7050008F7050008F7050008F70500083F -:1001B000F7050008F7050008F7050008F70500082F -:1001C000F7050008F7050008F7050008F70500081F -:1001D000F7050008096B0008F7050008F705000897 -:1001E000F7050008F7050008F7050008F7050008FF -:1001F000F7050008F7050008F7050008F7050008EF -:10020000F7050008F7050008F7050008F7050008DE -:10021000F7050008F7050008F7050008F7050008CE -:10022000F7050008F7050008F7050008F7050008BE -:10023000F7050008F7050008F7050008F7050008AE -:10024000F7050008F7050008F7050008F70500089E -:10025000F7050008F7050008F7050008F70500088E -:10026000F7050008F7050008F7050008F70500087E -:10027000F7050008F7050008F7050008F70500086E -:10028000F7050008F7050008F7050008F70500085E -:10029000F7050008F7050008F7050008F70500084E -:1002A000F7050008F7050008F7050008F70500083E -:1002B000F7050008F7050008F7050008F70500082E -:1002C000F7050008F7050008F7050008F70500081E -:1002D000F7050008F7050008F7050008F70500080E -:1002E000BD19000800000000000000000000000030 -:1002F00053B94AB9002908BF00281CBF4FF0FF318D -:100300004FF0FF3000F074B9ADF1080C6DE904CE88 -:1003100000F006F8DDF804E0DDE9022304B07047E0 -:100320002DE9F047089D04468E46002B4DD18A42A8 -:10033000944669D9B2FA82F252B101FA02F3C2F1DB -:10034000200120FA01F10CFA02FC41EA030E94406C -:100350004FEA1C48210CBEFBF8F61FFA8CF708FB8D -:1003600016E341EA034306FB07F199420AD91CEB65 -:10037000030306F1FF3080F01F81994240F21C8197 -:10038000023E63445B1AA4B2B3FBF8F008FB1033DF -:1003900044EA034400FB07F7A7420AD91CEB040414 -:1003A00000F1FF3380F00A81A74240F207816444E4 -:1003B000023840EA0640E41B00261DB1D440002369 -:1003C000C5E900433146BDE8F0878B4209D9002DCD -:1003D00000F0EF800026C5E9000130463146BDE857 -:1003E000F087B3FA83F6002E4AD18B4202D38242C1 -:1003F00000F2F980841A61EB030301209E46002D70 -:10040000E0D0C5E9004EDDE702B9FFDEB2FA82F2C4 -:10041000002A40F09280A1EB0C014FEA1C471FFA22 -:100420008CFE0126200CB1FBF7F307FB131140EA09 -:1004300001410EFB03F0884208D91CEB010103F1D6 -:10044000FF3802D2884200F2CB804346091AA4B298 -:10045000B1FBF7F007FB101144EA01440EFB00FE6C -:10046000A64508D91CEB040400F1FF3102D2A645D1 -:1004700000F2BB800846A4EB0E0440EA03409CE770 -:10048000C6F12007B34022FA07FC4CEA030C20FA1D -:1004900007F401FA06F31C43F9404FEA1C4900FA3D -:1004A00006F3B1FBF9F8200C1FFA8CFE09FB1811BA -:1004B00040EA014108FB0EF0884202FA06F20BD92D -:1004C0001CEB010108F1FF3A80F08880884240F27D -:1004D0008580A8F102086144091AA4B2B1FBF9F0C1 -:1004E00009FB101144EA014100FB0EFE8E4508D9BC -:1004F0001CEB010100F1FF346CD28E456AD9023841 -:10050000614440EA0840A0FB0294A1EB0E01A14225 -:10051000C846A64656D353D05DB1B3EB080261EB93 -:100520000E0101FA07F722FA06F3F1401F43C5E96D -:10053000007100263146BDE8F087C2F12003D840A3 -:100540000CFA02FC21FA03F3914001434FEA1C47E5 -:100550001FFA8CFEB3FBF7F007FB10360B0C43EAD7 -:10056000064300FB0EF69E4204FA02F408D91CEB87 -:10057000030300F1FF382FD29E422DD90238634485 -:100580009B1B89B2B3FBF7F607FB163341EA034125 -:1005900006FB0EF38B4208D91CEB010106F1FF3874 -:1005A00016D28B4214D9023E6144C91A46EA00466B -:1005B00038E72E46284605E70646E3E61846F8E6FD -:1005C0004B45A9D2B9EB020864EB0C0E0138A3E746 -:1005D0004646EAE7204694E74046D1E7D0467BE727 -:1005E000023B614432E7304609E76444023842E79F -:1005F000704700BF02E000F000F8FEE772B637482F -:1006000080F30888364880F3098836483649086000 -:1006100040F20000CCF200004EF63471CEF2000140 -:100620000860BFF34F8FBFF36F8F40F20000C0F23E -:10063000F0004EF68851CEF200010860BFF34F8FF4 -:10064000BFF36F8F4FF00000E1EE100A4EF63C71E1 -:10065000CEF200010860062080F31488BFF36F8F8C -:1006600005F0D2FC06F0D6FC4FF055301F491B4A6E -:1006700091423CBF41F8040BFAE71D49184A9142E8 -:100680003CBF41F8040BFAE71A491B4A1B4B9A423C -:100690003EBF51F8040B42F8040BF8E7002018495C -:1006A000184A91423CBF41F8040BFAE705F0EAFC16 -:1006B00006F032FD144C154DAC4203DA54F8041B1D -:1006C0008847F9E700F042F8114C124DAC4203DACA -:1006D00054F8041B8847F9E705F0D2BC0006002057 -:1006E000002200200000000808ED00E000000020CB -:1006F00000060020D07B000800220020D02200202D -:10070000D022002080720020E0020008E4020008ED -:10071000E4020008E40200082DE9F04F2DED108AF4 -:10072000C1F80CD0D0F80CD0BDEC108ABDE8F08F29 -:10073000002383F311882846A047002004F04EFFD1 -:10074000FEE704F0A7FE00DFFEE70000F8B501F0C9 -:1007500047F905F0DDFB074605F04CFC0546B8BB44 -:10076000204B9F4234D001339F4234D027F0FF0208 -:100770001D4B9A4232D12E4642F21074F8B200F06C -:100780006DFF00F071FF08B10024264601F02AFD3C -:1007900020B10024032000F07BF8264635B1134B2E -:1007A0009F4203D0002405F01DFC2646002005F0E2 -:1007B000B9FB0EB100F082F801F0C0FA00F088FF3A -:1007C00001F08AF9204600F01DF900F077F8F9E70A -:1007D0002E460024D5E704460126D2E7064641F21C -:1007E0008834CEE7010007B0000008B0263A09B00F -:1007F00008B501F03DF9A0F120035842584108BD69 -:1008000007B541F21203022101A8ADF8043001F04E -:100810004DF903B05DF804FB38B5302383F311883C -:10082000174803680BB104F0A5FF0023154A4FF4E5 -:100830007A71134804F094FF002383F31188124C5B -:10084000236813B12368013B2360636813B16368B5 -:10085000013B63600D4D2B7833B963687BB902208F -:1008600001F0EEF9322363602B78032B07D1636824 -:100870002BB9022001F0E4F94FF47A73636038BDBC -:10088000D022002019080008F0230020E8220020D0 -:10089000084B187003280CD8DFE800F008050208A0 -:1008A000022001F0CBB9022001F0C6B9024B0022B0 -:1008B0005A607047E8220020F0230020F8B501F0CC -:1008C00091FC30B1464B03221A700022454B5A600E -:1008D000F8BD454B454A1C4619680131F8D0043330 -:1008E0009342F9D16268424B9A42F1D9414B9B68DD -:1008F00003F1006303F580239A42E9D205F046FB39 -:1009000005F058FB002001F00DF90220FFF7C0FFB1 -:10091000394B00219A6C99641A6F19671A6FDA6C57 -:10092000D9645A6F59675A6F1A6D19659A6F99672A -:100930009B6F324BD3F8802042F00072C3F88020C6 -:10094000D3F8802022F00072C3F88020D3F88030E2 -:1009500072B64FF0E023C3F8084DD4E90004BFF3AA -:100960004F8FBFF36F8F264AC2F88410BFF34F8FAB -:10097000536923F480335361BFF34F8FD2F8803033 -:1009800043F6E076C3F3C905C3F34E335B0103EAD4 -:10099000060C29464CEA81770139C2F87472F9D203 -:1009A000203B13F1200FF2D1BFF34F8FBFF36F8FB6 -:1009B000BFF34F8FBFF36F8F536923F4003353613D -:1009C0000023C2F85032BFF34F8FBFF36F8F302335 -:1009D00083F31188854680F30888204778E700BFB5 -:1009E000E8220020F0230020000004082000040872 -:1009F000FFFF03080022002000450258004402586F -:100A000000ED00E02DE9F04F93B0B74B2022FF211D -:100A100000900AA89D6801F03BF9B44A1378A3B985 -:100A20000121B34811700360302383F311880368F8 -:100A30000BB104F09FFE0023AE4A4FF47A71AC482C -:100A400004F08EFE002383F31188009B13B1AA4BA0 -:100A5000009A1A60A94A1378032B03D0002313705D -:100A6000A54A53604FF0000A009CD3465646D14633 -:100A7000012001F0E3F824B19F4B1B68002B00F02C -:100A80002C82002000F0F4FF0390039B002B01DA7E -:100A900000F066FE039B002BEDDB012001F0CCF89B -:100AA000039B213B1F2BE3D801A252F823F000BF88 -:100AB000310B0008590B0008ED0B0008710A000803 -:100AC000710A0008710A00087F0C00084F0E000828 -:100AD000690D0008CB0D0008F30D0008190E000881 -:100AE000710A00082B0E0008710A00089D0E00080C -:100AF000D10B0008710A0008E10E00083D0B000848 -:100B0000D10B0008710A0008CB0D0008710A00081B -:100B1000710A0008710A0008710A0008710A0008C9 -:100B2000710A0008710A0008710A0008ED0B00083C -:100B30000220FFF75DFE002840F0F981009B0221B2 -:100B400005A8BAF1000F08BF1C4641F21233ADF8F8 -:100B5000143000F0ABFF8BE74FF47A7000F088FFA1 -:100B6000071EEBDB0220FFF743FE0028E6D0013F23 -:100B7000052F00F2DE81DFE807F0030A0D101336BF -:100B80000523042105A8059300F090FF17E0042138 -:100B90005548F9E704215A48F6E704215948F3E794 -:100BA0004FF01C08404608F1040800F0BDFF042186 -:100BB000059005A800F07AFFB8F12C0FF2D10120C2 -:100BC0004FF0000900FA07F747EA0B0B5FFA8BFBBF -:100BD00001F0AAF826B10BF00B030B2B08BF002481 -:100BE000FFF70EFE44E704214748CDE7002EA5D0CD -:100BF0000BF00B030B2BA1D10220FFF7F9FD0746E9 -:100C000000289BD00120002600F08CFF0220FFF777 -:100C10003FFE1FFA86F8404600F094FF0446B0B14C -:100C2000039940460136A1F140025142514100F082 -:100C3000A1FF0028EDD1BA46044641F21213022169 -:100C400005A83E46ADF8143000F030FF10E7254609 -:100C50000120FFF71DFE244B9B68AB4207D92846B5 -:100C600000F062FF013040F067810435F3E70025B2 -:100C7000224BBA463E461D701F4B5D60A8E7002E12 -:100C80003FF45CAF0BF00B030B2B7FF457AF02204C -:100C9000FFF7FEFD322000F0EBFEB0F10008FFF69A -:100CA0004DAF18F003077FF449AF0F4A08EB050377 -:100CB000926893423FF642AFB8F5807F3FF73EAF70 -:100CC000124BB845019323DD4FF47A7000F0D0FE4B -:100CD0000390039A002AFFF631AF039A0137019B74 -:100CE00003F8012BEDE700BF00220020EC230020D9 -:100CF000D022002019080008F0230020E82200205C -:100D000004220020082200200C220020EC220020D7 -:100D1000C820FFF76DFD074600283FF40FAF1F2DD9 -:100D200011D8C5F120020AAB25F0030084494245E1 -:100D3000184428BF4246019200F084FF019AFF2127 -:100D40007F4800F0A5FF4FEAA803C8F387027C495B -:100D50002846019300F0A4FF064600283FF46DAF3B -:100D6000019B05EB830533E70220FFF741FD0028D7 -:100D70003FF4E4AE00F010FF00283FF4DFAE0027A0 -:100D8000B846704B9B68BB4218D91F2F11D80A9BDD -:100D900001330ED027F0030312AA134453F8203C6A -:100DA00005934046042205A9043701F005FA804660 -:100DB000E7E7384600F0B8FE0590F2E7CDF814807A -:100DC000042105A800F072FE02E70023642104A8B4 -:100DD000049300F061FE00287FF4B0AE0220FFF71C -:100DE00007FD00283FF4AAAE049800F0CBFE059062 -:100DF000E6E70023642104A8049300F04DFE0028D8 -:100E00007FF49CAE0220FFF7F3FC00283FF496AE7F -:100E1000049800F0B9FEEAE70220FFF7E9FC002899 -:100E20003FF48CAE00F0C8FEE1E70220FFF7E0FCE3 -:100E300000283FF483AE05A9142000F0C3FE074646 -:100E40000421049004A800F031FE3946B9E73220AD -:100E500000F00EFE071EFFF671AEBB077FF46EAE0C -:100E6000384A07EB0903926893423FF667AE0220C7 -:100E7000FFF7BEFC00283FF461AE27F003074F44A4 -:100E8000B9453FF4A5AE484609F1040900F04CFE0F -:100E90000421059005A800F009FEF1E74FF47A70EF -:100EA000FFF7A6FC00283FF449AE00F075FE0028CD -:100EB00044D00A9B01330BD008220AA9002000F07D -:100EC000EFFE00283AD02022FF210AA800F0E0FE21 -:100ED000FFF796FC1C4804F087FB13B0BDE8F08FC9 -:100EE000002E3FF42BAE0BF00B030B2B7FF426AE42 -:100EF0000023642105A8059300F0CEFD07460028D5 -:100F00007FF41CAE0220FFF773FC804600283FF4FC -:100F100015AEFFF775FC41F2883004F065FB0598CB -:100F200000F04CFF46463C4600F0FEFEA0E50646BB -:100F30004EE64FF0000901E6BA467EE637467CE60B -:100F4000EC22002000220020A0860100094A49F27C -:100F50006900136899B21B0C00FB013344F2506125 -:100F60001360054B186882B2000C01FB0200186088 -:100F700080B270471422002010220020002110228D -:100F800010B5044600F084FE034B03CB2060616083 -:100F90001868A06010BD00BF00E8F11F2DE9F04106 -:100FA000ADF5507D0D46002140F275126EAC07463E -:100FB00010A80F9100F06CFE4FF4C472002120467F -:100FC00000F066FE0DF13C0802F07CFA4FF47A72F4 -:100FD000264BB0FBF2F0186093E80700022384E888 -:100FE00007000DF5ED702382FFF7C8FF43F204738D -:100FF0001F4907A8238406F0BFFB1E230DF2EB2236 -:101000000DF1340C84F8323107AB1E46083203CEA2 -:10101000664542F8080C42F8041C3346F5D13068A6 -:10102000414610602046B3889380012200F0E8FE1C -:10103000002380B2E97E0393AB7E029305F119038E -:1010400001930123009307A3D3E90023CDE9048092 -:10105000384602F0F5FD0DF5507DBDE8F08100BF8A -:10106000AFF300809E6AC421818A46EEF8230020F7 -:10107000887700082DE9F0412C4CDAB080460D4607 -:10108000237A5BBB27A9284600F0C8FF0746002843 -:1010900042D19DF89D60C82E3ED801464FF4A6620D -:1010A000204600F0F5FD4FF4807332460DF19E01AD -:1010B000C4F8F8314FF4007304F109002644C4F871 -:1010C0000C334FF44073C4F8203400F0BBFD9DF89E -:1010D0009C30777223720BB9EB7E237206AC8122AF -:1010E000002127A800F0D4FD0122214627A800F006 -:1010F000D1FF002380B2E97E0393AB7E029305F11A -:10110000190301932823CDE904400093404605A329 -:10111000D3E9002302F094FD5AB0BDE8F08100BF8E -:10112000AFF3008026417272DF25D7B7F048002068 -:10113000F0B5254E4FF48A75F1B0002405FB00652B -:1011400096F8D830D822214685F8DC303AA885F8C0 -:10115000E84006AF00F09CFD06F1090000F090FDAC -:10116000D5F8E430C2B206F109018DF8F0000DF1B6 -:10117000F100CDE93A3400F065FD394601223AA884 -:1011800000F0B4FF082380B2317ACDE90470012762 -:101190000E48CDE9023706F1D803019330230093BE -:1011A00007A3D3E9002302F04BFDA04206DD02F0C5 -:1011B00089F9C5F8E000384671B0F0BD2046FBE77C -:1011C00078F6339F93CACD8DF0480020103400206C -:1011D0002DE9F0411D4D86B01D4E1E4F284602F0F0 -:1011E0005BFD034658B30024DFF86C80ADF8144073 -:1011F0000294CDE90344027B8DF8142003AA996878 -:10120000406803C21B6843F00043029302F05CF99C -:1012100082190094384641F1000302A901F0E4F973 -:10122000A04205DD284602F03BFD88F80040D5E7E6 -:1012300098F80030072B05D8013388F8003006B045 -:10124000BDE8F081014802F02BFDF8E710340020E2 -:1012500040420F0040340020254E002070B50D465E -:1012600014461E4602F048FC50B9022E10D1012C43 -:101270000ED112A3D3E900230120C5E9002307E022 -:10128000282C10D005D8012C09D0052C0FD0002017 -:1012900070BD302CFBD10BA3D3E90023ECE70BA3EB -:1012A000D3E90023E8E70BA3D3E90023E4E70BA38A -:1012B000D3E90023E0E700BFAFF30080401DA12089 -:1012C00026812A0B78F6339F93CACD8D9E6AC4215E -:1012D000818A46EE26417272DF25D7B7F017304A71 -:1012E00039059E5638B505460E4C0021013500F0F3 -:1012F00041FCA4F82C55B4F82C0500F023FC78B17F -:10130000B4F82C0500F02EFC014648B9B4F82C05C1 -:1013100000F030FCB4F82C350133A4F82C35EAE7A2 -:1013200038BD00BFF04800200A4B0B4A10B51A60C8 -:1013300003F5805393F848203AB95C6C2CB12046F1 -:1013400000F0CEFF204606F0CDF90448BDE810407D -:1013500000F0C6BF403400203878000870440020F8 -:101360002DE9F04F8FB005460C4600AF02F0C4FBEC -:10137000002849D1237E022B1BD1E38A012B18D1EF -:1013800002F0A0F80646FFF7E1FD03464FF4C870EF -:1013900006F51676DFF8C082B3FBF0F202FB1033DD -:1013A00016FA83F3C8F80030E37E33B9A34B00226A -:1013B0001A703C37BD46BDE8F08F07F12401204686 -:1013C00000F0EAFD0028F4D107F11400FFF7D6FD84 -:1013D00097F8264007F1140107F12700224606F08E -:1013E00099F90028E2D10F2C08D8944B1C70D8F83A -:1013F0000030A3F51673C8F80030DAE797F8241028 -:10140000284602F071FBD4E7E38A282B2BD010D8B2 -:10141000012B23D0052BCCD1BFF34F8F8849894BAB -:10142000CA6802F4E0621343CB60BFF34F8F00BF82 -:10143000FDE7302BBDD1844EE17E327A9142B8D1A6 -:10144000607E3146002291F8DC50854200F0A58094 -:10145000013201F58A71042AF5D1AAE7214628460E -:10146000FFF79CFDA5E721462846FFF703FEA0E70E -:10147000B2F8EC507B6005F103094FEA99094FEA95 -:101480008902D11DC908A8EBC10300219D46EB4686 -:10149000584600F0FDFB04F1EE012A46584631445F -:1014A00000F0D0FB7B6813B9012000F03BFB96F8FD -:1014B000D20000F047FB044630B9307200F06CFBFC -:1014C000204600F02FFBB1E0D6F8D4203AB996F8C8 -:1014D000D200B6F82C25824201D8FFF703FFD6F8D8 -:1014E000D4202A44944208D296F8D200B6F82C258B -:1014F0000130824201D8FFF7F5FE5FFA89F25946C2 -:10150000706800F0CDFB08B9C54679E0726896F8BE -:10151000D2002A447260D6F8D42005EB0209C6F83E -:10152000D49000F00FFB814509D396F8D220D6F86D -:10153000D4000132001B86F8D220C6F8D400FF2D5B -:101540000FD80024347200F027FB204600F0EAFA9E -:1015500000F048FE3D4B188108B9FFF7AFF9C546CA -:1015600027E7BB6896F8D9000AFB0362FB68D2F84C -:10157000E41082F8E83001F58061C2F8E030C2F88A -:10158000E410FFF7D5FDFFF723FE96F8D9200132CE -:1015900002F0030286F8D920B6E74FF48A7A204693 -:1015A0000AFB02F505F1EA01314400F0CBFDF860D9 -:1015B00000287FF4FEAE0122354485F8E82001F0D2 -:1015C00081FFD5F8E020D6ED007A801A40F6B832D7 -:1015D000B8EE677ADFED1E6A192838BF19209042ED -:1015E00028BF104607EE900AF8EEE77A67EEA67A73 -:1015F000DFED186AE7EE267AFCEEE77AC6ED007AB0 -:1016000096F8D930BB60BA6873680AFB02F43219E5 -:1016100092F8E81059B1D2F8E410E8468B423FF452 -:1016200027AF002182F8E810C2F8E010C5467368C1 -:10163000064A9B0A01331381BBE600BF0934002030 -:1016400000ED00E00400FA05F0480020F823002037 -:10165000CDCCCC3D6666663F0C340020014B187043 -:10166000704700BF0424002038B54FF04054144B9D -:1016700022689A4221D1627D0025124B12481A70CD -:10168000C922237D0930114900F8013C4FF48073D1 -:10169000C0F8DB50C0F8EF314FF40073C0F80333EB -:1016A0004FF44073C0F8173400F0CCFAE02229461A -:1016B000204600F0EDFA012038BD0020FCE700BF15 -:1016C0009AAD44C504240020F048002016000030E4 -:1016D00037B500F087FD194D0223002218492881F3 -:1016E0006B710123174801F0D9FA002316494FF412 -:1016F00080520193154B16480093164B02F0CCF91B -:10170000154B197811B1124802F0EEF901F0DAFE2A -:101710000446FFF71BFC4FF4C873B0FBF3F202FB67 -:10172000130304F5167010FA83F00C4B186004F0E4 -:1017300061FC08B10F232B8103B030BDF8230020DA -:1017400040420F0040340020082400205D120008B1 -:101750001034002061130008042400200C34002001 -:101760002DE9F04F8C4C2DED028B85A7D7E9006752 -:1017700095B00FF21429D9E900899FED858BFFF709 -:1017800027FD0DAD0023DFF824B20C93ADF83C30FB -:101790000D936B6000234FF0010A0DF1250209A99A -:1017A00058468DF825308DF824A08DED008B01F082 -:1017B000F1FD9DF824200023002A40F0AE80204651 -:1017C00002F09AF90546002847D1DFF8E4B101F0AC -:1017D00079FEDBF8003098423FD301F073FE0790AA -:1017E000FFF7B4FB4FF4C873079AB0FBF3F101FBAA -:1017F000130302F5167010FA83F0CBF8000010A85E -:10180000DFF8B0B19BF80010002914BF2B465346F7 -:1018100007918DF83030FFF7B1FB079910AB0DF150 -:101820003100C1F110021944D2B2062A28BF0622A3 -:10183000079200F007FA079A0CAB20460393013297 -:101840001823D2B20293554B04923246CDE900A33D -:101850003B4602F097F98BF8005001F033FE504AF6 -:10186000504D1368C31AB3F57A7F32D3106001F07C -:101870002BFE02460B46204602F01CFA204602F0E0 -:101880003BF930B32B7A0DF1400BDFF82CA1002B84 -:1018900014BF032302238AF8053001F013FE4FF42E -:1018A0007A7301225946B0FBF3F0CAF800005046A3 -:1018B00000F04AFB182380B2424602933A4B019350 -:1018C00040F25513CDE903B0009320464B4602F099 -:1018D00059F92B7AABB101F0F5FD4FF0000A8346C0 -:1018E0004FF48A7295F8D900504400F0030002FBCF -:1018F000005393F8E81071B30AF1010ABAF1040F2A -:10190000F0D1C82003F070FE2B7A002B7FF435AFA6 -:1019100015B0BDEC028BBDE8F08F1946102210A85F -:1019200000F0B6F90DF126030AAA0CA9584601F0F9 -:1019300063F811AB95E8030083E803009DF83C30A1 -:1019400010A920468DF84C300C9B1093DDE90A233A -:1019500002F084FB1EE7D3F8E01049B12B68ABEB33 -:101960000101FA2B38BFFA230533B1EB430FC3D380 -:10197000FFF7DEFB4FF48A720028BDD1C1E700BF3C -:10198000401DA12026812A0BF1C6A7C1D068080FEF -:101990000000000000000000103400200834002087 -:1019A000204E0020F0480020244E0020403400202B -:1019B0000C34002009340020F823002008B5054825 -:1019C00001F0C0F8044A05490020BDE8084005F0D0 -:1019D00083BE00BF403400207C4E00202913000845 -:1019E000704700002DE9F84F4FF47A7306460D4614 -:1019F000002402FB03F7DFF85080DFF8509098F9DD -:101A000000305FFA84FA5A1C01D0A34212D159F86F -:101A100024002A4631460368D3F820B03B46D84715 -:101A2000854207D1074B012083F800A0BDE8F88F5D -:101A30000124E4E7002CFBD04FF4FA7003F0D4FD4E -:101A40000020F3E76C4E0020182200201C2200200A -:101A500070B504464FF47A76412C254628BF4125BF -:101A600006FB05F003F0C0FD641BF5D170BD00005E -:101A7000002307B5024601210DF107008DF807305C -:101A8000FFF7B0FF20B19DF8070003B05DF804FB3D -:101A90004FF0FF30F9E700000A46042108B5FFF7D0 -:101AA000A1FF80F00100C0B2404208BD074B0A46CA -:101AB00030B41978064B53F821400146236820467C -:101AC000DD69044BAC4630BC604700BF6C4E002063 -:101AD0001C220020A086010070B5104C0025104E7D -:101AE00004F09CF820803068238883420CD80025BD -:101AF0002088013804F08EF823880544013BB5F5B1 -:101B0000802F2380F4D370BD04F084F8336805443B -:101B10000133B5F5802F3360E5D3E8E76E4E002042 -:101B2000284E002004F048B900F1006000F5802044 -:101B30000068704700F10060920000F5802004F01A -:101B4000C9B80000054B1A68054B1B889B1A8342D5 -:101B500002D9104404F05EB800207047284E0020DF -:101B60006E4E0020024B1B68184404F059B800BFA9 -:101B7000284E0020024B1B68184404F063B800BFD5 -:101B8000284E00200020704700F1FF5000F58F1014 -:101B9000D0F8000870470000064991F8243033B1AE -:101BA00000230822086A81F82430FFF7C3BF012010 -:101BB000704700BF2C4E0020014B1868704700BFD3 -:101BC0000010005C194B01380322084470B51D68F1 -:101BD000174BC5F30B042D0C1E88A6420BD15C6875 -:101BE0000A46013C824213460FD214F9016F4EB1EE -:101BF00002F8016BF6E7013A03F10803ECD18142E8 -:101C00000B4602D22C2203F8012B0424094A168821 -:101C1000AE4204D1984284BF967803F8016B013C30 -:101C200002F10402F3D1581A70BD00BF0010005C2D -:101C300024220020D477000870470000704700007D -:101C400070470000002310B5934203D0CC5CC4540D -:101C50000133F9E710BD0000013810B510F9013F5C -:101C60003BB191F900409C4203D11AB10131013AD4 -:101C7000F4E71AB191F90020981A10BD1046FCE75C -:101C800003460246D01A12F9011B0029FAD1704707 -:101C900002440346934202D003F8011BFAE770475F -:101CA0002DE9F8431F4D14460746884695F8242031 -:101CB00052BBDFF870909CB395F824302BB92022EA -:101CC000FF2148462F62FFF7E3FF95F824004146C5 -:101CD000C0F1080205EB8000A24228BF2246D6B21E -:101CE0009200FFF7AFFF95F82430A41B17441E4461 -:101CF0009044E4B2F6B2082E85F82460DBD1FFF7F9 -:101D00004BFF0028D7D108E02B6A03EB8203834204 -:101D1000CFD0FFF741FF0028CBD10020BDE8F883EA -:101D20000120FBE72C4E0020024B1A78024B1A7060 -:101D3000704700BF6C4E00201822002038B51A4CA6 -:101D40001A4D204602F06EFF2946204602F096FF0B -:101D50002D684FF47A70D5F89020D2F8043843F00B -:101D60000203C2F80438FFF773FE1149284603F056 -:101D700093F8D5F890200F4DD2F80438286823F056 -:101D800002030D49A042C2F804384FF4E1330B605E -:101D900001D002F0A5FE6868A04204D00649BDE863 -:101DA000384002F09DBE38BD6055002064790008BF -:101DB0006C7900081C220020544E00200C4B70B59A -:101DC0000C4D04461E780C4B55F826209A420DD037 -:101DD0000A4B002118221846FFF75AFF04600146FB -:101DE00055F82600BDE8704002F07ABE70BD00BF15 -:101DF0006C4E00201C22002060550020544E002014 -:101E00002DE9F0470D46044600219046284640F251 -:101E10007912FFF73DFF234620220021284604F1D6 -:101E2000220702F0BDF8231D022220212846C026E9 -:101E300002F0B6F8631D03222221284602F0B0F812 -:101E4000A31D03222521284602F0AAF804F1080365 -:101E500010222821284602F0A3F804F110030822DA -:101E60003821284602F09CF804F111030822402191 -:101E7000284602F095F804F112030822482128466A -:101E800002F08EF804F1140320225021284602F0BB -:101E900087F804F1180340227021284602F080F8E8 -:101EA00004F120030822B021284602F079F804F159 -:101EB00021030822B821284602F072F8314608367C -:101EC0003B4608222846013702F06AF8B6F5A07FA3 -:101ED000F4D1002704F1330A04F132030822314619 -:101EE000284602F05DF894F832304FEAC7099F4265 -:101EF00009F5A47615D3B8F1000F08D1314609F2DF -:101F00004F1604F599730722284602F049F8274630 -:101F10003B1B94F8322193420CD3F01DC008BDE85E -:101F2000F0870AEB0703082231462846013702F002 -:101F300037F8D8E707F23313314608222846083627 -:101F4000013702F02DF8E3E713B5044608460021F7 -:101F50002022234601900160C0F8031002F020F80F -:101F6000231D01980222202102F01AF8631D019816 -:101F70000322222102F014F8A31D01980322252137 -:101F800002F00EF8019804F108031022282102F053 -:101F900007F8072002B010BD0023F7B50E46047FF6 -:101FA000072200911946054601F0BEFE731C01226E -:101FB000072100932846002301F0B6FEC4B9B31CE4 -:101FC000052208212846009323460D2401F0ACFE8B -:101FD0003746BB1BB278934211D307342B7FA88AB4 -:101FE000E408BBB9844294BF0020012003B0F0BDD7 -:101FF000AB8A0824DB00083BDB08B370E8E7FB1C76 -:10200000214608222846009300230834013701F0B6 -:102010008BFEDEE7201A18BF0120E7E70023F7B5A3 -:102020000E46047F082200911946054601F07CFE09 -:10203000731CC4B908220093234610241146284675 -:1020400001F072FE01235F1C7278013B934211D3B1 -:1020500007342B7FA88AE408BBB9844294BF0020D0 -:10206000012003B0F0BDAB8A0824DB00083BDB088D -:102070007370E7E7F31921460822284600930023EE -:1020800001F052FE08343B46DDE7201A18BF01205C -:10209000E7E70000F8B50E46054614460021812208 -:1020A0003046FFF7F5FD2B4608220021304601F0AF -:1020B00077FF7CB90F246B1C07220821304601F002 -:1020C0006FFF01235F1C6A78013B934204D3E01D3C -:1020D000C008F8BD0824F4E7EB1921460822304671 -:1020E00001F05EFF08343B46ECE70000F8B50E4611 -:1020F000054614460021CE223046FFF7C9FD2B4687 -:1021000028220021304601F04BFF7CB9302405F134 -:10211000080308222821304601F042FF2F467B1B8E -:102120002A7A934204D3E01DC008F8BD2824F5E7BD -:1021300007F109032146082230460834013701F02F -:102140002FFFECE7F7B5047F0E4600910123102224 -:102150000021054601F0E8FDC4B9B31C0922102195 -:10216000284600932346192401F0DEFD3746728885 -:10217000BB1B9A4211D807342B7FA88AE408BBB94D -:10218000844294BF0020012003B0F0BDAB8A10242C -:10219000DB00103BDB087380E8E73B1D214608228B -:1021A0002846009300230834013701F0BDFDDEE727 -:1021B000201A18BF0120E7E730B50A44084D9142C4 -:1021C0000DD011F8013B5840082340F30004013BB7 -:1021D0002C4013F0FF0384EA5000F6D1EFE730BD46 -:1021E0002083B8EDF7B5384A6B46106851686A46E7 -:1021F00003C308233549364805F09CFA04460028F5 -:1022000033D10A25334A6B46106851686A4603C3C6 -:10221000082331492E4805F08DFA0446002849D09C -:102220000369B3F5E01F45D8B0F8661040F23742B5 -:1022300091423FD1294A024402F15C018B4239D3D9 -:102240005C3B234900209E1AFFF7B6FF04F16401AE -:10225000074632460020FFF7AFFFA3689F4229D10F -:10226000E368984208BF002524E00369B3F5E01F46 -:1022700027D8418B40F23742914220D1174A02447D -:1022800002F110018B4218D3103B114900209D1A16 -:10229000FFF792FF04F1180106462A460020FFF7D7 -:1022A0008BFFA3689E4202D1E368984201D00D25BE -:1022B000A8E70025284603B0F0BD1025A2E70C25AD -:1022C000A0E70B259EE700BFE4770008DCFF1B00BA -:1022D00000000408ED77000890FF1B000800FCF7E1 -:1022E00010B5037C044613B9006805F00BFA2046CC -:1022F00010BD00000023BFF35B8FC360BFF35B8F93 -:10230000BFF35B8F8360BFF35B8F7047BFF35B8F5F -:102310000068BFF35B8F704770B505460C30FFF760 -:10232000F5FF044605F108063046FFF7EFFFA0422F -:1023300006D96D683046FFF7E9FF2544281A70BDBD -:102340003046FFF7E3FF201AF9E7000070B50546B5 -:102350004068A0B105F10C0605F10800FFF7D6FFB3 -:1023600004463046FFF7D2FF844204F1FF34304682 -:1023700094BF6D680025FFF7C9FF2C44201A70BD7B -:1023800038B50C460546FFF7C7FFA04210D305F14C -:102390000800FFF7BBFF04446868BFF35B8FB4FB22 -:1023A000F0F100FB11440120AC60BFF35B8F38BD3E -:1023B0000020FCE72DE9F041144607460D46FFF7E3 -:1023C000C5FF844228BF0446D4B1B84658F80C6B08 -:1023D0004046FFF79BFF3044286040467E68FFF789 -:1023E00095FF331A9C4203D801206C60BDE8F08150 -:1023F000A41B6B603B682044AB60E8600220F5E7FB -:102400002046F3E738B50C460546FFF79FFFA0428C -:1024100010D305F10C00FFF779FF04446868BFF39F -:102420005B8FB4FBF0F100FB11440120EC60BFF3C3 -:102430005B8F38BD0020FCE72DE9FF4188466946E7 -:1024400007466C46FFF7B6FF002506B204EBC6064A -:10245000B4420AD0626808EB050120680834FFF72F -:10246000F1FB54F8043C1D44F2E729463846FFF7D7 -:10247000C9FF284604B0BDE8F0810000F8B5054664 -:102480000C300F46FFF742FF05F1080604463046C0 -:10249000FFF73CFFA042304688BF6C68FFF736FF6D -:1024A000201A386020B12C683046FFF72FFF2044F7 -:1024B000F8BD000073B5144606460D46FFF72CFF25 -:1024C0008442019028BF0446DCB101A93046FFF7E1 -:1024D000D5FF019B33B93268C5E90233C5E9002451 -:1024E00001200CE09C42286038BF0194019884428E -:1024F0006860F5D93368241A0220AB60EC6002B042 -:1025000070BD2046FBE700002DE9FF410F466946FC -:102510006C46FFF7CFFF00B2002604EBC005AC42CB -:1025200009D0D4F80480B81954F8081B4246464430 -:10253000FFF788FBF3E7304604B0BDE8F081000008 -:1025400038B50546FFF7E0FF044601462846FFF789 -:1025500017FF204638BD0000302383F3118862B690 -:1025600070470000002383F3118862B670470000B3 -:10257000012070477047000010B4134602681468C9 -:102580000022A4465DF8044B6047000000F580502F -:1025900090F859047047000000F5805090F85204FC -:1025A0007047000000F5805090F958047047000013 -:1025B0004E20704700F5805208B5FFF7CDFFD2F8E6 -:1025C0009834D2F894041844D2F890341844D2F8CD -:1025D00078341844D2F888341844D2F88434184433 -:1025E000FFF7C0FF08BD00002DE9F04F0C4600F5D5 -:1025F000805185B01F4691F8523405469046BDF88B -:1026000038909BB1D1F874340133C1F87434236825 -:102610009A0006D4237B082B0BD9627B0AB10F2BBF -:1026200007D9D1F878340133C1F878344FF0FF304E -:102630000FE0FFF791FFEB6AD3F8C42012F4001A01 -:102640000AD0D1F87C3400200133C1F87C34FFF784 -:1026500089FF05B0BDE8F08F22684FF0480BD3F832 -:10266000C460002A6B6AC6F30446B4BF42F08042DD -:1026700092041BFB063BCBF8002023685B004FEA6B -:10268000066344BF42F00052CBF80020227B43EAAD -:1026900002437201CBF80430607B18B343F440135B -:1026A000CBF80430D1F8A4340133C1F8A434AB180A -:1026B00003F58353197B41F020011973207B0392AA -:1026C00000F05CFF0330039A80105FFA8AF30AF18E -:1026D000010A83420DDA04EB83010BEB83034968A3 -:1026E0009960F2E7AB1803F58353197B60F345114A -:1026F000E3E70121EB6A04F10C00B140C3F8D0100C -:10270000AB18214603F58253C3E9048705EB461352 -:1027100003F58253183351F804CB814243F804CBBC -:10272000F9D109882A442846198041F26803D65015 -:1027300002F5805209F0030392F86C1043F0100385 -:1027400021F01F010B43214682F86C304246FFF70F -:1027500009FF3B46CDF8009000F0D6FE012078E757 -:102760002DE9F04700F58056044696F85254002DA6 -:1027700040F00181037C032B40F092802B462846D9 -:102780002F465FFA83FC944510DA01EBCC0E51F82A -:102790003CC0BCF1000F04DBDEF804C0BCF1000F4C -:1027A00002DB01370133ECE70130FBE7FFF7D4FE32 -:1027B000E36AF0B9D3F8800040F00200C3F880006B -:1027C0004E23E06A002F6ED1D0F8803043F0010331 -:1027D000C0F88030694B6A4A1B6803F1805303F5E7 -:1027E0002C539B009342A36240F2AF80654800F0F7 -:1027F00063FE4D2842D8DFF884814FEA004EDFF8AF -:102800008891D8F800C04EEA8C0EC3F884E00CF131 -:10281000805303F52C539B00636100EB0C03D4F849 -:102820002CC0C8F80030C0F14E03DCF8800040F046 -:102830003000CCF880004FF0000CD4F81480E6464D -:102840005FFA8CF08242BCDD01EBC00A51F8300027 -:10285000002810DBDAF804A0BAF1000F0BDA09EA5D -:1028600000400AF07F0A40EA0A0040F0084048F8B9 -:102870002E000EF1010E0CF1010CE1E79A6922F035 -:1028800001029A6100F01EFE0646E36A9B69D907C1 -:1028900004D500F017FE831BFA2BF6D9FFF762FE72 -:1028A0002846BDE8F087B7EB530F3DD2DFF8CCE008 -:1028B0004FEA074CDEF800304CEA830CC0F888C0C1 -:1028C00003F1805003EB4703002700F52C50CEF8AE -:1028D0000030BC468000A061E06AD0F8803043F050 -:1028E0000C03C0F88030D4F818E0FBB29A427FF7AE -:1028F00071AF51F8330001EBC3080028D8F8043059 -:1029000001DB002B0EDB20F0604023F0604340F041 -:10291000005043F000434EF83C000EEBCC000CF1AD -:10292000010C43600137E0E7836923F00103836111 -:1029300000F0C8FD0646E36A9B69DA07AED500F0F1 -:10294000C1FD831BFA2BF6D9A8E7E26A936923F04D -:102950000103936100F0B6FD0746E36A9B69DB075C -:1029600005D500F0AFFDC31BFA2BF6D996E701257C -:1029700086F8525492E7002592E700BF784E002077 -:10298000FCB50040F87700080000FF0713B500F51C -:1029900080540191606CFFF7D9FC1F280AD92022CE -:1029A0000199606CFFF748FDA0F12003584258419F -:1029B00002B010BD0020FBE700F5805008B5FFF71E -:1029C000CBFD406CFFF796FCBDE80840FFF7CABDA1 -:1029D00000220260828142608260704700220023F0 -:1029E00010B5C0E90023002304460C3020F8043C55 -:1029F000FFF7EEFF204610BD2DE9F047074688B0EF -:102A00009A46884607F5805468469146FFF7A4FD2C -:102A1000FFF7E4FF606CFFF77FFC1F282DD9202211 -:102A20006946606CFFF78CFD202826D194F852345B -:102A30001BB303AD444605AB2E46083403CE9E427D -:102A400044F8080C44F8041C3546F5D1306841467A -:102A500020603846B388A380DDE90023C9E900235C -:102A6000BDF808304A46AAF80030FFF77BFD534610 -:102A700008B0BDE8F04700F035BD0020FFF772FD5B -:102A800008B0BDE8F08700002DE9F84F00230646A6 -:102A900000F58154054688461034C0E90133264BC1 -:102AA00046F8303B374638462037FFF797FFA742B6 -:102AB000F9D105F580544FF4805305F5A3594FF033 -:102AC000000A26630026676405F5835709F110099B -:102AD0004FF0000B1037E663C4E90D36012384F88C -:102AE000403084F84830A7F11800203747E910AB90 -:102AF000FFF76EFF47F8286C4F45F4D184F85884EF -:102B0000A4F85A64A4F85C64A4F85E6484F8606471 -:102B1000A4F86264A4F86464A4F8666484F8686441 -:102B2000B8F1000F02D0054800F0C6FC044B28465F -:102B3000EB62BDE8F88F00BF387800081C78000809 -:102B400000A00040044B10B5197804464A1C1A70C6 -:102B5000FFF79AFF204610BD754E00202DE9F04783 -:102B600000295FD0304F3148B7FBF1F581428CBF6F -:102B70000A201120431EB5FBF0FC00FB1C50DCB208 -:102B800020B1022B1846F5D8002037E00CF1FF35B4 -:102B9000B5F5806F32D2C4EBC4094FF47A7009F1F5 -:102BA00003034FEAE308C3F3C70308F1010AA4EBE8 -:102BB000030E08FB00085FFA8EF65AFA8EFEB8FB89 -:102BC000FEFEBEF5617F1BDC1FFA8EF4581C56FA20 -:102BD00080F00CFB00FCB7FBFCFC6145D4D1013B51 -:102BE000DBB20F2BD0D8711E0020C9B2072905D83F -:102BF000107101201480558053719171BDE8F087E8 -:102C000009F1FF334FEAE30EC3F3C7030EF10108E6 -:102C1000E41A0EFB0000E6B258FA84F4B0FBF4F4B8 -:102C2000A4B2D3E70846E9E700B4C4043F420F006A -:102C300038B540F27772C36A154CC3F8BC2007223E -:102C4000C36AC3F8C8202268C16A930043F4C02352 -:102C5000C1F8A03002F1805302F16C01C56A03F59E -:102C60002C53EA3289009B00226041F0E061094A5E -:102C7000C361C5F8C01003F5D87103F56A734162EA -:102C80009342836202D9044800F016FC38BD00BFAD -:102C9000784E0020FCB50040F87700082DE9F04F91 -:102CA00000F58055994689B0044695F858348A460F -:102CB0009046012B04D90027384609B0BDE8F08FB3 -:102CC000934A52F8231009B942F823009149C4F8F5 -:102CD0000CA00B7884F81090C3B9FFF73DFC8E4B25 -:102CE000D3F8EC2042F48072C3F8EC20D3F894209F -:102CF00042F48072C3F89420D3F8942022F48072B6 -:102D0000C3F8942001230B70FFF72CFC95F8513485 -:102D100073B903211320FFF71FFC01F02BFD0321E2 -:102D2000152001F027FD012385F85134FFF71AFC27 -:102D3000FFF712FCE26A936923F01003936100F03D -:102D4000C1FB0746E36A9E6916F0080607D000F04B -:102D5000B9FBC31BFA2BF5D9FFF704FCABE79A6963 -:102D600042F001029A6100F0ADFB0746E36A9A69FE -:102D7000D00705D400F0A6FBC31BFA2BF6D9EBE76E -:102D80009A69002704F5825B42F002020BF1100BF6 -:102D90009A61E36A5F65FFF7E5FB686CFFF7AAFAE3 -:102DA000202200216846FEF773FF02A8FFF710FEFD -:102DB0006A460BEB06030DF1180E0697944608338E -:102DC000BCE80300F44543F8080C43F8041C6246D1 -:102DD000F4D1DCF8000020361860B6F5806F9CF85E -:102DE00004201A71DCD1002304F5A252514620467A -:102DF0001A3285F8503485F85334FFF7AFFE074692 -:102E000090B9E26A936923F00103936100F05AFBE1 -:102E10000546E36A9B69D9077FF54DAF00F052FB89 -:102E2000431BFA2BF5D946E795F85F6495F85E24C5 -:102E30003602C5F86CA4E36A46EA426695F8602457 -:102E40001643B5F85C2446EA0246DE61B8F1000F8D -:102E500029D004F5A352414620460232FFF77EFEF8 -:102E600090B9E26A936923F00103936100F02AFBB1 -:102E70000546E36A9B69DA077FF51DAF00F022FB88 -:102E8000431BFA2BF5D916E795F8683495F86714C3 -:102E90001B01C5F87084E26A43EA0123B5F86414A3 -:102EA00043EA0143D360E36A00262046C3F8BC60CE -:102EB000FFF7BEFE85F859646FF04042E36A1A6579 -:102EC000164AE36A5A654FF00222E36A9A654FF0A8 -:102ED000FF32E36AC3F8E0200322E36A9145DA6532 -:102EE0003FF4EAAEE26A936923F00103936100F0D4 -:102EF000E9FA0646E36A9B69DB0705D500F0E2FACA -:102F0000831BFA2BF6D9D6E6012385F85234D3E693 -:102F1000704E0020744E00200044025855020002FA -:102F20002DE9F04F054689B090469946002741F2B9 -:102F3000680A00F58056EB6AD3F8D830FB40D80712 -:102F40004AD505EB47124FEA471B5244137919073C -:102F500042D4D6F880340133C6F8803413799A0607 -:102F600005EB0B0248BFD6F8A834524444BF0133E6 -:102F7000C6F8A834137943F008031371DB0723D58F -:102F800096F8533403B305F582546846FFF726FDDF -:102F900003AB18345C4404F1080C2068083454F87E -:102FA000041C1A46644503C21346F6D120686946DC -:102FB00010602846A2889A800123ADF808302B685B -:102FC000CDE90089DB6B9847D6F8543423B1D6F8A5 -:102FD0009C340133C6F89C340137202FABD109B0A3 -:102FE000BDE8F08F2DE9F04F0F468DB0044600F09C -:102FF0006BFA82468946002F5BD1E36AD3F8A020A2 -:1030000012F4FE0F03D100200DB0BDE8F08FD3F80D -:10301000A420920141BF04F58051D1F894240132DB -:10302000C1F89424D3F8A4205606ECD0D3F8A450C9 -:10303000E669C5F305254823E8464FF0000B03FB7E -:1030400005664046FFF7C4FC326851004ABF22F0D3 -:103050006043C2F38A4343F00043920048BF43F009 -:1030600080430093736813F400131BBF012304F51E -:1030700080528DF80D308DF80D301EBFD2F8AC3473 -:103080000133C2F8AC34F38803F00F038DF80C3031 -:103090009DF80C0000F072FA5FFA8BF3984225D984 -:1030A000F2180CA90BF1010B127A0B4403F82C2C2B -:1030B000EEE7012FA7D1E36AD3F8B02012F4FE0F98 -:1030C000A1D0D3F8B420950141BF04F58051D1F8C7 -:1030D00094240132C1F89424D3F8B420500692D03D -:1030E000D3F8B450266AC5F30525A4E7EFB9E36A1F -:1030F000C3F8A85004A807ADFFF770FC98E80F00CC -:1031000007C52B800023204604A9ADF8183023689A -:1031100004F58054DB6BCDE904A9984758B1D4F885 -:103120008C340133C4F88C346EE7012FE2D1E36AAA -:10313000C3F8B850DEE7D4F8903401200133C4F866 -:10314000903461E7F8B505460F4600F58054012636 -:1031500039462846FFF746FF10B184F85364F7E775 -:10316000D4F8543423B1D4F89C340133C4F89C34DB -:10317000F8BD0000C36AF0B51A6C12F47F0F2BD0B3 -:103180001B6C00F5805441F268054FF0010CC4F847 -:10319000A0340023471900EB43125E012A44117941 -:1031A00011F0020F15D0490713D4B959C66A0CFAA9 -:1031B00001F1D6F8CCE011EA0E0F0AD0C6F8D4100F -:1031C000117941F004011171D4F888240132C4F856 -:1031D00088240133202BDED1F0BD000010B5264C31 -:1031E000264B22680AB340B31A6D92050FD54FF4EF -:1031F00000721A6500F068F950EA01020B4602D02D -:10320000013861F1000302462068FFF789FE1B4A7E -:10321000136D9B012AD523684FF0007103F580538D -:103220001165012283F8592420E001221A65102239 -:103230001A654FF480521A6510BD196DC80702D483 -:10324000196D490705D50521104619650021FFF7BD -:1032500079FF0A4B1A6DD00602D41A6D510605D5B6 -:10326000502201211A652068FFF76CFF2068BDE835 -:103270001040FFF77FBF00BF704E002000A000404D -:1032800008B5FFF769F9FFF775FFBDE80840FFF7DC -:1032900069B90000C36AD3F8C00010F07C5005D0B3 -:1032A000D3F8C40080F40010C0F340507047000011 -:1032B00000F5805008B5FFF74FF9406CFFF72CF888 -:1032C000FFF750F943090CBF0120002008BD0000A2 -:1032D00000F5805393F8592462B1C16A8A6922F0DB -:1032E00001028A61D3F898240132C3F8982400229D -:1032F00083F85924704700002DE9F74300F5825107 -:1033000098460025FFF728F9103141F2680E4FF07A -:10331000010900F5805C00EB4514744423795E07D5 -:103320001CD4DB061AD58E69C36A09FA06F6D3F8EF -:10333000CC703E4212D04F6801970F689742019FB0 -:1033400077EB08070AD2C3F8D460237943F004036B -:103350002371DCF884340133CCF884340135203116 -:10336000202DD8D103B0BDE8F043FFF7FBB8000033 -:10337000F8B51E4600230F46054613701446FFF7A6 -:1033800097FF80F0010038701EB12846FFF782FFDA -:103390002070F8BD2DE9F04F85B099460D46804666 -:1033A000164691F800B0DDE90EA30293137801935D -:1033B00000F08AF82B7804460F4613B93378002BB7 -:1033C00042D022463B464046FFF796FFFFF758FFA4 -:1033D000FFF77EFF4B4632462946FFF7C9FF2B78A1 -:1033E00033B1BBF1000F03D0012005B0BDE8F08F71 -:1033F000337813B1019B002BF6D108F5805303936A -:103400005445029B77EB03031ED2039BD3F854046D -:10341000D0B10368AAEB0401DB6889B298474B4638 -:10342000324629464046FFF7A3FF2B7813B1BBF184 -:10343000000FD9D1337813B1019B002BD4D100F008 -:1034400043F804460F46DBE70020CEE708B500202E -:10345000FFF7C4FEBDE8084001F056B808B50120EA -:10346000FFF7BCFEBDE8084001F04EB800B59BB0C8 -:10347000EFF3098168226846FEF7E4FBEFF305836A -:10348000014B9B6BFEE700BF00ED00E008B5FFF7C6 -:10349000EDFF000000B59BB0EFF30981682268469C -:1034A000FEF7D0FBEFF30583014B5B6BFEE700BF3C -:1034B00000ED00E0FEE700000FB408B5029802F04E -:1034C0001FF8FEE702F0C4BC02F09CBC13B56C46CA -:1034D000031D84E8060094E8030083E8050001204A -:1034E00002B010BD73B58568019155B11B885B07AB -:1034F00007D4D0E900369B6B9847019AC1B2304699 -:10350000A847012002B070BDF0B5866889B00546B5 -:103510000C465EB1BDF838305B070AD4D0E90037FD -:103520009B6B98472246C1B23846B047012009B08C -:10353000F0BD0022002301F10806CDE9002300239D -:103540000A46ADF8083003AB1068083252F8041C84 -:103550001C46B24203C42346F6D11068206092880C -:10356000A280FFF7B1FF0423ADF808302B68CDE946 -:103570000001DB6B694628469847D7E7082817D92A -:1035800009280CD00A280CD00B280CD00C280CD001 -:103590000D280CD00E2814BF4020302070470C207E -:1035A0007047102070471420704718207047202063 -:1035B000704700002DE9F041456A15B94162BDE848 -:1035C000F0814B68AC4623F06047C3F38A464FEA6C -:1035D000D37EC3F3807816EA230638BF3E462B46D7 -:1035E0005A68BEEBD27F22F060440AD0002A18DA73 -:1035F000A40CB44217D19D420FD10D60DEE71346F3 -:10360000EEE7A74207D102F08044C2F38072424540 -:103610000BD054B1EFE708D2EDE7CCF800100B6007 -:10362000CDE7B44201D0B442E5D81A689C46002ADE -:10363000E5D11960C3E700002DE9F047089D01F0CE -:10364000070400EBD1004FF47F494FEAD50822442C -:1036500005F00705944201D1BDE8F08704F00707A3 -:1036600005F0070A111B08EBD50E57453E4613F827 -:103670000EC038BF5646C6F108068E4228BF0E4619 -:10368000E108415C34443544B94029FA06F721FA8F -:103690000AF1FFB28CEA010147FA0AF739408CEAD5 -:1036A000010C03F80EC0D5E780EA0120082341F29F -:1036B000210201B2013B4000002980B2B8BF504056 -:1036C00013F0FF03F5D1704738B50C468D18A542AD -:1036D00000D138BD14F8011BFFF7E6FFF7E7000043 -:1036E00042684AB1136881894360438901339BB2C0 -:1036F0009942438138BF83811046704770B588B0C6 -:10370000044620220D4668460021FEF7C1FA2046F5 -:103710000495FFF7E5FF024660B16B46054608AE2B -:103720001C46083503CCB44245F8080C45F8041C87 -:103730002346F5D1104608B070BD0000082817D9FF -:1037400009280CD00A280CD00B280CD00C280CD03F -:103750000D280CD00E2814BF4020302070470C20BC -:1037600070471020704714207047182070472020A1 -:1037700070470000082817D90C280CD910280CD93C -:1037800014280CD918280CD920280CD930288CBF23 -:103790000F200E207047092070470A2070470B2029 -:1037A00070470C2070470D20704700002DE9F8434A -:1037B000078C0446072F1ED900254FF6FF73D0E96A -:1037C0000298C5F12006A5F1200029FA05F1083577 -:1037D00008FA06F628FA00F0314301431846C9B248 -:1037E000FFF762FF402D0346EBD13A46E169BDE8A1 -:1037F000F843FFF769BF4FF6FF70BDE8F88300009C -:1038000010B54B6823B9CA8A63F30902CA8210BD96 -:1038100004691A681C600361C38A013BC3824A6061 -:10382000EFE700002DE9F84F1D46CB8A0F46814691 -:10383000C3F30901924605290B4630D00020AAB2F5 -:1038400007F11A049EB21FFA80F8042E0FD8904593 -:1038500003F1010306D30A44FB8A62F30903012042 -:10386000FB821AE01AF800600130E654EAE790455E -:10387000F1D2A1F1050B1C237C68BBFBF3F203FB27 -:1038800012BB1FFA8BF6002C45D14846FFF728FFE4 -:10389000044638B978606FF00200BDE8F88F4FF049 -:1038A0000008E6E7002606607860ADB24FF0000B36 -:1038B000454510D90AEB0803221D13F8011B08F136 -:1038C00001089155B1B21FFA88F81B292BD0454544 -:1038D00006F10106F1D8FB8AC3F30902154465F32A -:1038E0000903BCE701321C4692B22368002BF9D1D0 -:1038F0006B1F0B441C21B3FBF1F301339BB29A42C3 -:10390000D3D2BBF1000FD0D14846FFF7E9FE20B972 -:10391000C4F800B0BFE70122E7E7C0F800B05E4698 -:1039200020600446C1E74545D5D94846FFF7D8FE93 -:1039300008B92060AFE7C0F800B000262060044658 -:10394000B6E700002DE9F04F1C46074688462DEDEE -:10395000028B83B05B690192002B00F09A80238C6C -:103960002BB1E269002A00F09480072B35D807F1CB -:103970000C00FFF7B5FE054638B96FF00205284682 -:1039800003B0BDEC028BBDE8F08F14220021FEF7DE -:103990007FF9228CE16905F10800FEF753F9208CCC -:1039A00048F00041013080B2FFF7E4FEFFF7C6FEA9 -:1039B000013880B220840130287438466369228C33 -:1039C0001B782A4403F01F0363F03F0313726960FE -:1039D0002946FFF7EFFD0125D1E74FF0000900F17F -:1039E0000C034FF0800A4E464D4608EE103A18EE92 -:1039F000100AFFF775FE83460028BED0142200216E -:103A0000FEF746F9002E3AD1019B0222ABF80830AE -:103A10000BF1080E1FFA82FC218C0CF10100BCF1A5 -:103A2000060F80B201D88E422BD3FFF7A3FE8E4241 -:103A300008BF4FF0400AFFF781FE62690138013587 -:103A400012781BFA80F1013002F01F022DB242EA17 -:103A5000491289F001094AEA020A48F0004281F855 -:103A600008A059468BF810003846CBF804204FF0D8 -:103A7000000AFFF79FFD238CB342B8D17FE70022F5 -:103A8000C6E7E169895D01360EF80210B6B201326F -:103A9000C0E76FF0010572E7F8B515460E46302213 -:103AA000002104461F46FEF7F3F8069BB5F5001FFC -:103AB000A760636004F11000079B34BF6A094FF6EA -:103AC000FF72E661A362002397B29A4206D80023F0 -:103AD0000360A782E3822383E360F8BD06600133BD -:103AE00030462036F1E7000003781BB94BB2002BBB -:103AF000C8BF01707047000000787047F8B50C46E9 -:103B0000C969074611B9238C002B37D1257E1F2D9B -:103B100034D8387828BB228C072A2CD8268A36F04D -:103B200003032BD14FF6FF70FFF7CEFD20F001000D -:103B300031024FF6FF72400441EA0561400C41EA50 -:103B40004025234629463846FFF7FCFE002807DDBE -:103B5000626913780133DBB21F2B88BF0023137017 -:103B6000F8BD218A2D0645EA012505432046FFF7C9 -:103B70001DFE0246E5E76FF00300F1E76FF001007C -:103B8000EEE7000070B58AB00446164600212822F0 -:103B900068461D46FEF77CF8BDF838306946204679 -:103BA000ADF810300F9B05939DF840308DF818301C -:103BB000119B0793BDF84830CDE90265ADF8203080 -:103BC000FFF79CFF0AB070BD2DE9F041D3690546AF -:103BD0000C4616460BB9138C5BBB377E1F2F28D8BB -:103BE00095F80080B8F1000F26D03046FFF7DEFDD3 -:103BF000337821020246284641EAC331338A41EA3A -:103C0000080141EA076141EA0341334641F080017E -:103C1000FFF798FE00280ADD3378012B07D172697F -:103C200013780133DBB21F2B88BF00231370BDE86C -:103C3000F0816FF00100FAE76FF00300F7E7000092 -:103C4000F0B58BB004460D46174600212822684681 -:103C50001E46FEF71DF89DF84C30294620465A1E98 -:103C6000534253416A468DF800309DF84030ADF81C -:103C70001030119B05939DF848308DF81830149B37 -:103C80000793BDF85430CDE90276ADF82030FFF748 -:103C90009BFF0BB0F0BD0000406A00B104307047DC -:103CA000436A1A68426202691A600361C38A013B6F -:103CB000C38270472DE9F041D0F8208014461D469C -:103CC000184E4146002709B9BDE8F081D1E9022329 -:103CD000A21A65EB0303964277EB03031ED2036A35 -:103CE0008B420DD1FFF78CFD036A1B6803620369E9 -:103CF0000B60C38A0161013B016AC3828846E2E727 -:103D0000FFF77EFD0B68C8F8003003690B60C38ABB -:103D10000161013BC382D8F80010D4E788460968E6 -:103D2000D1E700BF80841E002DE9F04F8BB00D4617 -:103D300014469B46DDF850908046002800F018811C -:103D4000B9F1000F00F01481531E3F2B00F21081D7 -:103D5000012A03D1BBF1000F40F00A810023CDE915 -:103D60000833B8F81430B5EBC30F4FEAC30703D3D9 -:103D700000200BB0BDE8F08F2B199F42D8F80C3013 -:103D800036BF7F1B2746FFB21BB9D8F81030002B77 -:103D90007AD0272D4DD8C5F1280600232946B742F1 -:103DA000009308ABD8F808002CBFF6B23E46A7EB4C -:103DB000060A354432465FFA8AFAFFF73DFCB8F846 -:103DC0001430282103F10053053BDB000493D8F89D -:103DD0000C300393039B13B1BAF1000F2CD1D8F828 -:103DE000100040B1BAF1000F05D008AB5246691A75 -:103DF0000096FFF721FC38B2002FB9D066070AD031 -:103E00000AAB624203EBD40102F0070211F8083C4E -:103E1000134101F8083C082C3DD9102C40F2B58024 -:103E2000202C40F2B780BBF1000F00F09C800823EB -:103E300035E0BA460026C2E7049BE02B28BFE0230A -:103E400006930B44AB42059315D95A1B0398691A84 -:103E50000096924508AB00F1040034BF5246D2B23E -:103E60000792FFF7E9FB079A1644AAEB020A1544EA -:103E7000F6B25FFA8AFA049B069A05999B1A049394 -:103E8000039B1B680393A5E700933A4608AB2946BA -:103E9000D8F80800ADE7BBF1000F13D00123B4EB55 -:103EA000C30F6BD0082C12D89DF82030621E23FA65 -:103EB00002F2D50706D54FF0FF3202FA04F423438D -:103EC0008DF820309DF8203089F8003051E7102C13 -:103ED00012D8BDF82030621E23FA02F2D10706D5AF -:103EE0004FF0FF3202FA04F42343ADF82030BDF85E -:103EF0002030A9F800303CE7202C0FD80899631E29 -:103F000021FA03F3DA0705D54FF0FF3202FA04F481 -:103F10000C430894089BC9F800302AE7402C2AD0AB -:103F2000611EC4F12102A4F12103DDE9086526FA2E -:103F300001F105FA02F225FA03F311431943CB0705 -:103F400011D50122A4F12003C4F1200102FA03F3E8 -:103F500022FA01F1A2400B43524263EB4303324386 -:103F60002B43CDE90823DDE90823C9E9002300E755 -:103F70006FF00100FDE66FF00800FAE6082CA1D909 -:103F8000102CB4D9202CEED8C4E7BBF1000FAED072 -:103F9000022384E7BBF1000FBCD004237FE70000BD -:103FA000012A30B5144638BF012485B00025402CC5 -:103FB00028BF4024012ACDE9025518D81B788DF876 -:103FC000083063070AD004AB624203EBD40502F069 -:103FD000070215F8083C934005F8083C0346009199 -:103FE0002246002102A8FFF727FB05B030BD082AB2 -:103FF000E4D9102A03D81B88ADF80830E1E7202A5D -:1040000095BF1B68D3E900230293CDE90223D8E7CB -:1040100010B5CB681BB98B600B618B8210BD046936 -:104020001A681C600361C38A013BC382CA60F0E75F -:1040300003064CBFC0F3C0300220704708B50246EB -:10404000FFF7F6FF022806D15306C2F30F2001D175 -:1040500000F0030008BDC2F30740FBE72DE9F04F75 -:1040600093B004460D46CDE903230A681046FFF7D6 -:10407000DFFF0228824614BFC2F306260026002A6C -:1040800080F2F38112F0C04940F0EF81097B0029F2 -:1040900000F0EB81022803D02378B34240F0E8819E -:1040A000C2F3046310462944069302F07F0305938C -:1040B000FFF7C4FF059B002283464FEA8348002395 -:1040C00048EA0A4848EA4668CE78CDE90823F30969 -:1040D00048EA0008029368D0059B024608A92046DA -:1040E000009353466768B847002800F0C481276AE8 -:1040F0004FB9414604F10C00FFF700FB074690B9A9 -:104100006FF0020055E03B6998450DD03F68002FE5 -:10411000F9D1414604F10C00FFF7F0FA07460028F8 -:10412000EED0236A3B60276297F817C006F01F089D -:10413000CCF3840CACEB0800A8EB0C031FFA80FE58 -:104140000028B8BF0EF120001FFA83FEB8BF00B2EE -:10415000002B0793B8BF0EF12003D7E90221BCBFA3 -:104160001BB2079352EA010338D0039B4FF0000CB7 -:10417000DFF820E39A1A049B63EB010196457CEB80 -:1041800001032BD36B7B97F81AE0734519D1029B7F -:10419000002B78D0012821DC7868F8B9DFF8F0C26C -:1041A000944570EB010316D337E0276A27B96FF007 -:1041B0000C0013B0BDE8F08F3B699845B4D03F6860 -:1041C000F4E7B34890427CEB010301D30020F0E711 -:1041D000029B002BFAD0079B0F2B17DCFA7DB30054 -:1041E0003946204602F0030203F07C031343FB75BB -:1041F000FFF706FB6B7BBB76029B3BB9FB7DC3F3F2 -:104200008402013262F38603FB75D0E76A7BBB7ED2 -:104210009A42DBD1029B002B35D0B309022B32D05E -:10422000039B142200210DA8BB60049BFB60FDF7DB -:104230002FFD039B0AA920460A93049BADF83EB0CC -:104240000B932B1D8DF840A00C932B7B8DF8418098 -:10425000013BDBB2ADF83C30069B8DF84230059B4C -:104260008DF8433094F82C3083F001038DF84430FE -:10427000A3689847FB7DC3F38403013303F01F0356 -:104280009B02FB82A2E7FB7DC6F34012B2EBD31F79 -:1042900040F0F480C3F38403434540F0F280029A77 -:1042A000B6092B7B002A4DD0F2075DD4032B40F2D8 -:1042B000EB80039BAE1D394604F10C00BB60324617 -:1042C000049BFB602B7B033BDBB2FFF7ABFA0028C0 -:1042D0000CDA39462046FFF793FAFB7DC3F38403DB -:1042E000013303F01F039B02FB8209E7AB88DDE982 -:1042F00008843B834FF6FF73C9F12000A9F1200227 -:1043000028FA09F109F1080904FA00F024FA02F286 -:10431000014318461143C9B2FFF7C6F9B9F1400F7E -:104320000346E9D1B88231462A7B033AD2B2FFF77D -:10433000CBF9FB7DB882DA43C2F3C01262F3C71334 -:10434000FB7543E786B92E1D013B394604F10C008D -:10435000DBB23246FFF766FA0028BADB2A7B314629 -:10436000B88A013AD2B2E2E7F98A013BC1F3090106 -:10437000DAB204295BD8281D002307F11B069A42F4 -:1043800008D910F801CB013306F801C00131DBB2C6 -:104390000529F4D1039993420A9138BF0433049953 -:1043A0002CBF002355FA83F30B9107F11B010C91ED -:1043B00079680E930D91291DFB8AADF83EB0C3F3C9 -:1043C00009038DF840A08DF841801A44069B8DF8B2 -:1043D0004230059BADF83C208DF8433094F82C30EA -:1043E00083F001038DF844300023B88A7B602A7B78 -:1043F000013AFFF769F93B8BB882834203D1A36886 -:104400000AA92046984720460AA9FFF701FEFB7D2E -:10441000BA8AC3F38403013303F01F039B02FB82B8 -:104420003B8B9A420CBF00206FF01000C1E67B6806 -:10443000002BAFD0052001E01C3033461E68002E53 -:10444000FAD1091A2E1D081D184401EB090C5FFA58 -:1044500089F3BCF11B0F9DD89A429BD916F8013BFA -:1044600009F1010900F8013BEFE76FF00900A0E650 -:104470006FF00A009DE66FF00B009AE66FF00D00FA -:1044800097E66FF00E0094E66FF00F0091E600BF24 -:1044900040420F0080841E00EFF309830549683312 -:1044A0004A6B22F001024A6383F30988002383F3F5 -:1044B0001188704700EF00E0302080F3118862B669 -:1044C0000D4B0E4AD96821F4E0610904090C0A4336 -:1044D0000B49DA60D3F8FC2042F08072C3F8FC206C -:1044E000084AC2F8B01F116841F001011160202292 -:1044F000DA7783F82200704700ED00E00003FA0548 -:1045000055CEACC5001000E0302310B583F3118800 -:104510000E4B5B6813F4006314D0F1EE103AEFF326 -:1045200009844FF08073683CE361094BDB6B2366C1 -:1045300084F3098800F0A2FF10B1064BA36110BDFF -:10454000054BFBE783F31188F9E700BF00ED00E0BE -:1045500000EF00E0430700084607000802684368D0 -:104560001143016003B1184770470000024A136805 -:1045700043F0C003136070470078004013B50E4C41 -:10458000204600F0A1FA04F1140000234FF4007259 -:104590000A49009400F05EF9094B4FF40072094992 -:1045A00004F13800009400F0D7F9074A074BC4E93A -:1045B000172302B010BD00BF804E0020EC4E00203B -:1045C0006D450008EC5000200078004000E1F50542 -:1045D000037C30B5214C002918BF0C46012B0CD1AF -:1045E0001F4B984209D11F4B9A6C42F080429A644B -:1045F0001A6F42F080421A671B6F2268036EC16D0A -:1046000003EB52038466B3FBF2F36268150442BF06 -:1046100023F0070503F0070343EA4503CB60A368D3 -:1046200043F040034B60E36843F001038B6042F4C6 -:10463000967343F001030B604FF0FF330B6251059B -:1046400005D512F0102205D0B2F1805F04D080F8B9 -:10465000643030BD7F23FAE73F23F8E7787800081D -:10466000804E0020004502582DE9F047C66D0546F2 -:104670003768F469210734621AD014F0080118BFB2 -:104680004FF48071E20748BF41F02001A3074FF0CB -:10469000300348BF41F04001600748BF41F080014E -:1046A00083F31188281DFFF759FF002383F3118836 -:1046B000E2050AD5302383F311884FF48061281D69 -:1046C000FFF74CFF002383F311884FF030094FF0C0 -:1046D000000A14F0200838D13B0616D54FF03009F7 -:1046E00005F1380A200610D589F31188504600F0EC -:1046F00067F9002836DA0821281DFFF72FFF27F079 -:1047000080033360002383F31188790614D5620691 -:1047100012D5302383F31188D5E913239A4208D1A7 -:104720002B6C33B127F040071021281DFFF716FF2F -:104730003760002383F31188E30618D5AA6E136946 -:10474000ABB15069BDE8F047184789F31188736A27 -:10475000284695F86410194000F0D0F98AF31188C2 -:10476000F469B6E7B06288F31188F469BAE7BDE886 -:10477000F0870000090100F16043012203F5614365 -:10478000C9B283F8001300F01F039A4043099B004D -:1047900003F1604303F56143C3F880211A60704759 -:1047A000F8B51546826804460B46AA4200D28568D1 -:1047B000A1692669761AB5420BD218462A46FDF73A -:1047C00041FAA3692B44A3612846A3685B1BA3603D -:1047D000F8BD0CD9AF1B18463246FDF733FA3A46FE -:1047E000E1683044FDF72EFAE3683B44EBE71846F6 -:1047F0002A46FDF727FAE368E5E70000836893425D -:10480000F7B50446154600D28568D4E90460361A27 -:10481000B5420BD22A46FDF715FA63692B44636152 -:104820002846A3685B1BA36003B0F0BD0DD93246D8 -:10483000AF1B0191FDF706FA01993A46E068314451 -:10484000FDF700FAE3683B44E9E72A46FDF7FAF989 -:10485000E368E4E710B50A440024C361029B846066 -:10486000C16002610362C0E90000C0E9051110BD2A -:1048700008B5D0E90532934201D1826882B98268D5 -:10488000013282605A1C426119700021D0E9043261 -:104890009A4224BFC368436100F0C2FE002008BDF5 -:1048A0004FF0FF30FBE7000070B5302304460E46A2 -:1048B00083F31188A568A5B1A368A269013BA36031 -:1048C000531CA36115782269934224BFE368A36156 -:1048D000E3690BB120469847002383F311882846EB -:1048E00007E03146204600F08BFE0028E2DA85F32F -:1048F000118870BD2DE9F74F04460E4617469846BD -:10490000D0F81C904FF0300A8AF311884FF0000B5A -:10491000154665B12A4631462046FFF741FF03465A -:1049200060B94146204600F06BFE0028F1D000231C -:1049300083F31188781B03B0BDE8F08FB9F1000F45 -:1049400003D001902046C847019B8BF31188ED1AD4 -:104950001E448AF31188DCE7C160C361009B82605A -:104960000362C0E905111144C0E90000016170470C -:10497000F8B504460D461646302383F31188A76820 -:10498000A7B1A368013BA36063695A1C62611D70F3 -:10499000D4E904329A4224BFE3686361E3690BB14E -:1049A00020469847002080F3118807E031462046D2 -:1049B00000F026FE0028E2DA87F31188F8BD000037 -:1049C000D0E9052310B59A4201D182687AB982688C -:1049D0000021013282605A1C82611C7803699A426C -:1049E00024BFC368836100F01BFE204610BD4FF05A -:1049F000FF30FBE72DE9F74F04460E461746984671 -:104A0000D0F81C904FF0300A8AF311884FF0000B59 -:104A1000154665B12A4631462046FFF7EFFE0346AC -:104A200060B94146204600F0EBFD0028F1D000239C -:104A300083F31188781B03B0BDE8F08FB9F1000F44 -:104A400003D001902046C847019B8BF31188ED1AD3 -:104A50001E448AF31188DCE7026843681143016051 -:104A600003B11847704700001430FFF743BF000040 -:104A70004FF0FF331430FFF73DBF00003830FFF731 -:104A8000B9BF00004FF0FF333830FFF7B3BF00006D -:104A90001430FFF709BF00004FF0FF311430FFF76B -:104AA00003BF00003830FFF763BF00004FF0FF3254 -:104AB0003830FFF75DBF0000012914BF6FF013000D -:104AC00000207047FFF75ABD044B0360002343608A -:104AD000C0E9023301230374704700BF90780008D7 -:104AE00010B53023044683F31188FFF771FD0223CC -:104AF0000020237480F3118810BD000038B5C3690D -:104B000004460D461BB904210844FFF7A5FF2946BA -:104B100004F11400FFF7ACFE002806DA201D4FF464 -:104B20000061BDE83840FFF797BF38BD02684368B1 -:104B30001143016003B118477047000013B5406B83 -:104B400000F58054D4F8A4381A681178042914D1D7 -:104B5000017C022911D11979012312898B4013425A -:104B60000BD101A94C3002F00BF9D4F8A44802464D -:104B7000019B2179206800F0DFF902B010BD000030 -:104B8000143002F08DB800004FF0FF33143002F003 -:104B900087B800004C3002F05FB900004FF0FF33DF -:104BA0004C3002F059B90000143002F05BB800003C -:104BB0004FF0FF31143002F055B800004C3002F0D5 -:104BC0002BB900004FF0FF324C3002F025B9000045 -:104BD0000020704710B500F58054D4F8A4381A6846 -:104BE0001178042917D1017C022914D159790123A4 -:104BF00052898B4013420ED1143001F0EDFF024672 -:104C000048B1D4F8A4484FF4407361792068BDE8F6 -:104C1000104000F07FB910BD406BFFF7DBBF000014 -:104C2000704700007FB5124B01250426044603603F -:104C30000023057400F1840243602946C0E9023371 -:104C40000C4B0290143001934FF44073009601F026 -:104C50009FFF094B04F69442294604F14C0002944C -:104C6000CDE900634FF4407302F066F804B070BD04 -:104C7000B8780008194C00083D4B00080A6830233A -:104C800083F311880B790B3342F823004B791333EC -:104C900042F823008B7913B10B3342F8230000F55F -:104CA0008053C3F8A41802230374002080F31188F2 -:104CB0007047000038B5037F044613B190F85430B4 -:104CC000ABB90125201D0221FFF730FF04F11400CC -:104CD0006FF00101257700F0AFFC04F14C0084F87F -:104CE00054506FF00101BDE8384000F0A5BC38BD5C -:104CF00010B5012104460430FFF718FF0023237785 -:104D000084F8543010BD000038B504460025143036 -:104D100001F056FF04F14C00257702F025F8201D24 -:104D200084F854500121FFF701FF2046BDE83840C8 -:104D3000FFF750BF90F8803003F06003202B06D1BE -:104D400090F881200023212A03D81F2A06D80020AA -:104D50007047222AFBD1C0E91D3303E0034A4267B2 -:104D600007228267C3670120704700BF3C220020F2 -:104D700037B500F58055D5F8A4381A68117804299C -:104D80001AD1017C022917D11979012312898B408C -:104D9000134211D100F14C04204602F0A5F858B19D -:104DA00001A9204601F0ECFFD5F8A4480246019B7A -:104DB0002179206800F0C0F803B030BD01F10B0389 -:104DC000F0B550F8236085B004460D46FEB130239F -:104DD00083F3118804EB8507301D0821FFF7A6FE39 -:104DE000FB6806F14C005B691B681BB1019001F088 -:104DF000D5FF019803A901F0C3FF024648B1039B08 -:104E00002946204600F098F8002383F3118805B066 -:104E1000F0BDFB685A691268002AF5D01B8A013B75 -:104E20001340F1D104F18002EAE70000133138B5F4 -:104E300050F82140ECB1302383F3118804F58053FE -:104E4000D3F8A4281368527903EB8203DB689B69CB -:104E50005D6845B104216018FFF768FE294604F13A -:104E6000140001F0C3FE2046FFF7B4FE002383F3D5 -:104E7000118838BD7047000001F096B90123402227 -:104E8000002110B5044600F8303BFCF701FF002379 -:104E9000C4E9013310BD000010B53023044683F38C -:104EA00011882422416000210C30FCF7F1FE2046DD -:104EB00001F09CF902230020237080F3118810BDBB -:104EC00070B500EB8103054650690E461446DA6062 -:104ED00018B110220021FCF7DBFEA06918B11022E6 -:104EE0000021FCF7D5FE31462846BDE8704001F0B0 -:104EF0007DBA000083682022002103F0011310B561 -:104F0000044683601030FCF7C3FE2046BDE8104025 -:104F100001F0F8BAF0B4012500EB810447898D4017 -:104F2000E4683D43A469458123600023A260636077 -:104F3000F0BC01F015BB0000F0B4012500EB8104CA -:104F400007898D40E4683D4364690581236000233F -:104F5000A2606360F0BC01F08BBB000070B502235F -:104F600000250446242203702946C0F888500C30DE -:104F700040F8045CFCF78CFE204684F8705001F089 -:104F8000C9F963681B6823B129462046BDE8704013 -:104F9000184770BD0378052B10B504460AD080F879 -:104FA0008C300523037043681B680BB104219847BC -:104FB0000023A36010BD00000178052906D190F8F8 -:104FC0008C20436802701B6803B1184770470000CB -:104FD00070B590F87030044613B1002380F870303B -:104FE00004F18002204601F0B1FA63689B68B3B90E -:104FF00094F8803013F0600535D00021204601F090 -:10500000A3FD0021204601F093FD63681B6813B1E6 -:10501000062120469847062384F8703070BD20464C -:1050200098470028E4D0B4F88630A26F9A4288BF2F -:10503000A36794F98030A56F002B4FF0300380F206 -:105040000381002D00F0F280092284F8702083F3A0 -:10505000118800212046D4E91D23FFF76DFF0023AE -:1050600083F31188DAE794F8812003F07F0343EAA1 -:10507000022340F20232934200F0C58021D8B3F5FA -:10508000807F48D00DD8012B3FD0022B00F09380B9 -:10509000002BB2D104F1880262670222A267E367A3 -:1050A000C1E7B3F5817F00F09B80B3F5407FA4D1C9 -:1050B00094F88230012BA0D1B4F8883043F0020379 -:1050C00032E0B3F5006F4DD017D8B3F5A06F31D0F3 -:1050D000A3F5C063012B90D86368204694F8822022 -:1050E0005E6894F88310B4F88430B047002884D008 -:1050F000436863670368A3671AE0B3F5106F36D09F -:1051000040F6024293427FF478AF5C4B6367022320 -:10511000A3670023C3E794F88230012B7FF46DAFBF -:10512000B4F8883023F00203A4F88830C4E91D5590 -:10513000E56778E7B4F88030B3F5A06F0ED194F846 -:105140008230204684F88A3001F042F963681B6897 -:1051500013B1012120469847032323700023C4E99B -:105160001D339CE704F18B0363670123C3E72378B6 -:10517000042B10D1302383F311882046FFF7BAFEA9 -:1051800085F311880321636884F88B5021701B68B4 -:105190000BB12046984794F88230002BDED084F87B -:1051A0008B300423237063681B68002BD6D0022148 -:1051B00020469847D2E794F8843020461D0603F035 -:1051C0000F010AD501F0B4F9012804D002287FF4B8 -:1051D00014AF2B4B9AE72B4B98E701F09BF9F3E7C1 -:1051E00094F88230002B7FF408AF94F8843013F0E9 -:1051F0000F01B3D01A06204602D501F0BDFCADE781 -:1052000001F0AEFCAAE794F88230002B7FF4F5AEF3 -:1052100094F8843013F00F01A0D01B06204602D56D -:1052200001F092FC9AE701F083FC97E7142284F8DE -:10523000702083F311882B462A4629462046FFF723 -:1052400069FE85F31188E9E65DB1152284F87020C6 -:1052500083F3118800212046D4E91D23FFF75AFE6D -:10526000FDE60B2284F8702083F311882B462A4632 -:1052700029462046FFF760FEE3E700BFE878000814 -:10528000E0780008E478000838B590F870300446FB -:10529000002B3ED0063BDAB20F2A34D80F2B32D87F -:1052A000DFE803F037313108223231313131313129 -:1052B00031313737856FB0F886309D4214D2C368DC -:1052C0001B8AB5FBF3F203FB12556DB9302383F350 -:1052D00011882B462A462946FFF72EFE85F31188B2 -:1052E0000A2384F870300EE0142384F870303023E1 -:1052F00083F31188002320461A461946FFF70AFE59 -:10530000002383F3118838BDC36F03B1984700238E -:10531000E7E70021204601F017FC0021204601F0BC -:1053200007FC63681B6813B10621204698470623D3 -:10533000D7E7000010B590F870300446142B29D040 -:1053400017D8062B05D001D81BB110BD093B022B85 -:10535000FBD80021204601F0F7FB0021204601F098 -:10536000E7FB63681B6813B10621204698470623B4 -:1053700019E0152BE9D10B2380F87030302383F32B -:10538000118800231A461946FFF7D6FD002383F340 -:105390001188DAE7C3689B695B68002BD5D1C36FBE -:1053A00003B19847002384F87030CEE70023826869 -:1053B000037503691B6899689142FBD25A680360C0 -:1053C000426010605860704700238268037503696B -:1053D0001B6899689142FBD85A680360426010606C -:1053E0005860704708B50846302383F311880B7D59 -:1053F000032B05D0042B0DD02BB983F3118808BDE6 -:105400008B6900221A604FF0FF338361FFF7CEFFF4 -:105410000023F2E7D1E9003213605A60F3E700009D -:10542000FFF7C4BF054BD968087518680268536058 -:105430001A600122D8600275FBF76EB9F0520020A5 -:105440000C4B30B5DD684B1C87B004460FD02B46A3 -:10545000094A684600F084F92046FFF7E3FF009B05 -:1054600013B1684600F086F9A86907B030BDFFF7B0 -:10547000D9FFF9E7F0520020E5530008044B1A6801 -:10548000DB6890689B68984294BF002001207047B9 -:10549000F0520020084B10B51C68D8682268536091 -:1054A0001A600122DC602275FFF78EFF014620465C -:1054B000BDE81040FBF730B9F0520020044B1A68E9 -:1054C000DB6892689B689A4201D9FFF7E3BF704797 -:1054D000F052002038B5074C012300250649074843 -:1054E0002370656001F03EFD0223237085F311886F -:1054F00038BD00BF58550020F0780008F052002059 -:1055000008B572B6044B186500F06AFC00F03CFD6B -:10551000024B03221A70FEE7F0520020585500207B -:1055200000F05EB9EFF3118020B9EFF3058330226C -:1055300082F311887047000010B530B9EFF305848D -:10554000C4F3080414B180F3118810BDFFF7B6FF4F -:1055500084F31188F9E70000034A516853685B1A25 -:105560009842FBD8704700BF001000E08B60022318 -:10557000086108468B8270478368A3F1840243F870 -:10558000142C026943F8442C426943F8402C094A20 -:1055900043F8242CC268A3F1200043F8182C0222FF -:1055A00003F80C2C002203F80B2C034A43F8102CB0 -:1055B000704700BF31070008F052002008B5FFF720 -:1055C000DBFFBDE80840FFF72BBF0000024BDB68A4 -:1055D00098610F20FFF726BFF0520020302383F39D -:1055E0001188FFF7F3BF000008B50146302383F3AD -:1055F00011880820FFF724FF002383F3118808BDDA -:10560000064BDB6839B1426818605A60136043602A -:105610000420FFF715BF4FF0FF307047F052002015 -:105620000368984206D01A68026050601846996173 -:10563000FFF7F6BE7047000038B504460D462068F7 -:10564000844200D138BD036823605C608561FFF748 -:10565000E7FEF4E7036810B59C68A2420CD85C68CA -:105660008A600B604C602160596099688A1A9A6060 -:105670004FF0FF33836010BD121B1B68ECE7000086 -:105680000A2938BF0A2170B504460D460A2660195A -:1056900001F060FC01F048FC041BA54203D8751C16 -:1056A00004462E46F3E70A2E04D90120BDE87040D7 -:1056B00001F098BC70BD0000F8B5144B0D460A2AE5 -:1056C0004FF00A07D96103F11001826038BF0A2246 -:1056D000416019691446016048601861A81801F01A -:1056E00029FC01F021FC431B0646A34206D37C1C87 -:1056F00028192746354601F02DFCF2E70A2F04D978 -:105700000120BDE8F84001F06DBCF8BDF05200206A -:10571000F8B506460D4601F007FC0F4A134653F84C -:10572000107F9F4206D12A4601463046BDE8F84028 -:10573000FFF7C2BFD169BB68441A2C1928BF2C4699 -:10574000A34202D92946FFF79BFF22463146034870 -:10575000BDE8F840FFF77EBFF05200200053002064 -:10576000C0E90323002310B45DF8044B4361FFF745 -:10577000CFBF000010B5194C236998420DD0816845 -:10578000D0E9003213605A609A680A449A60002394 -:1057900003604FF0FF33A36110BD0268234643F856 -:1057A000102F53600022026022699A4203D1BDE8A3 -:1057B000104001F0C9BB936881680B44936001F00D -:1057C000B3FB2269E1699268441AA242E4D9114408 -:1057D000BDE81040091AFFF753BF00BFF052002088 -:1057E0002DE9F047DFF8BC8008F110072C4ED8F8FF -:1057F000105001F099FBD8F81C40AA68031B9A428C -:105800003ED814444FF00009D5E90032C8F81C40D6 -:1058100013605A60C5F80090D8F81030B34201D137 -:1058200001F092FB89F31188D5E9033128469847A6 -:10583000302383F311886B69002BD8D001F074FBFF -:105840006A69A0EB040982464A450DD2022001F0A4 -:10585000C9FB0022D8F81030B34208D1514628467F -:10586000BDE8F047FFF728BF121A2244F2E712EB17 -:1058700009092946384638BF4A46FFF7EBFEB5E727 -:10588000D8F81030B34208D01444C8F81C00211ACC -:10589000A960BDE8F047FFF7F3BEBDE8F08700BFA1 -:1058A00000530020F052002000207047FEE7000067 -:1058B000704700004FF0FF307047000002290CD005 -:1058C000032904D00129074818BF00207047032A84 -:1058D00005D8054800EBC200704704487047002017 -:1058E000704700BFC87900084C2200207C7900086E -:1058F00070B59AB005460846144601A900F0C2F8F2 -:1059000001A8FCF7BDF9431C0022C6B25B0010469B -:10591000C5E9003423700323023404F8013C01ABD1 -:10592000D1B202348E4201D81AB070BD13F8011BF7 -:10593000013204F8010C04F8021CF1E708B5302329 -:1059400083F311880348FFF713FA002383F31188C8 -:1059500008BD00BF6055002090F8803003F01F02A2 -:10596000012A07D190F881200B2A03D10023C0E936 -:105970001D3315E003F06003202B08D1B0F884300C -:105980002BB990F88120212A03D81F2A04D8FFF7C9 -:10599000D1B9222AEBD0FAE7034A4267072282678D -:1059A000C3670120704700BF4322002007B50529C7 -:1059B00017D8DFE801F0191603191920302383F3F3 -:1059C0001188104A01210190FFF77AFA019802210B -:1059D0000D4AFFF775FA0D48FFF796F9002383F398 -:1059E000118803B05DF804FB302383F31188074866 -:1059F000FFF760F9F2E7302383F311880348FFF7DC -:105A000077F9EBE71C790008407900086055002021 -:105A100038B50C4D0C4C2A460C4904F10800FFF730 -:105A200067FF05F1CA0204F110000949FFF760FFA2 -:105A300005F5CA7204F118000649BDE83840FFF7C1 -:105A400057BF00BF386E00204C220020FC780008B1 -:105A5000067900081179000870B5044608460D461D -:105A6000FCF70EF9C6B22046013403780BB918468C -:105A700070BD32462946FCF7EFF80028F3D101202B -:105A8000F6E700002DE9F04705460C46FCF7F8F86C -:105A90002A49C6B22846FFF7DFFF08B10936F6B239 -:105AA00027492846FFF7D8FF08B11036F6B2632E13 -:105AB0000BD8DFF88880DFF88890224FDFF890A0BD -:105AC0002E7846B92670BDE8F08729462046BDE805 -:105AD000F04701F051BE252E2CD107224146284621 -:105AE000FCF7BAF860B9184B224603F1100153F8DD -:105AF000040B8B4242F8040BF9D107351034DFE771 -:105B0000082249462846FCF7A7F898B9A21C0F4B73 -:105B1000197802320909C95D02F8041C13F8011B47 -:105B200001F00F015345C95D02F8031CF0D1183490 -:105B30000835C5E7013504F8016BC1E7E8790008CD -:105B400011790008F07900089677000800E8F11F45 -:105B50000CE8F11FBFF34F8F044B1A695107FCD1BA -:105B6000D3F810215207F8D1704700BF002000522F -:105B700008B50D4B1B78ABB9FFF7ECFF0B4BDA68A0 -:105B8000D10704D50A4A5A6002F188325A60D3F824 -:105B90000C21D20706D5064AC3F8042102F1883247 -:105BA000C3F8042108BD00BF9670002000200052F9 -:105BB0002301674508B5114B1B78F3B9104B1A69DF -:105BC000510703D5DA6842F04002DA60D3F81021B9 -:105BD000520705D5D3F80C2142F04002C3F80C213E -:105BE000FFF7B8FF064BDA6842F00102DA60D3F83B -:105BF0000C2142F00102C3F80C2108BD9670002070 -:105C0000002000520F289ABF00F580604004002059 -:105C1000704700004FF400307047000010207047BC -:105C20000F2808B50BD8FFF7EDFF00F50033026829 -:105C3000013204D104308342F9D1012008BD002093 -:105C4000FCE700000F2838B505463FD8FFF782FF74 -:105C50001F4CFFF78DFF4FF0FF3307286361C4F837 -:105C600014311DD82361FFF775FF030243F02403AD -:105C7000E360E36843F08003E36023695A07FCD4E0 -:105C80002846FFF767FFFFF7BDFF4FF4003100F034 -:105C900057F92846FFF78EFFBDE83840FFF7C0BF31 -:105CA000C4F81031FFF756FFA0F108031B0243F0C0 -:105CB0002403C4F80C31D4F80C3143F08003C4F849 -:105CC0000C31D4F810315B07FBD4D9E7002038BD84 -:105CD000002000522DE9F84F05460C46104645EAD3 -:105CE0000203DE0602D00020BDE8F88F20F01F007E -:105CF000DFF8BCB0DFF8BCA0FFF73AFF04EB000808 -:105D0000444503D10120FFF755FFEDE72022294646 -:105D1000204601F0FFFC10B920352034F0E72B4677 -:105D200005F120021F68791CDDD104339A42F9D1B4 -:105D300005F178431B481C4EB3F5801F1B4B38BF41 -:105D4000184603F1F80332BFD946D1461E46FFF785 -:105D500001FF0760A5EB040C336804F11C0143F05C -:105D600002033360231FD9F8007017F00507FAD13A -:105D700053F8042F8B424CF80320F4D1BFF34F8F1C -:105D8000FFF7E8FE4FF0FF3320222146036028464C -:105D9000336823F00203336001F0BCFC0028BBD061 -:105DA0003846B0E7142100520C2000521420005253 -:105DB000102000521021005210B5084C237828B151 -:105DC0001BB9FFF7D5FE0123237010BD002BFCD0BB -:105DD0002070BDE81040FFF7EDBE00BF96700020B8 -:105DE00038B5054D00240334696855F80C0B00F0F4 -:105DF000B9F8122CF7D138BD047A0008084601F032 -:105E000081BC000070B5104E82B0FFF78BFB0546D9 -:105E100001F08AF8326803469042336037BF0B4A7C -:105E20000A495168146836BF0131D1E90041516017 -:105E30000419284641F100010191FFF77DFB20463E -:105E4000019902B070BD00BF98700020A0700020C2 -:105E500070B5124E82B0FFF765FB054601F064F89D -:105E6000326803469042336037BF0D4A0C4951688F -:105E7000146836BF0131D1E9004151600419284648 -:105E800041F100010191FFF757FB4FF47A720023B3 -:105E900020460199FAF72CFA02B070BD98700020E4 -:105EA000A07000200244074BD2B210B5904200D13E -:105EB00010BD441C00B253F8200041F8040BE0B2BE -:105EC000F4E700BF504000580E4B30B51C6F24045F -:105ED00005D41C6F1C671C6F44F400441C670A4CFB -:105EE00002442368D2B243F480732360074B90428C -:105EF00000D130BD441C51F8045B00B243F820507F -:105F0000E0B2F4E7004402580048025850400058FC -:105F100007B5012201A90020FFF7C4FF019803B0D3 -:105F20005DF804FB13B50446FFF7F2FFA04205D06D -:105F3000012201A900200194FFF7C6FF02B010BDA5 -:105F40000144BFF34F8F064B884204D3BFF34F8FFA -:105F5000BFF36F8F7047C3F85C022030F4E700BFD7 -:105F600000ED00E00144BFF34F8F064B884204D39D -:105F7000BFF34F8FBFF36F8F7047C3F870022030AD -:105F8000F4E700BF00ED00E070470000074B45F26A -:105F900055521A6002225A6040F6FF729A604CF61F -:105FA000CC421A600122024B1A7070470048005818 -:105FB000AC700020034B1B781BB1034B4AF6AA229E -:105FC0001A607047AC70002000480058034B1A68F4 -:105FD0001AB9034AD2F8D0241A607047A87000207A -:105FE00000400258024B4FF48032C3F8D02470476F -:105FF0000040025808B5FFF7E9FF024B1868C0F3EC -:10600000806008BDA870002070B5BFF34F8FBFF34C -:106010006F8F1A4A0021C2F85012BFF34F8FBFF39F -:106020006F8F536943F400335361BFF34F8FBFF356 -:106030006F8FC2F88410BFF34F8FD2F8803043F6D1 -:10604000E074C3F3C900C3F34E335B0103EA0406F3 -:10605000014646EA81750139C2F86052F9D2203B07 -:1060600013F1200FF2D1BFF34F8F536943F4803304 -:106070005361BFF34F8FBFF36F8F70BD00ED00E032 -:10608000FEE70000214B2248224A70B5904237D3E8 -:10609000214BC11EDA1C121A22F003028B4238BFB8 -:1060A00000220021FBF7F4FD1C4A0023C2F88430D3 -:1060B000BFF34F8FD2F8803043F6E074C3F3C900CA -:1060C000C3F34E335B0103EA0406014646EA8175D9 -:1060D0000139C2F86C52F9D2203B13F1200FF2D1F2 -:1060E000BFF34F8FBFF36F8FBFF34F8FBFF36F8F30 -:1060F0000023C2F85032BFF34F8FBFF36F8F70BDD4 -:1061000053F8041B40F8041BC0E700BFA07C000844 -:1061100080720020807200208072002000ED00E07C -:10612000054B996B21EA000199631A6E22EA00027D -:106130001A661B6E704700BF0045025870B5D0E963 -:10614000244300224FF0FF359E6804EB42135101B7 -:10615000D3F80009002805DAD3F8000940F08040A0 -:10616000C3F80009D3F8000B002805DAD3F8000BB8 -:1061700040F08040C3F8000B013263189642C3F828 -:106180000859C3F8085BE0D24FF00113C4F81C387B -:1061900070BD0000890141F02001016103699B0687 -:1061A000FCD41220FFF7D8B910B50A4C2046FEF7F0 -:1061B00065FE094BC4F89030084BC4F89430084C85 -:1061C0002046FEF75BFE074BC4F89030064BC4F840 -:1061D000943010BDB070002000000840707A0008B4 -:1061E0004C710020000004407C7A000870B50378F0 -:1061F0000546012B58D13F4BD0F89040984254D1DE -:106200003D4B0E2165209A6B42F000629A631A6E34 -:1062100042F000621A661B6E384BD3F8802042F0C1 -:106220000062C3F88020D3F8802022F00062C3F817 -:106230008020D3F88030FEF79DFA314BE360314B7C -:10624000C4F800380023D5F89060C4F8003EC0239D -:1062500023604FF40413A3633369002BFCDA01239A -:106260000C203361FFF778F93369DB07FCD4122087 -:10627000FFF772F93369002BFCDA00262846A66086 -:10628000FFF75CFF6B68C4F81068DB68C4F814683B -:10629000C4F81C6863BB1C4BA3614FF0FF33636100 -:1062A000A36843F00103A36070BD184B9842C9D1A5 -:1062B000114B4FF080609A6B42F000729A631A6E35 -:1062C00042F000721A661B6E0C4BD3F8802042F02D -:1062D0000072C3F88020D3F8802022F00072C3F847 -:1062E0008020D3F88030FFF71BFF0E214D20A2E75E -:1062F000074BD1E7B0700020004502580044025817 -:106300004014004003002002003C30C04C710020CB -:10631000083C30C0F8B5D0F89040054600214FF059 -:1063200000662046FFF736FFD5F8941000234FF0A3 -:1063300001128F684FF0FF30C4F83438C4F81C28BD -:1063400004EB431201339F42C2F80069C2F8006BAC -:10635000C2F80809C2F8080BF2D20B68D5F89020F1 -:10636000C5F89830636210231361166916F01006A1 -:10637000FBD11220FFF7F0F8D4F8003823F4FE63C5 -:10638000C4F80038A36943F4402343F01003A36129 -:106390000923C4F81038C4F814380B4BEB604FF0E5 -:1063A000C043C4F8103B094BC4F8003BC4F8106963 -:1063B000C4F80039D5F8983003F1100243F4801383 -:1063C000C5F89820A362F8BD4C7A00084080001000 -:1063D000D0F8902090F88A10D2F8003823F4FE63A9 -:1063E00043EA0113C2F80038704700002DE9F84372 -:1063F00000EB8103D0F890500C468046DA680FFA23 -:1064000081F94801166806F00306731E022B05EB9E -:1064100041134FF0000194BFB604384EC3F8101B6F -:106420004FF0010104F1100398BF06F1805601FA04 -:1064300003F3916998BF06F5004600293AD0578AC0 -:1064400004F15801374349016F50D5F81C180B432C -:106450000021C5F81C382B180127C3F81019A740D4 -:106460005369611E9BB3138A928B9B08012A88BFD4 -:106470005343D8F89820981842EA034301F14002A8 -:106480002146C8F89800284605EB82025360FFF7C2 -:1064900081FE08EB8900C3681B8A43EA84534834B1 -:1064A0001E4364012E51D5F81C381F43C5F81C78D3 -:1064B000BDE8F88305EB4917D7F8001B21F400412C -:1064C000C7F8001BD5F81C1821EA0303C0E704F144 -:1064D0003F030B4A2846214605EB83035A60FFF72A -:1064E00059FE05EB4910D0F8003923F40043C0F8F9 -:1064F0000039D5F81C3823EA0707D7E700800010D9 -:1065000000040002D0F894201268C0F89820FFF729 -:1065100015BE00005831D0F8903049015B5813F493 -:10652000004004D013F4001F0CBF0220012070476C -:106530004831D0F8903049015B5813F4004004D042 -:1065400013F4001F0CBF02200120704700EB8101F3 -:10655000CB68196A0B6813604B6853607047000082 -:1065600000EB810330B5DD68AA691368D36019B9FF -:10657000402B84BF402313606B8A1468D0F89020AE -:106580001C4402EB4110013C09B2B4FBF3F4634339 -:10659000033323F0030343EAC44343F0C043C0F88A -:1065A000103B2B6803F00303012B0ED1D2F80838FF -:1065B00002EB411013F4807FD0F8003B14BF43F08E -:1065C000805343F00053C0F8003B02EB4112D2F875 -:1065D000003B43F00443C2F8003B30BD2DE9F041DD -:1065E000D0F8906005460C4606EB4113D3F8087BC3 -:1065F0003A07C3F8087B08D5D6F814381B0704D52A -:1066000000EB8103DB685B689847FA071FD5D6F873 -:106610001438DB071BD505EB8403D968CCB98B692B -:10662000488A5A68B2FBF0F600FB16228AB918684D -:10663000DA6890420DD2121AC3E90024302383F3A2 -:10664000118821462846FFF78BFF84F31188BDE8A7 -:10665000F081012303FA04F26B8923EA02036B81C0 -:10666000CB68002BF3D021462846BDE8F0411847FF -:1066700000EB81034A0170B5DD68D0F890306C6999 -:106680002668E66056BB1A444FF40020C2F8100991 -:106690002A6802F00302012A0AB20ED1D3F80808D0 -:1066A00003EB421410F4807FD4F8000914BF40F0CB -:1066B000805040F00050C4F8000903EB4212D2F8B9 -:1066C000000940F00440C2F800090122D3F8340860 -:1066D00002FA01F10143C3F8341870BD19B9402E14 -:1066E00084BF4020206020681A442E8A8419013C0F -:1066F000B4FBF6F440EAC44040F00050C6E70000A6 -:106700002DE9F843D0F8906005460C464F0106EBA2 -:106710004113D3F8088918F0010FC3F808891CD079 -:10672000D6F81038DB0718D500EB8103D3F80CC07E -:10673000DCF81430D3F800E0DA68964530D2A2EBEA -:106740000E024FF000091A60C3F80490302383F35F -:106750001188FFF78DFF89F3118818F0800F1DD085 -:10676000D6F834380126A640334217D005EB84030F -:106770000134D5F89050D3F80CC0E4B22F44DCF8C3 -:10678000142005EB0434D2F800E05168714514D3AD -:10679000D5F8343823EA0606C5F83468BDE8F8832E -:1067A000012303FA01F2038923EA02030381DCF8DF -:1067B0000830002BD1D09847CFE7AEEB0103BCF8EF -:1067C0001000834228BF0346D7F8180980B2B3EB04 -:1067D000800FE3D89068A0F1040959F8048FC4F839 -:1067E0000080A0EB09089844B8F1040FF5D81844CC -:1067F0000B4490605360C8E72DE9F84FD0F89050F3 -:1068000004466E69AB691E4016F480586E6103D071 -:10681000BDE8F84FFEF7A2BB002E12DAD5F8003E15 -:106820009B0705D0D5F8003E23F00303C5F8003ED2 -:10683000D5F80438204623F00103C5F80438FEF7E4 -:10684000BBFB370505D52046FFF778FC2046FEF751 -:10685000A1FBB0040CD5D5F8083813F0060FEB688F -:1068600023F470530CBF43F4105343F4A053EB6074 -:1068700031071BD56368DB681BB9AB6923F00803DC -:10688000AB612378052B0CD1D5F8003E9A0705D0D3 -:10689000D5F8003E23F00303C5F8003E2046FEF77E -:1068A0008BFB6368DB680BB120469847F30200F16D -:1068B000BA80B70226D5D4F8909000274FF0010A8D -:1068C00009EB4712D2F8003B03F44023B3F5802FC5 -:1068D00011D1D2F8003B002B0DDA62890AFA07F3D6 -:1068E00022EA0303638104EB8703DB68DB6813B1EF -:1068F0003946204698470137D4F89430FFB29B6858 -:106900009F42DDD9F00619D5D4F89000026AC2F38F -:106910000A1702F00F0302F4F012B2F5802F00F014 -:10692000CA80B2F5402F09D104EB8303002200F5A1 -:106930008050DB681B6A974240F0B0803003D5F886 -:10694000185835D5E90303D500212046FFF746FE48 -:10695000AA0303D501212046FFF740FE6B0303D5B0 -:1069600002212046FFF73AFE2F0303D503212046DC -:10697000FFF734FEE80203D504212046FFF72EFE80 -:10698000A90203D505212046FFF728FE6A0203D598 -:1069900006212046FFF722FE2B0203D507212046C1 -:1069A000FFF71CFEEF0103D508212046FFF716FE76 -:1069B000700340F1A780E90703D500212046FFF7C7 -:1069C0009FFEAA0703D501212046FFF799FE6B071A -:1069D00003D502212046FFF793FE2F0703D503219D -:1069E0002046FFF78DFEEE0603D504212046FFF773 -:1069F00087FEA80603D505212046FFF781FE69061C -:106A000003D506212046FFF77BFE2A0603D5072182 -:106A10002046FFF775FEEB0574D520460821BDE83A -:106A2000F84FFFF76DBED4F890904FF0000B4FF089 -:106A3000010AD4F894305FFA8BF79B689F423FF6C7 -:106A400038AF09EB4713D3F8002902F44022B2F51E -:106A5000802F20D1D3F80029002A1CDAD3F800298E -:106A600042F09042C3F80029D3F80029002AFBDB4A -:106A70003946D4F89000FFF78DFB22890AFA07F314 -:106A800022EA0303238104EB8703DB689B6813B1CD -:106A90003946204698470BF1010BCAE7910701D10F -:106AA000D0F80080072A02F101029CBF03F8018B95 -:106AB0004FEA18283FE704EB830300F58050DA68BB -:106AC000D2F818C0DCF80820DCE9001CA1EB0C0CA3 -:106AD00000218F4208D1DB689B699A683A449A602A -:106AE0005A683A445A6029E711F0030F01D1D0F8EF -:106AF00000808C4501F1010184BF02F8018B4FEA4F -:106B00001828E6E7BDE8F88F08B50348FFF774FEDC -:106B1000BDE80840FDF7F8BCB070002008B5034898 -:106B2000FFF76AFEBDE80840FDF7EEBC4C7100209F -:106B3000D0F8903003EB4111D1F8003B43F400133F -:106B4000C1F8003B70470000D0F8903003EB4111D2 -:106B5000D1F8003943F40013C1F800397047000040 -:106B6000D0F8903003EB4111D1F8003B23F400132F -:106B7000C1F8003B70470000D0F8903003EB4111A2 -:106B8000D1F8003923F40013C1F800397047000030 -:106B900030B50433039C0172002104FB0325C1605E -:106BA000C0E90653049B0363059BC0E90000C0E9EC -:106BB0000422C0E90842C0E90A11436330BD000065 -:106BC0000022416AC260C0E90411C0E90A226FF0E4 -:106BD0000101FEF731BD0000D0E90432934201D13A -:106BE000C2680AB9181D7047002070470369196010 -:106BF0000021C2680132C260C269134482699342B3 -:106C0000036124BF436A0361FEF70ABD38B5044639 -:106C10000D46E3683BB162690020131D1268A36250 -:106C20001344E36207E0237A33B929462046FEF78E -:106C3000E7FC0028EDDA38BD6FF00100FBE700004B -:106C4000C368C269013BC3604369134482699342CC -:106C5000436124BF436A436100238362036B03B132 -:106C60001847704770B53023044683F31188866A4D -:106C70003EB9FFF7CBFF054618B186F311882846C9 -:106C800070BDA36AE26A13F8015B9342A36202D368 -:106C90002046FFF7D5FF002383F31188EFE70000BC -:106CA0002DE9F84F04460E46174698464FF0300936 -:106CB00089F311880025AA46D4F828B0BBF1000F4B -:106CC00009D141462046FFF7A1FF20B18BF311887F -:106CD0002846BDE8F88FD4E90A12A7EB050B521A33 -:106CE000934528BF9346BBF1400F1BD9334601F1B2 -:106CF000400251F8040B914243F8040BF9D1A36A06 -:106D0000403640354033A362D4E90A239A4202D385 -:106D10002046FFF795FF8AF31188BD42D8D289F348 -:106D20001188C9E730465A46FAF78CFFA36A5E44D9 -:106D30005D445B44A362E7E710B5029C0433017233 -:106D400003FB0421C460C0E906130023C0E90A3331 -:106D5000039B0363049BC0E90000C0E90422C0E96F -:106D60000842436310BD0000026A6FF00101C26077 -:106D7000426AC0E904220022C0E90A22FEF75CBC94 -:106D8000D0E904239A4201D1C26822B9184650F8CA -:106D9000043B0B60704700231846FAE7C3680021E4 -:106DA000C2690133C36043691344826993424361FA -:106DB00024BF436A4361FEF733BC000038B5044684 -:106DC0000D46E3683BB1236900201A1DA262E26907 -:106DD0001344E36207E0237A33B929462046FEF7DD -:106DE0000FFC0028EDDA38BD6FF00100FBE7000072 -:106DF00003691960C268013AC260C26913448269BA -:106E00009342036124BF436A036100238362036BDF -:106E100003B118477047000070B530230D46044693 -:106E2000114683F31188866A2EB9FFF7C7FF10B1A8 -:106E300086F3118870BDA36A1D70A36AE26A0133EC -:106E40009342A36204D3E16920460439FFF7D0FFDF -:106E5000002080F31188EDE72DE9F84F04460D4638 -:106E6000904699464FF0300A8AF311880026B346BF -:106E7000A76A4FB949462046FFF7A0FF20B187F324 -:106E800011883046BDE8F88FD4E90A073A1AA8EB12 -:106E90000607974228BF1746402F1BD905F140032C -:106EA00055F8042B9D4240F8042BF9D1A36A4036D3 -:106EB0004033A362D4E90A239A4204D3E16920460D -:106EC0000439FFF795FF8BF311884645D9D28AF331 -:106ED0001188CDE729463A46FAF7B4FEA36A3D4445 -:106EE0003E443B44A362E5E7D0E904239A4217D12C -:106EF000C3689BB1836A8BB1043B9B1A0ED01360AD -:106F0000C368013BC360C3691A4483699A42026142 -:106F100024BF436A0361002383620123184670473C -:106F20000023FBE700F01CB9014B586A704700BF13 -:106F3000000C0040034B002258631A610222DA6001 -:106F4000704700BF000C0040014B0022DA60704720 -:106F5000000C0040014B5863704700BF000C00401C -:106F6000FEE7000070B51B4B0025044686B0586054 -:106F70000E4685620163FDF79FFA04F11003A560D8 -:106F8000E562C4E904334FF0FF33C4E90044C4E9C7 -:106F90000635FFF7C9FF2B46024604F134012046AF -:106FA000C4E9082380230C4A2565FEF7DFFA012394 -:106FB0000A4AE06000920375684672680192B268FE -:106FC000CDE90223064BCDE90435FEF7F7FA06B00A -:106FD00070BD00BF58550020887A00088D7A0008DF -:106FE000616F0008024AD36A1843D062704700BF3D -:106FF000F05200204B6843608B688360CB68C360AD -:107000000B6943614B6903628B6943620B680360E0 -:107010007047000008B53A4B40F2FF713948D3F889 -:1070200088200A43C3F88820D3F8882022F4FF621E -:1070300022F00702C3F88820D3F88830324B1A6C4C -:107040000A431A649A6E0A439A66304A9B6E114646 -:10705000FFF7D0FF00F5806002F11C01FFF7CAFFC7 -:1070600000F5806002F13801FFF7C4FF00F5806091 -:1070700002F15401FFF7BEFF00F5806002F17001DC -:10708000FFF7B8FF00F5806002F18C01FFF7B2FF57 -:1070900000F5806002F1A801FFF7ACFF00F5806009 -:1070A00002F1C401FFF7A6FF00F5806002F1E001E4 -:1070B000FFF7A0FF00F5806002F1FC01FFF79AFFE7 -:1070C00002F58C7100F58060FFF794FF00F006F97F -:1070D0000F4BD3F8902242F00102C3F89022D3F86C -:1070E000942242F00102C3F894220522C3F89820AA -:1070F0004FF06052C3F89C20064AC3F8A02008BD98 -:10710000004402580000025800450258947A0008D2 -:1071100000ED00E01F00080308B500F0BDFAFEF71F -:10712000D9F90C4BDA6B42F04002DA635A6E22F066 -:1071300040025A665B6E084B1A6842F008021A60F9 -:107140001A6842F004021A60FEF740FFBDE80840EA -:10715000FEF75EBC00450258001802487047000068 -:107160000E4B9A6C42F008029A641A6F42F00802C1 -:107170001A670B4A1B6FD36B43F00803D363C72214 -:10718000084B9A624FF0FF32DA6200229A615A632A -:10719000DA605A6001225A611A607047004502584D -:1071A0000010005C000C0040094A08B51169D36862 -:1071B0000B40D9B29B076FEA0101116107D530235B -:1071C00083F31188FEF7ACF9002383F3118808BD1F -:1071D000000C0040044BDA6B0243DA635A6E104332 -:1071E00058665B6E704700BF004502583A4B4FF03F -:1071F000FF31D3F8802062F00042C3F88020D3F83A -:10720000802002F00042C3F88020D3F88020D3F819 -:107210008420C3F88410D3F884200022C3F884208B -:10722000D3F88400D86F40F0FF4040F4FF0040F4F2 -:10723000DF4040F07F00D867D86F20F0FF4020F497 -:10724000FF0020F4DF4020F07F00D867D86FD3F82C -:1072500088006FEA40506FEA5050C3F88800D3F8B6 -:107260008800C0F30A00C3F88800D3F88800D3F878 -:107270009000C3F89010D3F89000C3F89020D3F892 -:107280009000D3F89400C3F89410D3F89400C3F896 -:107290009420D3F89400D3F89800C3F89810D3F84A -:1072A0009800C3F89820D3F89800D3F88C00C3F85E -:1072B0008C10D3F88C00C3F88C20D3F88C00D3F852 -:1072C0009C00C3F89C10D3F89C10C3F89C20D3F802 -:1072D0009C3000F0B5B900BF0044025808B5012247 -:1072E000504BC3F80821504B5A6D42F002025A65C8 -:1072F000DA6F42F00202DA670422DB6F4B4BDA608E -:107300005A689104FCD54A4A1A6001229A60494A97 -:10731000DA6000221A614FF440429A61434B9A6945 -:107320009204FCD51A6842F480721A60424B1A6FBC -:1073300012F4407F04D04FF480321A6700221A679B -:107340001A6842F001021A603B4B1A685007FCD5DC -:1073500000221A611A6912F03802FBD1012119606A -:107360004FF0804159605A67344ADA62344A1A61F0 -:107370001A6842F480321A602F4B1A689103FCD5C8 -:107380001A6842F480521A601A689204FCD52D4A99 -:107390002D499A6200225A63196301F57C01DA6370 -:1073A00001F5E77199635A64284A1A64284ADA6237 -:1073B0001A6842F0A8521A601F4B1A6802F028524D -:1073C000B2F1285FF9D148229A614FF48862DA61FC -:1073D00040221A621F4ADA641F4A1A651F4A5A6518 -:1073E0001F4A9A6532231F4A1360136803F00F0384 -:1073F000022BFAD1104A136943F003031361136996 -:1074000003F03803182BFAD14FF00050FFF7E2FEDB -:107410004FF08040FFF7DEFE4FF00040BDE808402F -:10742000FFF7D8BE008000510045025800480258BE -:1074300000C000F004000001004402580000FF01F9 -:10744000008890083220600063020901470E050899 -:10745000DD0BBF0120000020000001100910E0003A -:1074600000010110002000524FF0B04208B5D2F8E0 -:10747000883003F00103C2F8883023B1044A13684E -:107480000BB150689847BDE80840FDF73DB800BF14 -:10749000007200204FF0B04208B5D2F8883003F0F7 -:1074A0000203C2F8883023B1044A93680BB1D06854 -:1074B0009847BDE80840FDF727B800BF00720020DC -:1074C0004FF0B04208B5D2F8883003F00403C2F898 -:1074D000883023B1044A13690BB150699847BDE85D -:1074E0000840FDF711B800BF007200204FF0B04215 -:1074F00008B5D2F8883003F00803C2F8883023B109 -:10750000044A93690BB1D0699847BDE80840FCF77D -:10751000FBBF00BF007200204FF0B04208B5D2F8A8 -:10752000883003F01003C2F8883023B1044A136A8C -:107530000BB1506A9847BDE80840FCF7E5BF00BFB3 -:10754000007200204FF0B04310B5D3F8884004F427 -:107550007872C3F88820A30604D5124A936A0BB147 -:10756000D06A9847600604D50E4A136B0BB1506B76 -:107570009847210604D50B4A936B0BB1D06B984703 -:10758000E20504D5074A136C0BB1506C9847A3056C -:1075900004D5044A936C0BB1D06C9847BDE81040F9 -:1075A000FCF7B2BF007200204FF0B04310B5D3F823 -:1075B000884004F47C42C3F88820620504D5164A4A -:1075C000136D0BB1506D9847230504D5124A936D86 -:1075D0000BB1D06D9847E00404D50F4A136E0BB180 -:1075E000506E9847A10404D50B4A936E0BB1D06E30 -:1075F0009847620404D5084A136F0BB1506F98473F -:10760000230404D5044A936F0BB1D06F9847BDE8AB -:107610001040FCF779BF00BF0072002008B5034896 -:10762000FDF722F8BDE80840FCF76EBF804E002051 -:1076300008B5FFF7B9FDBDE80840FCF765BF0000DD -:10764000062108B50846FDF795F806210720FDF745 -:1076500091F806210820FDF78DF806210920FDF795 -:1076600089F806210A20FDF785F806211720FDF785 -:1076700081F806212820FDF77DF809217A20FDF701 -:1076800079F807213220FDF775F80C215220BDE86A -:107690000840FDF76FB8000008B5FFF7A7FD00F040 -:1076A0000DF8FDF70FFAFDF7E7FBFDF7B9FAFFF765 -:1076B00055FDBDE80840FFF735BC00000023054A32 -:1076C00019460133102BC2E9001102F10802F8D16A -:1076D000704700BF007200200B460146184600F0BC -:1076E00003B8000000F00EB810B5054C13462CB1DD -:1076F0000A4601460220AFF3008010BD2046FCE799 -:1077000000000000024B01461868FEF777BB00BF7F -:107710006C22002010B501390244904201D10020B2 -:1077200005E0037811F8014FA34201D0181B10BDEA -:107730000130F2E72DE9F041A3B1C91A17780144ED -:10774000044603F1FF3C8C42204601D9002009E0A9 -:107750000578BD4204F10104F5D10CEB0405D618FF -:10776000A54201D1BDE8F08115F8018D16F801EDB3 -:10777000F045F5D0E7E70000034611F8012B03F8C8 -:10778000012B002AF9D170476F72672E6172647500 -:1077900070696C6F742E4375626550696C6F742DDF -:1077A00043414E4D6F64000053544D333248373FD0 -:1077B0003F3F0053544D3332483733782F373278B8 -:1077C0000053544D3332483734332F3735332F3746 -:1077D0003530000001105A000310590001205800F4 -:1077E0000320560040A2E4F1646891060041A3E53D -:1077F000F26569920700000043414E4644496661C4 -:1078000063653A204D6573736167652052414D2071 -:107810004F766572666C6F772100000042616420CC -:1078200043414E496661636520696E6465782E0048 -:1078300000000000000000009D2C000879250008D1 -:107840009533000871250008E9250008F92900088A -:1078500061270008B1250008B52500088D2500081E -:1078600075250008B929000899250008CD340008BD -:10787000A52500088D2900080096000000000000E2 -:1078800000000000000000000000000000000000F8 -:1078900000000000854A0008714A0008AD4A00084F -:1078A000994A0008A54A0008914A00087D4A000844 -:1078B000694A0008B94A0008000000009D4B000812 -:1078C000894B0008C54B0008B14B0008BD4B0008B0 -:1078D000A94B0008954B0008814B0008D14B0008CC -:1078E0000000000001000000000000006330000004 -:1078F000EC78000848530020585500204172647508 -:1079000050696C6F740025424F415244252D424C02 -:10791000002553455249414C25000000020000005B -:1079200000000000BD4D00082D4E00084000400042 -:10793000086E0020186E0020020000000000000009 -:107940000300000000000000754E00080000000069 -:1079500010000000286E0020000000000100000060 -:1079600000000000B070002001010200AD590008C5 -:10797000BD580008595900083D590008430000004F -:107980008479000809024300020100C032090400A2 -:10799000000102020100052400100105240100017C -:1079A000042402020524060001070582030800FFE3 -:1079B00009040100020A000000070501024000005E -:1079C000070581024000000012000000D079000885 -:1079D0001201100102000040091241570002010289 -:1079E000030100000403090425424F4152442500CD -:1079F00030313233343536373839414243444546E5 -:107A00000000000000000020000002000200000052 -:107A10000001003000000000080000000000002409 -:107A200000000800040000000004000000FC00004A -:107A30000200000000000430008000000800000088 -:107A400000000038000001000100000000000000FC -:107A5000D14F00088952000835530008400040000B -:107A6000E8710020E871002001000000F87100209A -:107A7000800000004001000008000000000100003C -:107A800000100000080000006D61696E0069646C00 -:107A9000650000000000802A00000000AAAAAAAA2F -:107AA00000000024FFFF00000000000000A00A000A -:107AB0000000000000000000AAAAAAAA000000001E -:107AC000FFFF0000000000000000000000000000B8 -:107AD00000000000AAAAAAAA00000000FFFF000000 -:107AE00000000000000000000A000000000000008C -:107AF000AAAAAAAA00000000FFFF00009900000047 -:107B0000000000000080020000000000AAAAAAAA4B -:107B100000400100FFFF00000000007007000000AF -:107B20000000000000000000AAAAAAAA00000000AD -:107B3000FFFF000000000000000000000500000042 -:107B400000000000A5AAAAAA00000000FCFF000097 -:107B50000000000000000000000000000000000025 -:107B6000AAAAAAAA00000000FFFF0000000000006F -:107B7000000000000000000000000000AAAAAAAA5D -:107B800000000000FFFF00000000000000000000F7 -:107B90000000000000000000AAAAAAAA000000003D -:107BA000FFFF0000000000000000000000000000D7 -:107BB00000000000AAAAAAAA00000000FFFF00001F -:107BC00000000000000000005887FF7F0100000057 -:107BD0003704000000000000000018000000000052 -:107BE000FE2A0100D2040000FF00000060550020C2 -:107BF000804E002000000000A877000883040000E9 -:107C0000B377000850040000C17700080096000018 -:107C100000000800960000000008000004000000BA -:107C2000E4790008000000000000000000000000EF -:107C30000000000000000000000000007022002092 -:107C40000000000000000000000000000000000034 -:107C50000000000000000000000000000000000024 -:107C60000000000000000000000000000000000014 -:107C70000000000000000000000000000000000004 -:107C800000000000000000000000000000000000F4 -:107C900000000000000000000000000000000000E4 +:1000000000070020F1020008FD320008B5320008A8 +:10001000DD320008B5320008D5320008F3020008CE +:10002000F3020008F3020008F3020008E1420008AE +:10003000F3020008F3020008F3020008F3020008CC +:10004000F3020008F3020008F3020008F3020008BC +:10005000F3020008F3020008E17600080D770008BB +:10006000397700086577000891770008A5430008F4 +:10007000CD430008F9430008254400085144000816 +:1000800079440008A5440008F302000895320008EE +:10009000F3020008A5320008F3020008BD7700084B +:1000A000F3020008F3020008F3020008F30200085C +:1000B000F3020008F3020008F3020008F30200084C +:1000C000F3020008F3020008F3020008F30200083C +:1000D000F3020008F3020008F3020008F30200082C +:1000E00021780008F3020008F3020008F302000878 +:1000F000F3020008F3020008F3020008D1440008EC +:10010000F3020008F3020008A9780008F3020008CF +:10011000F3020008F3020008F3020008F3020008EB +:10012000FD44000825450008514500087D450008AC +:10013000A9450008F3020008F3020008F3020008D2 +:10014000F3020008F3020008F3020008F3020008BB +:10015000D1450008FD45000829460008F3020008C3 +:10016000F3020008F3020008F3020008F30200089B +:10017000F30200088D6D0008F3020008F302000886 +:10018000F3020008F302000895780008F302000863 +:10019000F3020008F3020008F3020008F30200086B +:1001A000F3020008F3020008F3020008F30200085B +:1001B000F3020008F3020008F3020008F30200084B +:1001C000F3020008F3020008F3020008F30200083B +:1001D000F3020008796D0008F3020008F30200083A +:1001E000F3020008F3020008F3020008F30200081B +:1001F000F3020008F3020008F3020008F30200080B +:10020000F3020008F3020008F3020008F3020008FA +:10021000F3020008F3020008F3020008F3020008EA +:10022000F3020008F3020008F3020008F3020008DA +:10023000F3020008F3020008F3020008F3020008CA +:10024000F3020008F3020008F3020008F3020008BA +:10025000F3020008F3020008F3020008F3020008AA +:10026000F3020008F3020008F3020008F30200089A +:10027000F3020008F3020008F3020008F30200088A +:10028000F3020008F3020008F3020008F30200087A +:10029000F3020008F3020008F3020008F30200086A +:1002A000F3020008F3020008F3020008F30200085A +:1002B000F3020008F3020008F3020008F30200084A +:1002C000F3020008F3020008F3020008F30200083A +:1002D000F3020008F3020008F3020008F30200082A +:1002E000D51600080000000000000000000000001B +:1002F00002E000F000F8FEE772B6374880F30888A5 +:10030000364880F3098836483649086040F20000D4 +:10031000CCF200004EF63471CEF200010860BFF35B +:100320004F8FBFF36F8F40F20000C0F2F0004EF627 +:100330008851CEF200010860BFF34F8FBFF36F8F7B +:100340004FF00000E1EE100A4EF63C71CEF20001D3 +:100350000860062080F31488BFF36F8F05F08CFFD0 +:1003600006F090FF4FF055301F491B4A91423CBFA9 +:1003700041F8040BFAE71D49184A91423CBF41F885 +:10038000040BFAE71A491B4A1B4B9A423EBF51F82D +:10039000040B42F8040BF8E700201849184A914270 +:1003A0003CBF41F8040BFAE705F0A4FF06F0ECFFB0 +:1003B000144C154DAC4203DA54F8041B8847F9E796 +:1003C00000F042F8114C124DAC4203DA54F8041B11 +:1003D0008847F9E705F08CBF0007002000230020C4 +:1003E0000000000808ED00E00001002000070020E8 +:1003F000607F000800230020D0230020D0230020AD +:1004000000740020E0020008E4020008E402000892 +:10041000E40200082DE9F04F2DED108AC1F80CD050 +:10042000D0F80CD0BDEC108ABDE8F08F002383F328 +:1004300011882846A047002005F004FAFEE705F0E1 +:1004400083F900DFFEE70000F8B501F0BFF901F025 +:1004500061FB05F095FE074605F004FF0546A8BBC5 +:100460001F4B9F4232D001339F4232D027F0FF0210 +:100470001C4B9A4230D12E4642F21074F8B200F072 +:1004800079FF00F07DFF08B10024264601F08AFDC7 +:1004900020B10024032000F079F8264635B1124B34 +:1004A0009F4203D0002405F0D5FE2646002005F02B +:1004B00071FE0EB100F080F801F0CAFA00F094FF6E +:1004C000204600F02BF900F077F8F9E72E460024DB +:1004D000D7E704460126D4E7064641F28834D0E740 +:1004E000010007B0000008B0263A09B008B501F0D5 +:1004F00039F9A0F120035842584108BD07B541F22F +:100500001203022101A8ADF8043001F049F903B04B +:100510005DF804FB38B5302383F31188174803686E +:100520000BB105F05BFA0023154A4FF47A711348BA +:1005300005F04AFA002383F31188124C236813B1A3 +:100540002368013B2360636813B16368013B636008 +:100550000D4D2B7833B963687BB9022001F0EAF9BD +:10056000322363602B78032B07D163682BB90220F9 +:1005700001F0E0F94FF47A73636038BDD0230020B6 +:1005800015050008F0240020E8230020084B18700F +:1005900003280CD8DFE800F008050208022001F06B +:1005A000C7B9022001F0C2B9024B00225A6070475D +:1005B000E8230020F0240020F8B501F0F3FC30B16E +:1005C0004D4B03221A7000224C4B5A60F8BD4C4B25 +:1005D0004C4A1C4619680131F8D004339342F9D1D2 +:1005E0006268494B9A42F1D9484B9B6803F100631A +:1005F00003F580239A42E9D205F000FE05F012FED1 +:10060000002001F009F90220FFF7C0FF404B002154 +:100610009A6C99641A6F19671A6FDA6CD9645A6FF9 +:1006200059675A6F1A6D19659A6F99679B6F394BA5 +:10063000D3F8802042F00062C3F88020D3F88020F5 +:1006400022F00062C3F88020D3F88020D3F8802005 +:1006500042F00072C3F88020D3F8802022F00072AC +:10066000C3F88020D3F8803072B64FF0E023C3F88F +:10067000084DD4E90004BFF34F8FBFF36F8F264AB4 +:10068000C2F88410BFF34F8F536923F48033536152 +:10069000BFF34F8FD2F8803043F6E076C3F3C9053D +:1006A000C3F34E335B0103EA060C29464CEA81771B +:1006B0000139C2F87472F9D2203B13F1200FF2D144 +:1006C000BFF34F8FBFF36F8FBFF34F8FBFF36F8FAA +:1006D000536923F4003353610023C2F85032BFF34F +:1006E0004F8FBFF36F8F302383F31188854680F3DC +:1006F000088820476AE700BFE8230020F024002094 +:100700000000040820000408FFFF03080023002065 +:10071000004502580044025800ED00E02DE9F04F7A +:1007200093B0B74B2022FF2100900AA89D6801F0EA +:1007300039F9B44A1378A3B90121B34811700360A1 +:10074000302383F3118803680BB105F047F90023C8 +:10075000AE4A4FF47A71AC4805F036F9002383F3C2 +:100760001188009B13B1AA4B009A1A60A94A13780A +:10077000032B03D000231370A54A53604FF0000AE7 +:10078000009CD3465646D146012001F0D1F824B151 +:100790009F4B1B68002B00F02C82002000F0E2FF32 +:1007A0000390039B002B01DA00F066FE039B002BF5 +:1007B000EDDB012001F0BAF8039B213B1F2BE3D8AE +:1007C00001A252F823F000BF490800087108000890 +:1007D000050900088907000889070008890700083B +:1007E00097090008670B0008810A0008E30A00085F +:1007F0000B0B0008310B000889070008430B0008A9 +:1008000089070008B50B0008E908000889070008F7 +:10081000F90B000855080008E908000889070008D6 +:10082000E30A00088907000889070008890700080B +:100830008907000889070008890700088907000858 +:1008400089070008050900080220FFF74FFE00286D +:1008500040F0F981009B022105A8BAF1000F08BF02 +:100860001C4641F21233ADF8143000F099FF8BE7CB +:100870004FF47A7000F076FF071EEBDB0220FFF7E3 +:1008800035FE0028E6D0013F052F00F2DE81DFE8CB +:1008900007F0030A0D1013360523042105A805935C +:1008A00000F07EFF17E004215548F9E704215A487B +:1008B000F6E704215948F3E74FF01C08404608F1D9 +:1008C000040800F0ABFF0421059005A800F068FFC4 +:1008D000B8F12C0FF2D101204FF0000900FA07F710 +:1008E00047EA0B0B5FFA8BFB01F0A8F826B10BF07F +:1008F0000B030B2B08BF0024FFF700FE44E7042185 +:100900004748CDE7002EA5D00BF00B030B2BA1D150 +:100910000220FFF7EBFD074600289BD001200026B0 +:1009200000F07AFF0220FFF731FE1FFA86F84046FA +:1009300000F082FF0446B0B1039940460136A1F1B0 +:1009400040025142514100F08FFF0028EDD1BA46DC +:10095000044641F21213022105A83E46ADF81430B8 +:1009600000F01EFF10E725460120FFF70FFE244B85 +:100970009B68AB4207D9284600F050FF013040F099 +:1009800067810435F3E70025224BBA463E461D70C9 +:100990001F4B5D60A8E7002E3FF45CAF0BF00B032C +:1009A0000B2B7FF457AF0220FFF7F0FD322000F051 +:1009B000D9FEB0F10008FFF64DAF18F003077FF441 +:1009C00049AF0F4A08EB0503926893423FF642AFE6 +:1009D000B8F5807F3FF73EAF124BB845019323DD5A +:1009E0004FF47A7000F0BEFE0390039A002AFFF6DF +:1009F00031AF039A0137019B03F8012BEDE700BFEC +:100A000000230020EC240020D0230020150500083E +:100A1000F0240020E82300200423002008230020E5 +:100A20000C230020EC230020C820FFF75FFD0746C1 +:100A300000283FF40FAF1F2D11D8C5F120020AABDB +:100A400025F0030084494245184428BF42460192DC +:100A500000F082FF019AFF217F4800F0A3FF4FEAD8 +:100A6000A803C8F387027C492846019300F0A2FF3F +:100A7000064600283FF46DAF019B05EB830533E785 +:100A80000220FFF733FD00283FF4E4AE00F0FEFE45 +:100A900000283FF4DFAE0027B846704B9B68BB428E +:100AA00018D91F2F11D80A9B01330ED027F003034A +:100AB00012AA134453F8203C05934046042205A98A +:100AC000043701F059FA8046E7E7384600F0A6FE01 +:100AD0000590F2E7CDF81480042105A800F060FE2F +:100AE00002E70023642104A8049300F04FFE0028CD +:100AF0007FF4B0AE0220FFF7F9FC00283FF4AAAE65 +:100B0000049800F0B9FE0590E6E70023642104A8EC +:100B1000049300F03BFE00287FF49CAE0220FFF718 +:100B2000E5FC00283FF496AE049800F0A7FEEAE743 +:100B30000220FFF7DBFC00283FF48CAE00F0B6FE8D +:100B4000E1E70220FFF7D2FC00283FF483AE05A9BD +:100B5000142000F0B1FE07460421049004A800F020 +:100B60001FFE3946B9E7322000F0FCFD071EFFF6F4 +:100B700071AEBB077FF46EAE384A07EB090392688B +:100B800093423FF667AE0220FFF7B0FC00283FF427 +:100B900061AE27F003074F44B9453FF4A5AE484680 +:100BA00009F1040900F03AFE0421059005A800F0BF +:100BB000F7FDF1E74FF47A70FFF798FC00283FF457 +:100BC00049AE00F063FE002844D00A9B01330BD0ED +:100BD00008220AA9002000F0EDFE00283AD02022C9 +:100BE000FF210AA800F0DEFEFFF788FC1C4804F095 +:100BF0002FFE13B0BDE8F08F002E3FF42BAE0BF0AC +:100C00000B030B2B7FF426AE0023642105A805936C +:100C100000F0BCFD074600287FF41CAE0220FFF761 +:100C200065FC804600283FF415AEFFF767FC41F2F3 +:100C3000883004F00DFE059800F04AFF46463C4619 +:100C400000F0FCFEA0E506464EE64FF0000901E686 +:100C5000BA467EE637467CE6EC23002000230020DF +:100C6000A0860100094A49F26900136899B21B0C79 +:100C700000FB013344F250611360054B186882B2E7 +:100C8000000C01FB0200186080B2704714230020A2 +:100C9000102300200021102210B5044600F082FE2F +:100CA000034B03CB206061601868A06010BD00BFDB +:100CB00000E8F11F2DE9F041ADF5507D0D46002112 +:100CC00040F275126EAC074610A80F9100F06AFE54 +:100CD0004FF4C4720021204600F064FE0DF13C0880 +:100CE00002F014FB4FF47A72264BB0FBF2F018605E +:100CF00093E80700022384E807000DF5ED702382D6 +:100D0000FFF7C8FF43F204731F4907A8238406F0C6 +:100D10006FFE1E230DF2EB220DF1340C84F83231FC +:100D200007AB1E46083203CE664542F8080C42F86F +:100D3000041C3346F5D13068414610602046B38824 +:100D40009380012200F03CFF002380B2E97E0393F0 +:100D5000AB7E029305F1190301930123009307A3CE +:100D6000D3E90023CDE90480384602F08DFE0DF56D +:100D7000507DBDE8F08100BFAFF300809E6AC421C2 +:100D8000818A46EEF8240020007A00082DE9F0411F +:100D90002C4CDAB080460D46237A5BBB27A9284647 +:100DA00001F01CF80746002842D19DF89D60C82E2E +:100DB0003ED801464FF4A662204600F0F3FD4FF402 +:100DC000807332460DF19E01C4F8F8314FF4007380 +:100DD00004F109002644C4F80C334FF44073C4F8FE +:100DE000203400F0B9FD9DF89C30777223720BB966 +:100DF000EB7E237206AC8122002127A800F0D2FDF1 +:100E00000122214627A801F025F8002380B2E97EBF +:100E10000393AB7E029305F1190301932823CDE9D7 +:100E200004400093404605A3D3E9002302F02CFEC2 +:100E30005AB0BDE8F08100BFAFF300802641727266 +:100E4000DF25D7B7004A0020F0B5254E4FF48A754C +:100E5000F1B0002405FB006596F8D830D822214671 +:100E600085F8DC303AA885F8E84006AF00F09AFD36 +:100E700006F1090000F08EFDD5F8E430C2B206F1AB +:100E800009018DF8F0000DF1F100CDE93A3400F0E0 +:100E900063FD394601223AA801F008F8082380B220 +:100EA000317ACDE9047001270E48CDE9023706F109 +:100EB000D80301933023009307A3D3E9002302F062 +:100EC000E3FDA04206DD02F021FAC5F8E000384655 +:100ED00071B0F0BD2046FBE778F6339F93CACD8D05 +:100EE000004A0020103500202DE9F0411D4D86B04C +:100EF0001D4E1E4F284602F0F3FD034658B3002452 +:100F0000DFF86C80ADF814400294CDE90344027B15 +:100F10008DF8142003AA9968406803C21B6843F047 +:100F20000043029302F0F4F982190094384641F12B +:100F3000000302A901F030FAA04205DD284602F0C4 +:100F4000D3FD88F80040D5E798F80030072B05D886 +:100F5000013388F8003006B0BDE8F081014802F0A6 +:100F6000C3FDF8E71035002040420F004035002057 +:100F7000354F002070B50D4614461E4602F0E0FCC9 +:100F800050B9022E10D1012C0ED112A3D3E90023A7 +:100F90000120C5E9002307E0282C10D005D8012C3A +:100FA00009D0052C0FD0002070BD302CFBD10BA335 +:100FB000D3E90023ECE70BA3D3E90023E8E70BA375 +:100FC000D3E90023E4E70BA3D3E90023E0E700BF64 +:100FD000AFF30080401DA12026812A0B78F6339FB5 +:100FE00093CACD8D9E6AC421818A46EE26417272D3 +:100FF000DF25D7B7F017304A39059E5638B5054674 +:101000000E4C0021013500F02FFCA4F82C55B4F84B +:101010002C0500F011FC78B1B4F82C0500F01CFC94 +:10102000014648B9B4F82C0500F01EFCB4F82C3584 +:101030000133A4F82C35EAE738BD00BF004A002090 +:101040000A4B0B4A10B51A6003F5805393F84820F9 +:101050003AB95C6C2CB1204601F022F8204606F02B +:101060007DFC0448BDE8104001F01AB8403500206E +:10107000B07A0008704500202DE9F04F8FB005468A +:101080000C4600AF02F05CFC002849D1237E022B05 +:101090001BD1E38A012B18D102F038F90646FFF77D +:1010A000E1FD03464FF4C87006F51676DFF8C082FE +:1010B000B3FBF0F202FB103316FA83F3C8F80030EA +:1010C000E37E33B9A34B00221A703C37BD46BDE81E +:1010D000F08F07F12401204600F03EFE0028F4D1F5 +:1010E00007F11400FFF7D6FD97F8264007F1140129 +:1010F00007F12700224606F049FC0028E2D10F2C18 +:1011000008D8944B1C70D8F80030A3F51673C8F8B3 +:101110000030DAE797F82410284602F009FCD4E7FB +:10112000E38A282B2BD010D8012B23D0052BCCD130 +:10113000BFF34F8F8849894BCA6802F4E0621343BA +:10114000CB60BFF34F8F00BFFDE7302BBDD1844E86 +:10115000E17E327A9142B8D1607E3146002291F828 +:10116000DC50854200F0A580013201F58A71042A25 +:10117000F5D1AAE721462846FFF79CFDA5E72146C1 +:101180002846FFF703FEA0E7B2F8EC507B6005F1BC +:1011900003094FEA99094FEA8902D11DC908A8EB52 +:1011A000C10300219D46EB46584600F0FBFB04F1CD +:1011B000EE012A465846314400F0CEFB7B6813B955 +:1011C000012000F029FB96F8D20000F035FB044620 +:1011D00030B9307200F05AFB204600F01DFBB1E040 +:1011E000D6F8D4203AB996F8D200B6F82C25824227 +:1011F00001D8FFF703FFD6F8D4202A44944208D23E +:1012000096F8D200B6F82C250130824201D8FFF7BB +:10121000F5FE5FFA89F25946706800F0CBFB08B919 +:10122000C54679E0726896F8D2002A447260D6F812 +:10123000D42005EB0209C6F8D49000F0FDFA8145F0 +:1012400009D396F8D220D6F8D4000132001B86F8D4 +:10125000D220C6F8D400FF2D0FD80024347200F03D +:1012600015FB204600F0D8FA00F09CFE3D4B18819B +:1012700008B9FFF7A1F9C54627E7BB6896F8D9007A +:101280000AFB0362FB68D2F8E41082F8E83001F54B +:101290008061C2F8E030C2F8E410FFF7D5FDFFF737 +:1012A00023FE96F8D920013202F0030286F8D920F5 +:1012B000B6E74FF48A7A20460AFB02F505F1EA0107 +:1012C000314400F01FFEF86000287FF4FEAE0122DA +:1012D000354485F8E82002F019F8D5F8E020D6ED7D +:1012E000007A801A40F6B832B8EE677ADFED1E6AEF +:1012F000192838BF1920904228BF104607EE900ADF +:10130000F8EEE77A67EEA67ADFED186AE7EE267A5E +:10131000FCEEE77AC6ED007A96F8D930BB60BA6881 +:1013200073680AFB02F4321992F8E81059B1D2F846 +:10133000E410E8468B423FF427AF002182F8E81022 +:10134000C2F8E010C5467368064A9B0A0133138150 +:10135000BBE600BF0935002000ED00E00400FA05FF +:10136000004A0020F8240020CDCCCC3D6666663FC4 +:101370000C350020014B1870704700BF0425002079 +:1013800038B54FF00054144B22689A4221D1627D47 +:101390000025124B12481A70C922237D09301149C9 +:1013A00000F8013C4FF48073C0F8DB50C0F8EF3117 +:1013B0004FF40073C0F803334FF44073C0F8173490 +:1013C00000F0CAFAE0222946204600F0EBFA01209C +:1013D00038BD0020FCE700BF9AAD44C504250020BD +:1013E000004A00201600002037B500F0DBFD194D43 +:1013F00002230022184928816B710123174801F04C +:1014000047FB002316494FF480520193154B1648B1 +:101410000093164B02F064FA154B197811B112487B +:1014200002F086FA01F072FF0446FFF71BFC4FF44E +:10143000C873B0FBF3F202FB130304F5167010FA45 +:1014400083F00C4B186004F00DFF08B10F232B81C3 +:1014500003B030BDF824002040420F00403500208A +:1014600008250020750F00081035002079100008AD +:10147000042500200C3500202DE9F04F8C4C2DED7B +:10148000028B85A7D7E9006795B00FF21429D9E937 +:1014900000899FED858BFFF727FD0DAD0023DFF859 +:1014A00024B20C93ADF83C300D936B6000234FF0E9 +:1014B000010A0DF1250209A958468DF825308DF84D +:1014C00024A08DED008B01F089FE9DF824200023DF +:1014D000002A40F0AE80204602F032FA054600288D +:1014E00047D1DFF8E4B101F011FFDBF8003098429A +:1014F0003FD301F00BFF0790FFF7B4FB4FF4C87325 +:10150000079AB0FBF3F101FB130302F5167010FA12 +:1015100083F0CBF8000010A8DFF8B0B19BF8001002 +:10152000002914BF2B46534607918DF83030FFF742 +:10153000B1FB079910AB0DF13100C1F11002194454 +:10154000D2B2062A28BF0622079200F005FA079AAF +:101550000CAB2046039301321823D2B20293554BB1 +:1015600004923246CDE900A33B4602F02FFA8BF8F5 +:10157000005001F0CBFE504A504D1368C31AB3F52A +:101580007A7F32D3106001F0C3FE02460B4620463C +:1015900002F0B4FA204602F0D3F930B32B7A0DF101 +:1015A000400BDFF82CA1002B14BF032302238AF881 +:1015B000053001F0ABFE4FF47A7301225946B0FBBF +:1015C000F3F0CAF80000504600F09EFB182380B2EA +:1015D000424602933A4B019340F25513CDE903B0D2 +:1015E000009320464B4602F0F1F92B7AABB101F0A3 +:1015F0008DFE4FF0000A83464FF48A7295F8D900A9 +:10160000504400F0030002FB005393F8E81071B35C +:101610000AF1010ABAF1040FF0D1C82004F018F958 +:101620002B7A002B7FF435AF15B0BDEC028BBDE8F3 +:10163000F08F1946102210A800F0B4F90DF126031E +:101640000AAA0CA9584601F0B3F811AB95E80300BB +:1016500083E803009DF83C3010A920468DF84C30FB +:101660000C9B1093DDE90A2302F01CFC1EE7D3F863 +:10167000E01049B12B68ABEB0101FA2B38BFFA231C +:101680000533B1EB430FC3D3FFF7DEFB4FF48A7290 +:101690000028BDD1C1E700BF401DA12026812A0B33 +:1016A000F1C6A7C1D068080F0000000000000000CC +:1016B0001035002008350020304F0020004A00205F +:1016C000344F0020403500200C3500200935002023 +:1016D000F824002008B5054801F012F9044A05492C +:1016E0000020BDE8084006F033B900BF40350020B7 +:1016F0008C4F0020411000082DE9F84F4FF47A7309 +:1017000006460D46002402FB03F7DFF85080DFF8A1 +:10171000509098F900305FFA84FA5A1C01D0A34225 +:1017200012D159F824002A4631460368D3F820B074 +:101730003B46D847854207D1074B012083F800A0DC +:10174000BDE8F88F0124E4E7002CFBD04FF4FA70D9 +:1017500004F07EF80020F3E77C4F002018230020DF +:101760001C230020002307B5024601210DF10700CC +:101770008DF80730FFF7C0FF20B19DF8070003B0D8 +:101780005DF804FB4FF0FF30F9E700000A46042142 +:1017900008B5FFF7B1FF80F00100C0B2404208BDBC +:1017A000074B0A4630B41978064B53F821400146DE +:1017B00023682046DD69044BAC4630BC604700BF5F +:1017C0007C4F00201C230020A086010070B5104C27 +:1017D0000025104E04F066FB208030682388834289 +:1017E0000CD800252088013804F058FB23880544D4 +:1017F000013BB5F5802F2380F4D370BD04F04EFB80 +:10180000336805440133B5F5802F3360E5D3E8E74D +:101810007E4F0020384F002004F012BC00F1006021 +:1018200000F580200068704700F10060920000F52C +:10183000802004F093BB0000054B1A68054B1B8801 +:101840009B1A834202D9104404F028BB0020704741 +:10185000384F00207E4F0020024B1B68184404F0D4 +:1018600023BB00BF384F0020024B1B68184404F014 +:101870002DBB00BF384F00200020704700F1FF5003 +:1018800000F58F10D0F8000870470000064991F865 +:10189000243033B100230822086A81F82430FFF78E +:1018A000C3BF0120704700BF3C4F0020014B1868A8 +:1018B000704700BF0010005C194B01380322084438 +:1018C00070B51D68174BC5F30B042D0C1E88A6427E +:1018D0000BD15C680A46013C824213460FD214F9D0 +:1018E000016F4EB102F8016BF6E7013A03F108030C +:1018F000ECD181420B4602D22C2203F8012B0424A6 +:10190000094A1688AE4204D1984284BF967803F8FB +:10191000016B013C02F10402F3D1581A70BD00BF03 +:101920000010005C242300204C7A0008704700005F +:10193000704700007047000070B504464FF47A7697 +:101940004CB1412C254628BF412506FB05F0641B00 +:1019500003F07EFFF4E770BD002310B5934203D07F +:10196000CC5CC4540133F9E710BD0000013810B558 +:1019700010F9013F3BB191F900409C4203D11AB1EB +:101980000131013AF4E71AB191F90020981A10BD1B +:101990001046FCE703460246D01A12F9011B002943 +:1019A000FAD1704702440346934202D003F8011B68 +:1019B000FAE770472DE9F8431F4D1446074688465D +:1019C00095F8242052BBDFF870909CB395F8243032 +:1019D0002BB92022FF2148462F62FFF7E3FF95F83D +:1019E00024004146C0F1080205EB8000A24228BF56 +:1019F0002246D6B29200FFF7AFFF95F82430A41B21 +:101A000017441E449044E4B2F6B2082E85F82460D0 +:101A1000DBD1FFF73BFF0028D7D108E02B6A03EBAF +:101A200082038342CFD0FFF731FF0028CBD10020C3 +:101A3000BDE8F8830120FBE73C4F0020024B1A78F9 +:101A4000024B1A70704700BF7C4F00201823002003 +:101A500038B51A4C1A4D204603F03EFA2946204666 +:101A600003F066FA2D684FF47A70D5F89020D2F81A +:101A7000043843F00203C2F80438FFF75DFF114950 +:101A8000284603F063FBD5F890200F4DD2F80438B8 +:101A9000286823F002030D49A042C2F804384FF42D +:101AA000E1330B6001D003F075F96868A04204D0FF +:101AB0000649BDE8384003F06DB938BDF056002046 +:101AC000FC7C0008047D00081C230020644F0020DB +:101AD0000C4B70B50C4D04461E780C4B55F8262067 +:101AE0009A420DD00A4B002118221846FFF75AFFE0 +:101AF0000460014655F82600BDE8704003F04AB97D +:101B000070BD00BF7C4F00201C230020F056002039 +:101B1000644F0020F0B5A1B071B60023012000246D +:101B200080261A46194602F01DFE4FF4D067214A5E +:101B30003D25136923BBD2F810310BBB036804F1B8 +:101B4000006199600368C3F80CD003685E600368A5 +:101B50001F6001680B6843F001030B6001680B68AC +:101B600023F01E030B6001680B68DB07FCD4037BCA +:101B70008034416805FA03F3B4F5001F0B60D8D137 +:101B800002F026FEB4F5001F11D000240A4E0B4DC2 +:101B9000012004F055FA3388A34205D9286820446F +:101BA000013404F093F9F6E7002004F049FA61B635 +:101BB00021B0F0BD002000527E4F0020384F0020A1 +:101BC0002DE9F0470D46044600219046284640F294 +:101BD0007912FFF7E7FE234620220021284604F170 +:101BE000220702F001F9231D022220212846C026E7 +:101BF00002F0FAF8631D03222221284602F0F4F8CD +:101C0000A31D03222521284602F0EEF804F1080363 +:101C100010222821284602F0E7F804F110030822D8 +:101C20003821284602F0E0F804F11103082240218F +:101C3000284602F0D9F804F1120308224821284668 +:101C400002F0D2F804F1140320225021284602F0B9 +:101C5000CBF804F1180340227021284602F0C4F8A2 +:101C600004F120030822B021284602F0BDF804F157 +:101C700021030822B821284602F0B6F8314608367A +:101C80003B4608222846013702F0AEF8B6F5A07FA1 +:101C9000F4D1002704F1330A04F13203082231465B +:101CA000284602F0A1F894F832304FEAC7099F4263 +:101CB00009F5A47615D3B8F1000F08D1314609F221 +:101CC0004F1604F599730722284602F08DF827462F +:101CD0003B1B94F8322193420CD3F01DC008BDE8A1 +:101CE000F0870AEB0703082231462846013702F045 +:101CF0007BF8D8E707F23313314608222846083626 +:101D0000013702F071F8E3E713B5044608460021F5 +:101D10002022234601900160C0F8031002F064F80D +:101D2000231D01980222202102F05EF8631D019814 +:101D30000322222102F058F8A31D01980322252135 +:101D400002F052F8019804F108031022282102F051 +:101D50004BF8072002B010BD0023F7B50E46047FF4 +:101D6000072200911946054601F002FF731C01226B +:101D7000072100932846002301F0FAFEC4B9B31CE2 +:101D8000052208212846009323460D2401F0F0FE89 +:101D90003746BB1BB278934211D307342B7FA88AF6 +:101DA000E408BBB9844294BF0020012003B0F0BD19 +:101DB000AB8A0824DB00083BDB08B370E8E7FB1CB8 +:101DC000214608222846009300230834013701F0F9 +:101DD000CFFEDEE7201A18BF0120E7E70023F7B5A2 +:101DE0000E46047F082200911946054601F0C0FE08 +:101DF000731CC4B9082200932346102411462846B8 +:101E000001F0B6FE01235F1C7278013B934211D3AF +:101E100007342B7FA88AE408BBB9844294BF002012 +:101E2000012003B0F0BDAB8A0824DB00083BDB08CF +:101E30007370E7E7F3192146082228460093002330 +:101E400001F096FE08343B46DDE7201A18BF01205A +:101E5000E7E70000F8B50E4605461446002181224A +:101E60003046FFF79FFD2B4608220021304601F047 +:101E7000BBFF7CB90F246B1C07220821304601F000 +:101E8000B3FF01235F1C6A78013B934204D3E01D3A +:101E9000C008F8BD0824F4E7EB19214608223046B3 +:101EA00001F0A2FF08343B46ECE70000F8B50E460F +:101EB000054614460021CE223046FFF773FD2B461F +:101EC00028220021304601F08FFF7CB9302405F133 +:101ED000080308222821304601F086FF2F467B1B8D +:101EE0002A7A934204D3E01DC008F8BD2824F5E700 +:101EF00007F109032146082230460834013701F072 +:101F000073FFECE7F7B5047F0E4600910123102222 +:101F10000021054601F02CFEC4B9B31C0922102192 +:101F2000284600932346192401F022FE3746728882 +:101F3000BB1B9A4211D807342B7FA88AE408BBB98F +:101F4000844294BF0020012003B0F0BDAB8A10246E +:101F5000DB00103BDB087380E8E73B1D21460822CD +:101F60002846009300230834013701F001FEDEE724 +:101F7000201A18BF0120E7E730B50A44084D914206 +:101F80000DD011F8013B5840082340F30004013BF9 +:101F90002C4013F0FF0384EA5000F6D1EFE730BD88 +:101FA0002083B8EDF7B5384A6B46106851686A4629 +:101FB00003C308233549364805F0F8FC04460028D9 +:101FC00033D10A25334A6B46106851686A4603C309 +:101FD000082331492E4805F0E9FC0446002849D081 +:101FE0000369B3F5E01F45D8B0F8661040F23742F8 +:101FF00091423FD1294A024402F15C018B4239D31C +:102000005C3B234900209E1AFFF7B6FF04F16401F0 +:10201000074632460020FFF7AFFFA3689F4229D151 +:10202000E368984208BF002524E00369B3F5E01F88 +:1020300027D8418B40F23742914220D1174A0244BF +:1020400002F110018B4218D3103B114900209D1A58 +:10205000FFF792FF04F1180106462A460020FFF719 +:102060008BFFA3689E4202D1E368984201D00D2500 +:10207000A8E70025284603B0F0BD1025A2E70C25EF +:10208000A0E70B259EE700BF5C7A0008DCFF1B0081 +:1020900000000408657A000890FF1B000800FCF7A8 +:1020A00010B5037C044613B9006805F067FC2046B0 +:1020B00010BD00000023BFF35B8FC360BFF35B8FD5 +:1020C000BFF35B8F8360BFF35B8F7047BFF35B8FA2 +:1020D0000068BFF35B8F704770B505460C30FFF7A3 +:1020E000F5FF044605F108063046FFF7EFFFA04272 +:1020F00006D96D683046FFF7E9FF2544281A70BD00 +:102100003046FFF7E3FF201AF9E7000070B50546F7 +:102110004068A0B105F10C0605F10800FFF7D6FFF5 +:1021200004463046FFF7D2FF844204F1FF343046C4 +:1021300094BF6D680025FFF7C9FF2C44201A70BDBD +:1021400038B50C460546FFF7C7FFA04210D305F18E +:102150000800FFF7BBFF04446868BFF35B8FB4FB64 +:10216000F0F100FB11440120AC60BFF35B8F38BD80 +:102170000020FCE72DE9F041144607460D46FFF725 +:10218000C5FF844228BF0446D4B1B84658F80C6B4A +:102190004046FFF79BFF3044286040467E68FFF7CB +:1021A00095FF331A9C4203D801206C60BDE8F08192 +:1021B000A41B6B603B682044AB60E8600220F5E73D +:1021C0002046F3E738B50C460546FFF79FFFA042CF +:1021D00010D305F10C00FFF779FF04446868BFF3E2 +:1021E0005B8FB4FBF0F100FB11440120EC60BFF306 +:1021F0005B8F38BD0020FCE72DE9FF41884669462A +:1022000007466C46FFF7B6FF002506B204EBC6068C +:10221000B4420AD0626808EB050120680834FFF771 +:102220009BFB54F8043C1D44F2E729463846FFF76F +:10223000C9FF284604B0BDE8F0810000F8B50546A6 +:102240000C300F46FFF742FF05F108060446304602 +:10225000FFF73CFFA042304688BF6C68FFF736FFAF +:10226000201A386020B12C683046FFF72FFF204439 +:10227000F8BD000073B5144606460D46FFF72CFF67 +:102280008442019028BF0446DCB101A93046FFF723 +:10229000D5FF019B33B93268C5E90233C5E9002493 +:1022A00001200CE09C42286038BF019401988442D0 +:1022B0006860F5D93368241A0220AB60EC6002B084 +:1022C00070BD2046FBE700002DE9FF410F4669463F +:1022D0006C46FFF7CFFF00B2002604EBC005AC420E +:1022E00009D0D4F80480B81954F8081B4246464473 +:1022F000FFF732FBF3E7304604B0BDE8F0810000A1 +:1023000038B50546FFF7E0FF044601462846FFF7CB +:1023100017FF204638BD00007047000010B4134678 +:10232000026814680022A4465DF8044B6047000070 +:1023300000F5805090F859047047000000F5805077 +:1023400090F852047047000000F5805090F958044E +:10235000704700004E207047302383F3118800F54A +:102360008052D2F89C34D2F898041844D2F89434AD +:102370001844D2F87C341844D2F88C341844D2F87B +:1023800088341844002383F31188704700F5805087 +:10239000C0F85414012070472DE9F04F0C4600F5A9 +:1023A000805185B01F4691F8523405469046BDF8DD +:1023B00038909BB1D1F878340133C1F87834236870 +:1023C000980006D4237B082B0BD9627B0AB10F2B14 +:1023D00007D9D1F87C340133C1F87C344FF0FF3099 +:1023E00010E0302383F31188EB6AD3F8C42012F491 +:1023F000001B0AD0D1F8803400200133C1F88034AA +:1024000080F3118805B0BDE8F08F20684822D3F82A +:10241000C4300028C3F3044A6B6AB4BF40F0804064 +:10242000800412FB0A334FEA4A16186022685200F1 +:102430004FEA0A6244BF40F000501860207B42EA35 +:1024400000425A60607B10B342F440125A60D1F8E7 +:10245000B0240132C1F8B024AA1902F58352117BCD +:1024600041F020011173207B039300F0ABFF033098 +:10247000039B80105FFA8BF20BF1010B82420DDAA5 +:1024800004EB820103EB820249689160F2E7AA192A +:1024900002F58352117B60F34511E3E70122EB6AF9 +:1024A00005EB4A1102FA0AF201F58251C3F8D02075 +:1024B000AB19183104F10C0203F58253C3E9048708 +:1024C000234653F8040B934241F8040BF9D11B88BF +:1024D0002E440B8041F2680346F803A006F58056AF +:1024E00009F0030396F86C2043F0100322F01F025A +:1024F000134386F86C30002383F3118842463B4631 +:1025000021462846CDF8009000F022FF012079E70F +:102510002DE9F04700F58056044696F85254002DF8 +:1025200040F00381037C032B40F0948028462B4627 +:102530002F465FFA80FC944510DA01EBCC0E51F87F +:102540003CC0BCF1000F04DBDEF804C0BCF1000F9E +:1025500002DB01370130ECE70133FBE7302080F389 +:102560001188E06AF3B9D0F8803043F00203C0F874 +:1025700080304E23E06A002F6FD1D0F8803043F0D6 +:102580000103C0F880306A4B6A4A1B6803F180532C +:1025900003F52C539B009342A36240F2B08066483F +:1025A00000F0AEFE4D2B42D8DFF884814FEA034E97 +:1025B000DFF88891D8F800C04EEA8C0EC0F884E0AD +:1025C0000CF1805000F52C508000606103EB0C0092 +:1025D000D4F82CC0C3F14E03C8F80000DCF880002A +:1025E00040F03000CCF880004FF0000CD4F814809C +:1025F000E6465FFA8CF08242BCDD01EBC00A51F87E +:102600003000002810DBDAF804A0BAF1000F0BDA72 +:1026100009EA00400AF07F0A40EA0A0040F0084058 +:1026200048F82E000EF1010E0CF1010CE1E7836970 +:1026300023F00103836100F069FE0646E36A9B69AB +:10264000D90704D500F062FE831BFA2BF6D90023CC +:1026500083F311882846BDE8F087B7EB530F3DD2CE +:10266000DFF8CCE04FEA074CDEF800304CEA830C90 +:10267000C0F888C003F1805003EB4703002700F542 +:102680002C50CEF80030BC468000A061E06AD0F843 +:10269000803043F00C03C0F88030D4F818E0FBB26F +:1026A0009A427FF770AF51F8330001EBC30800285E +:1026B000D8F8043001DB002B0EDB20F0604023F063 +:1026C000604340F0005043F000434EF83C000EEBF6 +:1026D000CC000CF1010C43600137E0E7836923F083 +:1026E0000103836100F012FE0646E36A9B69DA0784 +:1026F000ADD500F00BFE831BFA2BF6D9A7E7E26AF3 +:10270000936923F00103936100F000FE0746E36A3A +:102710009B69DB0705D500F0F9FDC31BFA2BF6D941 +:1027200095E7012586F8525491E7002592E700BF0E +:10273000884F0020FCB50040707A00080000FF07B9 +:1027400013B500F580540191606CFFF7DFFC1F2882 +:102750000AD920220199606CFFF74EFDA0F12003F9 +:102760005842584102B010BD0020FBE708B53023A5 +:1027700083F3118800F58050406CFFF79BFC002329 +:1027800083F3118808BD000000220260828142604C +:10279000826070470022002310B5C0E900230023A7 +:1027A00004460C3020F8043CFFF7EEFF204610BD35 +:1027B0002DE9F0479A4688B007468846914630236F +:1027C00083F3118807F580546846FFF7E3FF606CD8 +:1027D000FFF782FC1F282ED920226946606CFFF784 +:1027E0008FFD202827D194F8523423B303AD4446FB +:1027F00005AB2E46083403CE9E4244F8080C44F83C +:10280000041C3546F5D130682060B388A380DDE92B +:102810000023C9E90023BDF80830AAF800300023DE +:1028200083F3118853464A464146384608B0BDE80E +:10283000F04700F07BBD002080F3118808B0BDE8B0 +:10284000F08700002DE9F84F0023064600F581547B +:10285000054688461034C0E90133264B46F8303B24 +:10286000374638462037FFF795FFA742F9D105F5DF +:1028700080544FF4805305F5A3594FF0000A2663A6 +:102880000026676405F5835709F110094FF0000B26 +:102890001037E663C4E90D36012384F8403084F82C +:1028A0004830A7F11800203747E910ABFFF76CFF5D +:1028B00047F8286C4F45F4D184F85884A4F85A643A +:1028C000A4F85C64A4F85E6484F86064A4F86264AC +:1028D000A4F86464A4F8666484F86864B8F1000F2E +:1028E00002D0054800F00CFD044B2846EB62BDE821 +:1028F000F88F00BFB07A0008947A000800A000406A +:10290000044B10B5197804464A1C1A70FFF79AFF59 +:10291000204610BD854F00202DE9F04300295AD0F4 +:102920002E4E2F48B6FBF1F481428CBF0A201120B5 +:10293000431EB4FBF0F700FB1740DDB220B1022BC1 +:102940001846F5D8002032E07B1EB3F5806F2ED2FA +:10295000C5EBC5084FF47A7308F103044FEAE40E9F +:10296000C4F3C7040EF10109281B0EFB033E5FFAF6 +:1029700080FC59FA80F0BEFBF0F0B0F5617F18DC06 +:1029800083B2601C5CFA80F07843B6FBF0F08142C1 +:10299000D8D1611E0F29D5D80CF1FF310729D1D824 +:1029A0000120138057801071547182F806C0BDE871 +:1029B000F08308F1FF34E010C4F3C70400F1010E06 +:1029C0002D1B00FB03335FFA85FC5EFA85F5B3FB34 +:1029D000F5F39BB2D5E70846E9E700BF00B4C404AD +:1029E0003F420F0030B50D4B05200D4D1C786C4358 +:1029F0008C420ED159780120518099785171D97843 +:102A00009171197911715B7903EB83035B0013807A +:102A100030BD013803F10603E8D1F9E7F07A000888 +:102A200040420F0038B540F27772C36A154CC3F8C4 +:102A3000BC200722C36AC3F8C8202268C16A930079 +:102A400043F4C023C1F8A03002F1805302F16C01BD +:102A5000C56A03F52C53EA3289009B00226041F0DD +:102A6000E061094AC361C5F8C01003F5D87103F5E8 +:102A70006A7341629342836202D9044800F040FCC9 +:102A800038BD00BF884F0020FCB50040707A0008B8 +:102A90002DE9F04F00F580551F4689B0044695F8A2 +:102AA000583489469046012B04D90026304609B097 +:102AB000BDE8F08FA04A52F8231009B942F823006C +:102AC0009E48C4F80C9001782774C9B9302383F369 +:102AD00011889B4BD3F8EC2042F48072C3F8EC20B1 +:102AE000D3F8942042F48072C3F89420D3F8942051 +:102AF00022F48072C3F894200123037081F31188BB +:102B000095F851647EB9302383F311880321132093 +:102B100001F074FF0321152001F070FF012385F8F7 +:102B2000513486F31188302383F31188E26A936964 +:102B300023F01003936100F0E9FB8246E36A9E698B +:102B400016F0080609D000F0E1FBA0EB0A03FA2B0F +:102B5000F4D9002686F31188A8E79A6942F00102A9 +:102B60009A6100F0D3FB8246E36A9A69D00706D4E3 +:102B700000F0CCFBA0EB0A03FA2BF5D9E9E79A6940 +:102B80004FF0000A42F002029A61E36AC3F854A0CF +:102B90008AF3118804F5825B686CFFF78BFA0BF1FE +:102BA000100B202200216846FEF7FCFE02A8FFF76A +:102BB000EBFD6A460BEB06030DF1180ECDF818A0DD +:102BC00094460833BCE80300F44543F8080C43F886 +:102BD000041C6246F4D1DCF8000020361860B6F51B +:102BE000806F9CF804201A71DBD1002304F5A252F7 +:102BF000494620461A3285F8503485F85334FFF799 +:102C00008BFE064690B9E26A936923F00103936153 +:102C100000F07CFB0546E36A9B69D9077FF545AF69 +:102C200000F074FB431BFA2BF5D93EE795F85E34B0 +:102C3000C5F86C94591E95F85F34E26A013B1B029B +:102C400043EA416395F8601401390B43B5F85C140D +:102C5000013943EA0143D361B8F1000F36D004F5DE +:102C6000A352414620460232FFF7BCFE90B9E26A09 +:102C7000936923F00103936100F048FB0546E36A82 +:102C80009B69DA077FF511AF00F040FB431BFA2B7D +:102C9000F5D90AE795F86724C5F87084511E95F8B0 +:102CA0006824E36A013A120142EA012295F86614A7 +:102CB00001390A43B5F86414013942EA014242F489 +:102CC0000002DA604FF42062E36A9A64E36A4FF02C +:102CD00000082046C3F8BC80FFF7A4FE85F859849D +:102CE0006FF04042E36A1A65164AE36A5A654FF08C +:102CF0000222E36A9A654FF0FF32E36AC3F8E020EC +:102D00000322E36A9742DA653FF4D0AEE26A936940 +:102D100023F00103936100F0F9FA0746E36A9B6927 +:102D2000DB0705D500F0F2FAC31BFA2BF6D9BCE697 +:102D3000012385F85234B9E6804F0020844F0020EB +:102D400000440258550200022DE9F04F054689B0B3 +:102D500090469946002741F2680A00F58056EB6AD2 +:102D6000D3F8D830FB40D80751D505EB47124FEACE +:102D7000471B52441379190749D4D6F884340133D8 +:102D8000C6F8843405F5A553C3E9008913799A067A +:102D900005EB0B0248BFD6F8B434524444BF0133AC +:102DA000C6F8B434137943F008031371DB0723D555 +:102DB00096F8533403B305F582546846FFF7EAFCEE +:102DC00003AB18345C4404F1080C2068083454F850 +:102DD000041C1A46644503C21346F6D120686946AE +:102DE00010602846A2889A800123ADF808302B682D +:102DF000CDE90089DB6B9847D6F8A834D6F854049F +:102E00000133C6F8A83410B103681B69984701372D +:102E1000202FA4D109B0BDE8F08F00002DE9F04FBC +:102E20000F468DB0044600F073FA82468946002FA3 +:102E30005BD1E36AD3F8A02012F4FE0F03D1002087 +:102E40000DB0BDE8F08FD3F8A420920141BF04F586 +:102E50008051D1F898240132C1F89824D3F8A420E5 +:102E60005606ECD0D3F8A450E669C5F305254823EF +:102E7000E8464FF0000B03FB05664046FFF784FC75 +:102E8000326851004ABF22F06043C2F38A4343F0E4 +:102E90000043920048BF43F080430093736813F4EB +:102EA00000131BBF012304F580528DF80D308DF8FF +:102EB0000D301EBFD2F8B8340133C2F8B834F388ED +:102EC00003F00F038DF80C309DF80C0000F07AFA37 +:102ED0005FFA8BF3984225D9F2180CA90BF1010B7C +:102EE000127A0B4403F82C2CEEE7012FA7D1E36AEA +:102EF000D3F8B02012F4FE0FA1D0D3F8B42095017E +:102F000041BF04F58051D1F898240132C1F89824CA +:102F1000D3F8B420500692D0D3F8B450266AC5F343 +:102F20000525A4E7EFB9E36AC3F8A85004A807ADE4 +:102F3000FFF730FC98E80F0007C52B8000232046E0 +:102F400004A9ADF81830236804F58054DB6BCDE993 +:102F500004A9984758B1D4F890340133C4F8903498 +:102F60006EE7012FE2D1E36AC3F8B850DEE7D4F888 +:102F7000943401200133C4F8943461E72DE9F04121 +:102F800005460F4600F58054012639462846FFF7CE +:102F900045FF10B184F85364F7E7D4F8A834D4F8A7 +:102FA00054040133C4F8A83420B10368BDE8F041EB +:102FB0001B691847BDE8F081C36AF0B51A6C12F4BA +:102FC0007F0F2BD01B6C00F5805441F268054FF049 +:102FD000010CC4F8AC340023471900EB43125E0126 +:102FE0002A44117911F0020F15D0490713D4B959A9 +:102FF000C66A0CFA01F1D6F8CCE011EA0E0F0AD03D +:10300000C6F8D410117941F004011171D4F88C2460 +:103010000132C4F88C240133202BDED1F0BD000036 +:1030200010B5264C264B22680AB340B31A6D9205A0 +:103030000FD54FF400721A6500F06AF950EA0102E8 +:103040000B4602D0013861F1000302462068FFF709 +:103050007BFE1B4A136D9B012AD523684FF000713C +:1030600003F580531165012283F8592420E00122E1 +:103070001A6510221A654FF480521A6510BD196D39 +:10308000C80702D4196D490705D5052110461965F1 +:103090000021FFF773FF0A4B1A6DD00602D41A6D98 +:1030A000510605D5502201211A652068FFF766FFF9 +:1030B0002068BDE81040FFF77FBF00BF804F0020B1 +:1030C00000A0004008B5302383F31188FFF774FF98 +:1030D000002383F3118808BDC36AD3F8C00010F041 +:1030E0007C5005D0D3F8C40080F40010C0F34050E9 +:1030F0007047000008B5302383F3118800F5805035 +:10310000406CFEF7E9FF002383F3118843090CBFED +:103110000120002008BD000000F5805393F85924D9 +:1031200062B1C16A8A6922F001028A61D3F89C24E3 +:103130000132C3F89C24002283F859247047000010 +:103140002DE9F743302181F3118800F582510025E4 +:1031500041F2680E4FF00108103100F5805C00EB81 +:1031600045147444267977071CD4F6061AD58E695F +:10317000D0F82C9008FA06F6D9F8CC703E4211D05F +:103180004F6801970F689742019F9F410AD2C9F883 +:10319000D460267946F004062671DCF888440134B0 +:1031A000CCF8884401352031202DD8D1002383F379 +:1031B000118803B0BDE8F083F8B51E4600230F4622 +:1031C000054613701446FFF795FF80F00100387034 +:1031D0001EB12846FFF780FF2070F8BD2DE9F04FA3 +:1031E00085B099460D468046164691F800B0DDE957 +:1031F0000EA302931378019300F08AF82B7804460B +:103200000F4613B93378002B41D022463B46404647 +:10321000FFF796FFFFF756FFFFF77EFF4B4632465C +:103220002946FFF7C9FF2B7833B1BBF1000F03D05C +:10323000012005B0BDE8F08F337813B1019B002B5E +:10324000F6D108F5805303935445029B77EB0303B3 +:103250001DD2039BD3F85404C8B10368AAEB040140 +:103260001B6898474B46324629464046FFF7A4FF65 +:103270002B7813B1BBF1000FDAD1337813B1019B76 +:10328000002BD5D100F044F804460F46DCE70020BF +:10329000CFE7000008B50020FFF7C2FEBDE80840F8 +:1032A00001F056B808B50120FFF7BAFEBDE80840A6 +:1032B00001F04EB800B59BB0EFF309816822684673 +:1032C000FEF74AFBEFF30583014B9B6BFEE700BF64 +:1032D00000ED00E008B5FFF7EDFF000000B59BB082 +:1032E000EFF3098168226846FEF736FBEFF30583AA +:1032F000014B5B6BFEE700BF00ED00E0FEE7000066 +:103300000FB408B5029802F049FAFEE702F0DABEFF +:1033100002F0BCBE13B56C46031D84E8060094E8B9 +:10332000030083E80500012002B010BD73B5856875 +:10333000019155B11B885B0707D4D0E900369B6B20 +:103340009847019AC1B23046A847012002B070BD2B +:10335000F0B5866889B005460C465EB1BDF83830D8 +:103360005B070AD4D0E900379B6B98472246C1B26D +:103370003846B047012009B0F0BD0022002301F11A +:103380000806CDE9002300230A46ADF8083003AB58 +:103390001068083252F8041C1C46B24203C423468B +:1033A000F6D1106820609288A280FFF7B1FF042355 +:1033B000ADF808302B68CDE90001DB6B6946284683 +:1033C0009847D7E7082817D909280CD00A280CD025 +:1033D0000B280CD00C280CD00D280CD00E2814BFB4 +:1033E0004020302070470C20704710207047142078 +:1033F0007047182070472020704700002DE9F041E9 +:10340000456A15B94162BDE8F0814B68AC4623F0CE +:103410006047C3F38A464FEAD37EC3F3807816EA47 +:10342000230638BF3E462B465A68BEEBD27F22F0B9 +:1034300060440AD0002A18DAA40CB44217D19D4285 +:103440000FD10D60DEE71346EEE7A74207D102F089 +:103450008044C2F3807242450BD054B1EFE708D2EA +:10346000EDE7CCF800100B60CDE7B44201D0B442D8 +:10347000E5D81A689C46002AE5D11960C3E7000028 +:103480002DE9F047089D01F0070400EBD1004FF44F +:103490007F494FEAD508224405F00705944201D13F +:1034A000BDE8F08704F0070705F0070A111B08EBD9 +:1034B000D50E57453E4613F80EC038BF5646C6F1E6 +:1034C00008068E4228BF0E46E108415C344435446C +:1034D000B94029FA06F721FA0AF1FFB28CEA010194 +:1034E00047FA0AF739408CEA010C03F80EC0D5E719 +:1034F00080EA0120082341F2210201B2013B400091 +:10350000002980B2B8BF504013F0FF03F5D17047D7 +:1035100038B50C468D18A54200D138BD14F8011BF2 +:10352000FFF7E6FFF7E7000042684AB113688189B8 +:103530004360438901339BB29942438138BF838101 +:103540001046704770B588B0044620220D46684684 +:103550000021FEF727FA20460495FFF7E5FF024613 +:1035600060B16B46054608AE1C46083503CCB44234 +:1035700045F8080C45F8041C2346F5D1104608B060 +:1035800070BD0000082817D909280CD00A280CD0D3 +:103590000B280CD00C280CD00D280CD00E2814BFF2 +:1035A0004020302070470C207047102070471420B6 +:1035B000704718207047202070470000082817D94E +:1035C0000C280CD910280CD914280CD918280CD97F +:1035D00020280CD930288CBF0F200E2070470920DE +:1035E00070470A2070470B2070470C2070470D2051 +:1035F000704700002DE9F843078C0446072F1ED9B9 +:1036000000254FF6FF73D0E90298C5F12006A5F119 +:10361000200029FA05F1083508FA06F628FA00F024 +:10362000314301431846C9B2FFF762FF402D0346FC +:10363000EBD13A46E169BDE8F843FFF769BF4FF6C1 +:10364000FF70BDE8F883000010B54B6823B9CA8A43 +:1036500063F30902CA8210BD04691A681C60036121 +:10366000C38A013BC3824A60EFE700002DE9F84FAF +:103670001D46CB8A0F468146C3F3090192460529B0 +:103680000B4630D00020AAB207F11A049EB21FFAEE +:1036900080F8042E0FD8904503F1010306D30A44A5 +:1036A000FB8A62F309030120FB821AE01AF800602A +:1036B0000130E654EAE79045F1D2A1F1050B1C2355 +:1036C0007C68BBFBF3F203FB12BB1FFA8BF6002CEA +:1036D00045D14846FFF728FF044638B978606FF0B7 +:1036E0000200BDE8F88F4FF00008E6E7002606600C +:1036F0007860ADB24FF0000B454510D90AEB0803D6 +:10370000221D13F8011B08F101089155B1B21FFAEF +:1037100088F81B292BD0454506F10106F1D8FB8A14 +:10372000C3F30902154465F30903BCE701321C46E3 +:1037300092B22368002BF9D16B1F0B441C21B3FB01 +:10374000F1F301339BB29A42D3D2BBF1000FD0D137 +:103750004846FFF7E9FE20B9C4F800B0BFE70122F0 +:10376000E7E7C0F800B05E4620600446C1E7454583 +:10377000D5D94846FFF7D8FE08B92060AFE7C0F8B2 +:1037800000B0002620600446B6E700002DE9F04FA7 +:103790001C46074688462DED028B83B05B6901927B +:1037A000002B00F09A80238C2BB1E269002A00F0F4 +:1037B0009480072B35D807F10C00FFF7B5FE0546BE +:1037C00038B96FF00205284603B0BDEC028BBDE8A6 +:1037D000F08F14220021FEF7E5F8228CE16905F153 +:1037E0000800FEF7B9F8208C48F00041013080B2A3 +:1037F000FFF7E4FEFFF7C6FE013880B220840130F7 +:10380000287438466369228C1B782A4403F01F030E +:1038100063F03F03137269602946FFF7EFFD01254E +:10382000D1E74FF0000900F10C034FF0800A4E463B +:103830004D4608EE103A18EE100AFFF775FE834663 +:103840000028BED014220021FEF7ACF8002E3AD199 +:10385000019B0222ABF808300BF1080E1FFA82FC24 +:10386000218C0CF10100BCF1060F80B201D88E4210 +:103870002BD3FFF7A3FE8E4208BF4FF0400AFFF79D +:1038800081FE62690138013512781BFA80F101303E +:1038900002F01F022DB242EA491289F001094AEAF8 +:1038A000020A48F0004281F808A059468BF810003F +:1038B0003846CBF804204FF0000AFFF79FFD238C19 +:1038C000B342B8D17FE70022C6E7E169895D0136DE +:1038D0000EF80210B6B20132C0E76FF0010572E7D0 +:1038E000F8B515460E463022002104461F46FEF765 +:1038F00059F8069BB5F5001FA760636004F110003E +:10390000079B34BF6A094FF6FF72E661A36200238A +:1039100097B29A4206D800230360A782E3822383EA +:10392000E360F8BD0660013330462036F1E7000061 +:1039300003781BB94BB2002BC8BF01707047000061 +:1039400000787047F8B50C46C969074611B9238C51 +:10395000002B37D1257E1F2D34D8387828BB228CF8 +:10396000072A2CD8268A36F003032BD14FF6FF7096 +:10397000FFF7CEFD20F0010031024FF6FF72400448 +:1039800041EA0561400C41EA402523462946384674 +:10399000FFF7FCFE002807DD626913780133DBB214 +:1039A0001F2B88BF00231370F8BD218A2D0645EA1E +:1039B000012505432046FFF71DFE0246E5E76FF0AF +:1039C0000300F1E76FF00100EEE7000070B58AB088 +:1039D000044616460021282268461D46FDF7E2FFF0 +:1039E000BDF8383069462046ADF810300F9B05937E +:1039F0009DF840308DF81830119B0793BDF8483082 +:103A0000CDE90265ADF82030FFF79CFF0AB070BD2C +:103A10002DE9F041D36905460C4616460BB9138CC7 +:103A20005BBB377E1F2F28D895F80080B8F1000FB8 +:103A300026D03046FFF7DEFD3378210202462846C5 +:103A400041EAC331338A41EA080141EA076141EAA8 +:103A50000341334641F08001FFF798FE00280ADD5C +:103A60003378012B07D1726913780133DBB21F2B36 +:103A700088BF00231370BDE8F0816FF00100FAE702 +:103A80006FF00300F7E70000F0B58BB004460D4679 +:103A900017460021282268461E46FDF783FF9DF841 +:103AA0004C30294620465A1E534253416A468DF8EF +:103AB00000309DF84030ADF81030119B05939DF813 +:103AC00048308DF81830149B0793BDF85430CDE979 +:103AD0000276ADF82030FFF79BFF0BB0F0BD000081 +:103AE000406A00B104307047436A1A684262026952 +:103AF0001A600361C38A013BC38270472DE9F0411C +:103B0000D0F8208014461D46184E4146002709B9BA +:103B1000BDE8F081D1E90223A21A65EB03039642C6 +:103B200077EB03031ED2036A8B420DD1FFF78CFDA6 +:103B3000036A1B68036203690B60C38A0161013B6E +:103B4000016AC3828846E2E7FFF77EFD0B68C8F88A +:103B5000003003690B60C38A0161013BC382D8F85E +:103B60000010D4E788460968D1E700BF80841E00B2 +:103B70002DE9F04F8BB00D4614469B46DDF8509072 +:103B80008046002800F01881B9F1000F00F0148180 +:103B9000531E3F2B00F21081012A03D1BBF1000F0D +:103BA00040F00A810023CDE90833B8F81430B5EBB2 +:103BB000C30F4FEAC30703D300200BB0BDE8F08F5B +:103BC0002B199F42D8F80C3036BF7F1B2746FFB217 +:103BD0001BB9D8F81030002B7AD0272D4DD8C5F15D +:103BE000280600232946B742009308ABD8F80800FE +:103BF0002CBFF6B23E46A7EB060A354432465FFAC2 +:103C00008AFAFFF73DFCB8F81430282103F100537D +:103C1000053BDB000493D8F80C300393039B13B1EE +:103C2000BAF1000F2CD1D8F8100040B1BAF1000F52 +:103C300005D008AB5246691A0096FFF721FC38B24E +:103C4000002FB9D066070AD00AAB624203EBD40159 +:103C500002F0070211F8083C134101F8083C082C57 +:103C60003DD9102C40F2B580202C40F2B780BBF13A +:103C7000000F00F09C80082335E0BA460026C2E71A +:103C8000049BE02B28BFE02306930B44AB42059333 +:103C900015D95A1B0398691A0096924508AB00F192 +:103CA000040034BF5246D2B20792FFF7E9FB079AED +:103CB0001644AAEB020A1544F6B25FFA8AFA049B8C +:103CC000069A05999B1A0493039B1B680393A5E727 +:103CD00000933A4608AB2946D8F80800ADE7BBF197 +:103CE000000F13D00123B4EBC30F6BD0082C12D8F4 +:103CF0009DF82030621E23FA02F2D50706D54FF058 +:103D0000FF3202FA04F423438DF820309DF820306E +:103D100089F8003051E7102C12D8BDF82030621E0F +:103D200023FA02F2D10706D54FF0FF3202FA04F46B +:103D30002343ADF82030BDF82030A9F800303CE72F +:103D4000202C0FD80899631E21FA03F3DA0705D552 +:103D50004FF0FF3202FA04F40C430894089BC9F8B0 +:103D600000302AE7402C2AD0611EC4F12102A4F1C0 +:103D70002103DDE9086526FA01F105FA02F225FAC8 +:103D800003F311431943CB0711D50122A4F12003FA +:103D9000C4F1200102FA03F322FA01F1A2400B431D +:103DA000524263EB430332432B43CDE90823DDE961 +:103DB0000823C9E9002300E76FF00100FDE66FF07A +:103DC0000800FAE6082CA1D9102CB4D9202CEED882 +:103DD000C4E7BBF1000FAED0022384E7BBF1000FB4 +:103DE000BCD004237FE70000012A30B5144638BF59 +:103DF000012485B00025402C28BF4024012ACDE9AC +:103E0000025518D81B788DF8083063070AD004AB28 +:103E1000624203EBD40502F0070215F8083C934018 +:103E200005F8083C034600912246002102A8FFF74E +:103E300027FB05B030BD082AE4D9102A03D81B8817 +:103E4000ADF80830E1E7202A95BF1B68D3E90023CD +:103E50000293CDE90223D8E710B5CB681BB98B607C +:103E60000B618B8210BD04691A681C600361C38AF0 +:103E7000013BC382CA60F0E703064CBFC0F3C03009 +:103E80000220704708B50246FFF7F6FF022806D168 +:103E90005306C2F30F2001D100F0030008BDC2F3A6 +:103EA0000740FBE72DE9F04F93B004460D46CDE9FE +:103EB00003230A681046FFF7DFFF0228824614BF7B +:103EC000C2F306260026002A80F2F38112F0C049D0 +:103ED00040F0EF81097B002900F0EB81022803D03C +:103EE0002378B34240F0E881C2F3046310462944CA +:103EF000069302F07F030593FFF7C4FF059B0022A2 +:103F000083464FEA8348002348EA0A4848EA46685D +:103F1000CE78CDE90823F30948EA0008029368D077 +:103F2000059B024608A92046009353466768B84798 +:103F3000002800F0C481276A4FB9414604F10C0003 +:103F4000FFF700FB074690B96FF0020055E03B69B0 +:103F500098450DD03F68002FF9D1414604F10C007F +:103F6000FFF7F0FA07460028EED0236A3B6027628D +:103F700097F817C006F01F08CCF3840CACEB0800D0 +:103F8000A8EB0C031FFA80FE0028B8BF0EF120003A +:103F90001FFA83FEB8BF00B2002B0793B8BF0EF123 +:103FA0002003D7E90221BCBF1BB2079352EA0103E9 +:103FB00038D0039B4FF0000CDFF820E39A1A049BE3 +:103FC00063EB010196457CEB01032BD36B7B97F8E8 +:103FD0001AE0734519D1029B002B78D0012821DC0F +:103FE0007868F8B9DFF8F0C2944570EB010316D396 +:103FF00037E0276A27B96FF00C0013B0BDE8F08FE7 +:104000003B699845B4D03F68F4E7B34890427CEBF5 +:10401000010301D30020F0E7029B002BFAD0079B9D +:104020000F2B17DCFA7DB3003946204602F003025D +:1040300003F07C031343FB75FFF706FB6B7BBB763A +:10404000029B3BB9FB7DC3F38402013262F386031A +:10405000FB75D0E76A7BBB7E9A42DBD1029B002BCB +:1040600035D0B309022B32D0039B142200210DA8B6 +:10407000BB60049BFB60FDF795FC039B0AA92046EF +:104080000A93049BADF83EB00B932B1D8DF840A016 +:104090000C932B7B8DF84180013BDBB2ADF83C30BB +:1040A000069B8DF84230059B8DF8433094F82C30F8 +:1040B00083F001038DF84430A3689847FB7DC3F378 +:1040C0008403013303F01F039B02FB82A2E7FB7D05 +:1040D000C6F34012B2EBD31F40F0F480C3F3840365 +:1040E000434540F0F280029AB6092B7B002A4DD05E +:1040F000F2075DD4032B40F2EB80039BAE1D3946E3 +:1041000004F10C00BB603246049BFB602B7B033B3D +:10411000DBB2FFF7ABFA00280CDA39462046FFF78E +:1041200093FAFB7DC3F38403013303F01F039B0267 +:10413000FB8209E7AB88DDE908843B834FF6FF7318 +:10414000C9F12000A9F1200228FA09F109F10809B2 +:1041500004FA00F024FA02F2014318461143C9B2EE +:10416000FFF7C6F9B9F1400F0346E9D1B8823146ED +:104170002A7B033AD2B2FFF7CBF9FB7DB882DA4350 +:10418000C2F3C01262F3C713FB7543E786B92E1D55 +:10419000013B394604F10C00DBB23246FFF766FA08 +:1041A0000028BADB2A7B3146B88A013AD2B2E2E76C +:1041B000F98A013BC1F30901DAB204295BD8281D51 +:1041C000002307F11B069A4208D910F801CB0133EE +:1041D00006F801C00131DBB20529F4D103999342FD +:1041E0000A9138BF043304992CBF002355FA83F396 +:1041F0000B9107F11B010C9179680E930D91291D0C +:10420000FB8AADF83EB0C3F309038DF840A08DF8EA +:1042100041801A44069B8DF84230059BADF83C2046 +:104220008DF8433094F82C3083F001038DF844303E +:104230000023B88A7B602A7B013AFFF769F93B8B40 +:10424000B882834203D1A3680AA920469847204632 +:104250000AA9FFF701FEFB7DBA8AC3F38403013389 +:1042600003F01F039B02FB823B8B9A420CBF002092 +:104270006FF01000C1E67B68002BAFD0052001E095 +:104280001C3033461E68002EFAD1091A2E1D081D57 +:10429000184401EB090C5FFA89F3BCF11B0F9DD8A0 +:1042A0009A429BD916F8013B09F1010900F8013B3C +:1042B000EFE76FF00900A0E66FF00A009DE66FF0EF +:1042C0000B009AE66FF00D0097E66FF00E0094E693 +:1042D0006FF00F0091E600BF40420F0080841E0087 +:1042E000EFF30983054968334A6B22F001024A6300 +:1042F00083F30988002383F31188704700EF00E0FF +:10430000302080F3118862B60D4B0E4AD96821F433 +:10431000E0610904090C0A430B49DA60D3F8FC2078 +:1043200042F08072C3F8FC20084AC2F8B01F11683E +:1043300041F0010111602022DA7783F822007047F2 +:1043400000ED00E00003FA0555CEACC5001000E01A +:10435000302310B583F311880E4B5B6813F40063B0 +:1043600014D0F1EE103AEFF309844FF08073683CFB +:10437000E361094BDB6B236684F3098801F0D8F90C +:1043800010B1064BA36110BD054BFBE783F3118809 +:10439000F9E700BF00ED00E000EF00E03F04000897 +:1043A0004204000808B5074B074A196801F03D01AF +:1043B000996053680BB190689847BDE80840FFF7D3 +:1043C000C7BF00BF00000240904F002008B5084B57 +:1043D0001968890901F03D018A019A60054AD3688C +:1043E0000BB110699847BDE80840FFF7B1BF00BFA7 +:1043F00000000240904F002008B5084B1968090CD6 +:1044000001F03D010A049A60054A53690BB19069B5 +:104410009847BDE80840FFF79BBF00BF000002407F +:10442000904F002008B5084B1968890D01F03D0137 +:104430008A059A60054AD3690BB1106A9847BDE8AE +:104440000840FFF785BF00BF00000240904F0020EA +:1044500008B5074B074A596801F03D01D960536A16 +:104460000BB1906A9847BDE80840FFF771BF00BFE5 +:1044700000000240904F002008B5084B5968890998 +:1044800001F03D018A01DA60054AD36A0BB1106B75 +:104490009847BDE80840FFF75BBF00BF000002403F +:1044A000904F002008B5084B5968090C01F03D01F8 +:1044B0000A04DA60054A536B0BB1906B9847BDE86C +:1044C0000840FFF745BF00BF00000240904F0020AA +:1044D00008B5084B5968890D01F03D018A05DA607D +:1044E000054AD36B0BB1106C9847BDE80840FFF745 +:1044F0002FBF00BF00000240904F002008B5074BBF +:10450000074A196801F03D019960536C0BB1906C3A +:104510009847BDE80840FFF71BBF00BF00040240FA +:10452000904F002008B5084B1968890901F03D013A +:104530008A019A60054AD36C0BB1106D9847BDE8AB +:104540000840FFF705BF00BF00040240904F002065 +:1045500008B5084B1968090C01F03D010A049A607E +:10456000054A536D0BB1906D9847BDE80840FFF7C1 +:10457000EFBE00BF00040240904F002008B5084B7A +:104580001968890D01F03D018A059A60054AD36DCD +:104590000BB1106E9847BDE80840FFF7D9BE00BFC9 +:1045A00000040240904F002008B5074B074A5968A5 +:1045B00001F03D01D960536E0BB1906E9847BDE894 +:1045C0000840FFF7C5BE00BF00040240904F002026 +:1045D00008B5084B5968890901F03D018A01DA6084 +:1045E000054AD36E0BB1106F9847BDE80840FFF73E +:1045F000AFBE00BF00040240904F002008B5084B3A +:104600005968090C01F03D010A04DA60054A536F4C +:104610000BB1906F9847BDE80840FFF799BE00BF07 +:1046200000040240904F002008B5084B5968890DDE +:1046300001F03D018A05DA60054AD36F13B1D2F863 +:1046400080009847BDE80840FFF782BE00040240A2 +:10465000904F002000230C4910B51A460B4C0B60FC +:1046600054F82300026001EB430004334260402B06 +:10467000F6D1074A4FF0FF339360D360C2F8083495 +:10468000C2F80C3410BD00BF904F0020107B000812 +:10469000000002400F28F8B510D9102810D01128BA +:1046A00011D0122808D10F240720DFF8B4E001262A +:1046B000DEF80050A04208D9002649E00446F4E79D +:1046C0000F240020F1E70724FBE706FA00F73D423C +:1046D00040D1214C4FEA001C3D4304EB00160EEB89 +:1046E000C000CEF80050C0E90123FBB24BB11B481B +:1046F000836B43F001038363036E43F0010303669E +:10470000036E17F47F4F09D01448836B43F0020304 +:104710008363036E43F002030366036E54F80C00D8 +:10472000036823F01F030360056815F00105FBD142 +:1047300004EB0C033D2493F80CC05F6804FA0CF4FE +:104740003C6021240560446112B1987B00F056F969 +:104750003046F8BD0130ADE7107B00080045025837 +:10476000904F002010B5302484F31188FFF792FF9A +:10477000002383F3118810BD10B50446807B00F040 +:1047800053F901231049627B03FA02F20B6823EA12 +:104790000203DAB20B604AB90C4A916B21F00101B5 +:1047A0009163116E21F001011166126E13F47F4FB7 +:1047B00009D1064B9A6B22F002029A631A6E22F01C +:1047C00002021A661B6E10BD904F00200045025871 +:1047D00008B5302383F31188FFF7CEFF002383F35E +:1047E000118808BD026843681143016003B118478E +:1047F00070470000024A136843F0C003136070471B +:104800000078004013B50E4C204600F0B7FA04F1D2 +:10481000140000234FF400720A49009400F074F968 +:10482000094B4FF40072094904F13800009400F07C +:10483000EDF9074A074BC4E9172302B010BD00BFCA +:104840001450002080500020F547000880520020BE +:104850000078004000E1F505037C30B5214C0029CB +:1048600018BF0C46012B0CD11F4B984209D11F4B8E +:104870009A6C42F080429A641A6F42F080421A6742 +:104880001B6F2268036EC16D03EB52038466B3FB9A +:10489000F2F36268150442BF23F0070503F0070333 +:1048A00043EA4503CB60A36843F040034B60E368F1 +:1048B00043F001038B6042F4967343F001030B60F5 +:1048C0004FF0FF330B62510505D512F0102205D0D1 +:1048D000B2F1805F04D080F8643030BD7F23FAE706 +:1048E0003F23F8E7107C00081450002000450258D0 +:1048F0002DE9F047C66D05463768F4692107346233 +:104900001AD014F0080118BF4FF48071E20748BFB5 +:1049100041F02001A3074FF0300348BF41F04001B0 +:10492000600748BF41F0800183F31188281DFFF71D +:1049300059FF002383F31188E2050AD5302383F35E +:1049400011884FF48061281DFFF74CFF002383F38B +:1049500011884FF030094FF0000A14F0200838D1C8 +:104960003B0616D54FF0300905F1380A200610D560 +:1049700089F31188504600F07DF9002836DA0821C5 +:10498000281DFFF72FFF27F080033360002383F3F8 +:104990001188790614D5620612D5302383F3118865 +:1049A000D5E913239A4208D12B6C33B127F0400785 +:1049B0001021281DFFF716FF3760002383F31188AD +:1049C000E30618D5AA6E1369ABB15069BDE8F0478C +:1049D000184789F31188736A284695F864101940BE +:1049E00000F0E6F98AF31188F469B6E7B06288F35B +:1049F0001188F469BAE7BDE8F0870000090100F109 +:104A00006043012203F56143C9B283F8001300F04B +:104A10001F039A4043099B0003F1604303F5614380 +:104A2000C3F880211A60704700F01F0301229A40EA +:104A3000430900F160409B0000F5614003F16043D1 +:104A400003F56143C3F88020C3F88021002380F878 +:104A500000337047F8B51546826804460B46AA42F3 +:104A600000D28568A1692669761AB5420BD218462C +:104A70002A46FCF771FFA3692B44A3612846A3686B +:104A80005B1BA360F8BD0CD9AF1B18463246FCF780 +:104A900063FF3A46E1683044FCF75EFFE3683B445D +:104AA000EBE718462A46FCF757FFE368E5E7000006 +:104AB00083689342F7B50446154600D28568D4E969 +:104AC0000460361AB5420BD22A46FCF745FF6369EB +:104AD0002B4463612846A3685B1BA36003B0F0BD51 +:104AE0000DD93246AF1B0191FCF736FF01993A46CA +:104AF000E0683144FCF730FFE3683B44E9E72A46CD +:104B0000FCF72AFFE368E4E710B50A440024C36118 +:104B1000029B8460C16002610362C0E90000C0E9D9 +:104B2000051110BD08B5D0E90532934201D1826864 +:104B300082B98268013282605A1C42611970002178 +:104B4000D0E904329A4224BFC368436100F09CFE5E +:104B5000002008BD4FF0FF30FBE7000070B53023A8 +:104B600004460E4683F31188A568A5B1A368A2691F +:104B7000013BA360531CA36115782269934224BFB3 +:104B8000E368A361E3690BB120469847002383F3F0 +:104B90001188284607E03146204600F065FE0028CF +:104BA000E2DA85F3118870BD2DE9F74F04460E4611 +:104BB00017469846D0F81C904FF0300A8AF31188B7 +:104BC0004FF0000B154665B12A4631462046FFF7E7 +:104BD00041FF034660B94146204600F045FE0028EB +:104BE000F1D0002383F31188781B03B0BDE8F08F68 +:104BF000B9F1000F03D001902046C847019B8BF309 +:104C00001188ED1A1E448AF31188DCE7C160C36184 +:104C1000009B82600362C0E905111144C0E90000F5 +:104C200001617047F8B504460D461646302383F3FC +:104C30001188A768A7B1A368013BA36063695A1CE8 +:104C400062611D70D4E904329A4224BFE368636153 +:104C5000E3690BB120469847002080F3118807E0F4 +:104C60003146204600F000FE0028E2DA87F3118882 +:104C7000F8BD0000D0E9052310B59A4201D1826841 +:104C80007AB982680021013282605A1C82611C78E4 +:104C900003699A4224BFC368836100F0F5FD204692 +:104CA00010BD4FF0FF30FBE72DE9F74F04460E46ED +:104CB00017469846D0F81C904FF0300A8AF31188B6 +:104CC0004FF0000B154665B12A4631462046FFF7E6 +:104CD000EFFE034660B94146204600F0C5FD0028BE +:104CE000F1D0002383F31188781B03B0BDE8F08F67 +:104CF000B9F1000F03D001902046C847019B8BF308 +:104D00001188ED1A1E448AF31188DCE702684368B3 +:104D10001143016003B11847704700001430FFF7DA +:104D200043BF00004FF0FF331430FFF73DBF0000DA +:104D30003830FFF7B9BF00004FF0FF333830FFF7CE +:104D4000B3BF00001430FFF709BF00004FF0FF3180 +:104D50001430FFF703BF00003830FFF763BF0000D7 +:104D60004FF0FF323830FFF75DBF0000012914BF5C +:104D70006FF0130000207047FFF744BD044B036041 +:104D800000234360C0E9023301230374704700BF6E +:104D9000287C000810B53023044683F31188FFF700 +:104DA0005BFD02230020237480F3118810BD0000F6 +:104DB00038B5C36904460D461BB904210844FFF702 +:104DC000A5FF294604F11400FFF7ACFE002806DA1F +:104DD000201D4FF40061BDE83840FFF797BF38BD94 +:104DE000026843681143016003B11847704700002F +:104DF00013B5406B00F58054D4F8A4381A681178C4 +:104E0000042914D1017C022911D1197901231289B5 +:104E10008B4013420BD101A94C3002F0E9F8D4F8D1 +:104E2000A4480246019B2179206800F0DFF902B016 +:104E300010BD0000143002F06BB800004FF0FF33DB +:104E4000143002F065B800004C3002F03DB90000AB +:104E50004FF0FF334C3002F037B90000143002F04D +:104E600039B800004FF0FF31143002F033B80000C1 +:104E70004C3002F009B900004FF0FF324C3002F024 +:104E800003B900000020704710B500F58054D4F835 +:104E9000A4381A681178042917D1017C022914D189 +:104EA0005979012352898B4013420ED1143001F0FD +:104EB000CBFF024648B1D4F8A4484FF4407361795F +:104EC0002068BDE8104000F07FB910BD406BFFF7CF +:104ED000DBBF0000704700007FB5124B01250426A0 +:104EE000044603600023057400F1840243602946F0 +:104EF000C0E902330C4B0290143001934FF440731D +:104F0000009601F07DFF094B04F69442294604F116 +:104F10004C000294CDE900634FF4407302F044F872 +:104F200004B070BD507C0008CD4E0008F14D000863 +:104F30000A68302383F311880B790B3342F823007E +:104F40004B79133342F823008B7913B10B3342F8BA +:104F5000230000F58053C3F8A41802230374002033 +:104F600080F311887047000038B5037F044613B101 +:104F700090F85430ABB90125201D0221FFF730FF16 +:104F800004F114006FF00101257700F089FC04F1B1 +:104F90004C0084F854506FF00101BDE8384000F037 +:104FA0007FBC38BD10B5012104460430FFF718FF5F +:104FB0000023237784F8543010BD000038B5044630 +:104FC0000025143001F034FF04F14C00257702F085 +:104FD00003F8201D84F854500121FFF701FF2046FB +:104FE000BDE83840FFF750BF90F8803003F0600311 +:104FF000202B06D190F881200023212A03D81F2AD4 +:1050000006D800207047222AFBD1C0E91D3303E0F7 +:10501000034A426707228267C3670120704700BFC7 +:105020003C23002037B500F58055D5F8A4381A6820 +:10503000117804291AD1017C022917D11979012389 +:1050400012898B40134211D100F14C04204602F02A +:1050500083F858B101A9204601F0CAFFD5F8A44849 +:105060000246019B2179206800F0C0F803B030BDF2 +:1050700001F10B03F0B550F8236085B004460D46EE +:10508000FEB1302383F3118804EB8507301D08211E +:10509000FFF7A6FEFB6806F14C005B691B681BB1BD +:1050A000019001F0B3FF019803A901F0A1FF0246AE +:1050B00048B1039B2946204600F098F8002383F36B +:1050C000118805B0F0BDFB685A691268002AF5D056 +:1050D0001B8A013B1340F1D104F18002EAE7000092 +:1050E000133138B550F82140ECB1302383F31188E7 +:1050F00004F58053D3F8A4281368527903EB820394 +:10510000DB689B695D6845B104216018FFF768FEA4 +:10511000294604F1140001F0A1FE2046FFF7B4FE79 +:10512000002383F3118838BD7047000001F074B983 +:1051300001234022002110B5044600F8303BFCF763 +:1051400031FC0023C4E9013310BD000010B5302349 +:10515000044683F311882422416000210C30FCF7BF +:1051600021FC204601F07AF902230020237080F30D +:10517000118810BD70B500EB8103054650690E46DD +:105180001446DA6018B110220021FCF70BFCA0696C +:1051900018B110220021FCF705FC31462846BDE875 +:1051A000704001F05BBA000083682022002103F008 +:1051B000011310B5044683601030FCF7F3FB204662 +:1051C000BDE8104001F0D6BAF0B4012500EB81042F +:1051D00047898D40E4683D43A469458123600023ED +:1051E000A2606360F0BC01F0F3BA0000F0B40125E6 +:1051F00000EB810407898D40E4683D4364690581C3 +:1052000023600023A2606360F0BC01F069BB000072 +:1052100070B5022300250446242203702946C0F8F5 +:1052200088500C3040F8045CFCF7BCFB204684F846 +:10523000705001F0A7F963681B6823B12946204626 +:10524000BDE87040184770BD0378052B10B50446C3 +:105250000AD080F88C300523037043681B680BB1BB +:10526000042198470023A36010BD000001780529A0 +:1052700006D190F88C20436802701B6803B1184770 +:105280007047000070B590F87030044613B10023E9 +:1052900080F8703004F18002204601F08FFA6368D4 +:1052A0009B68B3B994F8803013F0600535D00021C5 +:1052B000204601F081FD0021204601F071FD636868 +:1052C0001B6813B1062120469847062384F87030E6 +:1052D00070BD204698470028E4D0B4F88630A26F0D +:1052E0009A4288BFA36794F98030A56F002B4FF0D6 +:1052F000300380F20381002D00F0F280092284F84F +:10530000702083F3118800212046D4E91D23FFF784 +:105310006DFF002383F31188DAE794F8812003F00E +:105320007F0343EA022340F20232934200F0C58039 +:1053300021D8B3F5807F48D00DD8012B3FD0022B68 +:1053400000F09380002BB2D104F188026267022240 +:10535000A267E367C1E7B3F5817F00F09B80B3F5F7 +:10536000407FA4D194F88230012BA0D1B4F88830CA +:1053700043F0020332E0B3F5006F4DD017D8B3F518 +:10538000A06F31D0A3F5C063012B90D8636820468D +:1053900094F882205E6894F88310B4F88430B047A3 +:1053A000002884D0436863670368A3671AE0B3F5F5 +:1053B000106F36D040F6024293427FF478AF5C4BD8 +:1053C00063670223A3670023C3E794F88230012BAD +:1053D0007FF46DAFB4F8883023F00203A4F888306E +:1053E000C4E91D55E56778E7B4F88030B3F5A06FE0 +:1053F0000ED194F88230204684F88A3001F020F9EA +:1054000063681B6813B1012120469847032323706A +:105410000023C4E91D339CE704F18B036367012378 +:10542000C3E72378042B10D1302383F3118820465F +:10543000FFF7BAFE85F311880321636884F88B5067 +:1054400021701B680BB12046984794F88230002BDE +:10545000DED084F88B300423237063681B68002B34 +:10546000D6D0022120469847D2E794F884302046CF +:105470001D0603F00F010AD501F092F9012804D0AE +:1054800002287FF414AF2B4B9AE72B4B98E701F0DF +:1054900079F9F3E794F88230002B7FF408AF94F8A1 +:1054A000843013F00F01B3D01A06204602D501F064 +:1054B0009BFCADE701F08CFCAAE794F88230002B4E +:1054C0007FF4F5AE94F8843013F00F01A0D01B06E2 +:1054D000204602D501F070FC9AE701F061FC97E7E5 +:1054E000142284F8702083F311882B462A4629461B +:1054F0002046FFF769FE85F31188E9E65DB11522C4 +:1055000084F8702083F3118800212046D4E91D23FC +:10551000FFF75AFEFDE60B2284F8702083F3118812 +:105520002B462A4629462046FFF760FEE3E700BFE8 +:10553000807C0008787C00087C7C000838B590F8F6 +:1055400070300446002B3ED0063BDAB20F2A34D826 +:105550000F2B32D8DFE803F03731310822323131F6 +:105560003131313131313737856FB0F886309D4276 +:1055700014D2C3681B8AB5FBF3F203FB12556DB955 +:10558000302383F311882B462A462946FFF72EFE47 +:1055900085F311880A2384F870300EE0142384F810 +:1055A0007030302383F31188002320461A461946B1 +:1055B000FFF70AFE002383F3118838BDC36F03B1E0 +:1055C00098470023E7E70021204601F0F5FB002182 +:1055D000204601F0E5FB63681B6813B106212046F5 +:1055E00098470623D7E7000010B590F870300446BE +:1055F000142B29D017D8062B05D001D81BB110BD0C +:10560000093B022BFBD80021204601F0D5FB0021ED +:10561000204601F0C5FB63681B6813B106212046D4 +:105620009847062319E0152BE9D10B2380F8703039 +:10563000302383F3118800231A461946FFF7D6FD5D +:10564000002383F31188DAE7C3689B695B68002B4A +:10565000D5D1C36F03B19847002384F87030CEE7EB +:1056600000238268037503691B6899689142FBD225 +:105670005A68036042601060586070470023826877 +:10568000037503691B6899689142FBD85A680360E7 +:10569000426010605860704708B50846302383F3B5 +:1056A00011880B7D032B05D0042B0DD02BB983F370 +:1056B000118808BD8B6900221A604FF0FF338361A7 +:1056C000FFF7CEFF0023F2E7D1E9003213605A6002 +:1056D000F3E70000FFF7C4BF054BD96808751868E9 +:1056E000026853601A600122D8600275FAF792BE10 +:1056F000805400200C4B30B5DD684B1C87B004464D +:105700000FD02B46094A684600F05EF92046FFF7A5 +:10571000E3FF009B13B1684600F060F9A86907B089 +:1057200030BDFFF7D9FFF9E78054002099560008F3 +:10573000044B1A68DB6890689B68984294BF00200D +:105740000120704780540020084B10B51C68D868B1 +:10575000226853601A600122DC602275FFF78EFF19 +:1057600001462046BDE81040FAF754BE80540020A0 +:1057700038B5074C012300250649074823706560AA +:1057800001F028FD0223237085F3118838BD00BF86 +:10579000E8560020887C00088054002008B572B6C6 +:1057A000044B186500F060FC00F026FD024B03225C +:1057B0001A70FEE780540020E856002000F044B93B +:1057C000034A516853685B1A9842FBD8704700BF80 +:1057D000001000E08B600223086108468B8270474E +:1057E0008368A3F1840243F8142C026943F8442C23 +:1057F000426943F8402C094A43F8242CC268A3F1BB +:10580000200043F8182C022203F80C2C002203F885 +:105810000B2C034A43F8102C704700BF2D040008DE +:105820008054002008B5FFF7DBFFBDE80840FFF714 +:1058300051BF0000024BDB6898610F20FFF74CBF9F +:1058400080540020302383F31188FFF7F3BF00005A +:1058500008B50146302383F311880820FFF74AFF7B +:10586000002383F3118808BD064BDB6839B1426819 +:1058700018605A60136043600420FFF73BBF4FF08D +:10588000FF307047805400200368984206D01A68A1 +:105890000260506018469961FFF71CBF7047000016 +:1058A00038B504460D462068844200D138BD0368EF +:1058B00023605C608561FFF70DFFF4E7036810B5B6 +:1058C0009C68A2420CD85C688A600B604C602160C6 +:1058D000596099688A1A9A604FF0FF33836010BD4F +:1058E000121B1B68ECE700000A2938BF0A2170B5BB +:1058F00004460D460A26601901F064FC01F04CFCD8 +:10590000041BA54203D8751C04462E46F3E70A2E55 +:1059100004D90120BDE8704001F09CBC70BD0000BE +:10592000F8B5144B0D460A2A4FF00A07D96103F166 +:105930001001826038BF0A22416019691446016073 +:1059400048601861A81801F02DFC01F025FC431BEC +:105950000646A34206D37C1C28192746354601F08B +:1059600031FCF2E70A2F04D90120BDE8F84001F02C +:1059700071BCF8BD80540020F8B506460D4601F014 +:105980000BFC0F4A134653F8107F9F4206D12A465C +:1059900001463046BDE8F840FFF7C2BFD169BB6899 +:1059A000441A2C1928BF2C46A34202D92946FFF7D6 +:1059B0009BFF224631460348BDE8F840FFF77EBF13 +:1059C0008054002090540020C0E90323002310B429 +:1059D0005DF8044B4361FFF7CFBF000010B5194CD1 +:1059E000236998420DD08168D0E9003213605A6073 +:1059F0009A680A449A60002303604FF0FF33A36162 +:105A000010BD0268234643F8102F53600022026045 +:105A100022699A4203D1BDE8104001F0CDBB9368E2 +:105A200081680B44936001F0B7FB2269E1699268D9 +:105A3000441AA242E4D91144BDE81040091AFFF704 +:105A400053BF00BF805400202DE9F047DFF8BC8031 +:105A500008F110072C4ED8F8105001F09DFBD8F833 +:105A60001C40AA68031B9A423ED814444FF0000918 +:105A7000D5E90032C8F81C4013605A60C5F80090A0 +:105A8000D8F81030B34201D101F096FB89F31188A8 +:105A9000D5E9033128469847302383F311886B6991 +:105AA000002BD8D001F078FB6A69A0EB040982468C +:105AB0004A450DD2022001F0CDFB0022D8F810306B +:105AC000B34208D151462846BDE8F047FFF728BF4A +:105AD000121A2244F2E712EB09092946384638BF68 +:105AE0004A46FFF7EBFEB5E7D8F81030B34208D0CE +:105AF0001444C8F81C00211AA960BDE8F047FFF75C +:105B0000F3BEBDE8F08700BF905400208054002011 +:105B100038B501F041FB054AD2E90845031B1819C5 +:105B200045F10001C2E9080138BD00BF80540020E2 +:105B300000207047FEE70000704700004FF0FF3084 +:105B40007047000002290CD0032904D0012907481E +:105B500018BF00207047032A05D8054800EBC20093 +:105B60007047044870470020704700BF607D000800 +:105B70004C230020147D000870B59AB005460846F5 +:105B8000144601A900F0C2F801A8FBF703FF431C6B +:105B90000022C6B25B001046C5E90034237003231F +:105BA000023404F8013C01ABD1B202348E4201D878 +:105BB0001AB070BD13F8011B013204F8010C04F88F +:105BC000021CF1E708B5302383F311880348FFF77F +:105BD00029FA002383F3118808BD00BFF056002086 +:105BE00090F8803003F01F02012A07D190F881203D +:105BF0000B2A03D10023C0E91D3315E003F0600335 +:105C0000202B08D1B0F884302BB990F88120212ABC +:105C100003D81F2A04D8FFF7E7B9222AEBD0FAE706 +:105C2000034A426707228267C3670120704700BFAB +:105C30004323002007B5052917D8DFE801F019161E +:105C400003191920302383F31188104A0121019090 +:105C5000FFF790FA019802210D4AFFF78BFA0D48E1 +:105C6000FFF7ACF9002383F3118803B05DF804FB60 +:105C7000302383F311880748FFF776F9F2E73023E2 +:105C800083F311880348FFF78DF9EBE7B47C000834 +:105C9000D87C0008F056002038B50C4D0C4C2A4634 +:105CA0000C4904F10800FFF767FF05F1CA0204F18F +:105CB00010000949FFF760FF05F5CA7204F11800EA +:105CC0000649BDE83840FFF757BF00BFC86F002046 +:105CD0004C230020947C00089E7C0008A97C0008CE +:105CE00070B5044608460D46FBF754FEC6B2204682 +:105CF000013403780BB9184670BD32462946FBF7CC +:105D000035FE0028F3D10120F6E700002DE9F04729 +:105D100005460C46FBF73EFE2A49C6B22846FFF769 +:105D2000DFFF08B10936F6B227492846FFF7D8FF4A +:105D300008B11036F6B2632E0BD8DFF88880DFF892 +:105D40008890224FDFF890A02E7846B92670BDE8E3 +:105D5000F08729462046BDE8F04701F049BE252ED0 +:105D60002CD1072241462846FBF700FE60B9184BAC +:105D7000224603F1100153F8040B8B4242F8040B46 +:105D8000F9D107351034DFE7082249462846FBF7EA +:105D9000EDFD98B9A21C0F4B197802320909C95DB3 +:105DA00002F8041C13F8011B01F00F015345C95DF3 +:105DB00002F8031CF0D118340835C5E7013504F8A2 +:105DC000016BC1E7807D0008A97C0008887D000880 +:105DD0000E7A000800E8F11F0CE8F11FBFF34F8FA7 +:105DE000044B1A695107FCD1D3F810215207F8D19E +:105DF000704700BF0020005208B50D4B1B78ABB9AF +:105E0000FFF7ECFF0B4BDA68D10704D50A4A5A605A +:105E100002F188325A60D3F80C21D20706D5064A1F +:105E2000C3F8042102F18832C3F8042108BD00BF81 +:105E300026720020002000522301674508B5114B4F +:105E40001B78F3B9104B1A69510703D5DA6842F091 +:105E50004002DA60D3F81021520705D5D3F80C219F +:105E600042F04002C3F80C21FFF7B8FF064BDA6896 +:105E700042F00102DA60D3F80C2142F00102C3F8CB +:105E80000C2108BD26720020002000520F289ABF66 +:105E900000F5806040040020704700004FF400309F +:105EA00070470000102070470F2808B50BD8FFF787 +:105EB000EDFF00F500330268013204D10430834263 +:105EC000F9D1012008BD0020FCE700000F2838B5FB +:105ED00005463FD8FFF782FF1F4CFFF78DFF4FF0BD +:105EE000FF3307286361C4F814311DD82361FFF71D +:105EF00075FF030243F02403E360E36843F080038B +:105F0000E36023695A07FCD42846FFF767FFFFF7D1 +:105F1000BDFF4FF4003100F04BF92846FFF78EFF2C +:105F2000BDE83840FFF7C0BFC4F81031FFF756FF97 +:105F3000A0F108031B0243F02403C4F80C31D4F889 +:105F40000C3143F08003C4F80C31D4F810315B07F6 +:105F5000FBD4D9E7002038BD002000522DE9F84FCE +:105F600005460C46104645EA0203DE0602D0002034 +:105F7000BDE8F88F20F01F00DFF8BCB0DFF8BCA050 +:105F8000FFF73AFF04EB0008444503D10120FFF777 +:105F900055FFEDE720222946204601F0F7FC10B915 +:105FA00020352034F0E72B4605F120021F68791CCC +:105FB000DDD104339A42F9D105F178431B481C4ED8 +:105FC000B3F5801F1B4B38BF184603F1F80332BFEF +:105FD000D946D1461E46FFF701FF0760A5EB040C2A +:105FE000336804F11C0143F002033360231FD9F826 +:105FF000007017F00507FAD153F8042F8B424CF8C4 +:106000000320F4D1BFF34F8FFFF7E8FE4FF0FF33CB +:106010002022214603602846336823F002033360C0 +:1060200001F0B4FC0028BBD03846B0E71421005280 +:106030000C20005214200052102000521021005257 +:1060400010B5084C237828B11BB9FFF7D5FE012302 +:10605000237010BD002BFCD02070BDE81040FFF76E +:10606000EDBE00BF2672002038B5054D0024033474 +:10607000696855F80C0B00F0ADF8122CF7D138BD5B +:106080009C7D0008084601F079BC000038B5EFF3AC +:1060900011859DB9EFF30584C4F30804302334B1AE +:1060A00083F31188FFF734FD85F3118838BD83F33E +:1060B0001188FFF72DFD84F3118838BDBDE8384005 +:1060C000FFF726BD10B5FFF7E1FF104CC008104ADE +:1060D000002340EA4170C908A0FB04ECA0FB020EBB +:1060E0001CEB0000A1FB044CA1FB02125B41001958 +:1060F00043EB0C0011EB0E0142F10002411842F19A +:106100000000090941EA007010BD00BFCFF753E35A +:10611000A59BC4200244074BD2B210B5904200D1D7 +:1061200010BD441C00B253F8200041F8040BE0B24B +:10613000F4E700BF504000580E4B30B51C6F2404EC +:1061400005D41C6F1C671C6F44F400441C670A4C88 +:1061500002442368D2B243F480732360074B904219 +:1061600000D130BD441C51F8045B00B243F820500C +:10617000E0B2F4E70044025800480258504000588A +:1061800007B5012201A90020FFF7C4FF019803B061 +:106190005DF804FB13B50446FFF7F2FFA04205D0FB +:1061A000012201A900200194FFF7C6FF02B010BD33 +:1061B0000144BFF34F8F064B884204D3BFF34F8F88 +:1061C000BFF36F8F7047C3F85C022030F4E700BF65 +:1061D00000ED00E00144BFF34F8F064B884204D32B +:1061E000BFF34F8FBFF36F8F7047C3F8700220303B +:1061F000F4E700BF00ED00E070470000074B45F2F8 +:1062000055521A6002225A6040F6FF729A604CF6AC +:10621000CC421A600122024B1A70704700480058A5 +:106220002C720020034B1B781BB1034B4AF6AA22A9 +:106230001A6070472C72002000480058034B1A68FF +:106240001AB9034AD2F8D0241A6070472872002085 +:1062500000400258024B4FF48032C3F8D0247047FC +:106260000040025808B5FFF7E9FF024B1868C0F379 +:10627000806008BD2872002070B5BFF34F8FBFF358 +:106280006F8F1A4A0021C2F85012BFF34F8FBFF32D +:106290006F8F536943F400335361BFF34F8FBFF3E4 +:1062A0006F8FC2F88410BFF34F8FD2F8803043F65F +:1062B000E074C3F3C900C3F34E335B0103EA040681 +:1062C000014646EA81750139C2F86052F9D2203B95 +:1062D00013F1200FF2D1BFF34F8F536943F4803392 +:1062E0005361BFF34F8FBFF36F8F70BD00ED00E0C0 +:1062F000FEE70000214B2248224A70B5904237D376 +:10630000214BC11EDA1C121A22F003028B4238BF45 +:1063100000220021FBF746FB1C4A0023C2F8843010 +:10632000BFF34F8FD2F8803043F6E074C3F3C90057 +:10633000C3F34E335B0103EA0406014646EA817566 +:106340000139C2F86C52F9D2203B13F1200FF2D17F +:10635000BFF34F8FBFF36F8FBFF34F8FBFF36F8FBD +:106360000023C2F85032BFF34F8FBFF36F8F70BD61 +:1063700053F8041B40F8041BC0E700BF308000083E +:1063800000740020007400200074002000ED00E084 +:10639000054B996B21EA000199631A6E22EA00020B +:1063A0001A661B6E704700BF0045025870B5D0E9F1 +:1063B000244300224FF0FF359E6804EB4213510145 +:1063C000D3F80009002805DAD3F8000940F080402E +:1063D000C3F80009D3F8000B002805DAD3F8000B46 +:1063E00040F08040C3F8000B013263189642C3F8B6 +:1063F0000859C3F8085BE0D24FF00113C4F81C3809 +:1064000070BD0000890141F02001016103699B0614 +:10641000FCD41220FFF7D4B910B50A4C2046FEF781 +:1064200087FE094BC4F89030084BC4F89430084CF0 +:106430002046FEF77DFE074BC4F89030064BC4F8AB +:10644000943010BD3072002000000840087E000823 +:10645000CC72002000000440147E000870B5037860 +:106460000546012B58D13F4BD0F89040984254D16B +:106470003D4B0E2165209A6B42F000629A631A6EC2 +:1064800042F000621A661B6E384BD3F8802042F04F +:106490000062C3F88020D3F8802022F00062C3F8A5 +:1064A0008020D3F88030FEF7A9FA314BE360314BFE +:1064B000C4F800380023D5F89060C4F8003EC0232B +:1064C00023604FF40413A3633369002BFCDA012328 +:1064D0000C203361FFF774F93369DB07FCD4122019 +:1064E000FFF76EF93369002BFCDA00262846A66018 +:1064F000FFF75CFF6B68C4F81068DB68C4F81468C9 +:10650000C4F81C6863BB1C4BA3614FF0FF3363618D +:10651000A36843F00103A36070BD184B9842C9D132 +:10652000114B4FF080609A6B42F000729A631A6EC2 +:1065300042F000721A661B6E0C4BD3F8802042F0BA +:106540000072C3F88020D3F8802022F00072C3F8D4 +:106550008020D3F88030FFF71BFF0E214D20A2E7EB +:10656000074BD1E730720020004502580044025822 +:106570004014004003002002003C30C0CC720020D8 +:10658000083C30C0F8B5D0F89040054600214FF0E7 +:1065900000662046FFF736FFD5F8941000234FF031 +:1065A00001128F684FF0FF30C4F83438C4F81C284B +:1065B00004EB431201339F42C2F80069C2F8006B3A +:1065C000C2F80809C2F8080BF2D20B68D5F890207F +:1065D000C5F89830636210231361166916F010062F +:1065E000FBD11220FFF7ECF8D4F8003823F4FE6357 +:1065F000C4F80038A36943F4402343F01003A361B7 +:106600000923C4F81038C4F814380B4BEB604FF072 +:10661000C043C4F8103B094BC4F8003BC4F81069F0 +:10662000C4F80039D5F8983003F1100243F4801310 +:10663000C5F89820A362F8BDE47D000840800010F2 +:10664000D0F8902090F88A10D2F8003823F4FE6336 +:1066500043EA0113C2F80038704700002DE9F843FF +:1066600000EB8103D0F890500C468046DA680FFAB0 +:1066700081F94801166806F00306731E022B05EB2C +:1066800041134FF0000194BFB604384EC3F8101BFD +:106690004FF0010104F1100398BF06F1805601FA92 +:1066A00003F3916998BF06F5004600293AD0578A4E +:1066B00004F15801374349016F50D5F81C180B43BA +:1066C0000021C5F81C382B180127C3F81019A74062 +:1066D0005369611E9BB3138A928B9B08012A88BF62 +:1066E0005343D8F89820981842EA034301F1400236 +:1066F0002146C8F89800284605EB82025360FFF750 +:1067000081FE08EB8900C3681B8A43EA845348343E +:106710001E4364012E51D5F81C381F43C5F81C7860 +:10672000BDE8F88305EB4917D7F8001B21F40041B9 +:10673000C7F8001BD5F81C1821EA0303C0E704F1D1 +:106740003F030B4A2846214605EB83035A60FFF7B7 +:1067500059FE05EB4910D0F8003923F40043C0F886 +:106760000039D5F81C3823EA0707D7E70080001066 +:1067700000040002D0F894201268C0F89820FFF7B7 +:1067800015BE00005831D0F8903049015B5813F421 +:10679000004004D013F4001F0CBF022001207047FA +:1067A0004831D0F8903049015B5813F4004004D0D0 +:1067B00013F4001F0CBF02200120704700EB810181 +:1067C000CB68196A0B6813604B6853607047000010 +:1067D00000EB810330B5DD68AA691368D36019B98D +:1067E000402B84BF402313606B8A1468D0F890203C +:1067F0001C4402EB4110013C09B2B4FBF3F46343C7 +:10680000033323F0030343EAC44343F0C043C0F817 +:10681000103B2B6803F00303012B0ED1D2F808388C +:1068200002EB411013F4807FD0F8003B14BF43F01B +:10683000805343F00053C0F8003B02EB4112D2F802 +:10684000003B43F00443C2F8003B30BD2DE9F0416A +:10685000D0F8906005460C4606EB4113D3F8087B50 +:106860003A07C3F8087B08D5D6F814381B0704D5B7 +:1068700000EB8103DB685B689847FA071FD5D6F801 +:106880001438DB071BD505EB8403D968CCB98B69B9 +:10689000488A5A68B2FBF0F600FB16228AB91868DB +:1068A000DA6890420DD2121AC3E90024302383F330 +:1068B000118821462846FFF78BFF84F31188BDE835 +:1068C000F081012303FA04F26B8923EA02036B814E +:1068D000CB68002BF3D021462846BDE8F04118478D +:1068E00000EB81034A0170B5DD68D0F890306C6927 +:1068F0002668E66056BB1A444FF40020C2F810091F +:106900002A6802F00302012A0AB20ED1D3F808085D +:1069100003EB421410F4807FD4F8000914BF40F058 +:10692000805040F00050C4F8000903EB4212D2F846 +:10693000000940F00440C2F800090122D3F83408ED +:1069400002FA01F10143C3F8341870BD19B9402EA1 +:1069500084BF4020206020681A442E8A8419013C9C +:10696000B4FBF6F440EAC44040F00050C6E7000033 +:106970002DE9F843D0F8906005460C464F0106EB30 +:106980004113D3F8088918F0010FC3F808891CD007 +:10699000D6F81038DB0718D500EB8103D3F80CC00C +:1069A000DCF81430D3F800E0DA68964530D2A2EB78 +:1069B0000E024FF000091A60C3F80490302383F3ED +:1069C0001188FFF78DFF89F3118818F0800F1DD013 +:1069D000D6F834380126A640334217D005EB84039D +:1069E0000134D5F89050D3F80CC0E4B22F44DCF851 +:1069F000142005EB0434D2F800E05168714514D33B +:106A0000D5F8343823EA0606C5F83468BDE8F883BB +:106A1000012303FA01F2038923EA02030381DCF86C +:106A20000830002BD1D09847CFE7AEEB0103BCF87C +:106A30001000834228BF0346D7F8180980B2B3EB91 +:106A4000800FE3D89068A0F1040959F8048FC4F8C6 +:106A50000080A0EB09089844B8F1040FF5D8184459 +:106A60000B4490605360C8E72DE9F84FD0F8905080 +:106A700004466E69AB691E4016F480586E6103D0FF +:106A8000BDE8F84FFEF7C4BB002E12DAD5F8003E81 +:106A90009B0705D0D5F8003E23F00303C5F8003E60 +:106AA000D5F80438204623F00103C5F80438FEF772 +:106AB000DDFB370505D52046FFF778FC2046FEF7BD +:106AC000C3FBB0040CD5D5F8083813F0060FEB68FB +:106AD00023F470530CBF43F4105343F4A053EB6002 +:106AE00031071BD56368DB681BB9AB6923F008036A +:106AF000AB612378052B0CD1D5F8003E9A0705D061 +:106B0000D5F8003E23F00303C5F8003E2046FEF70B +:106B1000ADFB6368DB680BB120469847F30200F1D8 +:106B2000BA80B70226D5D4F8909000274FF0010A1A +:106B300009EB4712D2F8003B03F44023B3F5802F52 +:106B400011D1D2F8003B002B0DDA62890AFA07F363 +:106B500022EA0303638104EB8703DB68DB6813B17C +:106B60003946204698470137D4F89430FFB29B68E5 +:106B70009F42DDD9F00619D5D4F89000026AC2F31D +:106B80000A1702F00F0302F4F012B2F5802F00F0A2 +:106B9000CA80B2F5402F09D104EB8303002200F52F +:106BA0008050DB681B6A974240F0B0803003D5F814 +:106BB000185835D5E90303D500212046FFF746FED6 +:106BC000AA0303D501212046FFF740FE6B0303D53E +:106BD00002212046FFF73AFE2F0303D5032120466A +:106BE000FFF734FEE80203D504212046FFF72EFE0E +:106BF000A90203D505212046FFF728FE6A0203D526 +:106C000006212046FFF722FE2B0203D5072120464E +:106C1000FFF71CFEEF0103D508212046FFF716FE03 +:106C2000700340F1A780E90703D500212046FFF754 +:106C30009FFEAA0703D501212046FFF799FE6B07A7 +:106C400003D502212046FFF793FE2F0703D503212A +:106C50002046FFF78DFEEE0603D504212046FFF700 +:106C600087FEA80603D505212046FFF781FE6906A9 +:106C700003D506212046FFF77BFE2A0603D5072110 +:106C80002046FFF775FEEB0574D520460821BDE8C8 +:106C9000F84FFFF76DBED4F890904FF0000B4FF017 +:106CA000010AD4F894305FFA8BF79B689F423FF655 +:106CB00038AF09EB4713D3F8002902F44022B2F5AC +:106CC000802F20D1D3F80029002A1CDAD3F800291C +:106CD00042F09042C3F80029D3F80029002AFBDBD8 +:106CE0003946D4F89000FFF78DFB22890AFA07F3A2 +:106CF00022EA0303238104EB8703DB689B6813B15B +:106D00003946204698470BF1010BCAE7910701D19C +:106D1000D0F80080072A02F101029CBF03F8018B22 +:106D20004FEA18283FE704EB830300F58050DA6848 +:106D3000D2F818C0DCF80820DCE9001CA1EB0C0C30 +:106D400000218F4208D1DB689B699A683A449A60B7 +:106D50005A683A445A6029E711F0030F01D1D0F87C +:106D600000808C4501F1010184BF02F8018B4FEADC +:106D70001828E6E7BDE8F88F08B50348FFF774FE6A +:106D8000BDE80840FDF7E4BA3072002008B50348BA +:106D9000FFF76AFEBDE80840FDF7DABACC720020C2 +:106DA000D0F8903003EB4111D1F8003B43F40013CD +:106DB000C1F8003B70470000D0F8903003EB411160 +:106DC000D1F8003943F40013C1F8003970470000CE +:106DD000D0F8903003EB4111D1F8003B23F40013BD +:106DE000C1F8003B70470000D0F8903003EB411130 +:106DF000D1F8003923F40013C1F8003970470000BE +:106E000030B50433039C0172002104FB0325C160EB +:106E1000C0E90653049B0363059BC0E90000C0E979 +:106E20000422C0E90842C0E90A11436330BD0000F2 +:106E30000022416AC260C0E90411C0E90A226FF071 +:106E40000101FEF72DBD0000D0E90432934201D1CB +:106E5000C2680AB9181D704700207047036919609D +:106E60000021C2680132C260C26913448269934240 +:106E7000036124BF436A0361FEF706BD38B50446CB +:106E80000D46E3683BB162690020131D1268A362DE +:106E90001344E36207E0237A33B929462046FEF71C +:106EA000E3FC0028EDDA38BD6FF00100FBE70000DD +:106EB000C368C269013BC36043691344826993425A +:106EC000436124BF436A436100238362036B03B1C0 +:106ED0001847704770B53023044683F31188866ADB +:106EE0003EB9FFF7CBFF054618B186F31188284657 +:106EF00070BDA36AE26A13F8015B9342A36202D3F6 +:106F00002046FFF7D5FF002383F31188EFE7000049 +:106F10002DE9F84F04460E46174698464FF03009C3 +:106F200089F311880025AA46D4F828B0BBF1000FD8 +:106F300009D141462046FFF7A1FF20B18BF311880C +:106F40002846BDE8F88FD4E90A12A7EB050B521AC0 +:106F5000934528BF9346BBF1400F1BD9334601F13F +:106F6000400251F8040B914243F8040BF9D1A36A93 +:106F7000403640354033A362D4E90A239A4202D313 +:106F80002046FFF795FF8AF31188BD42D8D289F3D6 +:106F90001188C9E730465A46FAF7DEFCA36A5E4418 +:106FA0005D445B44A362E7E710B5029C04330172C1 +:106FB00003FB0421C460C0E906130023C0E90A33BF +:106FC000039B0363049BC0E90000C0E90422C0E9FD +:106FD0000842436310BD0000026A6FF00101C26005 +:106FE000426AC0E904220022C0E90A22FEF758BC26 +:106FF000D0E904239A4201D1C26822B9184650F858 +:10700000043B0B60704700231846FAE7C368002171 +:10701000C2690133C3604369134482699342436187 +:1070200024BF436A4361FEF72FBC000038B5044615 +:107030000D46E3683BB1236900201A1DA262E26994 +:107040001344E36207E0237A33B929462046FEF76A +:107050000BFC0028EDDA38BD6FF00100FBE7000003 +:1070600003691960C268013AC260C2691344826947 +:107070009342036124BF436A036100238362036B6D +:1070800003B118477047000070B530230D46044621 +:10709000114683F31188866A2EB9FFF7C7FF10B136 +:1070A00086F3118870BDA36A1D70A36AE26A01337A +:1070B0009342A36204D3E16920460439FFF7D0FF6D +:1070C000002080F31188EDE72DE9F84F04460D46C6 +:1070D000904699464FF0300A8AF311880026B3464D +:1070E000A76A4FB949462046FFF7A0FF20B187F3B2 +:1070F00011883046BDE8F88FD4E90A073A1AA8EBA0 +:107100000607974228BF1746402F1BD905F14003B9 +:1071100055F8042B9D4240F8042BF9D1A36A403660 +:107120004033A362D4E90A239A4204D3E16920469A +:107130000439FFF795FF8BF311884645D9D28AF3BE +:107140001188CDE729463A46FAF706FCA36A3D4482 +:107150003E443B44A362E5E7D0E904239A4217D1B9 +:10716000C3689BB1836A8BB1043B9B1A0ED013603A +:10717000C368013BC360C3691A4483699A420261D0 +:1071800024BF436A036100238362012318467047CA +:107190000023FBE700F01CB9014B586A704700BFA1 +:1071A000000C0040034B002258631A610222DA608F +:1071B000704700BF000C0040014B0022DA607047AE +:1071C000000C0040014B5863704700BF000C0040AA +:1071D000FEE7000070B51B4B0025044686B05860E2 +:1071E0000E4685620163FDF78BF804F11003A5607C +:1071F000E562C4E904334FF0FF33C4E90044C4E955 +:107200000635FFF7C9FF2B46024604F1340120463C +:10721000C4E9082380230C4A2565FEF7DBFA012325 +:107220000A4AE06000920375684672680192B2688B +:10723000CDE90223064BCDE90435FEF7F3FA06B09B +:1072400070BD00BFE8560020207E0008257E0008A3 +:10725000D1710008024AD36A1843D062704700BF58 +:10726000805400204B6843608B688360CB68C360A8 +:107270000B6943614B6903628B6943620B6803606E +:107280007047000008B53A4B40F2FF713948D3F817 +:1072900088200A43C3F88820D3F8882022F4FF62AC +:1072A00022F00702C3F88820D3F88830324B1A6CDA +:1072B0000A431A649A6E0A439A66304A9B6E1146D4 +:1072C000FFF7D0FF00F5806002F11C01FFF7CAFF55 +:1072D00000F5806002F13801FFF7C4FF00F580601F +:1072E00002F15401FFF7BEFF00F5806002F170016A +:1072F000FFF7B8FF00F5806002F18C01FFF7B2FFE5 +:1073000000F5806002F1A801FFF7ACFF00F5806096 +:1073100002F1C401FFF7A6FF00F5806002F1E00171 +:10732000FFF7A0FF00F5806002F1FC01FFF79AFF74 +:1073300002F58C7100F58060FFF794FF00F00AF908 +:107340000F4BD3F8902242F00102C3F89022D3F8F9 +:10735000942242F00102C3F894220522C3F8982037 +:107360004FF06052C3F89C20064AC3F8A02008BD25 +:107370000044025800000258004502582C7E0008C4 +:1073800000ED00E01F00080308B500F0C1FAFEF7A9 +:10739000EFF90C4BDA6B42F04002DA635A6E22F0DE +:1073A00040025A665B6E084B1A6842F008021A6087 +:1073B0001A6842F004021A60FEF740FFBDE8084078 +:1073C000FEF76ABC004502580018024870470000EA +:1073D0000E4B9A6C42F008029A641A6F42F008024F +:1073E0001A670B4A1B6FD36B43F00803D363C722A2 +:1073F000084B9A624FF0FF32DA6200229A615A63B8 +:10740000DA605A6001225A611A60704700450258DA +:107410000010005C000C0040094A08B51169D368EF +:107420000B40D9B29B076FEA0101116107D53023E8 +:1074300083F31188FEF7C2F9002383F3118808BD96 +:10744000000C0040044BDA6B0243DA635A6E1043BF +:1074500058665B6E704700BF0045025808B53C4B4C +:107460004FF0FF31D3F8802062F00042C3F8802053 +:10747000D3F8802002F00042C3F88020D3F88020A7 +:10748000D3F88420C3F88410D3F884200022C3F8F2 +:107490008420D3F88400D86F40F0FF4040F4FF0010 +:1074A00040F4DF4040F07F00D867D86F20F0FF4005 +:1074B00020F4FF0020F4DF4020F07F00D867D86F71 +:1074C000D3F888006FEA40506FEA5050C3F8880044 +:1074D000D3F88800C0F30A00C3F88800D3F8880006 +:1074E000D3F89000C3F89010D3F89000C3F8902020 +:1074F000D3F89000D3F89400C3F89410D3F8940014 +:10750000C3F89420D3F89400D3F89800C3F89810E7 +:10751000D3F89800C3F89820D3F89800D3F88C00DB +:10752000C3F88C10D3F88C00C3F88C20D3F88C00EF +:10753000D3F89C00C3F89C10D3F89C10C3F89C208F +:10754000D3F89C30FDF786F8BDE8084000F0B4B9E8 +:107550000044025808B50122504BC3F80821504B93 +:107560005A6D42F002025A65DA6F42F00202DA679F +:107570000422DB6F4B4BDA605A689104FCD54A4A0F +:107580001A6001229A60494ADA6000221A614FF4B7 +:1075900040429A61434B9A699204FCD51A6842F4BE +:1075A00080721A60424B1A6F12F4407F04D04FF47D +:1075B00080321A6700221A671A6842F001021A60C4 +:1075C0003B4B1A685007FCD500221A611A6912F069 +:1075D0003802FBD1012119604FF0804159605A6790 +:1075E000344ADA62344A1A611A6842F480321A6004 +:1075F0002F4B1A689103FCD51A6842F480521A6026 +:107600001A689204FCD52D4A2D499A6200225A63C9 +:10761000196301F57C01DA6301F5E77199635A6436 +:10762000284A1A64284ADA621A6842F0A8521A6094 +:107630001F4B1A6802F02852B2F1285FF9D1482294 +:107640009A614FF48862DA6140221A621F4ADA6452 +:107650001F4A1A651F4A5A651F4A9A6532231F4AF4 +:107660001360136803F00F03022BFAD1104A136959 +:1076700043F003031361136903F03803182BFAD1A5 +:107680004FF00050FFF7DEFE4FF08040FFF7DAFECC +:107690004FF00040BDE80840FFF7D4BE0080005125 +:1076A000004502580048025800C000F004000001E4 +:1076B000004402580000FF0100889008322060005A +:1076C00063020901470E0508DD0BBF012000002001 +:1076D000000001100910E00000010110002000521C +:1076E0004FF0B04208B5D2F8883003F00103C2F879 +:1076F000883023B1044A13680BB150689847BDE83D +:107700000840FCF725BE00BF807300204FF0B04258 +:1077100008B5D2F8883003F00203C2F8883023B1EC +:10772000044A93680BB1D0689847BDE80840FCF75D +:107730000FBE00BF807300204FF0B04208B5D2F8F2 +:10774000883003F00403C2F8883023B1044A136977 +:107750000BB150699847BDE80840FCF7F9BD00BF80 +:10776000807300204FF0B04208B5D2F8883003F0A3 +:107770000803C2F8883023B1044A93690BB1D06979 +:107780009847BDE80840FCF7E3BD00BF80730020C8 +:107790004FF0B04208B5D2F8883003F01003C2F8B9 +:1077A000883023B1044A136A0BB1506A9847BDE888 +:1077B0000840FCF7CDBD00BF807300204FF0B04300 +:1077C00010B5D3F8884004F47872C3F88820A30673 +:1077D00004D5124A936A0BB1D06A9847600604D563 +:1077E0000E4A136B0BB1506B9847210604D50B4A18 +:1077F000936B0BB1D06B9847E20504D5074A136C25 +:107800000BB1506C9847A30504D5044A936C0BB197 +:10781000D06C9847BDE81040FCF79ABD80730020FB +:107820004FF0B04310B5D3F8884004F47C42C3F85D +:107830008820620504D5164A136D0BB1506D984728 +:10784000230504D5124A936D0BB1D06D9847E0041F +:1078500004D50F4A136E0BB1506E9847A10404D59E +:107860000B4A936E0BB1D06E9847620404D5084A58 +:10787000136F0BB1506F9847230404D5044A936FDC +:107880000BB1D06F9847BDE81040FCF761BD00BF59 +:107890008073002008B50348FDF72AF8BDE80840CA +:1078A000FCF756BD1450002008B5FFF7B5FDBDE844 +:1078B0000840FCF74DBD0000062108B50846FDF75D +:1078C0009DF806210720FDF799F806210820FDF70D +:1078D00095F806210920FDF791F806210A20FDF709 +:1078E0008DF806211720FDF789F806212820FDF7DD +:1078F00085F809217A20FDF781F807213220FDF76C +:107900007DF80C215220BDE80840FDF777B8000053 +:1079100008B5FFF7A3FD00F00DF8FDF72DFAFDF710 +:1079200005FCFDF7D7FAFFF751FDBDE80840FFF76A +:1079300031BC00000023054A19460133102BC2E96F +:10794000001102F10802F8D1704700BF80730020D7 +:107950000B460146184600F003B8000000F00EB8D0 +:1079600010B5054C13462CB10A4601460220AFF370 +:10797000008010BD2046FCE700000000024B0146DD +:107980001868FEF77FBB00BF6C23002010B50139DB +:107990000244904201D1002005E0037811F8014F24 +:1079A000A34201D0181B10BD0130F2E72DE9F041D0 +:1079B000A3B1C91A17780144044603F1FF3C8C4275 +:1079C000204601D9002009E00578BD4204F10104F8 +:1079D000F5D10CEB0405D618A54201D1BDE8F08124 +:1079E00015F8018D16F801EDF045F5D0E7E7000038 +:1079F000034611F8012B03F8012B002AF9D1704737 +:107A00006F72672E6172647570696C6F742E437546 +:107A1000626550696C6F742D43414E4D6F64000078 +:107A200053544D333248373F3F3F0053544D333268 +:107A3000483733782F3732780053544D3332483734 +:107A400034332F3735332F373530000001105A00CB +:107A500003105900012058000320560040A2E4F111 +:107A6000646891060041A3E5F26569920700000091 +:107A700043414E464449666163653A204D657373E0 +:107A80006167652052414D204F766572666C6F7755 +:107A9000210000004261642043414E4966616365F4 +:107AA00020696E6465782E00000000000000000070 +:107AB000912A00081D230008DD3100088D230008ED +:107AC00099230008B1270008112500085523000854 +:107AD0005923000831230008192300086D270008E6 +:107AE0003D230008153300084923000841270008FA +:107AF00001040E05054B02020E05054B04010E059F +:107B0000054B05010B04044B080106030346000066 +:107B100010000240080002400008024000000B0074 +:107B200028000240080002400408024006010C0040 +:107B300040000240080002400808024010020D0008 +:107B400058000240080002400C08024016030E00D4 +:107B5000700002400C0002401008024000040F00B8 +:107B6000880002400C000240140802400605100084 +:107B7000A00002400C00024018080240100611004C +:107B8000B80002400C0002401C08024016072F00FB +:107B90001004024008040240200802400008380097 +:107BA0002804024008040240240802400609390063 +:107BB000400402400804024028080240100A3A002B +:107BC00058040240080402402C080240160B3B00F7 +:107BD000700402400C04024030080240000C3C00DB +:107BE000880402400C04024034080240060D4400A0 +:107BF000A00402400C04024038080240100E450068 +:107C0000B80402400C0402403C080240160F460033 +:107C100000960000000000000000000000000000CE +:107C2000000000000000000000000000394D0008C6 +:107C3000254D0008614D00084D4D0008594D0008C4 +:107C4000454D0008314D00081D4D00086D4D0008E0 +:107C500000000000514E00083D4E0008794E00081B +:107C6000654E0008714E00085D4E0008494E000840 +:107C7000354E0008854E000800000000010000009D +:107C80000000000063300000847C0008D85400200D +:107C9000E85600204172647550696C6F740025428B +:107CA0004F415244252D424C002553455249414CE9 +:107CB00025000000020000000000000071500008D4 +:107CC000E150000840004000986F0020A86F00209D +:107CD000020000000000000003000000000000009F +:107CE000295100080000000010000000B86F0020BB +:107CF00000000000010000000000000030720020C1 +:107D000001010200355C0008455B0008E15B0008EA +:107D1000C55B0008430000001C7D00080902430009 +:107D2000020100C032090400000102020100052422 +:107D300000100105240100010424020205240600AC +:107D400001070582030800FF09040100020A000080 +:107D50000007050102400000070581024000000005 +:107D600012000000687D00081201100102000040AE +:107D70000912415700020102030100000403090433 +:107D800025424F41524425003031323334353637A5 +:107D900038394142434445460000000000010020BC +:107DA00000FF01000200000000000030000004009D +:107DB000080000000000002400000800040000008B +:107DC0000004000000FC000002000000000004307D +:107DD00000800000080000000000003800000100E2 +:107DE0000100000000000000855200083D55000819 +:107DF000E9550008400040006873002068730020C7 +:107E000001000000787300208000000040010000A5 +:107E10000800000000010000001000000800000041 +:107E20006D61696E0069646C650000000000802A65 +:107E300000000000AAAAAAAA00000024FFFF000078 +:107E40000000000000A00A00000000000000000088 +:107E5000AAAAAAAA00000000FFFF0000000000007C +:107E6000000000000000000000000000AAAAAAAA6A +:107E700000000000FFFF0000000000000000000004 +:107E80000A00000000000000AAAAAAAA0000000040 +:107E9000FFFF0000990000000000000000800200C9 +:107EA00000000000AAAAAAAA00400100FFFF0000EB +:107EB000000000700700000000000000000000004B +:107EC000AAAAAAAA00000000FFFF0000000000000C +:107ED000000000000500000000000000A5AAAAAAFA +:107EE00000000000FCFF0000000000000000000097 +:107EF0000000000000000000AAAAAAAA00000000DA +:107F0000FFFF000000000000000000000000000073 +:107F100000000000AAAAAAAA00000000FFFF0000BB +:107F20000000000000000000000000000000000051 +:107F3000AAAAAAAA00000000FFFF0000000000009B +:107F4000000000000000000000000000AAAAAAAA89 +:107F500000000000FFFF0000000000000000000023 +:107F600037040000000000000000180000000000BE +:107F7000FE2A0100D2040000FF000000F05600209D +:107F80001450002000000000207A00088304000044 +:107F90002B7A000850040000397A0008009600008F +:107FA0000000080096000000000800000400000027 +:107FB0007C7D0008000000000000000000000000C0 +:107FC00000000000000000000000000070230020FE +:107FD00000000000000000000000000000000000A1 +:107FE0000000000000000000000000000000000091 +:107FF0000000000000000000000000000000000081 +:108000000000000000000000000000000000000070 +:108010000000000000000000000000000000000060 +:108020000000000000000000000000000000000050 :00000001FF diff --git a/Tools/bootloaders/CubePilot-PPPGW_bl.bin b/Tools/bootloaders/CubePilot-PPPGW_bl.bin index 024aaaa4e7f857..517887441d56d2 100755 Binary files a/Tools/bootloaders/CubePilot-PPPGW_bl.bin and b/Tools/bootloaders/CubePilot-PPPGW_bl.bin differ diff --git a/Tools/bootloaders/CubeRedPrimary-PPPGW_bl.bin b/Tools/bootloaders/CubeRedPrimary-PPPGW_bl.bin index 981377a7456dc5..60d444d05398d0 100755 Binary files a/Tools/bootloaders/CubeRedPrimary-PPPGW_bl.bin and b/Tools/bootloaders/CubeRedPrimary-PPPGW_bl.bin differ diff --git a/Tools/bootloaders/FreeflyRTK_bl.bin b/Tools/bootloaders/FreeflyRTK_bl.bin index 08144e90fa3ee6..1175d29c49119f 100755 Binary files a/Tools/bootloaders/FreeflyRTK_bl.bin and b/Tools/bootloaders/FreeflyRTK_bl.bin differ diff --git a/Tools/bootloaders/FreeflyRTK_bl.elf b/Tools/bootloaders/FreeflyRTK_bl.elf index 64ba9bdb6458b6..02128459b32225 100755 Binary files a/Tools/bootloaders/FreeflyRTK_bl.elf and b/Tools/bootloaders/FreeflyRTK_bl.elf differ diff --git a/Tools/bootloaders/FreeflyRTK_bl.hex b/Tools/bootloaders/FreeflyRTK_bl.hex index f96d350ee15827..28cf89bbcb4601 100644 --- a/Tools/bootloaders/FreeflyRTK_bl.hex +++ b/Tools/bootloaders/FreeflyRTK_bl.hex @@ -1,1772 +1,1723 @@ :020000040800F2 -:1000000000070020150500088D2F0008452F000867 -:100010006D2F0008452F0008652F00081705000800 -:10002000170500081705000817050008813F00089C -:100030001705000817050008170500081705000830 -:100040001705000817050008170500081705000820 -:10005000170500081705000895660008BD6600082A -:10006000E56600080D6700083567000817050008F9 -:1000700017050008170500081705000817050008F0 -:10008000170500081705000817050008F92E0008D5 -:10009000252F0008352F0008170500085D670008A8 -:1000A00017050008170500081705000817050008C0 -:1000B0003168000817050008170500081705000833 -:1000C00017050008170500081705000817050008A0 -:1000D0001705000817050008170500081705000890 -:1000E000C167000817050008170500081705000874 -:1000F0001705000817050008170500081705000870 -:10010000170500081705000817050008170500085F -:10011000170500081705000817050008170500084F -:10012000170500081705000817050008170500083F -:10013000170500081705000817050008170500082F -:10014000170500081705000817050008715C00086E -:10015000170500081705000817050008170500080F -:1001600017050008170500081705000817050008FF -:1001700017050008170500081705000817050008EF -:1001800017050008170500081705000817050008DF -:1001900017050008170500081705000817050008CF -:1001A00017050008170500081705000817050008BF -:1001B00017050008170500081705000817050008AF -:1001C000170500081705000817050008170500089F -:1001D000170500081705000817050008170500088F -:1001E000170500081705000817050008170500087F -:1001F000170500081705000817050008170500086F -:10020000311900080000000000000000000000009C -:1002100053B94AB9002908BF00281CBF4FF0FF316D -:100220004FF0FF3000F074B9ADF1080C6DE904CE69 -:1002300000F006F8DDF804E0DDE9022304B07047C1 -:100240002DE9F047089D04468E46002B4DD18A4289 -:10025000944669D9B2FA82F252B101FA02F3C2F1BC -:10026000200120FA01F10CFA02FC41EA030E94404D -:100270004FEA1C48210CBEFBF8F61FFA8CF708FB6E -:1002800016E341EA034306FB07F199420AD91CEB46 -:10029000030306F1FF3080F01F81994240F21C8178 -:1002A000023E63445B1AA4B2B3FBF8F008FB1033C0 -:1002B00044EA034400FB07F7A7420AD91CEB0404F5 -:1002C00000F1FF3380F00A81A74240F207816444C5 -:1002D000023840EA0640E41B00261DB1D44000234A -:1002E000C5E900433146BDE8F0878B4209D9002DAE -:1002F00000F0EF800026C5E9000130463146BDE838 -:10030000F087B3FA83F6002E4AD18B4202D38242A1 -:1003100000F2F980841A61EB030301209E46002D50 -:10032000E0D0C5E9004EDDE702B9FFDEB2FA82F2A5 -:10033000002A40F09280A1EB0C014FEA1C471FFA03 -:100340008CFE0126200CB1FBF7F307FB131140EAEA -:1003500001410EFB03F0884208D91CEB010103F1B7 -:10036000FF3802D2884200F2CB804346091AA4B279 -:10037000B1FBF7F007FB101144EA01440EFB00FE4D -:10038000A64508D91CEB040400F1FF3102D2A645B2 -:1003900000F2BB800846A4EB0E0440EA03409CE751 -:1003A000C6F12007B34022FA07FC4CEA030C20FAFE -:1003B00007F401FA06F31C43F9404FEA1C4900FA1E -:1003C00006F3B1FBF9F8200C1FFA8CFE09FB18119B -:1003D00040EA014108FB0EF0884202FA06F20BD90E -:1003E0001CEB010108F1FF3A80F08880884240F25E -:1003F0008580A8F102086144091AA4B2B1FBF9F0A2 -:1004000009FB101144EA014100FB0EFE8E4508D99C -:100410001CEB010100F1FF346CD28E456AD9023821 -:10042000614440EA0840A0FB0294A1EB0E01A14206 -:10043000C846A64656D353D05DB1B3EB080261EB74 -:100440000E0101FA07F722FA06F3F1401F43C5E94E -:10045000007100263146BDE8F087C2F12003D84084 -:100460000CFA02FC21FA03F3914001434FEA1C47C6 -:100470001FFA8CFEB3FBF7F007FB10360B0C43EAB8 -:10048000064300FB0EF69E4204FA02F408D91CEB68 -:10049000030300F1FF382FD29E422DD90238634466 -:1004A0009B1B89B2B3FBF7F607FB163341EA034106 -:1004B00006FB0EF38B4208D91CEB010106F1FF3855 -:1004C00016D28B4214D9023E6144C91A46EA00464C -:1004D00038E72E46284605E70646E3E61846F8E6DE -:1004E0004B45A9D2B9EB020864EB0C0E0138A3E727 -:1004F0004646EAE7204694E74046D1E7D0467BE708 -:10050000023B614432E7304609E76444023842E77F -:10051000704700BF02E000F000F8FEE772B637480F -:1005200080F30888364880F30988364836490860E1 -:1005300040F20000CCF200004EF63471CEF2000121 -:100540000860BFF34F8FBFF36F8F40F20000C0F21F -:10055000F0004EF68851CEF200010860BFF34F8FD5 -:10056000BFF36F8F4FF00000E1EE100A4EF63C71C2 -:10057000CEF200010860062080F31488BFF36F8F6D -:1005800004F0D4FF05F036FF4FF055301F491B4AE9 -:1005900091423CBF41F8040BFAE71D49184A9142C9 -:1005A0003CBF41F8040BFAE71A491B4A1B4B9A421D -:1005B0003EBF51F8040B42F8040BF8E7002018493D -:1005C000184A91423CBF41F8040BFAE704F0ECFFF3 -:1005D00005F064FF144C154DAC4203DA54F8041BCB -:1005E0008847F9E700F042F8114C124DAC4203DAAB -:1005F00054F8041B8847F9E704F0D4BF0007002033 -:10060000002300200000000808ED00E000010020A9 -:1006100000070020D06D000800230020CC2300201C -:10062000D0230020705600200002000804020008B9 -:1006300004020008040200082DE9F04F2DED108A95 -:10064000C1F80CD0D0F80CD0BDEC108ABDE8F08F0A -:10065000002383F311882846A047002004F054FAB1 -:10066000FEE704F0ADF900DFFEE70000F8B501F0A9 -:1006700071F904F0D5FE074604F044FF0546002852 -:100680003BD1244B9F4238D001339F4238D0224B7C -:1006900027F0FF029A4236D1F8B200F067FF2E46EB -:1006A00042F2107400F068FF08B10024264601F001 -:1006B00059FD20B1032000F085F80024264635B10D -:1006C000164B9F4203D004F015FF0024264600205D -:1006D00004F0B0FE124B1B695B0418D40EB100F09D -:1006E00087F801F0EFFA00F0B3FF01F099F9204626 -:1006F00000F014F900F07CF8F9E72E460024D1E769 -:1007000004460126CEE706464FF47A74CAE7002471 -:10071000E7E700BF010007B0000008B0263A09B0C3 -:100720000008024008B501F04DF9A0F1200358423D -:10073000584108BD07B541F21203022101A8ADF8E6 -:10074000043001F05DF903B05DF804FB38B53023E7 -:1007500083F31188174803680BB104F0A1FA164A15 -:10076000144800234FF47A7104F090FA002383F3C5 -:100770001188124C236813B12368013B236063681E -:1007800013B16368013B63600D4D2B7833B9636827 -:100790007BB9022001F010FA322363602B78032B1F -:1007A00007D163682BB9022001F006FA4FF47A737F -:1007B000636038BDD02300204D070008F0240020DE -:1007C000E8230020084B187003280CD8DFE800F05D -:1007D00008050208022001F0E7B9022001F0DAB9A9 -:1007E000024B00225A607047E8230020F0240020CA -:1007F000F8B501F0B7FC30B1404B03221A70404B02 -:1008000000225A60F8BD3F4B3F4A1C46196801312F -:10081000F8D004339342F9D162683C4B9A42F1D943 -:100820003B4B9B6803F1006303F580339A42E9D2A6 -:1008300004F034FE04F046FE002001F00BF9022023 -:10084000FFF7C0FF334B00211A6C19641A6E19664A -:100850001A6E5A6C59645A6E59665A6E1A6942F089 -:1008600000521A611A6922F000521A611B6972B6AD -:100870004FF0E023C3F8084DD4E90004BFF34F8FD5 -:10088000BFF36F8F244AC2F88410BFF34F8F5369B0 -:1008900023F480335361BFF34F8FD2F88030C3F31A -:1008A000C905C3F34E335B0143F6E07603EA060C59 -:1008B00029464CEA81770139C2F87472F9D2203B9B -:1008C00013F1200FF2D1BFF34F8FBFF36F8FBFF340 -:1008D0004F8FBFF36F8F536923F4003353610023AD -:1008E000C2F85032BFF34F8FBFF36F8F302383F3C3 -:1008F0001188854680F30888204783E7E823002095 -:10090000F02400200000010820000108FFFF00087B -:10091000002300200038024000ED00E02DE9F04FF8 -:1009200093B0B74B00902022FF210AA89D6801F0E8 -:1009300073F9B44A1378A3B9B34801210360117065 -:10094000302383F3118803680BB104F0A9F9AF4A8F -:10095000AD4800234FF47A7104F098F9002383F333 -:100960001188009B13B1AA4B009A1A60A94A009CF7 -:100970001378032B1EBF00231370A54A4FF0000A03 -:1009800018BF5360D3465646D146012001F00CF9FA -:1009900024B19F4B1B68002B00F02B82002001F03C -:1009A00011F80390039B002B01DA00F099FE039BE2 -:1009B000002BEDDB012001F0EDF8039B213B1F2B09 -:1009C000E3D801A252F823F0490A0008710A00088E -:1009D000050B00088B0900088B0900088B0900082B -:1009E000970B0008670D0008810C0008E30C000855 -:1009F0000B0D0008310D00088B090008430D00089D -:100A00008B090008B50D0008E90A00088B090008E9 -:100A1000F90D0008550A0008E90A00088B090008CA -:100A2000E30C00088B0900088B0900088B090008FB -:100A30008B0900088B0900088B0900088B09000846 -:100A40008B090008050B00080220FFF76BFE002849 -:100A500040F0F981009B0221BAF1000F08BF1C464B -:100A600005A841F21233ADF8143000F0C9FF8CE74D -:100A70004FF47A7000F0A6FF071EEBDB0220FFF7B1 -:100A800051FE0028E6D0013F052F00F2DE81DFE8AD -:100A900007F0030A0D10133605230593042105A85A -:100AA00000F0AEFF17E056480421F9E75A48042148 -:100AB000F6E75A480421F3E74FF01C08404600F0DF -:100AC000CBFF08F104080590042105A800F098FF69 -:100AD000B8F12C0FF2D1012000FA07F747EA0B0B0F -:100AE0005FFA8BFB4FF0000901F0E2F826B10BF042 -:100AF0000B030B2B08BF0024FFF71CFE45E74848FB -:100B00000421CDE7002EA5D00BF00B030B2BA1D1B8 -:100B10000220FFF707FE074600289BD0012000F0C7 -:100B200099FF0220FFF74EFE00261FFA86F8404686 -:100B300000F0A0FF0446B0B10399A1F14002514278 -:100B40005141404600F0AEFF01360028EDD1BA46D3 -:100B5000044641F21213022105A8ADF814303E46B6 -:100B600000F04EFF11E70120FFF72CFE2546244B35 -:100B70009B68AB4207D9284600F06EFF013040F079 -:100B800067810435F3E7234B00251D70204BBA46DF -:100B90005D603E46A8E7002E3FF45CAF0BF00B0310 -:100BA0000B2B7FF457AF0220FFF70CFE322000F032 -:100BB00009FFB0F10008FFF64DAF18F003077FF40E -:100BC00049AF0F4A926808EB050393423FF642AFE4 -:100BD000B8F5807F3FF73EAF124B0193B84523DD58 -:100BE0004FF47A7000F0EEFE0390039A002AFFF6AD -:100BF00031AF019B039A03F8012B0137EDE700BFEA -:100C000000230020EC240020D02300204D07000802 -:100C1000F0240020E82300200423002008230020E3 -:100C20000C230020EC230020C820FFF77BFD0746A3 -:100C300000283FF40FAF1F2D11D8C5F12002424507 -:100C40000AAB25F0030028BF4246834901921844AD -:100C500000F0BCFF019A8048FF2100F0DDFF4FEA61 -:100C6000A8037D490193C8F38702284600F0DCFF02 -:100C7000064600283FF46DAF019B05EB830533E783 -:100C80000220FFF74FFD00283FF4E4AE00F02AFFFA -:100C900000283FF4DFAE0027B846704B9B68BB428C -:100CA00018D91F2F11D80A9B01330ED027F0030348 -:100CB00012AA134453F8203C05934046042205A988 -:100CC00001F008FA04378046E7E7384600F0C4FE32 -:100CD0000590F2E7CDF81480042105A800F090FEFD -:100CE00002E70023642104A8049300F07FFE00289B -:100CF0007FF4B0AE0220FFF715FD00283FF4AAAE46 -:100D0000049800F0D7FE0590E6E70023642104A8CC -:100D1000049300F06BFE00287FF49CAE0220FFF7E6 -:100D200001FD00283FF496AE049800F0D3FEEAE7F8 -:100D30000220FFF7F7FC00283FF48CAE00F0E2FE43 -:100D4000E1E70220FFF7EEFC00283FF483AE05A99F -:100D5000142000F0DDFE04210746049004A800F0F2 -:100D60004FFE3946B9E7322000F02CFE071EFFF691 -:100D700071AEBB077FF46EAE384A926807EB090389 -:100D800093423FF667AE0220FFF7CCFC00283FF409 -:100D900061AE27F003074F44B9453FF4A5AE48467E -:100DA00000F05AFE0421059005A800F029FE09F183 -:100DB0000409F1E74FF47A70FFF7B4FC00283FF420 -:100DC00049AE00F08FFE002844D00A9B01330BD0BF -:100DD00008220AA9002000F027FF00283AD020228C -:100DE000FF210AA800F018FFFFF7A4FC1C4803F03D -:100DF00091FE13B0BDE8F08F002E3FF42BAE0BF048 -:100E00000B030B2B7FF426AE0023642105A805936A -:100E100000F0ECFD074600287FF41CAE0220FFF72F -:100E200081FC804600283FF415AEFFF783FC41F2B9 -:100E3000883003F06FFE059800F06CFF464600F026 -:100E400037FF3C46A1E506464EE64FF0000901E6B5 -:100E5000BA467EE637467CE6EC23002000230020DD -:100E6000A0860100094A136849F2690099B21B0C77 -:100E700000FB01331360064B186844F2506182B2E4 -:100E8000000C01FB0200186080B27047182300209C -:100E90001423002010B500211022044600F0BCFEEF -:100EA000034B03CB206061601868A06010BD00BFD9 -:100EB000107AF01F2DE9F041ADF54E7D0DF13408AB -:100EC0006CAC40F2751207460D460EA80021C8F81A -:100ED000001000F0A1FE4FF4C4720021204600F083 -:100EE0009BFE02F05BF8254B4FF47A72B0FBF2F0F8 -:100EF000186093E80700022384E807000DF5E97005 -:100F00002382FFF7C7FF40F204431D49238406A84C -:100F100005F09EFD182384F832310DF2E3266B4470 -:100F20000DF1300C1A4603CA6245306071601346F9 -:100F300006F10806F6D141460122204600F0ECFEFB -:100F400000230393AB7E029305F11903019380B252 -:100F50000123CDE904800093E97E06A3D3E90023B1 -:100F6000384602F0E3FB0DF54E7DBDE8F08100BF91 -:100F7000AFF300809E6AC421818A46EEF8240020E7 -:100F8000606A00082DE9F0412C4C237ADAB08046E3 -:100F90000D465BBB27A9284600F0CEFF0746002878 -:100FA00042D19DF89D60C82E3ED801464FF4A662FE -:100FB000204600F031FE4FF48073C4F8F8314FF44E -:100FC0000073C4F80C334FF44073C4F82034324635 -:100FD0000DF19E0104F1090000F0F8FD26449DF892 -:100FE0009C30777223720BB9EB7E23728122002131 -:100FF00006AC27A800F010FE0122214627A800F029 -:10100000D7FF00230393AB7E029305F1190380B24F -:1010100001932823CDE904400093E97E05A3D3E999 -:101020000023404602F082FB5AB0BDE8F08100BFC9 -:10103000AFF3008026417272DF25D7B7104600203B -:10104000F0B5254E4FF48A7505FB0065F1B096F8B2 -:10105000D83085F8DC300024D822214685F8E840D5 -:101060003AA800F0D9FD06F1090000F0CDFDD5F851 -:10107000E4308DF8F000C2B206AF06F109010DF1BF -:10108000F100CDE93A3400F0A1FD394601223AA839 -:1010900000F0BAFF80B2CDE9047008230127CDE942 -:1010A000023706F1D803019330230093317A0B48BD -:1010B00007A3D3E9002302F039FBA04206DD01F0CB -:1010C0006DFFC5F8E000384671B0F0BD2046FBE783 -:1010D00078F6339F93CACD8D10460020103500203E -:1010E0002DE9F0411D4D1E4E1E4F86B0284602F0E0 -:1010F00049FB034658B30024CDE90344ADF814403E -:10110000027B8DF8142099684068029403AA03C2F8 -:101110001B68DFF8548043F00043029301F040FF66 -:10112000821941F10003009402A9384601F004FA43 -:10113000A04205DD284602F029FB88F80040D5E7EB -:1011400098F80030072B05D8013388F8003006B036 -:10115000BDE8F081014802F019FBF8E710350020E6 -:1011600040420F0040350020454B002070B50D4631 -:1011700014461E4602F036FA50B9022E10D1012C48 -:101180000ED112A3D3E90023C5E90023012007E013 -:10119000282C10D005D8012C09D0052C0FD0002008 -:1011A00070BD302CFBD10BA3D3E90023ECE70BA3DC -:1011B000D3E90023E8E70BA3D3E90023E4E70BA37B -:1011C000D3E90023E0E700BFAFF30080401DA1207A -:1011D00026812A0B78F6339F93CACD8D9E6AC4214F -:1011E000818A46EE26417272DF25D7B7F017304A62 -:1011F00039059E5638B505460E4C0021013500F0E4 -:1012000051FCA4F82C55B4F82C0500F033FC78B14F -:10121000B4F82C0500F03EFC014648B9B4F82C05A2 -:1012200000F040FCB4F82C350133A4F82C35EAE783 -:1012300038BD00BF1046002010B50A4B0A4A1A609C -:1012400003F5805393F860203AB9DC6D2CB1204649 -:1012500001F00AF8204605F03BFBBDE810400348CA -:1012600001F002B840350020E46A000888450020FB -:101270002DE9F04F8FB000AF05460C4602F0B2F9F1 -:10128000002849D1237E022B1BD1E38A012B18D1E0 -:1012900001F084FE0646FFF7E5FD03464FF4C870F3 -:1012A000DFF8C482B3FBF0F206F5167602FB1033CA -:1012B00016FA83F3C8F80030E37E33B9A34B00225B -:1012C0001A703C37BD46BDE8F08F07F12401204677 -:1012D00000F0F0FD0028F4D107F11400FFF7DAFD6B -:1012E00097F8264007F11401224607F1270005F080 -:1012F00039FB0028E2D10F2C08D8944B1C70D8F889 -:101300000030A3F51673C8F80030DAE797F8241018 -:10131000284602F05FF9D4E7E38A282B2BD010D8B7 -:10132000012B23D0052BCCD1BFF34F8F8849894B9C -:10133000CA6802F4E0621343CB60BFF34F8F00BF73 -:10134000FDE7302BBDD1844EE17E327A9142B8D197 -:10135000607E3146002291F8DC50854200F0A58085 -:101360000132042A01F58A71F5D1AAE721462846FF -:10137000FFF7A0FDA5E721462846FFF703FEA0E7FB -:10138000B2F8EC507B6005F103094FEA99094FEA86 -:101390008902D11DC908A8EBC1039D46EB46002177 -:1013A000584600F039FC04F1EE012A463144584613 -:1013B00000F00CFC7B6813B9012000F04BFB96F8A1 -:1013C000D20000F057FB044630B9307200F08AFBBF -:1013D000204600F03FFBB1E0D6F8D4203AB996F8A9 -:1013E000D200B6F82C25824201D8FFF703FFD6F8C9 -:1013F000D4202A44944208D296F8D200B6F82C257C -:101400000130824201D8FFF7F5FE70685FFA89F279 -:10141000594600F009FC08B9C54679E0726896F8AB -:10142000D2002A447260D6F8D42005EB0209C6F82F -:10143000D49000F01FFB814509D396F8D220D6F84E -:10144000D4000132001B86F8D220C6F8D400FF2D4C -:101450000FD80024347200F045FB204600F0FAFA61 -:1014600000F080FE3D4B188108B9FFF7C1F9C54671 -:1014700027E7BB6896F8D9000AFB0362FB68D2F83D -:10148000E41082F8E83001F58061C2F8E030C2F87B -:10149000E410FFF7D5FDFFF723FE96F8D9200132BF -:1014A00002F0030286F8D920B6E74FF48A7A0AFBE5 -:1014B00002F505F1EA013144204600F0D1FDF86063 -:1014C00000287FF4FEAE3544012285F8E82001F0C3 -:1014D00065FDD5F8E020D6ED007ADFED216A801AAF -:1014E000192838BF192040F6B832904228BF10465C -:1014F000B8EE677A07EE900AF8EEE77A67EEA67A1A -:10150000DFED186AE7EE267AFCEEE77AC6ED007AA0 -:1015100096F8D930BB60BA6873680AFB02F43219D6 -:1015200092F8E81059B1D2F8E4108B42E8463FF443 -:1015300027AF002182F8E810C2F8E010C5467368B2 -:10154000064A9B0A01331381BBE600BF0935002020 -:1015500000ED00E00400FA0510460020F824002009 -:10156000CDCCCC3D6666663F0C350020014B187033 -:10157000704700BF0425002030B54FF000542B4BBE -:1015800022689A4285B007D003F0C6FF044620BB0C -:101590000024204605B030BD254B627D25481A70D9 -:1015A000237D03724FF48073C0F8F8314FF4007359 -:1015B000C0F80C3300254FF44073C0F820341E49A6 -:1015C000C0F8E450C922093000F000FB2046E022B8 -:1015D000294600F021FB0124DBE7184A184D136C63 -:1015E00043F000731364AA6D164B9A42D0D12B6E50 -:1015F000013B7E2BCCD8144A07CA01AB83E8070015 -:101600001846032100F07CFD6B6D83424FF0000310 -:10161000BED12A6D8A4201BFAB65054B2A6E1A7096 -:1016200003BF0A4BEA6D1A601C46B2E79AAD44C587 -:10163000042500201046002016000020003802403B -:10164000006600405041A0B05866004010230020C2 -:1016500037B51A4D00F086FD02236B71184B2881B7 -:1016600019681848012201F037FB00230193164B3B -:10167000164900931648174B4FF4805201F082FF31 -:10168000154B197811B1124801F0A4FF01F086FC46 -:101690000446FFF7E7FB4FF4C873B0FBF3F202FB1D -:1016A000130304F5167010FA83F00C4B186003F066 -:1016B00029FF08B10F232B8103B030BDF82400208F -:1016C00010230020403500206D110008082500205F -:1016D0001035002071120008042500200C35002070 -:1016E0002DE9F04F2DED028B0FF23829D9E9008951 -:1016F000834C93B00BAE9FED7E8BFFF7F1FC814FD7 -:10170000DFF828A200230A93ADF834300B937360FE -:101710004FF0000B5B468DED008B01250DF11D0296 -:1017200007A938468DF81C508DF81DB001F084FAD9 -:101730009DF81C30002B40F0A580204601F052FFA0 -:101740000646002845D1704F01F028FC3B689842BE -:101750003FD301F023FC8246FFF784FB4FF4C873AC -:10176000B0FBF3F202FB13030AF5167010FA83F0D4 -:101770003860664F97F800B0CBF1100ABBF1000F4C -:1017800014BF33462B465FFA8AFA0EA88DF828302C -:10179000FFF780FBBAF1060F28BF4FF0060A0EAB29 -:1017A00003EB0B0152460DF1290000F00FFA0AABD2 -:1017B0000393182302930AF10102554BD2B2CDE9EB -:1017C0000053049220464CA3D3E9002301F050FFBC -:1017D0003E7001F0E3FB4F4A4F4D1368C31AB3F557 -:1017E0007A7F2ED3106001F0DBFB02460B462046C9 -:1017F00001F0D6FF204601F0F5FE10B32B7A474EDC -:10180000002B14BF03230223737101F0C7FB0EAF3B -:101810004FF47A730122B0FBF3F039463060304662 -:1018200000F020FB182302933D4B019380B240F25D -:101830005513CDE90370009342464B46204601F014 -:1018400017FF2B7A93B101F0A9FB002607464FF44E -:101850008A7A95F8D900304400F003000AFB00535F -:1018600093F8E82092B30136042EF2D1C82003F099 -:1018700051F92B7A002B7FF43DAF13B0BDEC028BF6 -:10188000BDE8F08FDAF8143083F04003CAF8143062 -:10189000594610220EA800F0BFF90DF11E0308AA48 -:1018A0000AA9384600F046FF96E803000FAB83E82C -:1018B00003009DF834308DF844300A9B0E930EA936 -:1018C000DDE90823204602F03FF921E7D3F8E020C4 -:1018D00042B12B68FA2B38BFFA23BA1A0533B2EBA0 -:1018E000430FC0D3FFF7ACFB0028BCD1BEE700BF5D -:1018F0000000000000000000401DA12026812A0BEE -:1019000010350020403500200C350020093500201E -:1019100008350020404B002010460020F82400200D -:10192000444B0020F1C6A7C1D068080F0000024058 -:1019300008B5054800F098FFBDE80840034A04498F -:10194000002004F0BFBF00BF40350020804B0020C6 -:10195000391200087047000070B50F4B1B78013337 -:10196000DBB2012B0C4611D80C4D29684FF47A7369 -:101970000E6AA2FB0332014622462846B047844243 -:1019800004D1074B00221A70012070BD4FF4FA7089 -:1019900003F0C0F80020F8E71C230020F84D0020D9 -:1019A000744B002070B504464FF47A76412C2546DE -:1019B00028BF412506FB05F003F0ACF8641BF5D108 -:1019C00070BD000007B50023024601210DF107009C -:1019D0008DF80730FFF7C0FF20B19DF8070003B076 -:1019E0005DF804FB4FF0FF30F9E700000A4608B548 -:1019F0000421FFF7B1FF80F00100C0B2404208BDF2 -:101A000030B4054C2368DD69044B0A46AC460146F8 -:101A1000204630BC604700BFF84D0020A086010082 -:101A200070B503F087FB094E094D3080002428680B -:101A30003388834208D903F077FB2B6804440133D1 -:101A4000B4F5803F2B60F2D370BD00BF764B002011 -:101A5000484B002003F01EBC00F1006000F5803010 -:101A60000068704700F10060920000F5803003F0DC -:101A7000A7BB0000054B1A68054B1B889B1A8342C5 -:101A800002D9104403F050BB00207047484B00209F -:101A9000764B0020024B1B68184403F04DBB00BF7F -:101AA000484B0020024B1B68184403F05DBB00BF8D -:101AB000484B002010F003030AD1B0F5047F05D293 -:101AC00000F10050A0F57920D0F800381846704792 -:101AD0000023FBE700F10050A0F57920D0F8100AB0 -:101AE00070470000064991F8243033B10023086A9A -:101AF00081F824300822FFF7B5BF0120704700BFEE -:101B00004C4B0020014B1868704700BF002004E0D8 -:101B1000F0B51E4B1D6801382E0C0A181C48C5F381 -:101B20000B04032335460788A7420BD144680B46B4 -:101B3000013C934218461BD214F9010F48B103F837 -:101B4000010BF6E7013B00F10800ECD191420ED207 -:101B50000B4618462C24B6F5805F00F8014B0AD1DD -:101B6000824202D94122981C5A70401AF0BD0846A0 -:101B7000B6F5805FF9D041F201039D42F5D1824272 -:101B8000F3D95A2300F8013BEFE700BF002004E03F -:101B900020230020022802BF024B4FF480029A61EA -:101BA000704700BF00000240022802BF014B4022E4 -:101BB0009A61704700000240022801BF024A53693F -:101BC00083F04003536170470000024010B50023CA -:101BD000934203D0CC5CC4540133F9E710BD00003C -:101BE00010B5013810F9013F3BB191F900409C421A -:101BF00003D11AB10131013AF4E71AB191F9002089 -:101C0000981A10BD1046FCE703460246D01A12F996 -:101C1000011B0029FAD1704702440346934202D0C7 -:101C200003F8011BFAE770472DE9F8431F4D1446EE -:101C300095F824200746884652BBDFF870909CB385 -:101C400095F824302BB92022FF2148462F62FFF758 -:101C5000E3FF95F82400C0F10802A24228BF224603 -:101C6000D6B24146920005EB8000FFF7AFFF95F832 -:101C70002430A41B1E44F6B2082E17449044E4B24C -:101C800085F82460DBD1FFF72DFF0028D7D108E0CD -:101C90002B6A03EB82038342CFD0FFF723FF002898 -:101CA000CBD10020BDE8F8830120FBE74C4B00209E -:101CB000024B1A78024B1A70704700BF744B002019 -:101CC0001C23002010B5104C104802F04BFA21469E -:101CD0000E4802F073FA2468E26ED2F8043843F03A -:101CE0000203C2F804384FF47A70FFF75BFE08492C -:101CF000204602F06BFBE26ED2F8043823F00203B8 -:101D0000C2F8043810BD00BFD06B0008F84D0020A9 -:101D1000D86B0008704700002DE9F0470D460446D7 -:101D200000219046284640F27912FFF775FF2346BE -:101D300020220021284601F0A9FE231D0222202195 -:101D4000284601F0A3FE631D03222221284601F04C -:101D50009DFEA31D03222521284601F097FE04F1D4 -:101D6000080310222821284601F090FE04F11003F8 -:101D700008223821284601F089FE04F111030822C7 -:101D80004021284601F082FE04F112030822482176 -:101D9000284601F07BFE04F114032022502128463E -:101DA00001F074FE04F1180340227021284601F06E -:101DB0006DFE04F120030822B021284601F066FEE2 -:101DC00004F121030822B821284601F05FFE04F146 -:101DD0002207C0263B46314608222846083601F035 -:101DE00055FEB6F5A07F07F10107F3D104F13203E8 -:101DF00008223146284601F049FE002704F1330A43 -:101E000094F832304FEAC7099F4209F5A47615D3FA -:101E1000B8F1000F08D1314604F59973072228461E -:101E200001F034FE09F24F16274694F832213B1B8D -:101E300093420CD3F01DC008BDE8F0870AEB0703FE -:101E400008223146284601F021FE0137D8E707F283 -:101E5000331331460822284601F018FE08360137B0 -:101E6000E3E7000013B5044608460021016023465D -:101E7000C0F803102022019001F008FE0198231DF4 -:101E80000222202101F002FE0198631D032222217B -:101E900001F0FCFD0198A31D0322252101F0F6FDB0 -:101EA000019804F108031022282101F0EFFD07201A -:101EB00002B010BDF7B50023047F00910E46072243 -:101EC0001946054601F0A6FC731C0093012200236D -:101ED0000721284601F09EFCC4B9B31C00930522DB -:101EE00023460821284601F095FC0D243746B27898 -:101EF000BB1B934211D32B7FA88A0734E408BBB9DC -:101F0000844294BF0020012003B0F0BDAB8ADB0007 -:101F1000083BDB08B3700824E8E7FB1C009321466C -:101F200000230822284601F075FC08340137DEE75B -:101F3000201A18BF0120E7E7F7B50023047F0091BE -:101F40000E4608221946054601F064FC731CC4B90C -:101F50000822009311462346284601F05BFC10241A -:101F6000012372785F1C013B934211D32B7FA88A17 -:101F70000734E408BBB9844294BF0020012003B0B9 -:101F8000F0BDAB8ADB00083BDB0873700824E7E791 -:101F9000F3190093214600230822284601F03AFC59 -:101FA00008343B46DDE7201A18BF0120E7E70000B0 -:101FB000F8B50E4605461446002181223046FFF74B -:101FC0002BFE2B4608220021304601F05FFD7CB934 -:101FD0006B1C07220821304601F058FD0F24012315 -:101FE0006A785F1C013B934204D3E01DC008F8BD32 -:101FF0000824F4E7EB1921460822304601F046FD9B -:1020000008343B46ECE70000F8B50E46054614469A -:102010000021CE223046FFF7FFFD2B46282200216B -:10202000304601F033FD7CB905F108030822282170 -:10203000304601F02BFD30242F462A7A7B1B934239 -:1020400004D3E01DC008F8BD2824F5E707F1090313 -:1020500021460822304601F019FD08340137ECE72B -:10206000F7B5047F00910E4601231022002105469A -:1020700001F0D0FBC4B9B31C009309222346102100 -:10208000284601F0C7FB192437467288BB1B9A42C9 -:1020900011D82B7FA88A0734E408BBB9844294BFC7 -:1020A0000020012003B0F0BDAB8ADB00103BDB0851 -:1020B00073801024E8E73B1D00932146002308228B -:1020C000284601F0A7FB08340137DEE7201A18BFC5 -:1020D0000120E7E730B5094D0A4491420DD011F8CF -:1020E000013B5840082340F30004013B2C4013F00F -:1020F000FF0384EA5000F6D1EFE730BD2083B8ED4E -:10210000F7B54FF0FF33DFF854C0DFF854E000EBD1 -:1021100081011A4688421CD050F8044B019401AF4B -:10212000042417F8015B82EA05620825DB181646CD -:1021300005F1FF355241002EBCBF83EA0C0382EA51 -:102140000E0215F0FF05F1D1013C14F0FF04E8D1B7 -:10215000E0E7D843D14303B0F0BD00BF9336EAA90E -:10216000EBE1F042F7B53A4A106851686B4603C399 -:102170006A4638493848082304F004FC044600281D -:1021800035D10A25354A106851686B4603C36A4643 -:1021900033493148082304F0F5FB044600284DD0AC -:1021A0000369B3F5E02F49D8B0F8662040F2044146 -:1021B0008A4201D0552A41D12A4A224402F15C01C7 -:1021C0008B423BD35C3B244900209E1AFFF782FFE1 -:1021D0003246074604F164010020FFF77BFFA36845 -:1021E0009F422BD1E368984208BF002526E003698F -:1021F000B3F5E02F29D8428B40F204418A4201D046 -:10220000552A20D1174A224402F110018B4218D3DB -:10221000103B114900209D1AFFF75CFF2A46064635 -:1022200004F118010020FFF755FFA3689E4202D178 -:10223000E368984201D00D25A4E70025284603B0A5 -:10224000F0BD10259EE70C259CE70B259AE700BF03 -:10225000A86A0008DCFF060000000108B16A000857 -:1022600090FF06000800FFF710B5037C044613B981 -:10227000006804F06FFB204610BD00000023BFF390 -:102280005B8FC360BFF35B8FBFF35B8F8360BFF374 -:102290005B8F7047BFF35B8F0068BFF35B8F704746 -:1022A00070B505460C30FFF7F5FF05F1080604464A -:1022B0003046FFF7EFFFA04206D930466D68FFF7C2 -:1022C000E9FF2544281A70BD3046FFF7E3FF201AC6 -:1022D000F9E7000070B50546406898B105F10800BF -:1022E000FFF7D8FF05F10C0604463046FFF7D2FF92 -:1022F0008442304694BF6D680025FFF7CBFF013C58 -:102300002C44201A70BD000038B50C460546FFF776 -:10231000C7FFA04210D305F10800FFF7BBFF04443C -:102320006868B4FBF0F100FB1144BFF35B8F012040 -:10233000AC60BFF35B8F38BD0020FCE72DE9F041B6 -:10234000144607460D46FFF7C5FF844228BF0446E2 -:10235000D4B1B84658F80C6B4046FFF79BFF3044A9 -:10236000286040467E68FFF795FF331A9C4203D8E9 -:102370006C600120BDE8F0816B60A41B3B68AB6022 -:102380002044E8600220F5E72046F3E738B50C4624 -:102390000546FFF79FFFA04210D305F10C00FFF7A1 -:1023A00079FF04446868B4FBF0F100FB1144BFF30B -:1023B0005B8F0120EC60BFF35B8F38BD0020FCE732 -:1023C0002DE9FF41884669460746FFF7B7FF6C468F -:1023D00006B204EBC6060025B44209D06268206844 -:1023E00008EB0501FFF7F2FB636808341D44F3E7CF -:1023F00029463846FFF7CAFF284604B0BDE8F081F9 -:10240000F8B505460C300F46FFF744FF05F1080606 -:1024100004463046FFF73EFFA042304688BF6C6856 -:10242000FFF738FF201A386020B130462C68FFF7DC -:1024300031FF2044F8BD000073B5144606460D4632 -:10244000FFF72EFF844228BF04460190DCB101A9AA -:102450003046FFF7D5FF019B33B93268C5E9023337 -:10246000C5E9002401200CE09C4238BF019428609B -:10247000019868608442F5D93368AB60241AEC6037 -:10248000022002B070BD2046FBE700002DE9FF41AD -:102490000F466946FFF7D0FF6C4600B204EBC0055B -:1024A0000026AC4209D0D4F8048054F8081BB819AF -:1024B0004246FFF78BFB4644F3E7304604B0BDE8E5 -:1024C000F081000038B50546FFF7E0FF04460146FD -:1024D0002846FFF719FF204638BD0000302383F35C -:1024E000118862B670470000002383F3118862B63A -:1024F0007047000010B4026854681A4623465DF81D -:10250000044B184701207047002070470020704797 -:1025100070470000002070470E20704700F5805083 -:1025200090F8C800C0F340007047000000F58050EC -:1025300090F9C90070470000F7B50C68BDF820702D -:1025400014F000541E466FD10B7B082B6CD8FFF79C -:10255000C5FF4569AB685B010CD4AB681B0108D4AF -:10256000AC6814F080545DD1FFF7BEFF204603B085 -:10257000F0BD01240B6804F1180C002BB8BFDB0080 -:102580004FEA0C1CB4BF43F004035B0545F80C3064 -:102590000B680FFA84FC13F0804F18BF05EB0C1E7C -:1025A00005EB0C1C1EBFDEF8803143F00203CEF8B1 -:1025B00080310B7BCCF8843105EB04158B68C5F8B2 -:1025C0008C314B68C5F88831DCF8803143F0010369 -:1025D000CCF8803100EB441541F268031D4403EB55 -:1025E00044130344C5E9002608330D4601F10C0CE1 -:1025F00055F804EB43F804EB6545F9D184342D8894 -:102600001D8000EB441407F00303257925F00B052A -:102610002B432371FFF768FF0097334600F0E0FC7F -:102620000120A4E70224A5E74FF0FF309FE7000058 -:1026300013B500F580540191E06DFFF74BFE1F28A4 -:102640000AD90199E06D2022FFF7BAFEA0F120031C -:102650005842584102B010BD0020FBE708B500F514 -:102660008050FFF73BFFC06DFFF708FEBDE8084054 -:10267000FFF73ABF002202608281426082607047A9 -:1026800010B500220023C0E9002300230446038183 -:102690000C30FFF7EFFF204610BD0000F0B50546F7 -:1026A00000F580500C4690F8C83013F0040FC3F3C7 -:1026B000800108BF114661F3820304F1840680F8AB -:1026C000C83005EB461389B01B79D8072ED57AB3ED -:1026D00019072DD46846FFF7D3FF05EB441303F524 -:1026E000835303F1180703AA103318685968144676 -:1026F00003C40833BB422246F7D1186820609B8888 -:10270000A380DDE90E23CDE900230123ADF80830D5 -:102710002B686946DB6B2846984705EB46152B79F5 -:102720001A075CBF43F008032B7101E0002AF4D1C3 -:1027300009B0F0BD2DE9F047074688B007F5805491 -:1027400068469A468846FFF7C9FE9146FFF798FF0C -:10275000E06DFFF7A5FD1F2829D9E06D202269460D -:10276000FFF7B0FE202822D103AD444605AB2E462C -:1027700003CE9E4220606160354604F10804F6D124 -:1027800030682060B388A380DDE90023C9E9002315 -:10279000BDF80830AAF80030FFF7A6FE4A465346B7 -:1027A0004146384608B0BDE8F04700F007BCFFF7E7 -:1027B0009BFE002008B0BDE8F08700002DE9F84F2F -:1027C0000023C0E90133254B044640F8183B0F466F -:1027D000FFF750FF04F12800FFF752FF04F148080B -:1027E00004F582554646083530462036FFF748FF47 -:1027F000AE42F9D104F580554FF480534FF00009F3 -:10280000C5E91339C5F848800123EE6504F58758FA -:1028100004F58456C5F8549085F8583085F8603032 -:10282000083608F108084FF0000A4FF0000B46E99F -:1028300008ABA6F11800FFF71DFF203646F8289CCC -:102840004645F4D185F8C97017B1054800F0A0FBE2 -:10285000044B63612046BDE8F88F00BFE46A0008BE -:10286000BC6A00080064004010B5044B19780446A7 -:102870004A1C1A70FFF7A2FF204610BD7C4B0020B7 -:102880002DE9F04300294FD0284B2948B0FBF1F047 -:1028900099428CBF0A2311235D1EB0FBF3F703FBA3 -:1028A0001703ECB22BB1022D2B46F5D80020BDE862 -:1028B000F0837E1EB6F5806FF8D2C4EBC40C0CF129 -:1028C00003034FEAE308C3F3C703A4EB030E08F1C5 -:1028D00001094FF47A755FFA8EF008FB055559FA35 -:1028E0008EFEB5FBFEF5B5F5617FC1BF0CF1FF3380 -:1028F000C3F3C703E01AC0B25C1C50FA84F40C4D59 -:102900007C43B5FBF4F4A142D0D1013BDBB20F2BE9 -:10291000CCD80138C0B20728C8D800211071168061 -:102920009170D3700120C2E70846C0E73F420F0014 -:1029300080F9370370B505460E464FF47A746B691B -:102940005B6803F00103B34207D04FF47A7002F0E2 -:10295000E1F8013CF3D1204670BD0120FCE7000006 -:1029600030B54269936913F0700F16D000230B4CF9 -:10297000936103F1840200EB421211794D0709D5EE -:10298000890707D5416954F823508D60117941F0CA -:10299000040111710133032BEBD130BDD06A000863 -:1029A00073B51D46436916469A68D207044609D591 -:1029B0009A6801219960C2F34002CDE900650021C7 -:1029C000FFF76CFE63699A68D1050BD59A684FF4DE -:1029D00080719960C2F34022CDE900650121204653 -:1029E000FFF75CFE63699A68D2030BD59A684FF4CF -:1029F00080319960C2F34042CDE900650221204652 -:102A0000FFF74CFE204602B0BDE87040FFF7A8BFBC -:102A1000F8B50446466900296CD106F10C07386800 -:102A200080076AD006EB01153868D5F8B00110F0C0 -:102A3000040FD5F8B0011ABFC00840F00040400DA7 -:102A4000A061D5F8B0C11CF0020F1CBF40F080405F -:102A5000A061D5F8B40106EB011100F00F0084F875 -:102A60002400D1F8B8012077D1F8B801000A6077C6 -:102A7000D1F8B801000CA077D1F8B801000EE077CA -:102A8000D1F8BC0184F82000D1F8BC01000A84F818 -:102A90002100D1F8BC01000C84F82200D1F8BC114F -:102AA000090E84F823103821396004F1340004F150 -:102AB000180104F1240551F8046B40F8046BA94295 -:102AC000F9D109880180C4E90A232146002323861D -:102AD00051F8283B2046DB6B984704F5805220468E -:102AE00092F8C83043F0040382F8C830BDE8F840DB -:102AF000FFF736BF06F1100791E7F8BD10B50446A1 -:102B000000F04EFA02460B4652EA030102D0013AA7 -:102B100063F100030449086820B12146BDE8104074 -:102B2000FFF776BF10BD00BF784B0020F8B500F569 -:102B300083511E46FFF7D2FCDFF844C00831002461 -:102B400004F1840500EB45152B795F070ED4DB06F5 -:102B50000CD5D1E900739742B34107D243695CF8C1 -:102B600024709F602B7943F004032B710134032CF4 -:102B700001F12001E4D1BDE8F840FFF7B5BC00BF8A -:102B8000D06A000808B5FFF7A9FCFFF7E9FEBDE829 -:102B90000840FFF7A9BC0000F8B5436905469868EE -:102BA00000F0E050B0F1E05F0F461FD0E8B1FFF752 -:102BB00095FC05F583541034002606F1840305EBDB -:102BC00043131B791A0706D50136032E04F120049E -:102BD000F3D1012007E05B07F6D42146384600F028 -:102BE00039FA0028F0D1FFF77FFCF8BD0120FCE79F -:102BF00000F5805008B5FFF771FCC06DFFF750FB82 -:102C0000FFF772FC43090CBF0120002008BD000043 -:102C1000F8B51D46002313700F4606461446FFF70D -:102C2000E7FF80F00100387025B129463046FFF7F4 -:102C3000B3FF2070F8BD00002DE9B8410C461546E1 -:102C40001F46804600F0ACF90B462178024609B9D0 -:102C5000287850B14046FFF769FFFFF793FF3B46E6 -:102C60002A462146FFF7D4FF0120BDE8B8810000C5 -:102C700010B5FFF733FC174B1A6C42F000721A6460 -:102C80001A6A42F000721A621A6A00F5805422F041 -:102C900000721A62FFF728FC94F8C830DB0718D4DA -:102CA000B9B103211320FFF719FC01F0CBF903217F -:102CB000142001F0C7F90321152001F0C3F994F89D -:102CC000C83043F0010384F8C830BDE81040FFF776 -:102CD0000BBC10BD003802402DE9F04700F58055CF -:102CE00088B095F8C930012B0446884616467FD82F -:102CF000804F57F823200AB947F82300D7F800A0DF -:102D0000C4F80C802674BAF1000F63D095F8C9306E -:102D1000012B6FD001212046FFF7AAFFFFF7DEFB52 -:102D20006269136823F0020313606269136843F059 -:102D300001031360636900275F6101212046FFF7EB -:102D4000D3FBFFF7F7FD002800F09580E86DFFF753 -:102D500095FA04F58359BA4609F1080920220021A1 -:102D60006846FEF759FF02A8FFF784FCCDF818A0CB -:102D70006A4609EB07030DF1180E9446BCE8030000 -:102D8000F44518605960624603F10803F5D1DCF898 -:102D90000000186020379CF804201A71602FDDD1E4 -:102DA00095F8C8306FF38203002785F8C8306A466B -:102DB00041462046ADF80070ADF802708DF8047001 -:102DC000FFF75EFD636948BB4FF400421A6008B02C -:102DD000BDE8F08741F2D00003F07CFD814610B1E0 -:102DE0005146FFF7EBFCC7F80090B9F1000F8DD109 -:102DF0000020ECE7386803681B6B98470146002801 -:102E000088D13868FFF734FF3868036832465B685A -:102E10004146984700287FF47DAFE9E761221A60B8 -:102E20009DF802309DF803201B06120402F4702264 -:102E300003F040731343BDF80020C2F309021343AB -:102E40009DF804201205022E02F4E0020CBF4FF0A0 -:102E500000410021134362690B43D361636913226C -:102E60005A616269136823F00103136039462046F2 -:102E7000FFF760FD08B96369A6E795F8C93093BB11 -:102E80006169D1F8002242F00102C1F800226169B3 -:102E9000D1F8002222F47C5222F00E02C1F8002266 -:102EA0006169D1F8002242F46062C1F800226269CF -:102EB000C2F814326269C2F80432626941F6FF71E5 -:102EC000C2F80C126269C2F840326269C2F8443238 -:102ED00063690122C3F81C226269D2F8003223F030 -:102EE0000103C2F8003295F8C83043F0020385F8B8 -:102EF000C8306CE7784B002008B500F051F850EA74 -:102F00000103024602D0421E61F10001044B186821 -:102F100010B10B46FFF744FDBDE8084001F068B86A -:102F2000784B002008B50020FFF7E8FDBDE8084019 -:102F300001F05EB808B50120FFF7E0FDBDE80840EC -:102F400001F056B800B59BB0EFF3098168226846DE -:102F5000FEF73CFEEFF30583014B9B6BFEE700BFE2 -:102F600000ED00E008B5FFF7EDFF000000B59BB0F5 -:102F7000EFF3098168226846FEF728FEEFF3058328 -:102F8000014B5B6BFEE700BF00ED00E0FEE70000D9 -:102F90000FB408B5029801F049FDFEE702F0DEB972 -:102FA00002F0B6B913B56C4684E80600031D94E838 -:102FB000030083E80500012002B010BD73B58568E9 -:102FC000019155B11B885B0707D4D0E900369B6B94 -:102FD0009847019AC1B23046A847012002B070BD9F -:102FE000F0B5866889B005460C465EB1BDF838304C -:102FF0005B070AD4D0E900379B6B98472246C1B2E1 -:103000003846B047012009B0F0BD00220023CDE9C9 -:1030100000230023ADF808300A4603AB01F108068F -:10302000106851681C4603C40832B2422346F7D1E7 -:10303000106820609288A280FFF7B2FF0423ADF8E9 -:1030400008302B68CDE90001DB6B694628469847BC -:10305000D8E7000030B503680968DD0FB5EBD17F14 -:1030600023F0604421F060424FEAD1700BD0002B76 -:10307000B8BFA40C0029B8BF920C944202D034BF50 -:103080000120002030BD944205D1C1F38070C3F30C -:1030900080738342F6D194422CBF00200120F1E7D7 -:1030A0002DE9F041456A15B94162BDE8F0814B68F0 -:1030B00023F06047C3F38A464FEAD37EC3F3807898 -:1030C00016EA230638BF3E46AC462B465A68BEEB8E -:1030D000D27F22F060440AD0002A18DAA40CB4424D -:1030E00017D19D420FD10D60DEE71346EEE7A742F0 -:1030F00007D102F08044C2F3807242450BD054B134 -:10310000EFE708D2EDE7CCF800100B60CDE7B44252 -:1031100001D0B442E5D81A689C46002AE5D119606E -:10312000C3E700002DE9F047089D01F007044FEACE -:10313000D508224405F0070500EBD1004FF47F4984 -:10314000944201D1BDE8F08704F0070705F0070AB3 -:1031500057453E4638BF5646C6F10806111B8E42FB -:1031600028BF0E46E10808EBD50E415C13F80EC0EF -:10317000B94029FA06F721FA0AF1FFB28CEA0101F7 -:1031800047FA0AF739408CEA010C03F80EC03444C0 -:103190003544D5E780EA0120082341F2210201B23B -:1031A0004000002980B203F1FF33B8BF504013F054 -:1031B000FF03F4D17047000038B50C468D18A542C6 -:1031C00000D138BD14F8011BFFF7E4FFF7E700005A -:1031D00042684AB1136843604389818901339BB2D5 -:1031E0009942438138BF83811046704770B588B0DB -:1031F000202204460D4668460021FEF70DFD2046BC -:103200000495FFF7E5FF024658B16B46054608AE48 -:103210001C4603CCB44228606960234605F10805CA -:10322000F6D1104608B070BD082817D909280CD06F -:103230000A280CD00B280CD00C280CD00D280CD050 -:103240000E2814BF4020302070470C2070471020FB -:1032500070471420704718207047202070470000E6 -:10326000082817D90C280CD910280CD914280CD9E7 -:1032700018280CD920280CD930288CBF0F200E20FC -:103280007047092070470A2070470B2070470C20B8 -:1032900070470D20704700002DE9F843078C072F79 -:1032A00004461ED9D0E9029800254FF6FF73C5F1F8 -:1032B0002006A5F1200029FA05F108FA06F628FAF9 -:1032C00000F031430143C9B21846FFF763FF0835E8 -:1032D000402D0346EBD1E1693A46BDE8F843FFF7DC -:1032E0006BBF4FF6FF70BDE8F883000010B54B6868 -:1032F00023B9CA8A63F30902CA8210BD04691A6835 -:103300001C600361C38A013BC3824A60EFE700008F -:103310002DE9F84F1D46CB8A0F46C3F30901052955 -:10332000814692460B4630D00020AAB207F11A041B -:103330009EB2042E1FFA80F80FD8904503F10103C6 -:1033400006D3FB8A0A4462F30903FB8201201AE0D8 -:103350001AF80060E6540130EAE79045F1D2A1F195 -:10336000050B1C237C68BBFBF3F203FB12BB1FFAAB -:103370008BF6002C45D14846FFF72AFF044638B9A2 -:1033800078606FF00200BDE8F88F4FF00008E6E7C4 -:10339000002606607860ADB24FF0000B454510D9AD -:1033A0000AEB0803221D13F8011B9155B1B208F175 -:1033B00001081B291FFA88F82BD0454506F10106A4 -:1033C000F1D8FB8AC3F30902154465F30903BCE78E -:1033D000013292B21C462368002BF9D16B1F0B44BB -:1033E0001C21B3FBF1F301339BB29A42D3D2BBF160 -:1033F000000FD0D14846FFF7EBFE20B9C4F800B06B -:10340000BFE70122E7E7C0F800B05E46206004464F -:10341000C1E74545D5D94846FFF7DAFE08B920602F -:10342000AFE7C0F800B0002620600446B6E7000011 -:103430002DE9F04F2DED028B1C4683B05B690192A4 -:1034400007468846002B00F09A80238C2BB1E26956 -:10345000002A00F09480072B35D807F10C00FFF705 -:10346000B7FE054638B96FF00205284603B0BDEC3B -:10347000028BBDE8F08F14220021FEF7CDFB228CD9 -:10348000E16905F10800FEF7A1FB208C013080B254 -:10349000FFF7E6FEFFF7C8FE013880B22084013056 -:1034A00028746369228C1B782A4403F01F0363F09D -:1034B0003F0348F000411372384669602946FFF720 -:1034C000EFFD0125D1E700F10C034FF0000908EEF4 -:1034D000103A4FF0800A4E464D4618EE100AFFF79C -:1034E00077FE83460028BED014220021FEF794FB0D -:1034F000002E3AD1019BABF8083002220BF1080EE6 -:103500001FFA82FC0CF10100BCF1060F218C80B285 -:1035100001D88E422BD3FFF7A3FEFFF785FE626929 -:103520001278013802F01F028E4208BF4FF0400AA5 -:1035300042EA49121BFA80F14AEA020A013048F0D5 -:10354000004281F808A08BF81000CBF804205946FF -:103550003846FFF7A5FD238C0135B3422DB289F023 -:1035600001094FF0000AB8D17FE70022C6E7E16900 -:10357000895D0EF802100136B6B20132C0E76FF075 -:10358000010572E7F8B515460E46302200210446C3 -:103590001F46FEF741FB069B6360B5F5001F079BC6 -:1035A000A76034BF6A094FF6FF72A36297B2E66163 -:1035B00004F1100000239A4206D800230360A7827A -:1035C000E3822383E360F8BD066001333046203692 -:1035D000F1E7000003781BB94BB2002BC8BF0170A4 -:1035E0007047000000787047F8B50C46C969074677 -:1035F00011B9238C002B37D1257E1F2D34D8387874 -:1036000028BB228C072A2CD8268A36F003032BD11C -:103610004FF6FF70FFF7D0FD20F0010031024004AB -:1036200041EA0561400C41EA40254FF6FF7223460E -:1036300029463846FFF7FCFE002807DD626913784B -:103640000133DBB21F2B88BF00231370F8BD218A22 -:103650002D0645EA012505432046FFF71DFE0246DB -:10366000E5E76FF00300F1E76FF00100EEE700001F -:1036700070B58AB0044616460021282268461D46C9 -:10368000FEF7CAFABDF83830ADF810300F9B05933D -:103690009DF840308DF81830119B07936946BDF8AE -:1036A0004830ADF820302046CDE90265FFF79CFF99 -:1036B0000AB070BD2DE9F041D36905460C461646A7 -:1036C0000BB9138C5BBB377E1F2F28D895F8008071 -:1036D000B8F1000F26D03046FFF7DEFD3378210227 -:1036E00041EAC33141EA0801338A41EA076141EA0C -:1036F00003410246334641F080012846FFF798FE19 -:1037000000280ADD3378012B07D172691378013361 -:10371000DBB21F2B88BF00231370BDE8F0816FF070 -:103720000100FAE76FF00300F7E70000F0B58BB097 -:1037300004460D4617460021282268461E46FEF71D -:103740006BFA9DF84C305A1E534253418DF80030AD -:103750009DF84030ADF81030119B05939DF848302E -:103760008DF81830149B07936A46BDF85430ADF8B5 -:10377000203029462046CDE90276FFF79BFF0BB0AB -:10378000F0BD0000406A00B104307047436A1A6817 -:10379000426202691A600361C38A013BC3827047B7 -:1037A0002DE9F041D0F82080194E14461D464146BF -:1037B000002709B9BDE8F081D1E90223A21A65EB1F -:1037C0000303964277EB03031ED2036A8B420DD1AB -:1037D000FFF78CFD036A1B68036203690B60C38AF1 -:1037E0000161016A013BC3828846E2E7FFF77EFD83 -:1037F0000B68C8F8003003690B60C38A0161013BA4 -:10380000C382D8F80010D4E788460968D1E700BF22 -:1038100080841E002DE9F04F8BB00D46DDF85090EE -:1038200014469B468046002800F01981B9F1000F2C -:1038300000F01581531E3F2B00F21181012A03D1A4 -:10384000BBF1000F40F00B810023CDE90833B8F83D -:103850001430B5EBC30F4FEAC30703D300200BB0FE -:10386000BDE8F08F2B199F42D8F80C303ABF7F1B70 -:10387000FFB227461BB9D8F81030002B7AD0272D7D -:103880004ED8C5F12806B7424FF000032CBFF6B260 -:103890003E4600932946D8F8080008AB3246FFF7A9 -:1038A00041FCA7EB060A35445FFA8AFAB8F81430EF -:1038B00003F10053053BDB000493D8F80C3003936D -:1038C0002821039B13B1BAF1000F2CD1D8F81000B6 -:1038D00040B1BAF1000F05D0009608AB5246691A04 -:1038E000FFF720FC38B2002FB8D066070AD00AAB29 -:1038F00003EBD401624211F8083C02F007021341C5 -:1039000001F8083C082C3CD9102C40F2B580202C42 -:1039100040F2B780BBF1000F00F09C80082334E038 -:10392000BA460026C2E7049BE02B28BFE02306939B -:103930000B44AB42059314D95A1B03980096924549 -:1039400034BF5246D2B2691A08AB04300792FFF76F -:10395000E9FB079A1644AAEB020A1544F6B25FFA8D -:103960008AFA049B069A05999B1A0493039B1B6889 -:103970000393A6E70093D8F8080008AB3A46294617 -:10398000AEE7BBF1000F13D00123B4EBC30F6CD033 -:10399000082C12D89DF82030621E23FA02F2D507B7 -:1039A00006D54FF0FF3202FA04F423438DF820309D -:1039B0009DF8203089F8003051E7102C12D8BDF85E -:1039C0002030621E23FA02F2D10706D54FF0FF32F3 -:1039D00002FA04F42343ADF82030BDF82030A9F8F2 -:1039E00000303CE7202C0FD80899631E21FA03F31E -:1039F000DA0705D54FF0FF3202FA04F40C430894BD -:103A0000089BC9F800302AE7402C2BD0DDE9086577 -:103A1000611EC4F12102A4F1210326FA01F105FA85 -:103A200002F225FA03F311431943CB0712D5012201 -:103A3000A4F12003C4F1200102FA03F322FA01F1F8 -:103A4000A240524243EA010363EB430332432B4358 -:103A5000CDE90823DDE90823C9E90023FFE66FF07B -:103A60000100FCE66FF00800F9E6082CA0D9102C44 -:103A7000B3D9202CEED8C3E7BBF1000FADD00223A1 -:103A800083E7BBF1000FBBD004237EE730B5012AEA -:103A9000144638BF0124402C85B028BF402400259F -:103AA000012ACDE9025518D81B788DF80830630734 -:103AB0000AD004AB03EBD405624215F8083C02F0CF -:103AC0000702934005F8083C009103462246002176 -:103AD00002A8FFF727FB05B030BD082AE4D9102A59 -:103AE00003D81B88ADF80830E1E7202A8DBFD3E961 -:103AF00000231B680293CDE90223D8E710B5CB68F9 -:103B00001BB98B600B618B8210BD04691A681C6045 -:103B10000361C38A013BC382CA60F0E703064CBF5E -:103B2000C0F3C0300220704708B50246FFF7F6FF29 -:103B3000022806D15306C2F30F2001D100F0030082 -:103B400008BDC2F30740FBE72DE9F04F93B0CDE984 -:103B500003230A6804461046FFF7E0FF022814BF5B -:103B6000C2F306260026002A0D46824680F2F28124 -:103B700012F0C04940F0EE81097B002900F0EA8193 -:103B8000022803D02378B34240F0E781C2F30463F4 -:103B90000693104602F07F030593FFF7C5FF059BD0 -:103BA00029444FEA834848EA0A4848EA4668CE78FA -:103BB00000230022CDE90823F309834648EA0008E0 -:103BC000029367D0059B009302466768534608A995 -:103BD0002046B847002800F0C381276A4FB9414604 -:103BE00004F10C00FFF702FB074690B96FF00200EA -:103BF00054E03B6998450DD03F68002FF9D141460C -:103C000004F10C00FFF7F2FA07460028EED0236A11 -:103C10003B60276297F817C006F01F08CCF3840CAE -:103C2000ACEB08001FFA80FE0028B8BF0EF12000A0 -:103C3000A8EB0C031FFA83FED7E90221B8BF00B23C -:103C4000002B0793BEBF0EF120031BB2079352EA6D -:103C5000010338D0039BDFF824E39A1A049B4FF04A -:103C6000000C63EB010196457CEB01032BD36B7BCE -:103C700097F81AE0734519D1029B002B78D00128E0 -:103C800021DC7868F8B9DFF8F0C2944570EB0103E5 -:103C900016D337E0276A27B96FF00C0013B0BDE8E0 -:103CA000F08F3B699845B5D03F68F4E7B248904241 -:103CB0007CEB010301D30020F0E7029B002BFAD03C -:103CC000079B0F2B17DCFA7DB30002F0030203F011 -:103CD0007C031343FB7539462046FFF707FB6B7BDC -:103CE000BB76029B3BB9FB7DC3F38402013262F3D6 -:103CF0008603FB75D0E76A7BBB7E9A42DBD1029BD1 -:103D0000002B35D0B309022B32D0039BBB60049B40 -:103D1000FB60142200210DA8FDF77EFF039B0A9390 -:103D2000049B0B932B1D0C932B7BADF83EB0013BFA -:103D3000DBB2ADF83C30069B8DF84230059B8DF828 -:103D4000433094F82C308DF840A083F001038DF8B7 -:103D500044308DF84180A3680AA920469847FB7D2E -:103D6000C3F38403013303F01F039B02FB82A2E72A -:103D7000FB7DC6F34012B2EBD31F40F0F480C3F3D7 -:103D80008403434540F0F280029A2B7BB609002A57 -:103D90004DD0F2075DD4032B40F2EB80039BBB6058 -:103DA000049BFB602B7BAE1D033BDBB232463946E6 -:103DB00004F10C00FFF7ACFA00280CDA3946204673 -:103DC000FFF794FAFB7DC3F38403013303F01F0371 -:103DD0009B02FB820AE7DDE90884AB883B834FF650 -:103DE000FF73C9F12000A9F1200228FA09F104FAB1 -:103DF00000F0014324FA02F211431846C9B2FFF75A -:103E0000C9F909F10809B9F1400F0346E9D1B882AF -:103E10002A7B033AD2B23146FFF7CEF9FB7DB88256 -:103E2000DA43C2F3C01262F3C713FB7543E786B9E6 -:103E30002E1D013BDBB23246394604F10C00FFF780 -:103E400067FA0028BADB2A7BB88A013AD2B2314637 -:103E5000E2E7F98AC1F30901013B0429DAB25BD830 -:103E6000281D002307F11B069A4208D910F801CB40 -:103E700006F801C0013101330529DBB2F4D1039901 -:103E80000A9104990B91934207F11B010C9138BFE1 -:103E9000043379680D9134BF55FA83F300230E93F0 -:103EA000FB8AADF83EB0C3F309031A44069B8DF8B4 -:103EB0004230059B8DF8433094F82C30ADF83C200F -:103EC00083F001038DF8443000238DF840A08DF875 -:103ED00041807B602A7BB88A013A291DFFF76CF983 -:103EE0003B8BB882834203D1A3680AA92046984736 -:103EF00020460AA9FFF702FEFB7DBA8AC3F38403BA -:103F0000013303F01F039B02FB823B8B9A420CBFE1 -:103F100000206FF01000C1E67B68002BAFD00520B9 -:103F200001E01C3033461E68002EFAD1091A081D24 -:103F30002E1D184401EB090CBCF11B0F5FFA89F32D -:103F40009DD89A429BD916F8013B00F8013B09F134 -:103F50000109EFE76FF00900A0E66FF00A009DE6A7 -:103F60006FF00B009AE66FF00D0097E66FF00E0011 -:103F700094E66FF00F0091E640420F0080841E002F -:103F8000EFF3098305494A6B22F001024A63683363 -:103F900083F30988002383F31188704700EF00E062 -:103FA000302080F3118862B60D4B0E4AD96821F497 -:103FB000E0610904090C0A43DA60D3F8FC200A49DD -:103FC00042F08072C3F8FC20084AC2F8B01F1168A2 -:103FD00041F0010111602022DA7783F82200704756 -:103FE00000ED00E00003FA0555CEACC5001000E07E -:103FF00010B5302383F311880E4B5B6813F4006314 -:1040000014D0F1EE103AEFF30984683C4FF080735E -:10401000E361094BDB6B236684F3098800F0C4FC81 -:1040200010B1064BA36110BD054BFBE783F311886C -:10403000F9E700BF00ED00E000EF00E063060008D4 -:104040006606000800F1604303F561430901C9B247 -:1040500083F80013012200F01F039A4043099B00DC -:1040600003F1604303F56143C3F880211A60704790 -:10407000026843681143016003B1184770470000AC -:1040800013B5446BD4F894341A681178042915D107 -:10409000217C022912D11979128901238B40134204 -:1040A0000CD101A904F14C0002F060F8D4F894445A -:1040B000019B21790246206800F0D6F902B010BDBC -:1040C000143001F0E3BF00004FF0FF33143001F073 -:1040D000DDBF00004C3002F0B5B800004FF0FF33F8 -:1040E0004C3002F0AFB80000143001F0B1BF000056 -:1040F0004FF0FF31143001F0ABBF00004C3002F044 -:1041000081B800004FF0FF324C3002F07BB8000065 -:104110000020704710B5D0F894341A68117804293B -:10412000044617D1017C022914D1597952890123FF -:104130008B4013420ED1143001F044FF024648B1C7 -:10414000D4F894444FF4807361792068BDE810403E -:1041500000F078B910BD0000406BFFF7DBBF000036 -:10416000704700007FB5124B036000234360C0E935 -:104170000233012502260F4B057404460290019379 -:1041800000F18402294600964FF48073143001F048 -:10419000F5FE094B0294CDE9006304F523724FF458 -:1041A0008073294604F14C0001F0BCFF04B070BDDF -:1041B000246B000859410008814000080B68302238 -:1041C00082F311880A7903EB820210624A790D3278 -:1041D00043F822008A7912B103EB820318620223AA -:1041E000C0F894140374002080F311887047000015 -:1041F00038B5037F044613B190F85430ABB9201D95 -:1042000001250221FFF734FF04F1140025776FF038 -:10421000010100F0A7FC84F8545004F14C006FF049 -:104220000101BDE8384000F09DBC38BD10B501214A -:1042300004460430FFF71CFF0023237784F8543032 -:1042400010BD000038B504460025143001F0AEFE64 -:1042500004F14C00257701F07DFF201D84F85450B7 -:104260000121FFF705FF2046BDE83840FFF752BFA8 -:1042700090F85C3003F06003202B07D190F85D20AC -:10428000212A4FF0000303D81F2A06D800207047C8 -:10429000222AFBD1C0E9143303E0034A0265072256 -:1042A00042658365012070473823002037B5D0F878 -:1042B00094341A681178042904461AD1017C022921 -:1042C00017D11979128901238B40134211D100F1C2 -:1042D0004C05284601F0FEFF58B101A9284601F01F -:1042E00045FFD4F89444019B21790246206800F0F0 -:1042F000BBF803B030BD0000F0B500EB810385B022 -:104300001E6A04460D46FEB1302383F3118804EB88 -:104310008507301D0821FFF7ABFEFB685B691B6852 -:1043200006F14C001BB1019001F02EFF019803A98A -:1043300001F01CFF024648B1039B2946204600F0CD -:1043400093F8002383F3118805B0F0BDFB685A6928 -:104350001268002AF5D01B8A013B1340F1D104F109 -:104360005C02EAE70D3138B550F82140DCB130236A -:1043700083F31188D4F894241368527903EB8203F1 -:10438000DB689B695D6845B104216018FFF770FE2A -:10439000294604F1140001F01FFE2046FFF7BAFE83 -:1043A000002383F3118838BD7047000001F080B905 -:1043B00010B501230446282200F8243B0021FDF714 -:1043C0002BFC0023C4E9013310BD000038B50446BE -:1043D000302383F311880025C0E90355C0E9055552 -:1043E000C0E90755416001F073F90223237085F39A -:1043F0001188284638BD000070B500EB81030546E2 -:104400005069DA600E46144618B110220021FDF7FB -:1044100003FCA06918B110220021FDF7FDFB314615 -:104420002846BDE8704001F01DBA0000826802F025 -:10443000011282600022C0E90422C0E90622026261 -:1044400001F09CBAF0B400EB81044789E4680125CF -:10445000A4698D403D43458123600023A2606360D1 -:10446000F0BC01F0B7BA0000F0B400EB810407899A -:10447000E468012564698D403D4305812360002384 -:10448000A2606360F0BC01F031BB000070B5022394 -:10449000002504460370C0E90255C0E90455C0E98F -:1044A00006554566056280F84C5001F077F963685F -:1044B0001B6823B129462046BDE87040184770BDEF -:1044C0000378052B10B504460AD080F86830052320 -:1044D000037043681B680BB1042198470023A36055 -:1044E00010BD00000178052906D190F868204368C6 -:1044F00002701B6803B118477047000070B590F850 -:104500004C30044613B1002380F84C3004F15C02B7 -:10451000204601F055FA63689B68B3B994F85C30A3 -:1045200013F0600535D00021204601F009FD00217F -:10453000204601F0FBFC63681B6813B1062120468E -:104540009847062384F84C3070BD204698470028D1 -:10455000E4D0B4F86230626D9A4288BF636594F922 -:104560005C30656D002B4FF0300380F20381002D2D -:1045700000F0F280092284F84C2083F31188002196 -:10458000D4E914232046FFF76FFF002383F311883B -:10459000DAE794F85D2003F07F0343EA022340F258 -:1045A0000232934200F0C58021D8B3F5807F48D015 -:1045B0000DD8012B3FD0022B00F09380002BB2D1FD -:1045C00004F16402226502226265A365C1E7B3F5C6 -:1045D000817F00F09B80B3F5407FA4D194F85E30DA -:1045E000012BA0D1B4F8643043F0020332E0B3F5FC -:1045F000006F4DD017D8B3F5A06F31D0A3F5C063CD -:10460000012B90D8636894F85E205E6894F85F1080 -:10461000B4F860302046B047002884D04368236552 -:10462000036863651AE0B3F5106F36D040F60242B6 -:1046300093427FF478AF5C4B2365022363650023CC -:10464000C3E794F85E30012B7FF46DAFB4F86430AB -:1046500023F00203C4E91455A4F86430A56578E793 -:10466000B4F85C30B3F5A06F0ED194F85E3084F8E6 -:104670006630204601F0EAF863681B6813B1012137 -:1046800020469847032323700023C4E914339CE792 -:1046900004F1670323650123C3E72378042B10D1BA -:1046A000302383F311882046FFF7C0FE85F311887D -:1046B0000321636884F8675021701B680BB12046A2 -:1046C000984794F85E30002BDED084F867300423DE -:1046D000237063681B68002BD6D0022120469847C0 -:1046E000D2E794F860301D0603F00F0120460AD58A -:1046F00001F058F9012804D002287FF414AF2B4BA5 -:104700009AE72B4B98E701F03FF9F3E794F85E3016 -:10471000002B7FF408AF94F8603013F00F01B3D092 -:104720001A06204602D501F01FFCADE701F012FC8D -:10473000AAE794F85E30002B7FF4F5AE94F8603071 -:1047400013F00F01A0D01B06204602D501F0F8FBA4 -:104750009AE701F0EBFB97E7142284F84C2083F3EF -:1047600011882B462A4629462046FFF76BFE85F323 -:104770001188E9E65DB1152284F84C2083F3118895 -:104780000021D4E914232046FFF75CFEFDE60B224E -:1047900084F84C2083F311882B462A46294620466C -:1047A000FFF762FEE3E700BF546B00084C6B0008A4 -:1047B000506B000838B590F84C300446002B3ED0C2 -:1047C000063BDAB20F2A34D80F2B32D8DFE803F0D9 -:1047D00037313108223231313131313131313737EE -:1047E000456DB0F862309D4214D2C3681B8AB5FB98 -:1047F000F3F203FB12556DB9302383F311882B4676 -:104800002A462946FFF730FE85F311880A2384F8EB -:104810004C300EE0142384F84C30302383F311889D -:1048200000231A4619462046FFF70CFE002383F3A7 -:10483000118838BD836D03B198470023E7E7002155 -:10484000204601F07DFB0021204601F06FFB6368EC -:104850001B6813B10621204698470623D7E70000BE -:1048600010B590F84C30142B044629D017D8062BDD -:1048700005D001D81BB110BD093B022BFBD800218C -:10488000204601F05DFB0021204601F04FFB6368EC -:104890001B6813B1062120469847062319E0152B03 -:1048A000E9D10B2380F84C30302383F311880023A7 -:1048B0001A461946FFF7D8FD002383F31188DAE77B -:1048C000C3689B695B68002BD5D1836D03B19847A2 -:1048D000002384F84C30CEE7002303758268036917 -:1048E0001B6899689142FBD25A680360426010606D -:1048F0005860704700230375826803691B689968D4 -:104900009142FBD85A68036042601060586070475B -:1049100008B50846302383F311880B7D032B05D09F -:10492000042B0DD02BB983F3118808BD8B690022AD -:104930001A604FF0FF338361FFF7CEFF0023F2E7E9 -:10494000D1E9003213605A60F3E70000FFF7C4BFFB -:10495000054BD9680875186802681A60536001220F -:104960000275D860FBF768BE884B002030B50C4B51 -:10497000DD684B1C87B004460FD02B46094A6846B9 -:1049800000F084F92046FFF7E3FF009B13B168466F -:1049900000F086F9A86907B030BDFFF7D9FFF9E745 -:1049A000884B002011490008044B1A68DB689068A6 -:1049B0009B68984294BF002001207047884B0020DC -:1049C000084B10B51C68D86822681A605360012231 -:1049D0002275DC60FFF78EFF01462046BDE81040DF -:1049E000FBF72ABE884B0020044B1A68DB689268EC -:1049F0009B689A4201D9FFF7E3BF7047884B0020BC -:104A000038B5074C07490848012300252370656025 -:104A100001F098FC0223237085F3118838BD00BF94 -:104A2000F04D00205C6B0008884B002008B572B682 -:104A3000044B186500F042FC00F02EFD024B0322EF -:104A40001A70FEE7884B0020F04D002000F05EB9A0 -:104A5000EFF3118020B9EFF30583302282F3118840 -:104A60007047000010B530B9EFF30584C4F30804B3 -:104A700014B180F3118810BDFFF7B6FF84F31188DD -:104A8000F9E70000034A516853685B1A9842FBD863 -:104A9000704700BF001000E08B60022308618B822A -:104AA000084670478368A3F1840243F8142C026916 -:104AB00043F8442C426943F8402C094A43F8242C1B -:104AC000C26843F8182C022203F80C2C002203F8C9 -:104AD0000B2C044A43F8102CA3F12000704700BFB0 -:104AE00051060008884B002008B5FFF7DBFFBDE842 -:104AF0000840FFF72BBF0000024BDB6898610F20D6 -:104B0000FFF726BF884B0020302383F31188FFF77F -:104B1000F3BF000008B50146302383F31188082055 -:104B2000FFF724FF002383F3118808BD064BDB68E1 -:104B300039B1426818605A60136043600420FFF77F -:104B400015BF4FF0FF307047884B00200368984234 -:104B500006D01A680260506099611846FFF7F6BEE9 -:104B60007047000038B504460D462068844200D1E5 -:104B700038BD036823605C608561FFF7E7FEF4E7FA -:104B800010B503689C68A2420CD85C688A600B6010 -:104B90004C602160596099688A1A9A604FF0FF331F -:104BA000836010BD1B68121BECE700000A2938BFA8 -:104BB0000A2170B504460D460A26601901F0BCFBB7 -:104BC00001F0A8FB041BA54203D8751C2E46044621 -:104BD000F3E70A2E04D9BDE87040012001F0F2BBD2 -:104BE00070BD0000F8B5144B0D46D96103F11001FA -:104BF00041600A2A1969826038BF0A220160486050 -:104C00001861A818144601F089FB0A2701F082FBFD -:104C1000431BA342064606D37C1C281901F08CFBDB -:104C200027463546F2E70A2F04D9BDE8F8400120AF -:104C300001F0C8BBF8BD00BF884B0020F8B50646A0 -:104C40000D4601F067FB0F4A134653F8107F9F4251 -:104C500006D12A4601463046BDE8F840FFF7C2BFFC -:104C6000D169BB68441A2C1928BF2C46A34202D92B -:104C70002946FFF79BFF224631460348BDE8F8402E -:104C8000FFF77EBF884B0020984B002010B4C0E98E -:104C9000032300235DF8044B4361FFF7CFBF0000FF -:104CA00010B5194C236998420DD0D0E900328168C3 -:104CB00013605A609A680A449A60002303604FF0B8 -:104CC000FF33A36110BD2346026843F8102F5360E1 -:104CD0000022026022699A4203D1BDE8104001F02F -:104CE00025BB936881680B44936001F013FB226934 -:104CF000E1699268441AA242E4D91144BDE8104027 -:104D0000091AFFF753BF00BF884B00202DE9F04779 -:104D1000DFF8BC8008F110072C4ED8F8105001F0D5 -:104D2000F9FAD8F81C40AA68031B9A423ED81444EA -:104D3000D5E900324FF00009C8F81C4013605A60F2 -:104D4000C5F80090D8F81030B34201D101F0EEFA66 -:104D500089F31188D5E9033128469847302383F336 -:104D600011886B69002BD8D001F0D4FA6A69A0EBE6 -:104D700004094A4582460DD2022001F023FB00229D -:104D8000D8F81030B34208D151462846BDE8F04764 -:104D9000FFF728BF121A2244F2E712EB090938BFC5 -:104DA0004A4629463846FFF7EBFEB5E7D8F81030FB -:104DB000B34208D01444211AC8F81C00A960BDE809 -:104DC000F047FFF7F3BEBDE8F08700BF984B002027 -:104DD000884B002000207047FEE70000704700006D -:104DE0004FF0FF307047000002290CD0032904D097 -:104DF0000129074818BF00207047032A05D8054835 -:104E000000EBC2007047044870470020704700BFA5 -:104E1000346C000848230020E86B000870B59AB095 -:104E20000546084601A9144600F0C2F801A8FCF79F -:104E3000EBFE431C5B00C5E9003400222370032312 -:104E40006370C6B201AB02341046D1B28E4204F197 -:104E5000020401D81AB070BD13F8011B04F8021C3B -:104E600004F8010C0132F0E708B5302383F3118810 -:104E70000348FFF71BFA002383F3118808BD00BF26 -:104E8000F84D002090F85C3003F01F02012A07D192 -:104E900090F85D200B2A03D10023C0E9143315E0FC -:104EA00003F06003202B08D1B0F860302BB990F8E4 -:104EB0005D20212A03D81F2A04D8FFF7D9B9222A56 -:104EC000EBD0FAE7034A02650722426583650120B9 -:104ED000704700BF3F23002007B5052917D8DFE83A -:104EE00001F0191603191920302383F31188104A91 -:104EF00001900121FFF780FA01980E4A0221FFF785 -:104F00007BFA0D48FFF79EF9002383F3118803B065 -:104F10005DF804FB302383F311880748FFF768F935 -:104F2000F2E7302383F311880348FFF77FF9EBE7BB -:104F3000886B0008AC6B0008F84D002038B50C4DAC -:104F40000C4C0D492A4604F10800FFF767FF05F1F4 -:104F5000CA0204F110000949FFF760FF05F5CA72A3 -:104F600004F118000649BDE83840FFF757BF00BFFD -:104F7000C052002048230020686B0008726B0008B4 -:104F80007D6B000870B5044608460D46FCF73CFEF4 -:104F9000C6B22046013403780BB9184670BD3246BC -:104FA0002946FCF71DFE0028F3D10120F6E700009A -:104FB0002DE9F84F05460C46FCF726FE2B49C6B2F4 -:104FC0002846FFF7DFFF08B10336F6B22849284626 -:104FD000FFF7D8FF08B11036F6B2632E0DD8DFF810 -:104FE0008C80DFF88C90234FDFF890A0DFF890B032 -:104FF0002E7846B92670BDE8F88F29462046BDE8D0 -:10500000F84F01F025BD252E2BD107224146284619 -:10501000FCF7E6FD58B9DBF800302360DBF804301C -:105020006360BBF80830238107350A34E0E70822C3 -:1050300049462846FCF7D4FD98B90F4BA21C1978B5 -:1050400009090232C95D02F8041C13F8011B01F0C2 -:105050000F015345C95D02F8031CF0D1183408351F -:10506000C6E704F8016B0135C2E700BF546C0008C5 -:105070007D6B00085C6C0008107AF01F1C7AF01F32 -:105080006E6A0008BFF34F8F024AD368DB03FCD47B -:10509000704700BF003C024008B5074B1B7853B96E -:1050A000FFF7F0FF054B1A69002ABFBF044A5A6098 -:1050B00002F188325A6008BD1E550020003C0240B3 -:1050C0002301674508B5054B1B7833B9FFF7DAFFB5 -:1050D000034A136943F00043136108BD1E550020C5 -:1050E000003C02400728F0B516D80C4C0C49237838 -:1050F0007BB90C4D0E4608234FF0006255F8047B37 -:1051000046F8042B013B13F0FF033A44F6D1012388 -:10511000237051F82000F0BD0020FCE7405500202E -:1051200020550020706C0008014B53F82000704798 -:10513000706C000808207047072810B5044601D994 -:10514000002010BDFFF7CEFF064B53F82430184463 -:10515000C21A0BB90120F4E712680132F0D1043B06 -:10516000F6E700BF706C0008072810B5044621D888 -:10517000FFF788FFFFF790FF0F4AF323D360C300C8 -:10518000DBB243F4007343F002031361136943F489 -:1051900080331361FFF776FFFFF7A4FF074B53F847 -:1051A000241000F055F9FFF78DFF2046BDE81040B0 -:1051B000FFF7C2BF002010BD003C0240706C000829 -:1051C000F8B512F00103144642D185182E4A9542D3 -:1051D00057D82E4B1B6813F0010352D02C4DFFF70C -:1051E0005BFFF323EB60FFF74DFF40F20127032C39 -:1051F00015D824F001046618254C401A40F2011716 -:10520000B142236900EB010524D123F0010323619E -:10521000FFF758FF0120F8BD043C0430E7E783079F -:10522000E7D12B6923F440732B612B693B432B613E -:1052300051F8046B0660BFF34F8FFFF723FF03683D -:105240009E42E9D02B6923F001032B61FFF73AFF5F -:105250000020E0E723F44073236123693B4323618B -:105260000B882B80BFF34F8FFFF70CFF2D8831F891 -:10527000023BADB2AB42C3D0236923F001032361EB -:10528000E4E71846C7E700BF0000080800380240FE -:10529000003C0240084908B50B7828B11BB9FFF75C -:1052A000FBFE01230B7008BD002BFCD0BDE80840BD -:1052B0000870FFF707BF00BF1E55002008B54FF468 -:1052C00080314FF0005000F0D5F809484FF43031EC -:1052D00000F0D0F807484FF4804100F0CBF8BDE86B -:1052E00008404FF470514FF4805000F0C3B800BF35 -:1052F0000000012000C003200846114601F00CBB4D -:10530000012001F009BB0000084601F023BB0000AA -:1053100070B582B0FFF79CFB0E4E054600F0FAFF19 -:105320003268904237BF0C4A0B49516814682EBF4F -:10533000D1E90041013151600419034641F10001F6 -:10534000284601913360FFF78DFB0199204602B09A -:1053500070BD00BF445500204855002070B582B094 -:10536000FFF776FB104E054600F0D4FF32689042FE -:1053700037BF0E4A0D49516814682EBFD1E900416C -:1053800001315160041941F10001034628460191A1 -:105390003360FFF767FB01994FF47A7200232046D0 -:1053A000FAF736FF02B070BD445500204855002082 -:1053B00010B50244064BD2B2904200D110BD441C3D -:1053C00000B253F8200041F8040BE0B2F4E700BF4C -:1053D000502800400F4B30B51C6F240407D41C6FBD -:1053E00044F400741C671C6F44F400441C670A4CAE -:1053F000236843F4807323600244084BD2B2904286 -:1054000000D130BD441C00B251F8045B43F8205079 -:10541000E0B2F4E70038024000700040502800403D -:1054200007B5012201A90020FFF7C2FF019803B0D0 -:105430005DF804FB13B50446FFF7F2FFA04205D068 -:10544000012201A900200194FFF7C4FF02B010BDA2 -:105450000144BFF34F8F064B884204D3BFF34F8FF5 -:10546000BFF36F8F7047C3F85C022030F4E700BFD2 -:1054700000ED00E00144BFF34F8F064B884204D398 -:10548000BFF34F8FBFF36F8F7047C3F870022030A8 -:10549000F4E700BF00ED00E070470000074B45F265 -:1054A00055521A6002225A6040F6FF729A604CF61A -:1054B000CC421A60024B01221A7070470030004043 -:1054C00054550020034B1B781BB1034B4AF6AA220C -:1054D0001A6070475455002000300040034B1A6892 -:1054E0001AB9034AD2F874281A6070475055002040 -:1054F00000300240024B4FF08072C3F874287047AE -:105500000030024008B5FFF7E9FF024B1868C0F30E -:10551000407008BD5055002008B5FFF7DFFF024B73 -:105520001868C0F3007008BD5055002070B5BFF377 -:105530004F8FBFF36F8F1A4A0021C2F85012BFF38A -:105540004F8FBFF36F8F536943F400335361BFF341 -:105550004F8FBFF36F8FC2F88410BFF34F8FD2F815 -:105560008030C3F3C900C3F34E335B0143F6E074EC -:1055700003EA0406014646EA81750139C2F8605221 -:10558000F9D2203B13F1200FF2D1BFF34F8F5369B3 -:1055900043F480335361BFF34F8FBFF36F8F70BD00 -:1055A00000ED00E0FEE7000070B5214B2148224AE3 -:1055B000904237D3214BDA1C121AC11E22F003028B -:1055C0008B4238BF00220021FCF726FB1C4A002337 -:1055D000C2F88430BFF34F8FD2F88030C3F3C900D4 -:1055E000C3F34E335B0143F6E07403EA040601465D -:1055F00046EA81750139C2F86C52F9D2203B13F1A9 -:10560000200FF2D1BFF34F8FBFF36F8FBFF34F8FD8 -:10561000BFF36F8F0023C2F85032BFF34F8FBFF339 -:105620006F8F70BD53F8041B40F8041BC0E700BF28 -:105630009C6E0008705600207056002070560020A6 -:1056400000ED00E070B5D0E91B439E6800224FF0EA -:10565000FF3504EB42135101D3F800090028BEBF07 -:10566000D3F8000940F08040C3F80009D3F8000BDC -:105670000028BEBFD3F8000B40F08040C3F8000BF9 -:10568000013263189642C3F80859C3F8085BE0D2A8 -:105690004FF00113C4F81C3870BD0000890141F0BF -:1056A0002001016103699B06FCD41220FFF7EAB9CF -:1056B00010B5054C2046FEF77BFE4FF0A043E36695 -:1056C000024B236710BD00BF58550020B46C000882 -:1056D00070B50378012B054650D12A4BC46E984211 -:1056E0001BD1294B5A6B42F080025A635A6D42F02B -:1056F00080025A655A6D5A6942F080025A615A69AD -:1057000022F080025A610E2143205B69FEF79AFC69 -:105710001E4BE3601E4BC4F800380023C4F8003E63 -:10572000C0232360EE6E4FF40413A3633369002B90 -:10573000FCDA012333610C20FFF7A4F93369DB079E -:10574000FCD41220FFF79EF93369002BFCDA002607 -:10575000A6602846FFF776FF6B68C4F81068DB6820 -:10576000C4F81468C4F81C684BB90A4BA3614FF025 -:10577000FF336361A36843F00103A36070BD064B70 -:10578000F4E700BF585500200038024040140040A4 -:1057900003002002003C30C0083C30C0F8B5C46EA5 -:1057A000054600212046FFF779FF296F00234FF0BF -:1057B00001128F68C4F834384FF00066C4F81C2812 -:1057C0004FF0FF3004EB431201339F42C2F80069EF -:1057D000C2F8006BC2F80809C2F8080BF2D20B68D5 -:1057E000EA6E6B67636210231361166916F0100688 -:1057F000FBD11220FFF746F9D4F8003823F4FE63FA -:10580000C4F80038A36943F4402343F01003A361B4 -:105810000923C4F81038C4F814380A4BEB604FF071 -:10582000C043C4F8103B084BC4F8003BC4F81069EF -:10583000C4F800396B6F03F1100243F480136A67F8 -:10584000A362F8BD906C000840800010C26E90F812 -:105850006610D2F8003823F4FE6343EA0113C2F85D -:10586000003870472DE9F84300EB8103C56EDA6814 -:10587000166806F00306731E022B05EB41130C4657 -:1058800080460FFA81F94FEA41104FF00001C3F84A -:10589000101B4FF0010104F1100398BFB60401FA88 -:1058A00003F391698EBF334E06F1805606F500462C -:1058B00000293AD0578A04F15801490137436F5003 -:1058C000D5F81C180B43C5F81C382B180021C3F859 -:1058D000101953690127611EA7409BB3138A928B4D -:1058E0009B08012A88BF5343D8F87420981842EACD -:1058F000034301F1400205EB8202C8F8740021461F -:1059000053602846FFF7CAFE08EB8900C3681B8A6C -:1059100043EA8453483464011E432E51D5F81C38A1 -:105920001F43C5F81C78BDE8F88305EB4917D7F885 -:10593000001B21F40041C7F8001BD5F81C1821EA10 -:105940000303C0E704F13F0305EB83030A4A5A60EF -:1059500028462146FFF7A2FE05EB4910D0F8003992 -:1059600023F40043C0F80039D5F81C3823EA0707B0 -:10597000D7E700BF0080001000040002026F126829 -:105980004267FFF75FBE00005831C36E49015B58A4 -:1059900013F4004004D013F4001F0CBF02200120B8 -:1059A000704700004831C36E49015B5813F4004052 -:1059B00004D013F4001F0CBF022001207047000028 -:1059C00000EB8101CB68196A0B6813604B68536068 -:1059D0007047000000EB810330B5DD68AA691368E9 -:1059E000D36019B9402B84BF402313606B8A1468BD -:1059F000C26E1C44013CB4FBF3F46343033323F055 -:105A0000030302EB411043EAC44343F0C043C0F830 -:105A1000103B2B6803F00303012B09B20ED1D2F81F -:105A2000083802EB411013F4807FD0F8003B14BF1C -:105A300043F0805343F00053C0F8003B02EB4112A7 -:105A4000D2F8003B43F00443C2F8003B30BD0000F5 -:105A50002DE9F041244DEE6E06EB40130446D3F8D9 -:105A6000087BC3F8087B38070AD5D6F8143819071D -:105A700006D505EB84032146DB6828465B6898471A -:105A8000FA071FD5D6F81438DB071BD505EB8403BE -:105A9000D968CCB98B69488A5A68B2FBF0F600FB2A -:105AA00016228AB91868DA6890420DD2121AC3E930 -:105AB0000024302383F311880B482146FFF78AFF27 -:105AC00084F31188BDE8F081012303FA04F26B89A5 -:105AD00023EA02036B81CB68002BF3D021460248F6 -:105AE000BDE8F041184700BF5855002000EB810386 -:105AF00070B5DD68C36E6C692668E6604A0156BB06 -:105B00001A444FF40020C2F810092A6802F0030278 -:105B1000012A0AB20ED1D3F8080803EB421410F49C -:105B2000807FD4F8000914BF40F0805040F000504E -:105B3000C4F8000903EB4212D2F8000940F0044017 -:105B4000C2F80009D3F83408012202FA01F1014336 -:105B5000C3F8341870BD19B9402E84BF40202060AE -:105B600020682E8A8419013CB4FBF6F440EAC44054 -:105B700040F000501A44C6E72DE9F8433B4DEE6E65 -:105B800006EB40130446D3F80889C3F8088918F0D7 -:105B9000010F4FEA40171AD0D6F81038DB0716D598 -:105BA00005EB8003D9684B691868DA68904230D2F7 -:105BB000121A4FF000091A60C3F80490302383F3DF -:105BC000118821462846FFF791FF89F3118818F0C4 -:105BD000800F1CD0D6F834380126A640334216D0A8 -:105BE00005EB8403ED6ED3F80CC0DCF8142001340F -:105BF000E4B2D2F800E005EB04342F44516871455B -:105C000015D3D5F8343823EA0606C5F83468BDE85C -:105C1000F883012303FA04F22B8923EA02032B8180 -:105C20008B68002BD3D0214628469847CFE7BCF895 -:105C30001000AEEB0103834228BF0346D7F81809D2 -:105C400080B2B3EB800FE2D89068A0F1040959F854 -:105C5000048FC4F80080A0EB09089844B8F1040F41 -:105C6000F5D818440B4490605360C7E7585500209E -:105C70002DE9F74FAC4CE56E6E69AB691E4016F42A -:105C800080586E6107D02046FEF700FC03B0BDE8E7 -:105C9000F04FFEF7ADB9002E12DAD5F8003EA2485B -:105CA0009B071EBFD5F8003E23F00303C5F8003E56 -:105CB000D5F8043823F00103C5F80438FEF712FCC8 -:105CC000370505D59848FFF7BDFC9748FEF7F8FB68 -:105CD000B0040CD5D5F8083813F0060FEB6823F4A0 -:105CE00070530CBF43F4105343F4A053EB603107DF -:105CF0001BD56368DB681BB9AB6923F00803AB6194 -:105D00002378052B0CD1D5F8003E87489A071EBF93 -:105D1000D5F8003E23F00303C5F8003EFEF7E2FB92 -:105D20006368DB680BB180489847F30200F1898013 -:105D3000B70227D5D4F86C90DFF8ECB100274FF00C -:105D4000010A09EB4712D2F8003B03F44023B3F5F4 -:105D5000802F11D1D2F8003B002B0DDA62890AFAAC -:105D600007F322EA0303638104EB8703DB68DB6844 -:105D700013B1394658469847236F01379B68FFB2E5 -:105D80009F42DED9F00617D5E76E3A6AC2F30A10D1 -:105D900002F00F0302F4F012B2F5802F00F09980A8 -:105DA000B2F5402F08D104EB83030022DB681B6AA5 -:105DB00007F5805790427ED13303D5F818481DD59A -:105DC000E70302D50020FFF743FEA50302D501201B -:105DD000FFF73EFE600302D50220FFF739FE2103E4 -:105DE00002D50320FFF734FEE20202D50420FFF7BC -:105DF0002FFEA30202D50520FFF72AFE77037FF5C9 -:105E000045AFE60702D50020FFF7B6FEA50702D58D -:105E10000120FFF7B1FE600702D50220FFF7ACFEBC -:105E2000210702D50320FFF7A7FEE20602D50420D2 -:105E3000FFF7A2FEA3067FF529AF0520FFF79CFE22 -:105E400024E7E36EDFF8E0A0019300274FF001099B -:105E5000236F9B685FFA87FB9B453FF669AF019B09 -:105E600003EB4B13D3F8001901F44021B1F5802F57 -:105E70001FD1D3F8001900291BDAD3F8001941F01B -:105E80009041C3F80019D3F800190029FBDB5946EB -:105E9000E06EFFF703FC218909FA0BF321EA030303 -:105EA000238104EB8B03DB689B6813B15946504692 -:105EB00098470137CCE7910708BFD7F80080072A39 -:105EC00098BF03F8018B02F1010298BF4FEA18282E -:105ED00070E7023304EB830207F580575268D2F86B -:105EE00018C0DCF80820DCE9001CA1EB0C0C002138 -:105EF00088420AD104EB830463689B699A68024470 -:105F00009A605A6802445A6056E711F0030F08BFBE -:105F1000D7F800808C4588BF02F8018B01F10101A0 -:105F200088BF4FEA1828E3E758550020C36E03EBFB -:105F30004111D1F8003B43F40013C1F8003B704716 -:105F4000C36E03EB4111D1F8003943F40013C1F8DB -:105F500000397047C36E03EB4111D1F8003B23F4C5 -:105F60000013C1F8003B7047C36E03EB4111D1F839 -:105F7000003923F40013C1F80039704730B5039C91 -:105F80000172043304FB0325C0E90653049B036339 -:105F90000021059BC160C0E90000C0E90422C0E9FE -:105FA0000842C0E90A11436330BD0000416A002283 -:105FB000C0E90411C0E90A22C2606FF00101FEF7D6 -:105FC000D1BD0000D0E90432934201D1C2680AB9C0 -:105FD000181D70470020704703691960C2680132BC -:105FE000C260C269134482690361934224BF436A59 -:105FF00003610021FEF7AABD38B504460D46E368EB -:106000003BB16269131D1268A3621344E36200206E -:1060100007E0237A33B929462046FEF787FD00289A -:10602000EDDA38BD6FF00100FBE70000C368C2691C -:10603000013BC3604369134482694361934224BFB7 -:10604000436A436100238362036B03B118477047BF -:1060500070B53023044683F31188866A3EB9FFF792 -:10606000CBFF054618B186F31188284670BDA36A98 -:10607000E26A13F8015BA362934202D32046FFF762 -:10608000D5FF002383F31188EFE700002DE9F84FD7 -:1060900004460E46174698464FF0300989F311889A -:1060A0000025AA46D4F828B0BBF1000F09D141461B -:1060B0002046FFF7A1FF20B18BF311882846BDE8E9 -:1060C000F88FD4E90A12A7EB050B521A934528BFA3 -:1060D0009346BBF1400F1BD9334601F1400251F802 -:1060E000040B43F8040B9142F9D1A36A40334036C4 -:1060F000A3624035D4E90A239A4202D32046FFF72F -:1061000095FF8AF31188BD42D8D289F31188C9E777 -:1061100030465A46FBF75AFDA36A5B445E44A362CD -:106120005D44E7E710B5029C0172043303FB0421D0 -:10613000C0E906130023C0E90A33039B0363049BF1 -:10614000C460C0E90000C0E90422C0E9084243631A -:1061500010BD0000026AC260426AC0E90422002247 -:10616000C0E90A226FF00101FEF7FCBCD0E904236C -:106170009A4201D1C26822B9184650F8043B0B601C -:10618000704700231846FAE7C368C2690133C36049 -:106190004369134482694361934224BF436A436164 -:1061A0000021FEF7D3BC000038B504460D46E36875 -:1061B0003BB123691A1DA262E2691344E362002025 -:1061C00007E0237A33B929462046FEF7AFFC0028C2 -:1061D000EDDA38BD6FF00100FBE7000003691960DC -:1061E000C268013AC260C269134482690361934282 -:1061F00024BF436A036100238362036B03B1184722 -:106200007047000070B530230D460446114683F3F5 -:106210001188866A2EB9FFF7C7FF10B186F311887F -:1062200070BDA36A1D70A36AE26A01339342A36240 -:1062300004D3E16920460439FFF7D0FF002080F342 -:106240001188EDE72DE9F84F04460D469046994632 -:106250004FF0300A8AF311880026B346A76A4FB977 -:1062600049462046FFF7A0FF20B187F3118830464A -:10627000BDE8F88FD4E90A073A1AA8EB0607974257 -:1062800028BF1746402F1BD905F1400355F8042BB2 -:1062900040F8042B9D42F9D1A36A4033A3624036F3 -:1062A000D4E90A239A4204D3E16920460439FFF76E -:1062B00095FF8BF311884645D9D28AF31188CDE733 -:1062C00029463A46FBF782FCA36A3B443D44A3625D -:1062D0003E44E5E7D0E904239A4217D1C3689BB155 -:1062E000836A8BB1043B9B1A0ED01360C368013BD9 -:1062F000C360C3691A44836902619A4224BF436A36 -:106300000361002383620123184670470023FBE7E3 -:1063100000F0D2B84FF08043586A70474FF0804386 -:10632000002258631A610222DA6070474FF08043FE -:106330000022DA60704700004FF0804358637047D6 -:10634000FEE7000070B51B4B01630025044686B0D4 -:10635000586085620E46FDF723FE04F11003C4E980 -:1063600004334FF0FF33C4E90635C4E90044A560A7 -:10637000E562FFF7CFFF2B460246C4E9082304F18C -:1063800034010D4A256580232046FEF785FB012355 -:10639000E0600A4A0375009272680192B268CDE922 -:1063A0000223074B6846CDE90435FEF79DFB06B096 -:1063B00070BD00BFF04D0020C06C0008C56C000827 -:1063C00041630008024AD36A1843D062704700BF95 -:1063D000884B00204B6843608B688360CB68C36048 -:1063E0000B6943614B6903628B6943620B6803600D -:1063F0007047000008B5264B26481A6940F2FF1185 -:106400000A431A611A6922F4FF7222F001021A612A -:106410001A691A6B0A431A631A6D0A431A651E4AEF -:106420001B6D1146FFF7D6FF02F11C0100F58060DD -:10643000FFF7D0FF02F1380100F58060FFF7CAFFD7 -:1064400002F1540100F58060FFF7C4FF02F1700112 -:1064500000F58060FFF7BEFF02F18C0100F580605F -:10646000FFF7B8FF02F1A80100F58060FFF7B2FF67 -:1064700002F1C40100F58060FFF7ACFF02F1E0011A -:1064800000F58060FFF7A6FFBDE8084000F088B87F -:106490000038024000000240CC6C000808B500F053 -:1064A000F3F9FEF7ADFAFFF719F8BDE80840FEF77B -:1064B00045BD0000704700000F4B1A6C42F001020E -:1064C0001A641A6E42F001021A660C4A1B6E936837 -:1064D00043F0010393604FF080436B229A624FF0C8 -:1064E000FF32DA6200229A615A63DA605A6001224E -:1064F0005A611A60704700BF00380240002004E073 -:106500004FF0804208B51169D3680B40D9B2C94336 -:106510009B07116107D5302383F31188FEF796FAA4 -:10652000002383F3118808BD1B4B1A696FEAC2521E -:106530006FEAD2521A611A69C2F308021A614FF067 -:10654000FF301A695A69586100215A6959615A69BC -:106550001A6A62F080521A621A6A02F080521A6253 -:106560001A6A5A6A58625A6A59625A6A0B4A106819 -:1065700040F480701060186F00F44070B0F5007F38 -:106580001EBF4FF4803018671967536823F40073F7 -:10659000536000F055B900BF003802400070004061 -:1065A000364B374A1A64374A4FF4404111601A6833 -:1065B00042F001021A601A689207FCD59A6822F02C -:1065C00003029A602D4B9A6812F00C02FBD11968F5 -:1065D00001F0F90119609A601A6842F480321A6079 -:1065E0001A689003FCD55A6F42F001025A67234B98 -:1065F0005A6F9107FCD5244A5A601A6842F080729B -:106600001A60204B5A685204FCD51A6842F4803252 -:106610001A605A68D003FCD51A6842F400321A6036 -:10662000184A53689903FCD5144B1A689201FCD59B -:10663000164A9A6040F20112C3F88C200022C3F877 -:106640009020134A40F207331360136803F00F03DE -:10665000072BFAD1094B9A6842F002029A609A68B5 -:1066600002F00C02082AFAD15A6C42F480425A64B1 -:106670005A6E42F480425A665B6E704700380240A0 -:106680000004001000700040106C4009009488382D -:10669000003C0240074A08B5536903F00103536107 -:1066A00023B1054A13680BB150689847BDE808400C -:1066B000FDF79EBC003C0140E8550020074A08B5A4 -:1066C000536903F00203536123B1054A93680BB188 -:1066D000D0689847BDE80840FDF78ABC003C0140FF -:1066E000E8550020074A08B5536903F004035361D5 -:1066F00023B1054A13690BB150699847BDE80840BA -:10670000FDF776BC003C0140E8550020074A08B57B -:10671000536903F00803536123B1054A93690BB130 -:10672000D0699847BDE80840FDF762BC003C0140D5 -:10673000E8550020074A08B5536903F01003536178 -:1067400023B1054A136A0BB1506A9847BDE8084067 -:10675000FDF74EBC003C0140E8550020164B10B53B -:106760005C6904F478725A61A30604D5134A936AEB -:106770000BB1D06A9847600604D5104A136B0BB171 -:10678000506B9847210604D50C4A936B0BB1D06B24 -:106790009847E20504D5094A136C0BB1506C984731 -:1067A000A30504D5054A936C0BB1D06C9847BDE89E -:1067B0001040FDF71DBC00BF003C0140E855002023 -:1067C000194B10B55C6904F47C425A61620504D52A -:1067D000164A136D0BB1506D9847230504D5134A23 -:1067E000936D0BB1D06D9847E00404D50F4A136E3A -:1067F0000BB1506E9847A10404D50C4A936E0BB1AF -:10680000D06E9847620404D5084A136F0BB1506FDD -:106810009847230404D5054A936F0BB1D06F98476E -:10682000BDE81040FDF7E4BB003C0140E855002006 -:1068300008B5FFF765FEBDE80840FDF7D9BB0000CD -:10684000062108B50846FDF7FDFB06210720FDF7E8 -:10685000F9FB06210820FDF7F5FB06210920FDF7CD -:10686000F1FB06210A20FDF7EDFB06211720FDF7BD -:10687000E9FB06212820FDF7E5FBBDE808400721DC -:106880001C20FDF7DFBB000008B5FFF74DFE00F050 -:106890000BF8FDF78BFDFDF763FCFFF70BFEBDE882 -:1068A0000840FFF735BD00000023054A19460133B3 -:1068B000102BC2E9001102F10802F8D1704700BFA5 -:1068C000E85500200B460146184600F02DB80000A0 -:1068D00000F040B8012838BF012010B5044620461A -:1068E00000F030F830B900F007F808B900F00CF803 -:1068F0008047F4E710BD0000024B1868BFF35B8FC0 -:10690000704700BF6856002008B5062000F084F8E4 -:106910000120FEF761FA0000024B0A4601461868A2 -:10692000FEF7EABC6823002010B5054C13462CB1D5 -:106930000A4601460220AFF3008010BD2046FCE766 -:1069400000000000024B01461868FEF7D9BC00BFEA -:1069500068230020024B01461868FEF7D5BC00BF33 -:106960006823002010B501390244904201D1002073 -:1069700005E0037811F8014FA34201D0181B10BDA8 -:106980000130F2E72DE9F041A3B1C91A17780144AB -:10699000044603F1FF3C8C42204601D9002009E067 -:1069A0000578BD4204F10104F5D10CEB0405D618BD -:1069B000A54201D1BDE8F08115F8018D16F801ED71 -:1069C000F045F5D0E7E700001F2938B504460D462D -:1069D00004D9162303604FF0FF3038BD426C12B16A -:1069E00052F821304BB9204600F030F82A460146D3 -:1069F0002046BDE8384000F017B8012B0AD0591CDA -:106A000003D1162303600120E7E7002442F8254064 -:106A1000284698470020E0E7024B01461868FFF738 -:106A2000D3BF00BF6823002038B5074D00230446BC -:106A3000084611462B60FEF7D3F9431C02D12B68A0 -:106A400003B1236038BD00BF6C560020FEF7C2B909 -:106A5000034611F8012B03F8012B002AF9D17047E6 -:106A60006F72672E6172647570696C6F742E4672F6 -:106A70006565666C7952544B0000000053544D33E9 -:106A800032463F3F3F3F3F3F0053544D333246373E -:106A90005B347C355D780053544D333246375B367A -:106AA0007C375D780000000040A2E4F16468910644 -:106AB0000041A3E5F265699207000000426164208D -:106AC00043414E496661636520696E6465782E00B6 -:106AD0008000000000800000000080000000000036 -:106AE00000000000F5240008D92C0008392C00080B -:106AF0000525000839250008352700080925000864 -:106B0000192500080D250008152500081125000885 -:106B10005D2600081D250008A52F00082D2500086A -:106B20003126000800000000DD400008C9400008D0 -:106B300005410008F1400008FD400008E940000858 -:106B4000D5400008C14000081141000800000000C5 -:106B5000010000000000000063300000586B0008D6 -:106B6000E04B0020F04D00204172647550696C6F5D -:106B7000740025424F415244252D424C0025534577 -:106B80005249414C250000000200000000000000B6 -:106B9000F942000865430008400040009052002080 -:106BA000A0520020020000000000000003000000CE -:106BB00000000000A94300080000000010000000D1 -:106BC000B0520020000000000100000000000000A2 -:106BD0005855002001010200D94E0008E94D000877 -:106BE000854E0008694E000843000000F06B000865 -:106BF00009024300020100C0320904000001020240 -:106C000001000524001001052401000104240202F2 -:106C10000524060001070582030800FF090401009E -:106C2000020A00000007050102400000070581027A -:106C300040000000120000003C6C0008120110012E -:106C40000200004009124157000201020301000046 -:106C50000403090425424F415244250030313233A8 -:106C60003435363738394142434445460000000048 -:106C70000040000000400000004000000040000014 -:106C800000000100000002000000020000000200FD -:106C900000000000FD440008B547000861480008F6 -:106CA00040004000D0550020D055002001000000D9 -:106CB000E0550020800000004001000005000000B9 -:106CC0006D61696E0069646C650000000010806A87 -:106CD00000000000AAAAAAAA00000064FFFF0000AA -:106CE0000000000000A00A0000000A0000000000F0 -:106CF000AAAAAAAA00000000FFFF000000000000EE -:106D0000990000000040000000000000AAAAAAAA02 -:106D100000000020FFFF0000000000000000000055 -:106D20000000000000000000AAAAAAAA00000000BB -:106D3000FFFF000000000000000000000000000055 -:106D400000000000AAAAAAAA00000000FFFF00009D -:106D50000000000000000000000000000000000033 -:106D6000AAAAAAAA00000000FFFF0000000000007D -:106D7000000000000000000000000000AAAAAAAA6B -:106D800000000000FFFF0000000000000000000005 -:106D900000000000000000000A00000000000000E9 -:106DA00003000000000000000000000000000000E0 -:106DB00000000000000000000000000000000000D3 -:106DC00000000000000000007894FF7F0100000038 -:106DD00004040000000000000000070000000000A4 -:106DE00040420F00FE2A0100D2040000FF00000014 -:106DF000000000007C6A000849040000896A00085D -:106E000051040000976A0008009600000000080086 -:106E1000960000000008000004000000506C00080C -:106E20000000000000000000000000000000000062 -:106E300000000000000000006C23002000000000A3 -:106E40000000000000000000000000000000000042 -:106E50000000000000000000000000000000000032 -:106E60000000000000000000000000000000000022 -:106E70000000000000000000000000000000000012 -:106E80000000000000000000000000000000000002 -:0C6E9000000000000000000000000000F6 +:100000000007002011020008B92C0008712C00081C +:10001000992C0008712C0008912C0008130200088C +:10002000130200081302000813020008AD3C000888 +:10003000130200081302000813020008130200084C +:10004000130200081302000813020008130200083C +:10005000130200081302000881630008A963000866 +:10006000D1630008F9630008216400081302000846 +:10007000130200081302000813020008130200080C +:10008000130200081302000813020008252C0008C0 +:10009000512C0008612C0008130200084964000874 +:1000A00013020008130200081302000813020008DC +:1000B0001D6500081302000813020008130200085F +:1000C00013020008130200081302000813020008BC +:1000D00013020008130200081302000813020008AC +:1000E000AD640008130200081302000813020008A0 +:1000F000130200081302000813020008130200088C +:10010000130200081302000813020008130200087B +:10011000130200081302000813020008130200086B +:10012000130200081302000813020008130200085B +:10013000130200081302000813020008130200084B +:100140001302000813020008130200085D5900089A +:10015000130200081302000813020008130200082B +:10016000130200081302000813020008130200081B +:10017000130200081302000813020008130200080B +:1001800013020008130200081302000813020008FB +:1001900013020008130200081302000813020008EB +:1001A00013020008130200081302000813020008DB +:1001B00013020008130200081302000813020008CB +:1001C00013020008130200081302000813020008BB +:1001D00013020008130200081302000813020008AB +:1001E000130200081302000813020008130200089B +:1001F000130200081302000813020008130200088B +:100200003D16000800000000000000000000000093 +:1002100002E000F000F8FEE772B6374880F3088885 +:10022000364880F3098836483649086040F20000B5 +:10023000CCF200004EF63471CEF200010860BFF33C +:100240004F8FBFF36F8F40F20000C0F2F0004EF608 +:100250008851CEF200010860BFF34F8FBFF36F8F5C +:100260004FF00000E1EE100A4EF63C71CEF20001B4 +:100270000860062080F31488BFF36F8F04F0CCFF72 +:1002800005F02EFF4FF055301F491B4A91423CBFED +:1002900041F8040BFAE71D49184A91423CBF41F866 +:1002A000040BFAE71A491B4A1B4B9A423EBF51F80E +:1002B000040B42F8040BF8E700201849184A914251 +:1002C0003CBF41F8040BFAE704F0E4FF05F05CFFE3 +:1002D000144C154DAC4203DA54F8041B8847F9E777 +:1002E00000F042F8114C124DAC4203DA54F8041BF2 +:1002F0008847F9E704F0CCBF000700200023002066 +:100300000000000808ED00E00001002000070020C8 +:10031000B86A000800230020CC230020D02300204E +:100320006C560020000200080402000804020008C5 +:10033000040200082DE9F04F2DED108AC1F80CD011 +:10034000D0F80CD0BDEC108ABDE8F08F002383F309 +:1003500011882846A047002004F046FAFEE704F082 +:10036000C5F900DFFEE70000F8B501F0CDF904F0B3 +:10037000CDFE074604F03CFF0546002839D1234B4B +:100380009F4236D001339F4236D0214B27F0FF02E7 +:100390009A4234D1F8B200F06FFF2E4642F2107448 +:1003A00000F070FF08B10024264601F05FFD20B187 +:1003B000032000F083F80024264635B1154B9F42F8 +:1003C00003D004F00DFF00242646002004F0A8FE10 +:1003D000114B1B695B0416D40EB100F085F801F0D7 +:1003E000F5FA00F0BBFF204600F01EF900F07CF8A3 +:1003F000F9E72E460024D3E704460126D0E7064657 +:100400004FF47A74CCE70024E9E700BF010007B09D +:10041000000008B0263A09B00008024008B501F013 +:1004200045F9A0F120035842584108BD07B541F2F3 +:100430001203022101A8ADF8043001F055F903B010 +:100440005DF804FB38B5302383F31188174803683F +:100450000BB104F095FA164A144800234FF47A7150 +:1004600004F084FA002383F31188124C236813B13B +:100470002368013B2360636813B16368013B6360D9 +:100480000D4D2B7833B963687BB9022001F008FA6F +:10049000322363602B78032B07D163682BB90220CA +:1004A00001F0FEF94FF47A73636038BDD023002069 +:1004B00045040008F0240020E8230020084B1870B1 +:1004C00003280CD8DFE800F008050208022001F03C +:1004D000DFB9022001F0D2B9024B00225A60704706 +:1004E000E8230020F0240020F8B501F0BFFC30B173 +:1004F000454B03221A70454B00225A60F8BD444B0D +:10050000444A1C4619680131F8D004339342F9D1AA +:100510006268414B9A42F1D9404B9B6803F10063FA +:1005200003F580339A42E9D204F02EFE04F040FE37 +:10053000002001F003F90220FFF7C0FF384B002133 +:100540001A6C19641A6E19661A6E5A6C59645A6ECE +:1005500059665A6E5A6942F080025A615A6922F00D +:1005600080025A615A691A6942F000521A611A6986 +:1005700022F000521A611B6972B64FF0E023C3F8F3 +:10058000084DD4E90004BFF34F8FBFF36F8F254AA6 +:10059000C2F88410BFF34F8F536923F48033536143 +:1005A000BFF34F8FD2F88030C3F3C905C3F34E3386 +:1005B0005B0143F6E07603EA060C29464CEA8177B4 +:1005C0000139C2F87472F9D2203B13F1200FF2D135 +:1005D000BFF34F8FBFF36F8FBFF34F8FBFF36F8F9B +:1005E000536923F4003353610023C2F85032BFF340 +:1005F0004F8FBFF36F8F302383F31188854680F3CD +:10060000088820477AE700BFE8230020F024002074 +:100610000000010820000108FFFF0008002300205F +:100620000038024000ED00E02DE9F04F93B0B74BE9 +:1006300000902022FF210AA89D6801F071F9B44AB8 +:100640001378A3B9B348012103601170302383F3F9 +:10065000118803680BB104F093F9AF4AAD48002349 +:100660004FF47A7104F082F9002383F31188009B20 +:1006700013B1AA4B009A1A60A94A009C1378032B65 +:100680001EBF00231370A54A4FF0000A18BF536025 +:10069000D3465646D146012001F0FAF824B19F4BCB +:1006A0001B68002B00F02B82002000F0FFFF03905E +:1006B000039B002B01DA00F099FE039B002BEDDB7E +:1006C000012001F0DBF8039B213B1F2BE3D801A2A3 +:1006D00052F823F0550700087D07000811080008AC +:1006E000970600089706000897060008A308000868 +:1006F000730A00088D090008EF090008170A0008AE +:100700003D0A0008970600084F0A000897060008EF +:10071000C10A0008F507000897060008050B000845 +:1007200061070008F507000897060008EF090008B0 +:100730009706000897060008970600089706000825 +:100740009706000897060008970600089706000815 +:10075000110800080220FFF761FE002840F0F9812F +:10076000009B0221BAF1000F08BF1C4605A841F208 +:100770001233ADF8143000F0B7FF8CE74FF47A7005 +:1007800000F094FF071EEBDB0220FFF747FE002876 +:10079000E6D0013F052F00F2DE81DFE807F0030A13 +:1007A0000D10133605230593042105A800F09CFFC6 +:1007B00017E056480421F9E75A480421F6E75A4859 +:1007C0000421F3E74FF01C08404600F0B9FF08F1A0 +:1007D00004080590042105A800F086FFB8F12C0F4D +:1007E000F2D1012000FA07F747EA0B0B5FFA8BFB07 +:1007F0004FF0000901F0E0F826B10BF00B030B2BD2 +:1008000008BF0024FFF712FE45E748480421CDE762 +:10081000002EA5D00BF00B030B2BA1D10220FFF76C +:10082000FDFD074600289BD0012000F087FF022035 +:10083000FFF744FE00261FFA86F8404600F08EFFC0 +:100840000446B0B10399A1F14002514251414046E2 +:1008500000F09CFF01360028EDD1BA46044641F273 +:100860001213022105A8ADF814303E4600F03CFFFB +:1008700011E70120FFF722FE2546244B9B68AB427F +:1008800007D9284600F05CFF013040F0678104354D +:10089000F3E7234B00251D70204BBA465D603E46B2 +:1008A000A8E7002E3FF45CAF0BF00B030B2B7FF49B +:1008B00057AF0220FFF702FE322000F0F7FEB0F142 +:1008C0000008FFF64DAF18F003077FF449AF0F4A59 +:1008D000926808EB050393423FF642AFB8F5807F7C +:1008E0003FF73EAF124B0193B84523DD4FF47A70CA +:1008F00000F0DCFE0390039A002AFFF631AF019B63 +:10090000039A03F8012B0137EDE700BF0023002015 +:10091000EC240020D023002045040008F02400200F +:10092000E823002004230020082300200C230020BB +:10093000EC230020C820FFF771FD074600283FF494 +:100940000FAF1F2D11D8C5F1200242450AAB25F08B +:10095000030028BF424683490192184400F0BAFFC1 +:10096000019A8048FF2100F0DBFF4FEAA8037D4990 +:100970000193C8F38702284600F0DAFF06460028F4 +:100980003FF46DAF019B05EB830533E70220FFF7D2 +:1009900045FD00283FF4E4AE00F018FF00283FF4C6 +:1009A000DFAE0027B846704B9B68BB4218D91F2F9B +:1009B00011D80A9B01330ED027F0030312AA134467 +:1009C00053F8203C05934046042205A901F006FA9D +:1009D00004378046E7E7384600F0B2FE0590F2E7BC +:1009E000CDF81480042105A800F07EFE02E7002364 +:1009F000642104A8049300F06DFE00287FF4B0AEDB +:100A00000220FFF70BFD00283FF4AAAE049800F087 +:100A1000C5FE0590E6E70023642104A8049300F0D6 +:100A200059FE00287FF49CAE0220FFF7F7FC002857 +:100A30003FF496AE049800F0C1FEEAE70220FFF70B +:100A4000EDFC00283FF48CAE00F0D0FEE1E7022080 +:100A5000FFF7E4FC00283FF483AE05A9142000F062 +:100A6000CBFE04210746049004A800F03DFE394661 +:100A7000B9E7322000F01AFE071EFFF671AEBB0781 +:100A80007FF46EAE384A926807EB090393423FF653 +:100A900067AE0220FFF7C2FC00283FF461AE27F0EA +:100AA00003074F44B9453FF4A5AE484600F048FE61 +:100AB0000421059005A800F017FE09F10409F1E7EB +:100AC0004FF47A70FFF7AAFC00283FF449AE00F01B +:100AD0007DFE002844D00A9B01330BD008220AA9CE +:100AE000002000F025FF00283AD02022FF210AA88C +:100AF00000F016FFFFF79AFC1C4803F07BFE13B0D2 +:100B0000BDE8F08F002E3FF42BAE0BF00B030B2B48 +:100B10007FF426AE0023642105A8059300F0DAFDDA +:100B2000074600287FF41CAE0220FFF777FC8046C2 +:100B300000283FF415AEFFF779FC41F2883003F04E +:100B400059FE059800F06AFF464600F035FF3C4626 +:100B5000A1E506464EE64FF0000901E6BA467EE6FC +:100B600037467CE6EC23002000230020A08601000D +:100B7000094A136849F2690099B21B0C00FB013362 +:100B80001360064B186844F2506182B2000C01FBFE +:100B90000200186080B27047182300201423002040 +:100BA00010B500211022044600F0BAFE034B03CB1F +:100BB000206061601868A06010BD00BF107AF01F4F +:100BC0002DE9F041ADF54E7D0DF134086CAC40F2ED +:100BD000751207460D460EA80021C8F8001000F057 +:100BE0009FFE4FF4C4720021204600F099FE02F0EF +:100BF0006BF8254B4FF47A72B0FBF2F0186093E873 +:100C00000700022384E807000DF5E9702382FFF74F +:100C1000C7FF40F204431D49238406A805F08EFD5A +:100C2000182384F832310DF2E3266B440DF1300CB9 +:100C30001A4603CA624530607160134606F1080621 +:100C4000F6D141460122204600F0EAFE002303933C +:100C5000AB7E029305F11903019380B20123CDE924 +:100C600004800093E97E06A3D3E90023384602F00E +:100C7000F3FB0DF54E7DBDE8F08100BFAFF30080C2 +:100C80009E6AC421818A46EEF82400204C67000841 +:100C90002DE9F0412C4C237ADAB080460D465BBB3F +:100CA00027A9284600F0CCFF0746002842D19DF82E +:100CB0009D60C82E3ED801464FF4A662204600F043 +:100CC0002FFE4FF48073C4F8F8314FF40073C4F86A +:100CD0000C334FF44073C4F8203432460DF19E01BA +:100CE00004F1090000F0F6FD26449DF89C3077726F +:100CF00023720BB9EB7E23728122002106AC27A858 +:100D000000F00EFE0122214627A800F0D5FF0023A7 +:100D10000393AB7E029305F1190380B2019328235C +:100D2000CDE904400093E97E05A3D3E900234046C2 +:100D300002F092FB5AB0BDE8F08100BFAFF3008033 +:100D400026417272DF25D7B718460020F0B5254E30 +:100D50004FF48A7505FB0065F1B096F8D83085F838 +:100D6000DC300024D822214685F8E8403AA800F07B +:100D7000D7FD06F1090000F0CBFDD5F8E4308DF881 +:100D8000F000C2B206AF06F109010DF1F100CDE9A4 +:100D90003A3400F09FFD394601223AA800F0B8FF2E +:100DA00080B2CDE9047008230127CDE9023706F1AE +:100DB000D803019330230093317A0B4807A3D3E97A +:100DC000002302F049FBA04206DD01F07DFFC5F8DB +:100DD000E000384671B0F0BD2046FBE778F6339F5F +:100DE00093CACD8D18460020103500202DE9F04122 +:100DF0001D4D1E4E1E4F86B0284602F059FB03467D +:100E000058B30024CDE90344ADF81440027B8DF8BB +:100E1000142099684068029403AA03C21B68DFF893 +:100E2000548043F00043029301F050FF821941F1D6 +:100E30000003009402A9384601F0FAF9A04205DD4A +:100E4000284602F039FB88F80040D5E798F80030D2 +:100E5000072B05D8013388F8003006B0BDE8F081D3 +:100E6000014802F029FBF8E71035002040420F004E +:100E7000403500204D4B002070B50D4614461E46EF +:100E800002F046FA50B9022E10D1012C0ED112A355 +:100E9000D3E90023C5E90023012007E0282C10D066 +:100EA00005D8012C09D0052C0FD0002070BD302CA6 +:100EB000FBD10BA3D3E90023ECE70BA3D3E9002379 +:100EC000E8E70BA3D3E90023E4E70BA3D3E900236E +:100ED000E0E700BFAFF30080401DA12026812A0B70 +:100EE00078F6339F93CACD8D9E6AC421818A46EEDF +:100EF00026417272DF25D7B7F017304A39059E5662 +:100F000038B505460E4C0021013500F03FFCA4F831 +:100F10002C55B4F82C0500F021FC78B1B4F82C0560 +:100F200000F02CFC014648B9B4F82C0500F02EFC6A +:100F3000B4F82C350133A4F82C35EAE738BD00BFEE +:100F40001846002010B50A4B0A4A1A6003F5805370 +:100F500093F860203AB9DC6D2CB1204601F008F816 +:100F6000204605F02BFBBDE81040034801F000B817 +:100F700040350020D0670008884500202DE9F04F5B +:100F80008FB000AF05460C4602F0C2F9002849D1E7 +:100F9000237E022B1BD1E38A012B18D101F094FE92 +:100FA0000646FFF7E5FD03464FF4C870DFF8C4823C +:100FB000B3FBF0F206F5167602FB103316FA83F354 +:100FC000C8F80030E37E33B9A34B00221A703C37D7 +:100FD000BD46BDE8F08F07F12401204600F0EEFD8C +:100FE0000028F4D107F11400FFF7DAFD97F8264046 +:100FF00007F11401224607F1270005F029FB00281C +:10100000E2D10F2C08D8944B1C70D8F80030A3F50F +:101010001673C8F80030DAE797F82410284602F073 +:101020006FF9D4E7E38A282B2BD010D8012B23D0DB +:10103000052BCCD1BFF34F8F8849894BCA6802F486 +:10104000E0621343CB60BFF34F8F00BFFDE7302B4F +:10105000BDD1844EE17E327A9142B8D1607E314674 +:10106000002291F8DC50854200F0A5800132042A6C +:1010700001F58A71F5D1AAE721462846FFF7A0FDC0 +:10108000A5E721462846FFF703FEA0E7B2F8EC509B +:101090007B6005F103094FEA99094FEA8902D11DE6 +:1010A000C908A8EBC1039D46EB460021584600F055 +:1010B00037FC04F1EE012A463144584600F00AFCA0 +:1010C0007B6813B9012000F039FB96F8D20000F0DC +:1010D00045FB044630B9307200F078FB204600F042 +:1010E0002DFBB1E0D6F8D4203AB996F8D200B6F884 +:1010F0002C25824201D8FFF703FFD6F8D4202A44DA +:10110000944208D296F8D200B6F82C2501308242DB +:1011100001D8FFF7F5FE70685FFA89F2594600F0D2 +:1011200007FC08B9C54679E0726896F8D2002A44EF +:101130007260D6F8D42005EB0209C6F8D49000F00E +:101140000DFB814509D396F8D220D6F8D4000132A0 +:10115000001B86F8D220C6F8D400FF2D0FD800243B +:10116000347200F033FB204600F0E8FA00F07EFE17 +:101170003D4B188108B9FFF7B7F9C54627E7BB68AB +:1011800096F8D9000AFB0362FB68D2F8E41082F8F3 +:10119000E83001F58061C2F8E030C2F8E410FFF7F2 +:1011A000D5FDFFF723FE96F8D920013202F00302A5 +:1011B00086F8D920B6E74FF48A7A0AFB02F505F1E2 +:1011C000EA013144204600F0CFFDF86000287FF4AA +:1011D000FEAE3544012285F8E82001F075FDD5F812 +:1011E000E020D6ED007ADFED216A801A192838BF99 +:1011F000192040F6B832904228BF1046B8EE677A00 +:1012000007EE900AF8EEE77A67EEA67ADFED186A45 +:10121000E7EE267AFCEEE77AC6ED007A96F8D9304A +:10122000BB60BA6873680AFB02F4321992F8E810DE +:1012300059B1D2F8E4108B42E8463FF427AF0021C1 +:1012400082F8E810C2F8E010C5467368064A9B0AA7 +:1012500001331381BBE600BF0935002000ED00E03B +:101260000400FA0518460020F8240020CDCCCC3D1F +:101270006666663F0C350020014B1870704700BF52 +:101280000425002030B54FF000542B4B22689A42C1 +:1012900085B007D003F0B6FF044620BB00242046EB +:1012A00005B030BD254B627D25481A70237D037241 +:1012B0004FF48073C0F8F8314FF40073C0F80C336A +:1012C00000254FF44073C0F820341E49C0F8E450A4 +:1012D000C922093000F0FEFA2046E022294600F03B +:1012E0001FFB0124DBE7184A184D136C43F0007311 +:1012F0001364AA6D164B9A42D0D12B6E013B7E2B04 +:10130000CCD8144A07CA01AB83E80700184603216A +:1013100000F07AFD6B6D83424FF00003BED12A6D61 +:101320008A4201BFAB65054B2A6E1A7003BF0A4B98 +:10133000EA6D1A601C46B2E79AAD44C50425002048 +:1013400018460020160000200038024000660040C9 +:101350005041A0B0586600401023002037B51A4D08 +:1013600000F084FD02236B71184B2881196818481E +:10137000012201F045FB00230193164B164900930F +:101380001648174B4FF4805201F092FF154B197815 +:1013900011B1124801F0B4FF01F096FC0446FFF7CA +:1013A000E7FB4FF4C873B0FBF3F202FB130304F541 +:1013B000167010FA83F00C4B186003F019FF08B197 +:1013C0000F232B8103B030BDF82400201023002010 +:1013D00040350020790E0008082500201035002037 +:1013E0007D0F0008042500200C3500202DE9F04F6A +:1013F0002DED028B0FF23829D9E90089834C93B087 +:101400000BAE9FED7E8BFFF7F1FC814FDFF828A23A +:1014100000230A93ADF834300B9373604FF0000B48 +:101420005B468DED008B01250DF11D0207A93846A5 +:101430008DF81C508DF81DB001F090FA9DF81C300D +:10144000002B40F0A580204601F062FF06460028F0 +:1014500045D1704F01F038FC3B6898423FD301F012 +:1014600033FC8246FFF784FB4FF4C873B0FBF3F202 +:1014700002FB13030AF5167010FA83F03860664F0A +:1014800097F800B0CBF1100ABBF1000F14BF334640 +:101490002B465FFA8AFA0EA88DF82830FFF780FBFA +:1014A000BAF1060F28BF4FF0060A0EAB03EB0B0193 +:1014B00052460DF1290000F00DFA0AAB03931823F0 +:1014C00002930AF10102554BD2B2CDE900530492C6 +:1014D00020464CA3D3E9002301F060FF3E7001F0E9 +:1014E000F3FB4F4A4F4D1368C31AB3F57A7F2ED3DF +:1014F000106001F0EBFB02460B46204601F0E6FFD0 +:10150000204601F005FF10B32B7A474E002B14BF85 +:1015100003230223737101F0D7FB0EAF4FF47A73EC +:101520000122B0FBF3F039463060304600F01EFB7C +:10153000182302933D4B019380B240F25513CDE93D +:101540000370009342464B46204601F027FF2B7A5A +:1015500093B101F0B9FB002607464FF48A7A95F85B +:10156000D900304400F003000AFB005393F8E82050 +:1015700092B30136042EF2D1C82003F03BF92B7A46 +:10158000002B7FF43DAF13B0BDEC028BBDE8F08FB4 +:10159000DAF8143083F04003CAF8143059461022A8 +:1015A0000EA800F0BDF90DF11E0308AA0AA93846DD +:1015B00000F03EFF96E803000FAB83E803009DF8C0 +:1015C00034308DF844300A9B0E930EA9DDE90823D0 +:1015D000204602F04FF921E7D3F8E02042B12B6812 +:1015E000FA2B38BFFA23BA1A0533B2EB430FC0D334 +:1015F000FFF7ACFB0028BCD1BEE700BF0000000035 +:1016000000000000401DA12026812A0B103500207B +:10161000403500200C350020093500200835002019 +:10162000484B002018460020F82400204C4B002096 +:10163000F1C6A7C1D068080F0000024008B50548F0 +:1016400000F092FFBDE80840034A0449002004F07E +:10165000AFBF00BF40350020884B0020450F000879 +:1016600070B50F4B1B780133DBB2012B0C4611D840 +:101670000C4D29684FF47A730E6AA2FB03320146BF +:1016800022462846B047844204D1074B00221A70F4 +:10169000012070BD4FF4FA7003F0ACF80020F8E7B9 +:1016A0001C230020004E00207C4B002007B50023A7 +:1016B000024601210DF107008DF80730FFF7D0FF3A +:1016C00020B19DF8070003B05DF804FB4FF0FF3038 +:1016D000F9E700000A4608B50421FFF7C1FF80F0D2 +:1016E0000100C0B2404208BD30B4054C2368DD693A +:1016F000044B0A46AC460146204630BC604700BF5A +:10170000004E0020A086010070B503F093FB094E47 +:10171000094D3080002428683388834208D903F0BB +:1017200083FB2B6804440133B4F5803F2B60F2D374 +:1017300070BD00BF7E4B0020504B002003F02ABC40 +:1017400000F1006000F580300068704700F1006033 +:10175000920000F5803003F0B3BB0000054B1A681F +:10176000054B1B889B1A834202D9104403F05CBBD3 +:1017700000207047504B00207E4B0020024B1B681E +:10178000184403F059BB00BF504B0020024B1B68AC +:10179000184403F069BB00BF504B002010F0030356 +:1017A0000AD1B0F5047F05D200F10050A0F57920F0 +:1017B000D0F80038184670470023FBE700F10050CE +:1017C000A0F57920D0F8100A70470000064991F87A +:1017D000243033B10023086A81F824300822FFF74F +:1017E000B5BF0120704700BF544B0020014B186863 +:1017F000704700BF002004E0F0B51E4B1D680138A3 +:101800002E0C0A181C48C5F30B0403233546078821 +:10181000A7420BD144680B46013C934218461BD2A9 +:1018200014F9010F48B103F8010BF6E7013B00F191 +:101830000800ECD191420ED20B4618462C24B6F586 +:10184000805F00F8014B0AD1824202D94122981CE4 +:101850005A70401AF0BD0846B6F5805FF9D041F2E3 +:1018600001039D42F5D18242F3D95A2300F8013B8E +:10187000EFE700BF002004E020230020022802BF81 +:10188000024B4FF480029A61704700BF0000024093 +:10189000022802BF014B40229A61704700000240BB +:1018A000022801BF024A536983F040035361704725 +:1018B0000000024070B504464FF47A764CB1412CDA +:1018C000254628BF412506FB05F002F093FF641B67 +:1018D000F4E770BD10B50023934203D0CC5CC45430 +:1018E0000133F9E710BD000010B5013810F9013FD0 +:1018F0003BB191F900409C4203D11AB10131013A48 +:10190000F4E71AB191F90020981A10BD1046FCE7CF +:1019100003460246D01A12F9011B0029FAD170477A +:1019200002440346934202D003F8011BFAE77047D2 +:101930002DE9F8431F4D144695F8242007468846A4 +:1019400052BBDFF870909CB395F824302BB920225D +:10195000FF2148462F62FFF7E3FF95F82400C0F10E +:101960000802A24228BF2246D6B24146920005EBA9 +:101970008000FFF7AFFF95F82430A41B1E44F6B299 +:10198000082E17449044E4B285F82460DBD1FFF7B9 +:101990001DFF0028D7D108E02B6A03EB82038342A6 +:1019A000CFD0FFF713FF0028CBD10020BDE8F8838C +:1019B0000120FBE7544B0020024B1A78024B1A70AF +:1019C000704700BF7C4B00201C23002010B5104C3A +:1019D000104802F05DFA21460E4802F085FA2468AC +:1019E000E26ED2F8043843F00203C2F804384FF430 +:1019F0007A70FFF75FFF0849204602F07DFBE26E38 +:101A0000D2F8043823F00203C2F8043810BD00BF36 +:101A1000BC680008004E0020C46800087047000041 +:101A20002DE9F0470D46044600219046284640F235 +:101A30007912FFF775FF234620220021284601F086 +:101A4000BBFE231D02222021284601F0B5FE631DA6 +:101A500003222221284601F0AFFEA31D03222521E7 +:101A6000284601F0A9FE04F1080310222821284687 +:101A700001F0A2FE04F1100308223821284601F0EB +:101A80009BFE04F1110308224021284601F094FE38 +:101A900004F1120308224821284601F08DFE04F1CA +:101AA000140320225021284601F086FE04F1180379 +:101AB00040227021284601F07FFE04F12003082215 +:101AC000B021284601F078FE04F121030822B82154 +:101AD000284601F071FE04F12207C0263B4631463C +:101AE00008222846083601F067FEB6F5A07F07F108 +:101AF0000107F3D104F1320308223146284601F0F0 +:101B00005BFE002704F1330A94F832304FEAC7092C +:101B10009F4209F5A47615D3B8F1000F08D13146DC +:101B200004F599730722284601F046FE09F24F1684 +:101B3000274694F832213B1B93420CD3F01DC0087A +:101B4000BDE8F0870AEB070308223146284601F07A +:101B500033FE0137D8E707F233133146082228460F +:101B600001F02AFE08360137E3E7000013B504460A +:101B70000846002101602346C0F80310202201908E +:101B800001F01AFE0198231D0222202101F014FE0B +:101B90000198631D0322222101F00EFE0198A31D6E +:101BA0000322252101F008FE019804F10803102208 +:101BB000282101F001FE072002B010BDF7B5002377 +:101BC000047F00910E4607221946054601F0B8FC35 +:101BD000731C0093012200230721284601F0B0FC6A +:101BE000C4B9B31C0093052223460821284601F0FE +:101BF000A7FC0D243746B278BB1B934211D32B7F31 +:101C0000A88A0734E408BBB9844294BF00200120AD +:101C100003B0F0BDAB8ADB00083BDB08B3700824DF +:101C2000E8E7FB1C0093214600230822284601F028 +:101C300087FC08340137DEE7201A18BF0120E7E7E8 +:101C4000F7B50023047F00910E4608221946054689 +:101C500001F076FC731CC4B9082200931146234698 +:101C6000284601F06DFC1024012372785F1C013BB3 +:101C7000934211D32B7FA88A0734E408BBB984426E +:101C800094BF0020012003B0F0BDAB8ADB00083B0D +:101C9000DB0873700824E7E7F3190093214600235B +:101CA0000822284601F04CFC08343B46DDE7201AA8 +:101CB00018BF0120E7E70000F8B50E4605461446B8 +:101CC000002181223046FFF72BFE2B4608220021FF +:101CD000304601F071FD7CB96B1C072208213046AB +:101CE00001F06AFD0F2401236A785F1C013B9342D7 +:101CF00004D3E01DC008F8BD0824F4E7EB19214621 +:101D00000822304601F058FD08343B46ECE700005D +:101D1000F8B50E46054614460021CE223046FFF7A0 +:101D2000FFFD2B4628220021304601F045FD7CB9FD +:101D300005F1080308222821304601F03DFD30243A +:101D40002F462A7A7B1B934204D3E01DC008F8BDBE +:101D50002824F5E707F1090321460822304601F05F +:101D60002BFD08340137ECE7F7B5047F00910E46F0 +:101D7000012310220021054601F0E2FBC4B9B31C87 +:101D80000093092223461021284601F0D9FB19248B +:101D900037467288BB1B9A4211D82B7FA88A07341A +:101DA000E408BBB9844294BF0020012003B0F0BD19 +:101DB000AB8ADB00103BDB0873801024E8E73B1D97 +:101DC0000093214600230822284601F0B9FB08347D +:101DD0000137DEE7201A18BF0120E7E730B5094DCB +:101DE0000A4491420DD011F8013B5840082340F3BA +:101DF0000004013B2C4013F0FF0384EA5000F6D1AD +:101E0000EFE730BD2083B8EDF7B54FF0FF33DFF8D3 +:101E100054C0DFF854E000EB81011A4688421CD020 +:101E200050F8044B019401AF042417F8015B82EAD7 +:101E300005620825DB18164605F1FF355241002ED4 +:101E4000BCBF83EA0C0382EA0E0215F0FF05F1D154 +:101E5000013C14F0FF04E8D1E0E7D843D14303B0DC +:101E6000F0BD00BF9336EAA9EBE1F042F7B53A4A7C +:101E7000106851686B4603C36A46384938480823DE +:101E800004F0F6FB0446002835D10A25354A1068CF +:101E900051686B4603C36A4633493148082304F04E +:101EA000E7FB044600284DD00369B3F5E02F49D87D +:101EB000B0F8662040F204418A4201D0552A41D14F +:101EC0002A4A224402F15C018B423BD35C3B244909 +:101ED00000209E1AFFF782FF3246074604F1640194 +:101EE0000020FFF77BFFA3689F422BD1E368984255 +:101EF00008BF002526E00369B3F5E02F29D8428BFF +:101F000040F204418A4201D0552A20D1174A224486 +:101F100002F110018B4218D3103B114900209D1A89 +:101F2000FFF75CFF2A46064604F118010020FFF780 +:101F300055FFA3689E4202D1E368984201D00D2567 +:101F4000A4E70025284603B0F0BD10259EE70C2528 +:101F50009CE70B259AE700BF94670008DCFF0600AA +:101F6000000001089D67000890FF06000800FFF7C9 +:101F700010B5037C044613B9006804F061FB2046E9 +:101F800010BD00000023BFF35B8FC360BFF35B8F06 +:101F9000BFF35B8F8360BFF35B8F7047BFF35B8FD3 +:101FA0000068BFF35B8F704770B505460C30FFF7D4 +:101FB000F5FF05F1080604463046FFF7EFFFA042A3 +:101FC00006D930466D68FFF7E9FF2544281A70BD31 +:101FD0003046FFF7E3FF201AF9E7000070B5054629 +:101FE000406898B105F10800FFF7D8FF05F10C062D +:101FF00004463046FFF7D2FF8442304694BF6D68F6 +:102000000025FFF7CBFF013C2C44201A70BD0000D7 +:1020100038B50C460546FFF7C7FFA04210D305F1BF +:102020000800FFF7BBFF04446868B4FBF0F100FB55 +:102030001144BFF35B8F0120AC60BFF35B8F38BDF1 +:102040000020FCE72DE9F041144607460D46FFF756 +:10205000C5FF844228BF0446D4B1B84658F80C6B7B +:102060004046FFF79BFF3044286040467E68FFF7FC +:1020700095FF331A9C4203D86C600120BDE8F081C3 +:102080006B60A41B3B68AB602044E8600220F5E76E +:102090002046F3E738B50C460546FFF79FFFA04200 +:1020A00010D305F10C00FFF779FF04446868B4FB16 +:1020B000F0F100FB1144BFF35B8F0120EC60BFF334 +:1020C0005B8F38BD0020FCE72DE9FF41884669465B +:1020D0000746FFF7B7FF6C4606B204EBC6060025BD +:1020E000B44209D06268206808EB0501FFF7F2FBF3 +:1020F000636808341D44F3E729463846FFF7CAFFF2 +:10210000284604B0BDE8F081F8B505460C300F460E +:10211000FFF744FF05F1080604463046FFF73EFF8F +:10212000A042304688BF6C68FFF738FF201A38603D +:1021300020B130462C68FFF731FF2044F8BD000085 +:1021400073B5144606460D46FFF72EFF844228BF9E +:1021500004460190DCB101A93046FFF7D5FF019B91 +:1021600033B93268C5E90233C5E9002401200CE027 +:102170009C4238BF01942860019868608442F5D978 +:102180003368AB60241AEC60022002B070BD2046B8 +:10219000FBE700002DE9FF410F466946FFF7D0FF3E +:1021A0006C4600B204EBC0050026AC4209D0D4F85E +:1021B000048054F8081BB8194246FFF78BFB4644CD +:1021C000F3E7304604B0BDE8F081000038B50546BD +:1021D000FFF7E0FF044601462846FFF719FF2046B7 +:1021E00038BD000010B4026854681A4623465DF8F2 +:1021F000044B1847002070470020704770470000CC +:10220000002070470E20704700F5805090F8C800FD +:10221000C0F340007047000000F5805090F9D000F6 +:102220007047000000F58050C0F8CC1001207047C6 +:10223000F7B50C68BDF8207014F0005470D10D7B18 +:10224000082D6DD8302585F311884569AE68760173 +:102250000CD4AC68240108D4AC6814F080545DD16F +:1022600084F31188204603B0F0BD01240E6804F108 +:10227000180C002EB8BFF6004FEA0C1CB4BF46F095 +:102280000406760545F80C600E680FFA84FC16F01B +:10229000804F18BF05EB0C1E05EB0C1C1EBFDEF8B3 +:1022A000806146F00206CEF880610E7BCCF8846136 +:1022B00005EB04158E68C5F88C614E68C5F8886119 +:1022C000DCF8805145F00105CCF8805100EB441654 +:1022D00041F268052E4405EB44150544C6E9002388 +:1022E00008350E4601F10C0C56F804EB45F804EBEA +:1022F0006645F9D1843436882E8000EB441407F00B +:102300000305267926F00B0635432571002484F356 +:102310001188009700F0FAFC0120A4E70224A5E749 +:102320004FF0FF309FE7000013B500F58054019196 +:10233000E06DFFF753FE1F280AD90199E06D2022B6 +:10234000FFF7C2FEA0F120035842584102B010BD71 +:102350000020FBE708B5302383F3118800F5805097 +:10236000C06DFFF70FFE002383F3118808BD000046 +:1023700000220260828142608260704710B50022B4 +:102380000023C0E900230023044603810C30FFF73B +:10239000EFFF204610BD0000F0B5054600F5805067 +:1023A0000C4690F8C83013F0040FC3F3800108BF47 +:1023B000114661F3820304F1840680F8C83005EB0E +:1023C000461389B01B79D8072ED57AB319072DD4B7 +:1023D0006846FFF7D3FF05EB441303F5835303F17E +:1023E000180703AA103318685968144603C4083341 +:1023F000BB422246F7D1186820609B88A380DDE9A4 +:102400000E23CDE900230123ADF808302B6869467F +:10241000DB6B2846984705EB46152B791A075CBFFE +:1024200043F008032B7101E0002AF4D109B0F0BD9C +:102430002DE9F0479A4688B00746884691463023F2 +:1024400083F3118807F580546846FFF797FFE06D26 +:10245000FFF7AAFD1F282AD9E06D20226946FFF761 +:10246000B5FE202823D103AD444605AB2E4603CE4E +:102470009E4220606160354604F10804F6D1306860 +:102480002060B388A380DDE90023C9E90023BDF8FB +:102490000830AAF80030002383F3118853464A46D7 +:1024A0004146384608B0BDE8F04700F01DBC0020AA +:1024B00080F3118808B0BDE8F08700002DE9F84FDF +:1024C0000023C0E90133254B044640F8183B0F4672 +:1024D000FFF74EFF04F12800FFF750FF04F1480812 +:1024E00004F582554646083530462036FFF746FF4C +:1024F000AE42F9D104F580554FF480534FF00009F6 +:10250000C5E91339C5F848800123EE6504F58758FD +:1025100004F58456C5F8549085F8583085F8603035 +:10252000083608F108084FF0000A4FF0000B46E9A2 +:1025300008ABA6F11800FFF71BFF203646F8289CD1 +:102540004645F4D185F8D07017B1054800F0B6FBC8 +:10255000044B63612046BDE8F88F00BFD0670008D8 +:10256000A86700080064004010B5044B19780446C1 +:102570004A1C1A70FFF7A2FF204610BD844B0020B2 +:102580002DE9F04300294FD0284B2948B0FBF1F04A +:1025900099428CBF0A2311235D1EB0FBF3F703FBA6 +:1025A0001703ECB22BB1022D2B46F5D80020BDE865 +:1025B000F0837E1EB6F5806FF8D2C4EBC40C0CF12C +:1025C00003034FEAE308C3F3C703A4EB030E08F1C8 +:1025D00001094FF47A755FFA8EF008FB055559FA38 +:1025E0008EFEB5FBFEF5B5F5617FC1BF0CF1FF3383 +:1025F000C3F3C703E01AC0B25C1C50FA84F40C4D5C +:102600007C43B5FBF4F4A142D0D1013BDBB20F2BEC +:10261000CCD80138C0B20728C8D800211071168064 +:102620009170D3700120C2E70846C0E73F420F0017 +:1026300080F9370370B505460E464FF47A746B691E +:102640005B6803F00103B34207D04FF47A7002F0E5 +:10265000D1F8013CF3D1204670BD0120FCE7000019 +:1026600030B54269936913F0700F16D000230B4CFC +:10267000936103F1840200EB421211794D0709D5F1 +:10268000890707D5416954F823508D60117941F0CD +:10269000040111710133032BEBD130BDBC6700087D +:1026A00073B51D46436916469A68D207044609D594 +:1026B0009A6801219960C2F34002CDE900650021CA +:1026C000FFF76AFE63699A68D1050BD59A684FF4E3 +:1026D00080719960C2F34022CDE900650121204656 +:1026E000FFF75AFE63699A68D2030BD59A684FF4D4 +:1026F00080319960C2F34042CDE900650221204655 +:10270000FFF74AFE04F58053D3F8CC0010B10368FC +:102710001B699847204602B0BDE87040FFF7A0BF94 +:10272000F8B504464669002972D106F10C073868ED +:10273000800770D006EB01153868D5F8B00110F0AD +:10274000040FD5F8B0011ABFC00840F00040400D9A +:10275000A061D5F8B0C11CF0020F1CBF40F0804052 +:10276000A061D5F8B40106EB011100F00F0084F868 +:102770002400D1F8B8012077D1F8B801000A6077B9 +:10278000D1F8B801000CA077D1F8B801000EE077BD +:10279000D1F8BC0184F82000D1F8BC01000A84F80B +:1027A0002100D1F8BC01000C84F82200D1F8BC1142 +:1027B000090E84F823103821396004F1340004F143 +:1027C000180104F1240551F8046B40F8046BA94288 +:1027D000F9D109880180C4E90A2321460023238610 +:1027E00051F8283B2046DB6B984704F5805393F85B +:1027F000C820D3F8CC0042F0040283F8C82010B1FE +:1028000003681B6998472046BDE8F840FFF728BFDA +:1028100006F110078BE7F8BD10B5044600F056FA34 +:1028200002460B4652EA030102D0013A63F100036B +:102830000449086820B12146BDE81040FFF770BF89 +:1028400010BD00BF804B0020F0B5302181F311880E +:10285000DFF848C000F583510831002404F18405F5 +:1028600000EB45152E7977070ED4F6060CD5D1E985 +:10287000007697429E4107D246695CF82470B760A3 +:102880002E7946F004062E710134032C01F120014B +:10289000E4D1002383F31188F0BD00BFBC670008BA +:1028A00008B5302383F31188FFF7DAFE002383F3A2 +:1028B000118808BDF8B543690546986800F0E050F6 +:1028C000B0F1E05F0F4621D0F8B1302383F31188D7 +:1028D00005F583541034002606F1840305EB4313F9 +:1028E0001B791A0706D50136032E04F12004F3D113 +:1028F000012007E05B07F6D42146384600F040FA95 +:102900000028F0D1002383F31188F8BD0120FCE7F3 +:1029100008B5302383F3118800F58050C06DFFF7B0 +:1029200043FB002383F3118843090CBF01200020DF +:1029300008BD0000F8B51D46002313700F4606467B +:102940001446FFF7E5FF80F00100387025B12946F5 +:102950003046FFF7AFFF2070F8BD00002DE9B84109 +:102960000C4615461F46804600F0B0F90B4621780C +:10297000024609B9287850B14046FFF765FFFFF7D6 +:102980008FFF3B462A462146FFF7D4FF0120BDE8D2 +:10299000B881000070B5302686F31188174B1A6C89 +:1029A00042F000721A641A6A42F000721A621A6ADD +:1029B00022F000721A62002383F3118800F580541C +:1029C00094F8C83013F0010516D1A9B186F3118827 +:1029D0000321132001F0CCF90321142001F0C8F9E0 +:1029E0000321152001F0C4F994F8C83043F0010325 +:1029F00084F8C83085F3118870BD00BF00380240EC +:102A00002DE9F04700F5805588B095F8D030012BBE +:102A100004468846164600F28180814F57F82320ED +:102A20000AB947F82300D7F800A0C4F80C80267430 +:102A3000BAF1000F64D095F8D030012B70D001218D +:102A40002046FFF7A7FF302383F3118862691368DC +:102A500023F0020313606269136843F001031360FB +:102A6000636900275F6187F3118801212046FFF722 +:102A7000E1FD002800F09580E86DFFF783FA04F58A +:102A80008359BA4609F10809202200216846FEF759 +:102A900047FF02A8FFF76CFCCDF818A06A4609EBC7 +:102AA00007030DF1180E9446BCE80300F4451860C6 +:102AB0005960624603F10803F5D1DCF800001860A4 +:102AC00020379CF804201A71602FDDD195F8C830AA +:102AD0006FF38203002785F8C8306A4641462046D6 +:102AE000ADF80070ADF802708DF80470FFF748FD86 +:102AF000636948BB4FF400421A6008B0BDE8F08734 +:102B000041F2D80003F05CFD814610B15146FFF759 +:102B1000D5FCC7F80090B9F1000F8CD10020ECE78C +:102B2000386803681B6B98470146002887D13868CE +:102B3000FFF730FF3868036832465B6841469847C4 +:102B400000287FF47CAFE9E761221A609DF802302B +:102B50009DF803201B06120402F4702203F0407358 +:102B60001343BDF80020C2F3090213439DF804206B +:102B70001205022E02F4E0020CBF4FF000410021CA +:102B8000134362690B43D361636913225A6162691B +:102B9000136823F00103136039462046FFF74AFD0E +:102BA00008B96369A6E795F8D03093BB6169D1F89D +:102BB000002242F00102C1F800226169D1F800222E +:102BC00022F47C5222F00E02C1F800226169D1F891 +:102BD000002242F46062C1F800226269C2F8143235 +:102BE0006269C2F80432626941F6FF71C2F80C12E0 +:102BF0006269C2F840326269C2F8443263690122F4 +:102C0000C3F81C226269D2F8003223F00103C2F833 +:102C1000003295F8C83043F0020385F8C8306CE7FD +:102C2000804B002008B500F051F850EA010302463D +:102C300002D0421E61F10001044B186810B10B462E +:102C4000FFF72EFDBDE8084001F068B8804B00207A +:102C500008B50020FFF7E0FDBDE8084001F05EB8D0 +:102C600008B50120FFF7D8FDBDE8084001F056B8CF +:102C700000B59BB0EFF3098168226846FEF72AFE93 +:102C8000EFF30583014B9B6BFEE700BF00ED00E017 +:102C900008B5FFF7EDFF000000B59BB0EFF3098129 +:102CA00068226846FEF716FEEFF30583014B5B6B67 +:102CB000FEE700BF00ED00E0FEE700000FB408B53E +:102CC000029801F03DFDFEE702F0BEB902F0A0B9A6 +:102CD00013B56C4684E80600031D94E8030083E8FE +:102CE0000500012002B010BD73B58568019155B192 +:102CF0001B885B0707D4D0E900369B6B9847019A85 +:102D0000C1B23046A847012002B070BDF0B5866858 +:102D100089B005460C465EB1BDF838305B070AD471 +:102D2000D0E900379B6B98472246C1B23846B0477E +:102D3000012009B0F0BD00220023CDE900230023CB +:102D4000ADF808300A4603AB01F108061068516877 +:102D50001C4603C40832B2422346F7D110682060F3 +:102D60009288A280FFF7B2FF0423ADF808302B68E9 +:102D7000CDE90001DB6B694628469847D8E700009B +:102D800030B503680968DD0FB5EBD17F23F06044EF +:102D900021F060424FEAD1700BD0002BB8BFA40CD9 +:102DA0000029B8BF920C944202D034BF0120002009 +:102DB00030BD944205D1C1F38070C3F38073834268 +:102DC000F6D194422CBF00200120F1E72DE9F0411B +:102DD000456A15B94162BDE8F0814B6823F0604750 +:102DE000C3F38A464FEAD37EC3F3807816EA2306FC +:102DF00038BF3E46AC462B465A68BEEBD27F22F027 +:102E000060440AD0002A18DAA40CB44217D19D42BB +:102E10000FD10D60DEE71346EEE7A74207D102F0BF +:102E20008044C2F3807242450BD054B1EFE708D220 +:102E3000EDE7CCF800100B60CDE7B44201D0B4420E +:102E4000E5D81A689C46002AE5D11960C3E700005E +:102E50002DE9F047089D01F007044FEAD508224408 +:102E600005F0070500EBD1004FF47F49944201D1F2 +:102E7000BDE8F08704F0070705F0070A57453E460E +:102E800038BF5646C6F10806111B8E4228BF0E46B3 +:102E9000E10808EBD50E415C13F80EC0B94029FAE1 +:102EA00006F721FA0AF1FFB28CEA010147FA0AF7A4 +:102EB00039408CEA010C03F80EC034443544D5E7A0 +:102EC00080EA0120082341F2210201B240000029DA +:102ED00080B203F1FF33B8BF504013F0FF03F4D1C9 +:102EE0007047000038B50C468D18A54200D138BD9A +:102EF00014F8011BFFF7E4FFF7E7000042684AB14E +:102F0000136843604389818901339BB299424381AD +:102F100038BF83811046704770B588B020220446C0 +:102F20000D4668460021FEF7FBFC20460495FFF79E +:102F3000E5FF024658B16B46054608AE1C4603CC79 +:102F4000B44228606960234605F10805F6D11046B1 +:102F500008B070BD082817D909280CD00A280CD051 +:102F60000B280CD00C280CD00D280CD00E2814BF28 +:102F70004020302070470C207047102070471420EC +:102F8000704718207047202070470000082817D984 +:102F90000C280CD910280CD914280CD918280CD9B5 +:102FA00020280CD930288CBF0F200E207047092014 +:102FB00070470A2070470B2070470C2070470D2087 +:102FC000704700002DE9F843078C072F04461ED9EF +:102FD000D0E9029800254FF6FF73C5F12006A5F150 +:102FE000200029FA05F108FA06F628FA00F0314324 +:102FF0000143C9B21846FFF763FF0835402D034669 +:10300000EBD1E1693A46BDE8F843FFF76BBF4FF6F5 +:10301000FF70BDE8F883000010B54B6823B9CA8A79 +:1030200063F30902CA8210BD04691A681C60036157 +:10303000C38A013BC3824A60EFE700002DE9F84FE5 +:103040001D46CB8A0F46C3F30901052981469246E6 +:103050000B4630D00020AAB207F11A049EB2042E0B +:103060001FFA80F80FD8904503F1010306D3FB8ABD +:103070000A4462F30903FB8201201AE01AF8006097 +:10308000E6540130EAE79045F1D2A1F1050B1C238B +:103090007C68BBFBF3F203FB12BB1FFA8BF6002C20 +:1030A00045D14846FFF72AFF044638B978606FF0EB +:1030B0000200BDE8F88F4FF00008E6E70026066042 +:1030C0007860ADB24FF0000B454510D90AEB08030C +:1030D000221D13F8011B9155B1B208F101081B29FB +:1030E0001FFA88F82BD0454506F10106F1D8FB8A76 +:1030F000C3F30902154465F30903BCE7013292B238 +:103100001C462368002BF9D16B1F0B441C21B3FB19 +:10311000F1F301339BB29A42D3D2BBF1000FD0D16D +:103120004846FFF7EBFE20B9C4F800B0BFE7012224 +:10313000E7E7C0F800B05E4620600446C1E74545B9 +:10314000D5D94846FFF7DAFE08B92060AFE7C0F8E6 +:1031500000B0002620600446B6E700002DE9F04FDD +:103160002DED028B1C4683B05B69019207468846B1 +:10317000002B00F09A80238C2BB1E269002A00F02A +:103180009480072B35D807F10C00FFF7B7FE0546F2 +:1031900038B96FF00205284603B0BDEC028BBDE8DC +:1031A000F08F14220021FEF7BBFB228CE16905F1B0 +:1031B0000800FEF78FFB208C013080B2FFF7E6FE9F +:1031C000FFF7C8FE013880B220840130287463699B +:1031D000228C1B782A4403F01F0363F03F0348F05E +:1031E00000411372384669602946FFF7EFFD01255B +:1031F000D1E700F10C034FF0000908EE103A4FF050 +:10320000800A4E464D4618EE100AFFF777FE8346B9 +:103210000028BED014220021FEF782FB002E3AD1F6 +:10322000019BABF8083002220BF1080E1FFA82FC5A +:103230000CF10100BCF1060F218C80B201D88E4246 +:103240002BD3FFF7A3FEFFF785FE626912780138E2 +:1032500002F01F028E4208BF4FF0400A42EA4912B4 +:103260001BFA80F14AEA020A013048F0004281F874 +:1032700008A08BF81000CBF8042059463846FFF719 +:10328000A5FD238C0135B3422DB289F001094FF021 +:10329000000AB8D17FE70022C6E7E169895D0EF830 +:1032A00002100136B6B20132C0E76FF0010572E7D5 +:1032B000F8B515460E463022002104461F46FEF79B +:1032C0002FFB069B6360B5F5001F079BA76034BF0B +:1032D0006A094FF6FF72A36297B2E66104F110002B +:1032E00000239A4206D800230360A782E382238347 +:1032F000E360F8BD0660013330462036F1E7000098 +:1033000003781BB94BB2002BC8BF01707047000097 +:1033100000787047F8B50C46C969074611B9238C87 +:10332000002B37D1257E1F2D34D8387828BB228C2E +:10333000072A2CD8268A36F003032BD14FF6FF70CC +:10334000FFF7D0FD20F001003102400441EA0561A1 +:10335000400C41EA40254FF6FF7223462946384685 +:10336000FFF7FCFE002807DD626913780133DBB24A +:103370001F2B88BF00231370F8BD218A2D0645EA54 +:10338000012505432046FFF71DFE0246E5E76FF0E5 +:103390000300F1E76FF00100EEE7000070B58AB0BE +:1033A000044616460021282268461D46FEF7B8FA54 +:1033B000BDF83830ADF810300F9B05939DF84030C4 +:1033C0008DF81830119B07936946BDF84830ADF869 +:1033D00020302046CDE90265FFF79CFF0AB070BDA2 +:1033E0002DE9F041D36905460C4616460BB9138CFE +:1033F0005BBB377E1F2F28D895F80080B8F1000FEF +:1034000026D03046FFF7DEFD3378210241EAC33192 +:1034100041EA0801338A41EA076141EA0341024671 +:10342000334641F080012846FFF798FE00280ADD68 +:103430003378012B07D1726913780133DBB21F2B6C +:1034400088BF00231370BDE8F0816FF00100FAE738 +:103450006FF00300F7E70000F0B58BB004460D46AF +:1034600017460021282268461E46FEF759FA9DF8A5 +:103470004C305A1E534253418DF800309DF8403075 +:10348000ADF81030119B05939DF848308DF8183039 +:10349000149B07936A46BDF85430ADF82030294696 +:1034A0002046CDE90276FFF79BFF0BB0F0BD000090 +:1034B000406A00B104307047436A1A684262026988 +:1034C0001A600361C38A013BC38270472DE9F04152 +:1034D000D0F82080194E14461D464146002709B9F0 +:1034E000BDE8F081D1E90223A21A65EB03039642FD +:1034F00077EB03031ED2036A8B420DD1FFF78CFDDD +:10350000036A1B68036203690B60C38A0161016A75 +:10351000013BC3828846E2E7FFF77EFD0B68C8F8EF +:10352000003003690B60C38A0161013BC382D8F894 +:103530000010D4E788460968D1E700BF80841E00E8 +:103540002DE9F04F8BB00D46DDF8509014469B46A8 +:103550008046002800F01981B9F1000F00F01581B4 +:10356000531E3F2B00F21181012A03D1BBF1000F42 +:1035700040F00B810023CDE90833B8F81430B5EBE7 +:10358000C30F4FEAC30703D300200BB0BDE8F08F91 +:103590002B199F42D8F80C303ABF7F1BFFB2274649 +:1035A0001BB9D8F81030002B7AD0272D4ED8C5F192 +:1035B0002806B7424FF000032CBFF6B23E460093F8 +:1035C0002946D8F8080008AB3246FFF741FCA7EBC4 +:1035D000060A35445FFA8AFAB8F8143003F100534A +:1035E000053BDB000493D8F80C3003932821039BA0 +:1035F00013B1BAF1000F2CD1D8F8100040B1BAF1D4 +:10360000000F05D0009608AB5246691AFFF720FC60 +:1036100038B2002FB8D066070AD00AAB03EBD4014A +:10362000624211F8083C02F00702134101F8083C1D +:10363000082C3CD9102C40F2B580202C40F2B780E9 +:10364000BBF1000F00F09C80082334E0BA4600264E +:10365000C2E7049BE02B28BFE02306930B44AB4258 +:10366000059314D95A1B03980096924534BF5246CD +:10367000D2B2691A08AB04300792FFF7E9FB079A48 +:103680001644AAEB020A1544F6B25FFA8AFA049BC2 +:10369000069A05999B1A0493039B1B680393A6E75C +:1036A0000093D8F8080008AB3A462946AEE7BBF1CC +:1036B000000F13D00123B4EBC30F6CD0082C12D829 +:1036C0009DF82030621E23FA02F2D50706D54FF08E +:1036D000FF3202FA04F423438DF820309DF82030A5 +:1036E00089F8003051E7102C12D8BDF82030621E46 +:1036F00023FA02F2D10706D54FF0FF3202FA04F4A2 +:103700002343ADF82030BDF82030A9F800303CE765 +:10371000202C0FD80899631E21FA03F3DA0705D588 +:103720004FF0FF3202FA04F40C430894089BC9F8E6 +:1037300000302AE7402C2BD0DDE90865611EC4F17A +:103740002102A4F1210326FA01F105FA02F225FA79 +:1037500003F311431943CB0712D50122A4F120032F +:10376000C4F1200102FA03F322FA01F1A24052420D +:1037700043EA010363EB430332432B43CDE90823C0 +:10378000DDE90823C9E90023FFE66FF00100FCE64C +:103790006FF00800F9E6082CA0D9102CB3D9202C22 +:1037A000EED8C3E7BBF1000FADD0022383E7BBF136 +:1037B000000FBBD004237EE730B5012A144638BF82 +:1037C0000124402C85B028BF40240025012ACDE9E2 +:1037D000025518D81B788DF8083063070AD004AB5F +:1037E00003EBD405624215F8083C02F0070293404F +:1037F00005F8083C009103462246002102A8FFF785 +:1038000027FB05B030BD082AE4D9102A03D81B884D +:10381000ADF80830E1E7202A8DBFD3E900231B680B +:103820000293CDE90223D8E710B5CB681BB98B60B2 +:103830000B618B8210BD04691A681C600361C38A26 +:10384000013BC382CA60F0E703064CBFC0F3C0303F +:103850000220704708B50246FFF7F6FF022806D19E +:103860005306C2F30F2001D100F0030008BDC2F3DC +:103870000740FBE72DE9F04F93B0CDE903230A6839 +:1038800004461046FFF7E0FF022814BFC2F30626E5 +:103890000026002A0D46824680F2F28112F0C049CD +:1038A00040F0EE81097B002900F0EA81022803D074 +:1038B0002378B34240F0E781C2F3046306931046D5 +:1038C00002F07F030593FFF7C5FF059B29444FEAEC +:1038D000834848EA0A4848EA4668CE78002300222E +:1038E000CDE90823F309834648EA0008029367D02C +:1038F000059B009302466768534608A92046B847CF +:10390000002800F0C381276A4FB9414604F10C003A +:10391000FFF702FB074690B96FF0020054E03B69E5 +:1039200098450DD03F68002FF9D1414604F10C00B5 +:10393000FFF7F2FA07460028EED0236A3B602762C1 +:1039400097F817C006F01F08CCF3840CACEB080006 +:103950001FFA80FE0028B8BF0EF12000A8EB0C0370 +:103960001FFA83FED7E90221B8BF00B2002B0793EC +:10397000BEBF0EF120031BB2079352EA010338D0F9 +:10398000039BDFF824E39A1A049B4FF0000C63EBCF +:10399000010196457CEB01032BD36B7B97F81AE072 +:1039A000734519D1029B002B78D0012821DC78685F +:1039B000F8B9DFF8F0C2944570EB010316D337E095 +:1039C000276A27B96FF00C0013B0BDE8F08F3B6990 +:1039D0009845B5D03F68F4E7B24890427CEB0103CC +:1039E00001D30020F0E7029B002BFAD0079B0F2B9E +:1039F00017DCFA7DB30002F0030203F07C031343EB +:103A0000FB7539462046FFF707FB6B7BBB76029BB5 +:103A10003BB9FB7DC3F38402013262F38603FB757D +:103A2000D0E76A7BBB7E9A42DBD1029B002B35D06C +:103A3000B309022B32D0039BBB60049BFB601422B2 +:103A400000210DA8FDF76CFF039B0A93049B0B93C9 +:103A50002B1D0C932B7BADF83EB0013BDBB2ADF8D8 +:103A60003C30069B8DF84230059B8DF8433094F82E +:103A70002C308DF840A083F001038DF844308DF890 +:103A80004180A3680AA920469847FB7DC3F38403BD +:103A9000013303F01F039B02FB82A2E7FB7DC6F309 +:103AA0004012B2EBD31F40F0F480C3F384034345CC +:103AB00040F0F280029A2B7BB609002A4DD0F20723 +:103AC0005DD4032B40F2EB80039BBB60049BFB6047 +:103AD0002B7BAE1D033BDBB23246394604F10C00B2 +:103AE000FFF7ACFA00280CDA39462046FFF794FAC3 +:103AF000FB7DC3F38403013303F01F039B02FB82AE +:103B00000AE7DDE90884AB883B834FF6FF73C9F110 +:103B10002000A9F1200228FA09F104FA00F001437B +:103B200024FA02F211431846C9B2FFF7C9F909F1A4 +:103B30000809B9F1400F0346E9D1B8822A7B033A5C +:103B4000D2B23146FFF7CEF9FB7DB882DA43C2F339 +:103B5000C01262F3C713FB7543E786B92E1D013B04 +:103B6000DBB23246394604F10C00FFF767FA002851 +:103B7000BADB2A7BB88A013AD2B23146E2E7F98A47 +:103B8000C1F30901013B0429DAB25BD8281D0023E7 +:103B900007F11B069A4208D910F801CB06F801C0BC +:103BA000013101330529DBB2F4D103990A9104995B +:103BB0000B91934207F11B010C9138BF04337968D4 +:103BC0000D9134BF55FA83F300230E93FB8AADF8B1 +:103BD0003EB0C3F309031A44069B8DF84230059B9F +:103BE0008DF8433094F82C30ADF83C2083F001037D +:103BF0008DF8443000238DF840A08DF841807B6023 +:103C00002A7BB88A013A291DFFF76CF93B8BB882F1 +:103C1000834203D1A3680AA92046984720460AA9EF +:103C2000FFF702FEFB7DBA8AC3F38403013303F07E +:103C30001F039B02FB823B8B9A420CBF00206FF05C +:103C40001000C1E67B68002BAFD0052001E01C30DE +:103C500033461E68002EFAD1091A081D2E1D18447D +:103C600001EB090CBCF11B0F5FFA89F39DD89A4256 +:103C70009BD916F8013B00F8013B09F10109EFE778 +:103C80006FF00900A0E66FF00A009DE66FF00B00F0 +:103C90009AE66FF00D0097E66FF00E0094E66FF075 +:103CA0000F0091E640420F0080841E00EFF309836D +:103CB00005494A6B22F001024A63683383F309889D +:103CC000002383F31188704700EF00E0302080F379 +:103CD000118862B60D4B0E4AD96821F4E0610904DF +:103CE000090C0A43DA60D3F8FC200A4942F08072DA +:103CF000C3F8FC20084AC2F8B01F116841F0010166 +:103D000011602022DA7783F82200704700ED00E08E +:103D10000003FA0555CEACC5001000E010B5302305 +:103D200083F311880E4B5B6813F4006314D0F1EE3B +:103D3000103AEFF30984683C4FF08073E361094B5C +:103D4000DB6B236684F3098800F0C4FC10B1064BDA +:103D5000A36110BD054BFBE783F31188F9E700BFB2 +:103D600000ED00E000EF00E05F03000862030008E0 +:103D700000F1604303F561430901C9B283F8001300 +:103D8000012200F01F039A4043099B0003F16043A6 +:103D900003F56143C3F880211A60704702684368E5 +:103DA0001143016003B118477047000013B5446B1D +:103DB000D4F894341A681178042915D1217C022989 +:103DC00012D11979128901238B4013420CD101A918 +:103DD00004F14C0002F040F8D4F89444019B21799E +:103DE0000246206800F0D6F902B010BD143001F090 +:103DF000C3BF00004FF0FF33143001F0BDBF00001F +:103E00004C3002F095B800004FF0FF334C3002F018 +:103E10008FB80000143001F091BF00004FF0FF3167 +:103E2000143001F08BBF00004C3002F061B800008C +:103E30004FF0FF324C3002F05BB8000000207047BA +:103E400010B5D0F894341A6811780429044617D1B3 +:103E5000017C022914D15979528901238B401342E4 +:103E60000ED1143001F024FF024648B1D4F8944436 +:103E70004FF4807361792068BDE8104000F078B994 +:103E800010BD0000406BFFF7DBBF00007047000073 +:103E90007FB5124B036000234360C0E90233012564 +:103EA00002260F4B057404460290019300F1840230 +:103EB000294600964FF48073143001F0D5FE094B6B +:103EC0000294CDE9006304F523724FF48073294610 +:103ED00004F14C0001F09CFF04B070BD10680008B4 +:103EE000853E0008AD3D00080B68302282F3118842 +:103EF0000A7903EB820210624A790D3243F82200FC +:103F00008A7912B103EB820318620223C0F8941479 +:103F10000374002080F311887047000038B5037FD8 +:103F2000044613B190F85430ABB9201D012502218D +:103F3000FFF734FF04F1140025776FF0010100F062 +:103F400081FC84F8545004F14C006FF00101BDE88D +:103F5000384000F077BC38BD10B50121044604306C +:103F6000FFF71CFF0023237784F8543010BD0000B6 +:103F700038B504460025143001F08EFE04F14C00E3 +:103F8000257701F05DFF201D84F854500121FFF7D3 +:103F900005FF2046BDE83840FFF752BF90F85C307F +:103FA00003F06003202B07D190F85D20212A4FF009 +:103FB000000303D81F2A06D800207047222AFBD10D +:103FC000C0E9143303E0034A0265072242658365B2 +:103FD000012070473823002037B5D0F894341A6890 +:103FE0001178042904461AD1017C022917D11979C4 +:103FF000128901238B40134211D100F14C05284650 +:1040000001F0DEFF58B101A9284601F025FFD4F8E0 +:104010009444019B21790246206800F0BBF803B06C +:1040200030BD0000F0B500EB810385B01E6A044688 +:104030000D46FEB1302383F3118804EB8507301D54 +:104040000821FFF7ABFEFB685B691B6806F14C00BB +:104050001BB1019001F00EFF019803A901F0FCFED5 +:10406000024648B1039B2946204600F093F80023FE +:1040700083F3118805B0F0BDFB685A691268002A05 +:10408000F5D01B8A013B1340F1D104F15C02EAE751 +:104090000D3138B550F82140DCB1302383F311885D +:1040A000D4F894241368527903EB8203DB689B698C +:1040B0005D6845B104216018FFF770FE294604F1E0 +:1040C000140001F0FFFD2046FFF7BAFE002383F342 +:1040D000118838BD7047000001F060B910B50123A8 +:1040E0000446282200F8243B0021FDF719FC002398 +:1040F000C4E9013310BD000038B50446302383F312 +:1041000011880025C0E90355C0E90555C0E90755E8 +:10411000416001F053F90223237085F3118828468A +:1041200038BD000070B500EB810305465069DA60C8 +:104130000E46144618B110220021FDF7F1FBA069CC +:1041400018B110220021FDF7EBFB31462846BDE8EF +:10415000704001F0FDB90000826802F00112826037 +:104160000022C0E90422C0E90622026201F07CBA02 +:10417000F0B400EB81044789E4680125A4698D400F +:104180003D43458123600023A2606360F0BC01F0E1 +:1041900097BA0000F0B400EB81040789E4680125B8 +:1041A00064698D403D43058123600023A260636004 +:1041B000F0BC01F011BB000070B5022300250446DD +:1041C0000370C0E90255C0E90455C0E906554566CB +:1041D000056280F84C5001F057F963681B6823B101 +:1041E00029462046BDE87040184770BD0378052B6E +:1041F00010B504460AD080F8683005230370436880 +:104200001B680BB1042198470023A36010BD000078 +:104210000178052906D190F86820436802701B6870 +:1042200003B118477047000070B590F84C30044651 +:1042300013B1002380F84C3004F15C02204601F0F9 +:1042400035FA63689B68B3B994F85C3013F0600585 +:1042500035D00021204601F0E9FC0021204601F084 +:10426000DBFC63681B6813B10621204698470623D0 +:1042700084F84C3070BD204698470028E4D0B4F84C +:104280006230626D9A4288BF636594F95C30656DF7 +:10429000002B4FF0300380F20381002D00F0F280FC +:1042A000092284F84C2083F311880021D4E91423D7 +:1042B0002046FFF76FFF002383F31188DAE794F8B5 +:1042C0005D2003F07F0343EA022340F2023293426F +:1042D00000F0C58021D8B3F5807F48D00DD8012BE0 +:1042E0003FD0022B00F09380002BB2D104F1640286 +:1042F000226502226265A365C1E7B3F5817F00F004 +:104300009B80B3F5407FA4D194F85E30012BA0D1FF +:10431000B4F8643043F0020332E0B3F5006F4DD0DF +:1043200017D8B3F5A06F31D0A3F5C063012B90D897 +:10433000636894F85E205E6894F85F10B4F86030AB +:104340002046B047002884D043682365036863652E +:104350001AE0B3F5106F36D040F6024293427FF474 +:1043600078AF5C4B2365022363650023C3E794F8B1 +:104370005E30012B7FF46DAFB4F8643023F002039C +:10438000C4E91455A4F86430A56578E7B4F85C3046 +:10439000B3F5A06F0ED194F85E3084F866302046F5 +:1043A00001F0CAF863681B6813B1012120469847E1 +:1043B000032323700023C4E914339CE704F167034B +:1043C00023650123C3E72378042B10D1302383F323 +:1043D00011882046FFF7C0FE85F31188032163682A +:1043E00084F8675021701B680BB12046984794F8F9 +:1043F0005E30002BDED084F86730042323706368BE +:104400001B68002BD6D0022120469847D2E794F8AB +:1044100060301D0603F00F0120460AD501F038F97F +:10442000012804D002287FF414AF2B4B9AE72B4BC2 +:1044300098E701F01FF9F3E794F85E30002B7FF462 +:1044400008AF94F8603013F00F01B3D01A0620467D +:1044500002D501F0FFFBADE701F0F2FBAAE794F80B +:104460005E30002B7FF4F5AE94F8603013F00F014E +:10447000A0D01B06204602D501F0D8FB9AE701F038 +:10448000CBFB97E7142284F84C2083F311882B464A +:104490002A4629462046FFF76BFE85F31188E9E698 +:1044A0005DB1152284F84C2083F311880021D4E9F2 +:1044B00014232046FFF75CFEFDE60B2284F84C2017 +:1044C00083F311882B462A4629462046FFF762FED1 +:1044D000E3E700BF40680008386800083C6800084F +:1044E00038B590F84C300446002B3ED0063BDAB28B +:1044F0000F2A34D80F2B32D8DFE803F037313108D8 +:10450000223231313131313131313737456DB0F807 +:1045100062309D4214D2C3681B8AB5FBF3F203FBE1 +:1045200012556DB9302383F311882B462A4629464C +:10453000FFF730FE85F311880A2384F84C300EE033 +:10454000142384F84C30302383F3118800231A4657 +:1045500019462046FFF70CFE002383F3118838BD6F +:10456000836D03B198470023E7E70021204601F05F +:104570005DFB0021204601F04FFB63681B6813B10F +:104580000621204698470623D7E7000010B590F88B +:104590004C30142B044629D017D8062B05D001D84F +:1045A0001BB110BD093B022BFBD80021204601F0B6 +:1045B0003DFB0021204601F02FFB63681B6813B10F +:1045C000062120469847062319E0152BE9D10B2335 +:1045D00080F84C30302383F3118800231A461946A3 +:1045E000FFF7D8FD002383F31188DAE7C3689B69DE +:1045F0005B68002BD5D1836D03B19847002384F805 +:104600004C30CEE700230375826803691B68996804 +:104610009142FBD25A680360426010605860704754 +:1046200000230375826803691B6899689142FBD86F +:104630005A680360426010605860704708B50846C9 +:10464000302383F311880B7D032B05D0042B0DD071 +:104650002BB983F3118808BD8B6900221A604FF0D3 +:10466000FF338361FFF7CEFF0023F2E7D1E9003289 +:1046700013605A60F3E70000FFF7C4BF054BD96829 +:104680000875186802681A60536001220275D860C4 +:10469000FBF750BE904B002030B50C4BDD684B1C37 +:1046A00087B004460FD02B46094A684600F05EF9F1 +:1046B0002046FFF7E3FF009B13B1684600F060F966 +:1046C000A86907B030BDFFF7D9FFF9E7904B00208C +:1046D0003D460008044B1A68DB6890689B68984266 +:1046E00094BF002001207047904B0020084B10B56C +:1046F0001C68D86822681A60536001222275DC6049 +:10470000FFF78EFF01462046BDE81040FBF712BEC2 +:10471000904B002038B5074C074908480123002575 +:104720002370656001F084FC0223237085F31188F7 +:1047300038BD00BFF84D002048680008904B0020AD +:1047400008B572B6044B186500F038FC00F01AFD8D +:10475000024B03221A70FEE7904B0020F84D002018 +:1047600000F044B9034A516853685B1A9842FBD879 +:10477000704700BF001000E08B60022308618B824D +:10478000084670478368A3F1840243F8142C026939 +:1047900043F8442C426943F8402C094A43F8242C3E +:1047A000C26843F8182C022203F80C2C002203F8EC +:1047B0000B2C044A43F8102CA3F12000704700BFD3 +:1047C0004D030008904B002008B5FFF7DBFFBDE864 +:1047D0000840FFF751BF0000024BDB6898610F20D3 +:1047E000FFF74CBF904B0020302383F31188FFF775 +:1047F000F3BF000008B50146302383F31188082079 +:10480000FFF74AFF002383F3118808BD064BDB68DE +:1048100039B1426818605A60136043600420FFF7A2 +:104820003BBF4FF0FF307047904B00200368984229 +:1048300006D01A680260506099611846FFF71CBFE5 +:104840007047000038B504460D462068844200D108 +:1048500038BD036823605C608561FFF70DFFF4E7F6 +:1048600010B503689C68A2420CD85C688A600B6033 +:104870004C602160596099688A1A9A604FF0FF3342 +:10488000836010BD1B68121BECE700000A2938BFCB +:104890000A2170B504460D460A26601901F0C2FBD4 +:1048A00001F0AEFB041BA54203D8751C2E4604463E +:1048B000F3E70A2E04D9BDE87040012001F0F8BBEF +:1048C00070BD0000F8B5144B0D46D96103F110011D +:1048D00041600A2A1969826038BF0A220160486073 +:1048E0001861A818144601F08FFB0A2701F088FB15 +:1048F000431BA342064606D37C1C281901F092FBF9 +:1049000027463546F2E70A2F04D9BDE8F8400120D2 +:1049100001F0CEBBF8BD00BF904B0020F8B50646B5 +:104920000D4601F06DFB0F4A134653F8107F9F426E +:1049300006D12A4601463046BDE8F840FFF7C2BF1F +:10494000D169BB68441A2C1928BF2C46A34202D94E +:104950002946FFF79BFF224631460348BDE8F84051 +:10496000FFF77EBF904B0020A04B002010B4C0E9A1 +:10497000032300235DF8044B4361FFF7CFBF000022 +:1049800010B5194C236998420DD0D0E900328168E6 +:1049900013605A609A680A449A60002303604FF0DB +:1049A000FF33A36110BD2346026843F8102F536004 +:1049B0000022026022699A4203D1BDE8104001F052 +:1049C0002BBB936881680B44936001F019FB22694B +:1049D000E1699268441AA242E4D91144BDE810404A +:1049E000091AFFF753BF00BF904B00202DE9F04795 +:1049F000DFF8BC8008F110072C4ED8F8105001F0F9 +:104A0000FFFAD8F81C40AA68031B9A423ED8144407 +:104A1000D5E900324FF00009C8F81C4013605A6015 +:104A2000C5F80090D8F81030B34201D101F0F4FA83 +:104A300089F31188D5E9033128469847302383F359 +:104A400011886B69002BD8D001F0DAFA6A69A0EB03 +:104A500004094A4582460DD2022001F029FB0022BA +:104A6000D8F81030B34208D151462846BDE8F04787 +:104A7000FFF728BF121A2244F2E712EB090938BFE8 +:104A80004A4629463846FFF7EBFEB5E7D8F810301E +:104A9000B34208D01444211AC8F81C00A960BDE82C +:104AA000F047FFF7F3BEBDE8F08700BFA04B002042 +:104AB000904B002038B501F0A3FA054AD2E9084529 +:104AC000031B181945F10001C2E9080138BD00BFF8 +:104AD000904B002000207047FEE700007047000068 +:104AE0004FF0FF307047000002290CD0032904D09A +:104AF0000129074818BF00207047032A05D8054838 +:104B000000EBC2007047044870470020704700BFA8 +:104B10002069000848230020D468000870B59AB0C6 +:104B20000546084601A9144600F0C2F801A8FCF7A2 +:104B3000EFFE431C5B00C5E9003400222370032311 +:104B40006370C6B201AB02341046D1B28E4204F19A +:104B5000020401D81AB070BD13F8011B04F8021C3E +:104B600004F8010C0132F0E708B5302383F3118813 +:104B70000348FFF731FA002383F3118808BD00BF13 +:104B8000004E002090F85C3003F01F02012A07D18C +:104B900090F85D200B2A03D10023C0E9143315E0FF +:104BA00003F06003202B08D1B0F860302BB990F8E7 +:104BB0005D20212A03D81F2A04D8FFF7EFB9222A43 +:104BC000EBD0FAE7034A02650722426583650120BC +:104BD000704700BF3F23002007B5052917D8DFE83D +:104BE00001F0191603191920302383F31188104A94 +:104BF00001900121FFF796FA01980E4A0221FFF772 +:104C000091FA0D48FFF7B4F9002383F3118803B03C +:104C10005DF804FB302383F311880748FFF77EF922 +:104C2000F2E7302383F311880348FFF795F9EBE7A8 +:104C30007468000898680008004E002038B50C4DD4 +:104C40000C4C0D492A4604F10800FFF767FF05F1F7 +:104C5000CA0204F110000949FFF760FF05F5CA72A6 +:104C600004F118000649BDE83840FFF757BF00BF00 +:104C7000C852002048230020546800085E680008DD +:104C80006968000870B5044608460D46FCF740FE0A +:104C9000C6B22046013403780BB9184670BD3246BF +:104CA0002946FCF721FE0028F3D10120F6E7000099 +:104CB0002DE9F84F05460C46FCF72AFE2B49C6B2F3 +:104CC0002846FFF7DFFF08B10336F6B22849284629 +:104CD000FFF7D8FF08B11036F6B2632E0DD8DFF813 +:104CE0008C80DFF88C90234FDFF890A0DFF890B035 +:104CF0002E7846B92670BDE8F88F29462046BDE8D3 +:104D0000F84F01F01BBD252E2BD107224146284626 +:104D1000FCF7EAFD58B9DBF800302360DBF804301B +:104D20006360BBF80830238107350A34E0E70822C6 +:104D300049462846FCF7D8FD98B90F4BA21C1978B4 +:104D400009090232C95D02F8041C13F8011B01F0C5 +:104D50000F015345C95D02F8031CF0D11834083522 +:104D6000C6E704F8016B0135C2E700BF40690008DF +:104D70006968000848690008107AF01F1C7AF01F63 +:104D80005A670008BFF34F8F024AD368DB03FCD495 +:104D9000704700BF003C024008B5074B1B7853B971 +:104DA000FFF7F0FF054B1A69002ABFBF044A5A609B +:104DB00002F188325A6008BD26550020003C0240AE +:104DC0002301674508B5054B1B7833B9FFF7DAFFB8 +:104DD000034A136943F00043136108BD26550020C0 +:104DE000003C02400728F0B516D80C4C0C4923783B +:104DF0007BB90C4D0E4608234FF0006255F8047B3A +:104E000046F8042B013B13F0FF033A44F6D101238B +:104E1000237051F82000F0BD0020FCE74855002029 +:104E2000285500205C690008014B53F820007047AA +:104E30005C69000808207047072810B5044601D9AE +:104E4000002010BDFFF7CEFF064B53F82430184466 +:104E5000C21A0BB90120F4E712680132F0D1043B09 +:104E6000F6E700BF5C690008072810B5044621D8A2 +:104E7000FFF788FFFFF790FF0F4AF323D360C300CB +:104E8000DBB243F4007343F002031361136943F48C +:104E900080331361FFF776FFFFF7A4FF074B53F84A +:104EA000241000F04BF9FFF78DFF2046BDE81040BD +:104EB000FFF7C2BF002010BD003C02405C69000843 +:104EC000F8B512F00103144642D185182E4A9542D6 +:104ED00057D82E4B1B6813F0010352D02C4DFFF70F +:104EE0005BFFF323EB60FFF74DFF40F20127032C3C +:104EF00015D824F001046618254C401A40F2011719 +:104F0000B142236900EB010524D123F001032361A1 +:104F1000FFF758FF0120F8BD043C0430E7E78307A2 +:104F2000E7D12B6923F440732B612B693B432B6141 +:104F300051F8046B0660BFF34F8FFFF723FF036840 +:104F40009E42E9D02B6923F001032B61FFF73AFF62 +:104F50000020E0E723F44073236123693B4323618E +:104F60000B882B80BFF34F8FFFF70CFF2D8831F894 +:104F7000023BADB2AB42C3D0236923F001032361EE +:104F8000E4E71846C7E700BF000008080038024001 +:104F9000003C0240084908B50B7828B11BB9FFF75F +:104FA000FBFE01230B7008BD002BFCD0BDE80840C0 +:104FB0000870FFF707BF00BF2655002008B50B4853 +:104FC0004FF47F4100F0CCF809484FF4303100F045 +:104FD000C7F808484FF4804100F0C2F8BDE8084027 +:104FE0004FF470514FF4805000F0BAB80001002027 +:104FF0000000012000C003200846114601F002BB5A +:10500000012001F0FFBA0000084601F019BB0000C2 +:1050100038B5EFF311859DB9EFF30584C4F30804A7 +:10502000302334B183F31188FFF744FD85F31188F1 +:1050300038BD83F31188FFF73DFD84F3118838BD37 +:10504000BDE83840FFF736BD38B5FFF7E1FF114C3A +:10505000114AC00840EA4170A0FB025EC908A0FBEB +:10506000040C1CEB050CA1FB04404FF000035B415A +:10507000A1FB02121CEB040C43EB000011EB0E0130 +:1050800042F10002411842F10000090941EA0070B2 +:1050900038BD00BFCFF753E3A59BC42010B5024431 +:1050A000064BD2B2904200D110BD441C00B253F85E +:1050B000200041F8040BE0B2F4E700BF50280040A4 +:1050C0000F4B30B51C6F240407D41C6F44F40074DC +:1050D0001C671C6F44F400441C670A4C236843F4AB +:1050E000807323600244084BD2B2904200D130BD9D +:1050F000441C00B251F8045B43F82050E0B2F4E7DE +:1051000000380240007000405028004007B50122DE +:1051100001A90020FFF7C2FF019803B05DF804FB6E +:1051200013B50446FFF7F2FFA04205D0012201A902 +:1051300000200194FFF7C4FF02B010BD0144BFF38B +:105140004F8F064B884204D3BFF34F8FBFF36F8F4F +:105150007047C3F85C022030F4E700BF00ED00E0C8 +:105160000144BFF34F8F064B884204D3BFF34F8FE8 +:10517000BFF36F8F7047C3F870022030F4E700BFB1 +:1051800000ED00E070470000074B45F255521A60F1 +:1051900002225A6040F6FF729A604CF6CC421A60C6 +:1051A000024B01221A707047003000405055002019 +:1051B000034B1B781BB1034B4AF6AA221A607047B7 +:1051C0005055002000300040034B1A681AB9034ABA +:1051D000D2F874281A6070474C5500200030024005 +:1051E000024B4FF08072C3F87428704700300240C1 +:1051F00008B5FFF7E9FF024B1868C0F3407008BD1F +:105200004C55002008B5FFF7DFFF024B1868C0F3CC +:10521000007008BD4C55002070B5BFF34F8FBFF331 +:105220006F8F1A4A0021C2F85012BFF34F8FBFF39D +:105230006F8F536943F400335361BFF34F8FBFF354 +:105240006F8FC2F88410BFF34F8FD2F88030C3F352 +:10525000C900C3F34E335B0143F6E07403EA04066E +:10526000014646EA81750139C2F86052F9D2203B05 +:1052700013F1200FF2D1BFF34F8F536943F4803302 +:105280005361BFF34F8FBFF36F8F70BD00ED00E030 +:10529000FEE7000070B5214B2148224A904237D3E7 +:1052A000214BDA1C121AC11E22F003028B4238BFB6 +:1052B00000220021FCF734FB1C4A0023C2F8843092 +:1052C000BFF34F8FD2F88030C3F3C900C3F34E331E +:1052D0005B0143F6E07403EA0406014646EA817581 +:1052E0000139C2F86C52F9D2203B13F1200FF2D1F0 +:1052F000BFF34F8FBFF36F8FBFF34F8FBFF36F8F2E +:105300000023C2F85032BFF34F8FBFF36F8F70BDD1 +:1053100053F8041B40F8041BC0E700BF846B00086F +:105320006C5600206C5600206C56002000ED00E00A +:1053300070B5D0E91B439E6800224FF0FF3504EBA7 +:1053400042135101D3F800090028BEBFD3F8000969 +:1053500040F08040C3F80009D3F8000B0028BEBF1E +:10536000D3F8000B40F08040C3F8000B0132631803 +:105370009642C3F80859C3F8085BE0D24FF0011316 +:10538000C4F81C3870BD0000890141F020010161A2 +:1053900003699B06FCD41220FFF7E4B910B5054C55 +:1053A0002046FEF79BFE4FF0A043E366024B2367C7 +:1053B00010BD00BF54550020A069000870B50378E7 +:1053C000012B054650D12A4BC46E98421BD1294B64 +:1053D0005A6B42F080025A635A6D42F080025A655D +:1053E0005A6D5A6942F080025A615A6922F080026D +:1053F0005A610E2143205B69FEF7BAFC1E4BE36045 +:105400001E4BC4F800380023C4F8003EC0232360BC +:10541000EE6E4FF40413A3633369002BFCDA01230F +:1054200033610C20FFF79EF93369DB07FCD41220AF +:10543000FFF798F93369002BFCDA0026A6602846AE +:10544000FFF776FF6B68C4F81068DB68C4F814686F +:10545000C4F81C684BB90A4BA3614FF0FF3363617A +:10546000A36843F00103A36070BD064BF4E700BFDF +:105470005455002000380240401400400300200230 +:10548000003C30C0083C30C0F8B5C46E0546002171 +:105490002046FFF779FF296F00234FF001128F6834 +:1054A000C4F834384FF00066C4F81C284FF0FF30C1 +:1054B00004EB431201339F42C2F80069C2F8006B4B +:1054C000C2F80809C2F8080BF2D20B68EA6E6B67E3 +:1054D000636210231361166916F01006FBD11220C7 +:1054E000FFF740F9D4F8003823F4FE63C4F800381D +:1054F000A36943F4402343F01003A3610923C4F8D4 +:105500001038C4F814380A4BEB604FF0C043C4F8AD +:10551000103B084BC4F8003BC4F81069C4F80039CC +:105520006B6F03F1100243F480136A67A362F8BD46 +:105530007C69000840800010C26E90F86610D2F8B6 +:10554000003823F4FE6343EA0113C2F800387047C1 +:105550002DE9F84300EB8103C56EDA68166806F0A2 +:105560000306731E022B05EB41130C4680460FFA0F +:1055700081F94FEA41104FF00001C3F8101B4FF0C2 +:10558000010104F1100398BFB60401FA03F3916915 +:105590008EBF334E06F1805606F5004600293AD0FC +:1055A000578A04F15801490137436F50D5F81C1848 +:1055B0000B43C5F81C382B180021C3F81019536988 +:1055C0000127611EA7409BB3138A928B9B08012A77 +:1055D00088BF5343D8F87420981842EA034301F176 +:1055E000400205EB8202C8F8740021465360284649 +:1055F000FFF7CAFE08EB8900C3681B8A43EA84539D +:10560000483464011E432E51D5F81C381F43C5F899 +:105610001C78BDE8F88305EB4917D7F8001B21F487 +:105620000041C7F8001BD5F81C1821EA0303C0E7A6 +:1056300004F13F0305EB83030A4A5A6028462146DA +:10564000FFF7A2FE05EB4910D0F8003923F4004320 +:10565000C0F80039D5F81C3823EA0707D7E700BFA0 +:105660000080001000040002026F12684267FFF71A +:105670005FBE00005831C36E49015B5813F400400F +:1056800004D013F4001F0CBF02200120704700005B +:105690004831C36E49015B5813F4004004D013F441 +:1056A000001F0CBF022001207047000000EB8101A9 +:1056B000CB68196A0B6813604B6853607047000031 +:1056C00000EB810330B5DD68AA691368D36019B9AE +:1056D000402B84BF402313606B8A1468C26E1C4445 +:1056E000013CB4FBF3F46343033323F0030302EB05 +:1056F000411043EAC44343F0C043C0F8103B2B6859 +:1057000003F00303012B09B20ED1D2F8083802EBE3 +:10571000411013F4807FD0F8003B14BF43F0805356 +:1057200043F00053C0F8003B02EB4112D2F8003BBB +:1057300043F00443C2F8003B30BD00002DE9F041C6 +:10574000244DEE6E06EB40130446D3F8087BC3F8F5 +:10575000087B38070AD5D6F81438190706D505EBA3 +:1057600084032146DB6828465B689847FA071FD503 +:10577000D6F81438DB071BD505EB8403D968CCB900 +:105780008B69488A5A68B2FBF0F600FB16228AB988 +:105790001868DA6890420DD2121AC3E90024302347 +:1057A00083F311880B482146FFF78AFF84F31188A1 +:1057B000BDE8F081012303FA04F26B8923EA0203B6 +:1057C0006B81CB68002BF3D021460248BDE8F04145 +:1057D000184700BF5455002000EB810370B5DD6809 +:1057E000C36E6C692668E6604A0156BB1A444FF4E2 +:1057F0000020C2F810092A6802F00302012A0AB246 +:105800000ED1D3F8080803EB421410F4807FD4F8CB +:10581000000914BF40F0805040F00050C4F8000967 +:1058200003EB4212D2F8000940F00440C2F800092C +:10583000D3F83408012202FA01F10143C3F8341805 +:1058400070BD19B9402E84BF4020206020682E8A88 +:105850008419013CB4FBF6F440EAC44040F0005027 +:105860001A44C6E72DE9F8433B4DEE6E06EB4013B4 +:105870000446D3F80889C3F8088918F0010F4FEAE5 +:1058800040171AD0D6F81038DB0716D505EB800381 +:10589000D9684B691868DA68904230D2121A4FF012 +:1058A00000091A60C3F80490302383F3118821465D +:1058B0002846FFF791FF89F3118818F0800F1CD05C +:1058C000D6F834380126A640334216D005EB8403BF +:1058D000ED6ED3F80CC0DCF814200134E4B2D2F839 +:1058E00000E005EB04342F445168714515D3D5F819 +:1058F000343823EA0606C5F83468BDE8F883012386 +:1059000003FA04F22B8923EA02032B818B68002B14 +:10591000D3D0214628469847CFE7BCF81000AEEB1D +:105920000103834228BF0346D7F8180980B2B3EBBE +:10593000800FE2D89068A0F1040959F8048FC4F8E8 +:105940000080A0EB09089844B8F1040FF5D818447A +:105950000B4490605360C7E7545500202DE9F74F82 +:10596000AC4CE56E6E69AB691E4016F480586E61F2 +:1059700007D02046FEF720FC03B0BDE8F04FFEF74D +:10598000CDB9002E12DAD5F8003EA2489B071EBF03 +:10599000D5F8003E23F00303C5F8003ED5F80438DF +:1059A00023F00103C5F80438FEF732FC370505D5AE +:1059B0009848FFF7BDFC9748FEF718FCB0040CD5DB +:1059C000D5F8083813F0060FEB6823F470530CBFBA +:1059D00043F4105343F4A053EB6031071BD56368C5 +:1059E000DB681BB9AB6923F00803AB612378052B97 +:1059F0000CD1D5F8003E87489A071EBFD5F8003E67 +:105A000023F00303C5F8003EFEF702FC6368DB6881 +:105A10000BB180489847F30200F18980B70227D57F +:105A2000D4F86C90DFF8ECB100274FF0010A09EBD5 +:105A30004712D2F8003B03F44023B3F5802F11D175 +:105A4000D2F8003B002B0DDA62890AFA07F322EA4A +:105A50000303638104EB8703DB68DB6813B139461A +:105A600058469847236F01379B68FFB29F42DED9A3 +:105A7000F00617D5E76E3A6AC2F30A1002F00F0378 +:105A800002F4F012B2F5802F00F09980B2F5402FA9 +:105A900008D104EB83030022DB681B6A07F58057FB +:105AA00090427ED13303D5F818481DD5E70302D5BF +:105AB0000020FFF743FEA50302D50120FFF73EFEBD +:105AC000600302D50220FFF739FE210302D503202F +:105AD000FFF734FEE20202D50420FFF72FFEA302F7 +:105AE00002D50520FFF72AFE77037FF545AFE607CD +:105AF00002D50020FFF7B6FEA50702D50120FFF76B +:105B0000B1FE600702D50220FFF7ACFE210702D5E7 +:105B10000320FFF7A7FEE20602D50420FFF7A2FE4E +:105B2000A3067FF529AF0520FFF79CFE24E7E36E6F +:105B3000DFF8E0A0019300274FF00109236F9B6875 +:105B40005FFA87FB9B453FF669AF019B03EB4B1365 +:105B5000D3F8001901F44021B1F5802F1FD1D3F8FB +:105B6000001900291BDAD3F8001941F09041C3F85D +:105B70000019D3F800190029FBDB5946E06EFFF746 +:105B800003FC218909FA0BF321EA0303238104EBC7 +:105B90008B03DB689B6813B1594650469847013721 +:105BA000CCE7910708BFD7F80080072A98BF03F811 +:105BB000018B02F1010298BF4FEA182870E7023307 +:105BC00004EB830207F580575268D2F818C0DCF85E +:105BD0000820DCE9001CA1EB0C0C002188420AD152 +:105BE00004EB830463689B699A6802449A605A686C +:105BF00002445A6056E711F0030F08BFD7F800803F +:105C00008C4588BF02F8018B01F1010188BF4FEA82 +:105C10001828E3E754550020C36E03EB4111D1F877 +:105C2000003B43F40013C1F8003B7047C36E03EB25 +:105C30004111D1F8003943F40013C1F8003970471D +:105C4000C36E03EB4111D1F8003B23F40013C1F8FC +:105C5000003B7047C36E03EB4111D1F8003923F4C8 +:105C60000013C1F80039704730B5039C017204334A +:105C700004FB0325C0E90653049B03630021059B35 +:105C8000C160C0E90000C0E90422C0E90842C0E9DF +:105C90000A11436330BD0000416A0022C0E90411CB +:105CA000C0E90A22C2606FF00101FEF7CBBD00001F +:105CB000D0E90432934201D1C2680AB9181D704775 +:105CC0000020704703691960C2680132C260C2696E +:105CD000134482690361934224BF436A0361002134 +:105CE000FEF7A4BD38B504460D46E3683BB16269D2 +:105CF000131D1268A3621344E362002007E0237AB5 +:105D000033B929462046FEF781FD0028EDDA38BD7B +:105D10006FF00100FBE70000C368C269013BC3608C +:105D20004369134482694361934224BF436A4361D8 +:105D300000238362036B03B11847704770B53023AB +:105D4000044683F31188866A3EB9FFF7CBFF054608 +:105D500018B186F31188284670BDA36AE26A13F869 +:105D6000015BA362934202D32046FFF7D5FF0023D5 +:105D700083F31188EFE700002DE9F84F04460E4643 +:105D8000174698464FF0300989F311880025AA4636 +:105D9000D4F828B0BBF1000F09D141462046FFF7E7 +:105DA000A1FF20B18BF311882846BDE8F88FD4E914 +:105DB0000A12A7EB050B521A934528BF9346BBF175 +:105DC000400F1BD9334601F1400251F8040B43F850 +:105DD000040B9142F9D1A36A40334036A3624035A7 +:105DE000D4E90A239A4202D32046FFF795FF8AF3AB +:105DF0001188BD42D8D289F31188C9E730465A4686 +:105E0000FBF768FDA36A5B445E44A3625D44E7E779 +:105E100010B5029C0172043303FB0421C0E9061390 +:105E20000023C0E90A33039B0363049BC460C0E9F9 +:105E30000000C0E90422C0E90842436310BD00002D +:105E4000026AC260426AC0E904220022C0E90A2252 +:105E50006FF00101FEF7F6BCD0E904239A4201D1AC +:105E6000C26822B9184650F8043B0B607047002303 +:105E70001846FAE7C368C2690133C3604369134433 +:105E800082694361934224BF436A43610021FEF764 +:105E9000CDBC000038B504460D46E3683BB123692C +:105EA0001A1DA262E2691344E362002007E0237A2C +:105EB00033B929462046FEF7A9FC0028EDDA38BDA3 +:105EC0006FF00100FBE7000003691960C268013A46 +:105ED000C260C269134482690361934224BF436A6A +:105EE000036100238362036B03B11847704700000E +:105EF00070B530230D460446114683F31188866A37 +:105F00002EB9FFF7C7FF10B186F3118870BDA36AE1 +:105F10001D70A36AE26A01339342A36204D3E1696C +:105F200020460439FFF7D0FF002080F31188EDE709 +:105F30002DE9F84F04460D46904699464FF0300A39 +:105F40008AF311880026B346A76A4FB9494620460E +:105F5000FFF7A0FF20B187F311883046BDE8F88F26 +:105F6000D4E90A073A1AA8EB0607974228BF174652 +:105F7000402F1BD905F1400355F8042B40F8042BA2 +:105F80009D42F9D1A36A4033A3624036D4E90A2383 +:105F90009A4204D3E16920460439FFF795FF8BF359 +:105FA00011884645D9D28AF31188CDE729463A4669 +:105FB000FBF790FCA36A3B443D44A3623E44E5E703 +:105FC000D0E904239A4217D1C3689BB1836A8BB18D +:105FD000043B9B1A0ED01360C368013BC360C369C6 +:105FE0001A44836902619A4224BF436A0361002311 +:105FF00083620123184670470023FBE700F0D2B804 +:106000004FF08043586A70474FF080430022586336 +:106010001A610222DA6070474FF080430022DA6092 +:10602000704700004FF0804358637047FEE7000060 +:1060300070B51B4B01630025044686B0586085622D +:106040000E46FDF743FE04F11003C4E904334FF09C +:10605000FF33C4E90635C4E90044A560E562FFF7F3 +:10606000CFFF2B460246C4E9082304F134010D4A50 +:10607000256580232046FEF77FFB0123E0600A4A66 +:106080000375009272680192B268CDE90223074B52 +:106090006846CDE90435FEF797FB06B070BD00BF3A +:1060A000F84D0020AC690008B16900082D600008B7 +:1060B000024AD36A1843D062704700BF904B002059 +:1060C0004B6843608B688360CB68C3600B69436136 +:1060D0004B6903628B6943620B6803607047000081 +:1060E00008B5264B26481A6940F2FF110A431A6187 +:1060F0001A6922F4FF7222F001021A611A691A6BFE +:106100000A431A631A6D0A431A651E4A1B6D11462B +:10611000FFF7D6FF02F11C0100F58060FFF7D0FF0A +:1061200002F1380100F58060FFF7CAFF02F1540167 +:1061300000F58060FFF7C4FF02F1700100F5806098 +:10614000FFF7BEFF02F18C0100F58060FFF7B8FF9A +:1061500002F1A80100F58060FFF7B2FF02F1C4016F +:1061600000F58060FFF7ACFF02F1E00100F5806010 +:10617000FFF7A6FFBDE8084000F088B800380240ED +:1061800000000240B869000808B500F0F3F9FEF716 +:10619000C1FAFFF719F8BDE80840FEF74FBD00004F +:1061A000704700000F4B1A6C42F001021A641A6E1D +:1061B00042F001021A660C4A1B6E936843F0010319 +:1061C00093604FF080436B229A624FF0FF32DA62A5 +:1061D00000229A615A63DA605A6001225A611A6099 +:1061E000704700BF00380240002004E04FF08042BA +:1061F00008B51169D3680B40D9B2C9439B07116137 +:1062000007D5302383F31188FEF7AAFA002383F31E +:10621000118808BD1B4B1A696FEAC2526FEAD2524D +:106220001A611A69C2F308021A614FF0FF301A6945 +:106230005A69586100215A6959615A691A6A62F0AB +:1062400080521A621A6A02F080521A621A6A5A6AF4 +:1062500058625A6A59625A6A0B4A106840F4807050 +:106260001060186F00F44070B0F5007F1EBF4FF44F +:10627000803018671967536823F40073536000F087 +:1062800055B900BF0038024000700040364B374A15 +:106290001A64374A4FF4404111601A6842F0010213 +:1062A0001A601A689207FCD59A6822F003029A6075 +:1062B0002D4B9A6812F00C02FBD1196801F0F9011C +:1062C00019609A601A6842F480321A601A68900362 +:1062D000FCD55A6F42F001025A67234B5A6F91075F +:1062E000FCD5244A5A601A6842F080721A60204B2A +:1062F0005A685204FCD51A6842F480321A605A680F +:10630000D003FCD51A6842F400321A60184A536868 +:106310009903FCD5144B1A689201FCD5164A9A6071 +:1063200040F20112C3F88C200022C3F89020134AD7 +:1063300040F207331360136803F00F03072BFAD101 +:10634000094B9A6842F002029A609A6802F00C02C5 +:10635000082AFAD15A6C42F480425A645A6E42F4C6 +:1063600080425A665B6E704700380240000400109D +:1063700000700040106C400900948838003C0240D6 +:10638000074A08B5536903F00103536123B1054A75 +:1063900013680BB150689847BDE80840FDF7BEBCD4 +:1063A000003C0140E4550020074A08B5536903F05A +:1063B0000203536123B1054A93680BB1D068984733 +:1063C000BDE80840FDF7AABC003C0140E4550020B0 +:1063D000074A08B5536903F00403536123B1054A22 +:1063E00013690BB150699847BDE80840FDF796BCAA +:1063F000003C0140E4550020074A08B5536903F00A +:106400000803536123B1054A93690BB1D0699847DA +:10641000BDE80840FDF782BC003C0140E455002087 +:10642000074A08B5536903F01003536123B1054AC5 +:10643000136A0BB1506A9847BDE80840FDF76EBC7F +:10644000003C0140E4550020164B10B55C6904F493 +:1064500078725A61A30604D5134A936A0BB1D06AC5 +:106460009847600604D5104A136B0BB1506B9847E0 +:10647000210604D50C4A936B0BB1D06B9847E2050B +:1064800004D5094A136C0BB1506C9847A30504D589 +:10649000054A936C0BB1D06C9847BDE81040FDF7EE +:1064A0003DBC00BF003C0140E4550020194B10B535 +:1064B0005C6904F47C425A61620504D5164A136D86 +:1064C0000BB1506D9847230504D5134A936D0BB15A +:1064D000D06D9847E00404D50F4A136E0BB1506E8F +:1064E0009847A10404D50C4A936E0BB1D06E98471F +:1064F000620404D5084A136F0BB1506F9847230408 +:1065000004D5054A936F0BB1D06F9847BDE8104092 +:10651000FDF704BC003C0140E455002008B5FFF73E +:1065200065FEBDE80840FDF7F9BB0000062108B58F +:106530000846FDF71DFC06210720FDF719FC062182 +:106540000820FDF715FC06210920FDF711FC0621A6 +:106550000A20FDF70DFC06211720FDF709FC062196 +:106560002820FDF705FCBDE8084007211C20FDF7A9 +:10657000FFBB000008B5FFF74DFE00F00BF8FDF77C +:10658000ABFDFDF783FCFFF70BFEBDE80840FFF70E +:1065900035BD00000023054A19460133102BC2E91E +:1065A000001102F10802F8D1704700BFE455002045 +:1065B0000B460146184600F02DB8000000F040B828 +:1065C000012838BF012010B50446204600F030F8FD +:1065D00030B900F007F808B900F00CF88047F4E78C +:1065E00010BD0000024B1868BFF35B8F704700BFFF +:1065F0006456002008B5062000F084F80120FEF75C +:106600006BFA0000024B0A4601461868FEF7F4BC1C +:106610006823002010B5054C13462CB10A460146EC +:106620000220AFF3008010BD2046FCE70000000010 +:10663000024B01461868FEF7E3BC00BF6823002048 +:10664000024B01461868FEF7DFBC00BF682300203C +:1066500010B501390244904201D1002005E00378D1 +:1066600011F8014FA34201D0181B10BD0130F2E711 +:106670002DE9F041A3B1C91A17780144044603F18A +:10668000FF3C8C42204601D9002009E00578BD423C +:1066900004F10104F5D10CEB0405D618A54201D193 +:1066A000BDE8F08115F8018D16F801EDF045F5D043 +:1066B000E7E700001F2938B504460D4604D9162324 +:1066C00003604FF0FF3038BD426C12B152F82130F8 +:1066D0004BB9204600F030F82A4601462046BDE876 +:1066E000384000F017B8012B0AD0591C03D11623EB +:1066F00003600120E7E7002442F825402846984738 +:106700000020E0E7024B01461868FFF7D3BF00BF47 +:106710006823002038B5074D00230446084611467B +:106720002B60FEF7DDF9431C02D12B6803B1236017 +:1067300038BD00BF68560020FEF7CCB9034611F8FB +:10674000012B03F8012B002AF9D170476F72672ED5 +:106750006172647570696C6F742E46726565666CE3 +:106760007952544B0000000053544D3332463F3FA2 +:106770003F3F3F3F0053544D333246375B347C3507 +:106780005D780053544D333246375B367C375D7845 +:106790000000000040A2E4F1646891060041A3E516 +:1067A000F2656992070000004261642043414E494E +:1067B0006661636520696E6465782E008000000064 +:1067C00000800000000080000000000000000000C9 +:1067D000E5210008012A00085D290008252200089B +:1067E0003122000831240008F521000805220008A4 +:1067F000F921000801220008FD21000855230008A6 +:1068000009220008D12C00081922000829230008B9 +:1068100000000000093E0008F53D0008313E000878 +:106820001D3E0008293E0008153E0008013E0008F4 +:10683000ED3D00083D3E00080000000001000000A2 +:10684000000000006330000044680008E84B0020AE +:10685000F84D00204172647550696C6F74002542D8 +:106860004F415244252D424C002553455249414C3D +:106870002500000002000000000000002540000884 +:10688000914000084000400098520020A85200208B +:1068900002000000000000000300000000000000F3 +:1068A000D54000080000000010000000B852002091 +:1068B000000000000100000000000000545500200E +:1068C00001010200D94B0008E94A0008854B000885 +:1068D000694B000843000000DC680008090243001F +:1068E000020100C032090400000102020100052477 +:1068F0000010010524010001042402020524060001 +:1069000001070582030800FF09040100020A0000D4 +:106910000007050102400000070581024000000059 +:106920001200000028690008120110010200004056 +:106930000912415700020102030100000403090487 +:1069400025424F41524425003031323334353637F9 +:1069500038394142434445460000000000400000F1 +:106960000040000000400000004000000000010066 +:106970000000020000000200000002000000000011 +:1069800029420008E14400088D450008400040000D +:10699000CC550020CC55002001000000DC55002023 +:1069A0008000000040010000050000006D61696E7C +:1069B0000069646C650000000010806A000000003F +:1069C000AAAAAAAA00000064FFFF000000000000BD +:1069D00000A00A0000000A0000000000AAAAAAAA5B +:1069E00000000000FFFF0000000000009900000010 +:1069F0000040000000000000AAAAAAAA000000208F +:106A0000FFFF000000000000000000000000000088 +:106A100000000000AAAAAAAA00000000FFFF0000D0 +:106A20000000000000000000000000000000000066 +:106A3000AAAAAAAA00000000FFFF000000000000B0 +:106A4000000000000000000000000000AAAAAAAA9E +:106A500000000000FFFF0000000000000000000038 +:106A60000000000000000000AAAAAAAA000000007E +:106A7000FFFF000000000000000000000000000018 +:106A8000000000000A0000000000000003000000F9 +:106A900000000000000000000000000000000000F6 +:106AA00000000000000000000000000000000000E6 +:106AB00000000000000000000404000000000000CE +:106AC000000007000000000040420F00FE2A010005 +:106AD000D2040000FF00000000000000686700080A +:106AE000490400007567000851040000836700082E +:106AF000009600000000080096000000000800005A +:106B0000040000003C6900080000000000000000D4 +:106B10000000000000000000000000000000000075 +:106B20006C230020000000000000000000000000B6 +:106B30000000000000000000000000000000000055 +:106B40000000000000000000000000000000000045 +:106B50000000000000000000000000000000000035 +:106B60000000000000000000000000000000000025 +:106B70000000000000000000000000000000000015 +:046B80000000000011 :00000001FF diff --git a/Tools/bootloaders/G4-ESC_bl.bin b/Tools/bootloaders/G4-ESC_bl.bin index c728bfb26d94c3..5e631262fa9746 100755 Binary files a/Tools/bootloaders/G4-ESC_bl.bin and b/Tools/bootloaders/G4-ESC_bl.bin differ diff --git a/Tools/bootloaders/Here4AP_bl.bin b/Tools/bootloaders/Here4AP_bl.bin index a815282c2037dc..be76f1f4814ac1 100755 Binary files a/Tools/bootloaders/Here4AP_bl.bin and b/Tools/bootloaders/Here4AP_bl.bin differ diff --git a/Tools/bootloaders/Here4FC_bl.bin b/Tools/bootloaders/Here4FC_bl.bin index 72a593edecc451..b84daeaa0e02db 100755 Binary files a/Tools/bootloaders/Here4FC_bl.bin and b/Tools/bootloaders/Here4FC_bl.bin differ diff --git a/Tools/bootloaders/Here4FC_bl.hex b/Tools/bootloaders/Here4FC_bl.hex index 2ca9ef747bf0b0..3d421f5cea1709 100644 --- a/Tools/bootloaders/Here4FC_bl.hex +++ b/Tools/bootloaders/Here4FC_bl.hex @@ -1,1594 +1,1650 @@ :020000040800F2 -:1000000000060020F50500081D350008D53400085D -:10001000FD340008D5340008F5340008F705000861 -:10002000F7050008F7050008F70500080145000876 -:10003000F7050008F7050008F7050008F7050008B0 -:10004000F7050008F7050008F7050008F7050008A0 -:10005000F7050008F7050008F15C00081D5D0008C1 -:10006000495D0008755D0008A15D0008F7050008FE -:10007000F7050008F7050008F7050008F705000870 -:10008000F7050008F7050008F705000885340008A3 -:10009000AD34000899340008C1340008CD5D000873 -:1000A000F7050008F7050008F7050008F705000840 -:1000B000F7050008F7050008F7050008F705000830 -:1000C000F7050008F7050008F7050008F705000820 -:1000D000F7050008A55E0008F7050008F705000809 -:1000E000315E0008F7050008F7050008F70500086D -:1000F000F7050008F7050008F7050008F7050008F0 -:10010000F7050008F7050008CD5E0008F7050008B0 -:10011000F7050008F7050008F7050008F7050008CF -:10012000F7050008F7050008F7050008F7050008BF -:10013000F7050008F7050008F7050008F7050008AF -:10014000F7050008F7050008F7050008F70500089F -:10015000F7050008F7050008F7050008F70500088F -:10016000F7050008F7050008F7050008F70500087F -:10017000F7050008F7050008F7050008F70500086F -:10018000F7050008F7050008F7050008B95E000844 -:10019000F7050008F7050008F7050008F70500084F -:1001A000F7050008F7050008F7050008F70500083F -:1001B000F7050008F7050008F7050008F70500082F -:1001C000F7050008F7050008F7050008F70500081F -:1001D000F7050008F7050008F7050008F70500080F -:1001E000F7050008F7050008F7050008F7050008FF -:1001F000F7050008F7050008F7050008F7050008EF -:10020000F7050008F7050008F7050008F7050008DE -:10021000F7050008F7050008F7050008F7050008CE -:10022000F7050008F7050008F7050008F7050008BE -:10023000F7050008F7050008F7050008F7050008AE -:10024000F7050008F7050008F7050008F70500089E -:10025000F7050008F7050008F7050008F70500088E -:10026000F7050008F7050008F7050008F70500087E -:10027000F7050008F7050008F7050008F70500086E -:10028000F7050008F7050008F7050008F70500085E -:10029000F7050008F7050008F7050008F70500084E -:1002A000F7050008F7050008F7050008F70500083E -:1002B000F7050008F7050008F7050008F70500082E -:1002C000F7050008F7050008F7050008F70500081E -:1002D000F7050008F7050008F7050008F70500080E -:1002E000CD19000800000000000000000000000020 -:1002F00053B94AB9002908BF00281CBF4FF0FF318D -:100300004FF0FF3000F074B9ADF1080C6DE904CE88 -:1003100000F006F8DDF804E0DDE9022304B07047E0 -:100320002DE9F047089D04468E46002B4DD18A42A8 -:10033000944669D9B2FA82F252B101FA02F3C2F1DB -:10034000200120FA01F10CFA02FC41EA030E94406C -:100350004FEA1C48210CBEFBF8F61FFA8CF708FB8D -:1003600016E341EA034306FB07F199420AD91CEB65 -:10037000030306F1FF3080F01F81994240F21C8197 -:10038000023E63445B1AA4B2B3FBF8F008FB1033DF -:1003900044EA034400FB07F7A7420AD91CEB040414 -:1003A00000F1FF3380F00A81A74240F207816444E4 -:1003B000023840EA0640E41B00261DB1D440002369 -:1003C000C5E900433146BDE8F0878B4209D9002DCD -:1003D00000F0EF800026C5E9000130463146BDE857 -:1003E000F087B3FA83F6002E4AD18B4202D38242C1 -:1003F00000F2F980841A61EB030301209E46002D70 -:10040000E0D0C5E9004EDDE702B9FFDEB2FA82F2C4 -:10041000002A40F09280A1EB0C014FEA1C471FFA22 -:100420008CFE0126200CB1FBF7F307FB131140EA09 -:1004300001410EFB03F0884208D91CEB010103F1D6 -:10044000FF3802D2884200F2CB804346091AA4B298 -:10045000B1FBF7F007FB101144EA01440EFB00FE6C -:10046000A64508D91CEB040400F1FF3102D2A645D1 -:1004700000F2BB800846A4EB0E0440EA03409CE770 -:10048000C6F12007B34022FA07FC4CEA030C20FA1D -:1004900007F401FA06F31C43F9404FEA1C4900FA3D -:1004A00006F3B1FBF9F8200C1FFA8CFE09FB1811BA -:1004B00040EA014108FB0EF0884202FA06F20BD92D -:1004C0001CEB010108F1FF3A80F08880884240F27D -:1004D0008580A8F102086144091AA4B2B1FBF9F0C1 -:1004E00009FB101144EA014100FB0EFE8E4508D9BC -:1004F0001CEB010100F1FF346CD28E456AD9023841 -:10050000614440EA0840A0FB0294A1EB0E01A14225 -:10051000C846A64656D353D05DB1B3EB080261EB93 -:100520000E0101FA07F722FA06F3F1401F43C5E96D -:10053000007100263146BDE8F087C2F12003D840A3 -:100540000CFA02FC21FA03F3914001434FEA1C47E5 -:100550001FFA8CFEB3FBF7F007FB10360B0C43EAD7 -:10056000064300FB0EF69E4204FA02F408D91CEB87 -:10057000030300F1FF382FD29E422DD90238634485 -:100580009B1B89B2B3FBF7F607FB163341EA034125 -:1005900006FB0EF38B4208D91CEB010106F1FF3874 -:1005A00016D28B4214D9023E6144C91A46EA00466B -:1005B00038E72E46284605E70646E3E61846F8E6FD -:1005C0004B45A9D2B9EB020864EB0C0E0138A3E746 -:1005D0004646EAE7204694E74046D1E7D0467BE727 -:1005E000023B614432E7304609E76444023842E79F -:1005F000704700BF02E000F000F8FEE772B637482F -:1006000080F30888364880F3098836483649086000 -:1006100040F20000CCF200004EF63471CEF2000140 -:100620000860BFF34F8FBFF36F8F40F20000C0F23E -:10063000F0004EF68851CEF200010860BFF34F8FF4 -:10064000BFF36F8F4FF00000E1EE100A4EF63C71E1 -:10065000CEF200010860062080F31488BFF36F8F8C -:1006600005F01AF805F01CF94FF055301F491B4AE8 -:1006700091423CBF41F8040BFAE71D49184A9142E8 -:100680003CBF41F8040BFAE71A491B4A1B4B9A423C -:100690003EBF51F8040B42F8040BF8E7002018495C -:1006A000184A91423CBF41F8040BFAE705F032F8D2 -:1006B00005F078F9144C154DAC4203DA54F8041BDC -:1006C0008847F9E700F042F8114C124DAC4203DACA -:1006D00054F8041B8847F9E705F01AB80006002013 -:1006E000002200200000000808ED00E000000020CB -:1006F00000060020E062000800220020A022002066 -:10070000A0220020086F0020E0020008E402000898 -:10071000E4020008E40200082DE9F04F2DED108AF4 -:10072000C1F80CD0D0F80CD0BDEC108ABDE8F08F29 -:10073000002383F311882846A047002004F0F0FB33 -:10074000FEE704F053FB00DFFEE70000F8B501F020 -:1007500053F904F025FF074604F094FF0546B8BBA3 -:10076000204B9F4234D001339F4234D027F0FF0208 -:100770001D4B9A4232D12E4642F21074F8B200F06C -:1007800071FF00F075FF08B10024264601F022FD3C -:1007900020B10024032000F07BF8264635B1134B2E -:1007A0009F4203D0002404F065FF2646002004F099 -:1007B00001FF0EB100F082F801F0ECFA00F08CFFBE -:1007C00001F0CAF9204600F00BF900F077F8F9E7DC -:1007D0002E460024D5E704460126D2E7064641F21C -:1007E0008834CEE7010007B0000008B0263A09B00F -:1007F00008B501F07DF9A0F120035842584108BD29 -:1008000007B541F21203022101A8ADF8043001F04E -:100810008DF903B05DF804FB38B5302383F31188FC -:10082000174803680BB104F039FC0023154A4FF454 -:100830007A71134804F028FC002383F31188124CCA -:10084000236813B12368013B2360636813B16368B5 -:10085000013B63600D4D2B7833B963687BB902208F -:1008600001F02EFA322363602B78032B07D16368E3 -:100870002BB9022001F024FA4FF47A73636038BD7B -:10088000A022002019080008C0230020B822002060 -:10089000084B187003280CD8DFE800F008050208A0 -:1008A000022001F00BBA022001F006BA024B00222E -:1008B0005A607047B8220020C0230020F8B501F02C -:1008C00089FC30B13E4B03221A7000223D4B5A6026 -:1008D000F8BD3D4B3D4A1C4619680131F8D0043340 -:1008E0009342F9D162683A4B9A42F1D9394B9B68ED -:1008F00003F1006303F580239A42E9D204F08EFEEF -:1009000004F0A0FE002001F04DF90220FFF7C0FF27 -:10091000314B00219A6C99641A6F19671A6FDA6C5F -:10092000D9645A6F59675A6F1A6D19659A6F99672A -:100930009B6F72B64FF0E023C3F8084DD4E9000472 -:10094000BFF34F8FBFF36F8F244AC2F88410BFF3F9 -:100950004F8F536923F480335361BFF34F8FD2F825 -:10096000803043F6E076C3F3C905C3F34E335B0131 -:1009700003EA060C29464CEA81770139C2F8747201 -:10098000F9D2203B13F1200FF2D1BFF34F8FBFF309 -:100990006F8FBFF34F8FBFF36F8F536923F4003313 -:1009A00053610023C2F85032BFF34F8FBFF36F8FF4 -:1009B000302383F31188854680F30888204787E732 -:1009C000B8220020C02300200000040820000408F2 -:1009D000FFFF0308002200200045025800ED00E060 -:1009E0002DE9F04F93B0B74B2022FF2100900AA8C9 -:1009F0009D6801F079F9B44A1378A3B90121B3488D -:100A000011700360302383F3118803680BB104F085 -:100A100045FB0023AE4A4FF47A71AC4804F034FB36 -:100A2000002383F31188009B13B1AA4B009A1A602C -:100A3000A94A1378032B03D000231370A54A5360EF -:100A40004FF0000A009CD3465646D146012001F0E3 -:100A500035F924B19F4B1B68002B00F02C8200203D -:100A600001F046F80390039B002B01DA00F088FEAA -:100A7000039B002BEDDB012001F01EF9039B213BC2 -:100A80001F2BE3D801A252F823F000BF0D0B000882 -:100A9000350B0008C90B00084D0A00084D0A000874 -:100AA0004D0A00085B0C00082B0E0008450D0008DD -:100AB000A70D0008CF0D0008F50D00084D0A00082D -:100AC000070E00084D0A0008790E0008AD0B00085B -:100AD0004D0A0008BD0E0008190B0008AD0B0008F8 -:100AE0004D0A0008A70D00084D0A00084D0A00082D -:100AF0004D0A00084D0A00084D0A00084D0A00087A -:100B00004D0A00084D0A0008C90B00080220FFF733 -:100B10006FFE002840F0F981009B022105A8BAF180 -:100B2000000F08BF1C4641F21233ADF8143000F03C -:100B3000FDFF8BE74FF47A7000F0DAFF071EEBDB66 -:100B40000220FFF755FE0028E6D0013F052F00F2F6 -:100B5000DE81DFE807F0030A0D10133605230421B8 -:100B600005A8059300F0E2FF17E004215548F9E7D6 -:100B700004215A48F6E704215948F3E74FF01C08CE -:100B8000404608F1040801F00FF80421059005A87B -:100B900000F0CCFFB8F12C0FF2D101204FF000098A -:100BA00000FA07F747EA0B0B5FFA8BFB01F0E8F856 -:100BB00026B10BF00B030B2B08BF0024FFF720FE20 -:100BC00044E704214748CDE7002EA5D00BF00B03E6 -:100BD0000B2BA1D10220FFF70BFE074600289BD06C -:100BE0000120002600F0DEFF0220FFF751FE1FFA71 -:100BF00086F8404600F0E6FF0446B0B1039940464F -:100C00000136A1F140025142514100F0F3FF0028AA -:100C1000EDD1BA46044641F21213022105A83E4620 -:100C2000ADF8143000F082FF10E725460120FFF7F1 -:100C30002FFE244B9B68AB4207D9284600F0B4FF37 -:100C4000013040F067810435F3E70025224BBA46B6 -:100C50003E461D701F4B5D60A8E7002E3FF45CAF61 -:100C60000BF00B030B2B7FF457AF0220FFF710FEA6 -:100C7000322000F03DFFB0F10008FFF64DAF18F054 -:100C800003077FF449AF0F4A08EB050392689342CC -:100C90003FF642AFB8F5807F3FF73EAF124BB84505 -:100CA000019323DD4FF47A7000F022FF0390039A42 -:100CB000002AFFF631AF039A0137019B03F8012B9D -:100CC000EDE700BF00220020BC230020A02200206E -:100CD00019080008C0230020B822002004220020A8 -:100CE000082200200C220020BC220020C820FFF790 -:100CF0007FFD074600283FF40FAF1F2D11D8C5F127 -:100D000020020AAB25F0030084494245184428BF5D -:100D10004246019200F0D6FF019AFF217F4800F081 -:100D2000E3FF4FEAA803C8F387027C4928460193F2 -:100D300000F0E2FF064600283FF46DAF019B05EB93 -:100D4000830533E70220FFF753FD00283FF4E4AEAC -:100D500000F062FF00283FF4DFAE0027B846704B7A -:100D60009B68BB4218D91F2F11D80A9B01330ED0A4 -:100D700027F0030312AA134453F8203C059340467E -:100D8000042205A9043701F00FFA8046E7E7384648 -:100D900000F00AFF0590F2E7CDF81480042105A8C1 -:100DA00000F0C4FE02E70023642104A8049300F0CD -:100DB000B3FE00287FF4B0AE0220FFF719FD002833 -:100DC0003FF4AAAE049800F01DFF0590E6E700236B -:100DD000642104A8049300F09FFE00287FF49CAED9 -:100DE0000220FFF705FD00283FF496AE049800F0BE -:100DF0000BFFEAE70220FFF7FBFC00283FF48CAE74 -:100E000000F01AFFE1E70220FFF7F2FC00283FF4B0 -:100E100083AE05A9142000F015FF074604210490B5 -:100E200004A800F083FE3946B9E7322000F060FEE6 -:100E3000071EFFF671AEBB077FF46EAE384A07EBB4 -:100E40000903926893423FF667AE0220FFF7D0FC99 -:100E500000283FF461AE27F003074F44B9453FF443 -:100E6000A5AE484609F1040900F09EFE0421059054 -:100E700005A800F05BFEF1E74FF47A70FFF7B8FCCD -:100E800000283FF449AE00F0C7FE002844D00A9B7A -:100E900001330BD008220AA9002000F02DFF002802 -:100EA0003AD02022FF210AA800F01EFFFFF7A8FC7D -:100EB0001C4804F03BF813B0BDE8F08F002E3FF45F -:100EC0002BAE0BF00B030B2B7FF426AE002364211B -:100ED00005A8059300F020FE074600287FF41CAE0D -:100EE0000220FFF785FC804600283FF415AEFFF78F -:100EF00087FC41F2883004F019F8059800F05EFF95 -:100F000046463C4600F03CFFA0E506464EE64FF064 -:100F1000000901E6BA467EE637467CE6BC220020A0 -:100F200000220020A0860100094A49F269001368E6 -:100F300099B21B0C00FB013344F250611360054B66 -:100F4000186882B2000C01FB0200186080B2704782 -:100F500014220020102200200021102210B5044687 -:100F600000F0C2FE034B03CB206061601868A060F4 -:100F700010BD00BF00E8F11F2DE9F041ADF54E7D39 -:100F80000D46002140F275126CAC07460EA80D917B -:100F900000F0AAFE4FF4C4720021204600F0A4FE27 -:100FA0000DF1340802F0C2FA4FF47A72264BB0FB0E -:100FB000F2F0186093E80700022384E807000DF5BB -:100FC000E9702382FFF7C8FF41F204331F4907A8E5 -:100FD000238405F011F815230DF2E3220DF12C0CFA -:100FE00084F8323107AB1E46083203CE664542F81C -:100FF000080C42F8041C3346F5D1306841461060B5 -:10100000204633791371012200F0F2FE002380B2F2 -:10101000E97E0393AB7E029305F11903019301234B -:10102000009307A3D3E90023CDE90480384602F0FA -:101030003BFE0DF54E7DBDE8F08100BFAFF30080B3 -:101040009E6AC421818A46EEC823002008600008F9 -:101050002DE9F0412C4CDAB080460D46237A5BBB7B -:1010600027A9284600F0D2FF0746002842D19DF864 -:101070009D60C82E3ED801464FF4A662204600F07F -:1010800033FE4FF4807332460DF19E01C4F8F831FF -:101090004FF4007304F109002644C4F80C334FF4F4 -:1010A0004073C4F8203400F00DFE9DF89C30777238 -:1010B00023720BB9EB7E237206AC8122002127A894 -:1010C00000F012FE0122214627A800F0DBFF0023DA -:1010D00080B2E97E0393AB7E029305F1190301937D -:1010E0002823CDE904400093404605A3D3E900231B -:1010F00002F0DAFD5AB0BDE8F08100BFAFF3008026 -:1011000026417272DF25D7B7905D0020F0B5254EDD -:101110004FF48A75F1B0002405FB006596F8D830CD -:10112000D822214685F8DC303AA885F8E84006AF99 -:1011300000F0DAFD06F1090000F0CEFDD5F8E4304C -:10114000C2B206F109018DF8F0000DF1F100CDE910 -:101150003A3400F0B7FD394601223AA800F0BEFF4C -:10116000082380B2317ACDE9047001270E48CDE919 -:10117000023706F1D80301933023009307A3D3E984 -:10118000002302F091FDA04206DD02F0CFF9C5F880 -:10119000E000384671B0F0BD2046FBE778F6339F9B -:1011A00093CACD8D905D0020E03300202DE9F04FF3 -:1011B000264F87B0DFF8A080254E384602F0A0FD0C -:1011C000034600283AD00024224DADF81440A14631 -:1011D0000294A246CDE90344027B8DF8142003AAB1 -:1011E0009968406803C21B6843F0004302932B6870 -:1011F00004F5A664D3F810B002F09AF910EB0802D7 -:10120000CDF800A0284605F5A65541F1000302A936 -:10121000D8470028C8BF49F00109B4F5266FE6D1C8 -:10122000B9F1000F05D0384602F06EFD86F800A037 -:10123000C3E73378072B04D80133337007B0BDE818 -:10124000F08F024802F060FDF8E700BFE0330020B5 -:10125000C56200201034002040420F0070B50D46DA -:1012600014461E4602F07CFC50B9022E10D1012C0F -:101270000ED112A3D3E900230120C5E9002307E022 -:10128000282C10D005D8012C09D0052C0FD0002017 -:1012900070BD302CFBD10BA3D3E90023ECE70BA3EB -:1012A000D3E90023E8E70BA3D3E90023E4E70BA38A -:1012B000D3E90023E0E700BFAFF30080401DA12089 -:1012C00026812A0B78F6339F93CACD8D9E6AC4215E -:1012D000818A46EE26417272DF25D7B7F017304A71 -:1012E00039059E5638B505460E4C0021013500F0F3 -:1012F00081FCA4F82C55B4F82C0500F063FC78B1FF -:10130000B4F82C0500F06EFC014648B9B4F82C0581 -:1013100000F070FCB4F82C350133A4F82C35EAE762 -:1013200038BD00BF905D0020F8B50D4C02260D4F72 -:10133000A4F5805343F8307C237E3BB965692DB119 -:10134000284600F0C5FF284604F00CFE2046A4F510 -:10135000A65400F0BDFF012E00D1F8BD0126E7E73D -:1013600000590020C06000082DE9F04F8FB00546FD -:101370000C4600AF02F0F4FB002849D1237E022B7B -:101380001BD1E38A012B18D102F0D0F80646FFF7F3 -:10139000CBFD03464FF4C87006F51676DFF8C08221 -:1013A000B3FBF0F202FB103316FA83F3C8F80030F7 -:1013B000E37E33B9A34B00221A703C37BD46BDE82B -:1013C000F08F07F12401204600F0DEFD0028F4D163 -:1013D00007F11400FFF7C0FD97F8264007F114014C -:1013E00007F12700224604F0D5FD0028E2D10F2C9A -:1013F00008D8944B1C70D8F80030A3F51673C8F8C1 -:101400000030DAE797F82410284602F0A1FBD4E771 -:10141000E38A282B2BD010D8012B23D0052BCCD13D -:10142000BFF34F8F8849894BCA6802F4E0621343C7 -:10143000CB60BFF34F8F00BFFDE7302BBDD1844E93 -:10144000E17E327A9142B8D1607E3146002291F835 -:10145000DC50854200F0A580013201F58A71042A32 -:10146000F5D1AAE721462846FFF786FDA5E72146E4 -:101470002846FFF7EDFDA0E7B2F8EC507B6005F1E0 -:1014800003094FEA99094FEA8902D11DC908A8EB5F -:10149000C10300219D46EB46584600F025FC04F1AF -:1014A000EE012A465846314400F00CFC7B6813B923 -:1014B000012000F077FB96F8D20000F083FB044691 -:1014C00030B9307200F0A8FB204600F06BFBB1E0B1 -:1014D000D6F8D4203AB996F8D200B6F82C25824234 -:1014E00001D8FFF7FFFED6F8D4202A44944208D250 -:1014F00096F8D200B6F82C250130824201D8FFF7C9 -:10150000F1FE5FFA89F25946706800F0F5FB08B900 -:10151000C54679E0726896F8D2002A447260D6F81F -:10152000D42005EB0209C6F8D49000F04BFB8145AE -:1015300009D396F8D220D6F8D4000132001B86F8E1 -:10154000D220C6F8D400FF2D0FD80024347200F04A -:1015500063FB204600F026FB00F03CFE3D4B18816B -:1015600008B9FFF7ABF9C54627E7BB6896F8D9007D -:101570000AFB0362FB68D2F8E41082F8E83001F558 -:101580008061C2F8E030C2F8E410FFF7BFFDFFF75A -:101590000DFE96F8D920013202F0030286F8D92018 -:1015A000B6E74FF48A7A20460AFB02F505F1EA0114 -:1015B000314400F0BFFDF86000287FF4FEAE012248 -:1015C000354485F8E82001F0B1FFD5F8E020D6EDEC -:1015D000007A801A40F6B832B8EE677ADFED1E6AFC -:1015E000192838BF1920904228BF104607EE900AEC -:1015F000F8EEE77A67EEA67ADFED186AE7EE267A6C -:10160000FCEEE77AC6ED007A96F8D930BB60BA688E -:1016100073680AFB02F4321992F8E81059B1D2F853 -:10162000E410E8468B423FF427AF002182F8E8102F -:10163000C2F8E010C5467368064A9B0A013313815D -:10164000BBE600BFD933002000ED00E00400FA053E -:10165000905D0020C8230020CDCCCC3D6666663F5F -:10166000DC330020014B1870704700BFD4230020EA -:1016700038B54FF04054144B22689A4221D1627D14 -:101680000025124B12481A70C922237D09301149D6 -:1016900000F8013C4FF48073C0F8DB50C0F8EF3124 -:1016A0004FF40073C0F803334FF44073C0F817349D -:1016B00000F008FBE0222946204600F015FB01203F -:1016C00038BD0020FCE700BF9AAD44C5D4230020FC -:1016D000905D00201600003037B500F07BFD1F4CF8 -:1016E0001F4D022301221F496B7123682881204668 -:1016F0005B68984704F5805301221A49D3F8C03437 -:1017000004F5A6505B689847002317494FF48052B0 -:101710000193164B16480093164B02F0F1F9164B45 -:10172000197811B1124802F013FA01F0FFFE0446D5 -:10173000FFF7FAFB4FF4C873B0FBF3F202FB13039D -:1017400004F5167010FA83F00C4B186003F09AFF42 -:1017500008B10F232B8103B030BD00BF103400202F -:10176000C823002040420F00D82300205D1200084B -:10177000E033002069130008D4230020DC3300206C -:101780002DE9F04F00242DED028B93B00DF12C08C4 -:101790004FF0010ADFF814B2FFF708FD0A94ADF824 -:1017A00034400B94C8F804409FED798B00267E4DA1 -:1017B00037462B680DF11D0207A928468DF81CA09D -:1017C0008DF81D408DED008BD3F808900023C8479D -:1017D0009DF81C90B9F1000F1ED0102200210EA818 -:1017E00000F082FA2B6808AA0AA95F6928460DF161 -:1017F0001E03B8470FAB4F4698E8030083E8030089 -:101800009DF834300EA958468DF844300A9B0E934B -:10181000DDE9082302F056FC06F5A66605F5A65597 -:10182000B6F5266FC5D1002FC0D1604802F098F9F7 -:1018300000283FD15E4E01F079FE3368984239D3DB -:1018400001F074FE0546FFF76FFB4FF4C8738DF887 -:101850002870B0FBF3F202FB130305F5167010FAC3 -:1018600083F03060534E377817B901238DF8283054 -:10187000C7F110050EA8FFF76FFB0EABEDB20DF12F -:101880002900D919062D28BF06252A46013500F062 -:1018900019FA0AABEDB24548039318230495029355 -:1018A000454B0193012300933BA3D3E9002302F0AE -:1018B0009DF9347001F03AFE404A414D1368C31A55 -:1018C000B3F57A7F2FD3106001F032FE02460B464B -:1018D000364802F023FA354802F042F918B32B7A61 -:1018E0000EAF384E002B14BF03230223737101F097 -:1018F0001DFE4FF47A7301223946B0FBF3F03060DD -:10190000304600F019FB182380B202932E4B01934E -:1019100040F25513CDE903700093244820A3D3E986 -:10192000002302F063F92B7A93B101F0FFFD00264A -:1019300007464FF48A7895F8D900304400F0030048 -:1019400008FB005393F8E82072B10136042EF2D15F -:10195000C82003F0EBFA2B7A002B7FF417AF13B0FB -:10196000BDEC028BBDE8F08FD3F8E02042B12B68CC -:10197000BA1AFA2B38BFFA230533B2EB430FE4D37C -:10198000FFF7C4FB0028E0D1E2E700BFAFF300801F -:101990000000000000000000401DA12026812A0B4D -:1019A000F1C6A7C1D068080F10340020E033002032 -:1019B000DC330020D9330020D8330020C06200205F -:1019C000905D0020C8230020C462002010B5074CA1 -:1019D000204601F0B1F804F5A65001F0ADF8044A34 -:1019E00004490020BDE8104004F0B6BA10340020CD -:1019F0002063002029130008F8B50A25204C012295 -:101A00004FF400712046192702F0EAFD204601221A -:101A10004FF4807102F0E4FD4FF4807665200138C8 -:101A200025D00822A2F10801B646332905D84FF087 -:101A3000000C66834FF000730DE0A1F13403668360 -:101A4000B3FBF7FC07FB1C33002B0CBF4FF0010C62 -:101A50004FF0000CEED1013143EA4C238A42A361DE -:101A6000A4F818E0E1D10832A02AD8D0DAE7013D85 -:101A700042F2107003F05AFA15F0FF05BFD1F8BD1D -:101A8000000402582DE9F84F4FF47A7306460D46CC -:101A9000002402FB03F7DFF85080DFF8509098F93C -:101AA00000305FFA84FA5A1C01D0A34212D159F8CF -:101AB00024002A4631460368D3F820B03B46D84775 -:101AC000854207D1074B012083F800A0BDE8F88FBD -:101AD0000124E4E7002CFBD04FF4FA7003F026FA5F -:101AE0000020F3E70C630020182200201C220020B5 -:101AF000002307B5024601210DF107008DF80730DC -:101B0000FFF7C0FF20B19DF8070003B05DF804FBAC -:101B10004FF0FF30F9E700000A46042108B5FFF74F -:101B2000B1FF80F00100C0B2404208BD074B0A4639 -:101B300030B41978064B53F82140014623682046FB -:101B4000DD69044BAC4630BC604700BF0C6300202D -:101B50001C220020A086010070B5104C0025104EFC -:101B600003F0A4FB20803068238883420CD8002532 -:101B70002088013803F096FB23880544013BB5F526 -:101B8000802F2380F4D370BD03F08CFB33680544B1 -:101B90000133B5F5802F3360E5D3E8E70E6300200D -:101BA000C862002003F050BC00F1006000F5802006 -:101BB0000068704700F10060920000F5802003F09B -:101BC000D1BB0000054B1A68054B1B889B1A83424A -:101BD00002D9104403F066BB00207047C8620020A1 -:101BE0000E630020024B1B68184403F061BB00BF6A -:101BF000C8620020024B1B68184403F06BBB00BF97 -:101C0000C86200200020704700F1FF5000F58F10DF -:101C1000D0F8000870470000064991F8243033B12D -:101C200000230822086A81F82430FFF7C3BF01208F -:101C3000704700BFCC620020014B1868704700BF9E -:101C40000010005C194B01380322084470B51D6870 -:101C5000174BC5F30B042D0C1E88A6420BD15C68F4 -:101C60000A46013C824213460FD214F9016F4EB16D -:101C700002F8016BF6E7013A03F10803ECD1814267 -:101C80000B4602D22C2203F8012B0424094A1688A1 -:101C9000AE4204D1984284BF967803F8016B013CB0 -:101CA00002F10402F3D1581A70BD00BF0010005CAD -:101CB000242200204C60000870470000704700009C -:101CC00070470000002310B5934203D0CC5CC4548D -:101CD0000133F9E710BD000003460246D01A12F99D -:101CE000011B0029FAD1704702440346934202D0F7 -:101CF00003F8011BFAE770472DE9F8431F4D14461E -:101D00000746884695F8242052BBDFF870909CB3B4 -:101D100095F824302BB92022FF2148462F62FFF787 -:101D2000E3FF95F824004146C0F1080205EB80006E -:101D3000A24228BF2246D6B29200FFF7C3FF95F811 -:101D40002430A41B17441E449044E4B2F6B2082E7B -:101D500085F82460DBD1FFF75FFF0028D7D108E0CA -:101D60002B6A03EB82038342CFD0FFF755FF002895 -:101D7000CBD10020BDE8F8830120FBE7CC62002036 -:101D8000024B1A78024B1A70704700BF0C63002098 -:101D90001822002010B5074C4FF4E13306492068A3 -:101DA0000B6002F089FF60680349BDE8104002F053 -:101DB00083BF00BF1C220020F4620020094B1822C0 -:101DC000002110B504461846FFF78EFF064A074B60 -:101DD00001461278046053F82200BDE8104002F07A -:101DE0006BBF00BFF46200200C6300201C220020A7 -:101DF0002DE9F0470D46044600219046284640F262 -:101E00007912FFF771FF234620220021284604F1B2 -:101E1000220702F0F9F8231D022220212846C026BD -:101E200002F0F2F8631D03222221284602F0ECF8AA -:101E3000A31D03222521284602F0E6F804F1080339 -:101E400010222821284602F0DFF804F110030822AE -:101E50003821284602F0D8F804F111030822402165 -:101E6000284602F0D1F804F112030822482128463E -:101E700002F0CAF804F1140320225021284602F08F -:101E8000C3F804F1180340227021284602F0BCF880 -:101E900004F120030822B021284602F0B5F804F12D -:101EA00021030822B821284602F0AEF83146083650 -:101EB0003B4608222846013702F0A6F8B6F5A07F77 -:101EC000F4D1002704F1330A04F132030822314629 -:101ED000284602F099F894F832304FEAC7099F4239 -:101EE00009F5A47615D3B8F1000F08D1314609F2EF -:101EF0004F1604F599730722284602F085F8274605 -:101F00003B1B94F8322193420CD3F01DC008BDE86E -:101F1000F0870AEB0703082231462846013702F012 -:101F200073F8D8E707F233133146082228460836FB -:101F3000013702F069F8E3E713B5044608460021CB -:101F40002022234601900160C0F8031002F05CF8E3 -:101F5000231D01980222202102F056F8631D0198EA -:101F60000322222102F050F8A31D0198032225210B -:101F700002F04AF8019804F108031022282102F027 -:101F800043F8072002B010BD0023F7B50E46047FCA -:101F9000072200911946054601F0FAFE731C012242 -:101FA000072100932846002301F0F2FEC4B9B31CB8 -:101FB000052208212846009323460D2401F0E8FE5F -:101FC0003746BB1BB278934211D307342B7FA88AC4 -:101FD000E408BBB9844294BF0020012003B0F0BDE7 -:101FE000AB8A0824DB00083BDB08B370E8E7FB1C86 -:101FF000214608222846009300230834013701F0C7 -:10200000C7FEDEE7201A18BF0120E7E70023F7B577 -:102010000E46047F082200911946054601F0B8FEDD -:10202000731CC4B908220093234610241146284685 -:1020300001F0AEFE01235F1C7278013B934211D385 -:1020400007342B7FA88AE408BBB9844294BF0020E0 -:10205000012003B0F0BDAB8A0824DB00083BDB089D -:102060007370E7E7F31921460822284600930023FE -:1020700001F08EFE08343B46DDE7201A18BF012030 -:10208000E7E70000F8B50E46054614460021812218 -:102090003046FFF729FE2B4608220021304601F08A -:1020A000B3FF7CB90F246B1C07220821304601F0D6 -:1020B000ABFF01235F1C6A78013B934204D3E01D10 -:1020C000C008F8BD0824F4E7EB1921460822304681 -:1020D00001F09AFF08343B46ECE70000F8B50E46E5 -:1020E000054614460021CE223046FFF7FDFD2B4663 -:1020F00028220021304601F087FF7CB9302405F109 -:10210000080308222821304601F07EFF2F467B1B62 -:102110002A7A934204D3E01DC008F8BD2824F5E7CD -:1021200007F109032146082230460834013701F03F -:102130006BFFECE7F7B5047F0E46009101231022F8 -:102140000021054601F024FEC4B9B31C0922102168 -:10215000284600932346192401F01AFE3746728858 -:10216000BB1B9A4211D807342B7FA88AE408BBB95D -:10217000844294BF0020012003B0F0BDAB8A10243C -:10218000DB00103BDB087380E8E73B1D214608229B -:102190002846009300230834013701F0F9FDDEE7FB -:1021A000201A18BF0120E7E730B50A44084D9142D4 -:1021B0000DD011F8013B5840082340F30004013BC7 -:1021C0002C4013F0FF0384EA5000F6D1EFE730BD56 -:1021D0002083B8EDF7B5384A6B46106851686A46F7 -:1021E00003C308233549364803F0E4FE04460028BB -:1021F00033D10A25334A6B46106851686A4603C3D7 -:10220000082331492E4803F0D5FE0446002849D062 -:102210000369B3F5E01F45D8B0F8661040F21342E9 -:1022200091423FD1294A024402F15C018B4239D3E9 -:102230005C3B234900209E1AFFF7B6FF04F16401BE -:10224000074632460020FFF7AFFFA3689F4229D11F -:10225000E368984208BF002524E00369B3F5E01F56 -:1022600027D8418B40F21342914220D1174A0244B1 -:1022700002F110018B4218D3103B114900209D1A26 -:10228000FFF792FF04F1180106462A460020FFF7E7 -:102290008BFFA3689E4202D1E368984201D00D25CE -:1022A000A8E70025284603B0F0BD1025A2E70C25BD -:1022B000A0E70B259EE700BF5C600008DCFF1B0069 -:1022C000000004086560000890FF1B000800FCF790 -:1022D00010B5037C044613B9006803F053FE204692 -:1022E00010BD00000023BFF35B8FC360BFF35B8FA3 -:1022F000BFF35B8F8360BFF35B8F7047BFF35B8F70 -:102300000068BFF35B8F704770B505460C30FFF770 -:10231000F5FF044605F108063046FFF7EFFFA0423F -:1023200006D96D683046FFF7E9FF2544281A70BDCD -:102330003046FFF7E3FF201AF9E7000070B50546C5 -:102340004068A0B105F10C0605F10800FFF7D6FFC3 -:1023500004463046FFF7D2FF844204F1FF34304692 -:1023600094BF6D680025FFF7C9FF2C44201A70BD8B -:1023700038B50C460546FFF7C7FFA04210D305F15C -:102380000800FFF7BBFF04446868BFF35B8FB4FB32 -:10239000F0F100FB11440120AC60BFF35B8F38BD4E -:1023A0000020FCE72DE9F041144607460D46FFF7F3 -:1023B000C5FF844228BF0446D4B1B84658F80C6B18 -:1023C0004046FFF79BFF3044286040467E68FFF799 -:1023D00095FF331A9C4203D801206C60BDE8F08160 -:1023E000A41B6B603B682044AB60E8600220F5E70B -:1023F0002046F3E738B50C460546FFF79FFFA0429D -:1024000010D305F10C00FFF779FF04446868BFF3AF -:102410005B8FB4FBF0F100FB11440120EC60BFF3D3 -:102420005B8F38BD0020FCE72DE9FF4188466946F7 -:1024300007466C46FFF7B6FF002506B204EBC6065A -:10244000B4420AD0626808EB050120680834FFF73F -:1024500039FC54F8043C1D44F2E729463846FFF79E -:10246000C9FF284604B0BDE8F0810000F8B5054674 -:102470000C300F46FFF742FF05F1080604463046D0 -:10248000FFF73CFFA042304688BF6C68FFF736FF7D -:10249000201A386020B12C683046FFF72FFF204407 -:1024A000F8BD000073B5144606460D46FFF72CFF35 -:1024B0008442019028BF0446DCB101A93046FFF7F1 -:1024C000D5FF019B33B93268C5E90233C5E9002461 -:1024D00001200CE09C42286038BF0194019884429E -:1024E0006860F5D93368241A0220AB60EC6002B052 -:1024F00070BD2046FBE700002DE9FF410F4669460D -:102500006C46FFF7CFFF00B2002604EBC005AC42DB -:1025100009D0D4F80480B81954F8081B4246464440 -:10252000FFF7D0FBF3E7304604B0BDE8F0810000D0 -:1025300038B50546FFF7E0FF044601462846FFF799 -:1025400017FF204638BD0000302383F3118862B6A0 -:1025500070470000002383F3118862B670470000C3 -:10256000012070477047000010B4134602681468D9 -:102570000022A4465DF8044B6047000000F580503F -:1025800090F859047047000000F5805090F852040C -:102590007047000000F5805090F958047047000023 -:1025A0004E20704700F5805208B5FFF7CDFFD2F8F6 -:1025B0009C34D2F898041844D2F894341844D2F8D1 -:1025C0007C341844D2F88C341844D2F88834184437 -:1025D000FFF7C0FF08BD00002DE9F04F0C4600F5E5 -:1025E000805185B01F4691F8523405469046BDF89B -:1025F00038909BB1D1F878340133C1F8783423682E -:102600009A0006D4237B082B0BD9627B0AB10F2BCF -:1026100007D9D1F87C340133C1F87C344FF0FF3056 -:102620000FE0FFF791FFEB6AD3F8C42012F4001A11 -:102630000AD0D1F8803400200133C1F88034FFF78C -:1026400089FF05B0BDE8F08F22684FF0480BD3F842 -:10265000C460002A6B6AC6F30446B4BF42F08042ED -:1026600092041BFB063BCBF8002023685B004FEA7B -:10267000066344BF42F00052CBF80020227B43EABD -:1026800002437201CBF80430607B18B343F440136B -:10269000CBF80430D1F8B0340133C1F8B034AB1802 -:1026A00003F58353197B41F020011973207B0392BA -:1026B00000F098FF0330039A80105FFA8AF30AF162 -:1026C000010A83420DDA04EB83010BEB83034968B3 -:1026D0009960F2E7AB1803F58353197B60F345115A -:1026E000E3E70121EB6A04F10C00B140C3F8D0101C -:1026F000AB18214603F58253C3E9048705EB461363 -:1027000003F58253183351F804CB814243F804CBCC -:10271000F9D109882A442846198041F26803D65025 -:1027200002F5805209F0030392F86C1043F0100395 -:1027300021F01F010B43214682F86C304246FFF71F -:1027400009FF3B46CDF8009000F012FF012078E72A -:102750002DE9F04700F58056044696F85254002DB6 -:1027600040F00181037C032B40F092802B462846E9 -:102770002F465FFA83FC944510DA01EBCC0E51F83A -:102780003CC0BCF1000F04DBDEF804C0BCF1000F5C -:1027900002DB01370133ECE70130FBE7FFF7D4FE42 -:1027A000E36AF0B9D3F8800040F00200C3F880007B -:1027B0004E23E06A002F6ED1D0F8803043F0010341 -:1027C000C0F88030694B6A4A1B6803F1805303F5F7 -:1027D0002C539B009342A36240F2AF80654800F007 -:1027E0009FFE4D2842D8DFF884814FEA004EDFF883 -:1027F0008891D8F800C04EEA8C0EC3F884E00CF142 -:10280000805303F52C539B00636100EB0C03D4F859 -:102810002CC0C8F80030C0F14E03DCF8800040F056 -:102820003000CCF880004FF0000CD4F81480E6465D -:102830005FFA8CF08242BCDD01EBC00A51F8300037 -:10284000002810DBDAF804A0BAF1000F0BDA09EA6D -:1028500000400AF07F0A40EA0A0040F0084048F8C9 -:102860002E000EF1010E0CF1010CE1E79A6922F045 -:1028700001029A6100F05AFE0646E36A9B69D90795 -:1028800004D500F053FE831BFA2BF6D9FFF762FE46 -:102890002846BDE8F087B7EB530F3DD2DFF8CCE018 -:1028A0004FEA074CDEF800304CEA830CC0F888C0D1 -:1028B00003F1805003EB4703002700F52C50CEF8BE -:1028C0000030BC468000A061E06AD0F8803043F060 -:1028D0000C03C0F88030D4F818E0FBB29A427FF7BE -:1028E00071AF51F8330001EBC3080028D8F8043069 -:1028F00001DB002B0EDB20F0604023F0604340F052 -:10290000005043F000434EF83C000EEBCC000CF1BD -:10291000010C43600137E0E7836923F00103836121 -:1029200000F004FE0646E36A9B69DA07AED500F0C4 -:10293000FDFD831BFA2BF6D9A8E7E26A936923F021 -:102940000103936100F0F2FD0746E36A9B69DB0730 -:1029500005D500F0EBFDC31BFA2BF6D996E7012550 -:1029600086F8525492E7002592E700BF1C630020CE -:10297000FCB50040706000080000FF0713B500F5CB -:1029800080540191606CFFF7D9FC1F280AD92022DE -:102990000199606CFFF748FDA0F1200358425841AF -:1029A00002B010BD0020FBE700F5805008B5FFF72E -:1029B000CBFD406CFFF796FCBDE80840FFF7CABDB1 -:1029C0000022026082814260826070470022002300 -:1029D00010B5C0E90023002304460C3020F8043C65 -:1029E000FFF7EEFF204610BD2DE9F047074688B0FF -:1029F0009A46884607F5805468469146FFF7A4FD3D -:102A0000FFF7E4FF606CFFF77FFC1F282DD9202221 -:102A10006946606CFFF78CFD202826D194F852346B -:102A20001BB303AD444605AB2E46083403CE9E428D -:102A300044F8080C44F8041C3546F5D1306841468A -:102A400020603846B388A380DDE90023C9E900236C -:102A5000BDF808304A46AAF80030FFF77BFD534620 -:102A600008B0BDE8F04700F071BD0020FFF772FD2F -:102A700008B0BDE8F08700002DE9F84F00230646B6 -:102A800000F58154054688461034C0E90133274BD0 -:102A900046F8303B374638462037FFF797FFA742C6 -:102AA000F9D105F580544FF4805305F5A3594FF043 -:102AB000000A26630026676405F5835709F11009AB -:102AC0004FF0000B1037E663C4E90D36012384F89C -:102AD000403084F84830A7F11800203747E910ABA0 -:102AE000FFF76EFF47F8286C4F45F4D1B8F1010F9E -:102AF00084F85884A4F85A64A4F85C64A4F85E646A -:102B000084F86064A4F86264A4F86464A4F8666459 -:102B100084F8686402D9064800F002FD054B284697 -:102B200053F82830EB62BDE8F88F00BFC0600008A2 -:102B300094600008B0600008044B10B51978044692 -:102B40004A1C1A70FFF798FF204610BD1963002039 -:102B50002DE9F04700295FD0304F3148B7FBF1F540 -:102B600081428CBF0A201120431EB5FBF0FC00FB04 -:102B70001C50DCB220B1022B1846F5D8002037E0FB -:102B80000CF1FF35B5F5806F32D2C4EBC4094FF4B8 -:102B90007A7009F103034FEAE308C3F3C70308F1AE -:102BA000010AA4EB030E08FB00085FFA8EF65AFA3E -:102BB0008EFEB8FBFEFEBEF5617F1BDC1FFA8EF4B5 -:102BC000581C56FA80F00CFB00FCB7FBFCFC61457E -:102BD000D4D1013BDBB20F2BD0D8711E0020C9B27B -:102BE000072905D810710120148055805371917107 -:102BF000BDE8F08709F1FF334FEAE30EC3F3C703E3 -:102C00000EF10108E41A0EFB0000E6B258FA84F453 -:102C1000B0FBF4F4A4B2D3E70846E9E700B4C40477 -:102C20003F420F0038B540F27772C36A154CC3F8C3 -:102C3000BC200722C36AC3F8C8202268C16A930077 -:102C400043F4C023C1F8A03002F1805302F16C01BB -:102C5000C56A03F52C53EA3289009B00226041F0DB -:102C6000E061094AC361C5F8C01003F5D87103F5E6 -:102C70006A7341629342836202D9044800F050FCB7 -:102C800038BD00BF1C630020FCB500407060000828 -:102C90002DE9F04F00F58055994689B0044695F826 -:102CA00058348A469046022B04D90027384609B08A -:102CB000BDE8F08F9B4A52F8231009B942F823006F -:102CC0009949C4F80CA00B7884F81090C3B9FFF7A9 -:102CD0003BFC964BD3F8EC2042F48072C3F8EC2016 -:102CE000D3F8942042F48072C3F89420D3F894204F -:102CF00022F48072C3F8942001230B70FFF72AFCA2 -:102D000095F851346BB9FFF71FFC894A95F8583490 -:102D1000D35CEBB1012B24D0012385F85134FFF7AC -:102D200019FCFFF711FCE26A936923F01003936129 -:102D300000F0FCFB0746E36A9E6916F0080617D010 -:102D400000F0F4FBC31BFA2BF5D9FFF703FCACE74B -:102D50000321132001F0FAFD0321152001F0F6FDF7 -:102D6000DAE70321142001F0F1FD03211620F5E735 -:102D70009A6942F001029A6100F0D8FB0746E36AC3 -:102D80009A69D00705D400F0D1FBC31BFA2BF6D902 -:102D9000DBE79A69002704F5825B42F002020BF13F -:102DA000100B9A61E36A5F65FFF7D4FB686CFFF76D -:102DB00099FA202200216846FEF796FF02A8FFF745 -:102DC000FFFD6A460BEB06030DF1180E06979446BD -:102DD0000833BCE80300F44543F8080C43F8041C2E -:102DE0006246F4D1DCF8000020361860B6F5806F3A -:102DF0009CF804201A71DCD1002304F5A25251463C -:102E000020461A3285F8503485F85334FFF7A0FE77 -:102E1000074690B9E26A936923F00103936100F0D9 -:102E200085FB0546E36A9B69D9077FF53EAF00F055 -:102E30007DFB431BFA2BF5D937E795F85F6495F8CE -:102E40005E243602C5F86CA4E36A46EA426695F849 -:102E500060241643B5F85C2446EA0246DE61B8F108 -:102E6000000F29D004F5A352414620460232FFF755 -:102E70006FFE90B9E26A936923F00103936100F059 -:102E800055FB0546E36A9B69DA077FF50EAF00F054 -:102E90004DFB431BFA2BF5D907E795F8683495F8F5 -:102EA00067141B01C5F87084E26A43EA0123B5F890 -:102EB000641443EA0143D360E36A00262046C3F862 -:102EC000BC60FFF7AFFE85F859646FF04042E36ADB -:102ED0001A65184AE36A5A654FF00222E36A9A6556 -:102EE0004FF0FF32E36AC3F8E0200322E36A914522 -:102EF000DA653FF4DBAEE26A936923F00103936184 -:102F000000F014FB0646E36A9B69DB0705D500F079 -:102F10000DFB831BFA2BF6D9C7E6012385F8523443 -:102F2000C4E600BF1063002018630020004402586C -:102F3000A8600008550200022DE9F04F054689B04F -:102F400090469946002741F2680A00F58056EB6AE0 -:102F5000D3F8D830FB40D8074ED505EB47124FEADF -:102F6000471B52441379190746D4D6F884340133E9 -:102F7000C6F8843405F5A553C3E9008913799A0688 -:102F800005EB0B0248BFD6F8B434524444BF0133BA -:102F9000C6F8B434137943F008031371DB0723D563 -:102FA00096F8533403B305F582546846FFF70EFDD7 -:102FB00003AB18345C4404F1080C2068083454F85E -:102FC000041C1A46644503C21346F6D120686946BC -:102FD00010602846A2889A800123ADF808302B683B -:102FE000CDE90089DB6B9847D6F8543423B1D6F885 -:102FF000A8340133C6F8A8340137202FA7D109B06F -:10300000BDE8F08F2DE9F04F0F468DB0044600F07B -:103010008FFA82468946002F5BD1E36AD3F8A0205D -:1030200012F4FE0F03D100200DB0BDE8F08FD3F8ED -:10303000A420920141BF04F58051D1F898240132B7 -:10304000C1F89824D3F8A4205606ECD0D3F8A450A5 -:10305000E669C5F305254823E8464FF0000B03FB5E -:1030600005664046FFF7ACFC326851004ABF22F0CB -:103070006043C2F38A4343F00043920048BF43F0E9 -:1030800080430093736813F400131BBF012304F5FE -:1030900080528DF80D308DF80D301EBFD2F8B83447 -:1030A0000133C2F8B834F38803F00F038DF80C3005 -:1030B0009DF80C0000F096FA5FFA8BF3984225D940 -:1030C000F2180CA90BF1010B127A0B4403F82C2C0B -:1030D000EEE7012FA7D1E36AD3F8B02012F4FE0F78 -:1030E000A1D0D3F8B420950141BF04F58051D1F8A7 -:1030F00098240132C1F89824D3F8B420500692D015 -:10310000D3F8B450266AC5F30525A4E7EFB9E36AFE -:10311000C3F8A85004A807ADFFF758FC98E80F00C3 -:1031200007C52B800023204604A9ADF8183023687A -:1031300004F58054DB6BCDE904A9984758B1D4F865 -:1031400090340133C4F890346EE7012FE2D1E36A82 -:10315000C3F8B850DEE7D4F8943401200133C4F842 -:10316000943461E7F8B505460F4600F58054012612 -:1031700039462846FFF746FF10B184F85364F7E755 -:10318000D4F8543423B1D4F8A8340133C4F8A834A3 -:10319000F8BD0000C36AF0B51A6C12F47F0F2BD093 -:1031A0001B6C00F5805441F268054FF0010CC4F827 -:1031B000AC340023471900EB43125E012A44117915 -:1031C00011F0020F15D0490713D4B959C66A0CFA89 -:1031D00001F1D6F8CCE011EA0E0F0AD0C6F8D410EF -:1031E000117941F004011171D4F88C240132C4F832 -:1031F0008C240133202BDED1F0BD00002B4B70B5A9 -:103200001E561B5C012B30D8294D2A4A55F8233015 -:1032100052F8264013B349B3236D9A0510D54FF4E5 -:103220000073236500F084F950EA01020B4602D0D6 -:10323000013861F10003024655F82600FFF77CFED5 -:10324000236D9B012CD54FF0007255F82630226576 -:1032500003F58053012283F8592421E001232365DB -:10326000102323654FF48053236570BD236DDA0767 -:1032700002D4236D5B0706D50523002155F82600EF -:103280002365FFF76FFF236DD80602D4236D59061F -:1032900006D55023012155F826002365FFF762FF6C -:1032A00055F82600BDE87040FFF774BFAC60000819 -:1032B00010630020B060000808B5FFF745F9FFF77C -:1032C00069FFBDE80840FFF745B90000C36AD3F8BD -:1032D000C00010F07C5005D0D3F8C40080F400107A -:1032E000C0F340507047000000F5805008B5FFF76C -:1032F0002BF9406CFFF708F8FFF72CF943090CBFD6 -:103300000120002008BD000000F5805393F85924E7 -:1033100062B1C16A8A6922F001028A61D3F89C24F1 -:103320000132C3F89C24002283F85924704700001E -:103330002DE9F74300F5825198460025FFF704F97F -:10334000103141F2680E4FF0010900F5805C00EB8E -:103350004514744423795E071CD4DB061AD58E69A4 -:10336000C36A09FA06F6D3F8CC703E4212D04F6811 -:1033700001970F689742019F77EB08070AD2C3F8BD -:10338000D460237943F004032371DCF888340133DB -:10339000CCF8883401352031202DD8D103B0BDE8D8 -:1033A000F043FFF7D7B80000F8B51E4600230F46DC -:1033B000054613701446FFF797FF80F00100387040 -:1033C0001EB12846FFF782FF2070F8BD2DE9F04FAF -:1033D00085B099460D468046164691F800B0DDE965 -:1033E0000EA302931378019300F0A2F82B78044601 -:1033F0000F4613B93378002B42D022463B46404655 -:10340000FFF796FFFFF758FFFFF77EFF4B46324668 -:103410002946FFF7C9FF2B7833B1BBF1000F03D06A -:10342000012005B0BDE8F08F337813B1019B002B6C -:10343000F6D108F5805303935445029B77EB0303C1 -:103440001ED2039BD3F85404D0B10368AAEB040145 -:10345000DB6889B298474B46324629464046FFF71B -:10346000A3FF2B7813B1BBF1000FD9D1337813B17F -:10347000019B002BD4D100F05BF804460F46DBE73C -:103480000020CEE7002108B50846FFF7B7FEBDE8EB -:10349000084001F06DB8000008B501210020FFF7D9 -:1034A000ADFEBDE8084001F063B8000008B500219A -:1034B0000120FFF7A3FEBDE8084001F059B8000065 -:1034C000012108B50846FFF799FEBDE8084001F064 -:1034D0004FB8000000B59BB0EFF309816822684641 -:1034E000FEF7F0FBEFF30583014B9B6BFEE700BF9C -:1034F00000ED00E008B5FFF7EDFF000000B59BB060 -:10350000EFF3098168226846FEF7DCFBEFF30583E1 -:10351000014B5B6BFEE700BF00ED00E0FEE7000043 -:103520000FB408B5029801F097FCFEE701F0D8BF90 -:1035300001F0B0BF13B56C46031D84E8060094E8A3 -:10354000030083E80500012002B010BD73B5856853 -:10355000019155B11B885B0707D4D0E900369B6BFE -:103560009847019AC1B23046A847012002B070BD09 -:10357000F0B5866889B005460C465EB1BDF83830B6 -:103580005B070AD4D0E900379B6B98472246C1B24B -:103590003846B047012009B0F0BD0022002301F1F8 -:1035A0000806CDE9002300230A46ADF8083003AB36 -:1035B0001068083252F8041C1C46B24203C4234669 -:1035C000F6D1106820609288A280FFF7B1FF042333 -:1035D000ADF808302B68CDE90001DB6B6946284661 -:1035E0009847D7E7082817D909280CD00A280CD003 -:1035F0000B280CD00C280CD00D280CD00E2814BF92 -:103600004020302070470C20704710207047142055 -:103610007047182070472020704700002DE9F041C6 -:10362000456A15B94162BDE8F0814B68AC4623F0AC -:103630006047C3F38A464FEAD37EC3F3807816EA25 -:10364000230638BF3E462B465A68BEEBD27F22F097 -:1036500060440AD0002A18DAA40CB44217D19D4263 -:103660000FD10D60DEE71346EEE7A74207D102F067 -:103670008044C2F3807242450BD054B1EFE708D2C8 -:10368000EDE7CCF800100B60CDE7B44201D0B442B6 -:10369000E5D81A689C46002AE5D11960C3E7000006 -:1036A0002DE9F047089D01F0070400EBD1004FF42D -:1036B0007F494FEAD508224405F00705944201D11D -:1036C000BDE8F08704F0070705F0070A111B08EBB7 -:1036D000D50E57453E4613F80EC038BF5646C6F1C4 -:1036E00008068E4228BF0E46E108415C344435444A -:1036F000B94029FA06F721FA0AF1FFB28CEA010172 -:1037000047FA0AF739408CEA010C03F80EC0D5E7F6 -:1037100080EA0120082341F2210201B2013B40006E -:10372000002980B2B8BF504013F0FF03F5D17047B5 -:1037300038B50C468D18A54200D138BD14F8011BD0 -:10374000FFF7E6FFF7E7000042684AB11368818996 -:103750004360438901339BB29942438138BF8381DF -:103760001046704770B588B0044620220D46684662 -:103770000021FEF7B9FA20460495FFF7E5FF02465F -:1037800060B16B46054608AE1C46083503CCB44212 -:1037900045F8080C45F8041C2346F5D1104608B03E -:1037A00070BD0000082817D909280CD00A280CD0B1 -:1037B0000B280CD00C280CD00D280CD00E2814BFD0 -:1037C0004020302070470C20704710207047142094 -:1037D000704718207047202070470000082817D92C -:1037E0000C280CD910280CD914280CD918280CD95D -:1037F00020280CD930288CBF0F200E2070470920BC -:1038000070470A2070470B2070470C2070470D202E -:10381000704700002DE9F843078C0446072F1ED996 -:1038200000254FF6FF73D0E90298C5F12006A5F1F7 -:10383000200029FA05F1083508FA06F628FA00F002 -:10384000314301431846C9B2FFF762FF402D0346DA -:10385000EBD13A46E169BDE8F843FFF769BF4FF69F -:10386000FF70BDE8F883000010B54B6823B9CA8A21 -:1038700063F30902CA8210BD04691A681C600361FF -:10388000C38A013BC3824A60EFE700002DE9F84F8D -:103890001D46CB8A0F468146C3F30901924605298E -:1038A0000B4630D00020AAB207F11A049EB21FFACC -:1038B00080F8042E0FD8904503F1010306D30A4483 -:1038C000FB8A62F309030120FB821AE01AF8006008 -:1038D0000130E654EAE79045F1D2A1F1050B1C2333 -:1038E0007C68BBFBF3F203FB12BB1FFA8BF6002CC8 -:1038F00045D14846FFF728FF044638B978606FF095 -:103900000200BDE8F88F4FF00008E6E700260660E9 -:103910007860ADB24FF0000B454510D90AEB0803B3 -:10392000221D13F8011B08F101089155B1B21FFACD -:1039300088F81B292BD0454506F10106F1D8FB8AF2 -:10394000C3F30902154465F30903BCE701321C46C1 -:1039500092B22368002BF9D16B1F0B441C21B3FBDF -:10396000F1F301339BB29A42D3D2BBF1000FD0D115 -:103970004846FFF7E9FE20B9C4F800B0BFE70122CE -:10398000E7E7C0F800B05E4620600446C1E7454561 -:10399000D5D94846FFF7D8FE08B92060AFE7C0F890 -:1039A00000B0002620600446B6E700002DE9F04F85 -:1039B0001C46074688462DED028B83B05B69019259 -:1039C000002B00F09A80238C2BB1E269002A00F0D2 -:1039D0009480072B35D807F10C00FFF7B5FE05469C -:1039E00038B96FF00205284603B0BDEC028BBDE884 -:1039F000F08F14220021FEF777F9228CE16905F19E -:103A00000800FEF75FF9208C48F00041013080B2D9 -:103A1000FFF7E4FEFFF7C6FE013880B220840130D4 -:103A2000287438466369228C1B782A4403F01F03EC -:103A300063F03F03137269602946FFF7EFFD01252C -:103A4000D1E74FF0000900F10C034FF0800A4E4619 -:103A50004D4608EE103A18EE100AFFF775FE834641 -:103A60000028BED014220021FEF73EF9002E3AD1E4 -:103A7000019B0222ABF808300BF1080E1FFA82FC02 -:103A8000218C0CF10100BCF1060F80B201D88E42EE -:103A90002BD3FFF7A3FE8E4208BF4FF0400AFFF77B -:103AA00081FE62690138013512781BFA80F101301C -:103AB00002F01F022DB242EA491289F001094AEAD6 -:103AC000020A48F0004281F808A059468BF810001D -:103AD0003846CBF804204FF0000AFFF79FFD238CF7 -:103AE000B342B8D17FE70022C6E7E169895D0136BC -:103AF0000EF80210B6B20132C0E76FF0010572E7AE -:103B0000F8B515460E463022002104461F46FEF742 -:103B1000EBF8069BB5F5001FA760636004F1100089 -:103B2000079B34BF6A094FF6FF72E661A362002368 -:103B300097B29A4206D800230360A782E3822383C8 -:103B4000E360F8BD0660013330462036F1E700003F -:103B500003781BB94BB2002BC8BF0170704700003F -:103B600000787047F8B50C46C969074611B9238C2F -:103B7000002B37D1257E1F2D34D8387828BB228CD6 -:103B8000072A2CD8268A36F003032BD14FF6FF7074 -:103B9000FFF7CEFD20F0010031024FF6FF72400426 -:103BA00041EA0561400C41EA402523462946384652 -:103BB000FFF7FCFE002807DD626913780133DBB2F2 -:103BC0001F2B88BF00231370F8BD218A2D0645EAFC -:103BD000012505432046FFF71DFE0246E5E76FF08D -:103BE0000300F1E76FF00100EEE7000070B58AB066 -:103BF000044616460021282268461D46FEF774F842 -:103C0000BDF8383069462046ADF810300F9B05935B -:103C10009DF840308DF81830119B0793BDF848305F -:103C2000CDE90265ADF82030FFF79CFF0AB070BD0A -:103C30002DE9F041D36905460C4616460BB9138CA5 -:103C40005BBB377E1F2F28D895F80080B8F1000F96 -:103C500026D03046FFF7DEFD3378210202462846A3 -:103C600041EAC331338A41EA080141EA076141EA86 -:103C70000341334641F08001FFF798FE00280ADD3A -:103C80003378012B07D1726913780133DBB21F2B14 -:103C900088BF00231370BDE8F0816FF00100FAE7E0 -:103CA0006FF00300F7E70000F0B58BB004460D4657 -:103CB00017460021282268461E46FEF715F89DF893 -:103CC0004C30294620465A1E534253416A468DF8CD -:103CD00000309DF84030ADF81030119B05939DF8F1 -:103CE00048308DF81830149B0793BDF85430CDE957 -:103CF0000276ADF82030FFF79BFF0BB0F0BD00005F -:103D0000406A00B104307047436A1A68426202692F -:103D10001A600361C38A013BC38270472DE9F041F9 -:103D2000D0F8208014461D46184E4146002709B998 -:103D3000BDE8F081D1E90223A21A65EB03039642A4 -:103D400077EB03031ED2036A8B420DD1FFF78CFD84 -:103D5000036A1B68036203690B60C38A0161013B4C -:103D6000016AC3828846E2E7FFF77EFD0B68C8F868 -:103D7000003003690B60C38A0161013BC382D8F83C -:103D80000010D4E788460968D1E700BF80841E0090 -:103D90002DE9F04F8BB00D4614469B46DDF8509050 -:103DA0008046002800F01881B9F1000F00F014815E -:103DB000531E3F2B00F21081012A03D1BBF1000FEB -:103DC00040F00A810023CDE90833B8F81430B5EB90 -:103DD000C30F4FEAC30703D300200BB0BDE8F08F39 -:103DE0002B199F42D8F80C3036BF7F1B2746FFB2F5 -:103DF0001BB9D8F81030002B7AD0272D4DD8C5F13B -:103E0000280600232946B742009308ABD8F80800DB -:103E10002CBFF6B23E46A7EB060A354432465FFA9F -:103E20008AFAFFF73DFCB8F81430282103F100535B -:103E3000053BDB000493D8F80C300393039B13B1CC -:103E4000BAF1000F2CD1D8F8100040B1BAF1000F30 -:103E500005D008AB5246691A0096FFF721FC38B22C -:103E6000002FB9D066070AD00AAB624203EBD40137 -:103E700002F0070211F8083C134101F8083C082C35 -:103E80003DD9102C40F2B580202C40F2B780BBF118 -:103E9000000F00F09C80082335E0BA460026C2E7F8 -:103EA000049BE02B28BFE02306930B44AB42059311 -:103EB00015D95A1B0398691A0096924508AB00F170 -:103EC000040034BF5246D2B20792FFF7E9FB079ACB -:103ED0001644AAEB020A1544F6B25FFA8AFA049B6A -:103EE000069A05999B1A0493039B1B680393A5E705 -:103EF00000933A4608AB2946D8F80800ADE7BBF175 -:103F0000000F13D00123B4EBC30F6BD0082C12D8D1 -:103F10009DF82030621E23FA02F2D50706D54FF035 -:103F2000FF3202FA04F423438DF820309DF820304C -:103F300089F8003051E7102C12D8BDF82030621EED -:103F400023FA02F2D10706D54FF0FF3202FA04F449 -:103F50002343ADF82030BDF82030A9F800303CE70D -:103F6000202C0FD80899631E21FA03F3DA0705D530 -:103F70004FF0FF3202FA04F40C430894089BC9F88E -:103F800000302AE7402C2AD0611EC4F12102A4F19E -:103F90002103DDE9086526FA01F105FA02F225FAA6 -:103FA00003F311431943CB0711D50122A4F12003D8 -:103FB000C4F1200102FA03F322FA01F1A2400B43FB -:103FC000524263EB430332432B43CDE90823DDE93F -:103FD0000823C9E9002300E76FF00100FDE66FF058 -:103FE0000800FAE6082CA1D9102CB4D9202CEED860 -:103FF000C4E7BBF1000FAED0022384E7BBF1000F92 -:10400000BCD004237FE70000012A30B5144638BF36 -:10401000012485B00025402C28BF4024012ACDE989 -:10402000025518D81B788DF8083063070AD004AB06 -:10403000624203EBD40502F0070215F8083C9340F6 -:1040400005F8083C034600912246002102A8FFF72C -:1040500027FB05B030BD082AE4D9102A03D81B88F5 -:10406000ADF80830E1E7202A95BF1B68D3E90023AB -:104070000293CDE90223D8E710B5CB681BB98B605A -:104080000B618B8210BD04691A681C600361C38ACE -:10409000013BC382CA60F0E703064CBFC0F3C030E7 -:1040A0000220704708B50246FFF7F6FF022806D146 -:1040B0005306C2F30F2001D100F0030008BDC2F384 -:1040C0000740FBE72DE9F04F93B004460D46CDE9DC -:1040D00003230A681046FFF7DFFF0228824614BF59 -:1040E000C2F306260026002A80F2F38112F0C049AE -:1040F00040F0EF81097B002900F0EB81022803D01A -:104100002378B34240F0E881C2F3046310462944A7 -:10411000069302F07F030593FFF7C4FF059B00227F -:1041200083464FEA8348002348EA0A4848EA46683B -:10413000CE78CDE90823F30948EA0008029368D055 -:10414000059B024608A92046009353466768B84776 -:10415000002800F0C481276A4FB9414604F10C00E1 -:10416000FFF700FB074690B96FF0020055E03B698E -:1041700098450DD03F68002FF9D1414604F10C005D -:10418000FFF7F0FA07460028EED0236A3B6027626B -:1041900097F817C006F01F08CCF3840CACEB0800AE -:1041A000A8EB0C031FFA80FE0028B8BF0EF1200018 -:1041B0001FFA83FEB8BF00B2002B0793B8BF0EF101 -:1041C0002003D7E90221BCBF1BB2079352EA0103C7 -:1041D00038D0039B4FF0000CDFF820E39A1A049BC1 -:1041E00063EB010196457CEB01032BD36B7B97F8C6 -:1041F0001AE0734519D1029B002B78D0012821DCED -:104200007868F8B9DFF8F0C2944570EB010316D373 -:1042100037E0276A27B96FF00C0013B0BDE8F08FC4 -:104220003B699845B4D03F68F4E7B34890427CEBD3 -:10423000010301D30020F0E7029B002BFAD0079B7B -:104240000F2B17DCFA7DB3003946204602F003023B -:1042500003F07C031343FB75FFF706FB6B7BBB7618 -:10426000029B3BB9FB7DC3F38402013262F38603F8 -:10427000FB75D0E76A7BBB7E9A42DBD1029B002BA9 -:1042800035D0B309022B32D0039B142200210DA894 -:10429000BB60049BFB60FDF727FD039B0AA920463A -:1042A0000A93049BADF83EB00B932B1D8DF840A0F4 -:1042B0000C932B7B8DF84180013BDBB2ADF83C3099 -:1042C000069B8DF84230059B8DF8433094F82C30D6 -:1042D00083F001038DF84430A3689847FB7DC3F356 -:1042E0008403013303F01F039B02FB82A2E7FB7DE3 -:1042F000C6F34012B2EBD31F40F0F480C3F3840343 -:10430000434540F0F280029AB6092B7B002A4DD03B -:10431000F2075DD4032B40F2EB80039BAE1D3946C0 -:1043200004F10C00BB603246049BFB602B7B033B1B -:10433000DBB2FFF7ABFA00280CDA39462046FFF76C -:1043400093FAFB7DC3F38403013303F01F039B0245 -:10435000FB8209E7AB88DDE908843B834FF6FF73F6 -:10436000C9F12000A9F1200228FA09F109F1080990 -:1043700004FA00F024FA02F2014318461143C9B2CC -:10438000FFF7C6F9B9F1400F0346E9D1B8823146CB -:104390002A7B033AD2B2FFF7CBF9FB7DB882DA432E -:1043A000C2F3C01262F3C713FB7543E786B92E1D33 -:1043B000013B394604F10C00DBB23246FFF766FAE6 -:1043C0000028BADB2A7B3146B88A013AD2B2E2E74A -:1043D000F98A013BC1F30901DAB204295BD8281D2F -:1043E000002307F11B069A4208D910F801CB0133CC -:1043F00006F801C00131DBB20529F4D103999342DB -:104400000A9138BF043304992CBF002355FA83F373 -:104410000B9107F11B010C9179680E930D91291DE9 -:10442000FB8AADF83EB0C3F309038DF840A08DF8C8 -:1044300041801A44069B8DF84230059BADF83C2024 -:104440008DF8433094F82C3083F001038DF844301C -:104450000023B88A7B602A7B013AFFF769F93B8B1E -:10446000B882834203D1A3680AA920469847204610 -:104470000AA9FFF701FEFB7DBA8AC3F38403013367 -:1044800003F01F039B02FB823B8B9A420CBF002070 -:104490006FF01000C1E67B68002BAFD0052001E073 -:1044A0001C3033461E68002EFAD1091A2E1D081D35 -:1044B000184401EB090C5FFA89F3BCF11B0F9DD87E -:1044C0009A429BD916F8013B09F1010900F8013B1A -:1044D000EFE76FF00900A0E66FF00A009DE66FF0CD -:1044E0000B009AE66FF00D0097E66FF00E0094E671 -:1044F0006FF00F0091E600BF40420F0080841E0065 -:10450000EFF30983054968334A6B22F001024A63DD -:1045100083F30988002383F31188704700EF00E0DC -:10452000302080F3118862B60D4B0E4AD96821F411 -:10453000E0610904090C0A430B49DA60D3F8FC2056 -:1045400042F08072C3F8FC20084AC2F8B01F11681C -:1045500041F0010111602022DA7783F822007047D0 -:1045600000ED00E00003FA0555CEACC5001000E0F8 -:10457000302310B583F311880E4B5B6813F400638E -:1045800014D0F1EE103AEFF309844FF08073683CD9 -:10459000E361094BDB6B236684F3098800F01AFCA6 -:1045A00010B1064BA36110BD054BFBE783F31188E7 -:1045B000F9E700BF00ED00E000EF00E0430700086E -:1045C000460700080023054A19460133102BC2E9AB -:1045D000001102F10802F8D1704700BF24630020E7 -:1045E0002DE9F74F02F0030AC2F3C313C2F38009A7 -:1045F000C2F3C108C2F3411E574600224FF00F0B11 -:104600000193CB0733D502F00703019C0125560027 -:104610009B00BAF1020F05FA02F504FA03FC4468A4 -:104620000BFA03F324EA05046FEA030344EA0904DE -:1046300044604FF00304856804FA06F625EA06058F -:104640006FEA060445EA08058560C56825EA06059F -:1046500045EA0E05C5601BD1072A13D8056A2B4011 -:1046600043EA0C03036203681C403C4304604908AE -:1046700022D04FEA490901324FEA88084FEA8E0EEC -:10468000BF00BEE7456A2B4043EA0C034362EAE7FA -:104690000568072A04EA050444EA0704046005D80B -:1046A000046A234043EA0C030362E0E7446A2340C0 -:1046B00043EA0C034362DAE703B0BDE8F08F000081 -:1046C000026843681143016003B118477047000056 -:1046D000024A136843F0C0031360704700100140A2 -:1046E000024A136843F0C00313607047007C004027 -:1046F00037B51A4C1A4D204600F0D2FA04F11400D6 -:10470000009400234FF40072164900F08FF94FF423 -:104710000072154904F138000094144B00F008FAB7 -:10472000134BC4E91735134C204600F0B9FA04F1D5 -:10473000140000234FF400720F49009400F076F942 -:104740000E4B4FF400720E4904F13800009400F053 -:10475000EFF90C4BC4E9173503B030BDA46300205A -:1047600000E1F5057C6400207C680020D14600084B -:1047700000100140106400207C660020E146000823 -:104780007C6A0020007C0040037C30B5284C002966 -:1047900018BF0C46012B0CD1264B984236D1264B24 -:1047A0001A6D42F010021A659A6F42F010029A6771 -:1047B0009B6F2268036EC16D03EB52038466B3FBEB -:1047C000F2F36268150442BF23F0070503F0070304 -:1047D00043EA4503CB60A36843F040034B60E368C2 -:1047E00043F001038B6042F4967343F001030B60C6 -:1047F0004FF0FF330B62510505D512F0102213D094 -:10480000B2F1805F12D080F8643030BD0B4B98421B -:10481000CFD1094B9A6C42F000429A641A6F42F071 -:1048200000421A671B6FC4E77F23ECE73F23EAE7E8 -:1048300000610008A46300200045025810640020B5 -:104840002DE9F047C66D05463768F46921073462E3 -:104850001AD014F0080118BF4FF48071E20748BF66 -:1048600041F02001A3074FF0300348BF41F0400161 -:10487000600748BF41F0800183F31188281DFFF7CE -:104880001FFF002383F31188E2050AD5302383F349 -:1048900011884FF48061281DFFF712FF002383F376 -:1048A00011884FF030094FF0000A14F0200838D179 -:1048B0003B0616D54FF0300905F1380A200610D511 -:1048C00089F31188504600F067F9002836DA08218C -:1048D000281DFFF7F5FE27F080033360002383F3E4 -:1048E0001188790614D5620612D5302383F3118816 -:1048F000D5E913239A4208D12B6C33B127F0400736 -:104900001021281DFFF7DCFE3760002383F3118898 -:10491000E30618D5AA6E1369ABB15069BDE8F0473C -:10492000184789F31188736A284695F8641019406E -:1049300000F0D0F98AF31188F469B6E7B06288F321 -:104940001188F469BAE7BDE8F0870000090100F1B9 -:104950006043012203F56143C9B283F8001300F0FC -:104960001F039A4043099B0003F1604303F5614331 -:10497000C3F880211A607047F8B51546826804466E -:104980000B46AA4200D28568A1692669761AB5420B -:104990000BD218462A46FDF795F9A3692B44A3616B -:1049A0002846A3685B1BA360F8BD0CD9AF1B184653 -:1049B0003246FDF787F93A46E1683044FDF782F95F -:1049C000E3683B44EBE718462A46FDF77BF9E368CA -:1049D000E5E7000083689342F7B50446154600D228 -:1049E0008568D4E90460361AB5420BD22A46FDF731 -:1049F00069F963692B4463612846A3685B1BA36064 -:104A000003B0F0BD0DD93246AF1B0191FDF75AF945 -:104A100001993A46E0683144FDF754F9E3683B44B4 -:104A2000E9E72A46FDF74EF9E368E4E710B50A44E2 -:104A30000024C361029B8460C16002610362C0E91B -:104A40000000C0E9051110BD08B5D0E90532934258 -:104A500001D1826882B98268013282605A1C426147 -:104A600019700021D0E904329A4224BFC36843611F -:104A700000F078FA002008BD4FF0FF30FBE700009F -:104A800070B5302304460E4683F31188A568A5B19E -:104A9000A368A269013BA360531CA3611578226936 -:104AA000934224BFE368A361E3690BB120469847B2 -:104AB000002383F31188284607E03146204600F0A2 -:104AC00041FA0028E2DA85F3118870BD2DE9F74F2D -:104AD00004460E4617469846D0F81C904FF0300A10 -:104AE0008AF311884FF0000B154665B12A4631460E -:104AF0002046FFF741FF034660B94146204600F0DB -:104B000021FA0028F1D0002383F31188781B03B029 -:104B1000BDE8F08FB9F1000F03D001902046C847DF -:104B2000019B8BF31188ED1A1E448AF31188DCE790 -:104B3000C160C361009B82600362C0E9051111443A -:104B4000C0E9000001617047F8B504460D461646FD -:104B5000302383F31188A768A7B1A368013BA36042 -:104B600063695A1C62611D70D4E904329A4224BF01 -:104B7000E3686361E3690BB120469847002080F346 -:104B8000118807E03146204600F0DCF90028E2DA1F -:104B900087F31188F8BD0000D0E9052310B59A42CB -:104BA00001D182687AB982680021013282605A1C80 -:104BB00082611C7803699A4224BFC368836100F054 -:104BC000D1F9204610BD4FF0FF30FBE72DE9F74F3C -:104BD00004460E4617469846D0F81C904FF0300A0F -:104BE0008AF311884FF0000B154665B12A4631460D -:104BF0002046FFF7EFFE034660B94146204600F02D -:104C0000A1F90028F1D0002383F31188781B03B0A9 -:104C1000BDE8F08FB9F1000F03D001902046C847DE -:104C2000019B8BF31188ED1A1E448AF31188DCE78F -:104C3000026843681143016003B1184770470000E0 -:104C40001430FFF743BF00004FF0FF331430FFF77D -:104C50003DBF00003830FFF7B9BF00004FF0FF3311 -:104C60003830FFF7B3BF00001430FFF709BF000072 -:104C70004FF0FF311430FFF703BF00003830FFF76B -:104C800063BF00004FF0FF323830FFF75DBF000018 -:104C9000012914BF6FF0130000207047FFF728BDF3 -:104CA000044B036000234360C0E902330123037413 -:104CB000704700BF1861000810B53023044683F325 -:104CC0001188FFF761FD02230020237480F311880F -:104CD00010BD000038B5C36904460D461BB9042158 -:104CE0000844FFF7A5FF294604F11400FFF7ACFEC6 -:104CF000002806DA201D4FF40061BDE83840FFF7B8 -:104D000097BF38BD00238268037503691B689968E3 -:104D10009142FBD25A68036042601060586070474D -:104D200000238268037503691B6899689142FBD868 -:104D30005A680360426010605860704708B50846C2 -:104D4000302383F311880B7D032B05D0042B0DD06A -:104D50002BB983F3118808BD8B6900221A604FF0CC -:104D6000FF338361FFF7CEFF0023F2E7D1E9003282 -:104D700013605A60F3E70000FFF7C4BF054BD96822 -:104D800008751868026853601A600122D8600275BD -:104D9000FBF7C2BC806C00200C4B30B5DD684B1CAF -:104DA00087B004460FD02B46094A684600F06CF9DC -:104DB0002046FFF7E3FF009B13B1684600F06EF951 -:104DC000A86907B030BDFFF7D9FFF9E7806C002074 -:104DD0003D4D0008044B1A68DB6890689B68984258 -:104DE00094BF002001207047806C0020084B10B554 -:104DF0001C68D868226853601A600122DC60227542 -:104E0000FFF78EFF01462046BDE81040FBF784BC4B -:104E1000806C0020044B1A68DB6892689B689A4299 -:104E200001D9FFF7E3BF7047806C002038B5074C0D -:104E300001230025064907482370656000F0D8FC6F -:104E40000223237085F3118838BD00BFE86E00206F -:104E500044610008806C002008B572B6044B1865E8 -:104E600000F006FB00F0D8FB024B03221A70FEE7AD -:104E7000806C0020E86E002000F046B9EFF311804E -:104E800020B9EFF30583302282F3118870470000C8 -:104E900010B530B9EFF30584C4F3080414B180F3FE -:104EA000118810BDFFF7B6FF84F31188F9E7000001 -:104EB0008B600223086108468B8270478368A3F1E8 -:104EC000840243F8142C026943F8442C426943F8E5 -:104ED000402C094A43F8242CC268A3F1200043F86F -:104EE000182C022203F80C2C002203F80B2C034A86 -:104EF00043F8102C704700BF31070008806C002079 -:104F000008B5FFF7DBFFBDE80840FFF735BF00003D -:104F1000024BDB6898610F20FFF730BF806C0020E8 -:104F2000302383F31188FFF7F3BF000008B5014673 -:104F3000302383F311880820FFF72EFF002383F32B -:104F4000118808BD064BDB6839B1426818605A60A9 -:104F5000136043600420FFF71FBF4FF0FF3070471E -:104F6000806C00200368984206D01A680260506086 -:104F700018469961FFF700BF70470000036810B53D -:104F80009C68A2420CD85C688A600B604C6021600F -:104F9000596099688A1A9A604FF0FF33836010BD98 -:104FA000121B1B68ECE700000A2938BF0A2170B504 -:104FB00004460D460A26601900F012FC00F0FAFBC8 -:104FC000041BA54203D8751C04462E46F3E70A2E9F -:104FD00004D90120BDE8704000F04ABC70BD00005B -:104FE000F8B5144B0D460A2A4FF00A07D96103F1B0 -:104FF0001001826038BF0A224160196914460160BD -:1050000048601861A81800F0DBFB00F0D3FB431BDD -:105010000646A34206D37C1C28192746354600F0D5 -:10502000DFFBF2E70A2F04D90120BDE8F84000F0C9 -:105030001FBCF8BD806C0020F8B506460D4600F098 -:10504000B9FB0F4A134653F8107F9F4206D12A46F8 -:1050500001463046BDE8F840FFF7C2BFD169BB68E2 -:10506000441A2C1928BF2C46A34202D92946FFF71F -:105070009BFF224631460348BDE8F840FFF77EBF5C -:10508000806C0020906C0020C0E90323002310B442 -:105090005DF8044B4361FFF7CFBF000010B5194C1A -:1050A000236998420DD08168D0E9003213605A60BC -:1050B0009A680A449A60002303604FF0FF33A361AB -:1050C00010BD0268234643F8102F5360002202608F -:1050D00022699A4203D1BDE8104000F07BBB93687F -:1050E00081680B44936000F065FB2269E169926876 -:1050F000441AA242E4D91144BDE81040091AFFF74E -:1051000053BF00BF806C00202DE9F047DFF8BC8062 -:1051100008F110072C4ED8F8105000F04BFBD8F8CF -:105120001C40AA68031B9A423ED814444FF0000961 -:10513000D5E90032C8F81C4013605A60C5F80090E9 -:10514000D8F81030B34201D100F044FB89F3118844 -:10515000D5E9033128469847302383F311886B69DA -:10516000002BD8D000F026FB6A69A0EB0409824628 -:105170004A450DD2022000F07BFB0022D8F8103007 -:10518000B34208D151462846BDE8F047FFF728BF93 -:10519000121A2244F2E712EB09092946384638BFB1 -:1051A0004A46FFF7EBFEB5E7D8F81030B34208D017 -:1051B0001444C8F81C00211AA960BDE8F047FFF7A5 -:1051C000F3BEBDE8F08700BF906C0020806C00202B -:1051D00000207047FEE70000704700004FF0FF30EE -:1051E00070470000BFF34F8F044B1A695107FCD181 -:1051F000D3F810215207F8D1704700BF00200052A9 -:1052000008B50D4B1B78ABB9FFF7ECFF0B4BDA6819 -:10521000D10704D50A4A5A6002F188325A60D3F89D -:105220000C21D20706D5064AC3F8042102F18832C0 -:10523000C3F8042108BD00BFF06E0020002000521A -:105240002301674508B5114B1B78F3B9104B1A6958 -:10525000510703D5DA6842F04002DA60D3F8102132 -:10526000520705D5D3F80C2142F04002C3F80C21B7 -:10527000FFF7B8FF064BDA6842F00102DA60D3F8B4 -:105280000C2142F00102C3F80C2108BDF06E002091 -:10529000002000520F289ABF00F5806040040020D3 -:1052A000704700004FF40030704700001020704736 -:1052B0000F2808B50BD8FFF7EDFF00F500330268A3 -:1052C000013204D104308342F9D1012008BD00200D -:1052D000FCE700000F2838B505463FD8FFF782FFEE -:1052E0001F4CFFF78DFF4FF0FF3307286361C4F8B1 -:1052F00014311DD82361FFF775FF030243F0240327 -:10530000E360E36843F08003E36023695A07FCD459 -:105310002846FFF767FFFFF7BDFF4FF4003100F0AD -:1053200057F92846FFF78EFFBDE83840FFF7C0BFAA -:10533000C4F81031FFF756FFA0F108031B0243F039 -:105340002403C4F80C31D4F80C3143F08003C4F8C2 -:105350000C31D4F810315B07FBD4D9E7002038BDFD -:10536000002000522DE9F84F05460C46104645EA4C -:105370000203DE0602D00020BDE8F88F20F01F00F7 -:10538000DFF8BCB0DFF8BCA0FFF73AFF04EB000881 -:10539000444503D10120FFF755FFEDE720222946C0 -:1053A000204600F0F7FD10B920352034F0E72B46F9 -:1053B00005F120021F68791CDDD104339A42F9D12E -:1053C00005F178431B481C4EB3F5801F1B4B38BFBB -:1053D000184603F1F80332BFD946D1461E46FFF7FF -:1053E00001FF0760A5EB040C336804F11C0143F0D6 -:1053F00002033360231FD9F8007017F00507FAD1B4 -:1054000053F8042F8B424CF80320F4D1BFF34F8F95 -:10541000FFF7E8FE4FF0FF332022214603602846C5 -:10542000336823F00203336000F0B4FD0028BBD0E2 -:105430003846B0E7142100520C20005214200052CC -:10544000102000521021005210B5084C237828B1CA -:105450001BB9FFF7D5FE0123237010BD002BFCD034 -:105460002070BDE81040FFF7EDBE00BFF06E0020D9 -:1054700038B5054D00240334696855F80C0B00F06D -:10548000B9F8122CF7D138BD50610008084600F079 -:1054900079BD000070B5104E82B0FFF7EFFC0546F5 -:1054A00000F088F9326803469042336037BF0B4AF8 -:1054B0000A495168146836BF0131D1E90041516091 -:1054C0000419284641F100010191FFF7E1FC204653 -:1054D000019902B070BD00BFF46E0020F86E00208C -:1054E00070B5124E82B0FFF7C9FC054600F062F9B4 -:1054F000326803469042336037BF0D4A0C49516809 -:10550000146836BF0131D1E90041516004192846C1 -:1055100041F100010191FFF7BBFC4FF47A720023C7 -:1055200020460199FAF7E4FE02B070BDF46E002047 -:10553000F86E00200244074BD2B210B5904200D161 -:1055400010BD441C00B253F8200041F8040BE0B237 -:10555000F4E700BF504000580E4B30B51C6F2404D8 -:1055600005D41C6F1C671C6F44F400441C670A4C74 -:1055700002442368D2B243F480732360074B904205 -:1055800000D130BD441C51F8045B00B243F82050F8 -:10559000E0B2F4E700440258004802585040005876 -:1055A00007B5012201A90020FFF7C4FF019803B04D -:1055B0005DF804FB13B50446FFF7F2FFA04205D0E7 -:1055C000012201A900200194FFF7C6FF02B010BD1F -:1055D0000144BFF34F8F064B884204D3BFF34F8F74 -:1055E000BFF36F8F7047C3F85C022030F4E700BF51 -:1055F00000ED00E00144BFF34F8F064B884204D317 -:10560000BFF34F8FBFF36F8F7047C3F87002203026 -:10561000F4E700BF00ED00E070470000074B45F2E3 -:1056200055521A6002225A6040F6FF729A604CF698 -:10563000CC421A600122024B1A7070470048005891 -:10564000046F0020034B1B781BB1034B4AF6AA22C0 -:105650001A607047046F002000480058034B1A6816 -:105660001AB9034AD2F8D0241A607047006F00209C -:1056700000400258024B4FF48032C3F8D0247047E8 -:105680000040025808B5FFF7E9FF024B1868C0F365 -:10569000806008BD006F002070B5BFF34F8FBFF36F -:1056A0006F8F1A4A0021C2F85012BFF34F8FBFF319 -:1056B0006F8F536943F400335361BFF34F8FBFF3D0 -:1056C0006F8FC2F88410BFF34F8FD2F8803043F64B -:1056D000E074C3F3C900C3F34E335B0103EA04066D -:1056E000014646EA81750139C2F86052F9D2203B81 -:1056F00013F1200FF2D1BFF34F8F536943F480337E -:105700005361BFF34F8FBFF36F8F70BD00ED00E0AB -:10571000FEE70000214B2248224A70B5904237D361 -:10572000214BC11EDA1C121A22F003028B4238BF31 -:1057300000220021FCF7D8FA1C4A0023C2F884306A -:10574000BFF34F8FD2F8803043F6E074C3F3C90043 -:10575000C3F34E335B0103EA0406014646EA817552 -:105760000139C2F86C52F9D2203B13F1200FF2D16B -:10577000BFF34F8FBFF36F8FBFF34F8FBFF36F8FA9 -:105780000023C2F85032BFF34F8FBFF36F8F70BD4D -:1057900053F8041B40F8041BC0E700BF80630008F7 -:1057A000086F0020086F0020086F002000ED00E067 -:1057B00000F01AB9014B586A704700BF000C004056 -:1057C000034B002258631A610222DA60704700BF5F -:1057D000000C0040014B0022DA607047000C0040D2 -:1057E000014B5863704700BF000C0040FEE700000B -:1057F00070B51B4B0025044686B058600E46856286 -:105800000163FEF78DFE04F11003A560E562C4E9B3 -:1058100004334FF0FF33C4E90044C4E90635FFF711 -:10582000C9FF2B46024604F134012046C4E908238F -:1058300080230C4A2565FFF73BFB01230A4AE06001 -:1058400000920375684672680192B268CDE902233E -:10585000064BCDE90435FFF753FB06B070BD00BF22 -:10586000E86E0020986100089D610008ED5700086F -:10587000024AD36A1843D062704700BF806C002090 -:105880004B6843608B688360CB68C3600B6943617E -:105890004B6903628B6943620B68036070470000C9 -:1058A00008B53A4B40F2FF713948D3F888200A43D3 -:1058B000C3F88820D3F8882022F4FF6222F0070280 -:1058C000C3F88820D3F88830324B1A6C0A431A6424 -:1058D0009A6E0A439A66304A9B6E1146FFF7D0FFD4 -:1058E00000F5806002F11C01FFF7CAFF00F580603F -:1058F00002F13801FFF7C4FF00F5806002F15401A6 -:10590000FFF7BEFF00F5806002F17001FFF7B8FFFE -:1059100000F5806002F18C01FFF7B2FF00F58060B6 -:1059200002F1A801FFF7ACFF00F5806002F1C401AD -:10593000FFF7A6FF00F5806002F1E001FFF7A0FF8E -:1059400000F5806002F1FC01FFF79AFF02F58C710F -:1059500000F58060FFF794FF00F004F90F4BD3F8D7 -:10596000902242F00102C3F89022D3F8942242F030 -:105970000102C3F894220522C3F898204FF0605228 -:10598000C3F89C20064AC3F8A02008BD0044025872 -:105990000000025800450258A461000800ED00E034 -:1059A0001F00080308B500F0C9FAFFF73FFA0B4BD8 -:1059B000DA6B42F04002DA635A6E22F040025A6615 -:1059C0005B6E074B1A6842F008021A601A6842F0D0 -:1059D00004021A60BDE80840FFF740BE00450258C7 -:1059E00000180248704700000E4B9A6C42F0080203 -:1059F0009A641A6F42F008021A670B4A1B6FD36B46 -:105A000043F00803D363C722084B9A624FF0FF327A -:105A1000DA6200229A615A63DA605A6001225A619E -:105A20001A607047004502580010005C000C0040EE -:105A3000094A08B51169D3680B40D9B29B076FEAD0 -:105A40000101116107D5302383F31188FFF714FAA0 -:105A5000002383F3118808BD000C0040044BDA6B6F -:105A60000243DA635A6E104358665B6E704700BF9C -:105A7000004502583A4B4FF0FF31D3F8802062F0D6 -:105A80000042C3F88020D3F8802002F00042C3F81F -:105A90008020D3F88020D3F88420C3F88410D3F872 -:105AA00084200022C3F88420D3F88400D86F40F00B -:105AB000FF4040F4FF0040F4DF4040F07F00D86733 -:105AC000D86F20F0FF4020F4FF0020F4DF4020F0EA -:105AD0007F00D867D86FD3F888006FEA40506FEA2C -:105AE0005050C3F88800D3F88800C0F30A00C3F808 -:105AF0008800D3F88800D3F89000C3F89010D3F84A -:105B00009000C3F89020D3F89000D3F89400C3F825 -:105B10009410D3F89400C3F89420D3F89400D3F8E9 -:105B20009800C3F89810D3F89800C3F89820D3F8D9 -:105B30009800D3F88C00C3F88C10D3F88C00C3F80D -:105B40008C20D3F88C00D3F89C00C3F89C10D3F8B9 -:105B50009C10C3F89C20D3F89C3000F0BFB900BF64 -:105B60000044025808B50122504BC3F80821504B9D -:105B70005A6D42F002025A65DA6F42F00202DA67A9 -:105B80000422DB6F4B4BDA605A689104FCD54A4A19 -:105B90001A6001229A60494ADA6000221A614FF4C1 -:105BA00040429A61434B9A699204FCD51A6842F4C8 -:105BB00080721A60424B1A6F12F4407F04D04FF487 -:105BC00080321A6700221A671A6842F001021A60CE -:105BD0003B4B1A685007FCD500221A611A6912F073 -:105BE0003802FBD1012119604FF0804159605A679A -:105BF000344ADA62344A1A611A6842F480321A600E -:105C00002F4B1A689103FCD51A6842F480521A602F -:105C10001A689204FCD52D4A2D499A6200225A63D3 -:105C2000196301F57C01DA6301F5E77199635A6440 -:105C3000284A1A64284ADA621A6842F0A8521A609E -:105C40001F4B1A6802F02852B2F1285FF9D148229E -:105C50009A614FF48862DA6140221A621F4ADA645C -:105C60001F4A1A651F4A5A651F4A9A6532231F4AFE -:105C70001360136803F00F03022BFAD1104A136963 -:105C800043F003031361136903F03803182BFAD1AF -:105C90004FF00050FFF7E2FE4FF08040FFF7DEFECE -:105CA0004FF00040BDE80840FFF7D8BE008000512B -:105CB000004502580048025800C000F004000001EE -:105CC000004402580000FF01008890083220600064 -:105CD00063020901470E0508DD0BBF01200000200B -:105CE000000001100910E000000101100020005226 -:105CF0004FF0B04208B5D2F8883003F00103C2F883 -:105D0000883023B1044A13680BB150689847BDE846 -:105D10000840FEF72DBC00BF246300204FF0B042C6 -:105D200008B5D2F8883003F00203C2F8883023B1F6 -:105D3000044A93680BB1D0689847BDE80840FEF765 -:105D400017BC00BF246300204FF0B04208B5D2F862 -:105D5000883003F00403C2F8883023B1044A136981 -:105D60000BB150699847BDE80840FEF701BC00BF81 -:105D7000246300204FF0B04208B5D2F8883003F019 -:105D80000803C2F8883023B1044A93690BB1D06983 -:105D90009847BDE80840FEF7EBBB00BF2463002036 -:105DA0004FF0B04208B5D2F8883003F01003C2F8C3 -:105DB000883023B1044A136A0BB1506A9847BDE892 -:105DC0000840FEF7D5BB00BF246300204FF0B0436E -:105DD00010B5D3F8884004F47872C3F88820A3067D -:105DE00004D5124A936A0BB1D06A9847600604D56D -:105DF0000E4A136B0BB1506B9847210604D50B4A22 -:105E0000936B0BB1D06B9847E20504D5074A136C2E -:105E10000BB1506C9847A30504D5044A936C0BB1A1 -:105E2000D06C9847BDE81040FEF7A2BB2463002069 -:105E30004FF0B04310B5D3F8884004F47C42C3F867 -:105E40008820620504D5164A136D0BB1506D984732 -:105E5000230504D5124A936D0BB1D06D9847E00429 -:105E600004D50F4A136E0BB1506E9847A10404D5A8 -:105E70000B4A936E0BB1D06E9847620404D5084A62 -:105E8000136F0BB1506F9847230404D5044A936FE6 -:105E90000BB1D06F9847BDE81040FEF769BB00BF5B -:105EA0002463002008B50348FEF7CAFCBDE808409B -:105EB000FEF75EBBA463002008B50348FEF7C0FCF4 -:105EC000BDE80840FEF754BB1064002008B5FFF79A -:105ED000AFFDBDE80840FEF74BBB0000062108B54A -:105EE0000846FEF733FD06210720FEF72FFD0621A9 -:105EF0000820FEF72BFD06210920FEF727FD0621CD -:105F00000A20FEF723FD06211720FEF71FFD0621BC -:105F10002820FEF71BFD09217A20FEF717FD072137 -:105F20003220FEF713FD0C212520FEF70FFD0C217A -:105F30005320BDE80840FEF709BD000008B5FFF793 -:105F400099FDFEF73FFBFEF7A9FEFFF74BFDBDE80D -:105F50000840FFF72DBC00000B460146184600F034 -:105F600003B8000000F00EB810B5054C13462CB174 -:105F70000A4601460220AFF3008010BD2046FCE730 -:105F800000000000024B01461868FFF77FBA00BF0F -:105F90003C22002010B501390244904201D100207A -:105FA00005E0037811F8014FA34201D0181B10BD82 -:105FB0000130F2E72DE9F041A3B1C91A1778014485 -:105FC000044603F1FF3C8C42204601D9002009E041 -:105FD0000578BD4204F10104F5D10CEB0405D61897 -:105FE000A54201D1BDE8F08115F8018D16F801ED4B -:105FF000F045F5D0E7E70000034611F8012B03F860 -:10600000012B002AF9D17047636F6D2E63756265AD -:1060100070696C6F742E6865726534666300000089 -:1060200053544D333248373F3F3F0053544D333282 -:10603000483733782F3732780053544D333248374E -:1060400034332F3735332F373530000001105A00E5 -:1060500003105900012058000320560040A2E4F12B -:10606000646891060041A3E5F265699207000000AB -:1060700043414E464449666163653A204D657373FA -:106080006167652052414D204F766572666C6F776F -:10609000210000004261642043414E49666163650E -:1060A00020696E6465782E00000100000001FF0089 -:1060B00000A0004000A4004000000000000000001C -:1060C000912C000869250008CD33000861250008DF -:1060D000D9250008E929000851270008A125000852 -:1060E000A52500087D25000865250008A9290008C8 -:1060F0008925000835350008952500087D29000808 -:1061000000960000000000000000000000000000F9 -:106110000000000000000000000000005D4C0008CE -:10612000494C0008854C0008714C00087D4C000863 -:10613000694C0008554C0008414C0008914C00087F -:106140006330000040610008D86C0020E86E002039 -:1061500000000020000002000200000000010030EA -:1061600000FF0300080000000000002400000800F9 -:10617000040000000004000000FC00000200000019 -:10618000000004300080000008000000000000381B -:1061900000000100010000006D61696E0069646C1F -:1061A000650000000000002800000000AAAAAAAABA -:1061B00000000024FFFF00000000000000000000BD -:1061C00000A0550A00000000AAAA9AAA00500000E8 -:1061D000FFF20000000000770000990000000000BE -:1061E00000000000AAAAAAAA00000000FFFF000009 -:1061F00000000000000000005A0000000000000045 -:106200009AAAAAAA00000000F3FF0000990000006B -:10621000000000000A00000000000000AAAAAAAACC -:1062200005000000FFFF00008800000000000000E3 -:106230000000000000000000AAAAAAAA00000000B6 -:10624000FFFF000000000000000000000000000050 -:1062500000000000AAAAAAAA00000000FFFF000098 -:10626000000000000000000000000000000000002E -:10627000AAAAAAAA00000000FFFF00000000000078 -:10628000000000000000000000000000AAAAAAAA66 -:1062900000000000FFFF0000000000000000000000 -:1062A0000000000000000000AAAAAAAA0000000046 -:1062B000FFFF0000000000000000000000000000E0 -:1062C00000000000AAAAAAAA00000000FFFF000028 -:1062D000000000000000000048A0FF7F0100000057 -:1062E000130400000000000000001800000000007F -:1062F000FE2A0100D2040000FF000000A463002079 -:1063000010640020000000002060000883040000EA -:106310002B60000850040000396000084022002073 -:10632000000000000000000000000000000000006D -:10633000000000000000000000000000000000005D -:10634000000000000000000000000000000000004D -:10635000000000000000000000000000000000003D -:10636000000000000000000000000000000000002D -:10637000000000000000000000000000000000001D +:1000000000070020F102000849330008013300080E +:10001000293300080133000821330008F3020008E7 +:10002000F3020008F3020008F30200082D43000861 +:10003000F3020008F3020008F3020008F3020008CC +:10004000F3020008F3020008F3020008F3020008BC +:10005000F3020008F30200084D5F0008795F000812 +:10006000A55F0008D15F0008FD5F0008F1430008AC +:100070001944000845440008714400089D440008E4 +:10008000C5440008F1440008F3020008B13200083A +:10009000D9320008C5320008ED3200082960000896 +:1000A000F3020008F3020008F3020008F30200085C +:1000B000F3020008F3020008F3020008F30200084C +:1000C000F3020008F3020008F3020008F30200083C +:1000D000F302000801610008F3020008F3020008BF +:1000E0008D600008F3020008F3020008F302000824 +:1000F000F3020008F3020008F30200081D4500089F +:10010000F3020008F302000829610008F302000866 +:10011000F3020008F3020008F3020008F3020008EB +:1001200049450008714500089D450008C94500087B +:10013000F5450008F3020008F3020008F302000886 +:10014000F3020008F3020008F3020008F3020008BB +:100150001D4600084946000875460008F3020008DD +:10016000F3020008F3020008F3020008F30200089B +:10017000F3020008F3020008F3020008F30200088B +:10018000F3020008F3020008F302000815610008FA +:10019000F3020008F3020008F3020008F30200086B +:1001A000F3020008F3020008F3020008F30200085B +:1001B000F3020008F3020008F3020008F30200084B +:1001C000F3020008F3020008F3020008F30200083B +:1001D000F3020008F3020008F3020008F30200082B +:1001E000F3020008F3020008F3020008F30200081B +:1001F000F3020008F3020008F3020008F30200080B +:10020000F3020008F3020008F3020008F3020008FA +:10021000F3020008F3020008F3020008F3020008EA +:10022000F3020008F3020008F3020008F3020008DA +:10023000F3020008F3020008F3020008F3020008CA +:10024000F3020008F3020008F3020008F3020008BA +:10025000F3020008F3020008F3020008F3020008AA +:10026000F3020008F3020008F3020008F30200089A +:10027000F3020008F3020008F3020008F30200088A +:10028000F3020008F3020008F3020008F30200087A +:10029000F3020008F3020008F3020008F30200086A +:1002A000F3020008F3020008F3020008F30200085A +:1002B000F3020008F3020008F3020008F30200084A +:1002C000F3020008F3020008F3020008F30200083A +:1002D000F3020008F3020008F3020008F30200082A +:1002E000CD16000800000000000000000000000023 +:1002F00002E000F000F8FEE772B6374880F30888A5 +:10030000364880F3098836483649086040F20000D4 +:10031000CCF200004EF63471CEF200010860BFF35B +:100320004F8FBFF36F8F40F20000C0F2F0004EF627 +:100330008851CEF200010860BFF34F8FBFF36F8F7B +:100340004FF00000E1EE100A4EF63C71CEF20001D3 +:100350000860062080F31488BFF36F8F05F0C6FA9B +:1003600005F0C8FB4FF055301F491B4A91423CBF76 +:1003700041F8040BFAE71D49184A91423CBF41F885 +:10038000040BFAE71A491B4A1B4B9A423EBF51F82D +:10039000040B42F8040BF8E700201849184A914270 +:1003A0003CBF41F8040BFAE705F0DEFA05F024FC47 +:1003B000144C154DAC4203DA54F8041B8847F9E796 +:1003C00000F042F8114C124DAC4203DA54F8041B11 +:1003D0008847F9E705F0C6BA00070020002300208F +:1003E0000000000808ED00E00001002000070020E8 +:1003F0005866000800230020A0230020A02300202E +:100400007C700020E0020008E4020008E40200081A +:10041000E40200082DE9F04F2DED108AC1F80CD050 +:10042000D0F80CD0BDEC108ABDE8F08F002383F328 +:1004300011882846A047002004F098FEFEE704F04B +:1004400021FE00DFFEE70000F8B501F055F901F0EC +:1004500003FA01F04DFB05F0CDF9074605F03CFA33 +:100460000546A8BB1F4B9F4232D001339F4232D07A +:1004700027F0FF021C4B9A4230D12E4642F21074F4 +:10048000F8B200F06FFF00F073FF08B100242646B9 +:1004900001F076FD20B10024032000F079F8264613 +:1004A00035B1124B9F4203D0002405F00DFA2646C9 +:1004B000002005F0A9F90EB100F080F801F0EAFA89 +:1004C00000F08AFF204600F00BF900F077F8F9E71A +:1004D0002E460024D7E704460126D4E7064641F21B +:1004E0008834D0E7010007B0000008B0263A09B010 +:1004F00008B501F07DF9A0F120035842584108BD2C +:1005000007B541F21203022101A8ADF8043001F051 +:100510008DF903B05DF804FB38B5302383F31188FF +:10052000174803680BB104F0DFFE0023154A4FF4AF +:100530007A71134804F0CEFE002383F31188124C25 +:10054000236813B12368013B2360636813B16368B8 +:10055000013B63600D4D2B7833B963687BB9022092 +:1005600001F02EFA322363602B78032B07D16368E6 +:100570002BB9022001F024FA4FF47A73636038BD7E +:10058000A023002019050008C0240020B823002063 +:10059000084B187003280CD8DFE800F008050208A3 +:1005A000022001F00BBA022001F006BA024B002231 +:1005B0005A607047B8230020C0240020F8B501F02D +:1005C000DFFC30B13E4B03221A7000223D4B5A60D3 +:1005D000F8BD3D4B3D4A1C4619680131F8D0043343 +:1005E0009342F9D162683A4B9A42F1D9394B9B68F0 +:1005F00003F1006303F580239A42E9D205F038F94C +:1006000005F04AF9002001F04DF90220FFF7C0FF84 +:10061000314B00219A6C99641A6F19671A6FDA6C62 +:10062000D9645A6F59675A6F1A6D19659A6F99672D +:100630009B6F72B64FF0E023C3F8084DD4E9000475 +:10064000BFF34F8FBFF36F8F244AC2F88410BFF3FC +:100650004F8F536923F480335361BFF34F8FD2F828 +:10066000803043F6E076C3F3C905C3F34E335B0134 +:1006700003EA060C29464CEA81770139C2F8747204 +:10068000F9D2203B13F1200FF2D1BFF34F8FBFF30C +:100690006F8FBFF34F8FBFF36F8F536923F4003316 +:1006A00053610023C2F85032BFF34F8FBFF36F8FF7 +:1006B000302383F31188854680F30888204787E735 +:1006C000B8230020C02400200000040820000408F3 +:1006D000FFFF0308002300200045025800ED00E062 +:1006E0002DE9F04F93B0B74B2022FF2100900AA8CC +:1006F0009D6801F079F9B44A1378A3B90121B34890 +:1007000011700360302383F3118803680BB104F088 +:10071000EBFD0023AE4A4FF47A71AC4804F0DAFDE9 +:10072000002383F31188009B13B1AA4B009A1A602F +:10073000A94A1378032B03D000231370A54A5360F2 +:100740004FF0000A009CD3465646D146012001F0E6 +:1007500035F924B19F4B1B68002B00F02C82002040 +:1007600001F046F80390039B002B01DA00F088FEAD +:10077000039B002BEDDB012001F01EF9039B213BC5 +:100780001F2BE3D801A252F823F000BF0D08000888 +:1007900035080008C90800084D0700084D07000883 +:1007A0004D0700085B0900082B0B0008450A0008EC +:1007B000A70A0008CF0A0008F50A00084D0700083C +:1007C000070B00084D070008790B0008AD0800086A +:1007D0004D070008BD0B000819080008AD08000807 +:1007E0004D070008A70A00084D0700084D0700083C +:1007F0004D0700084D0700084D0700084D07000889 +:100800004D0700084D070008C90800080220FFF73F +:100810006FFE002840F0F981009B022105A8BAF183 +:10082000000F08BF1C4641F21233ADF8143000F03F +:10083000FDFF8BE74FF47A7000F0DAFF071EEBDB69 +:100840000220FFF755FE0028E6D0013F052F00F2F9 +:10085000DE81DFE807F0030A0D10133605230421BB +:1008600005A8059300F0E2FF17E004215548F9E7D9 +:1008700004215A48F6E704215948F3E74FF01C08D1 +:10088000404608F1040801F00FF80421059005A87E +:1008900000F0CCFFB8F12C0FF2D101204FF000098D +:1008A00000FA07F747EA0B0B5FFA8BFB01F0E8F859 +:1008B00026B10BF00B030B2B08BF0024FFF720FE23 +:1008C00044E704214748CDE7002EA5D00BF00B03E9 +:1008D0000B2BA1D10220FFF70BFE074600289BD06F +:1008E0000120002600F0DEFF0220FFF751FE1FFA74 +:1008F00086F8404600F0E6FF0446B0B10399404652 +:100900000136A1F140025142514100F0F3FF0028AD +:10091000EDD1BA46044641F21213022105A83E4623 +:10092000ADF8143000F082FF10E725460120FFF7F4 +:100930002FFE244B9B68AB4207D9284600F0B4FF3A +:10094000013040F067810435F3E70025224BBA46B9 +:100950003E461D701F4B5D60A8E7002E3FF45CAF64 +:100960000BF00B030B2B7FF457AF0220FFF710FEA9 +:10097000322000F03DFFB0F10008FFF64DAF18F057 +:1009800003077FF449AF0F4A08EB050392689342CF +:100990003FF642AFB8F5807F3FF73EAF124BB84508 +:1009A000019323DD4FF47A7000F022FF0390039A45 +:1009B000002AFFF631AF039A0137019B03F8012BA0 +:1009C000EDE700BF00230020BC240020A02300206E +:1009D00019050008C0240020B823002004230020AB +:1009E000082300200C230020BC230020C820FFF790 +:1009F0007FFD074600283FF40FAF1F2D11D8C5F12A +:100A000020020AAB25F0030084494245184428BF60 +:100A10004246019200F0D6FF019AFF217F4800F084 +:100A2000E3FF4FEAA803C8F387027C4928460193F5 +:100A300000F0E2FF064600283FF46DAF019B05EB96 +:100A4000830533E70220FFF753FD00283FF4E4AEAF +:100A500000F062FF00283FF4DFAE0027B846704B7D +:100A60009B68BB4218D91F2F11D80A9B01330ED0A7 +:100A700027F0030312AA134453F8203C0593404681 +:100A8000042205A9043701F065FA8046E7E73846F5 +:100A900000F00AFF0590F2E7CDF81480042105A8C4 +:100AA00000F0C4FE02E70023642104A8049300F0D0 +:100AB000B3FE00287FF4B0AE0220FFF719FD002836 +:100AC0003FF4AAAE049800F01DFF0590E6E700236E +:100AD000642104A8049300F09FFE00287FF49CAEDC +:100AE0000220FFF705FD00283FF496AE049800F0C1 +:100AF0000BFFEAE70220FFF7FBFC00283FF48CAE77 +:100B000000F01AFFE1E70220FFF7F2FC00283FF4B3 +:100B100083AE05A9142000F015FF074604210490B8 +:100B200004A800F083FE3946B9E7322000F060FEE9 +:100B3000071EFFF671AEBB077FF46EAE384A07EBB7 +:100B40000903926893423FF667AE0220FFF7D0FC9C +:100B500000283FF461AE27F003074F44B9453FF446 +:100B6000A5AE484609F1040900F09EFE0421059057 +:100B700005A800F05BFEF1E74FF47A70FFF7B8FCD0 +:100B800000283FF449AE00F0C7FE002844D00A9B7D +:100B900001330BD008220AA9002000F02DFF002805 +:100BA0003AD02022FF210AA800F01EFFFFF7A8FC80 +:100BB0001C4804F0E1FA13B0BDE8F08F002E3FF4BA +:100BC0002BAE0BF00B030B2B7FF426AE002364211E +:100BD00005A8059300F020FE074600287FF41CAE10 +:100BE0000220FFF785FC804600283FF415AEFFF792 +:100BF00087FC41F2883004F0BFFA059800F05EFFF0 +:100C000046463C4600F03CFFA0E506464EE64FF067 +:100C1000000901E6BA467EE637467CE6BC230020A2 +:100C200000230020A0860100094A49F269001368E8 +:100C300099B21B0C00FB013344F250611360054B69 +:100C4000186882B2000C01FB0200186080B2704785 +:100C500014230020102300200021102210B5044688 +:100C600000F0C2FE034B03CB206061601868A060F7 +:100C700010BD00BF00E8F11F2DE9F041ADF54E7D3C +:100C80000D46002140F275126CAC07460EA80D917E +:100C900000F0AAFE4FF4C4720021204600F0A4FE2A +:100CA0000DF1340802F058FB4FF47A72264BB0FB7A +:100CB000F2F0186093E80700022384E807000DF5BE +:100CC000E9702382FFF7C8FF41F204331F4907A8E8 +:100CD000238405F0BFFA15230DF2E3220DF12C0C4D +:100CE00084F8323107AB1E46083203CE664542F81F +:100CF000080C42F8041C3346F5D1306841461060B8 +:100D0000204633791371012200F048FF002380B29E +:100D1000E97E0393AB7E029305F11903019301234E +:100D2000009307A3D3E90023CDE90480384602F0FD +:100D3000D1FE0DF54E7DBDE8F08100BFAFF3008020 +:100D40009E6AC421818A46EEC8240020646200089D +:100D50002DE9F0412C4CDAB080460D46237A5BBB7E +:100D600027A9284601F028F80746002842D19DF817 +:100D70009D60C82E3ED801464FF4A662204600F082 +:100D800033FE4FF4807332460DF19E01C4F8F83102 +:100D90004FF4007304F109002644C4F80C334FF4F7 +:100DA0004073C4F8203400F00DFE9DF89C3077723B +:100DB00023720BB9EB7E237206AC8122002127A897 +:100DC00000F012FE0122214627A801F031F800238D +:100DD00080B2E97E0393AB7E029305F11903019380 +:100DE0002823CDE904400093404605A3D3E900231E +:100DF00002F070FE5AB0BDE8F08100BFAFF3008092 +:100E000026417272DF25D7B7905E0020F0B5254EDF +:100E10004FF48A75F1B0002405FB006596F8D830D0 +:100E2000D822214685F8DC303AA885F8E84006AF9C +:100E300000F0DAFD06F1090000F0CEFDD5F8E4304F +:100E4000C2B206F109018DF8F0000DF1F100CDE913 +:100E50003A3400F0B7FD394601223AA801F014F8FF +:100E6000082380B2317ACDE9047001270E48CDE91C +:100E7000023706F1D80301933023009307A3D3E987 +:100E8000002302F027FEA04206DD02F065FAC5F855 +:100E9000E000384671B0F0BD2046FBE778F6339F9E +:100EA00093CACD8D905E0020E03400202DE9F04FF4 +:100EB000264F87B0DFF8A080254E384602F036FE78 +:100EC000034600283AD00024224DADF81440A14634 +:100ED0000294A246CDE90344027B8DF8142003AAB4 +:100EE0009968406803C21B6843F0004302932B6873 +:100EF00004F5A664D3F810B002F030FA10EB080243 +:100F0000CDF800A0284605F5A65541F1000302A939 +:100F1000D8470028C8BF49F00109B4F5266FE6D1CB +:100F2000B9F1000F05D0384602F004FE86F800A0A3 +:100F3000C3E73378072B04D80133337007B0BDE81B +:100F4000F08F024802F0F6FDF8E700BFE034002021 +:100F5000C56300201035002040420F0070B50D46DB +:100F600014461E4602F012FD50B9022E10D1012C7B +:100F70000ED112A3D3E900230120C5E9002307E025 +:100F8000282C10D005D8012C09D0052C0FD000201A +:100F900070BD302CFBD10BA3D3E90023ECE70BA3EE +:100FA000D3E90023E8E70BA3D3E90023E4E70BA38D +:100FB000D3E90023E0E700BFAFF30080401DA1208C +:100FC00026812A0B78F6339F93CACD8D9E6AC42161 +:100FD000818A46EE26417272DF25D7B7F017304A74 +:100FE00039059E5638B505460E4C0021013500F0F6 +:100FF00081FCA4F82C55B4F82C0500F063FC78B102 +:10100000B4F82C0500F06EFC014648B9B4F82C0584 +:1010100000F070FCB4F82C350133A4F82C35EAE765 +:1010200038BD00BF905E0020F8B50D4C02260D4F74 +:10103000A4F5805343F8307C237E3BB965692DB11C +:10104000284601F01BF8284605F0BAF82046A4F51A +:10105000A65401F013F8012E00D1F8BD0126E7E7F0 +:10106000005A00201C6300082DE9F04F8FB00546A0 +:101070000C4600AF02F08AFC002849D1237E022BE7 +:101080001BD1E38A012B18D102F066F90646FFF75F +:10109000CBFD03464FF4C87006F51676DFF8C08224 +:1010A000B3FBF0F202FB103316FA83F3C8F80030FA +:1010B000E37E33B9A34B00221A703C37BD46BDE82E +:1010C000F08F07F12401204600F034FE0028F4D10F +:1010D00007F11400FFF7C0FD97F8264007F114014F +:1010E00007F12700224605F083F80028E2D10F2CF3 +:1010F00008D8944B1C70D8F80030A3F51673C8F8C4 +:101100000030DAE797F82410284602F037FCD4E7DD +:10111000E38A282B2BD010D8012B23D0052BCCD140 +:10112000BFF34F8F8849894BCA6802F4E0621343CA +:10113000CB60BFF34F8F00BFFDE7302BBDD1844E96 +:10114000E17E327A9142B8D1607E3146002291F838 +:10115000DC50854200F0A580013201F58A71042A35 +:10116000F5D1AAE721462846FFF786FDA5E72146E7 +:101170002846FFF7EDFDA0E7B2F8EC507B6005F1E3 +:1011800003094FEA99094FEA8902D11DC908A8EB62 +:10119000C10300219D46EB46584600F025FC04F1B2 +:1011A000EE012A465846314400F00CFC7B6813B926 +:1011B000012000F077FB96F8D20000F083FB044694 +:1011C00030B9307200F0A8FB204600F06BFBB1E0B4 +:1011D000D6F8D4203AB996F8D200B6F82C25824237 +:1011E00001D8FFF7FFFED6F8D4202A44944208D253 +:1011F00096F8D200B6F82C250130824201D8FFF7CC +:10120000F1FE5FFA89F25946706800F0F5FB08B903 +:10121000C54679E0726896F8D2002A447260D6F822 +:10122000D42005EB0209C6F8D49000F04BFB8145B1 +:1012300009D396F8D220D6F8D4000132001B86F8E4 +:10124000D220C6F8D400FF2D0FD80024347200F04D +:1012500063FB204600F026FB00F092FE3D4B188118 +:1012600008B9FFF7ABF9C54627E7BB6896F8D90080 +:101270000AFB0362FB68D2F8E41082F8E83001F55B +:101280008061C2F8E030C2F8E410FFF7BFFDFFF75D +:101290000DFE96F8D920013202F0030286F8D9201B +:1012A000B6E74FF48A7A20460AFB02F505F1EA0117 +:1012B000314400F015FEF86000287FF4FEAE0122F4 +:1012C000354485F8E82002F047F8D5F8E020D6ED5F +:1012D000007A801A40F6B832B8EE677ADFED1E6AFF +:1012E000192838BF1920904228BF104607EE900AEF +:1012F000F8EEE77A67EEA67ADFED186AE7EE267A6F +:10130000FCEEE77AC6ED007A96F8D930BB60BA6891 +:1013100073680AFB02F4321992F8E81059B1D2F856 +:10132000E410E8468B423FF427AF002182F8E81032 +:10133000C2F8E010C5467368064A9B0A0133138160 +:10134000BBE600BFD934002000ED00E00400FA0540 +:10135000905E0020C8240020CDCCCC3D6666663F60 +:10136000DC340020014B1870704700BFD4240020EB +:1013700038B54FF00054144B22689A4221D1627D57 +:101380000025124B12481A70C922237D09301149D9 +:1013900000F8013C4FF48073C0F8DB50C0F8EF3127 +:1013A0004FF40073C0F803334FF44073C0F81734A0 +:1013B00000F008FBE0222946204600F015FB012042 +:1013C00038BD0020FCE700BF9AAD44C5D4240020FE +:1013D000905E00201600002037B500F0D1FD1F4CB4 +:1013E0001F4D022301221F496B712368288120466B +:1013F0005B68984704F5805301221A49D3F8C0343A +:1014000004F5A6505B689847002317494FF48052B3 +:101410000193164B16480093164B02F087FA164BB1 +:10142000197811B1124802F0A9FA01F095FF0446AB +:10143000FFF7FAFB4FF4C873B0FBF3F202FB1303A0 +:1014400004F5167010FA83F00C4B186004F044FA9F +:1014500008B10F232B8103B030BD00BF1035002031 +:10146000C824002040420F00D82400205D0F00084F +:10147000E034002069100008D4240020DC3400206F +:101480002DE9F04F00242DED028B93B00DF12C08C7 +:101490004FF0010ADFF814B2FFF708FD0A94ADF827 +:1014A00034400B94C8F804409FED798B00267E4DA4 +:1014B00037462B680DF11D0207A928468DF81CA0A0 +:1014C0008DF81D408DED008BD3F808900023C847A0 +:1014D0009DF81C90B9F1000F1ED0102200210EA81B +:1014E00000F082FA2B6808AA0AA95F6928460DF164 +:1014F0001E03B8470FAB4F4698E8030083E803008C +:101500009DF834300EA958468DF844300A9B0E934E +:10151000DDE9082302F0ECFC06F5A66605F5A65504 +:10152000B6F5266FC5D1002FC0D1604802F02EFA63 +:1015300000283FD15E4E01F00FFF3368984239D347 +:1015400001F00AFF0546FFF76FFB4FF4C8738DF8F3 +:101550002870B0FBF3F202FB130305F5167010FAC6 +:1015600083F03060534E377817B901238DF8283057 +:10157000C7F110050EA8FFF76FFB0EABEDB20DF132 +:101580002900D919062D28BF06252A46013500F065 +:1015900019FA0AABEDB24548039318230495029358 +:1015A000454B0193012300933BA3D3E9002302F0B1 +:1015B00033FA347001F0D0FE404A414D1368C31A2B +:1015C000B3F57A7F2FD3106001F0C8FE02460B46B8 +:1015D000364802F0B9FA354802F0D8F918B32B7A38 +:1015E0000EAF384E002B14BF03230223737101F09A +:1015F000B3FE4FF47A7301223946B0FBF3F030604A +:10160000304600F06FFB182380B202932E4B0193FB +:1016100040F25513CDE903700093244820A3D3E989 +:10162000002302F0F9F92B7A93B101F095FE002620 +:1016300007464FF48A7895F8D900304400F003004B +:1016400008FB005393F8E82072B10136042EF2D162 +:10165000C82003F091FD2B7A002B7FF417AF13B055 +:10166000BDEC028BBDE8F08FD3F8E02042B12B68CF +:10167000BA1AFA2B38BFFA230533B2EB430FE4D37F +:10168000FFF7C4FB0028E0D1E2E700BFAFF3008022 +:101690000000000000000000401DA12026812A0B50 +:1016A000F1C6A7C1D068080F10350020E034002033 +:1016B000DC340020D9340020D8340020C06300205E +:1016C000905E0020C8240020C463002010B5074CA1 +:1016D000204601F005F904F5A65001F001F9044A8D +:1016E00004490020BDE8104004F064BD103500201E +:1016F0002064002029100008F8B50A25204C01229A +:101700004FF400712046192703F0A0F8204601226B +:101710004FF4807103F09AF84FF480766520013819 +:1017200025D00822A2F10801B646332905D84FF08A +:10173000000C66834FF000730DE0A1F13403668363 +:10174000B3FBF7FC07FB1C33002B0CBF4FF0010C65 +:101750004FF0000CEED1013143EA4C238A42A361E1 +:10176000A4F818E0E1D10832A02AD8D0DAE7013D88 +:1017700042F2107003F000FD15F0FF05BFD1F8BD77 +:10178000000402582DE9F84F4FF47A7306460D46CF +:10179000002402FB03F7DFF85080DFF8509098F93F +:1017A00000305FFA84FA5A1C01D0A34212D159F8D2 +:1017B00024002A4631460368D3F820B03B46D84778 +:1017C000854207D1074B012083F800A0BDE8F88FC0 +:1017D0000124E4E7002CFBD04FF4FA7003F0CCFCBA +:1017E0000020F3E70C640020182300201C230020B5 +:1017F000002307B5024601210DF107008DF80730DF +:10180000FFF7C0FF20B19DF8070003B05DF804FBAF +:101810004FF0FF30F9E700000A46042108B5FFF752 +:10182000B1FF80F00100C0B2404208BD074B0A463C +:1018300030B41978064B53F82140014623682046FE +:10184000DD69044BAC4630BC604700BF0C6400202F +:101850001C230020A086010070B5104C0025104EFE +:1018600003F05AFE20803068238883420CD800257C +:101870002088013803F04CFE23880544013BB5F570 +:10188000802F2380F4D370BD03F042FE33680544FB +:101890000133B5F5802F3360E5D3E8E70E6400200F +:1018A000C863002003F006BF00F1006000F580204F +:1018B0000068704700F10060920000F5802003F09E +:1018C00087BE0000054B1A68054B1B889B1A834294 +:1018D00002D9104403F01CBE00207047C8630020EA +:1018E0000E640020024B1B68184403F017BE00BFB3 +:1018F000C8630020024B1B68184403F021BE00BFE0 +:10190000C86300200020704700F1FF5000F58F10E1 +:10191000D0F8000870470000064991F8243033B130 +:1019200000230822086A81F82430FFF7C3BF012092 +:10193000704700BFCC630020014B1868704700BFA0 +:101940000010005C194B01380322084470B51D6873 +:10195000174BC5F30B042D0C1E88A6420BD15C68F7 +:101960000A46013C824213460FD214F9016F4EB170 +:1019700002F8016BF6E7013A03F10803ECD181426A +:101980000B4602D22C2203F8012B0424094A1688A4 +:10199000AE4204D1984284BF967803F8016B013CB3 +:1019A00002F10402F3D1581A70BD00BF0010005CB0 +:1019B00024230020A8620008704700007047000040 +:1019C00070470000002310B5934203D0CC5CC45490 +:1019D0000133F9E710BD000003460246D01A12F9A0 +:1019E000011B0029FAD1704702440346934202D0FA +:1019F00003F8011BFAE770472DE9F8431F4D144621 +:101A00000746884695F8242052BBDFF870909CB3B7 +:101A100095F824302BB92022FF2148462F62FFF78A +:101A2000E3FF95F824004146C0F1080205EB800071 +:101A3000A24228BF2246D6B29200FFF7C3FF95F814 +:101A40002430A41B17441E449044E4B2F6B2082E7E +:101A500085F82460DBD1FFF75FFF0028D7D108E0CD +:101A60002B6A03EB82038342CFD0FFF755FF002898 +:101A7000CBD10020BDE8F8830120FBE7CC63002038 +:101A8000024B1A78024B1A70704700BF0C6400209A +:101A90001823002010B5074C4FF4E13306492068A5 +:101AA0000B6003F055FA60680349BDE8104003F08D +:101AB0004FBA00BF1C230020F4630020094B1822FA +:101AC000002110B504461846FFF78EFF064A074B63 +:101AD00001461278046053F82200BDE8104003F07C +:101AE00037BA00BFF46300200C6400201C230020E0 +:101AF000F0B5A1B071B600230120002480261A465B +:101B0000194602F055FE4FF4D067214A3D2513696E +:101B100023BBD2F810310BBB036804F1006199605C +:101B20000368C3F80CD003685E6003681F60016837 +:101B30000B6843F001030B6001680B6823F01E0380 +:101B40000B6001680B68DB07FCD4037B80344168C1 +:101B500005FA03F3B4F5001F0B60D8D102F05EFE66 +:101B6000B4F5001F11D000240A4E0B4D012003F0E4 +:101B7000A1FD3388A34205D928682044013403F02D +:101B8000DFFCF6E7002003F095FD61B621B0F0BD63 +:101B9000002000520E640020C86300202DE9F047A9 +:101BA0000D46044600219046284640F27912FFF780 +:101BB0001BFF234620220021284604F1220702F0C1 +:101BC00039F9231D022220212846C02602F032F9CD +:101BD000631D03222221284602F02CF9A31D0322B3 +:101BE0002521284602F026F904F1080310222821B5 +:101BF000284602F01FF904F1100308223821284674 +:101C000002F018F904F1110308224021284602F0DD +:101C100011F904F1120308224821284602F00AF9BA +:101C200004F1140320225021284602F003F904F1A4 +:101C3000180340227021284602F0FCF804F120032A +:101C40000822B021284602F0F5F804F12103082209 +:101C5000B821284602F0EEF8314608363B46082205 +:101C60002846013702F0E6F8B6F5A07FF4D1002748 +:101C700004F1330A04F1320308223146284602F007 +:101C8000D9F894F832304FEAC7099F4209F5A47693 +:101C900015D3B8F1000F08D1314609F24F1604F5FB +:101CA00099730722284602F0C5F827463B1B94F893 +:101CB000322193420CD3F01DC008BDE8F0870AEB37 +:101CC0000703082231462846013702F0B3F8D8E767 +:101CD00007F233133146082228460836013702F04E +:101CE000A9F8E3E713B5044608460021202223465D +:101CF00001900160C0F8031002F09CF8231D0198C8 +:101D00000222202102F096F8631D0198032222216D +:101D100002F090F8A31D01980322252102F08AF811 +:101D2000019804F108031022282102F083F807200B +:101D300002B010BD0023F7B50E46047F07220091C4 +:101D40001946054601F03AFF731C01220721009352 +:101D50002846002301F032FFC4B9B31C0522082134 +:101D60002846009323460D2401F028FF3746BB1B6D +:101D7000B278934211D307342B7FA88AE408BBB909 +:101D8000844294BF0020012003B0F0BDAB8A082438 +:101D9000DB00083BDB08B370E8E7FB1C21460822A8 +:101DA0002846009300230834013701F007FFDEE7DF +:101DB000201A18BF0120E7E70023F7B50E46047F7D +:101DC000082200911946054601F0F8FE731CC4B9BB +:101DD00008220093234610241146284601F0EEFE07 +:101DE00001235F1C7278013B934211D307342B7F90 +:101DF000A88AE408BBB9844294BF0020012003B044 +:101E0000F0BDAB8A0824DB00083BDB087370E7E712 +:101E1000F3192146082228460093002301F0CEFE44 +:101E200008343B46DDE7201A18BF0120E7E7000031 +:101E3000F8B50E4605461446002181223046FFF7CC +:101E4000D3FD2B4608220021304601F0F3FF7CB978 +:101E50000F246B1C07220821304601F0EBFF012301 +:101E60005F1C6A78013B934204D3E01DC008F8BDB3 +:101E70000824F4E7EB1921460822304601F0DAFF86 +:101E800008343B46ECE70000F8B50E46054614461C +:101E90000021CE223046FFF7A7FD2B462822002145 +:101EA000304601F0C7FF7CB9302405F10803082251 +:101EB0002821304601F0BEFF2F467B1B2A7A934231 +:101EC00004D3E01DC008F8BD2824F5E707F1090395 +:101ED0002146082230460834013701F0ABFFECE719 +:101EE000F7B5047F0E46009101231022002105461C +:101EF00001F064FEC4B9B31C0922102128460093E6 +:101F00002346192401F05AFE37467288BB1B9A42B9 +:101F100011D807342B7FA88AE408BBB9844294BF48 +:101F20000020012003B0F0BDAB8A1024DB00103B81 +:101F3000DB087380E8E73B1D214608222846009312 +:101F400000230834013701F039FEDEE7201A18BFFC +:101F50000120E7E730B50A44084D91420DD011F851 +:101F6000013B5840082340F30004013B2C4013F090 +:101F7000FF0384EA5000F6D1EFE730BD2083B8EDCF +:101F8000F7B5384A6B46106851686A4603C30823A0 +:101F90003549364804F03CF90446002833D10A2577 +:101FA000334A6B46106851686A4603C308233149B7 +:101FB0002E4804F02DF90446002849D00369B3F5F2 +:101FC000E01F45D8B0F8661040F2134291423FD16D +:101FD000294A024402F15C018B4239D35C3B23491C +:101FE00000209E1AFFF7B6FF04F16401074632464F +:101FF0000020FFF7AFFFA3689F4229D1E368984212 +:1020000008BF002524E00369B3F5E01F27D8418B02 +:1020100040F21342914220D1174A024402F11001CA +:102020008B4218D3103B114900209D1AFFF792FFF5 +:1020300004F1180106462A460020FFF78BFFA3682B +:102040009E4202D1E368984201D00D25A8E7002501 +:10205000284603B0F0BD1025A2E70C25A0E70B250C +:102060009EE700BFB8620008DCFF1B000000040808 +:10207000C162000890FF1B000800FCF710B5037C4C +:10208000044613B9006804F0ABF8204610BD000008 +:102090000023BFF35B8FC360BFF35B8FBFF35B8F26 +:1020A0008360BFF35B8F7047BFF35B8F0068BFF344 +:1020B0005B8F704770B505460C30FFF7F5FF04469F +:1020C00005F108063046FFF7EFFFA04206D96D681C +:1020D0003046FFF7E9FF2544281A70BD3046FFF768 +:1020E000E3FF201AF9E7000070B505464068A0B18B +:1020F00005F10C0605F10800FFF7D6FF044630464F +:10210000FFF7D2FF844204F1FF34304694BF6D687C +:102110000025FFF7C9FF2C44201A70BD38B50C46C6 +:102120000546FFF7C7FFA04210D305F10800FFF7EF +:10213000BBFF04446868BFF35B8FB4FBF0F100FBA6 +:1021400011440120AC60BFF35B8F38BD0020FCE779 +:102150002DE9F041144607460D46FFF7C5FF8442BE +:1021600028BF0446D4B1B84658F80C6B4046FFF778 +:102170009BFF3044286040467E68FFF795FF331A86 +:102180009C4203D801206C60BDE8F081A41B6B6009 +:102190003B682044AB60E8600220F5E72046F3E7A7 +:1021A00038B50C460546FFF79FFFA04210D305F156 +:1021B0000C00FFF779FF04446868BFF35B8FB4FB42 +:1021C000F0F100FB11440120EC60BFF35B8F38BDE0 +:1021D0000020FCE72DE9FF418846694607466C462A +:1021E000FFF7B6FF002506B204EBC606B4420AD0DC +:1021F000626808EB050120680834FFF7E3FB54F838 +:10220000043C1D44F2E729463846FFF7C9FF28463B +:1022100004B0BDE8F0810000F8B505460C300F466B +:10222000FFF742FF05F1080604463046FFF73CFF82 +:10223000A042304688BF6C68FFF736FF201A38602E +:1022400020B12C683046FFF72FFF2044F8BD000076 +:1022500073B5144606460D46FFF72CFF84420190E5 +:1022600028BF0446DCB101A93046FFF7D5FF019B2A +:1022700033B93268C5E90233C5E9002401200CE016 +:102280009C42286038BF0194019884426860F5D967 +:102290003368241A0220AB60EC6002B070BD2046A7 +:1022A000FBE700002DE9FF410F4669466C46FFF74A +:1022B000CFFF00B2002604EBC005AC4209D0D4F831 +:1022C0000480B81954F8081B42464644FFF77AFBCD +:1022D000F3E7304604B0BDE8F081000038B50546AC +:1022E000FFF7E0FF044601462846FFF717FF2046A8 +:1022F00038BD00007047000010B41346026814682F +:102300000022A4465DF8044B6047000000F58050B1 +:1023100090F859047047000000F5805090F852047E +:102320007047000000F5805090F958047047000095 +:102330004E207047302383F3118800F58052D2F885 +:102340009C34D2F898041844D2F894341844D2F843 +:102350007C341844D2F88C341844D2F888341844A9 +:10236000002383F31188704700F58050C0F854149F +:10237000012070472DE9F04F0C4600F5805185B0E3 +:102380001F4691F8523405469046BDF838909BB1EF +:10239000D1F878340133C1F878342368980006D432 +:1023A000237B082B0BD9627B0AB10F2B07D9D1F8FD +:1023B0007C340133C1F87C344FF0FF3010E030231F +:1023C00083F31188EB6AD3F8C42012F4001B0AD0FF +:1023D000D1F8803400200133C1F8803480F31188B3 +:1023E00005B0BDE8F08F20684822D3F8C43000283B +:1023F000C3F3044A6B6AB4BF40F08040800412FB10 +:102400000A334FEA4A161860226852004FEA0A62FD +:1024100044BF40F000501860207B42EA00425A60FE +:10242000607B10B342F440125A60D1F8B0240132FC +:10243000C1F8B024AA1902F58352117B41F02001A2 +:102440001173207B039300F0E3FF0330039B8010A4 +:102450005FFA8BF20BF1010B82420DDA04EB820181 +:1024600003EB820249689160F2E7AA1902F58352F0 +:10247000117B60F34511E3E70122EB6A05EB4A119A +:1024800002FA0AF201F58251C3F8D020AB191831D3 +:1024900004F10C0203F58253C3E90487234653F881 +:1024A000040B934241F8040BF9D11B882E440B8096 +:1024B00041F2680346F803A006F5805609F00303CD +:1024C00096F86C2043F0100322F01F02134386F8A5 +:1024D0006C30002383F3118842463B462146284650 +:1024E000CDF8009000F05AFF012079E72DE9F04780 +:1024F00000F58056044696F85254002D40F00381B2 +:10250000037C032B40F0948028462B462F465FFA2D +:1025100080FC944510DA01EBCC0E51F83CC0BCF1C4 +:10252000000F04DBDEF804C0BCF1000F02DB013752 +:102530000130ECE70133FBE7302080F31188E06ADB +:10254000F3B9D0F8803043F00203C0F880304E2356 +:10255000E06A002F6FD1D0F8803043F00103C0F85B +:1025600080306A4B6A4A1B6803F1805303F52C5391 +:102570009B009342A36240F2B080664800F0E6FE02 +:102580004D2B42D8DFF884814FEA034EDFF8889163 +:10259000D8F800C04EEA8C0EC0F884E00CF18050F0 +:1025A00000F52C508000606103EB0C00D4F82CC0C7 +:1025B000C3F14E03C8F80000DCF8800040F03000A2 +:1025C000CCF880004FF0000CD4F81480E6465FFA97 +:1025D0008CF08242BCDD01EBC00A51F830000028CB +:1025E00010DBDAF804A0BAF1000F0BDA09EA0040B8 +:1025F0000AF07F0A40EA0A0040F0084048F82E003E +:102600000EF1010E0CF1010CE1E7836923F00103E7 +:10261000836100F0A1FE0646E36A9B69D90704D5F1 +:1026200000F09AFE831BFA2BF6D9002383F311885E +:102630002846BDE8F087B7EB530F3DD2DFF8CCE07A +:102640004FEA074CDEF800304CEA830CC0F888C033 +:1026500003F1805003EB4703002700F52C50CEF820 +:102660000030BC468000A061E06AD0F8803043F0C2 +:102670000C03C0F88030D4F818E0FBB29A427FF720 +:1026800070AF51F8330001EBC3080028D8F80430CC +:1026900001DB002B0EDB20F0604023F0604340F0B4 +:1026A000005043F000434EF83C000EEBCC000CF120 +:1026B000010C43600137E0E7836923F00103836184 +:1026C00000F04AFE0646E36A9B69DA07ADD500F0E2 +:1026D00043FE831BFA2BF6D9A7E7E26A936923F03E +:1026E0000103936100F038FE0746E36A9B69DB074C +:1026F00005D500F031FEC31BFA2BF6D995E701256D +:1027000086F8525491E7002592E700BF1C64002030 +:10271000FCB50040CC6200080000FF0713B500F5CF +:1027200080540191606CFFF7DFFC1F280AD920223A +:102730000199606CFFF74EFDA0F12003584258410B +:1027400002B010BD0020FBE708B5302383F31188E9 +:1027500000F58050406CFFF79BFC002383F3118849 +:1027600008BD0000002202608281426082607047E2 +:102770000022002310B5C0E90023002304460C30DA +:1027800020F8043CFFF7EEFF204610BD2DE9F0478E +:102790009A4688B0074688469146302383F31188CD +:1027A00007F580546846FFF7E3FF606CFFF782FC93 +:1027B0001F282ED920226946606CFFF78FFD202844 +:1027C00027D194F8523423B303AD444605AB2E46CB +:1027D000083403CE9E4244F8080C44F8041C3546E5 +:1027E000F5D130682060B388A380DDE90023C9E912 +:1027F0000023BDF80830AAF80030002383F31188C5 +:1028000053464A464146384608B0BDE8F04700F016 +:10281000B3BD002080F3118808B0BDE8F087000048 +:102820002DE9F84F0023064600F5815405468846F9 +:102830001034C0E90133274B46F8303B3746384661 +:102840002037FFF795FFA742F9D105F580544FF4E3 +:10285000805305F5A3594FF0000A266300266764EC +:1028600005F5835709F110094FF0000B1037E663A7 +:10287000C4E90D36012384F8403084F84830A7F1CC +:102880001800203747E910ABFFF76CFF47F8286CBA +:102890004F45F4D1B8F1010F84F85884A4F85A6474 +:1028A000A4F85C64A4F85E6484F86064A4F86264CC +:1028B000A4F86464A4F8666484F8686402D90648DD +:1028C00000F044FD054B284653F82830EB62BDE884 +:1028D000F88F00BF1C630008F06200080C6300085A +:1028E000044B10B5197804464A1C1A70FFF798FF7C +:1028F000204610BD196400202DE9F04300295AD06C +:102900002E4E2F48B6FBF1F481428CBF0A201120D5 +:10291000431EB4FBF0F700FB1740DDB220B1022BE1 +:102920001846F5D8002032E07B1EB3F5806F2ED21A +:10293000C5EBC5084FF47A7308F103044FEAE40EBF +:10294000C4F3C7040EF10109281B0EFB033E5FFA16 +:1029500080FC59FA80F0BEFBF0F0B0F5617F18DC26 +:1029600083B2601C5CFA80F07843B6FBF0F08142E1 +:10297000D8D1611E0F29D5D80CF1FF310729D1D844 +:102980000120138057801071547182F806C0BDE891 +:10299000F08308F1FF34E010C4F3C70400F1010E26 +:1029A0002D1B00FB03335FFA85FC5EFA85F5B3FB54 +:1029B000F5F39BB2D5E70846E9E700BF00B4C404CD +:1029C0003F420F0030B50D4B05200D4D1C786C4378 +:1029D0008C420ED159780120518099785171D97863 +:1029E0009171197911715B7903EB83035B0013809B +:1029F00030BD013803F10603E8D1F9E75C63000854 +:102A000040420F0038B540F27772C36A154CC3F8E4 +:102A1000BC200722C36AC3F8C8202268C16A930099 +:102A200043F4C023C1F8A03002F1805302F16C01DD +:102A3000C56A03F52C53EA3289009B00226041F0FD +:102A4000E061094AC361C5F8C01003F5D87103F508 +:102A50006A7341629342836202D9044800F076FCB3 +:102A600038BD00BF1C640020FCB50040CC620008EB +:102A70002DE9F04F00F580551F4689B0044695F8C2 +:102A8000583489469046022B04D90026304609B0B6 +:102A9000BDE8F08FA84A52F8231009B942F8230084 +:102AA000A648C4F80C9001782774C9B9302383F381 +:102AB0001188A34BD3F8EC2042F48072C3F8EC20C9 +:102AC000D3F8942042F48072C3F89420D3F8942071 +:102AD00022F48072C3F894200123037081F31188DB +:102AE00095F851347BB9302383F31188954A95F8D2 +:102AF0005834D35C0BB3012B28D0012385F8513413 +:102B0000002383F31188302383F31188E26A9369E9 +:102B100023F01003936100F01FFC8246E36A9E6974 +:102B200016F0080619D000F017FCA0EB0A03FA2BE8 +:102B3000F4D9002686F31188A8E70321132002F0B8 +:102B40003BF80321152002F037F8D6E703211420C3 +:102B500002F032F803211620F5E79A6942F00102EB +:102B60009A6100F0F9FB8246E36A9A69D00706D4BD +:102B700000F0F2FBA0EB0A03FA2BF5D9D9E79A692A +:102B80004FF0000A42F002029A61E36AC3F854A0CF +:102B90008AF3118804F5825B686CFFF779FA0BF110 +:102BA000100B202200216846FEF71EFF02A8FFF747 +:102BB000D9FD6A460BEB06030DF1180ECDF818A0EF +:102BC00094460833BCE80300F44543F8080C43F886 +:102BD000041C6246F4D1DCF8000020361860B6F51B +:102BE000806F9CF804201A71DBD1002304F5A252F7 +:102BF000494620461A3285F8503485F85334FFF799 +:102C00007BFE064690B9E26A936923F00103936163 +:102C100000F0A2FB0546E36A9B69D9077FF535AF53 +:102C200000F09AFB431BFA2BF5D92EE795F85E349A +:102C3000C5F86C94591E95F85F34E26A013B1B029B +:102C400043EA416395F8601401390B43B5F85C140D +:102C5000013943EA0143D361B8F1000F36D004F5DE +:102C6000A352414620460232FFF7ACFE90B9E26A19 +:102C7000936923F00103936100F06EFB0546E36A5C +:102C80009B69DA077FF501AF00F066FB431BFA2B67 +:102C9000F5D9FAE695F86724C5F87084511E95F8C1 +:102CA0006824E36A013A120142EA012295F86614A7 +:102CB00001390A43B5F86414013942EA014242F489 +:102CC0000002DA604FF42062E36A9A64E36A4FF02C +:102CD00000082046C3F8BC80FFF794FE85F85984AD +:102CE0006FF04042E36A1A65174AE36A5A654FF08B +:102CF0000222E36A9A654FF0FF32E36AC3F8E020EC +:102D00000322E36A9742DA653FF4C0AEE26A936950 +:102D100023F00103936100F01FFB0746E36A9B6900 +:102D2000DB0705D500F018FBC31BFA2BF6D9ACE680 +:102D3000012385F85234A9E61064002018640020AD +:102D40000044025804630008550200022DE9F04FC8 +:102D5000054689B090469946002741F2680A00F579 +:102D60008056EB6AD3F8D830FB40D80751D505EB35 +:102D700047124FEA471B52441379190749D4D6F832 +:102D800084340133C6F8843405F5A553C3E90089BA +:102D900013799A0605EB0B0248BFD6F8B4345244B7 +:102DA00044BF0133C6F8B434137943F008031371F8 +:102DB000DB0723D596F8533403B305F582546846F0 +:102DC000FFF7D6FC03AB18345C4404F1080C206810 +:102DD000083454F8041C1A46644503C21346F6D15D +:102DE0002068694610602846A2889A800123ADF8C1 +:102DF00008302B68CDE90089DB6B9847D6F8A834FA +:102E0000D6F854040133C6F8A83410B103681B691E +:102E100098470137202FA4D109B0BDE8F08F0000FA +:102E20002DE9F04F0F468DB0044600F097FA824628 +:102E30008946002F5BD1E36AD3F8A02012F4FE0F7D +:102E400003D100200DB0BDE8F08FD3F8A42092018B +:102E500041BF04F58051D1F898240132C1F898247B +:102E6000D3F8A4205606ECD0D3F8A450E669C5F3F5 +:102E700005254823E8464FF0000B03FB0566404656 +:102E8000FFF770FC326851004ABF22F06043C2F382 +:102E90008A4343F00043920048BF43F080430093CD +:102EA000736813F400131BBF012304F580528DF8DF +:102EB0000D308DF80D301EBFD2F8B8340133C2F892 +:102EC000B834F38803F00F038DF80C309DF80C0034 +:102ED00000F09EFA5FFA8BF3984225D9F2180CA9FC +:102EE0000BF1010B127A0B4403F82C2CEEE7012FA7 +:102EF000A7D1E36AD3F8B02012F4FE0FA1D0D3F823 +:102F0000B420950141BF04F58051D1F898240132D5 +:102F1000C1F89824D3F8B420500692D0D3F8B45016 +:102F2000266AC5F30525A4E7EFB9E36AC3F8A850FC +:102F300004A807ADFFF71CFC98E80F0007C52B801D +:102F40000023204604A9ADF81830236804F5805406 +:102F5000DB6BCDE904A9984758B1D4F8903401331C +:102F6000C4F890346EE7012FE2D1E36AC3F8B85099 +:102F7000DEE7D4F8943401200133C4F8943461E7D7 +:102F80002DE9F04105460F4600F5805401263946EB +:102F90002846FFF745FF10B184F85364F7E7D4F8EB +:102FA000A834D4F854040133C4F8A83420B1036819 +:102FB000BDE8F0411B691847BDE8F081C36AF0B570 +:102FC0001A6C12F47F0F2BD01B6C00F5805441F269 +:102FD00068054FF0010CC4F8AC340023471900EB2E +:102FE00043125E012A44117911F0020F15D04907EE +:102FF00013D4B959C66A0CFA01F1D6F8CCE011EA3B +:103000000E0F0AD0C6F8D410117941F004011171E5 +:10301000D4F88C240132C4F88C240133202BDED167 +:10302000F0BD00002B4B70B51E561B5C012B30D839 +:10303000294D2A4A55F8233052F8264013B349B394 +:10304000236D9A0510D54FF40073236500F086F9BF +:1030500050EA01020B4602D0013861F1000302463A +:1030600055F82600FFF772FE236D9B012CD54FF01B +:10307000007255F82630226503F58053012283F84B +:10308000592421E001232365102323654FF4805345 +:10309000236570BD236DDA0702D4236D5B0706D567 +:1030A0000523002155F826002365FFF769FF236DEE +:1030B000D80602D4236D590606D55023012155F8B0 +:1030C00026002365FFF75CFF55F82600BDE8704039 +:1030D000FFF774BF08630008106400200C63000849 +:1030E00008B5302383F31188FFF768FF002383F3CB +:1030F000118808BDC36AD3F8C00010F07C5005D019 +:10310000D3F8C40080F40010C0F3405070470000B2 +:1031100008B5302383F3118800F58050406CFEF72A +:10312000C9FF002383F3118843090CBF012000204D +:1031300008BD000000F5805393F8592462B1C16ABC +:103140008A6922F001028A61D3F89C240132C3F813 +:103150009C24002283F85924704700002DE9F7438E +:10316000302181F3118800F58251002541F2680E6B +:103170004FF00108103100F5805C00EB45147444F9 +:10318000267977071CD4F6061AD58E69D0F82C90CC +:1031900008FA06F6D9F8CC703E4211D04F68019774 +:1031A0000F689742019F9F410AD2C9F8D4602679DF +:1031B00046F004062671DCF888440134CCF88844D3 +:1031C00001352031202DD8D1002383F3118803B09D +:1031D000BDE8F083F8B51E4600230F460546137080 +:1031E0001446FFF795FF80F0010038701EB12846A5 +:1031F000FFF780FF2070F8BD2DE9F04F85B09946AC +:103200000D468046164691F800B0DDE90EA3029304 +:103210001378019300F0A2F82B7804460F4613B9F7 +:103220003378002B41D022463B464046FFF796FFBD +:10323000FFF756FFFFF77EFF4B4632462946FFF762 +:10324000C9FF2B7833B1BBF1000F03D0012005B0CB +:10325000BDE8F08F337813B1019B002BF6D108F550 +:10326000805303935445029B77EB03031DD2039BCA +:10327000D3F85404C8B10368AAEB04011B6898474B +:103280004B46324629464046FFF7A4FF2B7813B140 +:10329000BBF1000FDAD1337813B1019B002BD5D1EC +:1032A00000F05CF804460F46DCE70020CFE70000A2 +:1032B000002108B50846FFF7B5FEBDE8084001F05B +:1032C0006DB8000008B501210020FFF7ABFEBDE896 +:1032D000084001F063B8000008B500210120FFF7A5 +:1032E000A1FEBDE8084001F059B80000012108B571 +:1032F0000846FFF797FEBDE8084001F04FB8000010 +:1033000000B59BB0EFF3098168226846FEF75AFBCF +:10331000EFF30583014B9B6BFEE700BF00ED00E080 +:1033200008B5FFF7EDFF000000B59BB0EFF3098192 +:1033300068226846FEF746FBEFF30583014B5B6BA3 +:10334000FEE700BF00ED00E0FEE700000FB408B5A7 +:10335000029801F0C1FEFEE702F0EEB902F0D0B92A +:1033600013B56C46031D84E8060094E8030083E867 +:103370000500012002B010BD73B58568019155B1FB +:103380001B885B0707D4D0E900369B6B9847019AEE +:10339000C1B23046A847012002B070BDF0B58668C2 +:1033A00089B005460C465EB1BDF838305B070AD4DB +:1033B000D0E900379B6B98472246C1B23846B047E8 +:1033C000012009B0F0BD0022002301F10806CDE97B +:1033D000002300230A46ADF8083003AB106808321A +:1033E00052F8041C1C46B24203C42346F6D11068AE +:1033F00020609288A280FFF7B1FF0423ADF8083067 +:103400002B68CDE90001DB6B694628469847D7E772 +:10341000082817D909280CD00A280CD00B280CD062 +:103420000C280CD00D280CD00E2814BF40203020C2 +:1034300070470C20704710207047142070471820E8 +:1034400070472020704700002DE9F041456A15B90A +:103450004162BDE8F0814B68AC4623F06047C3F39E +:103460008A464FEAD37EC3F3807816EA230638BF34 +:103470003E462B465A68BEEBD27F22F060440AD00B +:10348000002A18DAA40CB44217D19D420FD10D6066 +:10349000DEE71346EEE7A74207D102F08044C2F30D +:1034A000807242450BD054B1EFE708D2EDE7CCF87B +:1034B00000100B60CDE7B44201D0B442E5D81A68E1 +:1034C0009C46002AE5D11960C3E700002DE9F047CA +:1034D000089D01F0070400EBD1004FF47F494FEA4B +:1034E000D508224405F00705944201D1BDE8F087D4 +:1034F00004F0070705F0070A111B08EBD50E574526 +:103500003E4613F80EC038BF5646C6F108068E4236 +:1035100028BF0E46E108415C34443544B94029FADD +:1035200006F721FA0AF1FFB28CEA010147FA0AF71D +:1035300039408CEA010C03F80EC0D5E780EA01207F +:10354000082341F2210201B2013B4000002980B270 +:10355000B8BF504013F0FF03F5D1704738B50C46A3 +:103560008D18A54200D138BD14F8011BFFF7E6FF06 +:10357000F7E7000042684AB11368818943604389D4 +:1035800001339BB29942438138BF83811046704713 +:1035900070B588B0044620220D4668460021FEF72B +:1035A00023FA20460495FFF7E5FF024660B16B461B +:1035B000054608AE1C46083503CCB44245F8080C55 +:1035C00045F8041C2346F5D1104608B070BD000034 +:1035D000082817D909280CD00A280CD00B280CD0A1 +:1035E0000C280CD00D280CD00E2814BF4020302001 +:1035F00070470C2070471020704714207047182027 +:103600007047202070470000082817D90C280CD9D3 +:1036100010280CD914280CD918280CD920280CD91A +:1036200030288CBF0F200E207047092070470A20D9 +:1036300070470B2070470C2070470D20704700002A +:103640002DE9F843078C0446072F1ED900254FF6B5 +:10365000FF73D0E90298C5F12006A5F1200029FAF0 +:1036600005F1083508FA06F628FA00F0314301435F +:103670001846C9B2FFF762FF402D0346EBD13A4628 +:10368000E169BDE8F843FFF769BF4FF6FF70BDE899 +:10369000F883000010B54B6823B9CA8A63F30902A6 +:1036A000CA8210BD04691A681C600361C38A013BA9 +:1036B000C3824A60EFE700002DE9F84F1D46CB8A30 +:1036C0000F468146C3F30901924605290B4630D0C7 +:1036D0000020AAB207F11A049EB21FFA80F8042E45 +:1036E0000FD8904503F1010306D30A44FB8A62F325 +:1036F00009030120FB821AE01AF800600130E65449 +:10370000EAE79045F1D2A1F1050B1C237C68BBFBD5 +:10371000F3F203FB12BB1FFA8BF6002C45D148468F +:10372000FFF728FF044638B978606FF00200BDE863 +:10373000F88F4FF00008E6E7002606607860ADB22B +:103740004FF0000B454510D90AEB0803221D13F872 +:10375000011B08F101089155B1B21FFA88F81B2925 +:103760002BD0454506F10106F1D8FB8AC3F30902C7 +:10377000154465F30903BCE701321C4692B2236885 +:10378000002BF9D16B1F0B441C21B3FBF1F3013368 +:103790009BB29A42D3D2BBF1000FD0D14846FFF77B +:1037A000E9FE20B9C4F800B0BFE70122E7E7C0F89E +:1037B00000B05E4620600446C1E74545D5D948467D +:1037C000FFF7D8FE08B92060AFE7C0F800B00026C8 +:1037D00020600446B6E700002DE9F04F1C4607467E +:1037E00088462DED028B83B05B690192002B00F0BF +:1037F0009A80238C2BB1E269002A00F09480072B79 +:1038000035D807F10C00FFF7B5FE054638B96FF063 +:103810000205284603B0BDEC028BBDE8F08F1422F0 +:103820000021FEF7E1F8228CE16905F10800FEF7BE +:10383000C9F8208C48F00041013080B2FFF7E4FE67 +:10384000FFF7C6FE013880B2208401302874384664 +:103850006369228C1B782A4403F01F0363F03F0343 +:10386000137269602946FFF7EFFD0125D1E74FF09C +:10387000000900F10C034FF0800A4E464D4608EE59 +:10388000103A18EE100AFFF775FE83460028BED0E6 +:1038900014220021FEF7A8F8002E3AD1019B022243 +:1038A000ABF808300BF1080E1FFA82FC218C0CF1EA +:1038B0000100BCF1060F80B201D88E422BD3FFF776 +:1038C000A3FE8E4208BF4FF0400AFFF781FE6269F7 +:1038D0000138013512781BFA80F1013002F01F0225 +:1038E0002DB242EA491289F001094AEA020A48F077 +:1038F000004281F808A059468BF810003846CBF8F2 +:1039000004204FF0000AFFF79FFD238CB342B8D18B +:103910007FE70022C6E7E169895D01360EF80210F3 +:10392000B6B20132C0E76FF0010572E7F8B515468F +:103930000E463022002104461F46FEF755F8069B2E +:10394000B5F5001FA760636004F11000079B34BF4A +:103950006A094FF6FF72E661A362002397B29A42AA +:1039600006D800230360A782E3822383E360F8BDC7 +:103970000660013330462036F1E7000003781BB9BA +:103980004BB2002BC8BF0170704700000078704731 +:10399000F8B50C46C969074611B9238C002B37D1FD +:1039A000257E1F2D34D8387828BB228C072A2CD8A6 +:1039B000268A36F003032BD14FF6FF70FFF7CEFDBA +:1039C00020F0010031024FF6FF72400441EA056128 +:1039D000400C41EA4025234629463846FFF7FCFEC5 +:1039E000002807DD626913780133DBB21F2B88BF23 +:1039F00000231370F8BD218A2D0645EA01250543F1 +:103A00002046FFF71DFE0246E5E76FF00300F1E7F1 +:103A10006FF00100EEE7000070B58AB0044616466C +:103A20000021282268461D46FDF7DEFFBDF838302C +:103A300069462046ADF810300F9B05939DF8403045 +:103A40008DF81830119B0793BDF84830CDE9026519 +:103A5000ADF82030FFF79CFF0AB070BD2DE9F041B2 +:103A6000D36905460C4616460BB9138C5BBB377EF3 +:103A70001F2F28D895F80080B8F1000F26D03046C7 +:103A8000FFF7DEFD337821020246284641EAC331C2 +:103A9000338A41EA080141EA076141EA03413346BA +:103AA00041F08001FFF798FE00280ADD3378012BF2 +:103AB00007D1726913780133DBB21F2B88BF002353 +:103AC0001370BDE8F0816FF00100FAE76FF00300BA +:103AD000F7E70000F0B58BB004460D46174600210D +:103AE000282268461E46FDF77FFF9DF84C30294688 +:103AF00020465A1E534253416A468DF800309DF8C5 +:103B00004030ADF81030119B05939DF848308DF88A +:103B10001830149B0793BDF85430CDE90276ADF808 +:103B20002030FFF79BFF0BB0F0BD0000406A00B1F2 +:103B300004307047436A1A68426202691A6003617E +:103B4000C38A013BC38270472DE9F041D0F8208041 +:103B500014461D46184E4146002709B9BDE8F081BC +:103B6000D1E90223A21A65EB0303964277EB030324 +:103B70001ED2036A8B420DD1FFF78CFD036A1B68CE +:103B8000036203690B60C38A0161013B016AC3825E +:103B90008846E2E7FFF77EFD0B68C8F8003003694E +:103BA0000B60C38A0161013BC382D8F80010D4E7DF +:103BB00088460968D1E700BF80841E002DE9F04FD8 +:103BC0008BB00D4614469B46DDF850908046002889 +:103BD00000F01881B9F1000F00F01481531E3F2B43 +:103BE00000F21081012A03D1BBF1000F40F00A81DD +:103BF0000023CDE90833B8F81430B5EBC30F4FEA12 +:103C0000C30703D300200BB0BDE8F08F2B199F42F0 +:103C1000D8F80C3036BF7F1B2746FFB21BB9D8F847 +:103C20001030002B7AD0272D4DD8C5F1280600235F +:103C30002946B742009308ABD8F808002CBFF6B26B +:103C40003E46A7EB060A354432465FFA8AFAFFF78A +:103C50003DFCB8F81430282103F10053053BDB008C +:103C60000493D8F80C300393039B13B1BAF1000FFF +:103C70002CD1D8F8100040B1BAF1000F05D008AB34 +:103C80005246691A0096FFF721FC38B2002FB9D0CE +:103C900066070AD00AAB624203EBD40102F00702C6 +:103CA00011F8083C134101F8083C082C3DD9102CB0 +:103CB00040F2B580202C40F2B780BBF1000F00F03D +:103CC0009C80082335E0BA460026C2E7049BE02B1F +:103CD00028BFE02306930B44AB42059315D95A1B2A +:103CE0000398691A0096924508AB00F1040034BFAE +:103CF0005246D2B20792FFF7E9FB079A1644AAEBA5 +:103D0000020A1544F6B25FFA8AFA049B069A0599EC +:103D10009B1A0493039B1B680393A5E700933A4601 +:103D200008AB2946D8F80800ADE7BBF1000F13D067 +:103D30000123B4EBC30F6BD0082C12D89DF82030B0 +:103D4000621E23FA02F2D50706D54FF0FF3202FABF +:103D500004F423438DF820309DF8203089F800309A +:103D600051E7102C12D8BDF82030621E23FA02F25F +:103D7000D10706D54FF0FF3202FA04F42343ADF821 +:103D80002030BDF82030A9F800303CE7202C0FD8B7 +:103D90000899631E21FA03F3DA0705D54FF0FF32C5 +:103DA00002FA04F40C430894089BC9F800302AE78F +:103DB000402C2AD0611EC4F12102A4F12103DDE9C7 +:103DC000086526FA01F105FA02F225FA03F3114318 +:103DD0001943CB0711D50122A4F12003C4F120011E +:103DE00002FA03F322FA01F1A2400B43524263EBC1 +:103DF000430332432B43CDE90823DDE90823C9E916 +:103E0000002300E76FF00100FDE66FF00800FAE61E +:103E1000082CA1D9102CB4D9202CEED8C4E7BBF1C2 +:103E2000000FAED0022384E7BBF1000FBCD0042307 +:103E30007FE70000012A30B5144638BF012485B061 +:103E40000025402C28BF4024012ACDE9025518D86E +:103E50001B788DF8083063070AD004AB624203EB8D +:103E6000D40502F0070215F8083C934005F8083C19 +:103E7000034600912246002102A8FFF727FB05B068 +:103E800030BD082AE4D9102A03D81B88ADF80830C1 +:103E9000E1E7202A95BF1B68D3E900230293CDE90F +:103EA0000223D8E710B5CB681BB98B600B618B82FE +:103EB00010BD04691A681C600361C38A013BC38298 +:103EC000CA60F0E703064CBFC0F3C0300220704761 +:103ED00008B50246FFF7F6FF022806D15306C2F3E3 +:103EE0000F2001D100F0030008BDC2F30740FBE73B +:103EF0002DE9F04F93B004460D46CDE903230A683F +:103F00001046FFF7DFFF0228824614BFC2F30626E1 +:103F10000026002A80F2F38112F0C04940F0EF81C0 +:103F2000097B002900F0EB81022803D02378B342FB +:103F300040F0E881C2F3046310462944069302F07E +:103F40007F030593FFF7C4FF059B002283464FEADA +:103F50008348002348EA0A4848EA4668CE78CDE913 +:103F60000823F30948EA0008029368D0059B02463B +:103F700008A92046009353466768B847002800F018 +:103F8000C481276A4FB9414604F10C00FFF700FBDA +:103F9000074690B96FF0020055E03B6998450DD097 +:103FA0003F68002FF9D1414604F10C00FFF7F0FA09 +:103FB00007460028EED0236A3B60276297F817C0B7 +:103FC00006F01F08CCF3840CACEB0800A8EB0C0344 +:103FD0001FFA80FE0028B8BF0EF120001FFA83FEF2 +:103FE000B8BF00B2002B0793B8BF0EF12003D7E98A +:103FF0000221BCBF1BB2079352EA010338D0039BD6 +:104000004FF0000CDFF820E39A1A049B63EB0101E8 +:1040100096457CEB01032BD36B7B97F81AE0734535 +:1040200019D1029B002B78D0012821DC7868F8B9DF +:10403000DFF8F0C2944570EB010316D337E0276A2E +:1040400027B96FF00C0013B0BDE8F08F3B699845BD +:10405000B4D03F68F4E7B34890427CEB010301D34E +:104060000020F0E7029B002BFAD0079B0F2B17DCF8 +:10407000FA7DB3003946204602F0030203F07C03C8 +:104080001343FB75FFF706FB6B7BBB76029B3BB9CB +:10409000FB7DC3F38402013262F38603FB75D0E734 +:1040A0006A7BBB7E9A42DBD1029B002B35D0B309E1 +:1040B000022B32D0039B142200210DA8BB60049B6D +:1040C000FB60FDF791FC039B0AA920460A93049B21 +:1040D000ADF83EB00B932B1D8DF840A00C932B7BBD +:1040E0008DF84180013BDBB2ADF83C30069B8DF88A +:1040F0004230059B8DF8433094F82C3083F0010357 +:104100008DF84430A3689847FB7DC3F384030133E3 +:1041100003F01F039B02FB82A2E7FB7DC6F3401264 +:10412000B2EBD31F40F0F480C3F38403434540F067 +:10413000F280029AB6092B7B002A4DD0F2075DD49B +:10414000032B40F2EB80039BAE1D394604F10C00BB +:10415000BB603246049BFB602B7B033BDBB2FFF76B +:10416000ABFA00280CDA39462046FFF793FAFB7DBC +:10417000C3F38403013303F01F039B02FB8209E7AF +:10418000AB88DDE908843B834FF6FF73C9F120005B +:10419000A9F1200228FA09F109F1080904FA00F04E +:1041A00024FA02F2014318461143C9B2FFF7C6F9D7 +:1041B000B9F1400F0346E9D1B88231462A7B033A70 +:1041C000D2B2FFF7CBF9FB7DB882DA43C2F3C0125B +:1041D00062F3C713FB7543E786B92E1D013B3946D1 +:1041E00004F10C00DBB23246FFF766FA0028BADBB6 +:1041F0002A7B3146B88A013AD2B2E2E7F98A013B1A +:10420000C1F30901DAB204295BD8281D002307F1A4 +:104210001B069A4208D910F801CB013306F801C0F9 +:104220000131DBB20529F4D1039993420A9138BFD9 +:10423000043304992CBF002355FA83F30B9107F143 +:104240001B010C9179680E930D91291DFB8AADF825 +:104250003EB0C3F309038DF840A08DF841801A44A5 +:10426000069B8DF84230059BADF83C208DF843301D +:1042700094F82C3083F001038DF844300023B88A81 +:104280007B602A7B013AFFF769F93B8BB882834256 +:1042900003D1A3680AA92046984720460AA9FFF738 +:1042A00001FEFB7DBA8AC3F38403013303F01F03CD +:1042B0009B02FB823B8B9A420CBF00206FF01000E8 +:1042C000C1E67B68002BAFD0052001E01C303346EF +:1042D0001E68002EFAD1091A2E1D081D184401EB84 +:1042E000090C5FFA89F3BCF11B0F9DD89A429BD948 +:1042F00016F8013B09F1010900F8013BEFE76FF007 +:104300000900A0E66FF00A009DE66FF00B009AE648 +:104310006FF00D0097E66FF00E0094E66FF00F005F +:1043200091E600BF40420F0080841E00EFF3098336 +:10433000054968334A6B22F001024A6383F3098816 +:10434000002383F31188704700EF00E0302080F3F2 +:10435000118862B60D4B0E4AD96821F4E061090458 +:10436000090C0A430B49DA60D3F8FC2042F0807252 +:10437000C3F8FC20084AC2F8B01F116841F00101DF +:1043800011602022DA7783F82200704700ED00E008 +:104390000003FA0555CEACC5001000E0302310B57F +:1043A00083F311880E4B5B6813F4006314D0F1EEB5 +:1043B000103AEFF309844FF08073683CE361094BD6 +:1043C000DB6B236684F3098800F050FE10B1064BC6 +:1043D000A36110BD054BFBE783F31188F9E700BF2C +:1043E00000ED00E000EF00E03F0400084204000898 +:1043F00008B5074B074A196801F03D0199605368F9 +:104400000BB190689847BDE80840FFF7C7BF00BFF1 +:10441000000002402464002008B5084B196889098F +:1044200001F03D018A019A60054AD3680BB1106919 +:104430009847BDE80840FFF7B1BF00BF0000024049 +:104440002464002008B5084B1968090C01F03D01EF +:104450000A049A60054A53690BB190699847BDE810 +:104460000840FFF79BBF00BF00000240246400200B +:1044700008B5084B1968890D01F03D018A059A605D +:10448000054AD3690BB1106A9847BDE80840FFF7A9 +:1044900085BF00BF000002402464002008B5074B20 +:1044A000074A596801F03D01D960536A0BB1906A1F +:1044B0009847BDE80840FFF771BF00BF0000024009 +:1044C0002464002008B5084B5968890901F03D01B2 +:1044D0008A01DA60054AD36A0BB1106B9847BDE8D0 +:1044E0000840FFF75BBF00BF0000024024640020CB +:1044F00008B5084B5968090C01F03D010A04DA605F +:10450000054A536B0BB1906B9847BDE80840FFF725 +:1045100045BF00BF000002402464002008B5084BDE +:104520005968890D01F03D018A05DA60054AD36BAF +:104530000BB1106C9847BDE80840FFF72FBF00BFD4 +:10454000000002402464002008B5074B074A1968A0 +:1045500001F03D019960536C0BB1906C9847BDE838 +:104560000840FFF71BBF00BF000402402464002086 +:1045700008B5084B1968890901F03D018A019A6064 +:10458000054AD36C0BB1106D9847BDE80840FFF7A2 +:1045900005BF00BF000402402464002008B5084B9A +:1045A0001968090C01F03D010A049A60054A536D2F +:1045B0000BB1906D9847BDE80840FFF7EFBE00BF14 +:1045C000000402402464002008B5084B1968890DD6 +:1045D00001F03D018A059A60054AD36D0BB1106E5A +:1045E0009847BDE80840FFF7D9BE00BF000402406D +:1045F0002464002008B5074B074A596801F03D01C3 +:10460000D960536E0BB1906E9847BDE80840FFF734 +:10461000C5BE00BF000402402464002008B5084B5A +:104620005968890901F03D018A01DA60054AD36EB3 +:104630000BB1106F9847BDE80840FFF7AFBE00BF51 +:10464000000402402464002008B5084B5968090C96 +:1046500001F03D010A04DA60054A536F0BB1906F17 +:104660009847BDE80840FFF799BE00BF000402402C +:104670002464002008B5084B5968890D01F03D01FC +:104680008A05DA60054AD36F13B1D2F880009847E3 +:10469000BDE80840FFF782BE000402402464002009 +:1046A00000230C4910B51A460B4C0B6054F823003C +:1046B000026001EB430004334260402BF6D1074A0D +:1046C0004FF0FF339360D360C2F80834C2F80C3463 +:1046D00010BD00BF246400207C630008000002407D +:1046E0000F28F8B510D9102810D0112811D0122891 +:1046F00008D10F240720DFF8B4E00126DEF80050CF +:10470000A04208D9002649E00446F4E70F2400201F +:10471000F1E70724FBE706FA00F73D4240D1214CC0 +:104720004FEA001C3D4304EB00160EEBC000CEF830 +:104730000050C0E90123FBB24BB11B48836B43F02F +:1047400001038363036E43F001030366036E17F4F2 +:104750007F4F09D01448836B43F002038363036ED9 +:1047600043F002030366036E54F80C00036823F061 +:104770001F030360056815F00105FBD104EB0C0372 +:104780003D2493F80CC05F6804FA0CF43C602124CB +:104790000560446112B1987B00F00EFA3046F8BD16 +:1047A0000130ADE77C630008004502582464002016 +:1047B00010B5302484F31188FFF792FF002383F3B0 +:1047C000118810BD10B50446807B00F00BFA012360 +:1047D0001049627B03FA02F20B6823EA0203DAB2A1 +:1047E0000B604AB90C4A916B21F001019163116E83 +:1047F00021F001011166126E13F47F4F09D1064BAF +:104800009A6B22F002029A631A6E22F002021A6672 +:104810001B6E10BD246400200045025808B53023EB +:1048200083F31188FFF7CEFF002383F3118808BDBF +:104830000023054A19460133102BC2E9001102F189 +:104840000802F8D1704700BFA86400202DE9F74F97 +:1048500002F0030AC2F3C313C2F38009C2F3C10812 +:10486000C2F3411E574600224FF00F0B0193CB07B6 +:1048700033D502F00703019C012556009B00BAF1D5 +:10488000020F05FA02F504FA03FC44680BFA03F37D +:1048900024EA05046FEA030344EA090444604FF084 +:1048A0000304856804FA06F625EA06056FEA06049D +:1048B00045EA08058560C56825EA060545EA0E054E +:1048C000C5601BD1072A13D8056A2B4043EA0C03A5 +:1048D000036203681C403C430460490822D04FEA4D +:1048E000490901324FEA88084FEA8E0EBF00BEE741 +:1048F000456A2B4043EA0C034362EAE70568072A4E +:1049000004EA050444EA0704046005D8046A234065 +:1049100043EA0C030362E0E7446A234043EA0C03E2 +:104920004362DAE703B0BDE8F08F00000268436835 +:104930001143016003B1184770470000024A136831 +:1049400043F0C0031360704700100140024A13682F +:1049500043F0C00313607047007C004037B51A4C29 +:104960001A4D204600F0E8FA04F1140000940023E8 +:104970004FF40072164900F0A5F94FF40072154982 +:1049800004F138000094144B00F01EFA134BC4E9F4 +:104990001735134C204600F0CFFA04F11400002321 +:1049A0004FF400720F49009400F08CF90E4B4FF455 +:1049B00000720E4904F13800009400F005FA0C4B27 +:1049C000C4E9173503B030BD2865002000E1F505C6 +:1049D00000660020006A00203D49000800100140E8 +:1049E00094650020006800204D490008006C0020FC +:1049F000007C0040037C30B5284C002918BF0C46D1 +:104A0000012B0CD1264B984236D1264B1A6D42F021 +:104A100010021A659A6F42F010029A679B6F226823 +:104A2000036EC16D03EB52038466B3FBF2F362685D +:104A3000150442BF23F0070503F0070343EA4503CB +:104A4000CB60A36843F040034B60E36843F001038D +:104A50008B6042F4967343F001030B604FF0FF3319 +:104A60000B62510505D512F0102213D0B2F1805F10 +:104A700012D080F8643030BD0B4B9842CFD1094B37 +:104A80009A6C42F000429A641A6F42F000421A6730 +:104A90001B6FC4E77F23ECE73F23EAE77C64000851 +:104AA0002865002000450258946500202DE9F04754 +:104AB000C66D05463768F469210734621AD014F0D0 +:104AC000080118BF4FF48071E20748BF41F0200190 +:104AD000A3074FF0300348BF41F04001600748BFD3 +:104AE00041F0800183F31188281DFFF71FFF002389 +:104AF00083F31188E2050AD5302383F311884FF43C +:104B00008061281DFFF712FF002383F311884FF007 +:104B100030094FF0000A14F0200838D13B0616D5B2 +:104B20004FF0300905F1380A200610D589F31188B5 +:104B3000504600F07DF9002836DA0821281DFFF7DD +:104B4000F5FE27F080033360002383F31188790694 +:104B500014D5620612D5302383F31188D5E91323C7 +:104B60009A4208D12B6C33B127F040071021281D41 +:104B7000FFF7DCFE3760002383F31188E30618D5C6 +:104B8000AA6E1369ABB15069BDE8F047184789F3C5 +:104B90001188736A284695F86410194000F0E6F908 +:104BA0008AF31188F469B6E7B06288F31188F46972 +:104BB000BAE7BDE8F0870000090100F16043012277 +:104BC00003F56143C9B283F8001300F01F039A4054 +:104BD00043099B0003F1604303F56143C3F880215F +:104BE0001A60704700F01F0301229A40430900F148 +:104BF00060409B0000F5614003F1604303F56143B1 +:104C0000C3F88020C3F88021002380F80033704768 +:104C1000F8B51546826804460B46AA4200D285685C +:104C2000A1692669761AB5420BD218462A46FCF7C6 +:104C3000C9FEA3692B44A3612846A3685B1BA3603C +:104C4000F8BD0CD9AF1B18463246FCF7BBFE3A46FE +:104C5000E1683044FCF7B6FEE3683B44EBE71846F6 +:104C60002A46FCF7AFFEE368E5E70000836893425D +:104C7000F7B50446154600D28568D4E90460361AB3 +:104C8000B5420BD22A46FCF79DFE63692B44636153 +:104C90002846A3685B1BA36003B0F0BD0DD9324664 +:104CA000AF1B0191FCF78EFE01993A46E068314452 +:104CB000FCF788FEE3683B44E9E72A46FCF782FEFE +:104CC000E368E4E710B50A440024C361029B8460F2 +:104CD000C16002610362C0E90000C0E9051110BDB6 +:104CE00008B5D0E90532934201D1826882B9826861 +:104CF000013282605A1C426119700021D0E90432ED +:104D00009A4224BFC368436100F052FA002008BDF4 +:104D10004FF0FF30FBE7000070B5302304460E462D +:104D200083F31188A568A5B1A368A269013BA360BC +:104D3000531CA36115782269934224BFE368A361E1 +:104D4000E3690BB120469847002383F31188284676 +:104D500007E03146204600F01BFA0028E2DA85F32E +:104D6000118870BD2DE9F74F04460E461746984648 +:104D7000D0F81C904FF0300A8AF311884FF0000BE6 +:104D8000154665B12A4631462046FFF741FF0346E6 +:104D900060B94146204600F0FBF90028F1D000231D +:104DA00083F31188781B03B0BDE8F08FB9F1000FD1 +:104DB00003D001902046C847019B8BF31188ED1A60 +:104DC0001E448AF31188DCE7C160C361009B8260E6 +:104DD0000362C0E905111144C0E900000161704798 +:104DE000F8B504460D461646302383F31188A768AC +:104DF000A7B1A368013BA36063695A1C62611D707F +:104E0000D4E904329A4224BFE3686361E3690BB1D9 +:104E100020469847002080F3118807E0314620465D +:104E200000F0B6F90028E2DA87F31188F8BD000037 +:104E3000D0E9052310B59A4201D182687AB9826817 +:104E40000021013282605A1C82611C7803699A42F7 +:104E500024BFC368836100F0ABF9204610BD4FF05A +:104E6000FF30FBE72DE9F74F04460E4617469846FC +:104E7000D0F81C904FF0300A8AF311884FF0000BE5 +:104E8000154665B12A4631462046FFF7EFFE034638 +:104E900060B94146204600F07BF90028F1D000239C +:104EA00083F31188781B03B0BDE8F08FB9F1000FD0 +:104EB00003D001902046C847019B8BF31188ED1A5F +:104EC0001E448AF31188DCE70268436811430160DD +:104ED00003B11847704700001430FFF743BF0000CC +:104EE0004FF0FF331430FFF73DBF00003830FFF7BD +:104EF000B9BF00004FF0FF333830FFF7B3BF0000F9 +:104F00001430FFF709BF00004FF0FF311430FFF7F6 +:104F100003BF00003830FFF763BF00004FF0FF32DF +:104F20003830FFF75DBF0000012914BF6FF0130098 +:104F300000207047FFF712BD044B0360002343605D +:104F4000C0E9023301230374704700BF9464000872 +:104F500010B53023044683F31188FFF74BFD02237D +:104F60000020237480F3118810BD000038B5C36998 +:104F700004460D461BB904210844FFF7A5FF294646 +:104F800004F11400FFF7ACFE002806DA201D4FF4F0 +:104F90000061BDE83840FFF797BF38BD0023826845 +:104FA000037503691B6899689142FBD25A680360D4 +:104FB000426010605860704700238268037503697F +:104FC0001B6899689142FBD85A6803604260106080 +:104FD0005860704708B50846302383F311880B7D6D +:104FE000032B05D0042B0DD02BB983F3118808BDFA +:104FF0008B6900221A604FF0FF338361FFF7CEFF09 +:105000000023F2E7D1E9003213605A60F3E70000B1 +:10501000FFF7C4BF054BD96808751868026853606C +:105020001A600122D8600275FBF7F4B9006E002007 +:105030000C4B30B5DD684B1C87B004460FD02B46B7 +:10504000094A684600F046F92046FFF7E3FF009B57 +:1050500013B1684600F048F9A86907B030BDFFF702 +:10506000D9FFF9E7006E0020D54F0008044B1A68FD +:10507000DB6890689B68984294BF002001207047CD +:10508000006E0020084B10B51C68D8682268536079 +:105090001A600122DC602275FFF78EFF0146204670 +:1050A000BDE81040FBF7B6B9006E002038B5074CDC +:1050B00001230025064907482370656000F0C2FC03 +:1050C0000223237085F3118838BD00BF687000206B +:1050D000C0640008006E002008B572B6044B186565 +:1050E00000F0FCFA00F0C2FB024B03221A70FEE74C +:1050F000006E00206870002000F02CB98B60022345 +:10510000086108468B8270478368A3F1840243F8E4 +:10511000142C026943F8442C426943F8402C094A94 +:1051200043F8242CC268A3F1200043F8182C022273 +:1051300003F80C2C002203F80B2C034A43F8102C24 +:10514000704700BF2D040008006E002008B5FFF76F +:10515000DBFFBDE80840FFF75BBF0000024BDB68E8 +:1051600098610F20FFF756BF006E0020302383F3B5 +:105170001188FFF7F3BF000008B50146302383F321 +:1051800011880820FFF754FF002383F3118808BD1E +:10519000064BDB6839B1426818605A60136043609F +:1051A0000420FFF745BF4FF0FF307047006E00202E +:1051B0000368984206D01A680260506018469961E8 +:1051C000FFF726BF70470000036810B59C68A24235 +:1051D0000CD85C688A600B604C60216059609968EB +:1051E0008A1A9A604FF0FF33836010BD121B1B6850 +:1051F000ECE700000A2938BF0A2170B504460D46C5 +:105200000A26601900F016FC00F0FEFB041BA54204 +:1052100003D8751C04462E46F3E70A2E04D9012054 +:10522000BDE8704000F04EBC70BD0000F8B5144BF6 +:105230000D460A2A4FF00A07D96103F11001826076 +:1052400038BF0A224160196914460160486018613C +:10525000A81800F0DFFB00F0D7FB431B0646A34273 +:1052600006D37C1C28192746354600F0E3FBF2E7FD +:105270000A2F04D90120BDE8F84000F023BCF8BD96 +:10528000006E0020F8B506460D4600F0BDFB0F4A43 +:10529000134653F8107F9F4206D12A4601463046F6 +:1052A000BDE8F840FFF7C2BFD169BB68441A2C19AA +:1052B00028BF2C46A34202D92946FFF79BFF22466E +:1052C00031460348BDE8F840FFF77EBF006E00207E +:1052D000106E0020C0E90323002310B45DF8044BD6 +:1052E0004361FFF7CFBF000010B5194C2369984206 +:1052F0000DD08168D0E9003213605A609A680A4480 +:105300009A60002303604FF0FF33A36110BD026871 +:10531000234643F8102F53600022026022699A420C +:1053200003D1BDE8104000F07FBB936881680B4457 +:10533000936000F069FB2269E1699268441AA24215 +:10534000E4D91144BDE81040091AFFF753BF00BF6C +:10535000006E00202DE9F047DFF8BC8008F110074F +:105360002C4ED8F8105000F04FFBD8F81C40AA681B +:10537000031B9A423ED814444FF00009D5E900328D +:10538000C8F81C4013605A60C5F80090D8F8103077 +:10539000B34201D100F048FB89F31188D5E903310C +:1053A00028469847302383F311886B69002BD8D0A7 +:1053B00000F02AFB6A69A0EB040982464A450DD237 +:1053C000022000F07FFB0022D8F81030B34208D151 +:1053D00051462846BDE8F047FFF728BF121A22447D +:1053E000F2E712EB09092946384638BF4A46FFF76B +:1053F000EBFEB5E7D8F81030B34208D01444C8F833 +:105400001C00211AA960BDE8F047FFF7F3BEBDE814 +:10541000F08700BF106E0020006E002038B500F04D +:10542000F3FA054AD2E90845031B181945F10001B2 +:10543000C2E9080138BD00BF006E0020002070479F +:10544000FEE70000704700004FF0FF30704700009B +:10545000BFF34F8F044B1A695107FCD1D3F81021C9 +:105460005207F8D1704700BF0020005208B50D4B1D +:105470001B78ABB9FFF7ECFF0B4BDA68D10704D50B +:105480000A4A5A6002F188325A60D3F80C21D207D6 +:1054900006D5064AC3F8042102F18832C3F8042174 +:1054A00008BD00BF70700020002000522301674536 +:1054B00008B5114B1B78F3B9104B1A69510703D586 +:1054C000DA6842F04002DA60D3F81021520705D5BD +:1054D000D3F80C2142F04002C3F80C21FFF7B8FFCB +:1054E000064BDA6842F00102DA60D3F80C2142F090 +:1054F0000102C3F80C2108BD70700020002000528A +:105500000F289ABF00F5806040040020704700001B +:105510004FF4003070470000102070470F2808B586 +:105520000BD8FFF7EDFF00F500330268013204D11C +:1055300004308342F9D1012008BD0020FCE70000BF +:105540000F2838B505463FD8FFF782FF1F4CFFF7FD +:105550008DFF4FF0FF3307286361C4F814311DD865 +:105560002361FFF775FF030243F02403E360E36860 +:1055700043F08003E36023695A07FCD42846FFF711 +:1055800067FFFFF7BDFF4FF4003100F04BF92846ED +:10559000FFF78EFFBDE83840FFF7C0BFC4F81031F9 +:1055A000FFF756FFA0F108031B0243F02403C4F8E1 +:1055B0000C31D4F80C3143F08003C4F80C31D4F82A +:1055C00010315B07FBD4D9E7002038BD0020005222 +:1055D0002DE9F84F05460C46104645EA0203DE0663 +:1055E00002D00020BDE8F88F20F01F00DFF8BCB02B +:1055F000DFF8BCA0FFF73AFF04EB0008444503D1F5 +:105600000120FFF755FFEDE720222946204600F054 +:10561000EFFD10B920352034F0E72B4605F12002CC +:105620001F68791CDDD104339A42F9D105F1784322 +:105630001B481C4EB3F5801F1B4B38BF184603F1A7 +:10564000F80332BFD946D1461E46FFF701FF076077 +:10565000A5EB040C336804F11C0143F00203336032 +:10566000231FD9F8007017F00507FAD153F8042F5B +:105670008B424CF80320F4D1BFF34F8FFFF7E8FEC5 +:105680004FF0FF332022214603602846336823F081 +:105690000203336000F0ACFD0028BBD03846B0E711 +:1056A000142100520C2000521420005210200052ED +:1056B0001021005210B5084C237828B11BB9FFF710 +:1056C000D5FE0123237010BD002BFCD02070BDE857 +:1056D0001040FFF7EDBE00BF7070002038B5054DDB +:1056E00000240334696855F80C0B00F0ADF8122C57 +:1056F000F7D138BDCC640008084600F071BD000049 +:1057000038B5EFF311859DB9EFF30584C4F30804B0 +:10571000302334B183F31188FFF780FE85F31188BD +:1057200038BD83F31188FFF779FE84F3118838BD03 +:10573000BDE83840FFF772BE10B5FFF7E1FF104C2F +:10574000C008104A002340EA4170C908A0FB04ECDD +:10575000A0FB020E1CEB0000A1FB044CA1FB0212FB +:105760005B41001943EB0C0011EB0E0142F100020A +:10577000411842F10000090941EA007010BD00BF64 +:10578000CFF753E3A59BC4200244074BD2B210B518 +:10579000904200D110BD441C00B253F8200041F8E3 +:1057A000040BE0B2F4E700BF504000580E4B30B598 +:1057B0001C6F240405D41C6F1C671C6F44F4004448 +:1057C0001C670A4C02442368D2B243F480732360FE +:1057D000074B904200D130BD441C51F8045B00B22D +:1057E00043F82050E0B2F4E7004402580048025861 +:1057F0005040005807B5012201A90020FFF7C4FF5F +:10580000019803B05DF804FB13B50446FFF7F2FFFF +:10581000A04205D0012201A900200194FFF7C6FF94 +:1058200002B010BD0144BFF34F8F064B884204D332 +:10583000BFF34F8FBFF36F8F7047C3F85C02203008 +:10584000F4E700BF00ED00E00144BFF34F8F064BCB +:10585000884204D3BFF34F8FBFF36F8F7047C3F8F5 +:1058600070022030F4E700BF00ED00E07047000058 +:10587000074B45F255521A6002225A6040F6FF72F9 +:105880009A604CF6CC421A600122024B1A707047A3 +:105890000048005878700020034B1B781BB1034B65 +:1058A0004AF6AA221A607047787000200048005813 +:1058B000034B1A681AB9034AD2F8D0241A60704709 +:1058C0007470002000400258024B4FF48032C3F83D +:1058D000D02470470040025808B5FFF7E9FF024B9B +:1058E0001868C0F3806008BD7470002070B5BFF305 +:1058F0004F8FBFF36F8F1A4A0021C2F85012BFF3C7 +:105900004F8FBFF36F8F536943F400335361BFF37D +:105910004F8FBFF36F8FC2F88410BFF34F8FD2F851 +:10592000803043F6E074C3F3C900C3F34E335B0128 +:1059300003EA0406014646EA81750139C2F860525D +:10594000F9D2203B13F1200FF2D1BFF34F8F5369EF +:1059500043F480335361BFF34F8FBFF36F8F70BD3C +:1059600000ED00E0FEE70000214B2248224A70B51E +:10597000904237D3214BC11EDA1C121A22F00302C7 +:105980008B4238BF00220021FCF72EF81C4A00236E +:10599000C2F88430BFF34F8FD2F8803043F6E07402 +:1059A000C3F3C900C3F34E335B0103EA04060146A7 +:1059B00046EA81750139C2F86C52F9D2203B13F1E5 +:1059C000200FF2D1BFF34F8FBFF36F8FBFF34F8F15 +:1059D000BFF36F8F0023C2F85032BFF34F8FBFF376 +:1059E0006F8F70BD53F8041B40F8041BC0E700BF65 +:1059F000F86600087C7000207C7000207C7000201D +:105A000000ED00E000F01AB9014B586A704700BF82 +:105A1000000C0040034B002258631A610222DA6036 +:105A2000704700BF000C0040014B0022DA60704755 +:105A3000000C0040014B5863704700BF000C004051 +:105A4000FEE7000070B51B4B0025044686B0586089 +:105A50000E4685620163FEF779FC04F11003A56030 +:105A6000E562C4E904334FF0FF33C4E90044C4E9FC +:105A70000635FFF7C9FF2B46024604F134012046E4 +:105A8000C4E9082380230C4A2565FFF737FB01236F +:105A90000A4AE06000920375684672680192B26833 +:105AA000CDE90223064BCDE90435FFF74FFB06B0E5 +:105AB00070BD00BF687000201465000819650008FB +:105AC000415A0008024AD36A1843D062704700BFA7 +:105AD000006E00204B6843608B688360CB68C360B6 +:105AE0000B6943614B6903628B6943620B68036016 +:105AF0007047000008B53A4B40F2FF713948D3F8BF +:105B000088200A43C3F88820D3F8882022F4FF6253 +:105B100022F00702C3F88820D3F88830324B1A6C81 +:105B20000A431A649A6E0A439A66304A9B6E11467B +:105B3000FFF7D0FF00F5806002F11C01FFF7CAFFFC +:105B400000F5806002F13801FFF7C4FF00F58060C6 +:105B500002F15401FFF7BEFF00F5806002F1700111 +:105B6000FFF7B8FF00F5806002F18C01FFF7B2FF8C +:105B700000F5806002F1A801FFF7ACFF00F580603E +:105B800002F1C401FFF7A6FF00F5806002F1E00119 +:105B9000FFF7A0FF00F5806002F1FC01FFF79AFF1C +:105BA00002F58C7100F58060FFF794FF00F008F9B2 +:105BB0000F4BD3F8902242F00102C3F89022D3F8A1 +:105BC000942242F00102C3F894220522C3F89820DF +:105BD0004FF06052C3F89C20064AC3F8A02008BDCD +:105BE0000044025800000258004502582065000891 +:105BF00000ED00E01F00080308B500F0CDFAFFF744 +:105C000055FA0B4BDA6B42F04002DA635A6E22F01F +:105C100040025A665B6E074B1A6842F008021A602F +:105C20001A6842F004021A60BDE80840FFF740BE5F +:105C30000045025800180248704700000E4B9A6C4D +:105C400042F008029A641A6F42F008021A670B4A7F +:105C50001B6FD36B43F00803D363C722084B9A62D0 +:105C60004FF0FF32DA6200229A615A63DA605A60BA +:105C700001225A611A607047004502580010005C0A +:105C8000000C0040094A08B51169D3680B40D9B22D +:105C90009B076FEA0101116107D5302383F3118857 +:105CA000FFF72AFA002383F3118808BD000C004097 +:105CB000044BDA6B0243DA635A6E104358665B6E2C +:105CC000704700BF0045025808B53C4B4FF0FF310C +:105CD000D3F8802062F00042C3F88020D3F88020FF +:105CE00002F00042C3F88020D3F88020D3F884204B +:105CF000C3F88410D3F884200022C3F88420D3F89A +:105D00008400D86F40F0FF4040F4FF0040F4DF40D3 +:105D100040F07F00D867D86F20F0FF4020F4FF00EC +:105D200020F4DF4020F07F00D867D86FD3F88800D8 +:105D30006FEA40506FEA5050C3F88800D3F88800EB +:105D4000C0F30A00C3F88800D3F88800D3F89000A5 +:105D5000C3F89010D3F89000C3F89020D3F89000C7 +:105D6000D3F89400C3F89410D3F89400C3F89420A7 +:105D7000D3F89400D3F89800C3F89810D3F898009B +:105D8000C3F89820D3F89800D3F88C00C3F88C108F +:105D9000D3F88C00C3F88C20D3F88C00D3F89C0087 +:105DA000C3F89C10D3F89C10C3F89C20D3F89C3007 +:105DB000FEF776FCBDE8084000F0BEB9004402588A +:105DC00008B50122504BC3F80821504B5A6D42F0E0 +:105DD00002025A65DA6F42F00202DA670422DB6FD0 +:105DE0004B4BDA605A689104FCD54A4A1A6001228A +:105DF0009A60494ADA6000221A614FF440429A617F +:105E0000434B9A699204FCD51A6842F480721A6076 +:105E1000424B1A6F12F4407F04D04FF480321A675D +:105E200000221A671A6842F001021A603B4B1A6896 +:105E30005007FCD500221A611A6912F03802FBD112 +:105E4000012119604FF0804159605A67344ADA6283 +:105E5000344A1A611A6842F480321A602F4B1A6869 +:105E60009103FCD51A6842F480521A601A689204B1 +:105E7000FCD52D4A2D499A6200225A63196301F517 +:105E80007C01DA6301F5E77199635A64284A1A6460 +:105E9000284ADA621A6842F0A8521A601F4B1A6840 +:105EA00002F02852B2F1285FF9D148229A614FF4EA +:105EB0008862DA6140221A621F4ADA641F4A1A6550 +:105EC0001F4A5A651F4A9A6532231F4A1360136896 +:105ED00003F00F03022BFAD1104A136943F00303B6 +:105EE0001361136903F03803182BFAD14FF00050F7 +:105EF000FFF7DEFE4FF08040FFF7DAFE4FF0004084 +:105F0000BDE80840FFF7D4BE0080005100450258AC +:105F10000048025800C000F004000001004402588C +:105F20000000FF0100889008322060006302090130 +:105F3000470E0508DD0BBF01200000200000011006 +:105F40000910E00000010110002000524FF0B042A3 +:105F500008B5D2F8883003F00103C2F8883023B1C5 +:105F6000044A13680BB150689847BDE80840FEF733 +:105F700015BA00BFA86400204FF0B04208B5D2F8AF +:105F8000883003F00203C2F8883023B1044A9368D2 +:105F90000BB1D0689847BDE80840FEF7FFB900BFD5 +:105FA000A86400204FF0B04208B5D2F8883003F062 +:105FB0000403C2F8883023B1044A13690BB1506955 +:105FC0009847BDE80840FEF7E9B900BFA864002083 +:105FD0004FF0B04208B5D2F8883003F00803C2F899 +:105FE000883023B1044A93690BB1D0699847BDE862 +:105FF0000840FEF7D3B900BFA86400204FF0B042BC +:1060000008B5D2F8883003F01003C2F8883023B105 +:10601000044A136A0BB1506A9847BDE80840FEF77E +:10602000BDB900BFA86400204FF0B04310B5D3F84D +:10603000884004F47872C3F88820A30604D5124A75 +:10604000936A0BB1D06A9847600604D50E4A136B69 +:106050000BB1506B9847210604D50B4A936B0BB1DB +:10606000D06B9847E20504D5074A136C0BB1506C0E +:106070009847A30504D5044A936C0BB1D06C98479C +:10608000BDE81040FEF78AB9A86400204FF0B04385 +:1060900010B5D3F8884004F47C42C3F88820620528 +:1060A00004D5164A136D0BB1506D9847230504D5DE +:1060B000124A936D0BB1D06D9847E00404D50F4A96 +:1060C000136E0BB1506E9847A10404D50B4A936E22 +:1060D0000BB1D06E9847620404D5084A136F0BB118 +:1060E000506F9847230404D5044A936F0BB1D06FC7 +:1060F0009847BDE81040FEF751B900BFA8640020E2 +:1061000008B50348FEF7D2FCBDE80840FEF746B9E3 +:106110002865002008B50348FEF7C8FCBDE8084024 +:10612000FEF73CB99465002008B5FFF7ABFDBDE86C +:106130000840FEF733B90000062108B50846FEF70F +:106140003BFD06210720FEF737FD06210820FEF75C +:1061500033FD06210920FEF72FFD06210A20FEF758 +:106160002BFD06211720FEF727FD06212820FEF72C +:1061700023FD09217A20FEF71FFD07213220FEF7BB +:106180001BFD0C212520FEF717FD0C215320BDE837 +:106190000840FEF711BD000008B5FFF795FDFEF7BA +:1061A00047FBFEF7C7FEFFF747FDBDE80840FFF7D6 +:1061B00029BC00000B460146184600F003B8000059 +:1061C00000F00EB810B5054C13462CB10A46014636 +:1061D0000220AFF3008010BD2046FCE70000000065 +:1061E000024B01461868FFF787BA00BF3C23002026 +:1061F00010B501390244904201D1002005E0037836 +:1062000011F8014FA34201D0181B10BD0130F2E775 +:106210002DE9F041A3B1C91A17780144044603F1EE +:10622000FF3C8C42204601D9002009E00578BD42A0 +:1062300004F10104F5D10CEB0405D618A54201D1F7 +:10624000BDE8F08115F8018D16F801EDF045F5D0A7 +:10625000E7E70000034611F8012B03F8012B002AA1 +:10626000F9D17047636F6D2E6375626570696C6FED +:10627000742E6865726534666300000053544D33B4 +:106280003248373F3F3F0053544D3332483733781D +:106290002F3732780053544D3332483734332F3749 +:1062A00035332F373530000001105A0003105900E4 +:1062B000012058000320560040A2E4F164689106D2 +:1062C0000041A3E5F26569920700000043414E4694 +:1062D0004449666163653A204D6573736167652063 +:1062E00052414D204F766572666C6F772100000039 +:1062F0004261642043414E496661636520696E6472 +:1063000065782E00000100000001FF0000A00040A1 +:1063100000A400400000000000000000712A0008F6 +:10632000F9220008F93100086923000875230008E4 +:106330008D270008ED2400083123000835230008CC +:106340000D230008F522000849270008192300083A +:1063500061330008252300081D27000801040E05ED +:10636000054B02020E05054B04010E05054B050108 +:106370000B04044B08010603034600001000024012 +:10638000080002400008024000000B002800024004 +:10639000080002400408024006010C0040000240D0 +:1063A000080002400808024010020D005800024098 +:1063B000080002400C08024016030E007000024064 +:1063C0000C0002401008024000040F008800024048 +:1063D0000C0002401408024006051000A000024014 +:1063E0000C0002401808024010061100B8000240DC +:1063F0000C0002401C08024016072F001004024047 +:106400000804024020080240000838002804024026 +:1064100008040240240802400609390040040240F2 +:106420000804024028080240100A3A0058040240BA +:10643000080402402C080240160B3B007004024086 +:106440000C04024030080240000C3C00880402406A +:106450000C04024034080240060D4400A00402402F +:106460000C04024038080240100E4500B8040240F7 +:106470000C0402403C080240160F46000096000043 +:10648000000000000000000000000000000000000C +:106490000000000000000000F54E0008E14E00087A +:1064A0001D4F0008094F0008154F0008014F000854 +:1064B000ED4E0008D94E0008294F00086330000057 +:1064C000BC640008586E00206870002000010020A5 +:1064D00000FF010002000000000000300000040086 +:1064E0000800000000000024000008000400000074 +:1064F0000004000000FC0000020000000000043066 +:1065000000800000080000000000003800000100CA +:10651000010000006D61696E0069646C6500000037 +:106520000000002800000000AAAAAAAA0000002477 +:10653000FFFF0000000000000000000000A0550A5E +:1065400000000000AAAA9AAA00500000FFF2000072 +:10655000000000770000990000000000000000002B +:10656000AAAAAAAA00000000FFFF00000000000085 +:10657000000000005A000000000000009AAAAAAA29 +:1065800000000000F3FF0000990000000000000080 +:106590000A00000000000000AAAAAAAA0500000044 +:1065A000FFFF000088000000000000000000000065 +:1065B00000000000AAAAAAAA00000000FFFF000035 +:1065C00000000000000000000000000000000000CB +:1065D000AAAAAAAA00000000FFFF00000000000015 +:1065E000000000000000000000000000AAAAAAAA03 +:1065F00000000000FFFF000000000000000000009D +:106600000000000000000000AAAAAAAA00000000E2 +:10661000FFFF00000000000000000000000000007C +:1066200000000000AAAAAAAA00000000FFFF0000C4 +:10663000000000000000000000000000000000005A +:10664000AAAAAAAA00000000FFFF000000000000A4 +:106650000000000000000000130400000000000023 +:106660000000180000000000FE2A0100D204000013 +:10667000FF00000028650020946500200000000055 +:106680007C62000883040000876200085004000058 +:106690009562000840230020000000000000000078 +:1066A00000000000000000000000000000000000EA +:1066B00000000000000000000000000000000000DA +:1066C00000000000000000000000000000000000CA +:1066D00000000000000000000000000000000000BA +:1066E00000000000000000000000000000000000AA +:0866F0000000000000000000A2 :00000001FF diff --git a/Tools/bootloaders/Hitec-Airspeed_bl.bin b/Tools/bootloaders/Hitec-Airspeed_bl.bin index 55619f2fe2f12d..f0630d4b639cab 100755 Binary files a/Tools/bootloaders/Hitec-Airspeed_bl.bin and b/Tools/bootloaders/Hitec-Airspeed_bl.bin differ diff --git a/Tools/bootloaders/Hitec-Airspeed_bl.elf b/Tools/bootloaders/Hitec-Airspeed_bl.elf index 4d314a924ab645..af0727e16d9011 100755 Binary files a/Tools/bootloaders/Hitec-Airspeed_bl.elf and b/Tools/bootloaders/Hitec-Airspeed_bl.elf differ diff --git a/Tools/bootloaders/Hitec-Airspeed_bl.hex b/Tools/bootloaders/Hitec-Airspeed_bl.hex index efa3593106fa24..d820559c415220 100644 --- a/Tools/bootloaders/Hitec-Airspeed_bl.hex +++ b/Tools/bootloaders/Hitec-Airspeed_bl.hex @@ -1,1195 +1,1172 @@ :020000040800F2 -:1000000000090020F50400086928000821280008DC -:10001000492800082128000841280008F7040008A2 -:10002000F7040008F7040008F7040008493800083E -:10003000F7040008F7040008F7040008F7040008B4 -:10004000F7040008F7040008F7040008F7040008A4 -:10005000F7040008F7040008BD450008E54500085E -:100060000D460008354600085D460008F704000804 -:10007000F7040008F7040008F7040008F704000874 -:10008000F7040008F7040008F7040008F704000864 -:10009000F704000801280008112800088546000818 -:1000A000F7040008F7040008F7040008F704000844 -:1000B00059470008F7040008F7040008F70400088F -:1000C000F7040008F7040008F7040008F704000824 -:1000D000F7040008F7040008F7040008F704000814 -:1000E000E9460008F7040008F7040008F7040008D0 -:1000F000F7040008F7040008F7040008F7040008F4 -:10010000F7040008F7040008F7040008F7040008E3 -:10011000F7040008F7040008F7040008F7040008D3 -:10012000F7040008F7040008F7040008F7040008C3 -:10013000F7040008F7040008F7040008F7040008B3 -:10014000F7040008F7040008F7040008F7040008A3 -:10015000F7040008F7040008F7040008F704000893 -:10016000F7040008F7040008F7040008F704000883 -:10017000F7040008F7040008F7040008F704000873 -:10018000F7040008F7040008F7040008F704000863 -:10019000F7040008F7040008F7040008F704000853 -:1001A000F7040008F7040008F7040008F704000843 -:1001B000F7040008F7040008F7040008F704000833 -:1001C000F7040008F7040008F7040008F704000823 -:1001D000F7040008F7040008F7040008F704000813 -:1001E0007112000800000000000000000000000084 -:1001F00053B94AB9002908BF00281CBF4FF0FF318E -:100200004FF0FF3000F074B9ADF1080C6DE904CE89 -:1002100000F006F8DDF804E0DDE9022304B07047E1 -:100220002DE9F047089D04468E46002B4DD18A42A9 -:10023000944669D9B2FA82F252B101FA02F3C2F1DC -:10024000200120FA01F10CFA02FC41EA030E94406D -:100250004FEA1C48210CBEFBF8F61FFA8CF708FB8E -:1002600016E341EA034306FB07F199420AD91CEB66 -:10027000030306F1FF3080F01F81994240F21C8198 -:10028000023E63445B1AA4B2B3FBF8F008FB1033E0 -:1002900044EA034400FB07F7A7420AD91CEB040415 -:1002A00000F1FF3380F00A81A74240F207816444E5 -:1002B000023840EA0640E41B00261DB1D44000236A -:1002C000C5E900433146BDE8F0878B4209D9002DCE -:1002D00000F0EF800026C5E9000130463146BDE858 -:1002E000F087B3FA83F6002E4AD18B4202D38242C2 -:1002F00000F2F980841A61EB030301209E46002D71 -:10030000E0D0C5E9004EDDE702B9FFDEB2FA82F2C5 -:10031000002A40F09280A1EB0C014FEA1C471FFA23 -:100320008CFE0126200CB1FBF7F307FB131140EA0A -:1003300001410EFB03F0884208D91CEB010103F1D7 -:10034000FF3802D2884200F2CB804346091AA4B299 -:10035000B1FBF7F007FB101144EA01440EFB00FE6D -:10036000A64508D91CEB040400F1FF3102D2A645D2 -:1003700000F2BB800846A4EB0E0440EA03409CE771 -:10038000C6F12007B34022FA07FC4CEA030C20FA1E -:1003900007F401FA06F31C43F9404FEA1C4900FA3E -:1003A00006F3B1FBF9F8200C1FFA8CFE09FB1811BB -:1003B00040EA014108FB0EF0884202FA06F20BD92E -:1003C0001CEB010108F1FF3A80F08880884240F27E -:1003D0008580A8F102086144091AA4B2B1FBF9F0C2 -:1003E00009FB101144EA014100FB0EFE8E4508D9BD -:1003F0001CEB010100F1FF346CD28E456AD9023842 -:10040000614440EA0840A0FB0294A1EB0E01A14226 -:10041000C846A64656D353D05DB1B3EB080261EB94 -:100420000E0101FA07F722FA06F3F1401F43C5E96E -:10043000007100263146BDE8F087C2F12003D840A4 -:100440000CFA02FC21FA03F3914001434FEA1C47E6 -:100450001FFA8CFEB3FBF7F007FB10360B0C43EAD8 -:10046000064300FB0EF69E4204FA02F408D91CEB88 -:10047000030300F1FF382FD29E422DD90238634486 -:100480009B1B89B2B3FBF7F607FB163341EA034126 -:1004900006FB0EF38B4208D91CEB010106F1FF3875 -:1004A00016D28B4214D9023E6144C91A46EA00466C -:1004B00038E72E46284605E70646E3E61846F8E6FE -:1004C0004B45A9D2B9EB020864EB0C0E0138A3E747 -:1004D0004646EAE7204694E74046D1E7D0467BE728 -:1004E000023B614432E7304609E76444023842E7A0 -:1004F000704700BF02E000F000F8FEE772B6374830 -:1005000080F30888364880F3098836483649086001 -:1005100040F20000CCF200004EF63471CEF2000141 -:100520000860BFF34F8FBFF36F8F40F20000C0F23F -:10053000F0004EF68851CEF200010860BFF34F8FF5 -:10054000BFF36F8F4FF00000E1EE100A4EF63C71E2 -:10055000CEF200010860062080F31488BFF36F8F8D -:1005600003F05CFE03F0EEFE4FF055301F491B4ACE -:1005700091423CBF41F8040BFAE71D49184A9142E9 -:100580003CBF41F8040BFAE71A491B4A1B4B9A423D -:100590003EBF51F8040B42F8040BF8E7002018495D -:1005A000184A91423CBF41F8040BFAE703F03AFEC7 -:1005B00003F00EFF144C154DAC4203DA54F8041B43 -:1005C0008847F9E700F042F8114C124DAC4203DACB -:1005D00054F8041B8847F9E703F022BE0009002005 -:1005E000001100200000000808ED00E000010020DC -:1005F00000090020104A0008001100207C11002092 -:1006000080110020D83E0020E0010008E40100082D -:10061000E4010008E40100082DE9F04F2DED108AF7 -:10062000C1F80CD0C3689D46BDEC108ABDE8F08FC0 -:10063000002383F311882846A047002003F09AFA8C -:10064000FEE703F0FDF900DFFEE70000F8B500F07B -:1006500021FE03F085FD074603F0D6FD0546D0BB1D -:10066000294B9F4237D001339F4237D0274B27F089 -:10067000FF029A4235D1F8B200F044FC2E4642F215 -:10068000107400F045FC08B10024264601F0BAF8C9 -:1006900058B3032000F03EF80024264635B11C4B29 -:1006A0009F4203D003F0A8FD00242646002003F05B -:1006B00061FD0EB100F044F800F05CFC00F0ECFDD0 -:1006C00002F0DAF80546B4B900F09CFC4FF47A70F9 -:1006D00003F056FAF7E72E460024D2E70446012637 -:1006E000CFE706464FF47A74CBE7002CD6D04FF410 -:1006F0007A740126D2E702F0BFF8431BA342E3D984 -:1007000000F01EF8DCE700BF010007B0000008B0F1 -:10071000263A09B0084B187003280CD8DFE800F01F -:1007200008050208022000F013BE022000F008BEF7 -:10073000024B00225A607047801100208411002073 -:1007400038B501F05FF830B1254B03221A70254B04 -:1007500000225A6038BD244B244A19680131F9D06F -:1007600004339342F9D1224C1F4DD4F80428AA42F5 -:10077000F0D3204B9B6803F1006303F5D0439A420A -:10078000E8D203F00BFD03F01DFD002000F09EFDFC -:100790000220FFF7BFFF184B9A6D00229A65996FF0 -:1007A0009A67996FD96DDA65D96FDA67D96F196E63 -:1007B0001A66D3F88010C3F88020D3F8803072B660 -:1007C0004FF0E0233021C3F8085DD4F80038D4F8A6 -:1007D000042881F311889D4683F308881047B9E700 -:1007E00080110020841100200068000820680008A3 -:1007F000006000080011002000100240094A136840 -:1008000049F2690099B21B0C00FB01331360064BDF -:10081000186844F2506182B2000C01FB02001860BB -:1008200080B27047141100201011002010B5002173 -:100830001022044600F0A6FD034B03CB206061604C -:100840001868A06010BD00BF9075FF1F2DE9F04132 -:10085000ADF5507D0DF13C086EAC40F275120746C7 -:100860000D4610A80021C8F8001000F08BFD4FF4D1 -:10087000C4720021204600F085FD01F0FDFF254BEC -:100880004FF47A72B0FBF2F0186093E8070002238D -:1008900084E807000DF5ED702382FFF7C7FF41F2F2 -:1008A00004631D49238407A803F0ECFF1C2384F88C -:1008B00032310DF2EB226B440DF1340C1E4603CEA7 -:1008C000664510605160334602F10802F6D1306887 -:1008D000106041460122204600F0A0FD0023039352 -:1008E000AB7E029305F11903019380B20123CDE998 -:1008F00004800093E97E05A3D3E90023384602F083 -:1009000079FB0DF5507DBDE8F08100BF9E6AC421E2 -:10091000818A46EE8C110020944800082DE9F041B0 -:100920002C4C237ADAB080460D465BBB27A92846BB -:1009300000F084FE0746002842D19DF89D60C82E35 -:100940003ED801464FF4A662204600F01BFD4FF44E -:100950008073C4F8F8314FF40073C4F80C334FF4CB -:100960004073C4F8203432460DF19E0104F10900B1 -:1009700000F0F6FC26449DF89C30777223720BB988 -:10098000EB7E23728122002106AC27A800F0FAFC3E -:100990000122214627A800F08DFE00230393AB7EA1 -:1009A000029305F1190380B201932823CDE9044095 -:1009B0000093E97E05A3D3E90023404602F01AFB29 -:1009C0005AB0BDE8F08100BFAFF3008026417272DB -:1009D000DF25D7B788360020F0B5254E4FF48A754D -:1009E00005FB0065F1B096F8D83085F8DC300024BE -:1009F000D822214685F8E8403AA800F0C3FC06F169 -:100A0000090000F0B7FCD5F8E4308DF8F000C2B270 -:100A100006AF06F109010DF1F100CDE93A3400F01D -:100A20009FFC394601223AA800F070FE80B2CDE961 -:100A3000047008230127CDE9023706F1D80301939A -:100A400030230093317A0B4807A3D3E9002302F047 -:100A5000D1FAA04206DD01F00FFFC5F8E0003846EC -:100A600071B0F0BD2046FBE778F6339F93CACD8D79 -:100A700088360020A42100202DE9F0411D4D1E4E96 -:100A80001E4F86B0284602F0E1FA034658B3002410 -:100A9000CDE90344ADF81440027B8DF81420996829 -:100AA0004068029403AA03C21B68DFF8548043F035 -:100AB0000043029301F0E2FE821941F10003009429 -:100AC00002A9384601F0BAF8A04205DD284602F036 -:100AD000C1FA88F80040D5E798F80030072B05D810 -:100AE000013388F8003006B0BDE8F081014802F01B -:100AF000B1FAF8E7A421002040420F00D8210020DD -:100B0000BD3B002070B50D4614461E4602F0CEF9DE -:100B100050B9022E10D1012C0ED112A3D3E900231B -:100B2000C5E90023012007E0282C10D005D8012CAE -:100B300009D0052C0FD0002070BD302CFBD10BA3A9 -:100B4000D3E90023ECE70BA3D3E90023E8E70BA3E9 -:100B5000D3E90023E4E70BA3D3E90023E0E700BFD8 -:100B6000AFF30080401DA12026812A0B78F6339F29 -:100B700093CACD8D9E6AC421818A46EE2641727247 -:100B8000DF25D7B7F017304A39059E5638B50546E8 -:100B90000E4C0021013500F0BBFBA4F82C55B4F835 -:100BA0002C0500F09DFB78B1B4F82C0500F0A8FBF3 -:100BB000014648B9B4F82C0500F0AAFBB4F82C356E -:100BC0000133A4F82C35EAE738BD00BF8836002091 -:100BD00010B50A4B0A4A1A6003F5805393F848206F -:100BE0003AB95C6C2CB1204600F08AFE204603F036 -:100BF000FFFDBDE81040034800F082BED821002070 -:100C0000E4480008083200202DE9F04F8FB000AF13 -:100C100005460C4602F04AF9002849D1237E022BF2 -:100C20001BD1E38A012B18D101F026FE0646FFF7FF -:100C3000E5FD03464FF4C870DFF8C482B3FBF0F261 -:100C400006F5167602FB103316FA83F3C8F8003067 -:100C5000E37E33B9A34B00221A703C37BD46BDE892 -:100C6000F08F07F12401204600F0A6FC0028F4D103 -:100C700007F11400FFF7DAFD97F8264007F1140199 -:100C8000224607F1270003F0CBFD0028E2D10F2C0C -:100C900008D8944B1C70D8F80030A3F51673C8F828 -:100CA0000030DAE797F82410284602F0F7F8D4E786 -:100CB000E38A282B2BD010D8012B23D0052BCCD1A5 -:100CC000BFF34F8F8849894BCA6802F4E06213432F -:100CD000CB60BFF34F8F00BFFDE7302BBDD1844EFB -:100CE000E17E327A9142B8D1607E3146002291F89D -:100CF000DC50854200F0A5800132042A01F58A719A -:100D0000F5D1AAE721462846FFF7A0FDA5E7214631 -:100D10002846FFF703FEA0E7B2F8EC507B6005F130 -:100D200003094FEA99094FEA8902D11DC908A8EBC6 -:100D3000C1039D46EB460021584600F023FB04F119 -:100D4000EE012A463144584600F00AFB7B6813B98D -:100D5000012000F0BBFA96F8D20000F0C1FA044678 -:100D600030B9307200F0DCFA204600F0AFFAB1E0A2 -:100D7000D6F8D4203AB996F8D200B6F82C2582429B -:100D800001D8FFF703FFD6F8D4202A44944208D2B2 -:100D900096F8D200B6F82C250130824201D8FFF730 -:100DA000F5FE70685FFA89F2594600F0F3FA08B967 -:100DB000C54679E0726896F8D2002A447260D6F887 -:100DC000D42005EB0209C6F8D49000F089FA8145D9 -:100DD00009D396F8D220D6F8D4000132001B86F849 -:100DE000D220C6F8D400FF2D0FD80024347200F0B2 -:100DF00097FA204600F06AFA00F004FD3D4B188196 -:100E000008B9FFF79DFCC54627E7BB6896F8D900EF -:100E10000AFB0362FB68D2F8E41082F8E83001F5BF -:100E20008061C2F8E030C2F8E410FFF7D5FDFFF7AB -:100E300023FE96F8D920013202F0030286F8D92069 -:100E4000B6E74FF48A7A0AFB02F505F1EA0131446C -:100E5000204600F087FCF86000287FF4FEAE3544A1 -:100E6000012285F8E82001F007FDD5F8E020D6ED55 -:100E7000007ADFED216A801A192838BF192040F660 -:100E8000B832904228BF1046B8EE677A07EE900A53 -:100E9000F8EEE77A67EEA67ADFED186AE7EE267AD3 -:100EA000FCEEE77AC6ED007A96F8D930BB60BA68F6 -:100EB00073680AFB02F4321992F8E81059B1D2F8BB -:100EC000E4108B42E8463FF427AF002182F8E81097 -:100ED000C2F8E010C5467368064A9B0A01331381C5 -:100EE000BBE600BF9D21002000ED00E00400FA05F4 -:100EF000883600208C110020CDCCCC3D6666663F44 -:100F0000A0210020014B1870704700BF98110020ED -:100F100038B54FF00054134B22689A4220D1124B3F -:100F2000627D12481A70237D03724FF48073C0F8FB -:100F3000F8314FF40073C0F80C3300254FF44073C0 -:100F4000C0F820340A49C0F8E450C922093000F042 -:100F500007FAE0222946204600F014FA012038BDA5 -:100F60000020FCE79AAD44C5981100208836002087 -:100F70001600002037B500F045FC194D19492881AD -:100F800002236B7100220123174801F07FF8002330 -:100F90000193164B164900931648174B4FF4805295 -:100FA00001F054FF154B197811B1124801F076FF8A -:100FB00001F062FC0446FFF721FC4FF4C873B0FB5C -:100FC000F3F202FB130304F5167010FA83F00C4BD6 -:100FD000186003F019F908B10F232B8103B030BD5D -:100FE0008C11002040420F00D8210020050B000882 -:100FF0009C110020A4210020090C00089811002059 -:10100000A02100202DE9F04F2DED028B90A7D7E90C -:1010100000670FF24429D9E90089884C95B00DADDD -:101020009FED848BFFF728FDDFF834B200230C938B -:10103000ADF83C300D936B6000230DF125028DED72 -:10104000008B4FF0010A09A958468DF825308DF81C -:1010500024A001F079FB9DF824200023002A40F011 -:10106000AF80204601F022FF0546002847D1DFF877 -:10107000F4B101F001FCDBF8003098423FD301F0FD -:10108000FBFB0790FFF7BAFB079A4FF4C873B0FB5E -:10109000F3F101FB130302F5167010FA83F0CBF89D -:1010A0000000DFF8C4B19BF800100791002914BFBD -:1010B0002B46534610A88DF83030FFF7B7FB079941 -:1010C000C1F11002D2B2062A10AB28BF0622194481 -:1010D0000DF13100079200F043F9079A0CAB03932E -:1010E000182302930132564BD2B2CDE900A30492E9 -:1010F0003B463246204601F01FFF8BF8005001F0BE -:10110000BBFB504A504D1368C31AB3F57A7F32D3F4 -:10111000106001F0B3FB02460B46204601F0A4FF2D -:10112000204601F0C3FE30B32B7ADFF840A1002B3C -:1011300014BF032302238AF8053001F09DFB0DF153 -:10114000400B4FF47A730122B0FBF3F05946CAF812 -:101150000000504600F008FA182302933B4B01931D -:1011600080B240F25513CDE903B0009342464B469E -:10117000204601F0E1FE2B7AB3B101F07DFB4FF088 -:10118000000A83464FF48A7295F8D900504400F063 -:10119000030002FB005393F8E810002934D00AF151 -:1011A000010ABAF1040FEFD1C82002F0E9FC2B7A52 -:1011B000002B7FF434AF15B0BDEC028BBDE8F08F8F -:1011C0004FF0904110A84A6982F040024A611946E6 -:1011D000102200F0D7F80DF126030AAA0CA95846F0 -:1011E00000F01EFE95E8030011AB83E803009DF8B4 -:1011F0003C308DF84C300C9B109310A9DDE90A238C -:10120000204602F005F917E7D3F8E01049B12B6842 -:10121000FA2B38BFFA23ABEB01010533B1EB430FD7 -:10122000BDD3FFF7D9FB4FF48A720028B7D1BBE7D3 -:10123000AFF300800000000000000000A4210020A7 -:101240009C210020B83B002088360020BC3B0020B9 -:10125000401DA12026812A0BF1C6A7C1D068080F26 -:10126000D8210020A02100209D2100208C110020E9 -:1012700008B5054800F078FEBDE80840034A044977 -:10128000002003F0AFBA00BFD8210020F83B0020B7 -:10129000D10B00087047000070B502F0FDFD094E4B -:1012A000094D3080002428683388834208D902F031 -:1012B000EFFD2B6804440133B4F5D04F2B60F2D31B -:1012C00070BD00BFEC3B0020C03B002002F096BE8A -:1012D00000F10060920000F5D04002F019BE00005D -:1012E000054B1A68054B1B889B1A834202D9104490 -:1012F00002F0CEBD00207047C03B0020EC3B002038 -:10130000024B1B68184402F0C9BD00BFC03B00205F -:10131000024B1B68184402F0D3BD00BFC03B002045 -:10132000064991F8243033B10023086A81F824304B -:101330000822FFF7CDBF0120704700BFC43B00204B -:10134000022802BF4FF0904340229A61704700008C -:10135000022802BF4FF090434FF480029A61704719 -:1013600010B50023934203D0CC5CC4540133F9E799 -:1013700010BD000003460246D01A12F9011B0029D5 -:10138000FAD1704702440346934202D003F8011B8E -:10139000FAE770472DE9F8431F4D144695F82420CD -:1013A0000746884652BBDFF870909CB395F824300E -:1013B0002BB92022FF2148462F62FFF7E3FF95F863 -:1013C0002400C0F10802A24228BF2246D6B24146FC -:1013D000920005EB8000FFF7C3FF95F82430A41BB3 -:1013E0001E44F6B2082E17449044E4B285F82460F7 -:1013F000DBD1FFF795FF0028D7D108E02B6A03EB7C -:1014000082038342CFD0FFF78BFF0028CBD100208F -:10141000BDE8F8830120FBE7C43B00202DE9F0473D -:101420000D46044600219046284640F27912FFF707 -:10143000A9FF234620220021284601F08BFF231D0F -:1014400002222021284601F085FF631D032222216C -:10145000284601F07FFFA31D03222521284601F025 -:1014600079FF04F1080310222821284601F072FFB9 -:1014700004F1100308223821284601F06BFF04F123 -:10148000110308224021284601F064FF04F11203F1 -:1014900008224821284601F05DFF04F114032022B0 -:1014A0005021284601F056FF04F118034022702114 -:1014B000284601F04FFF04F120030822B0212846FE -:1014C00001F048FF04F121030822B821284601F069 -:1014D00041FF04F12207C0263B4631460822284638 -:1014E000083601F037FFB6F5A07F07F10107F3D109 -:1014F00004F1320308223146284601F02BFF002771 -:1015000004F1330A94F832304FEAC7099F4209F5D3 -:10151000A47615D3B8F1000F08D1314604F59973BC -:101520000722284601F016FF09F24F16274694F8C5 -:1015300032213B1B93420CD3F01DC008BDE8F0875D -:101540000AEB070308223146284601F003FF013762 -:10155000D8E707F2331331460822284601F0FAFE95 -:1015600008360137E3E7000013B5044608460021BA -:1015700001602346C0F803102022019001F0EAFE2A -:101580000198231D0222202101F0E4FE0198631D31 -:101590000322222101F0DEFE0198A31D0322252152 -:1015A00001F0D8FE019804F108031022282101F06F -:1015B000D1FE072002B010BDF7B50023047F0091D3 -:1015C0000E4607221946054601F088FD731C00935C -:1015D000012200230721284601F080FDC4B9B31C75 -:1015E0000093052223460821284601F077FD0D24AB -:1015F0003746B278BB1B934211D32B7FA88A07349E -:10160000E408BBB9844294BF0020012003B0F0BDC0 -:10161000AB8ADB00083BDB08B3700824E8E7FB1C5F -:101620000093214600230822284601F057FD083484 -:101630000137DEE7201A18BF0120E7E7F7B50023DE -:10164000047F00910E4608221946054601F046FD2A -:10165000731CC4B90822009311462346284601F0A2 -:101660003DFD1024012372785F1C013B934211D38E -:101670002B7FA88A0734E408BBB9844294BF0020BA -:10168000012003B0F0BDAB8ADB00083BDB087370C0 -:101690000824E7E7F319009321460023082228468F -:1016A00001F01CFD08343B46DDE7201A18BF01207D -:1016B000E7E70000F8B50E460546144600218122F2 -:1016C0003046FFF75FFE2B4608220021304601F02E -:1016D00041FE7CB96B1C07220821304601F03AFE1E -:1016E0000F2401236A785F1C013B934204D3E01D61 -:1016F000C008F8BD0824F4E7EB192146082230465B -:1017000001F028FE08343B46ECE70000F8B50E4631 -:10171000054614460021CE223046FFF733FE2B4605 -:1017200028220021304601F015FE7CB905F108039E -:1017300008222821304601F00DFE30242F462A7A57 -:101740007B1B934204D3E01DC008F8BD2824F5E7B5 -:1017500007F1090321460822304601F0FBFD083459 -:101760000137ECE7F7B5047F00910E460123102204 -:101770000021054601F0B2FCC4B9B31C0093092254 -:1017800023461021284601F0A9FC19243746728807 -:10179000BB1B9A4211D82B7FA88A0734E408BBB937 -:1017A000844294BF0020012003B0F0BDAB8ADB006F -:1017B000103BDB0873801024E8E73B1D00932146B3 -:1017C00000230822284601F089FC08340137DEE7AF -:1017D000201A18BF0120E7E730B5094D0A449142AD -:1017E0000DD011F8013B5840082340F30004013BA1 -:1017F0002C4013F0FF0384EA5000F6D1EFE730BD30 -:101800002083B8EDF7B5384A106851686B4603C3BA -:101810006A4636493648082303F012F80446002881 -:1018200033D10A25334A106851686B4603C36A46B0 -:1018300031492F48082303F003F80446002849D013 -:101840000369B3F5CC3F45D8B0F8661040F21642B4 -:1018500091423FD1294A024402F15C018B4239D3C3 -:101860005C3B234900209E1AFFF7B6FF324607462D -:1018700004F164010020FFF7AFFFA3689F4229D164 -:10188000E368984208BF002524E00369B3F5CC3F24 -:1018900027D8418B40F21642914220D1174A024488 -:1018A00002F110018B4218D3103B114900209D1A00 -:1018B000FFF792FF2A46064604F118010020FFF7C1 -:1018C0008BFFA3689E4202D1E368984201D00D25A8 -:1018D000A8E70025284603B0F0BD1025A2E70C2597 -:1018E000A0E70B259EE700BFB4480008DC97010085 -:1018F00000680008BD480008909701000898FFF7AD -:1019000010B5037C044613B9006802F081FF20463D -:1019100010BD00000023BFF35B8FC360BFF35B8F7C -:10192000BFF35B8F8360BFF35B8F7047BFF35B8F49 -:101930000068BFF35B8F704770B505460C30FFF74A -:10194000F5FF05F1080604463046FFF7EFFFA04219 -:1019500006D930466D68FFF7E9FF2544281A70BDA7 -:101960003046FFF7E3FF201AF9E7000070B505469F -:10197000406898B105F10800FFF7D8FF05F10C06A3 -:1019800004463046FFF7D2FF8442304694BF6D686C -:101990000025FFF7CBFF013C2C44201A70BD00004E -:1019A00038B50C460546FFF7C7FFA04210D305F136 -:1019B0000800FFF7BBFF04446868B4FBF0F100FBCC -:1019C0001144BFF35B8F0120AC60BFF35B8F38BD68 -:1019D0000020FCE72DE9F041144607460D46FFF7CD -:1019E000C5FF844228BF0446D4B1B84658F80C6BF2 -:1019F0004046FFF79BFF3044286040467E68FFF773 -:101A000095FF331A9C4203D86C600120BDE8F08139 -:101A10006B60A41B3B68AB602044E8600220F5E7E4 -:101A20002046F3E738B50C460546FFF79FFFA04276 -:101A300010D305F10C00FFF779FF04446868B4FB8C -:101A4000F0F100FB1144BFF35B8F0120EC60BFF3AA -:101A50005B8F38BD0020FCE72DE9FF4188466946D1 -:101A60000746FFF7B7FF6C4606B204EBC606002533 -:101A7000B44209D06268206808EB0501FFF770FCEA -:101A8000636808341D44F3E729463846FFF7CAFF68 -:101A9000284604B0BDE8F081F8B505460C300F4685 -:101AA000FFF744FF05F1080604463046FFF73EFF06 -:101AB000A042304688BF6C68FFF738FF201A3860B4 -:101AC00020B130462C68FFF731FF2044F8BD0000FC -:101AD00073B5144606460D46FFF72EFF844228BF15 -:101AE00004460190DCB101A93046FFF7D5FF019B08 -:101AF00033B93268C5E90233C5E9002401200CE09E -:101B00009C4238BF01942860019868608442F5D9EE -:101B10003368AB60241AEC60022002B070BD20462E -:101B2000FBE700002DE9FF410F466946FFF7D0FFB4 -:101B30006C4600B204EBC0050026AC4209D0D4F8D4 -:101B4000048054F8081BB8194246FFF709FC4644C4 -:101B5000F3E7304604B0BDE8F081000038B5054633 -:101B6000FFF7E0FF044601462846FFF719FF20462D -:101B700038BD0000302383F3118862B6704700003F -:101B8000002383F3118862B670470000012070477C -:101B90007047000010B41346026814680022A4467F -:101BA0005DF8044B6047000000F5805090F8590440 -:101BB0007047000000F5805090F852047047000014 -:101BC00000F5805090F9580470470000502070478D -:101BD00000F5805208B5FFF7CDFFD2F89834D2F85F -:101BE00094041844D2F890341844D2F87834184445 -:101BF000D2F888341844D2F884341844FFF7C0FF70 -:101C000008BD000038B5C26A936923F001039361EF -:101C1000044600F031FE0546E36A9B69DB0706D502 -:101C200000F02AFE431BFA2BF6D9002004E004F54D -:101C30008054012084F8520438BD00002DE9F04F93 -:101C40000C4600F5805185B01F4691F85234BDF81E -:101C50003890054690469BB1D1F874340133C1F8F1 -:101C6000743423689A0006D4237B082B0BD9627B3B -:101C70000AB10F2B07D9D1F878340133C1F8783481 -:101C80004FF0FF300FE0FFF775FFEB6AD3F8C42089 -:101C900012F4001A0AD0D1F87C340133C1F87C3434 -:101CA000FFF76EFF002005B0BDE8F08FD3F8C460E9 -:101CB00022686B6AC6F301464FF0480B002A1BFBF3 -:101CC000063BB4BF42F080429204CBF80020236868 -:101CD0005B0044BF42F00052CBF80020227B330669 -:101CE00043EA0243CBF80430607B720118B343F43B -:101CF0004013CBF80430D1F8A4340133C1F8A43434 -:101D0000AB1803F58353197B41F020011973207B35 -:101D1000039200F00DFE039A033080105FFA8AF3FD -:101D200083420AF1010A0DDA04EB83010BEB830312 -:101D300049689960F2E7AB1803F58353197B60F3A8 -:101D40004511E3E7EB6A0121B140C3F8CC10AB18B1 -:101D500003F58253C3E9048705EB461303F5825369 -:101D60002146183304F10C0051F804CB43F804CB9E -:101D70008142F9D1098819802A4441F26803284632 -:101D8000D65002F5805209F0030392F86C1043F02C -:101D9000100321F01F010B4382F86C30FFF7F0FEB7 -:101DA0004246CDF800903B46214600F087FD0120D9 -:101DB00079E7000013B500F580540191606CFFF7DE -:101DC000D5FD1F280AD90199606C2022FFF744FE37 -:101DD000A0F120035842584102B010BD0020FBE79B -:101DE00008B500F58050FFF7C5FE406CFFF792FD87 -:101DF000BDE80840FFF7C4BE002202608281426055 -:101E00008260704710B500220023C0E90023002340 -:101E1000044603810C30FFF7EFFF204610BD0000A1 -:101E20002DE9F047074688B007F5805468469A4682 -:101E30008846FFF79FFE9146FFF7E4FF606CFFF7CF -:101E40007BFD1F282CD9606C20226946FFF786FE97 -:101E5000202825D194F8523413B303AD444605AB82 -:101E60002E4603CE9E4220606160354604F1080490 -:101E7000F6D130682060B388A380DDE90023C9E98A -:101E80000023BDF80830AAF80030FFF779FE4A4673 -:101E900053464146384608B0BDE8F04700F0FCBC68 -:101EA000FFF76EFE002008B0BDE8F0872DE9F84F7F -:101EB00000230646C0E90133284B46F8303B00F5C5 -:101EC0008154054688463746103438462037FFF798 -:101ED00099FFA742F9D105F580544FF4805326634A -:101EE0000026C4E90D366764012305F5835705F51F -:101EF000A359E66384F8403084F84830103709F17C -:101F000010094FF0000A4FF0000B47E908ABA7F1AA -:101F10001800FFF771FF203747F8286C4F45F4D1C0 -:101F200084F85884A4F85A64A4F85C64A4F85E6445 -:101F300084F86064A4F86264A4F86464A4F8666435 -:101F400084F86864B8F1000F02D0054800F08EFCF8 -:101F5000044BEB622846BDE8F88F00BFE448000858 -:101F6000C84800080064004010B5044B19780446C6 -:101F70004A1C1A70FFF79AFF204610BDF53B00205F -:101F80002DE9F04300295FD03048314BB3FBF1F32A -:101F900081428CBF0A201120451EB3FBF0F700FBE5 -:101FA0001730ECB220B1022D2846F5D8002037E0DA -:101FB0007D1EB5F5806F33D2C4EBC40808F103036E -:101FC0004FEAE30EC3F3C703A4EB030C0EF10109C0 -:101FD0004FF47A705FFA8CF60EFB000E59FA8CFC07 -:101FE000BEFBFCFCBCF5617F1CDC1FFA8CF4581CAA -:101FF00056FA80F047431648B0FBF7F7B942D5D1FF -:10200000013BDBB20F2BD1D8711EC9B207294FF0AB -:10201000000005D810711480558053719171012012 -:10202000BDE8F08308F1FF334FEAE30CC3F3C703C5 -:10203000E41A0CF1010EE6B20CFB00005EFA84F427 -:10204000B0FBF4F4A4B2D2E70846E9E73F420F0040 -:1020500000366E010B4B10B54FF45472044600214C -:102060001846FFF78FF9084BA3614033E361D8337B -:102070002362F0336362E36A60610022C3F8C02028 -:1020800010BD00BF00A4004070A400402DE9F04F37 -:1020900000F58055994695F85834012B89B00446CF -:1020A0008A46904604D90027384609B0BDE8F08F2B -:1020B0008D4A52F8231009B942F823008B49C4F81D -:1020C0000CA00B7884F8109093B9FFF753FD884B60 -:1020D0009A6D42F000729A659A6B42F000729A63B0 -:1020E0009A6B22F000729A6301230B70FFF748FD90 -:1020F00095F8513473B903211520FFF73BFD01F02A -:1021000015FC0321162001F011FC012385F8513440 -:10211000FFF736FDFFF72EFDE26A936923F0100307 -:10212000936100F0A9FB0746E36A9E6916F0080672 -:1021300007D000F0A1FBC31BFA2BF5D9FFF720FD58 -:10214000B1E79A6942F001029A6100F095FB0746F7 -:10215000E36A9A69D00705D400F08EFBC31BFA2B03 -:10216000F6D9EBE79A6942F002029A61E36A002726 -:102170005F65FFF705FD686CFFF7CCFB04F5825B3C -:102180000BF1100B202200216846FFF7FBF802A894 -:10219000FFF732FE06976A460BEB06030DF1180EA9 -:1021A0009446BCE80300F44518605960624603F1A8 -:1021B0000803F5D1DCF80000186020369CF80420F4 -:1021C0001A71B6F5806FDDD1002304F5A25285F8AF -:1021D000503485F853341A3251462046FFF7D0FE6A -:1021E000074690B9E26A936923F00103936100F016 -:1021F00043FB0546E36A9B69D9077FF554AF00F0BE -:102200003BFB431BFA2BF5D94DE795F85F6495F836 -:102210005E24C5F86CA4360246EA426695F860244E -:10222000E36A1643B5F85C2446EA0246DE61B8F17B -:10223000000F29D004F5A352023241462046FFF791 -:102240009FFE90B9E26A936923F00103936100F065 -:1022500013FB0546E36A9B69DA077FF524AF00F0BC -:102260000BFB431BFA2BF5D91DE795F8683495F85D -:102270006714C5F870841B0143EA0123B5F86414A0 -:10228000E26A43EA0143D3602046FFF7E3FE0023FE -:1022900085F85934E36A6FF040421A65E36A154ADB -:1022A0005A65E36A44229A65E36A0722C3F8DC2090 -:1022B000E36A03229145DA653FF4F6AEE26A936978 -:1022C00023F00103936100F0D7FA0646E36A9B69A5 -:1022D000DB0705D500F0D0FA831BFA2BF6D9E2E62E -:1022E000012385F85234DFE6F03B0020F43B002068 -:1022F000001002409B0008002DE9F04F054689B010 -:1023000090469946002741F2680A00F58056EB6A2C -:10231000D3F8D430FB40D8074AD505EB47125244D6 -:102320004FEA471B1379190742D4D6F8803401339A -:10233000C6F8803413799A0648BFD6F8A83405EB5E -:102340000B0248BF0133524448BFC6F8A834137982 -:1023500043F008031371DB0722D596F85334FBB121 -:1023600005F58254183468465C44FFF74BFD03AB17 -:1023700004F1080C206861681A4603C208346445F9 -:102380001346F7D120681060A2889A800123ADF827 -:1023900008302B68CDE90089DB6B694628469847F1 -:1023A000D6F8543423B1D6F89C340133C6F89C34A3 -:1023B0000137202FABD109B0BDE8F08F2DE9F04FE8 -:1023C0008DB004460F4600F059FA82468946002F28 -:1023D00056D1E36AD3F89020920141BF04F58051B1 -:1023E000D1F894240132C1F89424D3F89020160730 -:1023F00003D100200DB0BDE8F08FD3F89050E6690E -:10240000C5F30125482303FB0566E8464046FFF770 -:10241000F3FC326851004ABF22F06043C2F38A43A2 -:1024200043F00043920048BF43F080430093736839 -:1024300013F400131FBF04F5805201238DF80D30F3 -:10244000D2F8AC340EBF8DF80D300133C2F8AC3485 -:10245000F38803F00F038DF80C304FF0000B9DF85C -:102460000C0000F065FA5FFA8BF3984220D9F2185D -:102470000CA90B44127A03F82C2C0BF1010BEEE79C -:10248000012FB6D1E36AD3F89820950141BF04F536 -:102490008051D1F894240132C1F89424D3F89820C3 -:1024A0001007A6D0D3F89850266AC5F30125A9E7EE -:1024B000EFB9E36AC3F8945004A8FFF7A3FC98E8C7 -:1024C0000F0007AD07C52B800023ADF81830236837 -:1024D0002046CDE904A9DB6B04A9984704F5805494 -:1024E00058B1D4F88C340133C4F88C3482E7012F0E -:1024F00004BFE36AC3F89C50DEE7D4F8903401339C -:10250000C4F89034012075E7F8B505460F4600F58C -:102510008054012639462846FFF750FF10B184F851 -:102520005364F7E7D4F8543423B1D4F89C3401331E -:10253000C4F89C34F8BD0000F0B5C36A1A6C12F4FC -:102540007F0F2BD000F580541B6CC4F8A03441F2EF -:102550006805002347194FF0010C00EB43122A4491 -:102560005E01117911F0020F15D0490713D4B95942 -:10257000C66AD6F8C8E00CFA01F111EA0E0F0AD0CB -:10258000C6F8D010117941F004011171D4F88824F3 -:102590000132C4F888240133202BDED1F0BD0000C5 -:1025A00010B5254C254B226802B338B31A6D1206BC -:1025B0000ED580221A6500F061F950EA01020B463F -:1025C00002D0013861F1000302462068FFF794FE53 -:1025D0001A4A136D1B032AD523684FF4002103F513 -:1025E00080531165012283F8592420E001221A65E5 -:1025F00008221A654FF480621A6510BD196DC8076C -:1026000002D4196D890705D50321196510460021EB -:10261000FFF77AFF094B1A6D100702D41A6DD10625 -:1026200005D518221A6520680121FFF76DFF206883 -:10263000BDE81040FFF780BFF03B00200064004081 -:1026400008B5FFF797FAFFF777FFBDE80840FFF7F7 -:1026500097BA0000C36AD3F8C40080F40010C0F336 -:102660004050704700F5805008B5FFF783FA406C82 -:10267000FFF762F9FFF784FA43090CBF012000203D -:1026800008BD000000F5805393F8592462B1C16A77 -:102690008A6922F001028A61D3F898240132C3F8D2 -:1026A0009824002283F85924704700002DE9F7434D -:1026B00000F5825198461031FFF75CFA002541F28F -:1026C000680E4FF0010900F5805C00EB451474447E -:1026D00023795E071CD4DB061AD5C36A8E69D3F84A -:1026E000C87009FA06F63E4212D04F6801970F688B -:1026F0009742019F77EB08070AD2C3F8D06023798D -:1027000043F004032371DCF884340133CCF88434BF -:102710000135202D01F12001D7D103B0BDE8F043F0 -:10272000FFF72EBAF8B51E46002313700F46054674 -:102730001446FFF797FF80F0010038701EB128465D -:10274000FFF788FF2070F8BD2DE9F04F85B099465E -:10275000DDE90EA30D4602931378019391F800B0C2 -:102760008046164600F08AF82B7804460F4613B9C7 -:102770003378002B42D022463B464046FFF796FF77 -:10278000FFF75EFFFFF77EFF4B4632462946FFF715 -:10279000C9FF2B7833B1BBF1000F03D0012005B086 -:1027A000BDE8F08F337813B1019B002BF6D108F50B -:1027B00080530393029B544577EB03031ED2039B84 -:1027C000D3F85404D0B10368AAEB0401DB6889B2E2 -:1027D00098474B46324629464046FFF7A3FF2B78E1 -:1027E00013B1BBF1000FD9D1337813B1019B002B8A -:1027F000D4D100F043F804460F46DBE70020CEE7D3 -:1028000008B50020FFF7CCFEBDE8084001F050B845 -:1028100008B50120FFF7C4FEBDE8084001F048B844 -:1028200000B59BB0EFF3098168226846FEF798FD7A -:10283000EFF30583014B9B6BFEE700BF00ED00E06B -:1028400008B5FFF7EDFF000000B59BB0EFF309817D -:1028500068226846FEF784FDEFF30583014B5B6B4E -:10286000FEE700BF00ED00E0FEE700000FB408B592 -:10287000029801F01BF9FEE701F00EBC01F0E6BB87 -:1028800013B56C4684E80600031D94E8030083E852 -:102890000500012002B010BD73B58568019155B1E6 -:1028A0001B885B0707D4D0E900369B6B9847019AD9 -:1028B000C1B23046A847012002B070BDF0B58668AD -:1028C00089B005460C465EB1BDF838305B070AD4C6 -:1028D000D0E900379B6B98472246C1B23846B047D3 -:1028E000012009B0F0BD00220023CDE90023002320 -:1028F000ADF808300A4603AB01F1080610685168CC -:102900001C4603C40832B2422346F7D11068206047 -:102910009288A280FFF7B2FF0423ADF808302B683D -:10292000CDE90001DB6B694628469847D8E70000EF -:10293000082817D909280CD00A280CD00B280CD04D -:102940000C280CD00D280CD00E2814BF40203020AD -:1029500070470C20704710207047142070471820D3 -:1029600070472020704700002DE9F041456A15B9F5 -:102970004162BDE8F0814B6823F06047C3F38A46AB -:102980004FEAD37EC3F3807816EA230638BF3E466B -:10299000AC462B465A68BEEBD27F22F060440AD088 -:1029A000002A18DAA40CB44217D19D420FD10D6051 -:1029B000DEE71346EEE7A74207D102F08044C2F3F8 -:1029C000807242450BD054B1EFE708D2EDE7CCF866 -:1029D00000100B60CDE7B44201D0B442E5D81A68CC -:1029E0009C46002AE5D11960C3E700002DE9F047B5 -:1029F000089D01F007044FEAD508224405F00705B9 -:102A000000EBD1004FF47F49944201D1BDE8F0873B -:102A100004F0070705F0070A57453E4638BF5646FB -:102A2000C6F10806111B8E4228BF0E46E10808EBCE -:102A3000D50E415C13F80EC0B94029FA06F721FA09 -:102A40000AF1FFB28CEA010147FA0AF739408CEA31 -:102A5000010C03F80EC034443544D5E780EA012068 -:102A6000082341F2210201B24000002980B203F1A3 -:102A7000FF33B8BF504013F0FF03F4D1704700009C -:102A800038B50C468D18A54200D138BD14F8011B8D -:102A9000FFF7E4FFF7E7000042684AB113684360BC -:102AA0004389818901339BB29942438138BF838135 -:102AB0001046704770B588B0202204460D4668461F -:102AC0000021FEF75FFC20460495FFF7E5FF024674 -:102AD00058B16B46054608AE1C4603CCB44228608C -:102AE0006960234605F10805F6D1104608B070BDAF -:102AF000082817D909280CD00A280CD00B280CD08C -:102B00000C280CD00D280CD00E2814BF40203020EB -:102B100070470C2070471020704714207047182011 -:102B20007047202070470000082817D90C280CD9BE -:102B300010280CD914280CD918280CD920280CD905 -:102B400030288CBF0F200E207047092070470A20C4 -:102B500070470B2070470C2070470D207047000015 -:102B60002DE9F843078C072F04461ED9D0E90298B7 -:102B700000254FF6FF73C5F12006A5F1200029FAC4 -:102B800005F108FA06F628FA00F031430143C9B20C -:102B90001846FFF763FF0835402D0346EBD1E16986 -:102BA0003A46BDE8F843FFF76BBF4FF6FF70BDE84C -:102BB000F883000010B54B6823B9CA8A63F3090291 -:102BC000CA8210BD04691A681C600361C38A013B94 -:102BD000C3824A60EFE700002DE9F84F1D46CB8A1B -:102BE0000F46C3F309010529814692460B4630D0B2 -:102BF0000020AAB207F11A049EB2042E1FFA80F830 -:102C00000FD8904503F1010306D3FB8A0A4462F30F -:102C10000903FB8201201AE01AF80060E654013033 -:102C2000EAE79045F1D2A1F1050B1C237C68BBFBC0 -:102C3000F3F203FB12BB1FFA8BF6002C45D148467A -:102C4000FFF72AFF044638B978606FF00200BDE84C -:102C5000F88F4FF00008E6E7002606607860ADB216 -:102C60004FF0000B454510D90AEB0803221D13F85D -:102C7000011B9155B1B208F101081B291FFA88F810 -:102C80002BD0454506F10106F1D8FB8AC3F30902B2 -:102C9000154465F30903BCE7013292B21C46236870 -:102CA000002BF9D16B1F0B441C21B3FBF1F3013353 -:102CB0009BB29A42D3D2BBF1000FD0D14846FFF766 -:102CC000EBFE20B9C4F800B0BFE70122E7E7C0F887 -:102CD00000B05E4620600446C1E74545D5D9484668 -:102CE000FFF7DAFE08B92060AFE7C0F800B00026B1 -:102CF00020600446B6E700002DE9F04F2DED028B71 -:102D00001C4683B05B69019207468846002B00F0A1 -:102D10009A80238C2BB1E269002A00F09480072B63 -:102D200035D807F10C00FFF7B7FE054638B96FF04C -:102D30000205284603B0BDEC028BBDE8F08F1422DB -:102D40000021FEF71FFB228CE16905F10800FEF768 -:102D500007FB208C013080B2FFF7E6FEFFF7C8FECC -:102D6000013880B22084013028746369228C1B787A -:102D70002A4403F01F0363F03F0348F0004113723D -:102D8000384669602946FFF7EFFD0125D1E700F1DC -:102D90000C034FF0000908EE103A4FF0800A4E463F -:102DA0004D4618EE100AFFF777FE83460028BED086 -:102DB00014220021FEF7E6FA002E3AD1019BABF86F -:102DC000083002220BF1080E1FFA82FC0CF1010000 -:102DD000BCF1060F218C80B201D88E422BD3FFF7B5 -:102DE000A3FEFFF785FE62691278013802F01F0228 -:102DF0008E4208BF4FF0400A42EA49121BFA80F1A6 -:102E00004AEA020A013048F0004281F808A08BF833 -:102E10001000CBF8042059463846FFF7A5FD238C57 -:102E20000135B3422DB289F001094FF0000AB8D143 -:102E30007FE70022C6E7E169895D0EF802100136DE -:102E4000B6B20132C0E76FF0010572E7F8B515467A -:102E50000E463022002104461F46FEF793FA069BD9 -:102E60006360B5F5001F079BA76034BF6A094FF682 -:102E7000FF72A36297B2E66104F1100000239A4248 -:102E800006D800230360A782E3822383E360F8BDB2 -:102E90000660013330462036F1E7000003781BB9A5 -:102EA0004BB2002BC8BF017070470000007870471C -:102EB000F8B50C46C969074611B9238C002B37D1E8 -:102EC000257E1F2D34D8387828BB228C072A2CD891 -:102ED000268A36F003032BD14FF6FF70FFF7D0FDA3 -:102EE00020F001003102400441EA0561400C41EA52 -:102EF00040254FF6FF72234629463846FFF7FCFE71 -:102F0000002807DD626913780133DBB21F2B88BF0D -:102F100000231370F8BD218A2D0645EA01250543DB -:102F20002046FFF71DFE0246E5E76FF00300F1E7DC -:102F30006FF00100EEE7000070B58AB00446164657 -:102F40000021282268461D46FEF71CFABDF83830DD -:102F5000ADF810300F9B05939DF840308DF8183078 -:102F6000119B07936946BDF84830ADF820302046E4 -:102F7000CDE90265FFF79CFF0AB070BD2DE9F04175 -:102F8000D36905460C4616460BB9138C5BBB377EDE -:102F90001F2F28D895F80080B8F1000F26D03046B2 -:102FA000FFF7DEFD3378210241EAC33141EA08012F -:102FB000338A41EA076141EA03410246334641F060 -:102FC00080012846FFF798FE00280ADD3378012BA0 -:102FD00007D1726913780133DBB21F2B88BF00233E -:102FE0001370BDE8F0816FF00100FAE76FF00300A5 -:102FF000F7E70000F0B58BB004460D4617460021F8 -:10300000282268461E46FEF7BDF99DF84C305A1E30 -:10301000534253418DF800309DF84030ADF81030E8 -:10302000119B05939DF848308DF81830149B079339 -:103030006A46BDF85430ADF8203029462046CDE927 -:103040000276FFF79BFF0BB0F0BD0000406A00B1B5 -:1030500004307047436A1A68426202691A60036169 -:10306000C38A013BC38270472DE9F041D0F820802C -:10307000194E14461D464146002709B9BDE8F081A6 -:10308000D1E90223A21A65EB0303964277EB03030F -:103090001ED2036A8B420DD1FFF78CFD036A1B68B9 -:1030A000036203690B60C38A0161016A013BC38249 -:1030B0008846E2E7FFF77EFD0B68C8F80030036939 -:1030C0000B60C38A0161013BC382D8F80010D4E7CA -:1030D00088460968D1E700BF80841E002DE9F04FC3 -:1030E0008BB00D46DDF8509014469B468046002874 -:1030F00000F01981B9F1000F00F01581531E3F2B2C -:1031000000F21181012A03D1BBF1000F40F00B81C5 -:103110000023CDE90833B8F81430B5EBC30F4FEAFC -:10312000C30703D300200BB0BDE8F08F2B199F42DB -:10313000D8F80C303ABF7F1BFFB227461BB9D8F82E -:103140001030002B7AD0272D4ED8C5F12806B74273 -:103150004FF000032CBFF6B23E4600932946D8F844 -:10316000080008AB3246FFF741FCA7EB060A3544DE -:103170005FFA8AFAB8F8143003F10053053BDB001C -:103180000493D8F80C3003932821039B13B1BAF1B0 -:10319000000F2CD1D8F8100040B1BAF1000F05D0C3 -:1031A000009608AB5246691AFFF720FC38B2002F90 -:1031B000B8D066070AD00AAB03EBD401624211F81B -:1031C000083C02F00702134101F8083C082C3CD9E6 -:1031D000102C40F2B580202C40F2B780BBF1000FDC -:1031E00000F09C80082334E0BA460026C2E7049B26 -:1031F000E02B28BFE02306930B44AB42059314D980 -:103200005A1B03980096924534BF5246D2B2691AAF -:1032100008AB04300792FFF7E9FB079A1644AAEBC4 -:10322000020A1544F6B25FFA8AFA049B069A0599D7 -:103230009B1A0493039B1B680393A6E70093D8F89B -:10324000080008AB3A462946AEE7BBF1000F13D0A1 -:103250000123B4EBC30F6CD0082C12D89DF820309A -:10326000621E23FA02F2D50706D54FF0FF3202FAAA -:1032700004F423438DF820309DF8203089F8003085 -:1032800051E7102C12D8BDF82030621E23FA02F24A -:10329000D10706D54FF0FF3202FA04F42343ADF80C -:1032A0002030BDF82030A9F800303CE7202C0FD8A2 -:1032B0000899631E21FA03F3DA0705D54FF0FF32B0 -:1032C00002FA04F40C430894089BC9F800302AE77A -:1032D000402C2BD0DDE90865611EC4F12102A4F168 -:1032E000210326FA01F105FA02F225FA03F311434C -:1032F0001943CB0712D50122A4F12003C4F1200108 -:1033000002FA03F322FA01F1A240524243EA010316 -:1033100063EB430332432B43CDE90823DDE9082364 -:10332000C9E90023FFE66FF00100FCE66FF008003A -:10333000F9E6082CA0D9102CB3D9202CEED8C3E77D -:10334000BBF1000FADD0022383E7BBF1000FBBD070 -:1033500004237EE730B5012A144638BF0124402CEF -:1033600085B028BF40240025012ACDE9025518D890 -:103370001B788DF8083063070AD004AB03EBD40543 -:10338000624215F8083C02F00702934005F8083C39 -:10339000009103462246002102A8FFF727FB05B053 -:1033A00030BD082AE4D9102A03D81B88ADF80830AC -:1033B000E1E7202A8DBFD3E900231B680293CDE902 -:1033C0000223D8E710B5CB681BB98B600B618B82E9 -:1033D00010BD04691A681C600361C38A013BC38283 -:1033E000CA60F0E703064CBFC0F3C030022070474C -:1033F00008B50246FFF7F6FF022806D15306C2F3CE -:103400000F2001D100F0030008BDC2F30740FBE725 -:103410002DE9F04F93B0CDE903230A680446104626 -:10342000FFF7E0FF022814BFC2F306260026002A99 -:103430000D46824680F2F28112F0C04940F0EE81E2 -:10344000097B002900F0EA81022803D02378B342E7 -:1034500040F0E781C2F304630693104602F07F0355 -:103460000593FFF7C5FF059B29444FEA834848EAC7 -:103470000A4848EA4668CE7800230022CDE90823AE -:10348000F309834648EA0008029367D0059B00933E -:1034900002466768534608A92046B847002800F04E -:1034A000C381276A4FB9414604F10C00FFF702FBC4 -:1034B000074690B96FF0020054E03B6998450DD083 -:1034C0003F68002FF9D1414604F10C00FFF7F2FAF2 -:1034D00007460028EED0236A3B60276297F817C0A2 -:1034E00006F01F08CCF3840CACEB08001FFA80FE3A -:1034F0000028B8BF0EF12000A8EB0C031FFA83FED2 -:10350000D7E90221B8BF00B2002B0793BEBF0EF16E -:1035100020031BB2079352EA010338D0039BDFF864 -:1035200024E39A1A049B4FF0000C63EB01019645CB -:103530007CEB01032BD36B7B97F81AE0734519D111 -:10354000029B002B78D0012821DC7868F8B9DFF8DD -:10355000F0C2944570EB010316D337E0276A27B910 -:103560006FF00C0013B0BDE8F08F3B699845B5D003 -:103570003F68F4E7B24890427CEB010301D300209E -:10358000F0E7029B002BFAD0079B0F2B17DCFA7D8C -:10359000B30002F0030203F07C031343FB753946CA -:1035A0002046FFF707FB6B7BBB76029B3BB9FB7D9D -:1035B000C3F38402013262F38603FB75D0E76A7BB2 -:1035C000BB7E9A42DBD1029B002B35D0B309022B84 -:1035D00032D0039BBB60049BFB60142200210DA82A -:1035E000FDF7D0FE039B0A93049B0B932B1D0C93BA -:1035F0002B7BADF83EB0013BDBB2ADF83C30069B17 -:103600008DF84230059B8DF8433094F82C308DF8BE -:1036100040A083F001038DF844308DF84180A36809 -:103620000AA920469847FB7DC3F38403013303F0C6 -:103630001F039B02FB82A2E7FB7DC6F34012B2EBA5 -:10364000D31F40F0F480C3F38403434540F0F2807D -:10365000029A2B7BB609002A4DD0F2075DD4032BCA -:1036600040F2EB80039BBB60049BFB602B7BAE1D99 -:10367000033BDBB23246394604F10C00FFF7ACFAEB -:1036800000280CDA39462046FFF794FAFB7DC3F395 -:103690008403013303F01F039B02FB820AE7DDE989 -:1036A0000884AB883B834FF6FF73C9F12000A9F172 -:1036B000200228FA09F104FA00F0014324FA02F288 -:1036C00011431846C9B2FFF7C9F909F10809B9F160 -:1036D000400F0346E9D1B8822A7B033AD2B2314681 -:1036E000FFF7CEF9FB7DB882DA43C2F3C01262F372 -:1036F000C713FB7543E786B92E1D013BDBB232468B -:10370000394604F10C00FFF767FA0028BADB2A7B80 -:10371000B88A013AD2B23146E2E7F98AC1F3090127 -:10372000013B0429DAB25BD8281D002307F11B06F0 -:103730009A4208D910F801CB06F801C001310133D3 -:103740000529DBB2F4D103990A9104990B919342B4 -:1037500007F11B010C9138BF043379680D9134BF18 -:1037600055FA83F300230E93FB8AADF83EB0C3F302 -:1037700009031A44069B8DF84230059B8DF84330AF -:1037800094F82C30ADF83C2083F001038DF84430E0 -:1037900000238DF840A08DF841807B602A7BB88A99 -:1037A000013A291DFFF76CF93B8BB882834203D1A4 -:1037B000A3680AA92046984720460AA9FFF702FEF7 -:1037C000FB7DBA8AC3F38403013303F01F039B021A -:1037D000FB823B8B9A420CBF00206FF01000C1E6C9 -:1037E0007B68002BAFD0052001E01C3033461E68FB -:1037F000002EFAD1091A081D2E1D184401EB090CE0 -:10380000BCF11B0F5FFA89F39DD89A429BD916F839 -:10381000013B00F8013B09F10109EFE76FF00900F6 -:10382000A0E66FF00A009DE66FF00B009AE66FF0DD -:103830000D0097E66FF00E0094E66FF00F0091E632 -:1038400040420F0080841E00EFF3098305494A6B54 -:1038500022F001024A63683383F30988002383F36B -:103860001188704700EF00E0302080F3118862B6C5 -:103870000C4B0D4AD96821F4E0610904090C0A4394 -:10388000DA60D3F8FC20094942F08072C3F8FC20CA -:103890000A6842F001020A602022DA7783F82200E7 -:1038A000704700BF00ED00E00003FA05001000E0E3 -:1038B00010B5302383F311880E4B5B6813F400635B -:1038C00014D0F1EE103AEFF30984683C4FF08073A6 -:1038D000E361094BDB6B236684F3098800F0A4F8ED -:1038E00010B1064BA36110BD054BFBE783F31188B4 -:1038F000F9E700BF00ED00E000EF00E0430600083C -:10390000460600084FF0E023002258684FF0FF31D0 -:10391000930003F1604303F5614301329042C3F821 -:103920008010C3F88011F3D27047000000F16043AB -:1039300003F561430901C9B283F80013012200F0C5 -:103940001F039A4043099B0003F1604303F5614361 -:10395000C3F880211A6070470023037582680369E9 -:103960001B6899689142FBD25A68036042601060FC -:103970005860704700230375826803691B68996863 -:103980009142FBD85A6803604260106058607047EB -:1039900008B50846302383F311880B7D032B05D02F -:1039A000042B0DD02BB983F3118808BD8B6900223D -:1039B0001A604FF0FF338361FFF7CEFF0023F2E779 -:1039C000D1E9003213605A60F3E70000FFF7C4BF8B -:1039D000054BD9680875186802681A60536001229F -:1039E0000275D860FCF718BE003C002030B50C4BC7 -:1039F000DD684B1C87B004460FD02B46094A684649 -:103A000000F050F92046FFF7E3FF009B13B1684632 -:103A100000F052F9A86907B030BDFFF7D9FFF9E708 -:103A2000003C002091390008044B1A68DB6890685C -:103A30009B68984294BF002001207047003C002002 -:103A4000084B10B51C68D86822681A6053600122C0 -:103A50002275DC60FFF78EFF01462046BDE810406E -:103A6000FCF7DABD003C0020044B1A68DB68926862 -:103A70009B689A4201D9FFF7E3BF7047003C0020E2 -:103A800038B5074C074908480123002523706560B5 -:103A900000F000FC0223237085F3118838BD00BFBD -:103AA000283E002028490008003C002008B572B6D6 -:103AB000044B186500F0B6FA00F06EFB024B0322CF -:103AC0001A70FEE7003C0020283E002000F02AB9D2 -:103AD000EFF3118020B9EFF30583302282F31188D0 -:103AE0007047000010B530B9EFF30584C4F3080443 -:103AF00014B180F3118810BDFFF7B6FF84F311886D -:103B0000F9E700008B60022308618B82084670474A -:103B10008368A3F1840243F8142C026943F8442C0F -:103B2000426943F8402C094A43F8242CC26843F800 -:103B3000182C022203F80C2C002203F80B2C044A48 -:103B400043F8102CA3F12000704700BF3106000895 -:103B5000003C002008B5FFF7DBFFBDE80840FFF799 -:103B600035BF0000024BDB6898610F20FFF730BFC4 -:103B7000003C0020302383F31188FFF7F3BF0000DF -:103B800008B50146302383F311880820FFF72EFF84 -:103B9000002383F3118808BD10B503689C68A24216 -:103BA0000CD85C688A600B604C6021605960996831 -:103BB0008A1A9A604FF0FF33836010BD1B68121B96 -:103BC000ECE700000A2938BF0A2170B504460D460B -:103BD0000A26601900F058FB00F044FB041BA542C4 -:103BE00003D8751C2E460446F3E70A2E04D9BDE817 -:103BF0007040012000F08EBB70BD0000F8B5144B82 -:103C00000D46D96103F1100141600A2A19698260E9 -:103C100038BF0A22016048601861A818144600F0F5 -:103C200025FB0A2700F01EFB431BA342064606D3D2 -:103C30007C1C281900F028FB27463546F2E70A2F9E -:103C400004D9BDE8F840012000F064BBF8BD00BF16 -:103C5000003C0020F8B506460D4600F003FB0F4A75 -:103C6000134653F8107F9F4206D12A46014630463C -:103C7000BDE8F840FFF7C2BFD169BB68441A2C19F0 -:103C800028BF2C46A34202D92946FFF79BFF2246B4 -:103C900031460348BDE8F840FFF77EBF003C0020F6 -:103CA000103C002010B4C0E9032300235DF8044B4E -:103CB0004361FFF7CFBF000010B5194C236998424C -:103CC0000DD0D0E90032816813605A609A680A44C6 -:103CD0009A60002303604FF0FF33A36110BD2346B9 -:103CE000026843F8102F53600022026022699A4252 -:103CF00003D1BDE8104000F0C1BA936881680B445D -:103D0000936000F0AFFA2269E1699268441AA24216 -:103D1000E4D91144BDE81040091AFFF753BF00BFB2 -:103D2000003C00202DE9F047DFF8BC8008F11007C7 -:103D30002C4ED8F8105000F095FAD8F81C40AA681C -:103D4000031B9A423ED81444D5E900324FF00009D3 -:103D5000C8F81C4013605A60C5F80090D8F81030BD -:103D6000B34201D100F08AFA89F31188D5E9033111 -:103D700028469847302383F311886B69002BD8D0ED -:103D800000F070FA6A69A0EB04094A4582460DD238 -:103D9000022000F0BFFA0022D8F81030B34208D158 -:103DA00051462846BDE8F047FFF728BF121A2244C3 -:103DB000F2E712EB090938BF4A4629463846FFF7B1 -:103DC000EBFEB5E7D8F81030B34208D01444211AFE -:103DD000C8F81C00A960BDE8F047FFF7F3BEBDE8D6 -:103DE000F08700BF103C0020003C002000207047FE -:103DF000FEE70000704700004FF0FF307047000002 -:103E0000BFF34F8F024A1369DB03FCD4704700BF36 -:103E10000020024008B5094B1B7873B9FFF7F0FF8B -:103E2000074B5A69002ABFBF064A9A6002F18832DE -:103E30009A601A6822F480621A6008BD403E002031 -:103E4000002002402301674508B50B4B1B7893B94E -:103E5000FFF7D6FF094B5A6942F000425A611A68CF -:103E600042F480521A601A6822F480521A601A686A -:103E700042F480621A6008BD403E002000200240EB -:103E80003F289ABF00F58030C00200207047000034 -:103E90004FF4006070470000402070473F2808B58D -:103EA0000BD8FFF7EDFF00F500630268013204D183 -:103EB00004308342F9D1012008BD0020FCE7000056 -:103EC0003F2810B504461FD8FFF79AFFFFF7A2FF5F -:103ED0000E4BF3221A6102225A615A6942EAC00269 -:103EE0005A615A6942F480325A61FFF789FF4FF4F0 -:103EF0000061FFF7C5FF00F04BF9FFF7A5FF204673 -:103F0000BDE81040FFF7CABF002010BD00200240EE -:103F10002DE9F84340EA020313F00703144606D0E4 -:103F2000304B40F231321A600020BDE8F88385182A -:103F30002D4A95420CD92B4A40F236311160F3E7F5 -:103F4000031D1B684A68934208D1083C08300831B9 -:103F5000072C14D902680B689A42F1D0FFF75AFF78 -:103F6000FFF74EFF214E08314FF001084FF00009D6 -:103F7000012CA1F1080706D8FFF766FF01E0002C2D -:103F8000ECD10120D1E7C6F81480054651F8083C71 -:103F900045F8043B51F8043C4360FFF731FF3369B7 -:103FA00043F001033361C6F81490026851F8083CED -:103FB0009A420CD00B4B40F25E321A600C4B1860E8 -:103FC0000C4B1C600C4B1F60FFF73EFFACE72D68ED -:103FD00051F8043C9D4201F10801EBD1083C083046 -:103FE000C6E700BF3C3E002000000208002002405F -:103FF000303E0020383E0020343E0020084908B5FD -:104000000B7828B11BB9FFF705FF01230B7008BD22 -:10401000002BFCD0BDE808400870FFF715BF00BFBB -:10402000403E002008B54FF4B0414FF0005000F082 -:10403000B1F8BDE808404FF420514FF0805000F037 -:10404000A9B80000084600F0E3BB000070B582B0DC -:10405000FFF73EFD0E4E054600F004F9326890422F -:1040600037BF0C4A0B49516814682EBFD1E9004193 -:10407000013151600419034641F1000128460191C4 -:104080003360FFF72FFD0199204602B070BD00BFDD -:10409000443E0020483E002070B582B0FFF718FD76 -:1040A000104E054600F0DEF83268904237BF0E4AE7 -:1040B0000D49516814682EBFD1E9004101315160AA -:1040C000041941F100010346284601913360FFF7CE -:1040D00009FD01994FF47A7200232046FCF788F815 -:1040E00002B070BD443E0020483E00200244D2B2DF -:1040F000904200D17047431C800000F1804000F5E1 -:104100001450006841F8040BD8B2F1E7124B10B517 -:10411000D3F89040240409D4D3F89040C3F89040D9 -:10412000D3F8904044F40044C3F890400B4C23680B -:10413000024443F480732360D2B2904200D110BD98 -:10414000431C800000F1804000F5145051F8044BEE -:104150000460D8B2F1E700BF0010024000700040D8 -:1041600007B5012201A90020FFF7C0FF019803B0A5 -:104170005DF804FB13B50446FFF7F2FFA04205D03B -:10418000012201A900200194FFF7C0FF02B010BD79 -:10419000704700007047000070470000074B45F271 -:1041A00055521A6002225A6040F6FF729A604CF62D -:1041B000CC421A60024B01221A7070470030004056 -:1041C000543E0020034B1B781BB1034B4AF6AA2236 -:1041D0001A607047543E002000300040054B1A68BA -:1041E00032B902F1804202F50432D2F894201A600A -:1041F000704700BF503E0020024B4FF40002C3F84E -:10420000942070470010024008B5FFF7E7FF024B0B -:104210001868C0F3407008BD503E00207047000091 -:10422000FEE700000A4B0B480B4A90420BD30B4BA6 -:10423000DA1C121AC11E22F003028B4238BF002280 -:104240000021FDF79FB853F8041B40F8041BECE76E -:104250008C4A0008D83E0020D83E0020D83E0020DE -:1042600000F0C2B84FF08043586A70474FF0804367 -:10427000002258631A610222DA6070474FF08043CF -:104280000022DA60704700004FF0804358637047A7 -:10429000FEE7000070B51B4B01630025044686B0A5 -:1042A000586085620E46FFF7DFFA04F11003C4E997 -:1042B00004334FF0FF33C4E90635C4E90044A56078 -:1042C000E562FFF7CFFF2B460246C4E9082304F15D -:1042D00034010D4A256580232046FFF713FC012396 -:1042E000E0600A4A0375009272680192B268CDE9F3 -:1042F0000223074B6846CDE90435FFF72BFC06B0D7 -:1043000070BD00BF283E002034490008394900082C -:1043100091420008024AD36A1843D062704700BF36 -:10432000003C00204B6843608B688360CB68C360AF -:104330000B6943614B6903628B6943620B680360DD -:104340007047000008B5204BDA6A42F07F02DA625B -:10435000DA6A22F07F02DA62DA6ADA6C42F07F020D -:10436000DA64DA6E42F07F02DA66184ADB6E1146D2 -:104370004FF09040FFF7D6FF02F11C0100F580607E -:10438000FFF7D0FF02F1380100F58060FFF7CAFFA8 -:1043900002F1540100F58060FFF7C4FF02F17001E3 -:1043A00000F58060FFF7BEFF02F18C0100F5806030 -:1043B000FFF7B8FF02F1A80100F58060FFF7B2FF38 -:1043C000BDE8084000F050B8001002404049000825 -:1043D00008B500F0EDF9FFF753FBBDE80840FFF723 -:1043E000FDBE0000704700000F4B9A6D42F00102C5 -:1043F0009A659A6F42F001029A670C4A9B6F936824 -:1044000043F0010393604FF08043A7229A624FF07C -:10441000FF32DA6200229A615A63DA605A6001223E -:104420005A611A60704700BF00100240002004E08B -:104430004FF0804208B51169D3680B40D9B2C94327 -:104440009B07116107D5302383F31188FFF73EFBEB -:10445000002383F3118808BD08B5FFF753FABDE8C0 -:10446000084000F081B900004E4B4FF0FF319A6ACE -:1044700099629A6A00229A62986AD86A60F07F000C -:10448000D862D86A00F07F00D862D86A186B1963C6 -:10449000186B1A63186B986B9963986B9A63986B97 -:1044A000D86BD963D86BDA63D86B186C1964196C44 -:1044B0001A64196C196E41F001011966D3F8801065 -:1044C00021F00101C3F88010D3F88010996D41F0FC -:1044D00080519965996F21F080519967996F3249A0 -:1044E0004FF400408860CA600A624A628A62CA6207 -:1044F0000A634A638A63CA630A644A648A64CA6450 -:104500000A654A654A604FF48072C1F880204FF412 -:1045100040720A604A6912F48062FBD1D3F89010AD -:1045200011F4407F1EBF4FF48031C3F89010C3F8E0 -:104530009020D3F8982042F00102C3F89820D3F8D5 -:1045400098209207FBD51A6842F480321A601A68E4 -:104550009003FCD5D3F8902022F00322C3F89020DA -:10456000124ADA601A6842F080721A601A68910181 -:10457000FCD50F490F4800229A60C3F888100E49F5 -:10458000C3F89C20016002684A401207FBD19A6878 -:1045900042F003029A609A6802F00C020C2AFAD1E7 -:1045A000704700BF0010024000700040232A6101E4 -:1045B000550100500020024004070400074A08B5D6 -:1045C000536903F00103536123B1054A13680BB12A -:1045D00050689847BDE80840FFF76AB900040140F9 -:1045E000583E0020074A08B5536903F0020353619F -:1045F00023B1054A93680BB1D0689847BDE80840DD -:10460000FFF756B900040140583E0020074A08B59C -:10461000536903F00403536123B1054A13690BB1D5 -:1046200050699847BDE80840FFF742B900040140CF -:10463000583E0020074A08B5536903F00803536148 -:1046400023B1054A93690BB1D0699847BDE808408A -:10465000FFF72EB900040140583E0020074A08B574 -:10466000536903F01003536123B1054A136A0BB178 -:10467000506A9847BDE80840FFF71AB900040140A6 -:10468000583E0020164B10B55C6904F478725A61EC -:10469000A30604D5134A936A0BB1D06A9847600603 -:1046A00004D5104A136B0BB1506B9847210604D503 -:1046B0000C4A936B0BB1D06B9847E20504D5094ABD -:1046C000136C0BB1506C9847A30504D5054A936C45 -:1046D0000BB1D06C9847BDE81040FFF7E9B800BFB8 -:1046E00000040140583E0020194B10B55C6904F4E9 -:1046F0007C425A61620504D5164A136D0BB1506DA8 -:104700009847230504D5134A936D0BB1D06D984794 -:10471000E00404D50F4A136E0BB1506E9847A10404 -:1047200004D50C4A936E0BB1D06E9847620404D541 -:10473000084A136F0BB1506F9847230404D5054AFC -:10474000936F0BB1D06F9847BDE81040FFF7B0B83A -:1047500000040140583E002008B5FFF769FEBDE89F -:104760000840FFF7A5B80000062108B50846FFF786 -:10477000DDF806210720FFF7D9F806210820FFF70A -:10478000D5F806210920FFF7D1F806210A20FFF706 -:10479000CDF806211720FFF7C9F806212820FFF7DA -:1047A000C5F8BDE8084007211C20FFF7BFB800008E -:1047B00008B5FFF751FE00F007F8FFF713FEBDE85C -:1047C0000840FFF74DBD00000023054A194601339C -:1047D000102BC2E9001102F10802F8D1704700BFA6 -:1047E000583E00200B460146184600F003B8000072 -:1047F00000F00EB810B5054C13462CB10A46014620 -:104800000220AFF3008010BD2046FCE7000000004E -:10481000024B01461868FFF715BC00BF18110020B5 -:1048200010B501390244904201D1002005E003781F -:1048300011F8014FA34201D0181B10BD0130F2E75F -:104840002DE9F041A3B1C91A17780144044603F1D8 -:10485000FF3C8C42204601D9002009E00578BD428A -:1048600004F10104F5D10CEB0405D618A54201D1E1 -:10487000BDE8F08115F8018D16F801EDF045F5D091 -:10488000E7E70000034611F8012B03F8012B002A8B -:10489000F9D170476F72672E6172647570696C6FC1 -:1048A000742E48697465632D41697273706565641F -:1048B0000000000040A2E4F1646891060041A3E515 -:1048C000F2656992070000004261642043414E494D -:1048D0006661636520696E6465782E0000000000E3 -:1048E000000000008D200008951B000849270008E3 -:1048F0008D1B00083D1C0008211E0008051C000837 -:10490000CD1B0008D11B0008A91B0008911B000843 -:10491000E11D0008B51B000881280008C11B000824 -:10492000B51D00086330000024490008583C0020F1 -:10493000283E00206D61696E0069646C65000000AE -:104940000010802A00000000AAAAAAAA00000024E1 -:10495000BFFF0000000000000090090000000001FF -:1049600000000000AAAAAAAA00000001FFFF0000A0 -:104970000000000000000000000000000000000037 -:10498000AAAAAAAA00000000FFFF00000000000081 -:10499000000000000000000000000000AAAAAAAA6F -:1049A00000000000FFFF0000000000000000000009 -:1049B0000000000000000000AAAAAAAA000000004F -:1049C000FFFF0000000000000000000000000000E9 -:1049D00000000000AAAAAAAA00000000FFFF000031 -:1049E00000000000000000000000000000000000C7 -:1049F000AAAAAAAA00000000FFFF00000000000011 -:104A0000000000001CB8FF7F010000000000000053 -:104A100016040000000000000098010000000000E3 -:104A2000FE2A0100D20400001C110020000000003A -:104A30000000000000000000000000000000000076 -:104A40000000000000000000000000000000000066 -:104A50000000000000000000000000000000000056 -:104A60000000000000000000000000000000000046 -:104A70000000000000000000000000000000000036 -:0C4A80000000000000000000000000002A +:1000000000090020F1010008E52500089D250008F1 +:10001000C52500089D250008BD250008F30100083E +:10002000F3010008F3010008F3010008C5350008DA +:10003000F3010008F3010008F3010008F3010008D0 +:10004000F3010008F3010008F3010008F3010008C0 +:10005000F3010008F3010008B9380008E13800088E +:10006000093900083139000859390008F30100083E +:10007000F3010008F3010008F3010008F301000890 +:10008000F3010008F3010008F3010008F301000880 +:10009000F30100087D2500088D250008813900083E +:1000A000F3010008F3010008F3010008F301000860 +:1000B000553A0008F3010008F3010008F3010008B5 +:1000C000F3010008F3010008F3010008F301000840 +:1000D000F3010008F3010008F3010008F301000830 +:1000E000E5390008F3010008F3010008F3010008F6 +:1000F000F3010008F3010008F3010008F301000810 +:10010000F3010008F3010008F3010008F3010008FF +:10011000F3010008F3010008F3010008F3010008EF +:10012000F3010008F3010008F3010008F3010008DF +:10013000F3010008F3010008F3010008F3010008CF +:10014000F3010008F3010008F3010008F3010008BF +:10015000F3010008F3010008F3010008F3010008AF +:10016000F3010008F3010008F3010008F30100089F +:10017000F3010008F3010008F3010008F30100088F +:10018000F3010008F3010008F3010008F30100087F +:10019000F3010008F3010008F3010008F30100086F +:1001A000F3010008F3010008F3010008F30100085F +:1001B000F3010008F3010008F3010008F30100084F +:1001C000F3010008F3010008F3010008F30100083F +:1001D000F3010008F3010008F3010008F30100082F +:1001E000650F000800000000000000000000000093 +:1001F00002E000F000F8FEE772B6374880F30888A6 +:10020000364880F3098836483649086040F20000D5 +:10021000CCF200004EF63471CEF200010860BFF35C +:100220004F8FBFF36F8F40F20000C0F2F0004EF628 +:100230008851CEF200010860BFF34F8FBFF36F8F7C +:100240004FF00000E1EE100A4EF63C71CEF20001D4 +:100250000860062080F31488BFF36F8F04F092F8D3 +:1002600004F072F94FF055301F491B4A91423CBFD0 +:1002700041F8040BFAE71D49184A91423CBF41F886 +:10028000040BFAE71A491B4A1B4B9A423EBF51F82E +:10029000040B42F8040BF8E700201849184A914271 +:1002A0003CBF41F8040BFAE704F070F804F092F94F +:1002B000144C154DAC4203DA54F8041B8847F9E797 +:1002C00000F042F8114C124DAC4203DA54F8041B12 +:1002D0008847F9E704F058B8000900200011002011 +:1002E0000000000808ED00E00001002000090020E7 +:1002F0007048000800110020A4110020A81100205F +:10030000043F0020E0010008E4010008E4010008C7 +:10031000E40100082DE9F04F2DED108AC1F80CD052 +:10032000C3689D46BDEC108ABDE8F08F002383F3BF +:1003300011882846A047002003F0CAFCFEE703F01E +:1003400053FC00DFFEE70000F8B500F01DFE03F0EF +:10035000BBFF074604F00CF80646C0BB274B9F4284 +:1003600035D001339F4235D0254B27F0FF029A420A +:1003700033D1F8B200F040FC354642F2107400F080 +:1003800041FC08B10024254601F0B4F848B303202D +:1003900000F03AF80024254636B11A4B9F4203D0AC +:1003A00003F0DEFF00242546002003F097FF0DB187 +:1003B00000F040F800F058FC02F01CF90546ACB91A +:1003C00000F09AFC4FF47A7003F088FCF7E73546AA +:1003D0000024D4E704460125D1E705464FF47A749A +:1003E000CDE7B4F57A7F08BF0125D5E702F002F921 +:1003F000431BA342E4D900F01DF8DDE7010007B07C +:10040000000008B0263A09B0084B187003280CD831 +:10041000DFE800F008050208022000F011BE02200B +:1004200000F006BE024B00225A607047A81100205F +:10043000AC11002038B501F05DF830B1254B032236 +:100440001A70254B00225A6038BD244B244A196883 +:100450000131F9D004339342F9D1224C1F4DD4F825 +:100460000428AA42F0D3204B9B6803F1006303F5F4 +:10047000D0439A42E8D203F045FF03F057FF002033 +:1004800000F09CFD0220FFF7BFFF184B9A6D002281 +:100490009A65996F9A67996FD96DDA65D96FDA673E +:1004A000D96F196E1A66D3F88010C3F88020D3F87C +:1004B000803072B64FF0E0233021C3F8085DD4F8E5 +:1004C0000038D4F8042881F311889D4683F3088806 +:1004D0001047B9E7A8110020AC11002000680008FF +:1004E0002068000800600008001100200010024091 +:1004F000094A136849F2690099B21B0C00FB0133E9 +:100500001360064B186844F2506182B2000C01FB84 +:100510000200186080B270471411002010110020F2 +:1005200010B500211022044600F0A4FD034B03CBBC +:10053000206061601868A06010BD00BF9075FF1F4B +:100540002DE9F041ADF5507D0DF13C086EAC40F267 +:10055000751207460D4610A80021C8F8001000F0DB +:1005600089FD4FF4C4720021204600F083FD02F0A3 +:1005700041F8254B4FF47A72B0FBF2F0186093E823 +:100580000700022384E807000DF5ED702382FFF7D2 +:10059000C7FF41F204631D49238407A804F082F8D1 +:1005A0001C2384F832310DF2EB226B440DF1340C34 +:1005B0001E4603CE664510605160334602F10802C4 +:1005C000F6D13068106041460122204600F09EFDC1 +:1005D00000230393AB7E029305F11903019380B2CC +:1005E0000123CDE904800093E97E05A3D3E900232C +:1005F000384602F0BDFB0DF5507DBDE8F08100BF2F +:100600009E6AC421818A46EEB4110020B4460008D7 +:100610002DE9F0412C4C237ADAB080460D465BBBC5 +:1006200027A9284600F082FE0746002842D19DF8FF +:100630009D60C82E3ED801464FF4A662204600F0C9 +:1006400019FD4FF48073C4F8F8314FF40073C4F807 +:100650000C334FF44073C4F8203432460DF19E0140 +:1006600004F1090000F0F4FC26449DF89C307772F8 +:1006700023720BB9EB7E23728122002106AC27A8DE +:1006800000F0F8FC0122214627A800F08BFE002391 +:100690000393AB7E029305F1190380B201932823E3 +:1006A000CDE904400093E97E05A3D3E90023404649 +:1006B00002F05EFB5AB0BDE8F08100BFAFF30080EE +:1006C00026417272DF25D7B7C0360020F0B5254E1F +:1006D0004FF48A7505FB0065F1B096F8D83085F8BF +:1006E000DC300024D822214685F8E8403AA800F002 +:1006F000C1FC06F1090000F0B5FCD5F8E4308DF836 +:10070000F000C2B206AF06F109010DF1F100CDE92A +:100710003A3400F09DFC394601223AA800F06EFE02 +:1007200080B2CDE9047008230127CDE9023706F134 +:10073000D803019330230093317A0B4807A3D3E900 +:10074000002302F015FBA04206DD01F053FFC5F8BF +:10075000E000384671B0F0BD2046FBE778F6339FE5 +:1007600093CACD8DC0360020CC2100202DE9F04168 +:100770001D4D1E4E1E4F86B0284602F025FB034637 +:1007800058B30024CDE90344ADF81440027B8DF842 +:10079000142099684068029403AA03C21B68DFF81A +:1007A000548043F00043029301F026FF821941F187 +:1007B0000003009402A9384601F0B0F8A04205DD1C +:1007C000284602F005FB88F80040D5E798F800308D +:1007D000072B05D8013388F8003006B0BDE8F0815A +:1007E000014802F0F5FAF8E7CC21002040420F0062 +:1007F00000220020F53B002070B50D4614461E4631 +:1008000002F012FA50B9022E10D1012C0ED112A30F +:10081000D3E90023C5E90023012007E0282C10D0EC +:1008200005D8012C09D0052C0FD0002070BD302C2C +:10083000FBD10BA3D3E90023ECE70BA3D3E90023FF +:10084000E8E70BA3D3E90023E4E70BA3D3E90023F4 +:10085000E0E700BFAFF30080401DA12026812A0BF6 +:1008600078F6339F93CACD8D9E6AC421818A46EE65 +:1008700026417272DF25D7B7F017304A39059E56E8 +:1008800038B505460E4C0021013500F0B9FBA4F83F +:100890002C55B4F82C0500F09BFB78B1B4F82C056E +:1008A00000F0A6FB014648B9B4F82C0500F0A8FBFF +:1008B000B4F82C350133A4F82C35EAE738BD00BF75 +:1008C000C036002010B50A4B0A4A1A6003F580535F +:1008D00093F848203AB95C6C2CB1204600F088FEB1 +:1008E000204603F095FEBDE81040034800F080BEAE +:1008F0000022002004470008303200202DE9F04F8C +:100900008FB000AF05460C4602F08EF9002849D1A1 +:10091000237E022B1BD1E38A012B18D101F06AFE42 +:100920000646FFF7E5FD03464FF4C870DFF8C482C2 +:10093000B3FBF0F206F5167602FB103316FA83F3DA +:10094000C8F80030E37E33B9A34B00221A703C375D +:10095000BD46BDE8F08F07F12401204600F0A4FC5D +:100960000028F4D107F11400FFF7DAFD97F82640CC +:1009700007F11401224607F1270003F061FE002869 +:10098000E2D10F2C08D8944B1C70D8F80030A3F596 +:100990001673C8F80030DAE797F82410284602F0FA +:1009A0003BF9D4E7E38A282B2BD010D8012B23D096 +:1009B000052BCCD1BFF34F8F8849894BCA6802F40D +:1009C000E0621343CB60BFF34F8F00BFFDE7302BD6 +:1009D000BDD1844EE17E327A9142B8D1607E3146FB +:1009E000002291F8DC50854200F0A5800132042AF3 +:1009F00001F58A71F5D1AAE721462846FFF7A0FD47 +:100A0000A5E721462846FFF703FEA0E7B2F8EC5021 +:100A10007B6005F103094FEA99094FEA8902D11D6C +:100A2000C908A8EBC1039D46EB460021584600F0DB +:100A300021FB04F1EE012A463144584600F008FB40 +:100A40007B6813B9012000F0B9FA96F8D20000F0E3 +:100A5000BFFA044630B9307200F0DAFA204600F0EE +:100A6000ADFAB1E0D6F8D4203AB996F8D200B6F88B +:100A70002C25824201D8FFF703FFD6F8D4202A4460 +:100A8000944208D296F8D200B6F82C250130824262 +:100A900001D8FFF7F5FE70685FFA89F2594600F059 +:100AA000F1FA08B9C54679E0726896F8D2002A448E +:100AB0007260D6F8D42005EB0209C6F8D49000F095 +:100AC00087FA814509D396F8D220D6F8D4000132AE +:100AD000001B86F8D220C6F8D400FF2D0FD80024C2 +:100AE000347200F095FA204600F068FA00F002FD3A +:100AF0003D4B188108B9FFF79DFCC54627E7BB6849 +:100B000096F8D9000AFB0362FB68D2F8E41082F879 +:100B1000E83001F58061C2F8E030C2F8E410FFF778 +:100B2000D5FDFFF723FE96F8D920013202F003022B +:100B300086F8D920B6E74FF48A7A0AFB02F505F168 +:100B4000EA013144204600F085FCF86000287FF47B +:100B5000FEAE3544012285F8E82001F04BFDD5F8C2 +:100B6000E020D6ED007ADFED216A801A192838BF1F +:100B7000192040F6B832904228BF1046B8EE677A86 +:100B800007EE900AF8EEE77A67EEA67ADFED186ACC +:100B9000E7EE267AFCEEE77AC6ED007A96F8D930D1 +:100BA000BB60BA6873680AFB02F4321992F8E81065 +:100BB00059B1D2F8E4108B42E8463FF427AF002148 +:100BC00082F8E810C2F8E010C5467368064A9B0A2E +:100BD00001331381BBE600BFC521002000ED00E01A +:100BE0000400FA05C0360020B4110020CDCCCC3D65 +:100BF0006666663FC8210020014B1870704700BF31 +:100C0000C011002038B54FF00054134B22689A42AF +:100C100020D1124B627D12481A70237D03724FF46B +:100C20008073C0F8F8314FF40073C0F80C3300251E +:100C30004FF44073C0F820340A49C0F8E450C92288 +:100C4000093000F005FAE0222946204600F012FAA9 +:100C5000012038BD0020FCE79AAD44C5C01100203A +:100C6000C03600201600002037B500F043FC194DB7 +:100C70001949288102236B7100220123174801F0D2 +:100C800097F800230193164B164900931648174B0B +:100C90004FF4805201F098FF154B197811B11248AA +:100CA00001F0BAFF01F0A6FC0446FFF721FC4FF467 +:100CB000C873B0FBF3F202FB130304F5167010FACD +:100CC00083F00C4B186003F053FB08B10F232B810A +:100CD00003B030BDB411002040420F0000220020BC +:100CE000F9070008C4110020CC210020FD080008ED +:100CF000C0110020C82100202DE9F04F2DED028BFE +:100D000090A7D7E900670FF24429D9E90089884CF8 +:100D100095B00DAD9FED848BFFF728FDDFF834B261 +:100D200000230C93ADF83C300D936B6000230DF164 +:100D300025028DED008B4FF0010A09A958468DF868 +:100D400025308DF824A001F0BDFB9DF82420002360 +:100D5000002A40F0AF80204601F066FF05460028DB +:100D600047D1DFF8F4B101F045FCDBF800309842E0 +:100D70003FD301F03FFC0790FFF7BAFB079A4FF40F +:100D8000C873B0FBF3F101FB130302F5167010FA00 +:100D900083F0CBF80000DFF8C4B19BF80010079196 +:100DA000002914BF2B46534610A88DF83030FFF7AA +:100DB000B7FB0799C1F11002D2B2062A10AB28BFC7 +:100DC000062219440DF13100079200F041F9079A0B +:100DD0000CAB0393182302930132564BD2B2CDE9E8 +:100DE00000A304923B463246204601F063FF8BF895 +:100DF000005001F0FFFB504A504D1368C31AB3F581 +:100E00007A7F32D3106001F0F7FB02460B46204692 +:100E100001F0E8FF204601F007FF30B32B7ADFF83E +:100E200040A1002B14BF032302238AF8053001F0F0 +:100E3000E1FB0DF1400B4FF47A730122B0FBF3F0AC +:100E40005946CAF80000504600F006FA18230293EB +:100E50003B4B019380B240F25513CDE903B00093B0 +:100E600042464B46204601F025FF2B7AB3B101F0F4 +:100E7000C1FB4FF0000A83464FF48A7295F8D900FF +:100E8000504400F0030002FB005393F8E8100029DF +:100E900034D00AF1010ABAF1040FEFD1C82002F0F0 +:100EA0001DFF2B7A002B7FF434AF15B0BDEC028B05 +:100EB000BDE8F08F4FF0904110A84A6982F04002DF +:100EC0004A611946102200F0D5F80DF126030AAA4E +:100ED0000CA9584600F016FE95E8030011AB83E814 +:100EE00003009DF83C308DF84C300C9B109310A9FA +:100EF000DDE90A23204602F049F917E7D3F8E010AC +:100F000049B12B68FA2B38BFFA23ABEB010105334B +:100F1000B1EB430FBDD3FFF7D9FB4FF48A72002822 +:100F2000B7D1BBE7AFF30080000000000000000075 +:100F3000CC210020C4210020F03B0020C03600203E +:100F4000F43B0020401DA12026812A0BF1C6A7C139 +:100F5000D068080F00220020C8210020C5210020F1 +:100F6000B411002008B5054800F072FEBDE8084045 +:100F7000034A0449002003F045BB00BF00220020C3 +:100F8000303C0020C508000870B503F043F8094E56 +:100F9000094D3080002428683388834208D903F043 +:100FA00035F82B6804440133B4F5D04F2B60F2D3ED +:100FB00070BD00BF243C0020F83B002003F0DCB8EB +:100FC00000F10060920000F5D04003F05FB800002F +:100FD000054B1A68054B1B889B1A834202D91044A3 +:100FE00003F014B800207047F83B0020243C002098 +:100FF000024B1B68184403F00FB800BFF83B0020F9 +:10100000024B1B68184403F019B800BFF83B0020DE +:10101000064991F8243033B10023086A81F824305E +:101020000822FFF7CDBF0120704700BFFC3B002026 +:10103000022802BF4FF0904340229A61704700009F +:10104000022802BF4FF090434FF480029A6170472C +:1010500010B50023934203D0CC5CC4540133F9E7AC +:1010600010BD000003460246D01A12F9011B0029E8 +:10107000FAD1704702440346934202D003F8011BA1 +:10108000FAE770472DE9F8431F4D144695F82420E0 +:101090000746884652BBDFF870909CB395F8243021 +:1010A0002BB92022FF2148462F62FFF7E3FF95F876 +:1010B0002400C0F10802A24228BF2246D6B241460F +:1010C000920005EB8000FFF7C3FF95F82430A41BC6 +:1010D0001E44F6B2082E17449044E4B285F824600A +:1010E000DBD1FFF795FF0028D7D108E02B6A03EB8F +:1010F00082038342CFD0FFF78BFF0028CBD10020A3 +:10110000BDE8F8830120FBE7FC3B00202DE9F04718 +:101110000D46044600219046284640F27912FFF71A +:10112000A9FF234620220021284601F0D1FF231DDC +:1011300002222021284601F0CBFF631D0322222139 +:10114000284601F0C5FFA31D03222521284601F0F2 +:10115000BFFF04F1080310222821284601F0B8FF40 +:1011600004F1100308223821284601F0B1FF04F1F0 +:10117000110308224021284601F0AAFF04F11203BE +:1011800008224821284601F0A3FF04F1140320227D +:101190005021284601F09CFF04F1180340227021E1 +:1011A000284601F095FF04F120030822B0212846CB +:1011B00001F08EFF04F121030822B821284601F036 +:1011C00087FF04F12207C0263B4631460822284605 +:1011D000083601F07DFFB6F5A07F07F10107F3D1D6 +:1011E00004F1320308223146284601F071FF00273E +:1011F00004F1330A94F832304FEAC7099F4209F5E7 +:10120000A47615D3B8F1000F08D1314604F59973CF +:101210000722284601F05CFF09F24F16274694F892 +:1012200032213B1B93420CD3F01DC008BDE8F08770 +:101230000AEB070308223146284601F049FF01372F +:10124000D8E707F2331331460822284601F040FF61 +:1012500008360137E3E7000013B5044608460021CD +:1012600001602346C0F803102022019001F030FFF6 +:101270000198231D0222202101F02AFF0198631DFD +:101280000322222101F024FF0198A31D032225211E +:1012900001F01EFF019804F108031022282101F03B +:1012A00017FF072002B010BDF7B50023047F00919F +:1012B0000E4607221946054601F0CEFD731C009329 +:1012C000012200230721284601F0C6FDC4B9B31C42 +:1012D0000093052223460821284601F0BDFD0D2478 +:1012E0003746B278BB1B934211D32B7FA88A0734B1 +:1012F000E408BBB9844294BF0020012003B0F0BDD4 +:10130000AB8ADB00083BDB08B3700824E8E7FB1C72 +:101310000093214600230822284601F09DFD083451 +:101320000137DEE7201A18BF0120E7E7F7B50023F1 +:10133000047F00910E4608221946054601F08CFDF7 +:10134000731CC4B90822009311462346284601F0B5 +:1013500083FD1024012372785F1C013B934211D35B +:101360002B7FA88A0734E408BBB9844294BF0020CD +:10137000012003B0F0BDAB8ADB00083BDB087370D3 +:101380000824E7E7F31900932146002308222846A2 +:1013900001F062FD08343B46DDE7201A18BF01204A +:1013A000E7E70000F8B50E46054614460021812205 +:1013B0003046FFF75FFE2B4608220021304601F041 +:1013C00087FE7CB96B1C07220821304601F080FEA5 +:1013D0000F2401236A785F1C013B934204D3E01D74 +:1013E000C008F8BD0824F4E7EB192146082230466E +:1013F00001F06EFE08343B46ECE70000F8B50E46FF +:10140000054614460021CE223046FFF733FE2B4618 +:1014100028220021304601F05BFE7CB905F108036B +:1014200008222821304601F053FE30242F462A7A24 +:101430007B1B934204D3E01DC008F8BD2824F5E7C8 +:1014400007F1090321460822304601F041FE083425 +:101450000137ECE7F7B5047F00910E460123102217 +:101460000021054601F0F8FCC4B9B31C0093092221 +:1014700023461021284601F0EFFC192437467288D4 +:10148000BB1B9A4211D82B7FA88A0734E408BBB94A +:10149000844294BF0020012003B0F0BDAB8ADB0082 +:1014A000103BDB0873801024E8E73B1D00932146C6 +:1014B00000230822284601F0CFFC08340137DEE77C +:1014C000201A18BF0120E7E730B5094D0A449142C0 +:1014D0000DD011F8013B5840082340F30004013BB4 +:1014E0002C4013F0FF0384EA5000F6D1EFE730BD43 +:1014F0002083B8EDF7B5384A106851686B4603C3CE +:101500006A4636493648082303F0AAF804460028FC +:1015100033D10A25334A106851686B4603C36A46C3 +:1015200031492F48082303F09BF80446002849D08E +:101530000369B3F5CC3F45D8B0F8661040F21642C7 +:1015400091423FD1294A024402F15C018B4239D3D6 +:101550005C3B234900209E1AFFF7B6FF3246074640 +:1015600004F164010020FFF7AFFFA3689F4229D177 +:10157000E368984208BF002524E00369B3F5CC3F37 +:1015800027D8418B40F21642914220D1174A02449B +:1015900002F110018B4218D3103B114900209D1A13 +:1015A000FFF792FF2A46064604F118010020FFF7D4 +:1015B0008BFFA3689E4202D1E368984201D00D25BB +:1015C000A8E70025284603B0F0BD1025A2E70C25AA +:1015D000A0E70B259EE700BFD4460008DC9701007A +:1015E00000680008DD460008909701000898FFF7A2 +:1015F00010B5037C044613B9006803F019F82046BF +:1016000010BD00000023BFF35B8FC360BFF35B8F8F +:10161000BFF35B8F8360BFF35B8F7047BFF35B8F5C +:101620000068BFF35B8F704770B505460C30FFF75D +:10163000F5FF05F1080604463046FFF7EFFFA0422C +:1016400006D930466D68FFF7E9FF2544281A70BDBA +:101650003046FFF7E3FF201AF9E7000070B50546B2 +:10166000406898B105F10800FFF7D8FF05F10C06B6 +:1016700004463046FFF7D2FF8442304694BF6D687F +:101680000025FFF7CBFF013C2C44201A70BD000061 +:1016900038B50C460546FFF7C7FFA04210D305F149 +:1016A0000800FFF7BBFF04446868B4FBF0F100FBDF +:1016B0001144BFF35B8F0120AC60BFF35B8F38BD7B +:1016C0000020FCE72DE9F041144607460D46FFF7E0 +:1016D000C5FF844228BF0446D4B1B84658F80C6B05 +:1016E0004046FFF79BFF3044286040467E68FFF786 +:1016F00095FF331A9C4203D86C600120BDE8F0814D +:101700006B60A41B3B68AB602044E8600220F5E7F7 +:101710002046F3E738B50C460546FFF79FFFA04289 +:1017200010D305F10C00FFF779FF04446868B4FB9F +:10173000F0F100FB1144BFF35B8F0120EC60BFF3BD +:101740005B8F38BD0020FCE72DE9FF4188466946E4 +:101750000746FFF7B7FF6C4606B204EBC606002546 +:10176000B44209D06268206808EB0501FFF770FCFD +:10177000636808341D44F3E729463846FFF7CAFF7B +:10178000284604B0BDE8F081F8B505460C300F4698 +:10179000FFF744FF05F1080604463046FFF73EFF19 +:1017A000A042304688BF6C68FFF738FF201A3860C7 +:1017B00020B130462C68FFF731FF2044F8BD00000F +:1017C00073B5144606460D46FFF72EFF844228BF28 +:1017D00004460190DCB101A93046FFF7D5FF019B1B +:1017E00033B93268C5E90233C5E9002401200CE0B1 +:1017F0009C4238BF01942860019868608442F5D902 +:101800003368AB60241AEC60022002B070BD204641 +:10181000FBE700002DE9FF410F466946FFF7D0FFC7 +:101820006C4600B204EBC0050026AC4209D0D4F8E7 +:10183000048054F8081BB8194246FFF709FC4644D7 +:10184000F3E7304604B0BDE8F081000038B5054646 +:10185000FFF7E0FF044601462846FFF719FF204640 +:1018600038BD00007047000010B4134602681468C9 +:101870000022A4465DF8044B6047000000F580504C +:1018800090F859047047000000F5805090F8520419 +:101890007047000000F5805090F958047047000030 +:1018A00050207047302383F3118800F58052D2F81E +:1018B0009C34D2F898041844D2F894341844D2F8DE +:1018C0007C341844D2F88C341844D2F88834184444 +:1018D000002383F31188704700F58050C0F854143A +:1018E0000120704738B5C26A936923F00103936100 +:1018F000044600F07FFE0546E36A9B69DB0706D5D8 +:1019000000F078FE431BFA2BF6D9002004E004F522 +:101910008054012084F8520438BD00002DE9F04FB6 +:101920000C4600F5805185B01F4691F85234BDF841 +:101930003890054690469BB1D1F878340133C1F810 +:1019400078342368980006D4237B082B0BD9627B5C +:101950000AB10F2B07D9D1F87C340133C1F87C349C +:101960004FF0FF3010E0302383F31188EB6AD3F897 +:10197000C42012F4001B0AD0D1F880340133C1F81E +:101980008034002080F3118805B0BDE8F08FD3F8D3 +:10199000C4302068C3F3014A6B6A4822002812FB56 +:1019A0000A33B4BF40F080408004186022685200BF +:1019B00044BF40F000501860207B4FEA0A6242EAC0 +:1019C00000425A60607B4FEA4A1610B342F440125C +:1019D0005A60D1F8B0240132C1F8B024AA1902F536 +:1019E0008352117B41F020011173207B039300F09F +:1019F0005DFE039B033080105FFA8BF282420BF195 +:101A0000010B0DDA04EB820103EB8202496891605D +:101A1000F2E7AA1902F58352117B60F34511E3E75F +:101A2000EB6A012202FA0AF2C3F8CC2005EB4A1154 +:101A3000AB1903F5825301F58251C3E904871831CC +:101A4000234604F10C0253F8040B41F8040B9342B3 +:101A5000F9D11B880B802E4441F2680346F803A09D +:101A600006F5805609F0030396F86C2043F0100346 +:101A700022F01F02134386F86C30002383F3118891 +:101A8000CDF8009042463B462146284600F0D4FD62 +:101A9000012079E713B500F580540191606CFFF7E0 +:101AA000DDFD1F280AD90199606C2022FFF74CFE4A +:101AB000A0F120035842584102B010BD0020FBE7BE +:101AC00008B5302383F3118800F58050406CFFF790 +:101AD00099FD002383F3118808BD000000220260F5 +:101AE000828142608260704710B500220023C0E905 +:101AF00000230023044603810C30FFF7EFFF20464C +:101B000010BD00002DE9F0479A4688B00746884688 +:101B10009146302383F3118807F580546846FFF718 +:101B2000E3FF606CFFF780FD1F282DD9606C202239 +:101B30006946FFF78BFE202826D194F852341BB358 +:101B400003AD444605AB2E4603CE9E422060616045 +:101B5000354604F10804F6D130682060B388A380CC +:101B6000DDE90023C9E90023BDF80830AAF80030F8 +:101B7000002383F3118853464A464146384608B04D +:101B8000BDE8F04700F046BD002080F3118808B0A2 +:101B9000BDE8F0872DE9F84F00230646C0E9013380 +:101BA000284B46F8303B00F58154054688463746B9 +:101BB000103438462037FFF797FFA742F9D105F5D3 +:101BC00080544FF4805326630026C4E90D366764C1 +:101BD000012305F5835705F5A359E66384F84030E2 +:101BE00084F84830103709F110094FF0000A4FF01F +:101BF000000B47E908ABA7F11800FFF76FFF20378C +:101C000047F8286C4F45F4D184F85884A4F85A64F6 +:101C1000A4F85C64A4F85E6484F86064A4F8626468 +:101C2000A4F86464A4F8666484F86864B8F1000FEA +:101C300002D0054800F0D8FC044BEB622846BDE812 +:101C4000F88F00BF04470008E84600080064004021 +:101C500010B5044B197804464A1C1A70FFF79AFF16 +:101C6000204610BD2D3C00202DE9F84315460C46BA +:101C700000295CD0022001F019FE2E49B0FBF4F7D8 +:101C80008C428CBF0A2111214B1EB7FBF1F601FBE0 +:101C90001671DAB221B1022B1946F5D8002032E0D4 +:101CA000731EB3F5806FF9D2C2EBC20808F10301CD +:101CB0004FEAE10EC1F3C701A2EB010C0EF10109DD +:101CC0004FF47A735FFA8CF70EFB033E59FA8CFCE3 +:101CD000BEFBFCFCBCF5617F17DC1FFA8CF34A1CD1 +:101CE00057FA82F27243B0FBF2F08442D6D14A1E18 +:101CF0000F2AD3D87A1E072AD0D801202B806E80D5 +:101D000028716971AF71BDE8F88308F1FF314FEABE +:101D1000E10CC1F3C701521A0CF1010ED7B20CFB52 +:101D200003335EFA82F2B3FBF2F39BB2D7E70846C5 +:101D3000E9E700BF3F420F0030B50D4B0D4D0520C8 +:101D40001C786C438C420ED159785180997851712E +:101D5000D9789171197911715B7903EB83035B0079 +:101D60001380012030BD013803F10603E8D1F9E703 +:101D70004447000840420F000B4B10B54FF454721B +:101D8000044600211846FFF775F9084BA36140335C +:101D9000E361D8332362F0336362E36A6061002257 +:101DA000C3F8C02010BD00BF00A4004070A40040D4 +:101DB0002DE9F04F00F580551F4695F85834012B5A +:101DC00089B004468946904604D90026304609B0B9 +:101DD000BDE8F08F9A4A52F8231009B942F823005F +:101DE0009848C4F80C900178277499B9302383F38C +:101DF0001188954B9A6D42F000729A659A6B42F089 +:101E000000729A639A6B22F000729A630123037046 +:101E100081F3118895F851647EB9302383F31188DA +:101E20000321152001F056FE0321162001F052FE79 +:101E3000012385F8513486F31188302383F3118808 +:101E4000E26A936923F01003936100F0D3FB8246AA +:101E5000E36A9E6916F0080609D000F0CBFBA0EB00 +:101E60000A03FA2BF4D9002686F31188AEE79A69A3 +:101E700042F001029A6100F0BDFB8246E36A9A6972 +:101E8000D00706D400F0B6FBA0EB0A03FA2BF5D975 +:101E9000E9E79A6942F002029A61E36A4FF0000AA8 +:101EA000C3F854A08AF31188686CFFF7ABFB04F504 +:101EB000825B0BF1100B202200216846FFF7DAF855 +:101EC00002A8FFF70BFECDF818A06A460BEB06033D +:101ED0000DF1180E9446BCE80300F44518605960F3 +:101EE000624603F10803F5D1DCF8000018602036E3 +:101EF0009CF804201A71B6F5806FDCD1002304F53C +:101F0000A25285F8503485F853341A324946204697 +:101F1000FFF7AAFE064690B9E26A936923F001032F +:101F2000936100F067FB0546E36A9B69D9077FF57B +:101F30004CAF00F05FFB431BFA2BF5D945E795F852 +:101F40005E34C5F86C94591E95F85F34E26A013B23 +:101F50001B0243EA416395F8601401390B43B5F85D +:101F60005C14013943EA0143D361B8F1000F36D064 +:101F700004F5A352023241462046FFF7DDFE90B938 +:101F8000E26A936923F00103936100F033FB054695 +:101F9000E36A9B69DA077FF518AF00F02BFB431B60 +:101FA000FA2BF5D911E795F86724C5F87084511E0E +:101FB00095F86824E36A013A120142EA012295F891 +:101FC000661401390A43B5F86414013942EA014242 +:101FD00042F40002DA60E36A4FF420629A64204619 +:101FE000FFF7CAFE002385F85934E36A6FF04042D8 +:101FF0001A65E36A154A5A65E36A44229A65E36AF8 +:102000000722C3F8DC20E36A03229742DA653FF433 +:10201000DDAEE26A936923F00103936100F0EAFA0E +:102020000746E36A9B69DB0705D500F0E3FAC31BAB +:10203000FA2BF6D9C9E6012385F85234C6E600BF6B +:10204000283C00202C3C0020001002409B0008008F +:102050002DE9F04F054689B090469946002741F298 +:10206000680A00F58056EB6AD3F8D430FB40D807F5 +:1020700051D505EB471252444FEA471B1379190714 +:1020800049D4D6F884340133C6F8843405F5A55311 +:10209000C3E9008913799A0648BFD6F8B43405EB32 +:1020A0000B0248BF0133524448BFC6F8B434137919 +:1020B00043F008031371DB0722D596F85334FBB1C4 +:1020C00005F58254183468465C44FFF70DFD03ABF8 +:1020D00004F1080C206861681A4603C2083464459C +:1020E0001346F7D120681060A2889A800123ADF8CA +:1020F00008302B68CDE90089DB6B69462846984794 +:10210000D6F8A834D6F854040133C6F8A83410B170 +:1021100003681B6998470137202FA4D109B0BDE897 +:10212000F08F00002DE9F04F8DB004460F4600F00F +:1021300063FA82468946002F56D1E36AD3F890208D +:10214000920141BF04F58051D1F898240132C1F8C1 +:102150009824D3F89020160703D100200DB0BDE8D5 +:10216000F08FD3F89050E669C5F30125482303FBAF +:102170000566E8464046FFF7B1FC326851004ABFA9 +:1021800022F06043C2F38A4343F00043920048BF09 +:1021900043F080430093736813F400131FBF04F5EA +:1021A000805201238DF80D30D2F8B8340EBF8DF86F +:1021B0000D300133C2F8B834F38803F00F038DF803 +:1021C0000C304FF0000B9DF80C0000F06FFA5FFA36 +:1021D0008BF3984220D9F2180CA90B44127A03F819 +:1021E0002C2C0BF1010BEEE7012FB6D1E36AD3F8EB +:1021F0009820950141BF04F58051D1F8982401320F +:10220000C1F89824D3F898201007A6D0D3F8985096 +:10221000266AC5F30125A9E7EFB9E36AC3F894502C +:1022200004A8FFF761FC98E80F0007AD07C52B80F5 +:102230000023ADF8183023682046CDE904A9DB6BF4 +:1022400004A9984704F5805458B1D4F89034013368 +:10225000C4F8903482E7012F04BFE36AC3F89C50AE +:10226000DEE7D4F894340133C4F89434012075E7E0 +:102270002DE9F04105460F4600F580540126394608 +:102280002846FFF74FFF10B184F85364F7E7D4F8FE +:10229000A834D4F854040133C4F8A83420B1036836 +:1022A000BDE8F0411B691847BDE8F081F0B5C36A8D +:1022B0001A6C12F47F0F2BD000F580541B6CC4F8FD +:1022C000AC3441F26805002347194FF0010C00EBD4 +:1022D00043122A445E01117911F0020F15D049070B +:1022E00013D4B959C66AD6F8C8E00CFA01F111EA5C +:1022F0000E0F0AD0C6F8D010117941F00401117107 +:10230000D4F88C240132C4F88C240133202BDED184 +:10231000F0BD000010B5254C254B226802B338B340 +:102320001A6D12060ED580221A6500F065F950EA82 +:1023300001020B4602D0013861F100030246206819 +:10234000FFF786FE1A4A136D1B032AD523684FF444 +:10235000002103F580531165012283F8592420E000 +:1023600001221A6508221A654FF480621A6510BDB1 +:10237000196DC80702D4196D890705D503211965A0 +:1023800010460021FFF774FF094B1A6D100702D4A5 +:102390001A6DD10605D518221A6520680121FFF7AC +:1023A00067FF2068BDE81040FFF780BF283C002091 +:1023B0000064004008B5302383F31188FFF776FFEF +:1023C000002383F3118808BDC36AD3F8C40080F4E6 +:1023D0000010C0F34050704708B5302383F31188D4 +:1023E00000F58050406CFFF71FF9002383F311883C +:1023F00043090CBF0120002008BD000000F58053F8 +:1024000093F8592462B1C16A8A6922F001028A6193 +:10241000D3F89C240132C3F89C24002283F8592469 +:10242000704700002DE9F743302181F3118800F552 +:1024300082511031002541F2680E4FF0010800F57D +:10244000805C00EB45147444267977071CD4F606AB +:102450001AD5D0F82C908E69D9F8C87008FA06F60B +:102460003E4211D04F6801970F689742019F9F41EC +:102470000AD2C9F8D060267946F004062671DCF845 +:1024800088440134CCF888440135202D01F1200125 +:10249000D7D1002383F3118803B0BDE8F083000097 +:1024A000F8B51E46002313700F4605461446FFF785 +:1024B00093FF80F0010038701EB12846FFF784FFBB +:1024C0002070F8BD2DE9F04F85B09946DDE90EA3E7 +:1024D0000D4602931378019391F800B0804616469A +:1024E00000F08AF82B7804460F4613B93378002B96 +:1024F00041D022463B464046FFF794FFFFF75AFF84 +:10250000FFF77CFF4B4632462946FFF7C9FF2B7881 +:1025100033B1BBF1000F03D0012005B0BDE8F08F4F +:10252000337813B1019B002BF6D108F58053039348 +:10253000029B544577EB03031DD2039BD3F854044D +:10254000C8B10368AAEB04011B6898474B463246A2 +:1025500029464046FFF7A4FF2B7813B1BBF1000FCB +:10256000DAD1337813B1019B002BD5D100F044F8B8 +:1025700004460F46DCE70020CFE7000008B5002046 +:10258000FFF7C8FEBDE8084001F050B808B50120CB +:10259000FFF7C0FEBDE8084001F048B800B59BB0A9 +:1025A000EFF3098168226846FEF752FDEFF30583D9 +:1025B000014B9B6BFEE700BF00ED00E008B5FFF7A5 +:1025C000EDFF000000B59BB0EFF30981682268467B +:1025D000FEF73EFDEFF30583014B5B6BFEE700BFAB +:1025E00000ED00E0FEE700000FB408B5029801F02E +:1025F00025FBFEE701F004BE01F0E6BD13B56C4615 +:1026000084E80600031D94E8030083E80500012028 +:1026100002B010BD73B58568019155B11B885B0789 +:1026200007D4D0E900369B6B9847019AC1B2304677 +:10263000A847012002B070BDF0B5866889B0054694 +:102640000C465EB1BDF838305B070AD4D0E90037DC +:102650009B6B98472246C1B23846B047012009B06B +:10266000F0BD00220023CDE900230023ADF808309F +:102670000A4603AB01F10806106851681C4603C402 +:102680000832B2422346F7D1106820609288A280B7 +:10269000FFF7B2FF0423ADF808302B68CDE9000145 +:1026A000DB6B694628469847D8E70000082817D909 +:1026B00009280CD00A280CD00B280CD00C280CD0E0 +:1026C0000D280CD00E2814BF4020302070470C205D +:1026D0007047102070471420704718207047202042 +:1026E000704700002DE9F041456A15B94162BDE827 +:1026F000F0814B6823F06047C3F38A464FEAD37EEC +:10270000C3F3807816EA230638BF3E46AC462B4614 +:102710005A68BEEBD27F22F060440AD0002A18DA51 +:10272000A40CB44217D19D420FD10D60DEE71346D1 +:10273000EEE7A74207D102F08044C2F3807242451F +:102740000BD054B1EFE708D2EDE7CCF800100B60E6 +:10275000CDE7B44201D0B442E5D81A689C46002ABD +:10276000E5D11960C3E700002DE9F047089D01F0AD +:1027700007044FEAD508224405F0070500EBD10015 +:102780004FF47F49944201D1BDE8F08704F0070778 +:1027900005F0070A57453E4638BF5646C6F10806BB +:1027A000111B8E4228BF0E46E10808EBD50E415C96 +:1027B00013F80EC0B94029FA06F721FA0AF1FFB260 +:1027C0008CEA010147FA0AF739408CEA010C03F858 +:1027D0000EC034443544D5E780EA0120082341F295 +:1027E000210201B24000002980B203F1FF33B8BFDB +:1027F000504013F0FF03F4D17047000038B50C4689 +:102800008D18A54200D138BD14F8011BFFF7E4FF75 +:10281000F7E7000042684AB1136843604389818941 +:1028200001339BB29942438138BF83811046704780 +:1028300070B588B0202204460D4668460021FEF798 +:1028400019FC20460495FFF7E5FF024658B16B4698 +:10285000054608AE1C4603CCB44228606960234696 +:1028600005F10805F6D1104608B070BD082817D943 +:1028700009280CD00A280CD00B280CD00C280CD01E +:102880000D280CD00E2814BF4020302070470C209B +:102890007047102070471420704718207047202080 +:1028A00070470000082817D90C280CD910280CD91B +:1028B00014280CD918280CD920280CD930288CBF02 +:1028C0000F200E207047092070470A2070470B2008 +:1028D00070470C2070470D20704700002DE9F84329 +:1028E000078C072F04461ED9D0E9029800254FF621 +:1028F000FF73C5F12006A5F1200029FA05F108FAB9 +:1029000006F628FA00F031430143C9B21846FFF732 +:1029100063FF0835402D0346EBD1E1693A46BDE837 +:10292000F843FFF76BBF4FF6FF70BDE8F883000078 +:1029300010B54B6823B9CA8A63F30902CA8210BD75 +:1029400004691A681C600361C38A013BC3824A6040 +:10295000EFE700002DE9F84F1D46CB8A0F46C3F381 +:1029600009010529814692460B4630D00020AAB2C3 +:1029700007F11A049EB2042E1FFA80F80FD8904572 +:1029800003F1010306D3FB8A0A4462F30903FB82C5 +:1029900001201AE01AF80060E6540130EAE7904599 +:1029A000F1D2A1F1050B1C237C68BBFBF3F203FB06 +:1029B00012BB1FFA8BF6002C45D14846FFF72AFFC1 +:1029C000044638B978606FF00200BDE8F88F4FF028 +:1029D0000008E6E7002606607860ADB24FF0000B15 +:1029E000454510D90AEB0803221D13F8011B915528 +:1029F000B1B208F101081B291FFA88F82BD0454510 +:102A000006F10106F1D8FB8AC3F30902154465F308 +:102A10000903BCE7013292B21C462368002BF9D1AE +:102A20006B1F0B441C21B3FBF1F301339BB29A42A1 +:102A3000D3D2BBF1000FD0D14846FFF7EBFE20B94F +:102A4000C4F800B0BFE70122E7E7C0F800B05E4677 +:102A500020600446C1E74545D5D94846FFF7DAFE70 +:102A600008B92060AFE7C0F800B000262060044637 +:102A7000B6E700002DE9F04F2DED028B1C4683B028 +:102A80005B69019207468846002B00F09A80238CF0 +:102A90002BB1E269002A00F09480072B35D807F1AA +:102AA0000C00FFF7B7FE054638B96FF0020528465F +:102AB00003B0BDEC028BBDE8F08F14220021FEF7BD +:102AC000D9FA228CE16905F10800FEF7C1FA208CE1 +:102AD000013080B2FFF7E6FEFFF7C8FE013880B292 +:102AE0002084013028746369228C1B782A4403F007 +:102AF0001F0363F03F0348F00041137238466960DA +:102B00002946FFF7EFFD0125D1E700F10C034FF057 +:102B1000000908EE103A4FF0800A4E464D4618EE76 +:102B2000100AFFF777FE83460028BED0142200214A +:102B3000FEF7A0FA002E3AD1019BABF80830022232 +:102B40000BF1080E1FFA82FC0CF10100BCF1060F1C +:102B5000218C80B201D88E422BD3FFF7A3FEFFF762 +:102B600085FE62691278013802F01F028E4208BFAA +:102B70004FF0400A42EA49121BFA80F14AEA020A7F +:102B8000013048F0004281F808A08BF81000CBF823 +:102B9000042059463846FFF7A5FD238C0135B34282 +:102BA0002DB289F001094FF0000AB8D17FE7002269 +:102BB000C6E7E169895D0EF802100136B6B201324E +:102BC000C0E76FF0010572E7F8B515460E463022F2 +:102BD000002104461F46FEF74DFA069B6360B5F5DB +:102BE000001F079BA76034BF6A094FF6FF72A362FC +:102BF00097B2E66104F1100000239A4206D8002340 +:102C00000360A782E3822383E360F8BD066001339B +:102C100030462036F1E7000003781BB94BB2002B99 +:102C2000C8BF01707047000000787047F8B50C46C7 +:102C3000C969074611B9238C002B37D1257E1F2D7A +:102C400034D8387828BB228C072A2CD8268A36F02C +:102C500003032BD14FF6FF70FFF7D0FD20F00100EA +:102C60003102400441EA0561400C41EA40254FF63B +:102C7000FF72234629463846FFF7FCFE002807DD91 +:102C8000626913780133DBB21F2B88BF00231370F6 +:102C9000F8BD218A2D0645EA012505432046FFF7A8 +:102CA0001DFE0246E5E76FF00300F1E76FF001005B +:102CB000EEE7000070B58AB00446164600212822CF +:102CC00068461D46FEF7D6F9BDF83830ADF810302D +:102CD0000F9B05939DF840308DF81830119B07939A +:102CE0006946BDF84830ADF820302046CDE9026590 +:102CF000FFF79CFF0AB070BD2DE9F041D36905468E +:102D00000C4616460BB9138C5BBB377E1F2F28D899 +:102D100095F80080B8F1000F26D03046FFF7DEFDB1 +:102D20003378210241EAC33141EA0801338A41EA9A +:102D3000076141EA03410246334641F080012846DB +:102D4000FFF798FE00280ADD3378012B07D172695E +:102D500013780133DBB21F2B88BF00231370BDE84B +:102D6000F0816FF00100FAE76FF00300F7E7000071 +:102D7000F0B58BB004460D46174600212822684660 +:102D80001E46FEF777F99DF84C305A1E53425341C8 +:102D90008DF800309DF84030ADF81030119B059350 +:102DA0009DF848308DF81830149B07936A46BDF89B +:102DB0005430ADF8203029462046CDE90276FFF7A1 +:102DC0009BFF0BB0F0BD0000406A00B104307047BB +:102DD000436A1A68426202691A600361C38A013B4E +:102DE000C38270472DE9F041D0F82080194E144677 +:102DF0001D464146002709B9BDE8F081D1E902230B +:102E0000A21A65EB0303964277EB03031ED2036A13 +:102E10008B420DD1FFF78CFD036A1B6803620369C7 +:102E20000B60C38A0161016A013BC3828846E2E705 +:102E3000FFF77EFD0B68C8F8003003690B60C38A9A +:102E40000161013BC382D8F80010D4E788460968C5 +:102E5000D1E700BF80841E002DE9F04F8BB00D46F6 +:102E6000DDF8509014469B468046002800F01981FA +:102E7000B9F1000F00F01581531E3F2B00F21181B4 +:102E8000012A03D1BBF1000F40F00B810023CDE9F3 +:102E90000833B8F81430B5EBC30F4FEAC30703D3B8 +:102EA00000200BB0BDE8F08F2B199F42D8F80C30F2 +:102EB0003ABF7F1BFFB227461BB9D8F81030002B52 +:102EC0007AD0272D4ED8C5F12806B7424FF000031F +:102ED0002CBFF6B23E4600932946D8F8080008AB4E +:102EE0003246FFF741FCA7EB060A35445FFA8AFA3F +:102EF000B8F8143003F10053053BDB000493D8F815 +:102F00000C3003932821039B13B1BAF1000F2CD18D +:102F1000D8F8100040B1BAF1000F05D0009608AB08 +:102F20005246691AFFF720FC38B2002FB8D0660766 +:102F30000AD00AAB03EBD401624211F8083C02F05C +:102F40000702134101F8083C082C3CD9102C40F230 +:102F5000B580202C40F2B780BBF1000F00F09C80C0 +:102F6000082334E0BA460026C2E7049BE02B28BFC2 +:102F7000E02306930B44AB42059314D95A1B0398E4 +:102F80000096924534BF5246D2B2691A08AB04305B +:102F90000792FFF7E9FB079A1644AAEB020A1544C9 +:102FA000F6B25FFA8AFA049B069A05999B1A049373 +:102FB000039B1B680393A6E70093D8F8080008ABAF +:102FC0003A462946AEE7BBF1000F13D00123B4EB1C +:102FD000C30F6CD0082C12D89DF82030621E23FA43 +:102FE00002F2D50706D54FF0FF3202FA04F423436C +:102FF0008DF820309DF8203089F8003051E7102CF2 +:1030000012D8BDF82030621E23FA02F2D10706D58D +:103010004FF0FF3202FA04F42343ADF82030BDF83C +:103020002030A9F800303CE7202C0FD80899631E07 +:1030300021FA03F3DA0705D54FF0FF3202FA04F460 +:103040000C430894089BC9F800302AE7402C2BD089 +:10305000DDE90865611EC4F12102A4F1210326FA0D +:1030600001F105FA02F225FA03F311431943CB07E4 +:1030700012D50122A4F12003C4F1200102FA03F3C6 +:1030800022FA01F1A240524243EA010363EB4303F7 +:1030900032432B43CDE90823DDE90823C9E90023A6 +:1030A000FFE66FF00100FCE66FF00800F9E6082C7F +:1030B000A0D9102CB3D9202CEED8C3E7BBF1000F58 +:1030C000ADD0022383E7BBF1000FBBD004237EE722 +:1030D00030B5012A144638BF0124402C85B028BFE2 +:1030E00040240025012ACDE9025518D81B788DF817 +:1030F000083063070AD004AB03EBD405624215F82D +:10310000083C02F00702934005F8083C0091034692 +:103110002246002102A8FFF727FB05B030BD082A90 +:10312000E4D9102A03D81B88ADF80830E1E7202A3B +:103130008DBFD3E900231B680293CDE90223D8E7B2 +:1031400010B5CB681BB98B600B618B8210BD046915 +:103150001A681C600361C38A013BC382CA60F0E73E +:1031600003064CBFC0F3C0300220704708B50246CA +:10317000FFF7F6FF022806D15306C2F30F2001D154 +:1031800000F0030008BDC2F30740FBE72DE9F04F54 +:1031900093B0CDE903230A6804461046FFF7E0FF29 +:1031A000022814BFC2F306260026002A0D468246D6 +:1031B00080F2F28112F0C04940F0EE81097B0029D3 +:1031C00000F0EA81022803D02378B34240F0E7817F +:1031D000C2F304630693104602F07F030593FFF7E2 +:1031E000C5FF059B29444FEA834848EA0A4848EA54 +:1031F0004668CE7800230022CDE90823F3098346F0 +:1032000048EA0008029367D0059B0093024667686E +:10321000534608A92046B847002800F0C381276A12 +:103220004FB9414604F10C00FFF702FB074690B985 +:103230006FF0020054E03B6998450DD03F68002FC5 +:10324000F9D1414604F10C00FFF7F2FA07460028D5 +:10325000EED0236A3B60276297F817C006F01F087C +:10326000CCF3840CACEB08001FFA80FE0028B8BF3A +:103270000EF12000A8EB0C031FFA83FED7E9022110 +:10328000B8BF00B2002B0793BEBF0EF120031BB2E4 +:10329000079352EA010338D0039BDFF824E39A1A1C +:1032A000049B4FF0000C63EB010196457CEB01039E +:1032B0002BD36B7B97F81AE0734519D1029B002B37 +:1032C00078D0012821DC7868F8B9DFF8F0C294459D +:1032D00070EB010316D337E0276A27B96FF00C00B3 +:1032E00013B0BDE8F08F3B699845B5D03F68F4E76F +:1032F000B24890427CEB010301D30020F0E7029B2F +:10330000002BFAD0079B0F2B17DCFA7DB30002F0DD +:10331000030203F07C031343FB7539462046FFF795 +:1033200007FB6B7BBB76029B3BB9FB7DC3F384023F +:10333000013262F38603FB75D0E76A7BBB7E9A425B +:10334000DBD1029B002B35D0B309022B32D0039B7B +:10335000BB60049BFB60142200210DA8FDF78AFED0 +:10336000039B0A93049B0B932B1D0C932B7BADF8B3 +:103370003EB0013BDBB2ADF83C30069B8DF84230ED +:10338000059B8DF8433094F82C308DF840A083F0E5 +:1033900001038DF844308DF84180A3680AA92046C6 +:1033A0009847FB7DC3F38403013303F01F039B02A3 +:1033B000FB82A2E7FB7DC6F34012B2EBD31F40F0C5 +:1033C000F480C3F38403434540F0F280029A2B7BE0 +:1033D000B609002A4DD0F2075DD4032B40F2EB80F2 +:1033E000039BBB60049BFB602B7BAE1D033BDBB2EE +:1033F0003246394604F10C00FFF7ACFA00280CDA2B +:1034000039462046FFF794FAFB7DC3F3840301336A +:1034100003F01F039B02FB820AE7DDE90884AB8807 +:103420003B834FF6FF73C9F12000A9F1200228FA6F +:1034300009F104FA00F0014324FA02F2114318469C +:10344000C9B2FFF7C9F909F10809B9F1400F0346FC +:10345000E9D1B8822A7B033AD2B23146FFF7CEF9DE +:10346000FB7DB882DA43C2F3C01262F3C713FB7567 +:1034700043E786B92E1D013BDBB23246394604F1E3 +:103480000C00FFF767FA0028BADB2A7BB88A013AFA +:10349000D2B23146E2E7F98AC1F30901013B0429BE +:1034A000DAB25BD8281D002307F11B069A4208D91F +:1034B00010F801CB06F801C0013101330529DBB258 +:1034C000F4D103990A9104990B91934207F11B01DE +:1034D0000C9138BF043379680D9134BF55FA83F3EA +:1034E00000230E93FB8AADF83EB0C3F309031A44E0 +:1034F000069B8DF84230059B8DF8433094F82C30B4 +:10350000ADF83C2083F001038DF8443000238DF8A2 +:1035100040A08DF841807B602A7BB88A013A291D42 +:10352000FFF76CF93B8BB882834203D1A3680AA9E9 +:103530002046984720460AA9FFF702FEFB7DBA8A7B +:10354000C3F38403013303F01F039B02FB823B8B15 +:103550009A420CBF00206FF01000C1E67B68002B80 +:10356000AFD0052001E01C3033461E68002EFAD192 +:10357000091A081D2E1D184401EB090CBCF11B0F84 +:103580005FFA89F39DD89A429BD916F8013B00F85F +:10359000013B09F10109EFE76FF00900A0E66FF0C8 +:1035A0000A009DE66FF00B009AE66FF00D0097E6BB +:1035B0006FF00E0094E66FF00F0091E640420F00AE +:1035C00080841E00EFF3098305494A6B22F0010253 +:1035D0004A63683383F30988002383F311887047B3 +:1035E00000EF00E0302080F3118862B60C4B0D4AEA +:1035F000D96821F4E0610904090C0A43DA60D3F8C0 +:10360000FC20094942F08072C3F8FC200A6842F0AD +:1036100001020A602022DA7783F82200704700BF97 +:1036200000ED00E00003FA05001000E010B53023C3 +:1036300083F311880E4B5B6813F4006314D0F1EE32 +:10364000103AEFF30984683C4FF08073E361094B53 +:10365000DB6B236684F3098800F0BAFA10B1064BDD +:10366000A36110BD054BFBE783F31188F9E700BFA9 +:1036700000ED00E000EF00E03F0300084203000817 +:10368000434B4FF4007270B51A605A6912F4C06F60 +:10369000FBD1404B9A6802F00C02042A20D01A6831 +:1036A00042F480721A601A685205FCD501229A60B1 +:1036B0009A6802F00C02042AFAD13749374A0A60A4 +:1036C0000A6812F00F02FBD1C3F8982063221A6037 +:1036D0001A689603FCD42E4A4FF48071C2F8801009 +:1036E000C468E50306D51A6842F480321A601A6885 +:1036F0009103FCD5C269D20709D5D3F8982042F0CE +:103700000102C3F89820D3F898209607FBD54269A8 +:10371000DA6044F480721A6004F0807111B11A68A2 +:103720009501FBD5996802691B4E22F0030501F053 +:10373000030129439960856935603168694009074B +:10374000FBD1134905680D6046684E608068C1F87A +:1037500080006E0417D448698505FCD4996802F08E +:10376000030021F0030101439960920099685140E0 +:1037700011F00C0FFAD1E2055EBF1A6822F48072D4 +:103780001A60002070BD48698005FCD5E6E700BFDF +:1037900000700040001002400020024000060400BB +:1037A00008B500F083F9BDE8084000F05BB90000FF +:1037B00010B5394C3948A36A4FF0FF32A262A36AB0 +:1037C0000023A362A16AE16A61F07F01E162E16A1C +:1037D00001F07F01E162E16A216B2263216B2363C7 +:1037E000216BA16BA263A16BA363A16BE16BE2638D +:1037F000E16BE363E16B216C2264226C2364226C35 +:10380000226E42F001022266D4F8802022F00102EA +:10381000C4F88020D4F88020A26D42F08052A265C6 +:10382000A26F22F08052A267A26F1D4A4FF400419E +:103830009160D360136253629362D36213635363E4 +:103840009363D363136453649364D36413655365C0 +:10385000116841F480711160D4F8902012F4407F17 +:103860001EBF4FF48032C4F89020C4F890300D4A47 +:103870000023A360C4F88820C4F89C30FFF700FF41 +:1038800010B1094800F0DAF9D4F8903023F003239E +:10389000C4F8903010BD00BF001002406C47000813 +:1038A000007000405501005164470008014B53F877 +:1038B0002000704718110020074A08B5536903F02B +:1038C0000103536123B1054A13680BB1506898474F +:1038D000BDE80840FFF7AABE00040140843E002076 +:1038E000074A08B5536903F00203536123B1054A3F +:1038F00093680BB1D0689847BDE80840FFF796BEC3 +:1039000000040140843E0020074A08B5536903F0D3 +:103910000403536123B1054A13690BB150699847F9 +:10392000BDE80840FFF782BE00040140843E00204D +:10393000074A08B5536903F00803536123B1054AE8 +:1039400093690BB1D0699847BDE80840FFF76EBE98 +:1039500000040140843E0020074A08B5536903F083 +:103960001003536123B1054A136A0BB1506A98479B +:10397000BDE80840FFF75ABE00040140843E002025 +:10398000164B10B55C6904F478725A61A30604D52D +:10399000134A936A0BB1D06A9847600604D5104A5F +:1039A000136B0BB1506B9847210604D50C4A936BEF +:1039B0000BB1D06B9847E20504D5094A136C0BB1E3 +:1039C000506C9847A30504D5054A936C0BB1D06C95 +:1039D0009847BDE81040FFF729BE00BF0004014032 +:1039E000843E0020194B10B55C6904F47C425A6196 +:1039F000620504D5164A136D0BB1506D9847230527 +:103A000004D5134A936D0BB1D06D9847E00404D5EB +:103A10000F4A136E0BB1506E9847A10404D50C4A9F +:103A2000936E0BB1D06E9847620404D5084A136FA9 +:103A30000BB1506F9847230404D5054A936F0BB11F +:103A4000D06F9847BDE81040FFF7F0BD000401407B +:103A5000843E002008B500F0F1FCBDE80840FFF707 +:103A6000E5BD0000062108B5084600F033F8062140 +:103A7000072000F02FF80621082000F02BF806217F +:103A8000092000F027F806210A2000F023F806217B +:103A9000172000F01FF80621282000F01BF8BDE8D1 +:103AA000084007211C2000F015B800004FF0E0236B +:103AB000002258684FF0FF31930003F1604303F593 +:103AC000614301329042C3F88010C3F88011F3D2F1 +:103AD0007047000000F1604303F561430901C9B27A +:103AE00083F80013012200F01F039A4043099B0052 +:103AF00003F1604303F56143C3F880211A60704706 +:103B000000230375826803691B6899689142FBD2A0 +:103B10005A68036042601060586070470023037564 +:103B2000826803691B6899689142FBD85A680360F0 +:103B3000426010605860704708B50846302383F330 +:103B400011880B7D032B05D0042B0DD02BB983F3EB +:103B5000118808BD8B6900221A604FF0FF33836122 +:103B6000FFF7CEFF0023F2E7D1E9003213605A607D +:103B7000F3E70000FFF7C4BF054BD9680875186864 +:103B800002681A60536001220275D860FCF7C2BB5C +:103B9000383C002030B50C4BDD684B1C87B0044628 +:103BA0000FD02B46094A684600F02AF92046FFF755 +:103BB000E3FF009B13B1684600F02CF9A86907B039 +:103BC00030BDFFF7D9FFF9E7383C0020393B00084A +:103BD000044B1A68DB6890689B68984294BF002089 +:103BE00001207047383C0020084B10B51C68D8688D +:103BF00022681A60536001222275DC60FFF78EFF95 +:103C000001462046BDE81040FCF784BB383C00204C +:103C100038B5074C07490848012300252370656023 +:103C200000F03AFC0223237085F3118838BD00BFF1 +:103C3000603E002090470008383C002008B572B66E +:103C4000044B186500F0ACFA00F05AFB024B03225B +:103C50001A70FEE7383C0020603E002000F010B9EA +:103C60008B60022308618B82084670478368A3F14A +:103C7000840243F8142C026943F8442C426943F847 +:103C8000402C094A43F8242CC26843F8182C02221D +:103C900003F80C2C002203F80B2C044A43F8102CD8 +:103CA000A3F12000704700BF2D030008383C00201E +:103CB00008B5FFF7DBFFBDE80840FFF75BBF00007A +:103CC000024BDB6898610F20FFF756BF383C00209D +:103CD000302383F31188FFF7F3BF000008B50146D6 +:103CE000302383F311880820FFF754FF002383F368 +:103CF000118808BD10B503689C68A2420CD85C68A6 +:103D00008A600B604C602160596099688A1A9A60D9 +:103D10004FF0FF33836010BD1B68121BECE70000FF +:103D20000A2938BF0A2170B504460D460A266019D3 +:103D300000F0ACFB00F098FB041BA54203D8751CF7 +:103D40002E460446F3E70A2E04D9BDE87040012050 +:103D500000F0E2BB70BD0000F8B5144B0D46D96110 +:103D600003F1100141600A2A1969826038BF0A22F2 +:103D7000016048601861A818144600F079FB0A2712 +:103D800000F072FB431BA342064606D37C1C281995 +:103D900000F07CFB27463546F2E70A2F04D9BDE840 +:103DA000F840012000F0B8BBF8BD00BF383C00204F +:103DB000F8B506460D4600F057FB0F4A134653F878 +:103DC000107F9F4206D12A4601463046BDE8F840A2 +:103DD000FFF7C2BFD169BB68441A2C1928BF2C4613 +:103DE000A34202D92946FFF79BFF224631460348EA +:103DF000BDE8F840FFF77EBF383C0020483C00207B +:103E000010B4C0E9032300235DF8044B4361FFF7BE +:103E1000CFBF000010B5194C236998420DD0D0E9EE +:103E20000032816813605A609A680A449A600023DD +:103E300003604FF0FF33A36110BD2346026843F8CF +:103E4000102F53600022026022699A4203D1BDE81C +:103E5000104000F015BB936881680B44936000F03C +:103E600003FB2269E1699268441AA242E4D9114431 +:103E7000BDE81040091AFFF753BF00BF383C0020CF +:103E80002DE9F047DFF8BC8008F110072C4ED8F878 +:103E9000105000F0E9FAD8F81C40AA68031B9A42B7 +:103EA0003ED81444D5E900324FF00009C8F81C4050 +:103EB00013605A60C5F80090D8F81030B34201D1B1 +:103EC00000F0DEFA89F31188D5E9033128469847D6 +:103ED000302383F311886B69002BD8D000F0C4FA2B +:103EE0006A69A0EB04094A4582460DD2022000F01F +:103EF00013FB0022D8F81030B34208D151462846AF +:103F0000BDE8F047FFF728BF121A2244F2E712EB90 +:103F1000090938BF4A4629463846FFF7EBFEB5E7A0 +:103F2000D8F81030B34208D01444211AC8F81C0045 +:103F3000A960BDE8F047FFF7F3BEBDE8F08700BF1A +:103F4000483C0020383C002038B500F08DFA054A86 +:103F5000D2E90845031B181945F10001C2E908011F +:103F600038BD00BF383C002000207047FEE700004D +:103F7000704700004FF0FF3070470000BFF34F8FD5 +:103F8000024A1369DB03FCD4704700BF00200240E3 +:103F900008B5094B1B7873B9FFF7F0FF074B5A6957 +:103FA000002ABFBF064A9A6002F188329A601A68F6 +:103FB00022F480621A6008BD783E00200020024092 +:103FC0002301674508B50B4B1B7893B9FFF7D6FF64 +:103FD000094B5A6942F000425A611A6842F4805211 +:103FE0001A601A6822F480521A601A6842F48062D9 +:103FF0001A6008BD783E0020002002403F289ABF8A +:1040000000F58030C0020020704700004FF40060CF +:1040100070470000402070473F2808B50BD8FFF7D5 +:10402000EDFF00F500630268013204D104308342E1 +:10403000F9D1012008BD0020FCE700003F2810B5A1 +:1040400004461FD8FFF79AFFFFF7A2FF0E4BF3229B +:104050001A6102225A615A6942EAC0025A615A69D7 +:1040600042F480325A61FFF789FF4FF40061FFF795 +:10407000C5FF00F041F9FFF7A5FF2046BDE810405D +:10408000FFF7CABF002010BD002002402DE9F84311 +:1040900040EA020313F00703144606D0304B40F207 +:1040A00041321A600020BDE8F88385182D4A9542F8 +:1040B0000CD92B4A40F246311160F3E7031D1B680F +:1040C0004A68934208D1083C08300831072C14D9BB +:1040D00002680B689A42F1D0FFF75AFFFFF74EFFD4 +:1040E000214E08314FF001084FF00009012CA1F1D9 +:1040F000080706D8FFF766FF01E0002CECD101208D +:10410000D1E7C6F81480054651F8083C45F8043B51 +:1041100051F8043C4360FFF731FF336943F001037A +:104120003361C6F81490026851F8083C9A420CD0EA +:104130000B4B40F26E321A600C4B18600C4B1C603B +:104140000C4B1F60FFF73EFFACE72D6851F8043CB5 +:104150009D4201F10801EBD1083C0830C6E700BFE1 +:10416000743E00200000020800200240683E00204B +:10417000703E00206C3E0020084908B50B7828B13D +:104180001BB9FFF705FF01230B7008BD002BFCD006 +:10419000BDE808400870FFF715BF00BF783E00205B +:1041A00008B506484FF4AE4100F0A8F8BDE8084055 +:1041B0004FF420514FF0805000F0A0B800010020D3 +:1041C000084600F035BA000038B5EFF311859DB907 +:1041D000EFF30584C4F30804302334B183F311886A +:1041E000FFF7B2FE85F3118838BD83F31188FFF71E +:1041F000ABFE84F3118838BDBDE83840FFF7A4BE9C +:1042000038B5FFF7E1FF114C114AC00840EA417090 +:10421000A0FB025EC908A0FB040C1CEB050CA1FB73 +:1042200004404FF000035B41A1FB02121CEB040CA5 +:1042300043EB000011EB0E0142F10002411842F184 +:104240000000090941EA007038BD00BFCFF753E311 +:10425000A59BC4200244D2B2904200D17047431CB7 +:10426000800000F1804000F51450006841F8040B14 +:10427000D8B2F1E7124B10B5D3F89040240409D41A +:10428000D3F89040C3F89040D3F8904044F40044F1 +:10429000C3F890400B4C2368024443F480732360BE +:1042A000D2B2904200D110BD431C800000F180408A +:1042B00000F5145051F8044B0460D8B2F1E700BF88 +:1042C000001002400070004007B5012201A9002043 +:1042D000FFF7C0FF019803B05DF804FB13B5044677 +:1042E000FFF7F2FFA04205D0012201A900200194AE +:1042F000FFF7C0FF02B010BD70470000704700001C +:1043000070470000074B45F255521A6002225A606E +:1043100040F6FF729A604CF6CC421A60024B0122C2 +:104320001A70704700300040803E0020034B1B781D +:104330001BB1034B4AF6AA221A607047803E002048 +:1043400000300040054B1A6832B902F1804202F594 +:104350000432D2F894201A60704700BF7C3E0020DF +:10436000024B4FF40002C3F8942070470010024043 +:1043700008B5FFF7E7FF024B1868C0F3407008BDAF +:104380007C3E002070470000FEE700000A4B0B480F +:104390000B4A90420BD30B4BDA1C121AC11E22F0AF +:1043A00003028B4238BF00220021FCF763BE53F8A2 +:1043B000041B40F8041BECE714490008043F0020EC +:1043C000043F0020043F00200023054A1946013322 +:1043D000102BC2E9001102F10802F8D1704700BFAA +:1043E000843E002008B5124B9A6D42F001029A6596 +:1043F0009A6F42F001029A670E4A9B6F936843F0EE +:10440000010393600620FFF751FA0B4BB0FBF3F06A +:104410004FF080434FF0FF3201389862DA62002299 +:104420009A615A63DA605A6001225A611A6008BDC3 +:1044300000100240002004E040420F004FF0804294 +:1044400008B51169D3680B40D9B2C9439B07116104 +:1044500007D5302383F31188FFF700FC002383F393 +:10446000118808BDFFF7BEBF4FF08043586A704700 +:104470004FF08043002258631A610222DA607047CD +:104480004FF080430022DA60704700004FF0804315 +:1044900058637047FEE7000070B51B4B01630025B1 +:1044A000044686B0586085620E46FFF79BF804F11B +:1044B0001003C4E904334FF0FF33C4E90635C4E9FF +:1044C0000044A560E562FFF7CFFF2B460246C4E932 +:1044D000082304F134010D4A256580232046FFF7A7 +:1044E000BFFB0123E0600A4A0375009272680192E3 +:1044F000B268CDE90223074B6846CDE90435FFF7E2 +:10450000D7FB06B070BD00BF603E00209C4700088E +:10451000A147000895440008024AD36A1843D062B4 +:10452000704700BF383C00204B6843608B68836055 +:10453000CB68C3600B6943614B6903628B6943625B +:104540000B6803607047000008B5204BDA6A42F040 +:104550007F02DA62DA6A22F07F02DA62DA6ADA6C01 +:1045600042F07F02DA64DA6E42F07F02DA66184ABD +:10457000DB6E11464FF09040FFF7D6FF02F11C01B1 +:1045800000F58060FFF7D0FF02F1380100F5806090 +:10459000FFF7CAFF02F1540100F58060FFF7C4FF86 +:1045A00002F1700100F58060FFF7BEFF02F18C019F +:1045B00000F58060FFF7B8FF02F1A80100F5806008 +:1045C000FFF7B2FFBDE80840FFF7F2B80010024065 +:1045D000A847000808B500F009F8FFF719FBBDE887 +:1045E0000840FFF7AFBE00007047000008B5FFF7B6 +:1045F000D7F8FFF7E9FEFFF7F7FFBDE80840FFF740 +:1046000031BF00000B460146184600F003B8000019 +:1046100000F00EB810B5054C13462CB10A46014601 +:104620000220AFF3008010BD2046FCE70000000030 +:10463000024B01461868FFF7C3BD00BF40110020C0 +:1046400010B501390244904201D1002005E0037801 +:1046500011F8014FA34201D0181B10BD0130F2E741 +:104660002DE9F041A3B1C91A17780144044603F1BA +:10467000FF3C8C42204601D9002009E00578BD426C +:1046800004F10104F5D10CEB0405D618A54201D1C3 +:10469000BDE8F08115F8018D16F801EDF045F5D073 +:1046A000E7E70000034611F8012B03F8012B002A6D +:1046B000F9D170476F72672E6172647570696C6FA3 +:1046C000742E48697465632D416972737065656401 +:1046D0000000000040A2E4F1646891060041A3E5F7 +:1046E000F2656992070000004261642043414E492F +:1046F0006661636520696E6465782E0000000000C5 +:1047000000000000B11D000869180008C524000859 +:10471000D91800081D190008051B0008E518000835 +:10472000A1180008A51800087D18000865180008E1 +:10473000C11A000889180008FD250008951800080E +:10474000951A000801040E05054B02020E05054BE3 +:1047500004010E05054B05010B04044B080106037B +:1047600003460000636C6B73776300000003000076 +:104770000000000000010000000001010300000033 +:104780002328310104070400010000006330000009 +:104790008C470008903C0020603E00206D61696EEF +:1047A0000069646C650000000010802A00000000B1 +:1047B000AAAAAAAA00000024BFFF0000000000006F +:1047C000009009000000000100000000AAAAAAAAA7 +:1047D00000000001FFFF00000000000000000000DA +:1047E0000000000000000000AAAAAAAA0000000021 +:1047F000FFFF0000000000000000000000000000BB +:1048000000000000AAAAAAAA00000000FFFF000002 +:104810000000000000000000000000000000000098 +:10482000AAAAAAAA00000000FFFF000000000000E2 +:10483000000000000000000000000000AAAAAAAAD0 +:1048400000000000FFFF000000000000000000006A +:104850000000000000000000AAAAAAAA00000000B0 +:10486000FFFF00000000000000000000000000004A +:104870001604000000000000009801000000000085 +:10488000FE2A0100D2040000006889096D8BB9027C +:1048900000B4C404006889090068890900688909AE +:1048A000006889090068890900688909000000001A +:1048B0004411002000000000000000000000000083 +:1048C00000000000000000000000000000000000E8 +:1048D00000000000000000000000000000000000D8 +:1048E00000000000000000000000000000000000C8 +:1048F00000000000000000000000000000000000B8 +:1049000000000000000000000000000000000000A7 +:0449100000000000A3 :00000001FF diff --git a/Tools/bootloaders/HitecMosaic_bl.bin b/Tools/bootloaders/HitecMosaic_bl.bin index 055e5bd818531e..435a304f49aa5d 100755 Binary files a/Tools/bootloaders/HitecMosaic_bl.bin and b/Tools/bootloaders/HitecMosaic_bl.bin differ diff --git a/Tools/bootloaders/HitecMosaic_bl.elf b/Tools/bootloaders/HitecMosaic_bl.elf index 3fe7c2f127917b..6ae0d4bffdf870 100755 Binary files a/Tools/bootloaders/HitecMosaic_bl.elf and b/Tools/bootloaders/HitecMosaic_bl.elf differ diff --git a/Tools/bootloaders/HitecMosaic_bl.hex b/Tools/bootloaders/HitecMosaic_bl.hex index 91872d56ef6c4e..224893272ad5a2 100644 --- a/Tools/bootloaders/HitecMosaic_bl.hex +++ b/Tools/bootloaders/HitecMosaic_bl.hex @@ -1,1217 +1,1172 @@ :020000040800F2 -:1000000000090020B5040008CD250008852500085A -:10001000AD25000885250008A5250008B7040008BF -:10002000B7040008B7040008B7040008C135000889 -:10003000B7040008B7040008B704000875430008B7 -:10004000B7040008B7040008B7040008B7040008A4 -:10005000B7040008B70400085940000885400008AC -:10006000B1400008DD40000809410008B70400085D -:10007000B7040008B7040008B7040008B704000874 -:10008000B7040008B7040008B704000839250008C1 -:100090006525000875250008B704000835410008EB -:1000A000B7040008B7040008B7040008B704000844 -:1000B000B7040008B7040008B7040008B704000834 -:1000C000B7040008B7040008B7040008B704000824 -:1000D000B7040008B7040008654500087945000822 -:1000E0009D410008B7040008B7040008B7040008E1 -:1000F000B7040008B7040008B7040008B7040008F4 -:10010000B7040008B7040008B7040008B7040008E3 -:10011000B7040008B7040008B7040008B7040008D3 -:10012000B7040008B7040008B7040008B7040008C3 -:10013000B7040008B7040008B7040008B7040008B3 -:10014000B7040008B7040008B7040008B7040008A3 -:10015000B7040008B7040008B7040008B704000893 -:10016000B7040008B7040008B7040008B704000883 -:10017000B7040008B7040008B7040008B704000873 -:10018000B7040008B7040008B7040008B704000863 -:10019000B7040008B7040008B7040008B704000853 -:1001A0002112000800000000000000000000000014 -:1001B00053B94AB9002908BF00281CBF4FF0FF31CE -:1001C0004FF0FF3000F074B9ADF1080C6DE904CECA -:1001D00000F006F8DDF804E0DDE9022304B0704722 -:1001E0002DE9F047089D04468E46002B4DD18A42EA -:1001F000944669D9B2FA82F252B101FA02F3C2F11D -:10020000200120FA01F10CFA02FC41EA030E9440AD -:100210004FEA1C48210CBEFBF8F61FFA8CF708FBCE -:1002200016E341EA034306FB07F199420AD91CEBA6 -:10023000030306F1FF3080F01F81994240F21C81D8 -:10024000023E63445B1AA4B2B3FBF8F008FB103320 -:1002500044EA034400FB07F7A7420AD91CEB040455 -:1002600000F1FF3380F00A81A74240F20781644425 -:10027000023840EA0640E41B00261DB1D4400023AA -:10028000C5E900433146BDE8F0878B4209D9002D0E -:1002900000F0EF800026C5E9000130463146BDE898 -:1002A000F087B3FA83F6002E4AD18B4202D3824202 -:1002B00000F2F980841A61EB030301209E46002DB1 -:1002C000E0D0C5E9004EDDE702B9FFDEB2FA82F206 -:1002D000002A40F09280A1EB0C014FEA1C471FFA64 -:1002E0008CFE0126200CB1FBF7F307FB131140EA4B -:1002F00001410EFB03F0884208D91CEB010103F118 -:10030000FF3802D2884200F2CB804346091AA4B2D9 -:10031000B1FBF7F007FB101144EA01440EFB00FEAD -:10032000A64508D91CEB040400F1FF3102D2A64512 -:1003300000F2BB800846A4EB0E0440EA03409CE7B1 -:10034000C6F12007B34022FA07FC4CEA030C20FA5E -:1003500007F401FA06F31C43F9404FEA1C4900FA7E -:1003600006F3B1FBF9F8200C1FFA8CFE09FB1811FB -:1003700040EA014108FB0EF0884202FA06F20BD96E -:100380001CEB010108F1FF3A80F08880884240F2BE -:100390008580A8F102086144091AA4B2B1FBF9F002 -:1003A00009FB101144EA014100FB0EFE8E4508D9FD -:1003B0001CEB010100F1FF346CD28E456AD9023882 -:1003C000614440EA0840A0FB0294A1EB0E01A14267 -:1003D000C846A64656D353D05DB1B3EB080261EBD5 -:1003E0000E0101FA07F722FA06F3F1401F43C5E9AF -:1003F000007100263146BDE8F087C2F12003D840E5 -:100400000CFA02FC21FA03F3914001434FEA1C4726 -:100410001FFA8CFEB3FBF7F007FB10360B0C43EA18 -:10042000064300FB0EF69E4204FA02F408D91CEBC8 -:10043000030300F1FF382FD29E422DD902386344C6 -:100440009B1B89B2B3FBF7F607FB163341EA034166 -:1004500006FB0EF38B4208D91CEB010106F1FF38B5 -:1004600016D28B4214D9023E6144C91A46EA0046AC -:1004700038E72E46284605E70646E3E61846F8E63E -:100480004B45A9D2B9EB020864EB0C0E0138A3E787 -:100490004646EAE7204694E74046D1E7D0467BE768 -:1004A000023B614432E7304609E76444023842E7E0 -:1004B000704700BF02E000F000F8FEE772B6374870 -:1004C00080F30888364880F3098836483649086042 -:1004D00040F20000CCF200004EF63471CEF2000182 -:1004E0000860BFF34F8FBFF36F8F40F20000C0F280 -:1004F000F0004EF68851CEF200010860BFF34F8F36 -:10050000BFF36F8F4FF00000E1EE100A4EF63C7122 -:10051000CEF200010860062080F31488BFF36F8FCD -:1005200003F04EFC03F0C2FC4FF055301F491B4A4C -:1005300091423CBF41F8040BFAE71D49184A914229 -:100540003CBF41F8040BFAE71A491B4A1B4B9A427D -:100550003EBF51F8040B42F8040BF8E7002018499D -:10056000184A91423CBF41F8040BFAE703F02CFC17 -:1005700003F0D8FC144C154DAC4203DA54F8041BBC -:100580008847F9E700F042F8114C124DAC4203DA0B -:1005900054F8041B8847F9E703F014BC0009002055 -:1005A000001100200000000808ED00E0000100201C -:1005B00000090020704B0008001100207C11002071 -:1005C00080110020583C0020A0010008A401000870 -:1005D000A4010008A40100082DE9F04F2DED108AB8 -:1005E000C1F80CD0C3689D46BDEC108ABDE8F08F01 -:1005F000002383F311882846A047002003F06AF9FE -:10060000FEE703F0CDF800DFFEE70000F8B500F0EC -:1006100019FE03F079FB074603F0C8FB05460028E6 -:1006200041D12D4B9F423ED001339F423ED02B4BB8 -:1006300027F0FF029A423CD1F8B200F03FFC2E4670 -:1006400042F2107400F040FC08B10024264601F08C -:10065000B1F890B3032000F045F80024264635B1E8 -:100660001F4B9F4203D003F099FB00242646002035 -:1006700003F054FB4FF090431B6913F0200322D08A -:100680000EB100F045F800F051FC00F0DDFD01F086 -:10069000A5FF0546CCB101F0A1FF401BA04214D933 -:1006A00000F036F8F3E72E460024CBE70446012697 -:1006B000C8E706464FF47A74C4E7002CCFD04FF455 -:1006C0007A740126CBE71C46DDE700F077FC0120B9 -:1006D00003F006F9DEE700BF010007B0000008B034 -:1006E000263A09B0084B187003280CD8DFE800F050 -:1006F00008050208022000F003BE022000F0F8BD49 -:10070000024B00225A6070478011002084110020A3 -:1007100038B501F04FF830B11F4B03221A701F4B50 -:1007200000225A6038BD1E4B1E4A19680131F9D0AB -:1007300004339342F9D11C4C194DD4F80428AA4231 -:10074000F0D31A4B9B6803F1006303F5D0439A4240 -:10075000E8D203F0F7FA03F009FB002000F08EFD69 -:100760000220FFF7BFFF124BDA690022DA61D96974 -:1007700099699A619B6972B64FF0E0233021C3F802 -:10078000085DD4F80038D4F8042881F311889D4618 -:1007900083F308881047C5E78011002084110020EA -:1007A00000680008206800080060000800110020B0 -:1007B00000100240094A136849F2690099B21B0C03 -:1007C00000FB01331360064B186844F2506182B29B -:1007D000000C01FB0200186080B270471411002069 -:1007E0001011002010B500211022044600F0A2FDD7 -:1007F000034B03CB206061601868A06010BD00BF90 -:10080000ACF7FF1F2DE9F041ADF54E7D0DF1340839 -:100810006CAC40F2751207460D460EA80021C8F8D0 -:10082000001000F087FD4FF4C4720021204600F054 -:1008300081FD01F0D3FE254B4FF47A72B0FBF2F04C -:10084000186093E80700022384E807000DF5E970BB -:100850002382FFF7C7FF4FF603031D49238406A831 -:1008600004F0B6F8192384F832310DF2E32206AB16 -:100870000DF1300C1E4603CE6645106051603346C4 -:1008800002F10802F6D13378137041460122204666 -:1008900000F09CFD00230393AB7E029305F1190346 -:1008A000019380B20123CDE904800093E97E05A382 -:1008B000D3E90023384602F059FA0DF54E7DBDE824 -:1008C000F08100BF9E6AC421818A46EE8C1100200F -:1008D000E04900082DE9F0412C4C237ADAB080463B -:1008E0000D465BBB27A9284600F080FE074600287E -:1008F00042D19DF89D60C82E3ED801464FF4A662B5 -:10090000204600F017FD4FF48073C4F8F8314FF41F -:100910000073C4F80C334FF44073C4F820343246EB -:100920000DF19E0104F1090000F0F2FC26449DF84F -:100930009C30777223720BB9EB7E237281220021E7 -:1009400006AC27A800F0F6FC0122214627A800F0FB -:1009500089FE00230393AB7E029305F1190380B255 -:1009600001932823CDE904400093E97E05A3D3E950 -:100970000023404602F0FAF95AB0BDE8F08100BF0A -:10098000AFF3008026417272DF25D7B7A83200206E -:10099000F0B5254E4FF48A7505FB0065F1B096F869 -:1009A000D83085F8DC300024D822214685F8E8408C -:1009B0003AA800F0BFFC06F1090000F0B3FCD5F83E -:1009C000E4308DF8F000C2B206AF06F109010DF176 -:1009D000F100CDE93A3400F09BFC394601223AA8F7 -:1009E00000F06CFE80B2CDE9047008230127CDE948 -:1009F000023706F1D803019330230093317A0B4874 -:100A000007A3D3E9002302F0B1F9A04206DD01F00B -:100A1000E5FDC5F8E000384671B0F0BD2046FBE7C3 -:100A200078F6339F93CACD8DA8320020A4210020F0 -:100A30002DE9F0411D4D1E4E1E4F86B0284602F096 -:100A4000C1F9034658B30024CDE90344ADF814407E -:100A5000027B8DF8142099684068029403AA03C2AF -:100A60001B68DFF8548043F00043029301F0B8FDA7 -:100A7000821941F10003009402A9384601F07CF884 -:100A8000A04205DD284602F0A1F988F80040D5E72C -:100A900098F80030072B05D8013388F8003006B0ED -:100AA000BDE8F081014802F091F9F8E7A4210020A7 -:100AB00040420F00D8210020DD37002070B50D46E0 -:100AC00014461E4602F0AEF850B9022E10D1012C89 -:100AD0000ED112A3D3E90023C5E90023012007E0CA -:100AE000282C10D005D8012C09D0052C0FD00020BF -:100AF00070BD302CFBD10BA3D3E90023ECE70BA393 -:100B0000D3E90023E8E70BA3D3E90023E4E70BA331 -:100B1000D3E90023E0E700BFAFF30080401DA12030 -:100B200026812A0B78F6339F93CACD8D9E6AC42105 -:100B3000818A46EE26417272DF25D7B7F017304A18 -:100B400039059E5638B505460E4C0021013500F09A -:100B5000B7FBA4F82C55B4F82C0500F099FB78B13C -:100B6000B4F82C0500F0A4FB014648B9B4F82C05F4 -:100B700000F0A6FBB4F82C350133A4F82C35EAE7D5 -:100B800038BD00BFA832002010B50A4B0A4A1A60CF -:100B900003F5805393F860203AB9DC6D2CB1204600 -:100BA00000F082FE204603F053FEBDE810400348EB -:100BB00000F07ABED8210020384A000820320020F8 -:100BC0002DE9F04F8FB000AF05460C4602F02AF831 -:100BD000002849D1237E022B1BD1E38A012B18D197 -:100BE00001F0FCFC0646FFF7E5FD03464FF4C87034 -:100BF000DFF8C482B3FBF0F206F5167602FB103381 -:100C000016FA83F3C8F80030E37E33B9A34B002211 -:100C10001A703C37BD46BDE8F08F07F1240120462D -:100C200000F0A2FC0028F4D107F11400FFF7DAFD70 -:100C300097F8264007F11401224607F1270003F038 -:100C400051FE0028E2D10F2C08D8944B1C70D8F824 -:100C50000030A3F51673C8F80030DAE797F82410CF -:100C6000284601F0D7FFD4E7E38A282B2BD010D8F1 -:100C7000012B23D0052BCCD1BFF34F8F8849894B53 -:100C8000CA6802F4E0621343CB60BFF34F8F00BF2A -:100C9000FDE7302BBDD1844EE17E327A9142B8D14E -:100CA000607E3146002291F8DC50854200F0A5803C -:100CB0000132042A01F58A71F5D1AAE721462846B6 -:100CC000FFF7A0FDA5E721462846FFF703FEA0E7B2 -:100CD000B2F8EC507B6005F103094FEA99094FEA3D -:100CE0008902D11DC908A8EBC1039D46EB4600212E -:100CF000584600F01FFB04F1EE012A4631445846E5 -:100D000000F006FB7B6813B9012000F0B7FA96F8F3 -:100D1000D20000F0BDFA044630B9307200F0D8FAC3 -:100D2000204600F0ABFAB1E0D6F8D4203AB996F8F4 -:100D3000D200B6F82C25824201D8FFF703FFD6F87F -:100D4000D4202A44944208D296F8D200B6F82C2532 -:100D50000130824201D8FFF7F5FE70685FFA89F230 -:100D6000594600F0EFFA08B9C54679E0726896F87E -:100D7000D2002A447260D6F8D42005EB0209C6F8E6 -:100D8000D49000F085FA814509D396F8D220D6F8A0 -:100D9000D4000132001B86F8D220C6F8D400FF2D03 -:100DA0000FD80024347200F093FA204600F066FA5F -:100DB00000F000FD3D4B188108B9FFF7A9FCC546BE -:100DC00027E7BB6896F8D9000AFB0362FB68D2F8F4 -:100DD000E41082F8E83001F58061C2F8E030C2F832 -:100DE000E410FFF7D5FDFFF723FE96F8D920013276 -:100DF00002F0030286F8D920B6E74FF48A7A0AFB9C -:100E000002F505F1EA013144204600F083FCF86068 -:100E100000287FF4FEAE3544012285F8E82001F079 -:100E2000DDFBD5F8E020D6ED007ADFED216A801AEF -:100E3000192838BF192040F6B832904228BF104612 -:100E4000B8EE677A07EE900AF8EEE77A67EEA67AD0 -:100E5000DFED186AE7EE267AFCEEE77AC6ED007A57 -:100E600096F8D930BB60BA6873680AFB02F432198D -:100E700092F8E81059B1D2F8E4108B42E8463FF4FA -:100E800027AF002182F8E810C2F8E010C546736869 -:100E9000064A9B0A01331381BBE600BF9D21002057 -:100EA00000ED00E00400FA05A83200208C110020BB -:100EB000CDCCCC3D6666663FA0210020014B18706A -:100EC000704700BF9811002038B54FF00054134B05 -:100ED00022689A4220D1124B627D12481A70237DFB -:100EE00003724FF48073C0F8F8314FF40073C0F808 -:100EF0000C3300254FF44073C0F820340A49C0F881 -:100F0000E450C922093000F003FAE02229462046C5 -:100F100000F010FA012038BD0020FCE79AAD44C56E -:100F200098110020A83200201600002037B500F0EC -:100F300041FC194D194928810223012218486B717F -:100F400001F0EAF900230193164B17490093174863 -:100F5000174B4FF4805201F035FE164B197811B142 -:100F6000124801F057FE01F039FB0446FFF722FC5E -:100F70004FF4C873B0FBF3F202FB130304F51670D1 -:100F800010FA83F00C4B186002F010FF08B10F2329 -:100F90002B8103B030BD00BF8C11002040420F00F8 -:100FA000D8210020BD0A00089C110020A4210020A7 -:100FB000C10B000898110020A02100202DE9F04F5E -:100FC0002DED028B8EA7D7E900670FF23C29D9E9F6 -:100FD0000089864C95B00DAD9FED828BFFF728FD03 -:100FE000DFF82CB200230C93ADF83C300D936B600E -:100FF00000230DF125028DED008B4FF0010A09A9A8 -:1010000058468DF825308DF824A001F035F99DF86B -:1010100024200023002A40F0AB80204601F002FE8D -:101020000546002847D1DFF8ECB101F0D7FADBF82C -:10103000003098423FD301F0D1FA0790FFF7BAFB96 -:10104000079A4FF4C873B0FBF3F101FB130302F5E9 -:10105000167010FA83F0CBF80000DFF8BCB19BF8F3 -:1010600000100791002914BF2B46534610A88DF895 -:101070003030FFF7B7FB0799C1F11002D2B2062A50 -:1010800010AB28BF062219440DF13100079200F081 -:101090003FF9079A0CAB0393182302930132544B88 -:1010A000D2B2CDE900A304923B463246204601F07D -:1010B000FFFD8BF8005001F091FA4E4A4E4D136837 -:1010C000C31AB3F57A7F32D3106001F089FA024671 -:1010D0000B46204601F084FE204601F0A3FD30B30C -:1010E0002B7ADFF838A1002B14BF032302238AF8E0 -:1010F000053001F073FA0DF1400B4FF47A730122C1 -:10110000B0FBF3F05946CAF80000504600F004FA6C -:1011100018230293394B019380B240F25513CDE965 -:1011200003B0009342464B46204601F0C1FD2B7AA6 -:10113000CBB101F053FA4FF0000A83464FF48A72A4 -:1011400095F8D900504400F0030002FB005393F8D7 -:10115000E81089B30AF1010ABAF1040FF0D12B7A31 -:10116000002B7FF438AF15B0BDEC028BBDE8F08FDB -:101170004FF0904110A84A6982F040024A61194636 -:10118000102200F0D7F80DF126030AAA0CA9584640 -:1011900000F0F0FD95E8030011AB83E803009DF833 -:1011A0003C308DF84C300C9B109310A9DDE90A23DC -:1011B000204601F0E9FF1BE7D3F8E01049B12B68A6 -:1011C000FA2B38BFFA23ABEB01010533B1EB430F28 -:1011D000C0D3FFF7DDFB4FF48A720028BAD1BEE717 -:1011E000AFF300800000000000000000A4210020F8 -:1011F0009C210020D8370020A8320020DC370020B6 -:10120000401DA12026812A0BF1C6A7C1D068080F76 -:10121000D8210020A02100209D2100208C11002039 -:1012200008B5054800F040FEBDE80840034A0449FF -:10123000002003F007BB00BFD82100201838002091 -:10124000890B00087047000070B502F013FC094ECE -:10125000094D3080002428683388834208D902F081 -:1012600005FC2B6804440133B4F5D04F2B60F2D356 -:1012700070BD00BF0C380020E037002002F086BCB3 -:1012800000F10060920000F5D04002F02DBC00009B -:10129000054B1A68054B1B889B1A834202D91044E0 -:1012A00002F0E4BB00207047E03700200C3800203B -:1012B000024B1B68184402F0DFBB00BFE037002080 -:1012C000024B1B68184402F0E9BB00BFE037002066 -:1012D000064991F8243033B10023086A81F824309C -:1012E0000822FFF7CDBF0120704700BFE437002080 -:1012F000022802BF4FF0904340229A6170470000DD -:10130000022802BF4FF090434FF480029A61704769 -:1013100010B50023934203D0CC5CC4540133F9E7E9 -:1013200010BD000003460246D01A12F9011B002925 -:10133000FAD1704702440346934202D003F8011BDE -:10134000FAE770472DE9F8431F4D144695F824201D -:101350000746884652BBDFF870909CB395F824305E -:101360002BB92022FF2148462F62FFF7E3FF95F8B3 -:101370002400C0F10802A24228BF2246D6B241464C -:10138000920005EB8000FFF7C3FF95F82430A41B03 -:101390001E44F6B2082E17449044E4B285F8246047 -:1013A000DBD1FFF795FF0028D7D108E02B6A03EBCC -:1013B00082038342CFD0FFF78BFF0028CBD10020E0 -:1013C000BDE8F8830120FBE7E43700202DE9F04772 -:1013D0000D46044600219046284640F27912FFF758 -:1013E000A9FF234620220021284601F06FFE231D7D -:1013F00002222021284601F069FE631D03222221DA -:10140000284601F063FEA31D03222521284601F092 -:101410005DFE04F1080310222821284601F056FE43 -:1014200004F1100308223821284601F04FFE04F190 -:10143000110308224021284601F048FE04F112035E -:1014400008224821284601F041FE04F1140320221D -:101450005021284601F03AFE04F118034022702181 -:10146000284601F033FE04F120030822B02128466B -:1014700001F02CFE04F121030822B821284601F0D6 -:1014800025FE04F12207C0263B46314608222846A5 -:10149000083601F01BFEB6F5A07F07F10107F3D176 -:1014A00004F1320308223146284601F00FFE0027DE -:1014B00004F1330A94F832304FEAC7099F4209F524 -:1014C000A47615D3B8F1000F08D1314604F599730D -:1014D0000722284601F0FAFD09F24F16274694F834 -:1014E00032213B1B93420CD3F01DC008BDE8F087AE -:1014F0000AEB070308223146284601F0E7FD0137D1 -:10150000D8E707F2331331460822284601F0DEFD02 -:1015100008360137E3E7000013B50446084600210A -:1015200001602346C0F803102022019001F0CEFD97 -:101530000198231D0222202101F0C8FD0198631D9E -:101540000322222101F0C2FD0198A31D03222521BF -:1015500001F0BCFD019804F108031022282101F0DC -:10156000B5FD072002B010BDF7B50023047F009140 -:101570000E4607221946054601F06CFC731C0093C9 -:10158000012200230721284601F064FCC4B9B31CE2 -:101590000093052223460821284601F05BFC0D2418 -:1015A0003746B278BB1B934211D32B7FA88A0734EE -:1015B000E408BBB9844294BF0020012003B0F0BD11 -:1015C000AB8ADB00083BDB08B3700824E8E7FB1CB0 -:1015D0000093214600230822284601F03BFC0834F2 -:1015E0000137DEE7201A18BF0120E7E7F7B500232F -:1015F000047F00910E4608221946054601F02AFC98 -:10160000731CC4B90822009311462346284601F0F2 -:1016100021FC1024012372785F1C013B934211D3FB -:101620002B7FA88A0734E408BBB9844294BF00200A -:10163000012003B0F0BDAB8ADB00083BDB08737010 -:101640000824E7E7F31900932146002308222846DF -:1016500001F000FC08343B46DDE7201A18BF0120EA -:10166000E7E70000F8B50E46054614460021812242 -:101670003046FFF75FFE2B4608220021304601F07E -:1016800025FD7CB96B1C07220821304601F01EFDA8 -:101690000F2401236A785F1C013B934204D3E01DB1 -:1016A000C008F8BD0824F4E7EB19214608223046AB -:1016B00001F00CFD08343B46ECE70000F8B50E469F -:1016C000054614460021CE223046FFF733FE2B4656 -:1016D00028220021304601F0F9FC7CB905F108030D -:1016E00008222821304601F0F1FC30242F462A7AC6 -:1016F0007B1B934204D3E01DC008F8BD2824F5E706 -:1017000007F1090321460822304601F0DFFC0834C6 -:101710000137ECE7F7B5047F00910E460123102254 -:101720000021054601F096FBC4B9B31C00930922C1 -:1017300023461021284601F08DFB19243746728874 -:10174000BB1B9A4211D82B7FA88A0734E408BBB987 -:10175000844294BF0020012003B0F0BDAB8ADB00BF -:10176000103BDB0873801024E8E73B1D0093214603 -:1017700000230822284601F06DFB08340137DEE71C -:10178000201A18BF0120E7E730B5094D0A449142FD -:101790000DD011F8013B5840082340F30004013BF1 -:1017A0002C4013F0FF0384EA5000F6D1EFE730BD80 -:1017B0002083B8EDF7B5364A106851686B4603C30D -:1017C0006A4634493448082303F09CF8044690BB29 -:1017D0000A25324A106851686B4603C36A4630498D -:1017E0002D48082303F08EF80446002847D00369EB -:1017F000B3F5663F43D8B0F86620B2F57E7F3ED1A0 -:10180000284A024402F15C018B4238D35C3B2249F6 -:1018100000209E1AFFF7B8FF3246074604F1640124 -:101820000020FFF7B1FFA3689F4228D1E3689842E8 -:1018300008BF002523E00369B3F5663F26D8428B35 -:10184000B2F57E7F20D1174A024402F110018B428B -:1018500018D3103B104900209D1AFFF795FF2A4628 -:10186000064604F118010020FFF78EFFA3689E4290 -:1018700002D1E368984201D00D25AAE70025284649 -:1018800003B0F0BD1025A4E70C25A2E70B25A0E7C7 -:10189000FC490008DC97030000680008054A0008BE -:1018A000909703000898FFF710B5037C044613B91E -:1018B000006803F00FF8204610BD00000023BFF3BE -:1018C0005B8FC360BFF35B8FBFF35B8F8360BFF33E -:1018D0005B8F7047BFF35B8F0068BFF35B8F704710 -:1018E00070B505460C30FFF7F5FF05F10806044614 -:1018F0003046FFF7EFFFA04206D930466D68FFF78C -:10190000E9FF2544281A70BD3046FFF7E3FF201A8F -:10191000F9E7000070B50546406898B105F1080088 -:10192000FFF7D8FF05F10C0604463046FFF7D2FF5B -:101930008442304694BF6D680025FFF7CBFF013C21 -:101940002C44201A70BD000038B50C460546FFF740 -:10195000C7FFA04210D305F10800FFF7BBFF044406 -:101960006868B4FBF0F100FB1144BFF35B8F01200A -:10197000AC60BFF35B8F38BD0020FCE72DE9F04180 -:10198000144607460D46FFF7C5FF844228BF0446AC -:10199000D4B1B84658F80C6B4046FFF79BFF304473 -:1019A000286040467E68FFF795FF331A9C4203D8B3 -:1019B0006C600120BDE8F0816B60A41B3B68AB60EC -:1019C0002044E8600220F5E72046F3E738B50C46EE -:1019D0000546FFF79FFFA04210D305F10C00FFF76B -:1019E00079FF04446868B4FBF0F100FB1144BFF3D5 -:1019F0005B8F0120EC60BFF35B8F38BD0020FCE7FC -:101A00002DE9FF41884669460746FFF7B7FF6C4658 -:101A100006B204EBC6060025B44209D0626820680D -:101A200008EB0501FFF774FC636808341D44F3E715 -:101A300029463846FFF7CAFF284604B0BDE8F081C2 -:101A4000F8B505460C300F46FFF744FF05F10806D0 -:101A500004463046FFF73EFFA042304688BF6C6820 -:101A6000FFF738FF201A386020B130462C68FFF7A6 -:101A700031FF2044F8BD000073B5144606460D46FC -:101A8000FFF72EFF844228BF04460190DCB101A974 -:101A90003046FFF7D5FF019B33B93268C5E9023301 -:101AA000C5E9002401200CE09C4238BF0194286065 -:101AB000019868608442F5D93368AB60241AEC6001 -:101AC000022002B070BD2046FBE700002DE9FF4177 -:101AD0000F466946FFF7D0FF6C4600B204EBC00525 -:101AE0000026AC4209D0D4F8048054F8081BB81979 -:101AF0004246FFF70DFC4644F3E7304604B0BDE82C -:101B0000F081000038B50546FFF7E0FF04460146C6 -:101B10002846FFF719FF204638BD0000302383F325 -:101B2000118862B670470000002383F3118862B603 -:101B30007047000010B4026854681A4623465DF8E6 -:101B4000044B184701207047002070470020704761 -:101B500070470000002070470E20704700F580504D -:101B600090F8C800C0F340007047000000F58050B6 -:101B700090F9C90070470000F7B50C68BDF82070F7 -:101B800014F000541E466FD10B7B082B6CD8FFF766 -:101B9000C5FF4569AB685B010CD4AB681B0108D479 -:101BA000AC6814F080545DD1FFF7BEFF204603B04F -:101BB000F0BD01240B6804F1180C002BB8BFDB004A -:101BC0004FEA0C1CB4BF43F004035B0545F80C302E -:101BD0000B680FFA84FC13F0804F18BF05EB0C1E46 -:101BE00005EB0C1C1EBFDEF8803143F00203CEF87B -:101BF00080310B7BCCF8843105EB04158B68C5F87C -:101C00008C314B68C5F88831DCF8803143F0010332 -:101C1000CCF8803100EB441541F268031D4403EB1E -:101C200044130344C5E9002608330D4601F10C0CAA -:101C300055F804EB43F804EB6545F9D184342D885D -:101C40001D8000EB441407F00303257925F00B05F4 -:101C50002B432371FFF768FF0097334600F0E0FC49 -:101C60000120A4E70224A5E74FF0FF309FE7000022 -:101C700013B500F580540191E06DFFF74BFE1F286E -:101C80000AD90199E06D2022FFF7BAFEA0F12003E6 -:101C90005842584102B010BD0020FBE708B500F5DE -:101CA0008050FFF73BFFC06DFFF708FEBDE808401E -:101CB000FFF73ABF00220260828142608260704773 -:101CC00010B500220023C0E900230023044603814D -:101CD0000C30FFF7EFFF204610BD0000F0B50546C1 -:101CE00000F580500C4690F8C83013F0040FC3F391 -:101CF000800108BF114661F3820304F1840680F875 -:101D0000C83005EB461389B01B79D8072ED57AB3B6 -:101D100019072DD46846FFF7D3FF05EB441303F5ED -:101D2000835303F1180703AA10331868596814463F -:101D300003C40833BB422246F7D1186820609B8851 -:101D4000A380DDE90E23CDE900230123ADF808309F -:101D50002B686946DB6B2846984705EB46152B79BF -:101D60001A075CBF43F008032B7101E0002AF4D18D -:101D700009B0F0BD2DE9F047074688B007F580545B -:101D800068469A468846FFF7C9FE9146FFF798FFD6 -:101D9000E06DFFF7A5FD1F2829D9E06D20226946D7 -:101DA000FFF7B0FE202822D103AD444605AB2E46F6 -:101DB00003CE9E4220606160354604F10804F6D1EE -:101DC00030682060B388A380DDE90023C9E90023DF -:101DD000BDF80830AAF80030FFF7A6FE4A46534681 -:101DE0004146384608B0BDE8F04700F007BCFFF7B1 -:101DF0009BFE002008B0BDE8F08700002DE9F84FF9 -:101E00000023C0E90133254B044640F8183B0F4638 -:101E1000FFF750FF04F12800FFF752FF04F14808D4 -:101E200004F582554646083530462036FFF748FF10 -:101E3000AE42F9D104F580554FF480534FF00009BC -:101E4000C5E91339C5F848800123EE6504F58758C4 -:101E500004F58456C5F8549085F8583085F86030FC -:101E6000083608F108084FF0000A4FF0000B46E969 -:101E700008ABA6F11800FFF71DFF203646F8289C96 -:101E80004645F4D185F8C97017B1054800F0A0FBAC -:101E9000044B63612046BDE8F88F00BF384A000854 -:101EA000104A00080064004010B5044B197804463D -:101EB0004A1C1A70FFF7A2FF204610BD14380020FC -:101EC0002DE9F047002950D0294B2A4FB7FBF1F5F7 -:101ED00099428CBF0A231123581EB5FBF3FC03FB68 -:101EE0001C53C4B22BB102280346F5D80020BDE82C -:101EF000F0870CF1FF36B6F5806FF7D2C4EBC40E55 -:101F00000EF103034FEAE309C3F3C703A4EB03088D -:101F100009F1010A4FF47A755FFA88F009FB05555B -:101F20005AFA88F8B5FBF8F5B5F5617FC1BF0EF137 -:101F3000FF33C3F3C703E01AC0B25C1C50FA84F449 -:101F40000CFB04F4B7FBF4F4A142CFD1013BDBB2AC -:101F50000F2BCBD80138C0B20728C7D80021107189 -:101F600016809170D3700120C1E70846BFE700BF1B -:101F70003F420F000051250270B505460E464FF452 -:101F80007A746B695B6803F00103B3424FF00100A0 -:101F900004D001F0A5FC013CF3D1204670BD000047 -:101FA00030B54269936913F0700F16D000230B4CC3 -:101FB000936103F1840200EB421211794D0709D5B8 -:101FC000890707D5416954F823508D60117941F094 -:101FD000040111710133032BEBD130BD244A0008F9 -:101FE00073B51D46436916469A68D207044609D55B -:101FF0009A6801219960C2F34002CDE90065002191 -:10200000FFF76CFE63699A68D1050BD59A684FF4A7 -:1020100080719960C2F34022CDE90065012120461C -:10202000FFF75CFE63699A68D2030BD59A684FF498 -:1020300080319960C2F34042CDE90065022120461B -:10204000FFF74CFE204602B0BDE87040FFF7A8BF86 -:10205000F8B50446466900296CD106F10C073868CA -:1020600080076AD006EB01153868D5F8B00110F08A -:10207000040FD5F8B0011ABFC00840F00040400D71 -:10208000A061D5F8B0C11CF0020F1CBF40F0804029 -:10209000A061D5F8B40106EB011100F00F0084F83F -:1020A0002400D1F8B8012077D1F8B801000A607790 -:1020B000D1F8B801000CA077D1F8B801000EE07794 -:1020C000D1F8BC0184F82000D1F8BC01000A84F8E2 -:1020D0002100D1F8BC01000C84F82200D1F8BC1119 -:1020E000090E84F823103821396004F1340004F11A -:1020F000180104F1240551F8046B40F8046BA9425F -:10210000F9D109880180C4E90A23214600232386E6 -:1021100051F8283B2046DB6B984704F58052204657 -:1021200092F8C83043F0040382F8C830BDE8F840A4 -:10213000FFF736BF06F1100791E7F8BD10B504466A -:1021400000F04EFA02460B4652EA030102D0013A71 -:1021500063F100030449086820B12146BDE810403E -:10216000FFF776BF10BD00BF10380020F8B500F5AE -:1021700083511E46FFF7D2FCDFF844C0083100242B -:1021800004F1840500EB45152B795F070ED4DB06BF -:102190000CD5D1E900739742B34107D243695CF88B -:1021A00024709F602B7943F004032B710134032CBE -:1021B00001F12001E4D1BDE8F840FFF7B5BC00BF54 -:1021C000244A000808B5FFF7A9FCFFF7E9FEBDE8BF -:1021D0000840FFF7A9BC0000F8B5436905469868B8 -:1021E00000F0E050B0F1E05F0F461FD0E8B1FFF71C -:1021F00095FC05F583541034002606F1840305EBA5 -:1022000043131B791A0706D50136032E04F1200467 -:10221000F3D1012007E05B07F6D42146384600F0F1 -:1022200039FA0028F0D1FFF77FFCF8BD0120FCE768 -:1022300000F5805008B5FFF771FCC06DFFF750FB4B -:10224000FFF772FC43090CBF0120002008BD00000D -:10225000F8B51D46002313700F4606461446FFF7D7 -:10226000E7FF80F00100387025B129463046FFF7BE -:10227000B3FF2070F8BD00002DE9B8410C461546AB -:102280001F46804600F0ACF90B462178024609B99A -:10229000287850B14046FFF769FFFFF793FF3B46B0 -:1022A0002A462146FFF7D4FF0120BDE8B88100008F -:1022B00010B5FFF733FC174BDA6942F00072DA61B0 -:1022C0001A6942F000721A611A6900F5805422F00E -:1022D00000721A61FFF728FC94F8C830DB0718D4A5 -:1022E000B9B103211320FFF719FC01F0C7F903214D -:1022F000142001F0C3F90321152001F0BFF994F86F -:10230000C83043F0010384F8C830BDE81040FFF73F -:102310000BBC10BD001002402DE9F04700F58055C0 -:1023200088B095F8C930012B0446884616467FD8F8 -:10233000804F57F823200AB947F82300D7F800A0A8 -:10234000C4F80C802674BAF1000F63D095F8C93038 -:10235000012B6FD001212046FFF7AAFFFFF7DEFB1C -:102360006269136823F0020313606269136843F023 -:1023700001031360636900275F6101212046FFF7B5 -:10238000D3FBFFF7F9FD002800F09580E86DFFF71B -:1023900095FA04F58359BA4609F10809202200216B -:1023A0006846FEF7C7FF02A8FFF784FCCDF818A027 -:1023B0006A4609EB07030DF1180E9446BCE80300CA -:1023C000F44518605960624603F10803F5D1DCF862 -:1023D0000000186020379CF804201A71602FDDD1AE -:1023E00095F8C8306FF38203002785F8C8306A4635 -:1023F00041462046ADF80070ADF802708DF80470CB -:10240000FFF75EFD636948BB4FF400421A6008B0F5 -:10241000BDE8F08741F2D00002F01CFA814610B10D -:102420005146FFF7EBFCC7F80090B9F1000F8DD1D2 -:102430000020ECE7386803681B6B984701460028CA -:1024400088D13868FFF734FF3868036832465B6824 -:102450004146984700287FF47DAFE9E761221A6082 -:102460009DF802309DF803201B06120402F470222E -:1024700003F040731343BDF80020C2F30902134375 -:102480009DF804201205022E02F4E0020CBF4FF06A -:1024900000410021134362690B43D3616369132236 -:1024A0005A616269136823F00103136039462046BC -:1024B000FFF762FD08B96369A6E795F8C93093BBD9 -:1024C0006169D1F8002242F00102C1F8002261697D -:1024D000D1F8002222F47C5222F00E02C1F8002230 -:1024E0006169D1F8002242F46062C1F80022626999 -:1024F000C2F814326269C2F80432626941F6FF71AF -:10250000C2F80C126269C2F840326269C2F8443201 -:1025100063690122C3F81C226269D2F8003223F0F9 -:102520000103C2F8003295F8C83043F0020385F881 -:10253000C8306CE71038002008B500F051F850EAB8 -:102540000103024602D0421E61F10001044B1868EB -:1025500010B10B46FFF744FDBDE8084001F064B838 -:102560001038002008B50020FFF7E8FDBDE808405E -:1025700001F05AB808B50120FFF7E0FDBDE80840BA -:1025800001F052B800B59BB0EFF3098168226846AC -:10259000FEF7BEFEEFF30583014B9B6BFEE700BF2A -:1025A00000ED00E008B5FFF7EDFF000000B59BB0BF -:1025B000EFF3098168226846FEF7AAFEEFF3058370 -:1025C000014B5B6BFEE700BF00ED00E0FEE70000A3 -:1025D0000FB408B5029801F019F9FEE701F02EBB1F -:1025E00001F004BB13B56C4684E80600031D94E8B3 -:1025F000030083E80500012002B010BD73B58568B3 -:10260000019155B11B885B0707D4D0E900369B6B5D -:102610009847019AC1B23046A847012002B070BD68 -:10262000F0B5866889B005460C465EB1BDF8383015 -:102630005B070AD4D0E900379B6B98472246C1B2AA -:102640003846B047012009B0F0BD00220023CDE993 -:1026500000230023ADF808300A4603AB01F1080659 -:10266000106851681C4603C40832B2422346F7D1B1 -:10267000106820609288A280FFF7B2FF0423ADF8B3 -:1026800008302B68CDE90001DB6B69462846984786 -:10269000D8E7000030B503680968DD0FB5EBD17FDE -:1026A00023F0604421F060424FEAD1700BD0002B40 -:1026B000B8BFA40C0029B8BF920C944202D034BF1A -:1026C0000120002030BD944205D1C1F38070C3F3D6 -:1026D00080738342F6D194422CBF00200120F1E7A1 -:1026E0002DE9F041456A15B94162BDE8F0814B68BA -:1026F00023F06047C3F38A464FEAD37EC3F3807862 -:1027000016EA230638BF3E46AC462B465A68BEEB57 -:10271000D27F22F060440AD0002A18DAA40CB44216 -:1027200017D19D420FD10D60DEE71346EEE7A742B9 -:1027300007D102F08044C2F3807242450BD054B1FD -:10274000EFE708D2EDE7CCF800100B60CDE7B4421C -:1027500001D0B442E5D81A689C46002AE5D1196038 -:10276000C3E700002DE9F047089D01F007044FEA98 -:10277000D508224405F0070500EBD1004FF47F494E -:10278000944201D1BDE8F08704F0070705F0070A7D -:1027900057453E4638BF5646C6F10806111B8E42C5 -:1027A00028BF0E46E10808EBD50E415C13F80EC0B9 -:1027B000B94029FA06F721FA0AF1FFB28CEA0101C1 -:1027C00047FA0AF739408CEA010C03F80EC034448A -:1027D0003544D5E780EA0120082341F2210201B205 -:1027E0004000002980B203F1FF33B8BF504013F01E -:1027F000FF03F4D17047000038B50C468D18A54290 -:1028000000D138BD14F8011BFFF7E4FFF7E7000023 -:1028100042684AB1136843604389818901339BB29E -:102820009942438138BF83811046704770B588B0A4 -:10283000202204460D4668460021FEF77BFD204617 -:102840000495FFF7E5FF024658B16B46054608AE12 -:102850001C4603CCB44228606960234605F1080594 -:10286000F6D1104608B070BD082817D909280CD039 -:102870000A280CD00B280CD00C280CD00D280CD01A -:102880000E2814BF4020302070470C2070471020C5 -:1028900070471420704718207047202070470000B0 -:1028A000082817D90C280CD910280CD914280CD9B1 -:1028B00018280CD920280CD930288CBF0F200E20C6 -:1028C0007047092070470A2070470B2070470C2082 -:1028D00070470D20704700002DE9F843078C072F43 -:1028E00004461ED9D0E9029800254FF6FF73C5F1C2 -:1028F0002006A5F1200029FA05F108FA06F628FAC3 -:1029000000F031430143C9B21846FFF763FF0835B1 -:10291000402D0346EBD1E1693A46BDE8F843FFF7A5 -:102920006BBF4FF6FF70BDE8F883000010B54B6831 -:1029300023B9CA8A63F30902CA8210BD04691A68FE -:102940001C600361C38A013BC3824A60EFE7000059 -:102950002DE9F84F1D46CB8A0F46C3F3090105291F -:10296000814692460B4630D00020AAB207F11A04E5 -:102970009EB2042E1FFA80F80FD8904503F1010390 -:1029800006D3FB8A0A4462F30903FB8201201AE0A2 -:102990001AF80060E6540130EAE79045F1D2A1F15F -:1029A000050B1C237C68BBFBF3F203FB12BB1FFA75 -:1029B0008BF6002C45D14846FFF72AFF044638B96C -:1029C00078606FF00200BDE8F88F4FF00008E6E78E -:1029D000002606607860ADB24FF0000B454510D977 -:1029E0000AEB0803221D13F8011B9155B1B208F13F -:1029F00001081B291FFA88F82BD0454506F101066E -:102A0000F1D8FB8AC3F30902154465F30903BCE757 -:102A1000013292B21C462368002BF9D16B1F0B4484 -:102A20001C21B3FBF1F301339BB29A42D3D2BBF129 -:102A3000000FD0D14846FFF7EBFE20B9C4F800B034 -:102A4000BFE70122E7E7C0F800B05E462060044619 -:102A5000C1E74545D5D94846FFF7DAFE08B92060F9 -:102A6000AFE7C0F800B0002620600446B6E70000DB -:102A70002DE9F04F2DED028B1C4683B05B6901926E -:102A800007468846002B00F09A80238C2BB1E26920 -:102A9000002A00F09480072B35D807F10C00FFF7CF -:102AA000B7FE054638B96FF00205284603B0BDEC05 -:102AB000028BBDE8F08F14220021FEF73BFC228C34 -:102AC000E16905F10800FEF723FC208C013080B29B -:102AD000FFF7E6FEFFF7C8FE013880B22084013020 -:102AE00028746369228C1B782A4403F01F0363F067 -:102AF0003F0348F000411372384669602946FFF7EA -:102B0000EFFD0125D1E700F10C034FF0000908EEBD -:102B1000103A4FF0800A4E464D4618EE100AFFF765 -:102B200077FE83460028BED014220021FEF702FC67 -:102B3000002E3AD1019BABF8083002220BF1080EAF -:102B40001FFA82FC0CF10100BCF1060F218C80B24F -:102B500001D88E422BD3FFF7A3FEFFF785FE6269F3 -:102B60001278013802F01F028E4208BF4FF0400A6F -:102B700042EA49121BFA80F14AEA020A013048F09F -:102B8000004281F808A08BF81000CBF804205946C9 -:102B90003846FFF7A5FD238C0135B3422DB289F0ED -:102BA00001094FF0000AB8D17FE70022C6E7E169CA -:102BB000895D0EF802100136B6B20132C0E76FF03F -:102BC000010572E7F8B515460E463022002104468D -:102BD0001F46FEF7AFFB069B6360B5F5001F079B22 -:102BE000A76034BF6A094FF6FF72A36297B2E6612D -:102BF00004F1100000239A4206D800230360A78244 -:102C0000E3822383E360F8BD06600133304620365B -:102C1000F1E7000003781BB94BB2002BC8BF01706D -:102C20007047000000787047F8B50C46C969074640 -:102C300011B9238C002B37D1257E1F2D34D838783D -:102C400028BB228C072A2CD8268A36F003032BD1E6 -:102C50004FF6FF70FFF7D0FD20F001003102400475 -:102C600041EA0561400C41EA40254FF6FF722346D8 -:102C700029463846FFF7FCFE002807DD6269137815 -:102C80000133DBB21F2B88BF00231370F8BD218AEC -:102C90002D0645EA012505432046FFF71DFE0246A5 -:102CA000E5E76FF00300F1E76FF00100EEE70000E9 -:102CB00070B58AB0044616460021282268461D4693 -:102CC000FEF738FBBDF83830ADF810300F9B059398 -:102CD0009DF840308DF81830119B07936946BDF878 -:102CE0004830ADF820302046CDE90265FFF79CFF63 -:102CF0000AB070BD2DE9F041D36905460C46164671 -:102D00000BB9138C5BBB377E1F2F28D895F800803A -:102D1000B8F1000F26D03046FFF7DEFD33782102F0 -:102D200041EAC33141EA0801338A41EA076141EAD5 -:102D300003410246334641F080012846FFF798FEE2 -:102D400000280ADD3378012B07D17269137801332B -:102D5000DBB21F2B88BF00231370BDE8F0816FF03A -:102D60000100FAE76FF00300F7E70000F0B58BB061 -:102D700004460D4617460021282268461E46FEF7E7 -:102D8000D9FA9DF84C305A1E534253418DF8003009 -:102D90009DF84030ADF81030119B05939DF84830F8 -:102DA0008DF81830149B07936A46BDF85430ADF87F -:102DB000203029462046CDE90276FFF79BFF0BB075 -:102DC000F0BD0000406A00B104307047436A1A68E1 -:102DD000426202691A600361C38A013BC382704781 -:102DE0002DE9F041D0F82080194E14461D46414689 -:102DF000002709B9BDE8F081D1E90223A21A65EBE9 -:102E00000303964277EB03031ED2036A8B420DD174 -:102E1000FFF78CFD036A1B68036203690B60C38ABA -:102E20000161016A013BC3828846E2E7FFF77EFD4C -:102E30000B68C8F8003003690B60C38A0161013B6D -:102E4000C382D8F80010D4E788460968D1E700BFEC -:102E500080841E002DE9F04F8BB00D46DDF85090B8 -:102E600014469B468046002800F01981B9F1000FF6 -:102E700000F01581531E3F2B00F21181012A03D16E -:102E8000BBF1000F40F00B810023CDE90833B8F807 -:102E90001430B5EBC30F4FEAC30703D300200BB0C8 -:102EA000BDE8F08F2B199F42D8F80C303ABF7F1B3A -:102EB000FFB227461BB9D8F81030002B7AD0272D47 -:102EC0004ED8C5F12806B7424FF000032CBFF6B22A -:102ED0003E4600932946D8F8080008AB3246FFF773 -:102EE00041FCA7EB060A35445FFA8AFAB8F81430B9 -:102EF00003F10053053BDB000493D8F80C30039337 -:102F00002821039B13B1BAF1000F2CD1D8F810007F -:102F100040B1BAF1000F05D0009608AB5246691ACD -:102F2000FFF720FC38B2002FB8D066070AD00AABF2 -:102F300003EBD401624211F8083C02F0070213418E -:102F400001F8083C082C3CD9102C40F2B580202C0C -:102F500040F2B780BBF1000F00F09C80082334E002 -:102F6000BA460026C2E7049BE02B28BFE023069365 -:102F70000B44AB42059314D95A1B03980096924513 -:102F800034BF5246D2B2691A08AB04300792FFF739 -:102F9000E9FB079A1644AAEB020A1544F6B25FFA57 -:102FA0008AFA049B069A05999B1A0493039B1B6853 -:102FB0000393A6E70093D8F8080008AB3A462946E1 -:102FC000AEE7BBF1000F13D00123B4EBC30F6CD0FD -:102FD000082C12D89DF82030621E23FA02F2D50781 -:102FE00006D54FF0FF3202FA04F423438DF8203067 -:102FF0009DF8203089F8003051E7102C12D8BDF828 -:103000002030621E23FA02F2D10706D54FF0FF32BC -:1030100002FA04F42343ADF82030BDF82030A9F8BB -:1030200000303CE7202C0FD80899631E21FA03F3E7 -:10303000DA0705D54FF0FF3202FA04F40C43089486 -:10304000089BC9F800302AE7402C2BD0DDE9086541 -:10305000611EC4F12102A4F1210326FA01F105FA4F -:1030600002F225FA03F311431943CB0712D50122CB -:10307000A4F12003C4F1200102FA03F322FA01F1C2 -:10308000A240524243EA010363EB430332432B4322 -:10309000CDE90823DDE90823C9E90023FFE66FF045 -:1030A0000100FCE66FF00800F9E6082CA0D9102C0E -:1030B000B3D9202CEED8C3E7BBF1000FADD002236B -:1030C00083E7BBF1000FBBD004237EE730B5012AB4 -:1030D000144638BF0124402C85B028BF4024002569 -:1030E000012ACDE9025518D81B788DF808306307FE -:1030F0000AD004AB03EBD405624215F8083C02F099 -:103100000702934005F8083C00910346224600213F -:1031100002A8FFF727FB05B030BD082AE4D9102A22 -:1031200003D81B88ADF80830E1E7202A8DBFD3E92A -:1031300000231B680293CDE90223D8E710B5CB68C2 -:103140001BB98B600B618B8210BD04691A681C600F -:103150000361C38A013BC382CA60F0E703064CBF28 -:10316000C0F3C0300220704708B50246FFF7F6FFF3 -:10317000022806D15306C2F30F2001D100F003004C -:1031800008BDC2F30740FBE72DE9F04F93B0CDE94E -:1031900003230A6804461046FFF7E0FF022814BF25 -:1031A000C2F306260026002A0D46824680F2F281EE -:1031B00012F0C04940F0EE81097B002900F0EA815D -:1031C000022803D02378B34240F0E781C2F30463BE -:1031D0000693104602F07F030593FFF7C5FF059B9A -:1031E00029444FEA834848EA0A4848EA4668CE78C4 -:1031F00000230022CDE90823F309834648EA0008AA -:10320000029367D0059B009302466768534608A95E -:103210002046B847002800F0C381276A4FB94146CD -:1032200004F10C00FFF702FB074690B96FF00200B3 -:1032300054E03B6998450DD03F68002FF9D14146D5 -:1032400004F10C00FFF7F2FA07460028EED0236ADB -:103250003B60276297F817C006F01F08CCF3840C78 -:10326000ACEB08001FFA80FE0028B8BF0EF120006A -:10327000A8EB0C031FFA83FED7E90221B8BF00B206 -:10328000002B0793BEBF0EF120031BB2079352EA37 -:10329000010338D0039BDFF824E39A1A049B4FF014 -:1032A000000C63EB010196457CEB01032BD36B7B98 -:1032B00097F81AE0734519D1029B002B78D00128AA -:1032C00021DC7868F8B9DFF8F0C2944570EB0103AF -:1032D00016D337E0276A27B96FF00C0013B0BDE8AA -:1032E000F08F3B699845B5D03F68F4E7B24890420B -:1032F0007CEB010301D30020F0E7029B002BFAD006 -:10330000079B0F2B17DCFA7DB30002F0030203F0DA -:103310007C031343FB7539462046FFF707FB6B7BA5 -:10332000BB76029B3BB9FB7DC3F38402013262F39F -:103330008603FB75D0E76A7BBB7E9A42DBD1029B9A -:10334000002B35D0B309022B32D0039BBB60049B0A -:10335000FB60142200210DA8FDF7ECFF039B0A93EC -:10336000049B0B932B1D0C932B7BADF83EB0013BC4 -:10337000DBB2ADF83C30069B8DF84230059B8DF8F2 -:10338000433094F82C308DF840A083F001038DF881 -:1033900044308DF84180A3680AA920469847FB7DF8 -:1033A000C3F38403013303F01F039B02FB82A2E7F4 -:1033B000FB7DC6F34012B2EBD31F40F0F480C3F3A1 -:1033C0008403434540F0F280029A2B7BB609002A21 -:1033D0004DD0F2075DD4032B40F2EB80039BBB6022 -:1033E000049BFB602B7BAE1D033BDBB232463946B0 -:1033F00004F10C00FFF7ACFA00280CDA394620463D -:10340000FFF794FAFB7DC3F38403013303F01F033A -:103410009B02FB820AE7DDE90884AB883B834FF619 -:10342000FF73C9F12000A9F1200228FA09F104FA7A -:1034300000F0014324FA02F211431846C9B2FFF723 -:10344000C9F909F10809B9F1400F0346E9D1B88279 -:103450002A7B033AD2B23146FFF7CEF9FB7DB88220 -:10346000DA43C2F3C01262F3C713FB7543E786B9B0 -:103470002E1D013BDBB23246394604F10C00FFF74A -:1034800067FA0028BADB2A7BB88A013AD2B2314601 -:10349000E2E7F98AC1F30901013B0429DAB25BD8FA -:1034A000281D002307F11B069A4208D910F801CB0A -:1034B00006F801C0013101330529DBB2F4D10399CB -:1034C0000A9104990B91934207F11B010C9138BFAB -:1034D000043379680D9134BF55FA83F300230E93BA -:1034E000FB8AADF83EB0C3F309031A44069B8DF87E -:1034F0004230059B8DF8433094F82C30ADF83C20D9 -:1035000083F001038DF8443000238DF840A08DF83E -:1035100041807B602A7BB88A013A291DFFF76CF94C -:103520003B8BB882834203D1A3680AA920469847FF -:1035300020460AA9FFF702FEFB7DBA8AC3F3840383 -:10354000013303F01F039B02FB823B8B9A420CBFAB -:1035500000206FF01000C1E67B68002BAFD0052083 -:1035600001E01C3033461E68002EFAD1091A081DEE -:103570002E1D184401EB090CBCF11B0F5FFA89F3F7 -:103580009DD89A429BD916F8013B00F8013B09F1FE -:103590000109EFE76FF00900A0E66FF00A009DE671 -:1035A0006FF00B009AE66FF00D0097E66FF00E00DB -:1035B00094E66FF00F0091E640420F0080841E00F9 -:1035C000EFF3098305494A6B22F001024A6368332D -:1035D00083F30988002383F31188704700EF00E02C -:1035E000302080F3118862B60C4B0D4AD96821F463 -:1035F000E0610904090C0A43DA60D3F8FC200949A8 -:1036000042F08072C3F8FC200A6842F001020A60AE -:103610002022DA7783F82200704700BF00ED00E037 -:103620000003FA05001000E010B5302383F3118881 -:103630000E4B5B6813F4006314D0F1EE103AEFF315 -:103640000984683C4FF08073E361094BDB6B2366B0 -:1036500084F3098800F098F810B1064BA36110BDFF -:10366000054BFBE783F31188F9E700BF00ED00E0AD -:1036700000EF00E0030600080606000800F16043C2 -:1036800003F561430901C9B283F80013012200F078 -:103690001F039A4043099B0003F1604303F5614314 -:1036A000C3F880211A60704700F16040090100F5FD -:1036B0006D40C9B2017670470023037582680369C3 -:1036C0001B6899689142FBD25A680360426010609F -:1036D0005860704700230375826803691B68996806 -:1036E0009142FBD85A68036042601060586070478E -:1036F00008B50846302383F311880B7D032B05D0D2 -:10370000042B0DD02BB983F3118808BD8B690022DF -:103710001A604FF0FF338361FFF7CEFF0023F2E71B -:10372000D1E9003213605A60F3E70000FFF7C4BF2D -:10373000054BD9680875186802681A605360012241 -:103740000275D860FCF748BF2038002030B50C4B1C -:10375000DD684B1C87B004460FD02B46094A6846EB -:1037600000F0FEF82046FFF7E3FF009B13B1684628 -:1037700000F000F9A86907B030BDFFF7D9FFF9E7FD -:1037800020380020F1360008044B1A68DB68906886 -:103790009B68984294BF0020012070472038002089 -:1037A000084B10B51C68D86822681A605360012263 -:1037B0002275DC60FFF78EFF01462046BDE8104011 -:1037C000FCF70ABF20380020044B1A68DB689268B7 -:1037D0009B689A4201D9FFF7E3BF70472038002069 -:1037E00038B5074C07490848012300252370656058 -:1037F00000F00AFB0223237085F3118838BD00BF57 -:10380000483A00207C4A00082038002008B572B6EB -:10381000044B186500F0CEF900F092FA024B032237 -:103820001A70FEE720380020483A002000F0B4B8B3 -:10383000EFF3118020B9EFF30583302282F3118872 -:103840007047000010B530B9EFF30584C4F30804E5 -:1038500014B180F3118810BDFFF7B6FF84F311880F -:10386000F9E700008B60022308618B8208467047ED -:103870008368A3F1840243F8142C026943F8442CB2 -:10388000426943F8402C094A43F8242CC26843F8A3 -:10389000182C022203F80C2C002203F80B2C044AEB -:1038A00043F8102CA3F12000704700BFF105000879 -:1038B0002038002008B5FFF7DBFFBDE80840FFF720 -:1038C00035BF0000024BDB6898610F20FFF730BF67 -:1038D00020380020302383F31188FFF7F3BF000066 -:1038E00008B50146302383F311880820FFF72EFF27 -:1038F000002383F3118808BD064BDB6839B14268A9 -:1039000018605A60136043600420FFF71FBF4FF038 -:10391000FF307047203800200368984206D01A68AC -:103920000260506099611846FFF700BF70470000C1 -:1039300010B50A4C23699A6891420CD85A68816084 -:103940000360426010609A685860511A99604FF0A5 -:10395000FF33A36110BD1B68891AECE720380020F3 -:1039600010B4C0E9032300235DF8044B4361FFF763 -:10397000DFBF0000036881689A680A449A60426861 -:1039800013605A6000230360024B4FF0FF329A61CC -:10399000704700BF2038002070B5124DEB692A46F1 -:1039A0000133EB6152F8103F934206D09A68013A16 -:1039B0009A6030262C69A36803B170BDD4E9002158 -:1039C0000A605160236083F31188D4E903312046F3 -:1039D000984786F3118861690029EBD02046FFF7EC -:1039E000A7FFE7E72038002000207047FEE700002F -:1039F000704700004FF0FF3070470000BFF34F8F5B -:103A0000024AD368DB07FCD4704700BF00200240A5 -:103A100008B5074B1B7853B9FFF7F0FF054B1A6940 -:103A2000120641BF044A5A6002F188325A6008BD4A -:103A3000603A0020002002402301674508B5054B8D -:103A40001B7833B9FFF7DAFF034A136943F08003A9 -:103A5000136108BD603A0020002002407F289ABF11 -:103A600000F58030C0020020704700004FF4006075 -:103A700070470000802070477F2808B50BD8FFF7FB -:103A8000EDFF00F500630268013204D10430834287 -:103A9000F9D1012008BD0020FCE700007F2810B507 -:103AA00004461CD8FFF7AAFFFFF7B2FF0D4BF32225 -:103AB000DA6002221A61FFF7D1FF58611A6942F0F9 -:103AC00040021A614FF40061FFF798FF00F034F9EB -:103AD000FFF7B4FF2046BDE81040FFF7CDBF002040 -:103AE00010BD00BF002002402DE9F84312F0010391 -:103AF000144606D01F4B40F2F3221A600020BDE8A6 -:103B0000F88385181C4A954204D91A4A4FF43E712D -:103B10001160F3E7FFF77CFFFFF770FFDFF86880C5 -:103B2000451A4FF00109012C05EB01060F4603D899 -:103B3000FFF784FF0120E2E73B88C8F8109033804C -:103B40000020FFF75BFFC8F81000338831F8022B24 -:103B50009BB29A420CD0074B40F20F321A60074BCF -:103B60001E60074B1C60074B1F60FFF767FFC6E72F -:103B7000023CD8E75C3A002000000408503A0020DC -:103B8000583A0020543A002000200240084908B565 -:103B90000B7828B11BB9FFF73BFF01230B7008BD61 -:103BA000002BFCD0BDE808400870FFF747BF00BFFE -:103BB000603A002008B54FF420414FF0005000F06B -:103BC000BDF8BDE808404FF400514FF0805000F0C0 -:103BD000B5B800000846114600F05EBE012000F0B6 -:103BE0005BBE0000084600F075BE000030B583B033 -:103BF000FFF71EFE0E4B0F4DDB692A684FF47A71FA -:103C000001FB03F3934237BF0B4A0B495168146819 -:103C10002B602EBFD1E90041013151601C1941F1E7 -:103C200000010191FFF70EFE0199204603B030BD5F -:103C300020380020643A0020683A002030B583B074 -:103C4000FFF7F6FD114B124DDB692A684FF47A71CC -:103C500001FB03F3934237BF0E4A0E4951681468C3 -:103C60002B602EBFD1E90041013151601C1941F197 -:103C700000010191FFF7E6FD01994FF47A720023EC -:103C80002046FCF795FA03B030BD00BF2038002075 -:103C9000643A0020683A002010B50244064BD2B2C4 -:103CA000904200D110BD441C00B253F8200041F8EE -:103CB000040BE0B2F4E700BF502800400F4B30B5D2 -:103CC0001C6A240407D41C6A44F440741C621C6AF5 -:103CD00044F400441C620A4C236843F4807323605C -:103CE0000244084BD2B2904200D130BD441C00B215 -:103CF00051F8045B43F82050E0B2F4E700100240B2 -:103D0000007000405028004007B5012201A90020A2 -:103D1000FFF7C2FF019803B05DF804FB13B504463A -:103D2000FFF7F2FFA04205D0012201A90020019473 -:103D3000FFF7C4FF02B010BD7047000070470000DD -:103D400070470000074B45F255521A6002225A6034 -:103D500040F6FF729A604CF6CC421A60024B012288 -:103D60001A70704700300040743A0020034B1B78F3 -:103D70001BB1034B4AF6AA221A607047743A00201E -:103D800000300040044B1A682AB902F1804202F563 -:103D90000432526A1A607047703A0020024B4FF0AA -:103DA00080725A62704700BF0010024008B5FFF7EA -:103DB000E9FF024B1868C0F3407008BD703A00205C -:103DC00070470000FEE700000A4B0B480B4A904288 -:103DD0000BD30B4BDA1C121AC11E22F003028B42CA -:103DE00038BF00220021FDF7A5BA53F8041B40F8A4 -:103DF000041BECE7EC4B0008583C0020583C00202A -:103E0000583C0020FEE7000070B51B4B0163002505 -:103E1000044686B0586085620E46FFF7E1FB04F168 -:103E20001003C4E904334FF0FF33A361134BE56182 -:103E3000D969A5600A462B46C4E9082304F1340178 -:103E4000C4E900440E4AE562256580232046FFF759 -:103E500009FD0123E0600B4A03750092726801922C -:103E6000B268CDE90223084B6846CDE90435FFF777 -:103E700021FD06B070BD00BF483A00202038002068 -:103E8000884A00088D4A0008053E00084B684360D8 -:103E90008B688360CB68C3600B6943614B690362C5 -:103EA0008B6943620B6803607047000008B51B4BC9 -:103EB0009A6A42F4FC029A629A6A22F4FC029A62BA -:103EC0009A6A5A6942F4FC025A61154A5B691146C2 -:103ED0004FF09040FFF7DAFF02F11C0100F580601F -:103EE000FFF7D4FF02F1380100F58060FFF7CEFF45 -:103EF00002F1540100F58060FFF7C8FF02F1700184 -:103F000000F58060FFF7C2FF02F18C0100F58060D0 -:103F1000FFF7BCFFBDE8084000F05AB800100240AF -:103F2000944A000808B500F093F9FFF759FCBDE882 -:103F30000840FFF727BF00007047000010B5214C74 -:103F4000A36A63F4FC03A362A36A03F4FC03A36201 -:103F50004FF0FF32A36A23692261236900232361A2 -:103F60002169E168E260E268E360E268E2691649BB -:103F700042F08052E261E2690A6842F480720A60AB -:103F8000226A02F44072B2F5407F1EBF4FF48032C5 -:103F900022622362236A1B0407D4236A43F440731A -:103FA0002362236A43F40043236200F031F9A369DA -:103FB000064A43F00103A361A369136843F0200399 -:103FC000136010BD0010024000700040000001406E -:103FD0001E4B1A6842F001021A601A689007FCD55D -:103FE0005A6822F003025A605A6812F00C02FBD1A0 -:103FF000196801F0F90119605A601A6842F48032B8 -:104000001A601A689103FCD5114A5A604FF40452A1 -:10401000DA6230221A631A6842F080721A601A68F3 -:104020009201FCD50B4912220A600A6802F00702CD -:10403000022AFAD15A6842F002025A605A6802F023 -:104040000C02082AFAD11A6B1A637047001002405A -:104050000024050000200240084A08B55169136891 -:104060000B4003F00103536123B1054A13680BB100 -:1040700050689847BDE80840FFF7D6BA00040140F1 -:10408000783A0020084A08B5516913680B4003F0DC -:104090000203536123B1054A93680BB1D068984776 -:1040A000BDE80840FFF7C0BA00040140783A00209C -:1040B000084A08B5516913680B4003F004035361C3 -:1040C00023B1054A13690BB150699847BDE8084010 -:1040D000FFF7AABA00040140783A0020084A08B560 -:1040E000516913680B4003F00803536123B1054A7B -:1040F00093690BB1D0699847BDE80840FFF794BABF -:1041000000040140783A0020084A08B55169136854 -:104110000B4003F01003536123B1054A136A0BB13E -:10412000506A9847BDE80840FFF77EBA0004014096 -:10413000783A0020174B10B55A691C68144004F4F3 -:1041400078725A61A30604D5134A936A0BB1D06AF8 -:104150009847600604D5104A136B0BB1506B984713 -:10416000210604D50C4A936B0BB1D06B9847E2053E -:1041700004D5094A136C0BB1506C9847A30504D5BC -:10418000054A936C0BB1D06C9847BDE81040FFF71F -:104190004BBA00BF00040140783A00201A4B10B51A -:1041A0005A691C68144004F47C425A61620504D5C3 -:1041B000164A136D0BB1506D9847230504D5134A69 -:1041C000936D0BB1D06D9847E00404D50F4A136E80 -:1041D0000BB1506E9847A10404D50C4A936E0BB1F5 -:1041E000D06E9847620404D5084A136F0BB1506F24 -:1041F0009847230404D5054A936F0BB1D06F9847B5 -:10420000BDE81040FFF710BA00040140783A0020E2 -:10421000062108B50846FFF731FA06210720FFF707 -:104220002DFA06210820FFF729FA06210920FFF7B9 -:1042300025FA06210A20FFF721FA06211720FFF7A9 -:104240001DFABDE8084006212820FFF717BA000034 -:1042500008B5FFF773FE00F067F800F03DF8FFF7D0 -:104260006BFEBDE8084000F05DB8000002684368DE -:104270001143016003B1184770470000143000F08B -:104280002FBA00004FF0FF33143000F029BA0000BD -:10429000383000F0A5BA00004FF0FF33383000F09E -:1042A0009FBA0000143000F0F5B900004FF0FF3164 -:1042B000143000F0EFB90000383000F04FBA0000C1 -:1042C0004FF0FF32383000F049BA0000012914BF26 -:1042D0006FF013000020704700F06CB8044B0360CF -:1042E0000023C0E90233436001230374704700BF19 -:1042F0003C4B000838B5C36904460D461BB9042180 -:104300000844FFF7B3FF294604F1140000F0A6F9B2 -:10431000002806DA201D4FF40061BDE83840FFF7A1 -:10432000A5BF38BD00F00EB80023054A1946013379 -:10433000102BC2E9001102F10802F8D1704700BF4A -:10434000783A00204FF0E023044A5A6100229A6133 -:1043500007221A6108210B20FFF7A6B93F190100B7 -:1043600008B5302383F31188FFF760FA002383F345 -:10437000118808BD08B5FFF7F3FFBDE80840FFF757 -:1043800053B90000026843681143016003B1184744 -:1043900070470000024A136843F0C003136070477F -:1043A00000440040024A136843F0C00313607047A2 -:1043B0000048004037B51D4C1D4D2046FFF78EFFCD -:1043C000009404F114001B490023202200F038F966 -:1043D0002022009404F13800174B184900F0B2F97C -:1043E000174BC4E91735174C0C212620FFF746F967 -:1043F0002046FFF773FF04F11400134900940023D3 -:10440000202200F01DF904F13800104B10490094EF -:10441000202200F097F90F4B0C212720C4E9173513 -:1044200003B0BDE83040FFF729B900BFF83A0020DB -:1044300000512502D03B002095430008103C00208D -:1044400000440040643B0020F03B0020A5430008EE -:10445000303C0020004800402DE9F047C66D376829 -:10446000F46934622107054619D014F0080118BF19 -:104470004FF48071E20748BF41F02001A30748BF15 -:1044800041F04001600748BF41F08001302383F3D1 -:104490001188281DFFF776FF002383F31188E205BA -:1044A0000AD5302383F311884FF48061281DFFF76C -:1044B00069FF002383F311884FF030094FF0000AA1 -:1044C00014F0200838D13B0616D54FF0300905F11D -:1044D000380A200610D589F31188504600F066F995 -:1044E000002836DA0821281DFFF74CFF27F080034B -:1044F0003360002383F31188790614D5620612D540 -:10450000302383F31188D5E913239A4208D12B6C09 -:1045100033B11021281D27F04007FFF733FF376024 -:10452000002383F31188E30619D5AA6E1369B3B18A -:10453000BDE8F0475069184789F31188B38C95F8A6 -:10454000641028461940FFF7D5FE8AF31188F469F4 -:10455000B6E780B2308588F31188F469B9E7BDE821 -:10456000F087000008B50348FFF776FFBDE8084074 -:10457000FFF75AB8F83A002008B50348FFF76CFF78 -:10458000BDE80840FFF750B8643B0020F8B5154679 -:1045900082680669AA420B46816938BF8568761A27 -:1045A000B54204460BD218462A46FCF7B1FEA36971 -:1045B0002B44A361A3685B1BA3602846F8BD0CD9FC -:1045C00018463246FCF7A4FEAF1BE1683A46304479 -:1045D000FCF79EFEE3683B44EBE718462A46FCF7EF -:1045E00097FEE368E5E7000083689342F7B5154658 -:1045F000044638BF8568D0E90460361AB5420BD24C -:104600002A46FCF785FE63692B446361A36828464C -:104610005B1BA36003B0F0BD0DD932460191FCF7DE -:1046200077FE0199E068AF1B3A463144FCF770FE13 -:10463000E3683B44E9E72A46FCF76AFEE368E4E7FF -:1046400010B50A440024C361029B8460C0E90000E5 -:10465000C0E90511C1600261036210BD08B5D0E96F -:104660000532934201D1826882B982680132826048 -:104670005A1C42611970D0E904329A4224BFC368BF -:1046800043610021FFF748F9002008BD4FF0FF30DB -:10469000FBE7000070B5302304460E4683F3118813 -:1046A000A568A5B1A368A269013BA360531CA361DF -:1046B00015782269934224BFE368A361E3690BB1D3 -:1046C00020469847002383F31188284607E03146A7 -:1046D0002046FFF711F90028E2DA85F3118870BD52 -:1046E0002DE9F74F04460E4617469846D0F81C9021 -:1046F0004FF0300A8AF311884FF0000B154665B170 -:104700002A4631462046FFF741FF034660B941463D -:104710002046FFF7F1F80028F1D0002383F3118839 -:10472000781B03B0BDE8F08FB9F1000F03D0019002 -:104730002046C847019B8BF31188ED1A1E448AF36B -:104740001188DCE7C0E90511C160C3611144009B19 -:104750008260C0E90000016103627047F8B5044659 -:104760000D461646302383F31188A768A7B1A368C6 -:10477000013BA36063695A1C62611D70D4E9043275 -:104780009A4224BFE3686361E3690BB1204698470E -:10479000002080F3118807E031462046FFF7ACF88F -:1047A0000028E2DA87F31188F8BD0000D0E905237C -:1047B0009A4210B501D182687AB98268013282606A -:1047C0005A1C82611C7803699A4224BFC3688361C2 -:1047D0000021FFF7A1F8204610BD4FF0FF30FBE7A6 -:1047E0002DE9F74F04460E4617469846D0F81C9020 -:1047F0004FF0300A8AF311884FF0000B154665B16F -:104800002A4631462046FFF7EFFE034660B941468F -:104810002046FFF771F80028F1D0002383F31188B8 -:10482000781B03B0BDE8F08FB9F1000F03D0019001 -:104830002046C847019B8BF31188ED1A1E448AF36A -:104840001188DCE70B460146184600F02DB8000041 -:1048500000F040B8012838BF012010B504462046BA -:1048600000F030F830B900F007F808B900F00CF8A3 -:104870008047F4E710BD0000024B1868BFF35B8F60 -:10488000704700BF503C002008B5062000F084F8B7 -:104890000120FFF7ABF80000024B0A4601461868FA -:1048A000FFF798B91811002010B5054C13462CB12C -:1048B0000A4601460220AFF3008010BD2046FCE707 -:1048C00000000000024B01461868FFF787B900BFDF -:1048D00018110020024B01461868FFF783B900BF8A -:1048E0001811002010B501390244904201D1002076 -:1048F00005E0037811F8014FA34201D0181B10BD49 -:104900000130F2E72DE9F041A3B1C91A177801444B -:10491000044603F1FF3C8C42204601D9002009E007 -:104920000578BD4204F10104F5D10CEB0405D6185D -:10493000A54201D1BDE8F08115F8018D16F801ED11 -:10494000F045F5D0E7E700001F2938B504460D46CD -:1049500004D9162303604FF0FF3038BD426C12B10A -:1049600052F821304BB9204600F030F82A46014673 -:104970002046BDE8384000F017B8012B0AD0591C7A -:1049800003D1162303600120E7E7002442F8254005 -:10499000284698470020E0E7024B01461868FFF7D9 -:1049A000D3BF00BF1811002038B5074D00230446BF -:1049B000084611462B60FFF71DF8431C02D12B68F7 -:1049C00003B1236038BD00BF543C0020FFF70CB892 -:1049D000034611F8012B03F8012B002AF9D1704787 -:1049E0006F72672E6172647570696C6F742E48699E -:1049F0007465634D6F7361696300000040A2E4F168 -:104A0000646891060041A3E5F26569920700000021 -:104A10004261642043414E496661636520696E646A -:104A200065782E00800000000080000000008000FB -:104A30000000000000000000351B000819230008DA -:104A400079220008451B0008791B0008751D000825 -:104A5000491B0008591B00084D1B0008551B000886 -:104A6000511B00089D1C00085D1B0008E52500087F -:104A70006D1B0008711C000863300000784A0008B4 -:104A800078380020483A00206D61696E0069646CD6 -:104A900065000000A010002800000000FAAAAAAAE1 -:104AA00050040024BFFF0000007700000000000059 -:104AB0001410AA0000000000AAAAFAAA04005000DC -:104AC000FBFF0000000000009977000000000000DC -:104AD00000000000AAAAAAAA00000000FFFF000030 -:104AE00000000000000000000000000000000000C6 -:104AF000AAAAAAAA00000000FFFF00000000000010 -:104B0000000000000000000000000000AAAAAAAAFD -:104B100000000000FFFF0000000000000000000097 -:104B20000000000000000000AAAAAAAA00000000DD -:104B3000FFFF000000000000000000000000000077 -:104B40009942000885420008C1420008AD420008B1 -:104B5000B9420008A5420008914200087D420008C1 -:104B6000CD4200087CB6FF7F01000000000000007D -:104B7000F80300000000000000980300000000009F -:104B8000FE2A0100D20400001C11002000000000D9 -:104B90000000000000000000000000000000000015 -:104BA0000000000000000000000000000000000005 -:104BB00000000000000000000000000000000000F5 -:104BC00000000000000000000000000000000000E5 -:104BD00000000000000000000000000000000000D5 -:0C4BE000000000000000000000000000C9 +:1000000000090020B1010008E1220008992200083F +:10001000C122000899220008B9220008B301000893 +:10002000B3010008B3010008B3010008D53200088D +:10003000B3010008B3010008B3010008A54000089F +:10004000B3010008B3010008B3010008B3010008C0 +:10005000B3010008B3010008893D0008B53D000860 +:10006000E13D00080D3E0008393E0008B3010008DC +:10007000B3010008B3010008B3010008B301000890 +:10008000B3010008B3010008B30100084D220008C5 +:100090007922000889220008B3010008653E0008A3 +:1000A000B3010008B3010008B3010008B301000860 +:1000B000B3010008B3010008B3010008B301000850 +:1000C000B3010008B3010008B3010008B301000840 +:1000D000B3010008B301000895420008A9420008D6 +:1000E000CD3E0008B3010008B3010008B3010008C9 +:1000F000B3010008B3010008B3010008B301000810 +:10010000B3010008B3010008B3010008B3010008FF +:10011000B3010008B3010008B3010008B3010008EF +:10012000B3010008B3010008B3010008B3010008DF +:10013000B3010008B3010008B3010008B3010008CF +:10014000B3010008B3010008B3010008B3010008BF +:10015000B3010008B3010008B3010008B3010008AF +:10016000B3010008B3010008B3010008B30100089F +:10017000B3010008B3010008B3010008B30100088F +:10018000B3010008B3010008B3010008B30100087F +:10019000B3010008B3010008B3010008B30100086F +:1001A000150F000800000000000000000000000023 +:1001B00002E000F000F8FEE772B6374880F30888E6 +:1001C000364880F3098836483649086040F2000016 +:1001D000CCF200004EF63471CEF200010860BFF39D +:1001E0004F8FBFF36F8F40F20000C0F2F0004EF669 +:1001F0008851CEF200010860BFF34F8FBFF36F8FBD +:100200004FF00000E1EE100A4EF63C71CEF2000114 +:100210000860062080F31488BFF36F8F03F068FC3A +:1002200003F0DCFC4FF055301F491B4A91423CBFA4 +:1002300041F8040BFAE71D49184A91423CBF41F8C6 +:10024000040BFAE71A491B4A1B4B9A423EBF51F86E +:10025000040B42F8040BF8E700201849184A9142B1 +:100260003CBF41F8040BFAE703F046FC03F0F2FC54 +:10027000144C154DAC4203DA54F8041B8847F9E7D7 +:1002800000F042F8114C124DAC4203DA54F8041B52 +:100290008847F9E703F02EBC000900200011002078 +:1002A0000000000808ED00E0000100200009002027 +:1002B00098480008001100207C11002080110020C7 +:1002C000543C0020A0010008A4010008A40100087B +:1002D000A40100082DE9F04F2DED108AC1F80CD0D3 +:1002E000C3689D46BDEC108ABDE8F08F002383F300 +:1002F00011882846A047002003F050F9FEE703F0DC +:10030000D9F800DFFEE70000F8B500F015FE03F0B5 +:1003100093FB074603F0E2FB064600283FD12B4B38 +:100320009F423CD001339F423CD0294B27F0FF0233 +:100330009A423AD1F8B200F03BFC354642F21074D2 +:1003400000F03CFC08B10024254601F0ABF880B376 +:10035000032000F041F80024254636B11D4B9F4292 +:1003600003D003F0B3FB00242546002003F06EFB0E +:100370004FF090431B6913F020031FD00DB100F024 +:1003800041F800F04DFC01F0B3FF0546C4B101F0A7 +:10039000AFFF401BA04213D900F034F8F3E7354615 +:1003A0000024CDE704460125CAE705464FF47A74D8 +:1003B000C6E7B4F57A7F08BF0125CEE71C46E0E723 +:1003C00000F076FC012003F0EFF8DFE7010007B052 +:1003D000000008B0263A09B0084B187003280CD862 +:1003E000DFE800F008050208022000F001BE02204C +:1003F00000F0F6BD024B00225A60704780110020C9 +:100400008411002038B501F04DF830B11F4B0322A4 +:100410001A701F4B00225A6038BD1E4B1E4A1968C5 +:100420000131F9D004339342F9D11C4C194DD4F861 +:100430000428AA42F0D31A4B9B6803F1006303F52A +:10044000D0439A42E8D203F015FB03F027FB0020CB +:1004500000F08CFD0220FFF7BFFF124BDA6900228B +:10046000DA61D96999699A619B6972B64FF0E023A4 +:100470003021C3F8085DD4F80038D4F8042881F39B +:1004800011889D4683F308881047C5E78011002036 +:10049000841100200068000820680008006000083F +:1004A0000011002000100240094A136849F2690057 +:1004B00099B21B0C00FB01331360064B186844F221 +:1004C000506182B2000C01FB0200186080B27047DC +:1004D000141100201011002010B500211022044634 +:1004E00000F0A0FD034B03CB206061601868A060A2 +:1004F00010BD00BFACF7FF1F2DE9F041ADF54E7DFB +:100500000DF134086CAC40F2751207460D460EA88A +:100510000021C8F8001000F085FD4FF4C4720021DE +:10052000204600F07FFD01F0E3FE254B4FF47A7288 +:10053000B0FBF2F0186093E80700022384E807009C +:100540000DF5E9702382FFF7C7FF4FF603031D493E +:10055000238406A804F0D4F8192384F832310DF26C +:10056000E32206AB0DF1300C1E4603CE664510604B +:100570005160334602F10802F6D1337813704146D8 +:100580000122204600F09AFD00230393AB7E0293E4 +:1005900005F11903019380B20123CDE90480009392 +:1005A000E97E05A3D3E90023384602F069FA0DF588 +:1005B0004E7DBDE8F08100BF9E6AC421818A46EE6F +:1005C0008C110020104700082DE9F0412C4C237AB3 +:1005D000DAB080460D465BBB27A9284600F07EFEB8 +:1005E0000746002842D19DF89D60C82E3ED801469E +:1005F0004FF4A662204600F015FD4FF48073C4F856 +:10060000F8314FF40073C4F80C334FF44073C4F85E +:10061000203432460DF19E0104F1090000F0F0FC97 +:1006200026449DF89C30777223720BB9EB7E2372BF +:100630008122002106AC27A800F0F4FC012221460B +:1006400027A800F087FE00230393AB7E029305F1F9 +:10065000190380B201932823CDE904400093E97E79 +:1006600005A3D3E90023404602F00AFA5AB0BDE8D8 +:10067000F08100BFAFF3008026417272DF25D7B74B +:10068000B0320020F0B5254E4FF48A7505FB0065A9 +:10069000F1B096F8D83085F8DC300024D822214615 +:1006A00085F8E8403AA800F0BDFC06F1090000F02A +:1006B000B1FCD5F8E4308DF8F000C2B206AF06F117 +:1006C00009010DF1F100CDE93A3400F099FC394609 +:1006D00001223AA800F06AFE80B2CDE90470082336 +:1006E0000127CDE9023706F1D803019330230093A7 +:1006F000317A0B4807A3D3E9002302F0C1F9A042E5 +:1007000006DD01F0F5FDC5F8E000384671B0F0BD3A +:100710002046FBE778F6339F93CACD8DB032002098 +:10072000A42100202DE9F0411D4D1E4E1E4F86B024 +:10073000284602F0D1F9034658B30024CDE903441A +:10074000ADF81440027B8DF814209968406802943B +:1007500003AA03C21B68DFF8548043F000430293EE +:1007600001F0C8FD821941F10003009402A9384646 +:1007700001F072F8A04205DD284602F0B1F988F8D0 +:100780000040D5E798F80030072B05D8013388F8EA +:10079000003006B0BDE8F081014802F0A1F9F8E7A9 +:1007A000A421002040420F00D8210020E53700207E +:1007B00070B50D4614461E4602F0BEF850B9022E22 +:1007C00010D1012C0ED112A3D3E90023C5E90023D7 +:1007D000012007E0282C10D005D8012C09D0052CC9 +:1007E0000FD0002070BD302CFBD10BA3D3E9002328 +:1007F000ECE70BA3D3E90023E8E70BA3D3E900233D +:10080000E4E70BA3D3E90023E0E700BFAFF30080E8 +:10081000401DA12026812A0B78F6339F93CACD8DE7 +:100820009E6AC421818A46EE26417272DF25D7B7BF +:10083000F017304A39059E5638B505460E4C002152 +:10084000013500F0B5FBA4F82C55B4F82C0500F0E8 +:1008500097FB78B1B4F82C0500F0A2FB014648B92B +:10086000B4F82C0500F0A4FBB4F82C350133A4F83F +:100870002C35EAE738BD00BFB032002010B50A4B76 +:100880000A4A1A6003F5805393F860203AB9DC6D88 +:100890002CB1204600F080FE204603F071FEBDE83A +:1008A0001040034800F078BED821002068470008B7 +:1008B000203200202DE9F04F8FB000AF05460C46E6 +:1008C00002F03AF8002849D1237E022B1BD1E38A9B +:1008D000012B18D101F00CFD0646FFF7E5FD03469C +:1008E0004FF4C870DFF8C482B3FBF0F206F5167659 +:1008F00002FB103316FA83F3C8F80030E37E33B9F5 +:10090000A34B00221A703C37BD46BDE8F08F07F1BB +:100910002401204600F0A0FC0028F4D107F11400C7 +:10092000FFF7DAFD97F8264007F11401224607F198 +:10093000270003F06FFE0028E2D10F2C08D8944B5B +:100940001C70D8F80030A3F51673C8F80030DAE749 +:1009500097F82410284601F0E7FFD4E7E38A282B14 +:100960002BD010D8012B23D0052BCCD1BFF34F8F28 +:100970008849894BCA6802F4E0621343CB60BFF335 +:100980004F8F00BFFDE7302BBDD1844EE17E327A20 +:100990009142B8D1607E3146002291F8DC50854208 +:1009A00000F0A5800132042A01F58A71F5D1AAE789 +:1009B00021462846FFF7A0FDA5E721462846FFF778 +:1009C00003FEA0E7B2F8EC507B6005F103094FEAA3 +:1009D00099094FEA8902D11DC908A8EBC1039D46B8 +:1009E000EB460021584600F01DFB04F1EE012A46BB +:1009F0003144584600F004FB7B6813B9012000F035 +:100A0000B5FA96F8D20000F0BBFA044630B930725D +:100A100000F0D6FA204600F0A9FAB1E0D6F8D420CA +:100A20003AB996F8D200B6F82C25824201D8FFF7E1 +:100A300003FFD6F8D4202A44944208D296F8D20074 +:100A4000B6F82C250130824201D8FFF7F5FE706818 +:100A50005FFA89F2594600F0EDFA08B9C54679E027 +:100A6000726896F8D2002A447260D6F8D42005EB5A +:100A70000209C6F8D49000F083FA814509D396F8AC +:100A8000D220D6F8D4000132001B86F8D220C6F856 +:100A9000D400FF2D0FD80024347200F091FA2046C4 +:100AA00000F064FA00F0FEFC3D4B188108B9FFF736 +:100AB000A9FCC54627E7BB6896F8D9000AFB036284 +:100AC000FB68D2F8E41082F8E83001F58061C2F8E2 +:100AD000E030C2F8E410FFF7D5FDFFF723FE96F8EB +:100AE000D920013202F0030286F8D920B6E74FF48C +:100AF0008A7A0AFB02F505F1EA013144204600F04A +:100B000081FCF86000287FF4FEAE3544012285F8B0 +:100B1000E82001F0EDFBD5F8E020D6ED007ADFED1E +:100B2000216A801A192838BF192040F6B83290423D +:100B300028BF1046B8EE677A07EE900AF8EEE77A1B +:100B400067EEA67ADFED186AE7EE267AFCEEE77A22 +:100B5000C6ED007A96F8D930BB60BA6873680AFBB4 +:100B600002F4321992F8E81059B1D2F8E4108B422D +:100B7000E8463FF427AF002182F8E810C2F8E01001 +:100B8000C5467368064A9B0A01331381BBE600BF62 +:100B90009D21002000ED00E00400FA05B0320020A5 +:100BA0008C110020CDCCCC3D6666663FA021002094 +:100BB000014B1870704700BF9811002038B54FF0F6 +:100BC0000054134B22689A4220D1124B627D124886 +:100BD0001A70237D03724FF48073C0F8F8314FF41C +:100BE0000073C0F80C3300254FF44073C0F8203474 +:100BF0000A49C0F8E450C922093000F001FAE022A5 +:100C00002946204600F00EFA012038BD0020FCE7FE +:100C10009AAD44C598110020B03200201600002083 +:100C200037B500F03FFC194D1949288102230122F4 +:100C300018486B7101F0F8F900230193164B17491E +:100C400000931748174B4FF4805201F045FE164BA6 +:100C5000197811B1124801F067FE01F049FB044612 +:100C6000FFF722FC4FF4C873B0FBF3F202FB13034F +:100C700004F5167010FA83F00C4B186002F02EFF8A +:100C800008B10F232B8103B030BD00BF8C110020B1 +:100C900040420F00D8210020B10700089C1100201D +:100CA000A4210020B508000898110020A0210020F0 +:100CB0002DE9F04F2DED028B8EA7D7E900670FF2DB +:100CC0003C29D9E90089864C95B00DAD9FED828B0A +:100CD000FFF728FDDFF82CB200230C93ADF83C3071 +:100CE0000D936B6000230DF125028DED008B4FF00D +:100CF000010A09A958468DF825308DF824A001F085 +:100D000041F99DF824200023002A40F0AB802046C2 +:100D100001F012FE0546002847D1DFF8ECB101F0E2 +:100D2000E7FADBF8003098423FD301F0E1FA079090 +:100D3000FFF7BAFB079A4FF4C873B0FBF3F101FB5E +:100D4000130302F5167010FA83F0CBF80000DFF8F9 +:100D5000BCB19BF800100791002914BF2B465346E5 +:100D600010A88DF83030FFF7B7FB0799C1F11002DA +:100D7000D2B2062A10AB28BF062219440DF1310069 +:100D8000079200F03DF9079A0CAB039318230293E6 +:100D90000132544BD2B2CDE900A304923B46324615 +:100DA000204601F00FFE8BF8005001F0A1FA4E4AE8 +:100DB0004E4D1368C31AB3F57A7F32D3106001F039 +:100DC00099FA02460B46204601F094FE204601F0B7 +:100DD000B3FD30B32B7ADFF838A1002B14BF032307 +:100DE00002238AF8053001F083FA0DF1400B4FF42D +:100DF0007A730122B0FBF3F05946CAF8000050465E +:100E000000F002FA18230293394B019380B240F2AA +:100E10005513CDE903B0009342464B46204601F0FE +:100E2000D1FD2B7ACBB101F063FA4FF0000A834673 +:100E30004FF48A7295F8D900504400F0030002FB89 +:100E4000005393F8E81089B30AF1010ABAF1040FCC +:100E5000F0D12B7A002B7FF438AF15B0BDEC028BAC +:100E6000BDE8F08F4FF0904110A84A6982F040022F +:100E70004A611946102200F0D5F80DF126030AAA9E +:100E80000CA9584600F0E8FD95E8030011AB83E893 +:100E900003009DF83C308DF84C300C9B109310A94A +:100EA000DDE90A23204601F0F9FF1BE7D3F8E01043 +:100EB00049B12B68FA2B38BFFA23ABEB010105339C +:100EC000B1EB430FC0D3FFF7DDFB4FF48A7200286C +:100ED000BAD1BEE7AFF300800000000000000000C0 +:100EE000A42100209C210020E0370020B032002007 +:100EF000E4370020401DA12026812A0BF1C6A7C19E +:100F0000D068080FD8210020A02100209D210020BA +:100F10008C11002008B5054800F03AFEBDE80840F5 +:100F2000034A0449002003F025BB00BFD82100205C +:100F3000203800207D08000870B502F00DFC094E35 +:100F4000094D3080002428683388834208D902F094 +:100F5000FFFB2B6804440133B4F5D04F2B60F2D370 +:100F600070BD00BF14380020E837002002F080BCBC +:100F700000F10060920000F5D04002F027BC0000B4 +:100F8000054B1A68054B1B889B1A834202D91044F3 +:100F900002F0DEBB00207047E83700201438002044 +:100FA000024B1B68184402F0D9BB00BFE837002091 +:100FB000024B1B68184402F0E3BB00BFE837002077 +:100FC000064991F8243033B10023086A81F82430AF +:100FD0000822FFF7CDBF0120704700BFEC3700208B +:100FE000022802BF4FF0904340229A6170470000F0 +:100FF000022802BF4FF090434FF480029A6170477D +:1010000010B50023934203D0CC5CC4540133F9E7FC +:1010100010BD000003460246D01A12F9011B002938 +:10102000FAD1704702440346934202D003F8011BF1 +:10103000FAE770472DE9F8431F4D144695F8242030 +:101040000746884652BBDFF870909CB395F8243071 +:101050002BB92022FF2148462F62FFF7E3FF95F8C6 +:101060002400C0F10802A24228BF2246D6B241465F +:10107000920005EB8000FFF7C3FF95F82430A41B16 +:101080001E44F6B2082E17449044E4B285F824605A +:10109000DBD1FFF795FF0028D7D108E02B6A03EBDF +:1010A00082038342CFD0FFF78BFF0028CBD10020F3 +:1010B000BDE8F8830120FBE7EC3700202DE9F0477D +:1010C0000D46044600219046284640F27912FFF76B +:1010D000A9FF234620220021284601F081FE231D7E +:1010E00002222021284601F07BFE631D03222221DB +:1010F000284601F075FEA31D03222521284601F094 +:101100006FFE04F1080310222821284601F068FE32 +:1011100004F1100308223821284601F061FE04F191 +:10112000110308224021284601F05AFE04F112035F +:1011300008224821284601F053FE04F1140320221E +:101140005021284601F04CFE04F118034022702182 +:10115000284601F045FE04F120030822B02128466C +:1011600001F03EFE04F121030822B821284601F0D7 +:1011700037FE04F12207C0263B46314608222846A6 +:10118000083601F02DFEB6F5A07F07F10107F3D177 +:1011900004F1320308223146284601F021FE0027DF +:1011A00004F1330A94F832304FEAC7099F4209F537 +:1011B000A47615D3B8F1000F08D1314604F5997320 +:1011C0000722284601F00CFE09F24F16274694F834 +:1011D00032213B1B93420CD3F01DC008BDE8F087C1 +:1011E0000AEB070308223146284601F0F9FD0137D2 +:1011F000D8E707F2331331460822284601F0F0FD04 +:1012000008360137E3E7000013B50446084600211D +:1012100001602346C0F803102022019001F0E0FD98 +:101220000198231D0222202101F0DAFD0198631D9F +:101230000322222101F0D4FD0198A31D03222521C0 +:1012400001F0CEFD019804F108031022282101F0DD +:10125000C7FD072002B010BDF7B50023047F009141 +:101260000E4607221946054601F07EFC731C0093CA +:10127000012200230721284601F076FCC4B9B31CE3 +:101280000093052223460821284601F06DFC0D2419 +:101290003746B278BB1B934211D32B7FA88A073401 +:1012A000E408BBB9844294BF0020012003B0F0BD24 +:1012B000AB8ADB00083BDB08B3700824E8E7FB1CC3 +:1012C0000093214600230822284601F04DFC0834F3 +:1012D0000137DEE7201A18BF0120E7E7F7B5002342 +:1012E000047F00910E4608221946054601F03CFC99 +:1012F000731CC4B90822009311462346284601F006 +:1013000033FC1024012372785F1C013B934211D3FC +:101310002B7FA88A0734E408BBB9844294BF00201D +:10132000012003B0F0BDAB8ADB00083BDB08737023 +:101330000824E7E7F31900932146002308222846F2 +:1013400001F012FC08343B46DDE7201A18BF0120EB +:10135000E7E70000F8B50E46054614460021812255 +:101360003046FFF75FFE2B4608220021304601F091 +:1013700037FD7CB96B1C07220821304601F030FD97 +:101380000F2401236A785F1C013B934204D3E01DC4 +:10139000C008F8BD0824F4E7EB19214608223046BE +:1013A00001F01EFD08343B46ECE70000F8B50E46A0 +:1013B000054614460021CE223046FFF733FE2B4669 +:1013C00028220021304601F00BFD7CB905F108030D +:1013D00008222821304601F003FD30242F462A7AC6 +:1013E0007B1B934204D3E01DC008F8BD2824F5E719 +:1013F00007F1090321460822304601F0F1FC0834C8 +:101400000137ECE7F7B5047F00910E460123102267 +:101410000021054601F0A8FBC4B9B31C00930922C2 +:1014200023461021284601F09FFB19243746728875 +:10143000BB1B9A4211D82B7FA88A0734E408BBB99A +:10144000844294BF0020012003B0F0BDAB8ADB00D2 +:10145000103BDB0873801024E8E73B1D0093214616 +:1014600000230822284601F07FFB08340137DEE71D +:10147000201A18BF0120E7E730B5094D0A44914210 +:101480000DD011F8013B5840082340F30004013B04 +:101490002C4013F0FF0384EA5000F6D1EFE730BD93 +:1014A0002083B8EDF7B5364A106851686B4603C320 +:1014B0006A4634493448082303F0BCF8044690BB1C +:1014C0000A25324A106851686B4603C36A463049A0 +:1014D0002D48082303F0AEF80446002847D00369DE +:1014E000B3F5663F43D8B0F86620B2F57E7F3ED1B3 +:1014F000284A024402F15C018B4238D35C3B22490A +:1015000000209E1AFFF7B8FF3246074604F1640137 +:101510000020FFF7B1FFA3689F4228D1E3689842FB +:1015200008BF002523E00369B3F5663F26D8428B48 +:10153000B2F57E7F20D1174A024402F110018B429E +:1015400018D3103B104900209D1AFFF795FF2A463B +:10155000064604F118010020FFF78EFFA3689E42A3 +:1015600002D1E368984201D00D25AAE7002528465C +:1015700003B0F0BD1025A4E70C25A2E70B25A0E7DA +:101580002C470008DC970300006800083547000876 +:10159000909703000898FFF710B5037C044613B931 +:1015A000006803F02FF8204610BD00000023BFF3B1 +:1015B0005B8FC360BFF35B8FBFF35B8F8360BFF351 +:1015C0005B8F7047BFF35B8F0068BFF35B8F704723 +:1015D00070B505460C30FFF7F5FF05F10806044627 +:1015E0003046FFF7EFFFA04206D930466D68FFF79F +:1015F000E9FF2544281A70BD3046FFF7E3FF201AA3 +:10160000F9E7000070B50546406898B105F108009B +:10161000FFF7D8FF05F10C0604463046FFF7D2FF6E +:101620008442304694BF6D680025FFF7CBFF013C34 +:101630002C44201A70BD000038B50C460546FFF753 +:10164000C7FFA04210D305F10800FFF7BBFF044419 +:101650006868B4FBF0F100FB1144BFF35B8F01201D +:10166000AC60BFF35B8F38BD0020FCE72DE9F04193 +:10167000144607460D46FFF7C5FF844228BF0446BF +:10168000D4B1B84658F80C6B4046FFF79BFF304486 +:10169000286040467E68FFF795FF331A9C4203D8C6 +:1016A0006C600120BDE8F0816B60A41B3B68AB60FF +:1016B0002044E8600220F5E72046F3E738B50C4601 +:1016C0000546FFF79FFFA04210D305F10C00FFF77E +:1016D00079FF04446868B4FBF0F100FB1144BFF3E8 +:1016E0005B8F0120EC60BFF35B8F38BD0020FCE70F +:1016F0002DE9FF41884669460746FFF7B7FF6C466C +:1017000006B204EBC6060025B44209D06268206820 +:1017100008EB0501FFF774FC636808341D44F3E728 +:1017200029463846FFF7CAFF284604B0BDE8F081D5 +:10173000F8B505460C300F46FFF744FF05F10806E3 +:1017400004463046FFF73EFFA042304688BF6C6833 +:10175000FFF738FF201A386020B130462C68FFF7B9 +:1017600031FF2044F8BD000073B5144606460D460F +:10177000FFF72EFF844228BF04460190DCB101A987 +:101780003046FFF7D5FF019B33B93268C5E9023314 +:10179000C5E9002401200CE09C4238BF0194286078 +:1017A000019868608442F5D93368AB60241AEC6014 +:1017B000022002B070BD2046FBE700002DE9FF418A +:1017C0000F466946FFF7D0FF6C4600B204EBC00538 +:1017D0000026AC4209D0D4F8048054F8081BB8198C +:1017E0004246FFF70DFC4644F3E7304604B0BDE83F +:1017F000F081000038B50546FFF7E0FF04460146DA +:101800002846FFF719FF204638BD000010B40268D3 +:1018100054681A4623465DF8044B18470020704769 +:101820000020704770470000002070470E2070476E +:1018300000F5805090F8C800C0F3400070470000E9 +:1018400000F5805090F9D0007047000000F58050FE +:10185000C0F8CC1001207047F7B50C68BDF82070B7 +:1018600014F0005470D10D7B082D6DD8302585F310 +:1018700011884569AE6876010CD4AC68240108D49F +:10188000AC6814F080545DD184F31188204603B015 +:10189000F0BD01240E6804F1180C002EB8BFF6004C +:1018A0004FEA0C1CB4BF46F00406760545F80C6000 +:1018B0000E680FFA84FC16F0804F18BF05EB0C1E63 +:1018C00005EB0C1C1EBFDEF8806146F00206CEF868 +:1018D00080610E7BCCF8846105EB04158E68C5F839 +:1018E0008C614E68C5F88861DCF8805145F00105CF +:1018F000CCF8805100EB441641F268052E4405EB0C +:1019000044150544C6E9002308350E4601F10C0CC8 +:1019100056F804EB45F804EB6645F9D18434368873 +:101920002E8000EB441407F00305267926F00B0601 +:1019300035432571002484F31188009700F0FAFCE8 +:101940000120A4E70224A5E74FF0FF309FE7000045 +:1019500013B500F580540191E06DFFF753FE1F2889 +:101960000AD90199E06D2022FFF7C2FEA0F1200301 +:101970005842584102B010BD0020FBE708B53023A3 +:1019800083F3118800F58050C06DFFF70FFE002330 +:1019900083F3118808BD000000220260828142604A +:1019A0008260704710B500220023C0E900230023A5 +:1019B000044603810C30FFF7EFFF204610BD000006 +:1019C000F0B5054600F580500C4690F8C83013F08D +:1019D000040FC3F3800108BF114661F3820304F1D1 +:1019E000840680F8C83005EB461389B01B79D80708 +:1019F0002ED57AB319072DD46846FFF7D3FF05EB30 +:101A0000441303F5835303F1180703AA103318682E +:101A10005968144603C40833BB422246F7D11868FC +:101A200020609B88A380DDE90E23CDE900230123FC +:101A3000ADF808302B686946DB6B2846984705EB04 +:101A400046152B791A075CBF43F008032B7101E0A0 +:101A5000002AF4D109B0F0BD2DE9F0479A4688B0CC +:101A6000074688469146302383F3118807F5805452 +:101A70006846FFF797FFE06DFFF7AAFD1F282AD9F8 +:101A8000E06D20226946FFF7B5FE202823D103AD83 +:101A9000444605AB2E4603CE9E422060616035462B +:101AA00004F10804F6D130682060B388A380DDE932 +:101AB0000023C9E90023BDF80830AAF8003000234C +:101AC00083F3118853464A464146384608B0BDE87C +:101AD000F04700F01DBC002080F3118808B0BDE87D +:101AE000F08700002DE9F84F0023C0E90133254BB2 +:101AF000044640F8183B0F46FFF74EFF04F128005C +:101B0000FFF750FF04F1480804F5825546460835B2 +:101B100030462036FFF746FFAE42F9D104F5805536 +:101B20004FF480534FF00009C5E91339C5F84880D8 +:101B30000123EE6504F5875804F58456C5F85490E2 +:101B400085F8583085F86030083608F108084FF0FD +:101B5000000A4FF0000B46E908ABA6F11800FFF7AA +:101B60001BFF203646F8289C4645F4D185F8D070F6 +:101B700017B1054800F0B6FB044B63612046BDE891 +:101B8000F88F00BF68470008404700080064004025 +:101B900010B5044B197804464A1C1A70FFF7A2FFCF +:101BA000204610BD1C3800202DE9F047002950D0F8 +:101BB000294B2A4FB7FBF1F599428CBF0A23112319 +:101BC000581EB5FBF3FC03FB1C53C4B22BB1022817 +:101BD0000346F5D80020BDE8F0870CF1FF36B6F5D6 +:101BE000806FF7D2C4EBC40E0EF103034FEAE30992 +:101BF000C3F3C703A4EB030809F1010A4FF47A7594 +:101C00005FFA88F009FB05555AFA88F8B5FBF8F534 +:101C1000B5F5617FC1BF0EF1FF33C3F3C703E01A0F +:101C2000C0B25C1C50FA84F40CFB04F4B7FBF4F46F +:101C3000A142CFD1013BDBB20F2BCBD80138C0B2D0 +:101C40000728C7D80021107116809170D370012029 +:101C5000C1E70846BFE700BF3F420F000051250221 +:101C600070B505460E464FF47A746B695B6803F0F5 +:101C70000103B3424FF0010004D001F095FC013C98 +:101C8000F3D1204670BD000030B54269936913F06E +:101C9000700F16D000230B4C936103F1840200EB0C +:101CA000421211794D0709D5890707D5416954F8C2 +:101CB00023508D60117941F0040111710133032B20 +:101CC000EBD130BD5447000873B51D464369164635 +:101CD0009A68D207044609D59A6801219960C2F32F +:101CE0004002CDE900650021FFF76AFE63699A684A +:101CF000D1050BD59A684FF480719960C2F34022E8 +:101D0000CDE9006501212046FFF75AFE63699A6814 +:101D1000D2030BD59A684FF480319960C2F34042E8 +:101D2000CDE9006502212046FFF74AFE04F5805305 +:101D3000D3F8CC0010B103681B699847204602B065 +:101D4000BDE87040FFF7A0BFF8B50446466900291A +:101D500072D106F10C073868800770D006EB0115C8 +:101D60003868D5F8B00110F0040FD5F8B0011ABFEB +:101D7000C00840F00040400DA061D5F8B0C11CF093 +:101D8000020F1CBF40F08040A061D5F8B40106EB03 +:101D9000011100F00F0084F82400D1F8B801207779 +:101DA000D1F8B801000A6077D1F8B801000CA0772B +:101DB000D1F8B801000EE077D1F8BC0184F820001A +:101DC000D1F8BC01000A84F82100D1F8BC01000C54 +:101DD00084F82200D1F8BC11090E84F823103821B0 +:101DE000396004F1340004F1180104F1240551F8BC +:101DF000046B40F8046BA942F9D109880180C4E959 +:101E00000A2321460023238651F8283B2046DB6B1A +:101E1000984704F5805393F8C820D3F8CC0042F0DB +:101E2000040283F8C82010B103681B699847204654 +:101E3000BDE8F840FFF728BF06F110078BE7F8BDB3 +:101E400010B5044600F056FA02460B4652EA03016A +:101E500002D0013A63F100030449086820B1214629 +:101E6000BDE81040FFF770BF10BD00BF183800205C +:101E7000F0B5302181F31188DFF848C000F58351B7 +:101E80000831002404F1840500EB45152E7977070D +:101E90000ED4F6060CD5D1E9007697429E4107D2C2 +:101EA00046695CF82470B7602E7946F004062E71FE +:101EB0000134032C01F12001E4D1002383F31188C4 +:101EC000F0BD00BF5447000808B5302383F31188E4 +:101ED000FFF7DAFE002383F3118808BDF8B54369E4 +:101EE0000546986800F0E050B0F1E05F0F4621D061 +:101EF000F8B1302383F3118805F58354103400269C +:101F000006F1840305EB43131B791A0706D5013646 +:101F1000032E04F12004F3D1012007E05B07F6D47F +:101F20002146384600F040FA0028F0D1002383F320 +:101F30001188F8BD0120FCE708B5302383F3118830 +:101F400000F58050C06DFFF743FB002383F3118839 +:101F500043090CBF0120002008BD0000F8B51D4654 +:101F6000002313700F4606461446FFF7E5FF80F086 +:101F70000100387025B129463046FFF7AFFF2070C9 +:101F8000F8BD00002DE9B8410C4615461F468046B5 +:101F900000F0B0F90B462178024609B9287850B113 +:101FA0004046FFF765FFFFF78FFF3B462A46214675 +:101FB000FFF7D4FF0120BDE8B881000070B53026DE +:101FC00086F31188174BDA6942F00072DA611A69F8 +:101FD00042F000721A611A6922F000721A6100233D +:101FE00083F3118800F5805494F8C83013F001058C +:101FF00016D1A9B186F311880321132001F0C8F985 +:102000000321142001F0C4F90321152001F0C0F9C7 +:1020100094F8C83043F0010384F8C83085F3118880 +:1020200070BD00BF001002402DE9F04700F580555B +:1020300088B095F8D030012B04468846164600F249 +:102040008180814F57F823200AB947F82300D7F839 +:1020500000A0C4F80C802674BAF1000F64D095F883 +:10206000D030012B70D001212046FFF7A7FF30238D +:1020700083F311886269136823F0020313606269B5 +:10208000136843F001031360636900275F6187F3FE +:10209000118801212046FFF7E3FD002800F095801C +:1020A000E86DFFF783FA04F58359BA4609F1080988 +:1020B000202200216846FEF7B5FF02A8FFF76CFC5E +:1020C000CDF818A06A4609EB07030DF1180E9446E7 +:1020D000BCE80300F44518605960624603F1080348 +:1020E000F5D1DCF80000186020379CF804201A7144 +:1020F000602FDDD195F8C8306FF38203002785F893 +:10210000C8306A4641462046ADF80070ADF802700E +:102110008DF80470FFF748FD636948BB4FF4004237 +:102120001A6008B0BDE8F08741F2D80002F02AFA40 +:10213000814610B15146FFF7D5FCC7F80090B9F1C0 +:10214000000F8CD10020ECE7386803681B6B9847C0 +:102150000146002887D13868FFF730FF38680368E8 +:1021600032465B684146984700287FF47CAFE9E738 +:1021700061221A609DF802309DF803201B061204AC +:1021800002F4702203F040731343BDF80020C2F341 +:10219000090213439DF804201205022E02F4E00206 +:1021A0000CBF4FF000410021134362690B43D36120 +:1021B000636913225A616269136823F00103136093 +:1021C00039462046FFF74CFD08B96369A6E795F844 +:1021D000D03093BB6169D1F8002242F00102C1F80E +:1021E00000226169D1F8002222F47C5222F00E0212 +:1021F000C1F800226169D1F8002242F46062C1F89E +:1022000000226269C2F814326269C2F8043262695B +:1022100041F6FF71C2F80C126269C2F8403262697D +:10222000C2F8443263690122C3F81C226269D2F801 +:10223000003223F00103C2F8003295F8C83043F0B1 +:10224000020385F8C8306CE71838002008B500F0A4 +:1022500051F850EA0103024602D0421E61F100012A +:10226000044B186810B10B46FFF72EFDBDE808407F +:1022700001F064B81838002008B50020FFF7E0FD31 +:10228000BDE8084001F05AB808B50120FFF7D8FDB5 +:10229000BDE8084001F052B800B59BB0EFF30981EA +:1022A00068226846FEF7ACFEEFF30583014B9B6B9B +:1022B000FEE700BF00ED00E008B5FFF7EDFF00000E +:1022C00000B59BB0EFF3098168226846FEF798FEDF +:1022D000EFF30583014B5B6BFEE700BF00ED00E011 +:1022E000FEE700000FB408B5029801F00DF9FEE713 +:1022F00001F040BB01F0ECBA13B56C4684E806006F +:10230000031D94E8030083E80500012002B010BD1E +:1023100073B58568019155B11B885B0707D4D0E977 +:1023200000369B6B9847019AC1B23046A8470120FE +:1023300002B070BDF0B5866889B005460C465EB146 +:10234000BDF838305B070AD4D0E900379B6B98475B +:102350002246C1B23846B047012009B0F0BD002284 +:102360000023CDE900230023ADF808300A4603AB73 +:1023700001F10806106851681C4603C40832B242D5 +:102380002346F7D1106820609288A280FFF7B2FF41 +:102390000423ADF808302B68CDE90001DB6B6946FA +:1023A00028469847D8E7000030B503680968DD0F74 +:1023B000B5EBD17F23F0604421F060424FEAD17049 +:1023C0000BD0002BB8BFA40C0029B8BF920C9442CC +:1023D00002D034BF0120002030BD944205D1C1F3AA +:1023E0008070C3F380738342F6D194422CBF0020E7 +:1023F0000120F1E72DE9F041456A15B94162BDE8D8 +:10240000F0814B6823F06047C3F38A464FEAD37EDE +:10241000C3F3807816EA230638BF3E46AC462B4607 +:102420005A68BEEBD27F22F060440AD0002A18DA44 +:10243000A40CB44217D19D420FD10D60DEE71346C4 +:10244000EEE7A74207D102F08044C2F38072424512 +:102450000BD054B1EFE708D2EDE7CCF800100B60D9 +:10246000CDE7B44201D0B442E5D81A689C46002AB0 +:10247000E5D11960C3E700002DE9F047089D01F0A0 +:1024800007044FEAD508224405F0070500EBD10008 +:102490004FF47F49944201D1BDE8F08704F007076B +:1024A00005F0070A57453E4638BF5646C6F10806AE +:1024B000111B8E4228BF0E46E10808EBD50E415C89 +:1024C00013F80EC0B94029FA06F721FA0AF1FFB253 +:1024D0008CEA010147FA0AF739408CEA010C03F84B +:1024E0000EC034443544D5E780EA0120082341F288 +:1024F000210201B24000002980B203F1FF33B8BFCE +:10250000504013F0FF03F4D17047000038B50C467B +:102510008D18A54200D138BD14F8011BFFF7E4FF68 +:10252000F7E7000042684AB1136843604389818934 +:1025300001339BB29942438138BF83811046704773 +:1025400070B588B0202204460D4668460021FEF78B +:1025500069FD20460495FFF7E5FF024658B16B463A +:10256000054608AE1C4603CCB44228606960234689 +:1025700005F10805F6D1104608B070BD082817D936 +:1025800009280CD00A280CD00B280CD00C280CD011 +:102590000D280CD00E2814BF4020302070470C208E +:1025A0007047102070471420704718207047202073 +:1025B00070470000082817D90C280CD910280CD90E +:1025C00014280CD918280CD920280CD930288CBFF5 +:1025D0000F200E207047092070470A2070470B20FB +:1025E00070470C2070470D20704700002DE9F8431C +:1025F000078C072F04461ED9D0E9029800254FF614 +:10260000FF73C5F12006A5F1200029FA05F108FAAB +:1026100006F628FA00F031430143C9B21846FFF725 +:1026200063FF0835402D0346EBD1E1693A46BDE82A +:10263000F843FFF76BBF4FF6FF70BDE8F88300006B +:1026400010B54B6823B9CA8A63F30902CA8210BD68 +:1026500004691A681C600361C38A013BC3824A6033 +:10266000EFE700002DE9F84F1D46CB8A0F46C3F374 +:1026700009010529814692460B4630D00020AAB2B6 +:1026800007F11A049EB2042E1FFA80F80FD8904565 +:1026900003F1010306D3FB8A0A4462F30903FB82B8 +:1026A00001201AE01AF80060E6540130EAE790458C +:1026B000F1D2A1F1050B1C237C68BBFBF3F203FBF9 +:1026C00012BB1FFA8BF6002C45D14846FFF72AFFB4 +:1026D000044638B978606FF00200BDE8F88F4FF01B +:1026E0000008E6E7002606607860ADB24FF0000B08 +:1026F000454510D90AEB0803221D13F8011B91551B +:10270000B1B208F101081B291FFA88F82BD0454502 +:1027100006F10106F1D8FB8AC3F30902154465F3FB +:102720000903BCE7013292B21C462368002BF9D1A1 +:102730006B1F0B441C21B3FBF1F301339BB29A4294 +:10274000D3D2BBF1000FD0D14846FFF7EBFE20B942 +:10275000C4F800B0BFE70122E7E7C0F800B05E466A +:1027600020600446C1E74545D5D94846FFF7DAFE63 +:1027700008B92060AFE7C0F800B00026206004462A +:10278000B6E700002DE9F04F2DED028B1C4683B01B +:102790005B69019207468846002B00F09A80238CE3 +:1027A0002BB1E269002A00F09480072B35D807F19D +:1027B0000C00FFF7B7FE054638B96FF00205284652 +:1027C00003B0BDEC028BBDE8F08F14220021FEF7B0 +:1027D00029FC228CE16905F10800FEF711FC208C30 +:1027E000013080B2FFF7E6FEFFF7C8FE013880B285 +:1027F0002084013028746369228C1B782A4403F0FA +:102800001F0363F03F0348F00041137238466960CC +:102810002946FFF7EFFD0125D1E700F10C034FF04A +:10282000000908EE103A4FF0800A4E464D4618EE69 +:10283000100AFFF777FE83460028BED0142200213D +:10284000FEF7F0FB002E3AD1019BABF808300222D4 +:102850000BF1080E1FFA82FC0CF10100BCF1060F0F +:10286000218C80B201D88E422BD3FFF7A3FEFFF755 +:1028700085FE62691278013802F01F028E4208BF9D +:102880004FF0400A42EA49121BFA80F14AEA020A72 +:10289000013048F0004281F808A08BF81000CBF816 +:1028A000042059463846FFF7A5FD238C0135B34275 +:1028B0002DB289F001094FF0000AB8D17FE700225C +:1028C000C6E7E169895D0EF802100136B6B2013241 +:1028D000C0E76FF0010572E7F8B515460E463022E5 +:1028E000002104461F46FEF79DFB069B6360B5F57D +:1028F000001F079BA76034BF6A094FF6FF72A362EF +:1029000097B2E66104F1100000239A4206D8002332 +:102910000360A782E3822383E360F8BD066001338E +:1029200030462036F1E7000003781BB94BB2002B8C +:10293000C8BF01707047000000787047F8B50C46BA +:10294000C969074611B9238C002B37D1257E1F2D6D +:1029500034D8387828BB228C072A2CD8268A36F01F +:1029600003032BD14FF6FF70FFF7D0FD20F00100DD +:102970003102400441EA0561400C41EA40254FF62E +:10298000FF72234629463846FFF7FCFE002807DD84 +:10299000626913780133DBB21F2B88BF00231370E9 +:1029A000F8BD218A2D0645EA012505432046FFF79B +:1029B0001DFE0246E5E76FF00300F1E76FF001004E +:1029C000EEE7000070B58AB00446164600212822C2 +:1029D00068461D46FEF726FBBDF83830ADF81030CE +:1029E0000F9B05939DF840308DF81830119B07938D +:1029F0006946BDF84830ADF820302046CDE9026583 +:102A0000FFF79CFF0AB070BD2DE9F041D369054680 +:102A10000C4616460BB9138C5BBB377E1F2F28D88C +:102A200095F80080B8F1000F26D03046FFF7DEFDA4 +:102A30003378210241EAC33141EA0801338A41EA8D +:102A4000076141EA03410246334641F080012846CE +:102A5000FFF798FE00280ADD3378012B07D1726951 +:102A600013780133DBB21F2B88BF00231370BDE83E +:102A7000F0816FF00100FAE76FF00300F7E7000064 +:102A8000F0B58BB004460D46174600212822684653 +:102A90001E46FEF7C7FA9DF84C305A1E534253416A +:102AA0008DF800309DF84030ADF81030119B059343 +:102AB0009DF848308DF81830149B07936A46BDF88E +:102AC0005430ADF8203029462046CDE90276FFF794 +:102AD0009BFF0BB0F0BD0000406A00B104307047AE +:102AE000436A1A68426202691A600361C38A013B41 +:102AF000C38270472DE9F041D0F82080194E14466A +:102B00001D464146002709B9BDE8F081D1E90223FD +:102B1000A21A65EB0303964277EB03031ED2036A06 +:102B20008B420DD1FFF78CFD036A1B6803620369BA +:102B30000B60C38A0161016A013BC3828846E2E7F8 +:102B4000FFF77EFD0B68C8F8003003690B60C38A8D +:102B50000161013BC382D8F80010D4E788460968B8 +:102B6000D1E700BF80841E002DE9F04F8BB00D46E9 +:102B7000DDF8509014469B468046002800F01981ED +:102B8000B9F1000F00F01581531E3F2B00F21181A7 +:102B9000012A03D1BBF1000F40F00B810023CDE9E6 +:102BA0000833B8F81430B5EBC30F4FEAC30703D3AB +:102BB00000200BB0BDE8F08F2B199F42D8F80C30E5 +:102BC0003ABF7F1BFFB227461BB9D8F81030002B45 +:102BD0007AD0272D4ED8C5F12806B7424FF0000312 +:102BE0002CBFF6B23E4600932946D8F8080008AB41 +:102BF0003246FFF741FCA7EB060A35445FFA8AFA32 +:102C0000B8F8143003F10053053BDB000493D8F807 +:102C10000C3003932821039B13B1BAF1000F2CD180 +:102C2000D8F8100040B1BAF1000F05D0009608ABFB +:102C30005246691AFFF720FC38B2002FB8D0660759 +:102C40000AD00AAB03EBD401624211F8083C02F04F +:102C50000702134101F8083C082C3CD9102C40F223 +:102C6000B580202C40F2B780BBF1000F00F09C80B3 +:102C7000082334E0BA460026C2E7049BE02B28BFB5 +:102C8000E02306930B44AB42059314D95A1B0398D7 +:102C90000096924534BF5246D2B2691A08AB04304E +:102CA0000792FFF7E9FB079A1644AAEB020A1544BC +:102CB000F6B25FFA8AFA049B069A05999B1A049366 +:102CC000039B1B680393A6E70093D8F8080008ABA2 +:102CD0003A462946AEE7BBF1000F13D00123B4EB0F +:102CE000C30F6CD0082C12D89DF82030621E23FA36 +:102CF00002F2D50706D54FF0FF3202FA04F423435F +:102D00008DF820309DF8203089F8003051E7102CE4 +:102D100012D8BDF82030621E23FA02F2D10706D580 +:102D20004FF0FF3202FA04F42343ADF82030BDF82F +:102D30002030A9F800303CE7202C0FD80899631EFA +:102D400021FA03F3DA0705D54FF0FF3202FA04F453 +:102D50000C430894089BC9F800302AE7402C2BD07C +:102D6000DDE90865611EC4F12102A4F1210326FA00 +:102D700001F105FA02F225FA03F311431943CB07D7 +:102D800012D50122A4F12003C4F1200102FA03F3B9 +:102D900022FA01F1A240524243EA010363EB4303EA +:102DA00032432B43CDE90823DDE90823C9E9002399 +:102DB000FFE66FF00100FCE66FF00800F9E6082C72 +:102DC000A0D9102CB3D9202CEED8C3E7BBF1000F4B +:102DD000ADD0022383E7BBF1000FBBD004237EE715 +:102DE00030B5012A144638BF0124402C85B028BFD5 +:102DF00040240025012ACDE9025518D81B788DF80A +:102E0000083063070AD004AB03EBD405624215F81F +:102E1000083C02F00702934005F8083C0091034685 +:102E20002246002102A8FFF727FB05B030BD082A83 +:102E3000E4D9102A03D81B88ADF80830E1E7202A2E +:102E40008DBFD3E900231B680293CDE90223D8E7A5 +:102E500010B5CB681BB98B600B618B8210BD046908 +:102E60001A681C600361C38A013BC382CA60F0E731 +:102E700003064CBFC0F3C0300220704708B50246BD +:102E8000FFF7F6FF022806D15306C2F30F2001D147 +:102E900000F0030008BDC2F30740FBE72DE9F04F47 +:102EA00093B0CDE903230A6804461046FFF7E0FF1C +:102EB000022814BFC2F306260026002A0D468246C9 +:102EC00080F2F28112F0C04940F0EE81097B0029C6 +:102ED00000F0EA81022803D02378B34240F0E78172 +:102EE000C2F304630693104602F07F030593FFF7D5 +:102EF000C5FF059B29444FEA834848EA0A4848EA47 +:102F00004668CE7800230022CDE90823F3098346E2 +:102F100048EA0008029367D0059B00930246676861 +:102F2000534608A92046B847002800F0C381276A05 +:102F30004FB9414604F10C00FFF702FB074690B978 +:102F40006FF0020054E03B6998450DD03F68002FB8 +:102F5000F9D1414604F10C00FFF7F2FA07460028C8 +:102F6000EED0236A3B60276297F817C006F01F086F +:102F7000CCF3840CACEB08001FFA80FE0028B8BF2D +:102F80000EF12000A8EB0C031FFA83FED7E9022103 +:102F9000B8BF00B2002B0793BEBF0EF120031BB2D7 +:102FA000079352EA010338D0039BDFF824E39A1A0F +:102FB000049B4FF0000C63EB010196457CEB010391 +:102FC0002BD36B7B97F81AE0734519D1029B002B2A +:102FD00078D0012821DC7868F8B9DFF8F0C2944590 +:102FE00070EB010316D337E0276A27B96FF00C00A6 +:102FF00013B0BDE8F08F3B699845B5D03F68F4E762 +:10300000B24890427CEB010301D30020F0E7029B21 +:10301000002BFAD0079B0F2B17DCFA7DB30002F0D0 +:10302000030203F07C031343FB7539462046FFF788 +:1030300007FB6B7BBB76029B3BB9FB7DC3F3840232 +:10304000013262F38603FB75D0E76A7BBB7E9A424E +:10305000DBD1029B002B35D0B309022B32D0039B6E +:10306000BB60049BFB60142200210DA8FDF7DAFF72 +:10307000039B0A93049B0B932B1D0C932B7BADF8A6 +:103080003EB0013BDBB2ADF83C30069B8DF84230E0 +:10309000059B8DF8433094F82C308DF840A083F0D8 +:1030A00001038DF844308DF84180A3680AA92046B9 +:1030B0009847FB7DC3F38403013303F01F039B0296 +:1030C000FB82A2E7FB7DC6F34012B2EBD31F40F0B8 +:1030D000F480C3F38403434540F0F280029A2B7BD3 +:1030E000B609002A4DD0F2075DD4032B40F2EB80E5 +:1030F000039BBB60049BFB602B7BAE1D033BDBB2E1 +:103100003246394604F10C00FFF7ACFA00280CDA1D +:1031100039462046FFF794FAFB7DC3F3840301335D +:1031200003F01F039B02FB820AE7DDE90884AB88FA +:103130003B834FF6FF73C9F12000A9F1200228FA62 +:1031400009F104FA00F0014324FA02F2114318468F +:10315000C9B2FFF7C9F909F10809B9F1400F0346EF +:10316000E9D1B8822A7B033AD2B23146FFF7CEF9D1 +:10317000FB7DB882DA43C2F3C01262F3C713FB755A +:1031800043E786B92E1D013BDBB23246394604F1D6 +:103190000C00FFF767FA0028BADB2A7BB88A013AED +:1031A000D2B23146E2E7F98AC1F30901013B0429B1 +:1031B000DAB25BD8281D002307F11B069A4208D912 +:1031C00010F801CB06F801C0013101330529DBB24B +:1031D000F4D103990A9104990B91934207F11B01D1 +:1031E0000C9138BF043379680D9134BF55FA83F3DD +:1031F00000230E93FB8AADF83EB0C3F309031A44D3 +:10320000069B8DF84230059B8DF8433094F82C30A6 +:10321000ADF83C2083F001038DF8443000238DF895 +:1032200040A08DF841807B602A7BB88A013A291D35 +:10323000FFF76CF93B8BB882834203D1A3680AA9DC +:103240002046984720460AA9FFF702FEFB7DBA8A6E +:10325000C3F38403013303F01F039B02FB823B8B08 +:103260009A420CBF00206FF01000C1E67B68002B73 +:10327000AFD0052001E01C3033461E68002EFAD185 +:10328000091A081D2E1D184401EB090CBCF11B0F77 +:103290005FFA89F39DD89A429BD916F8013B00F852 +:1032A000013B09F10109EFE76FF00900A0E66FF0BB +:1032B0000A009DE66FF00B009AE66FF00D0097E6AE +:1032C0006FF00E0094E66FF00F0091E640420F00A1 +:1032D00080841E00EFF3098305494A6B22F0010246 +:1032E0004A63683383F30988002383F311887047A6 +:1032F00000EF00E0302080F3118862B60C4B0D4ADD +:10330000D96821F4E0610904090C0A43DA60D3F8B2 +:10331000FC20094942F08072C3F8FC200A6842F0A0 +:1033200001020A602022DA7783F82200704700BF8A +:1033300000ED00E00003FA05001000E010B53023B6 +:1033400083F311880E4B5B6813F4006314D0F1EE25 +:10335000103AEFF30984683C4FF08073E361094B46 +:10336000DB6B236684F3098800F098F810B1064BF4 +:10337000A36110BD054BFBE783F31188F9E700BF9C +:1033800000ED00E000EF00E0FF020008020300088B +:1033900000F1604303F561430901C9B283F80013EA +:1033A000012200F01F039A4043099B0003F1604390 +:1033B00003F56143C3F880211A60704700F1604053 +:1033C000090100F56D40C9B201767047002303750D +:1033D000826803691B6899689142FBD25A6803604E +:1033E000426010605860704700230375826803696B +:1033F0001B6899689142FBD85A680360426010606C +:103400005860704708B50846302383F311880B7D58 +:10341000032B05D0042B0DD02BB983F3118808BDE5 +:103420008B6900221A604FF0FF338361FFF7CEFFF4 +:103430000023F2E7D1E9003213605A60F3E700009D +:10344000FFF7C4BF054BD9680875186802681A6091 +:10345000536001220275D860FCF73CBF2838002079 +:1034600030B50C4BDD684B1C87B004460FD02B46A3 +:10347000094A684600F0D8F82046FFF7E3FF009BB2 +:1034800013B1684600F0DAF8A86907B030BDFFF75D +:10349000D9FFF9E72838002005340008044B1A68E2 +:1034A000DB6890689B68984294BF002001207047B9 +:1034B00028380020084B10B51C68D86822681A60AC +:1034C000536001222275DC60FFF78EFF0146204623 +:1034D000BDE81040FCF7FEBE2838002038B5074C88 +:1034E00007490848012300252370656000F024FB8C +:1034F0000223237085F3118838BD00BF503A0020A5 +:10350000AC4700082838002008B572B6044B18658F +:1035100000F0C2F900F0ACFA024B03221A70FEE789 +:1035200028380020503A002000F09AB88B6002231F +:1035300008618B82084670478368A3F1840243F8D0 +:10354000142C026943F8442C426943F8402C094A80 +:1035500043F8242CC26843F8182C022203F80C2CE0 +:10356000002203F80B2C044A43F8102CA3F120008E +:10357000704700BFED0200082838002008B5FFF7AB +:10358000DBFFBDE80840FFF75BBF0000024BDB68D4 +:1035900098610F20FFF756BF28380020302383F3AF +:1035A0001188FFF7F3BF000008B50146302383F30D +:1035B00011880820FFF754FF002383F3118808BD0A +:1035C000064BDB6839B1426818605A60136043608B +:1035D0000420FFF745BF4FF0FF3070472838002028 +:1035E0000368984206D01A680260506099611846D4 +:1035F000FFF726BF7047000010B50A4C23699A6890 +:1036000091420CD85A6881600360426010609A68E9 +:103610005860511A99604FF0FF33A36110BD1B68C9 +:10362000891AECE72838002010B4C0E903230023EE +:103630005DF8044B4361FFF7DFBF0000036881685A +:103640009A680A449A60426813605A6000230360D3 +:10365000024B4FF0FF329A61704700BF28380020BC +:1036600070B5124DEB692A460133EB6152F8103FF9 +:10367000934206D09A68013A9A6030262C69A36872 +:1036800003B170BDD4E900210A605160236083F367 +:103690001188D4E903312046984786F3118861697F +:1036A0000029EBD02046FFF7A7FFE7E728380020E6 +:1036B000054A30B5D369D2E908451B1B181945F1F5 +:1036C0000001C2E9080130BD283800200020704701 +:1036D000FEE70000704700004FF0FF307047000029 +:1036E000BFF34F8F024AD368DB07FCD4704700BF9B +:1036F0000020024008B5074B1B7853B9FFF7F0FFD5 +:10370000054B1A69120641BF044A5A6002F1883219 +:103710005A6008BD683A0020002002402301674536 +:1037200008B5054B1B7833B9FFF7DAFF034A136975 +:1037300043F08003136108BD683A00200020024076 +:103740007F289ABF00F58030C0020020704700003B +:103750004FF4006070470000802070477F2808B554 +:103760000BD8FFF7EDFF00F500630268013204D1CA +:1037700004308342F9D1012008BD0020FCE700009D +:103780007F2810B504461CD8FFF7AAFFFFF7B2FF49 +:103790000D4BF322DA6002221A61FFF7D1FF586164 +:1037A0001A6942F040021A614FF40061FFF798FF76 +:1037B00000F05AF9FFF7B4FF2046BDE81040FFF7CC +:1037C000CDBF002010BD00BF002002402DE9F8430E +:1037D00012F00103144606D01F4B40F203321A6068 +:1037E0000020BDE8F88385181C4A954204D91A4A7E +:1037F0004FF442711160F3E7FFF77CFFFFF770FFB2 +:10380000DFF86880451A4FF00109012C05EB01062D +:103810000F4603D8FFF784FF0120E2E73B88C8F892 +:10382000109033800020FFF75BFFC8F8100033884A +:1038300031F8022B9BB29A420CD0074B40F21F3258 +:103840001A60074B1E60074B1C60074B1F60FFF799 +:1038500067FFC6E7023CD8E7643A0020000004088E +:10386000583A0020603A00205C3A002000200240D4 +:10387000084908B50B7828B11BB9FFF73BFF0123B6 +:103880000B7008BD002BFCD0BDE808400870FFF7A6 +:1038900047BF00BF683A002008B506484FF41F41F3 +:1038A00000F0E4F8BDE808404FF400514FF08050BC +:1038B00000F0DCB8000100200846114600F084BE8C +:1038C000012000F081BE0000084600F09BBE000011 +:1038D00038B5EFF31185BDBBEFF30584C4F30804DD +:1038E0003023C4B183F31188FFF7E2FE4C0142019B +:1038F000121A44EAD06464EB01049300A4001B187C +:1039000044EA927441EB0401C900D80041EA5371C2 +:1039100085F3118838BD83F31188FFF7C9FE4D0187 +:103920004201121A45EAD06565EB01059300AD002E +:103930001B1845EA927541EB0501C900D80041EA20 +:10394000537184F3118838BDFFF7B2FE4B01440177 +:10395000241A43EAD06363EB0103A2009B00121810 +:1039600043EA947341EB0301C900D00041EA52716C +:1039700038BD00BF38B5FFF7ABFF114C114AC00886 +:1039800040EA4170A0FB025EC908A0FB040C1CEBDE +:10399000050CA1FB04404FF000035B41A1FB0212A8 +:1039A0001CEB040C43EB000011EB0E0142F1000292 +:1039B000411842F10000090941EA007038BD00BF1A +:1039C000CFF753E3A59BC42010B50244064BD2B2F7 +:1039D000904200D110BD441C00B253F8200041F8C1 +:1039E000040BE0B2F4E700BF502800400F4B30B5A5 +:1039F0001C6A240407D41C6A44F440741C621C6AC8 +:103A000044F400441C620A4C236843F4807323602E +:103A10000244084BD2B2904200D130BD441C00B2E7 +:103A200051F8045B43F82050E0B2F4E70010024084 +:103A3000007000405028004007B5012201A9002075 +:103A4000FFF7C2FF019803B05DF804FB13B504460D +:103A5000FFF7F2FFA04205D0012201A90020019446 +:103A6000FFF7C4FF02B010BD7047000070470000B0 +:103A700070470000074B45F255521A6002225A6007 +:103A800040F6FF729A604CF6CC421A60024B01225B +:103A90001A70704700300040703A0020034B1B78CA +:103AA0001BB1034B4AF6AA221A607047703A0020F5 +:103AB00000300040044B1A682AB902F1804202F536 +:103AC0000432526A1A6070476C3A0020024B4FF081 +:103AD00080725A62704700BF0010024008B5FFF7BD +:103AE000E9FF024B1868C0F3407008BD6C3A002033 +:103AF00070470000FEE700000A4B0B480B4A90425B +:103B00000BD30B4BDA1C121AC11E22F003028B429C +:103B100038BF00220021FDF785BA53F8041B40F896 +:103B2000041BECE714490008543C0020543C0020DE +:103B3000543C0020FEE7000070B51B4B01630025DC +:103B4000044686B0586085620E46FFF7D3FB04F149 +:103B50001003C4E904334FF0FF33A361134BE56155 +:103B6000D969A5600A462B46C4E9082304F134014B +:103B7000C4E900440E4AE562256580232046FFF72C +:103B8000D5FC0123E0600B4A037500927268019234 +:103B9000B268CDE90223084B6846CDE90435FFF74A +:103BA000EDFC06B070BD00BF503A00202838002060 +:103BB000B8470008BD470008353B00084B68436024 +:103BC0008B688360CB68C3600B6943614B69036298 +:103BD0008B6943620B6803607047000008B51B4B9C +:103BE0009A6A42F4FC029A629A6A22F4FC029A628D +:103BF0009A6A5A6942F4FC025A61154A5B69114695 +:103C00004FF09040FFF7DAFF02F11C0100F58060F1 +:103C1000FFF7D4FF02F1380100F58060FFF7CEFF17 +:103C200002F1540100F58060FFF7C8FF02F1700156 +:103C300000F58060FFF7C2FF02F18C0100F58060A3 +:103C4000FFF7BCFFBDE8084000F05AB80010024082 +:103C5000C447000808B500F093F9FFF73FFCBDE842 +:103C60000840FFF727BF00007047000010B5214C47 +:103C7000A36A63F4FC03A362A36A03F4FC03A362D4 +:103C80004FF0FF32A36A2369226123690023236175 +:103C90002169E168E260E268E360E268E26916498E +:103CA00042F08052E261E2690A6842F480720A607E +:103CB000226A02F44072B2F5407F1EBF4FF4803298 +:103CC00022622362236A1B0407D4236A43F44073ED +:103CD0002362236A43F40043236200F031F9A369AD +:103CE000064A43F00103A361A369136843F020036C +:103CF000136010BD00100240007000400000014041 +:103D00001E4B1A6842F001021A601A689007FCD52F +:103D10005A6822F003025A605A6812F00C02FBD172 +:103D2000196801F0F90119605A601A6842F480328A +:103D30001A601A689103FCD5114A5A604FF4045274 +:103D4000DA6230221A631A6842F080721A601A68C6 +:103D50009201FCD50B4912220A600A6802F00702A0 +:103D6000022AFAD15A6842F002025A605A6802F0F6 +:103D70000C02082AFAD11A6B1A637047001002402D +:103D80000024050000200240084A08B55169136864 +:103D90000B4003F00103536123B1054A13680BB1D3 +:103DA00050689847BDE80840FFF7C8BA00040140D2 +:103DB000743A0020084A08B5516913680B4003F0B3 +:103DC0000203536123B1054A93680BB1D068984749 +:103DD000BDE80840FFF7B2BA00040140743A002081 +:103DE000084A08B5516913680B4003F00403536196 +:103DF00023B1054A13690BB150699847BDE80840E3 +:103E0000FFF79CBA00040140743A0020084A08B544 +:103E1000516913680B4003F00803536123B1054A4D +:103E200093690BB1D0699847BDE80840FFF786BA9F +:103E300000040140743A0020084A08B5516913682B +:103E40000B4003F01003536123B1054A136A0BB111 +:103E5000506A9847BDE80840FFF770BA0004014077 +:103E6000743A0020174B10B55A691C68144004F4CA +:103E700078725A61A30604D5134A936A0BB1D06ACB +:103E80009847600604D5104A136B0BB1506B9847E6 +:103E9000210604D50C4A936B0BB1D06B9847E20511 +:103EA00004D5094A136C0BB1506C9847A30504D58F +:103EB000054A936C0BB1D06C9847BDE81040FFF7F2 +:103EC0003DBA00BF00040140743A00201A4B10B5FF +:103ED0005A691C68144004F47C425A61620504D596 +:103EE000164A136D0BB1506D9847230504D5134A3C +:103EF000936D0BB1D06D9847E00404D50F4A136E53 +:103F00000BB1506E9847A10404D50C4A936E0BB1C7 +:103F1000D06E9847620404D5084A136F0BB1506FF6 +:103F20009847230404D5054A936F0BB1D06F984787 +:103F3000BDE81040FFF702BA00040140743A0020C7 +:103F4000062108B50846FFF723FA06210720FFF7E8 +:103F50001FFA06210820FFF71BFA06210920FFF7A8 +:103F600017FA06210A20FFF713FA06211720FFF798 +:103F70000FFABDE8084006212820FFF709BA000023 +:103F800008B5FFF773FE00F067F800F03DF8FFF7A3 +:103F90006BFEBDE8084000F05DB8000002684368B1 +:103FA0001143016003B1184770470000143000F05E +:103FB0002FBA00004FF0FF33143000F029BA000090 +:103FC000383000F0A5BA00004FF0FF33383000F071 +:103FD0009FBA0000143000F0F5B900004FF0FF3137 +:103FE000143000F0EFB90000383000F04FBA000094 +:103FF0004FF0FF32383000F049BA0000012914BFF9 +:104000006FF013000020704700F06CB8044B0360A1 +:104010000023C0E90233436001230374704700BFEB +:104020006C48000838B5C36904460D461BB9042125 +:104030000844FFF7B3FF294604F1140000F0A6F985 +:10404000002806DA201D4FF40061BDE83840FFF774 +:10405000A5BF38BD00F00EB80023054A194601334C +:10406000102BC2E9001102F10802F8D1704700BF1D +:10407000743A00204FF0E023044A5A6100229A610A +:1040800007221A6108210B20FFF798B93F19010098 +:1040900008B5302383F31188FFF746FA002383F332 +:1040A000118808BD08B5FFF7F3FFBDE80840FFF72A +:1040B00045B90000026843681143016003B1184725 +:1040C00070470000024A136843F0C0031360704752 +:1040D00000440040024A136843F0C0031360704775 +:1040E0000048004037B51D4C1D4D2046FFF78EFFA0 +:1040F000009404F114001B490023202200F038F939 +:104100002022009404F13800174B184900F0B2F94E +:10411000174BC4E91735174C0C212620FFF738F947 +:104120002046FFF773FF04F11400134900940023A5 +:10413000202200F01DF904F13800104B10490094C2 +:10414000202200F097F90F4B0C212720C4E91735E6 +:1041500003B0BDE83040FFF71BB900BFF43A0020C0 +:1041600000512502CC3B0020C54000080C3C00203B +:1041700000440040603B0020EC3B0020D54000089C +:104180002C3C0020004800402DE9F047C66D376800 +:10419000F46934622107054619D014F0080118BFEC +:1041A0004FF48071E20748BF41F02001A30748BFE8 +:1041B00041F04001600748BF41F08001302383F3A4 +:1041C0001188281DFFF776FF002383F31188E2058D +:1041D0000AD5302383F311884FF48061281DFFF73F +:1041E00069FF002383F311884FF030094FF0000A74 +:1041F00014F0200838D13B0616D54FF0300905F1F0 +:10420000380A200610D589F31188504600F066F967 +:10421000002836DA0821281DFFF74CFF27F080031D +:104220003360002383F31188790614D5620612D512 +:10423000302383F31188D5E913239A4208D12B6CDC +:1042400033B11021281D27F04007FFF733FF3760F7 +:10425000002383F31188E30619D5AA6E1369B3B15D +:10426000BDE8F0475069184789F31188B38C95F879 +:10427000641028461940FFF7D5FE8AF31188F469C7 +:10428000B6E780B2308588F31188F469B9E7BDE8F4 +:10429000F087000008B50348FFF776FFBDE8084047 +:1042A000FFF74CB8F43A002008B50348FFF76CFF5D +:1042B000BDE80840FFF742B8603B0020F8B515465E +:1042C00082680669AA420B46816938BF8568761AFA +:1042D000B54204460BD218462A46FCF791FEA36964 +:1042E0002B44A361A3685B1BA3602846F8BD0CD9CF +:1042F00018463246FCF784FEAF1BE1683A4630446C +:10430000FCF77EFEE3683B44EBE718462A46FCF7E1 +:1043100077FEE368E5E7000083689342F7B515464A +:10432000044638BF8568D0E90460361AB5420BD21E +:104330002A46FCF765FE63692B446361A36828463F +:104340005B1BA36003B0F0BD0DD932460191FCF7B1 +:1043500057FE0199E068AF1B3A463144FCF750FE26 +:10436000E3683B44E9E72A46FCF74AFEE368E4E7F2 +:1043700010B50A440024C361029B8460C0E90000B8 +:10438000C0E90511C1600261036210BD08B5D0E942 +:104390000532934201D1826882B98268013282601B +:1043A0005A1C42611970D0E904329A4224BFC36892 +:1043B00043610021FFF714F9002008BD4FF0FF30E2 +:1043C000FBE7000070B5302304460E4683F31188E6 +:1043D000A568A5B1A368A269013BA360531CA361B2 +:1043E00015782269934224BFE368A361E3690BB1A6 +:1043F00020469847002383F31188284607E031467A +:104400002046FFF7DDF80028E2DA85F3118870BD59 +:104410002DE9F74F04460E4617469846D0F81C90F3 +:104420004FF0300A8AF311884FF0000B154665B142 +:104430002A4631462046FFF741FF034660B9414610 +:104440002046FFF7BDF80028F1D0002383F3118840 +:10445000781B03B0BDE8F08FB9F1000F03D00190D5 +:104460002046C847019B8BF31188ED1A1E448AF33E +:104470001188DCE7C0E90511C160C3611144009BEC +:104480008260C0E90000016103627047F8B504462C +:104490000D461646302383F31188A768A7B1A36899 +:1044A000013BA36063695A1C62611D70D4E9043248 +:1044B0009A4224BFE3686361E3690BB120469847E1 +:1044C000002080F3118807E031462046FFF778F896 +:1044D0000028E2DA87F31188F8BD0000D0E905234F +:1044E0009A4210B501D182687AB98268013282603D +:1044F0005A1C82611C7803699A4224BFC368836195 +:104500000021FFF76DF8204610BD4FF0FF30FBE7AC +:104510002DE9F74F04460E4617469846D0F81C90F2 +:104520004FF0300A8AF311884FF0000B154665B141 +:104530002A4631462046FFF7EFFE034660B9414662 +:104540002046FFF73DF80028F1D0002383F31188BF +:10455000781B03B0BDE8F08FB9F1000F03D00190D4 +:104560002046C847019B8BF31188ED1A1E448AF33D +:104570001188DCE70B460146184600F02DB8000014 +:1045800000F040B8012838BF012010B5044620468D +:1045900000F030F830B900F007F808B900F00CF876 +:1045A0008047F4E710BD0000024B1868BFF35B8F33 +:1045B000704700BF4C3C002008B5062000F084F88E +:1045C0000120FFF785F80000024B0A4601461868F3 +:1045D000FFF772B91811002010B5054C13462CB125 +:1045E0000A4601460220AFF3008010BD2046FCE7DA +:1045F00000000000024B01461868FFF761B900BFD8 +:1046000018110020024B01461868FFF75DB900BF82 +:104610001811002010B501390244904201D1002048 +:1046200005E0037811F8014FA34201D0181B10BD1B +:104630000130F2E72DE9F041A3B1C91A177801441E +:10464000044603F1FF3C8C42204601D9002009E0DA +:104650000578BD4204F10104F5D10CEB0405D61830 +:10466000A54201D1BDE8F08115F8018D16F801EDE4 +:10467000F045F5D0E7E700001F2938B504460D46A0 +:1046800004D9162303604FF0FF3038BD426C12B1DD +:1046900052F821304BB9204600F030F82A46014646 +:1046A0002046BDE8384000F017B8012B0AD0591C4D +:1046B00003D1162303600120E7E7002442F82540D8 +:1046C000284698470020E0E7024B01461868FFF7AC +:1046D000D3BF00BF1811002038B5074D0023044692 +:1046E000084611462B60FEF7F7FF431C02D12B68EA +:1046F00003B1236038BD00BF503C0020FEF7E6BF89 +:10470000034611F8012B03F8012B002AF9D1704759 +:104710006F72672E6172647570696C6F742E486970 +:104720007465634D6F7361696300000040A2E4F13A +:10473000646891060041A3E5F265699207000000F4 +:104740004261642043414E496661636520696E643D +:1047500065782E00800000000080000000008000CE +:1047600000000000000000000D18000829200008CB +:10477000851F00084D18000859180008591A00082C +:104780001D1800082D180008211800082918000815 +:10479000251800087D19000831180008F9220008C2 +:1047A000411800085119000863300000A8470008AC +:1047B00080380020503A00206D61696E0069646C99 +:1047C00065000000A010002800000000FAAAAAAAB4 +:1047D00050040024BFFF000000770000000000002C +:1047E0001410AA0000000000AAAAFAAA04005000AF +:1047F000FBFF0000000000009977000000000000AF +:1048000000000000AAAAAAAA00000000FFFF000002 +:104810000000000000000000000000000000000098 +:10482000AAAAAAAA00000000FFFF000000000000E2 +:10483000000000000000000000000000AAAAAAAAD0 +:1048400000000000FFFF000000000000000000006A +:104850000000000000000000AAAAAAAA00000000B0 +:10486000FFFF00000000000000000000000000004A +:10487000C93F0008B53F0008F13F0008DD3F0008D0 +:10488000E93F0008D53F0008C13F0008AD3F0008E0 +:10489000FD3F000800000000F803000000000000D9 +:1048A0000098030000000000FE2A0100D20400006E +:1048B0001C110020000000000000000000000000AB +:1048C00000000000000000000000000000000000E8 +:1048D00000000000000000000000000000000000D8 +:1048E00000000000000000000000000000000000C8 +:1048F00000000000000000000000000000000000B8 +:1049000000000000000000000000000000000000A7 +:0449100000000000A3 :00000001FF diff --git a/Tools/bootloaders/HolybroG4_Compass_bl.bin b/Tools/bootloaders/HolybroG4_Compass_bl.bin index 1fae62e434005d..e9415120d2456d 100755 Binary files a/Tools/bootloaders/HolybroG4_Compass_bl.bin and b/Tools/bootloaders/HolybroG4_Compass_bl.bin differ diff --git a/Tools/bootloaders/HolybroG4_GPS_bl.bin b/Tools/bootloaders/HolybroG4_GPS_bl.bin index 6889581a3b3206..53050cf9b337ae 100755 Binary files a/Tools/bootloaders/HolybroG4_GPS_bl.bin and b/Tools/bootloaders/HolybroG4_GPS_bl.bin differ diff --git a/Tools/bootloaders/HolybroG4_GPS_bl.elf b/Tools/bootloaders/HolybroG4_GPS_bl.elf index 66b34a15b100fb..02ecaa18732328 100755 Binary files a/Tools/bootloaders/HolybroG4_GPS_bl.elf and b/Tools/bootloaders/HolybroG4_GPS_bl.elf differ diff --git a/Tools/bootloaders/HolybroG4_GPS_bl.hex b/Tools/bootloaders/HolybroG4_GPS_bl.hex index b8ae6e861be360..2b20bbc5869292 100644 --- a/Tools/bootloaders/HolybroG4_GPS_bl.hex +++ b/Tools/bootloaders/HolybroG4_GPS_bl.hex @@ -1,1428 +1,1404 @@ :020000040800F2 -:1000000000070020F504000899300008513000086E -:10001000793000085130000871300008F7040008FA -:10002000F7040008F7040008F70400087940000806 -:10003000F7040008F7040008F7040008F7040008B4 -:10004000F7040008F7040008F7040008F7040008A4 -:10005000F7040008F7040008C9530008F15300082A -:10006000195400084154000869540008F7040008B6 -:10007000F7040008F7040008F7040008F704000874 -:10008000F7040008F7040008F7040008F704000864 -:10009000F7040008013000081530000891540008EA -:1000A000F7040008F7040008F7040008F704000844 -:1000B00079550008F7040008F7040008F704000861 -:1000C000F7040008F7040008F7040008F704000824 -:1000D000F7040008F704000865550008F704000855 -:1000E000F5540008F7040008F7040008F7040008B6 -:1000F000F7040008F7040008F7040008F7040008F4 -:10010000F7040008F7040008F7040008F7040008E3 -:10011000F7040008F7040008F7040008F7040008D3 -:10012000F7040008F7040008F7040008F7040008C3 -:10013000F7040008F7040008F7040008F7040008B3 -:10014000F7040008F7040008F7040008F7040008A3 -:10015000F7040008F7040008F7040008F704000893 -:10016000F7040008F7040008F7040008F704000883 -:10017000F7040008F7040008F7040008F704000873 -:10018000F7040008F7040008F7040008F704000863 -:10019000F7040008F7040008293000083D30000883 -:1001A000F7040008F7040008F7040008F704000843 -:1001B000F7040008F7040008F7040008F704000833 -:1001C000F7040008F7040008F7040008F704000823 -:1001D000F7040008F7040008F7040008F704000813 -:1001E00045180008000000000000000000000000AA -:1001F00053B94AB9002908BF00281CBF4FF0FF318E -:100200004FF0FF3000F074B9ADF1080C6DE904CE89 -:1002100000F006F8DDF804E0DDE9022304B07047E1 -:100220002DE9F047089D04468E46002B4DD18A42A9 -:10023000944669D9B2FA82F252B101FA02F3C2F1DC -:10024000200120FA01F10CFA02FC41EA030E94406D -:100250004FEA1C48210CBEFBF8F61FFA8CF708FB8E -:1002600016E341EA034306FB07F199420AD91CEB66 -:10027000030306F1FF3080F01F81994240F21C8198 -:10028000023E63445B1AA4B2B3FBF8F008FB1033E0 -:1002900044EA034400FB07F7A7420AD91CEB040415 -:1002A00000F1FF3380F00A81A74240F207816444E5 -:1002B000023840EA0640E41B00261DB1D44000236A -:1002C000C5E900433146BDE8F0878B4209D9002DCE -:1002D00000F0EF800026C5E9000130463146BDE858 -:1002E000F087B3FA83F6002E4AD18B4202D38242C2 -:1002F00000F2F980841A61EB030301209E46002D71 -:10030000E0D0C5E9004EDDE702B9FFDEB2FA82F2C5 -:10031000002A40F09280A1EB0C014FEA1C471FFA23 -:100320008CFE0126200CB1FBF7F307FB131140EA0A -:1003300001410EFB03F0884208D91CEB010103F1D7 -:10034000FF3802D2884200F2CB804346091AA4B299 -:10035000B1FBF7F007FB101144EA01440EFB00FE6D -:10036000A64508D91CEB040400F1FF3102D2A645D2 -:1003700000F2BB800846A4EB0E0440EA03409CE771 -:10038000C6F12007B34022FA07FC4CEA030C20FA1E -:1003900007F401FA06F31C43F9404FEA1C4900FA3E -:1003A00006F3B1FBF9F8200C1FFA8CFE09FB1811BB -:1003B00040EA014108FB0EF0884202FA06F20BD92E -:1003C0001CEB010108F1FF3A80F08880884240F27E -:1003D0008580A8F102086144091AA4B2B1FBF9F0C2 -:1003E00009FB101144EA014100FB0EFE8E4508D9BD -:1003F0001CEB010100F1FF346CD28E456AD9023842 -:10040000614440EA0840A0FB0294A1EB0E01A14226 -:10041000C846A64656D353D05DB1B3EB080261EB94 -:100420000E0101FA07F722FA06F3F1401F43C5E96E -:10043000007100263146BDE8F087C2F12003D840A4 -:100440000CFA02FC21FA03F3914001434FEA1C47E6 -:100450001FFA8CFEB3FBF7F007FB10360B0C43EAD8 -:10046000064300FB0EF69E4204FA02F408D91CEB88 -:10047000030300F1FF382FD29E422DD90238634486 -:100480009B1B89B2B3FBF7F607FB163341EA034126 -:1004900006FB0EF38B4208D91CEB010106F1FF3875 -:1004A00016D28B4214D9023E6144C91A46EA00466C -:1004B00038E72E46284605E70646E3E61846F8E6FE -:1004C0004B45A9D2B9EB020864EB0C0E0138A3E747 -:1004D0004646EAE7204694E74046D1E7D0467BE728 -:1004E000023B614432E7304609E76444023842E7A0 -:1004F000704700BF02E000F000F8FEE772B6374830 -:1005000080F30888364880F3098836483649086001 -:1005100040F20000CCF200004EF63471CEF2000141 -:100520000860BFF34F8FBFF36F8F40F20000C0F23F -:10053000F0004EF68851CEF200010860BFF34F8FF5 -:10054000BFF36F8F4FF00000E1EE100A4EF63C71E2 -:10055000CEF200010860062080F31488BFF36F8F8D -:1005600004F062FD04F0F4FD4FF055301F491B4AC2 -:1005700091423CBF41F8040BFAE71D49184A9142E9 -:100580003CBF41F8040BFAE71A491B4A1B4B9A423D -:100590003EBF51F8040B42F8040BF8E7002018495D -:1005A000184A91423CBF41F8040BFAE704F040FDC1 -:1005B00004F014FE144C154DAC4203DA54F8041B3D -:1005C0008847F9E700F042F8114C124DAC4203DACB -:1005D00054F8041B8847F9E704F028BD0007002001 -:1005E000002300200000000808ED00E000010020CA -:1005F0000007002090580008002300208C230020D2 -:100600009023002078690020E0010008E401000840 -:10061000E4010008E40100082DE9F04F2DED108AF7 -:10062000C1F80CD0C3689D46BDEC108ABDE8F08FC0 -:10063000002383F311882846A047002004F082F9A4 -:10064000FEE704F0E5F800DFFEE70000F8B501F092 -:100650000FF904F08BFC074604F0DCFC0546B8BB40 -:10066000204B9F4234D001339F4234D01E4B27F0A1 -:10067000FF029A4232D1F8B200F028FF2E4642F231 -:10068000107400F029FF08B10024264601F07CFC1C -:1006900020B1032000F07CF80024264635B1134B2E -:1006A0009F4203D004F0AEFC00242646002004F054 -:1006B00067FC0EB100F082F801F04CFA00F03EFF4A -:1006C00001F034F9204600F0D1F800F077F8F9E7AE -:1006D0002E460024D5E704460126D2E7064640F61A -:1006E000C414CEE7010007B0000008B0263A09B0F4 -:1006F00008B501F0E7F8A0F120035842584108BDC1 -:1007000007B541F21203022101A8ADF8043001F04F -:10071000F7F803B05DF804FB38B5302383F3118894 -:10072000174803680BB104F0CBF9164A14480023AC -:100730004FF47A7104F0BAF9002383F31188124C54 -:10074000236813B12368013B2360636813B16368B6 -:10075000013B63600D4D2B7833B963687BB9022090 -:1007600001F086F9322363602B78032B07D163688D -:100770002BB9022001F07CF94FF47A73636038BD25 -:100780009023002019070008B0240020A82300208F -:10079000084B187003280CD8DFE800F008050208A1 -:1007A000022001F05BB9022001F04EB9024B002299 -:1007B0005A607047A8230020B024002010B501F033 -:1007C000E3FB30B1234B03221A70234B00225A6003 -:1007D00010BD224B224A1C4619680131F8D004335F -:1007E0009342F9D16268A242F2D31E4B9B6803F197 -:1007F000006303F510439A42EAD204F0D5FB04F0FB -:10080000E7FB002001F0ACF80220FFF7C1FF164B18 -:100810009A6D00229A65996F9A67996FD96DDA651A -:10082000D96FDA67D96F196E1A66D3F88010C3F8DA -:100830008020D3F8803072B64FF0E0233021C3F827 -:10084000084DD4E9003281F311889D4683F308886E -:100850001047BDE7A8230020B02400200090000826 -:100860002090000800230020001002402DE9F04FE6 -:1008700093B0AC4B00902022FF210AA89D6801F0A4 -:1008800013F9A94A1378A3B9A8480121036011708C -:10089000302383F3118803680BB104F011F9A44AE3 -:1008A000A24800234FF47A7104F000F9002383F387 -:1008B0001188009B13B19F4B009A1A609E4A009CBE -:1008C0001378032B1EBF002313709A4A4FF0000ABF -:1008D00018BF5360D3465646D146012001F0BEF8FA -:1008E00024B1944B1B68002B00F01582002000F00F -:1008F000E9FF0390039B002B01DA00F073FE039BDA -:10090000002BEDDB012001F09FF8039B213B162B10 -:10091000E3D801A252F823F0750900089D090008E8 -:10092000310A0008DB080008DB080008DB080008C3 -:10093000BB0A00088B0C0008A50B0008070C000878 -:100940002F0C0008550C0008DB080008670C000895 -:10095000DB080008D90C0008150A0008DB080008AD -:100960001D0D000881090008150A0008DB080008B1 -:10097000070C00080220FFF7BBFE002840F0F581BD -:10098000009B0221BAF1000F08BF1C4605A841F2E6 -:100990001233ADF8143000F0B3FF9EE74FF47A70D5 -:1009A00000F090FF071EEBDB0220FFF7A1FE0028FE -:1009B000E6D0013F052F00F2DA81DFE807F0030AF5 -:1009C0000D10133605230593042105A800F098FFA8 -:1009D00017E054480421F9E758480421F6E758483D -:1009E0000421F3E74FF01C08404600F0BBFF08F17C -:1009F00004080590042105A800F082FFB8F12C0F2F -:100A0000F2D1012000FA07F747EA0B0B5FFA8BFBE4 -:100A10004FF0000901F094F826B10BF00B030B2BFB -:100A200008BF0024FFF76CFE57E746480421CDE7D6 -:100A3000002EA5D00BF00B030B2BA1D10220FFF74A -:100A400057FE074600289BD0012000F089FF0220B6 -:100A5000FFF79EFE00261FFA86F8404600F090FF42 -:100A6000044690B10021404600F0A2FF0136002864 -:100A7000F1D1BA46044641F21213022105A8ADF89D -:100A800014303E4600F03CFF27E70120FFF780FED0 -:100A90002546244B9B68AB4207D9284600F062FFED -:100AA000013040F067810435F3E7234B00251D70CA -:100AB000204BBA465D603E46ACE7002E3FF460AF87 -:100AC0000BF00B030B2B7FF45BAF0220FFF760FEF4 -:100AD000322000F0F7FEB0F10008FFF651AF18F039 -:100AE00003077FF44DAF0F4A926808EB050393426A -:100AF0003FF646AFB8F5807F3FF742AF124B019308 -:100B0000B84523DD4FF47A7000F0DCFE0390039AC1 -:100B1000002AFFF635AF019B039A03F8012B01373A -:100B2000EDE700BF00230020AC240020902300202C -:100B300019070008B0240020A82300200423002067 -:100B4000082300200C230020AC230020C820FFF73E -:100B5000CFFD074600283FF413AF1F2D11D8C5F174 -:100B6000200242450AAB25F0030028BF42468349D4 -:100B70000192184400F086FF019A8048FF2100F09E -:100B800093FF4FEAA8037D490193C8F387022846E3 -:100B900000F092FF064600283FF46DAF019B05EB85 -:100BA000830537E70220FFF7A3FD00283FF4E8AEF6 -:100BB00000F010FF00283FF4E3AE0027B846704B6A -:100BC0009B68BB4218D91F2F11D80A9B01330ED046 -:100BD00027F0030312AA134453F8203C0593404620 -:100BE000042205A901F0BAF904378046E7E7384640 -:100BF00000F0B8FE0590F2E7CDF81480042105A8B6 -:100C000000F07EFE06E70023642104A8049300F0B0 -:100C10006DFE00287FF4B4AE0220FFF769FD0028C6 -:100C20003FF4AEAE049800F0CBFE0590E6E700235B -:100C3000642104A8049300F059FE00287FF4A0AEBC -:100C40000220FFF755FD00283FF49AAE049800F00B -:100C5000B9FEEAE70220FFF74BFD00283FF490AE13 -:100C600000F0C8FEE1E70220FFF742FD00283FF454 -:100C700087AE05A9142000F0C3FE042107460490A6 -:100C800004A800F03DFE3946B9E7322000F01AFE14 -:100C9000071EFFF675AEBB077FF472AE384A926846 -:100CA00007EB090393423FF66BAE0220FFF720FDEE -:100CB00000283FF465AE27F003074F44B9453FF4E1 -:100CC000A9AE484600F04EFE0421059005A800F0AC -:100CD00017FE09F10409F1E74FF47A70FFF708FDF8 -:100CE00000283FF44DAE00F075FE002844D00A9B6A -:100CF00001330BD008220AA9002000F0DDFE0028F5 -:100D00003AD02022FF210AA800F0CEFEFFF7F8FC1F -:100D10001C4803F01DFE13B0BDE8F08F002E3FF419 -:100D20002FAE0BF00B030B2B7FF42AAE00236421B4 -:100D300005A8059300F0DAFD074600287FF420AEF1 -:100D40000220FFF7D5FC804600283FF419AEFFF7DC -:100D5000D7FC41F2883003F0FBFD059800F006FF58 -:100D6000464600F0EDFE3C46B7E5064652E64FF03B -:100D7000000905E6BA467EE637467CE6AC2300204D -:100D800000230020A0860100094A136849F2690087 -:100D900099B21B0C00FB01331360064B186844F238 -:100DA000506182B2000C01FB0200186080B27047F3 -:100DB000142300201023002010B500211022044627 -:100DC00000F072FE034B03CB206061601868A060E6 -:100DD00010BD00BF9075FF1F2DE9F041ADF54E7DB0 -:100DE0000DF134086CAC40F2751207460D460EA8A2 -:100DF0000021C8F8001000F057FE4FF4C472002123 -:100E0000204600F051FE02F04FF9274B4FF47A7262 -:100E1000B0FBF2F0186093E80700022384E80700B3 -:100E20000DF5E9702382FFF7C7FF41F604531F4910 -:100E3000238406A804F03CFC1B2384F832310DF215 -:100E4000E32206AB0DF1300C1E4603CE6645106062 -:100E50005160334602F10802F6D13188B3789370BD -:100E6000118020464146012200F09AFE00230393A0 -:100E7000AB7E029305F11903019380B20123CDE902 -:100E800004800093E97E06A3D3E90023384602F0EC -:100E9000C9FC0DF54E7DBDE8F08100BFAFF30080C9 -:100EA0009E6AC421818A46EEB8240020C0560008FC -:100EB0002DE9F0412C4C237ADAB080460D465BBB1D -:100EC00027A9284600F07CFF0746002842D19DF85C -:100ED0009D60C82E3ED801464FF4A662204600F021 -:100EE000E3FD4FF48073C4F8F8314FF40073C4F895 -:100EF0000C334FF44073C4F8203432460DF19E0198 -:100F000004F1090000F0BEFD26449DF89C30777284 -:100F100023720BB9EB7E23728122002106AC27A835 -:100F200000F0C2FD0122214627A800F085FF002322 -:100F30000393AB7E029305F1190380B2019328233A -:100F4000CDE904400093E97E05A3D3E900234046A0 -:100F500002F068FC5AB0BDE8F08100BFAFF300803A -:100F600026417272DF25D7B7605E0020F0B5254EAE -:100F70004FF48A7505FB0065F1B096F8D83085F816 -:100F8000DC300024D822214685F8E8403AA800F059 -:100F90008BFD06F1090000F07FFDD5F8E4308DF8F7 -:100FA000F000C2B206AF06F109010DF1F100CDE982 -:100FB0003A3400F067FD394601223AA800F068FF94 -:100FC00080B2CDE9047008230127CDE9023706F18C -:100FD000D803019330230093317A0B4807A3D3E958 -:100FE000002302F01FFCA04206DD02F05DF8C5F808 -:100FF000E000384671B0F0BD2046FBE778F6339F3D -:1010000093CACD8D605E0020D03400202DE9F04FD2 -:10101000274FDFF8A880274E87B0384602F02EFC15 -:10102000034600283DD00024CDE90344ADF8144028 -:10103000027B8DF8142099684068029403AA03C2C9 -:101040001B681D4D43F000430293A146A2462B6846 -:10105000D3F810B002F02AF810EB080241F10003B7 -:101060002846CDF800A002A9D84704F22C5440F637 -:1010700058230028C8BF49F0010905F5A5559C4231 -:1010800005F11005E3D1B9F1000F05D0384602F0A3 -:10109000F9FB86F800A0C0E73378072B04D80133AA -:1010A000337007B0BDE8F08F014802F0EBFBF8E7C2 -:1010B000D0340020956300200035002040420F000E -:1010C00070B50D4614461E4602F008FB50B9022EBC -:1010D00010D1012C0ED112A3D3E90023C5E90023BE -:1010E000012007E0282C10D005D8012C09D0052CB0 -:1010F0000FD0002070BD302CFBD10BA3D3E900230F -:10110000ECE70BA3D3E90023E8E70BA3D3E9002323 -:10111000E4E70BA3D3E90023E0E700BFAFF30080CF -:10112000401DA12026812A0B78F6339F93CACD8DCE -:101130009E6AC421818A46EE26417272DF25D7B7A6 -:10114000F017304A39059E5638B505460E4C002139 -:10115000013500F02DFCA4F82C55B4F82C0500F056 -:101160000FFC78B1B4F82C0500F01AFC014648B920 -:10117000B4F82C0500F01CFCB4F82C350133A4F8AD -:101180002C35EAE738BD00BF605E0020F8B50E4C94 -:101190000E4F0226A4F5805343F8307C237E3BB9E2 -:1011A00065692DB1284600F06DFF284604F036FA37 -:1011B000204600F067FFA4F5A554012EA4F1100409 -:1011C00000D1F8BD0126E5E7E059002028570008C6 -:1011D0002DE9F04F8FB000AF05460C4602F07EFAC5 -:1011E000002849D1237E022B1BD1E38A012B18D181 -:1011F00001F05AFF0646FFF7C7FD03464FF4C870DB -:10120000DFF8C482B3FBF0F206F5167602FB10336A -:1012100016FA83F3C8F80030E37E33B9A34B0022FB -:101220001A703C37BD46BDE8F08F07F12401204617 -:1012300000F084FD0028F4D107F11400FFF7BCFD95 -:1012400097F8264007F11401224607F1270004F021 -:10125000FDF90028E2D10F2C08D8944B1C70D8F867 -:101260000030A3F51673C8F80030DAE797F82410B9 -:10127000284602F02BFAD4E7E38A282B2BD010D88B -:10128000012B23D0052BCCD1BFF34F8F8849894B3D -:10129000CA6802F4E0621343CB60BFF34F8F00BF14 -:1012A000FDE7302BBDD1844EE17E327A9142B8D138 -:1012B000607E3146002291F8DC50854200F0A58026 -:1012C0000132042A01F58A71F5D1AAE721462846A0 -:1012D000FFF782FDA5E721462846FFF7E9FDA0E7D5 -:1012E000B2F8EC507B6005F103094FEA99094FEA27 -:1012F0008902D11DC908A8EBC1039D46EB46002118 -:10130000584600F0D1FB04F1EE012A46314458461C -:1013100000F0B8FB7B6813B9012000F021FB96F8C0 -:10132000D20000F02DFB044630B9307200F052FBC1 -:10133000204600F015FBB1E0D6F8D4203AB996F873 -:10134000D200B6F82C25824201D8FFF7FDFED6F870 -:10135000D4202A44944208D296F8D200B6F82C251C -:101360000130824201D8FFF7EFFE70685FFA89F220 -:10137000594600F0A1FB08B9C54679E0726896F8B5 -:10138000D2002A447260D6F8D42005EB0209C6F8D0 -:10139000D49000F0F5FA814509D396F8D220D6F81A -:1013A000D4000132001B86F8D220C6F8D400FF2DED -:1013B0000FD80024347200F00DFB204600F0D0FA64 -:1013C00000F0E2FD3D4B188108B9FFF7F7F9C5467B -:1013D00027E7BB6896F8D9000AFB0362FB68D2F8DE -:1013E000E41082F8E83001F58061C2F8E030C2F81C -:1013F000E410FFF7BBFDFFF709FE96F8D920013294 -:1014000002F0030286F8D920B6E74FF48A7A0AFB85 -:1014100002F505F1EA013144204600F065FDF8606F -:1014200000287FF4FEAE3544012285F8E82001F063 -:101430003BFED5F8E020D6ED007ADFED216A801A78 -:10144000192838BF192040F6B832904228BF1046FC -:10145000B8EE677A07EE900AF8EEE77A67EEA67ABA -:10146000DFED186AE7EE267AFCEEE77AC6ED007A41 -:1014700096F8D930BB60BA6873680AFB02F4321977 -:1014800092F8E81059B1D2F8E4108B42E8463FF4E4 -:1014900027AF002182F8E810C2F8E010C546736853 -:1014A000064A9B0A01331381BBE600BFC934002002 -:1014B00000ED00E00400FA05605E0020B824002082 -:1014C000CDCCCC3D6666663FCC340020014B187015 -:1014D000704700BFC424002038B54FF00054134BB0 -:1014E00022689A4220D1124B627D12481A70237DE5 -:1014F00003724FF48073C0F8F8314FF40073C0F8F2 -:101500000C3300254FF44073C0F820340A49C0F86A -:10151000E450C922093000F0B5FAE02229462046FD -:1015200000F0C2FA012038BD0020FCE79AAD44C5A6 -:10153000C4240020605E00201600002037B500F0B3 -:1015400023FD1F4C1F4D2049288102236B71236806 -:10155000204604F580545B6801229847D4F8B034E3 -:1015600019495B68012204F59660984700230193AE -:10157000164B174900931748174B4FF4805202F04F -:101580007DF8164B197811B1124802F09FF801F05E -:101590008BFD0446FFF7F8FB4FF4C873B0FBF3F282 -:1015A00002FB130304F5167010FA83F00C4B18605D -:1015B00003F030FD08B10F232B8103B030BD00BF15 -:1015C00000350020B824002040420F00C110000860 -:1015D000C8240020D0340020D1110008C4240020E9 -:1015E000CC3400202DE9F04F2DED028B002593B077 -:1015F0000DF12C089FED838BDFF84492FFF706FD79 -:101600000A95ADF834500B95C8F804500026834C69 -:10161000DFF80CB2374601238DF81C3023688DF8B3 -:101620001D508DED008B0DF11D02D3F808A007A908 -:1016300000232046D0479DF81CA0BAF1000F24D00B -:10164000D9F8143083F48063C9F8143010220021D3 -:101650000EA800F029FA236808AA5F690AA90DF10B -:101660001E032046B84798E803000FAB83E8030049 -:101670009DF834308DF844300A9B0E930EA9DDE9B5 -:101680000823584602F0DCFA574606F22C5640F67C -:10169000582304F5A5549E4204F11004BBD1002F39 -:1016A000B4D15F4802F01AF800283FD15D4E01F036 -:1016B000FBFC3368984239D301F0F6FC0446FFF78F -:1016C00063FB4FF4C873B0FBF3F202FB130304F5A2 -:1016D000167010FA83F03060534E8DF8287037780A -:1016E00017B901238DF82830C7F11004E4B20EA811 -:1016F000FFF762FB062C28BF06240EAB2246D91941 -:101700000DF1290000F0BEF90AAB039318230293F0 -:101710000134464B0193E4B2012300934048049402 -:101720003AA3D3E9002302F01FF8357001F0BCFCA6 -:101730003F4A404C1368C31AB3F57A7F2FD3106029 -:1017400001F0B4FC02460B46354802F0A5F83448D7 -:1017500001F0C4FF18B3237A374E002B14BF0323C4 -:101760000223737101F0A0FC0EAF4FF47A730122D3 -:10177000B0FBF3F039463060304600F0B7FA18237A -:1017800002932E4B019380B240F25513CDE90370C2 -:10179000009323481FA3D3E9002301F0E5FF237A38 -:1017A00093B101F081FC002607464FF48A7894F843 -:1017B000D900304400F0030008FB004393F8E82010 -:1017C00072B10136042EF2D1C82003F0C1F8237A99 -:1017D000002B7FF40DAF13B0BDEC028BBDE8F08F92 -:1017E000D3F8E02042B12368FA2B38BFFA23BA1AA3 -:1017F0000533B2EB430FE4D3FFF7B8FB0028E0D189 -:10180000E2E700BF0000000000000000401DA12032 -:1018100026812A0BF1C6A7C1D068080F0035002029 -:10182000D0340020CC340020C9340020C83400203B -:1018300090630020605E0020B824002094630020A4 -:101840000008004808B5064800F052FF054800F0BF -:101850004FFFBDE80840044A0449002003F0D8BE09 -:1018600000350020B0490020EC6300208D110008F5 -:101870007047000070B5104B1B780133DBB2012BB1 -:101880000C4612D80D4B1D6829684FF47A730E6A06 -:10189000A2FB0332014622462846B047844204D1C7 -:1018A000074B00221A70012070BD4FF4FA7003F04C -:1018B0004FF80020F8E700BF182300201C23002069 -:1018C000DC63002007B50023024601210DF107006B -:1018D0008DF80730FFF7CEFF20B19DF8070003B069 -:1018E0005DF804FB4FF0FF30F9E700000A4608B549 -:1018F0000421FFF7BFFF80F00100C0B2404208BDE5 -:1019000030B4074B0A461978064B53F82140236838 -:10191000DD69054B0146AC46204630BC604700BF40 -:10192000DC6300201C230020A086010070B503F0BA -:10193000B7F9094E094D3080002428683388834266 -:1019400008D903F0A9F92B6804440133B4F5104F0A -:101950002B60F2D370BD00BFDE63002098630020CF -:1019600003F052BA00F1006000F5104000687047C3 -:1019700000F10060920000F5104003F0CFB90000C4 -:10198000054B1A68054B1B889B1A834202D91044E9 -:1019900003F082B90020704798630020DE630020C6 -:1019A000024B1B68184403F07FB900BF9863002006 -:1019B000024B1B68184403F089B900BF98630020EC -:1019C0000020704700F10050A0F51040D0F89005BD -:1019D00070470000064991F8243033B10023086AAB -:1019E00081F824300822FFF7C3BF0120704700BFF1 -:1019F0009C630020014B1868704700BF002004E082 -:101A000030B50F4B0F4C1B682288C3F30B03013812 -:101A1000934208440BD164680A46013C8242134653 -:101A20000BD214F9015F2DB102F8015BF6E7814298 -:101A30000B4602D22C2203F8012B581A30BD00BFEE -:101A4000002004E020230020022802BF024B4FF0B8 -:101A500080629A61704700BF00080048022802BFF8 -:101A6000024B4FF480629A61704700BF0008004843 -:101A7000022801BF024A536983F4806353617047AF -:101A80000008004810B50023934203D0CC5CC45436 -:101A90000133F9E710BD000003460246D01A12F9DF -:101AA000011B0029FAD1704702440346934202D039 -:101AB00003F8011BFAE770472DE9F8431F4D144660 -:101AC00095F824200746884652BBDFF870909CB3F7 -:101AD00095F824302BB92022FF2148462F62FFF7CA -:101AE000E3FF95F82400C0F10802A24228BF224675 -:101AF000D6B24146920005EB8000FFF7C3FF95F890 -:101B00002430A41B1E44F6B2082E17449044E4B2BD -:101B100085F82460DBD1FFF75DFF0028D7D108E00E -:101B20002B6A03EB82038342CFD0FFF753FF0028D9 -:101B3000CBD10020BDE8F8830120FBE79C630020A7 -:101B4000024B1A78024B1A70704700BFDC6300200A -:101B50001823002003494FF461430B60024B1868BF -:101B600002F0BCBDC46300201C230020094B10B54B -:101B70001822044600211846FFF796FF064A074B35 -:101B8000127804600146BDE8104053F8220002F0CC -:101B9000A5BD00BFC4630020DC6300201C2300201F -:101BA0002DE9F0470D46044600219046284640F2B4 -:101BB0007912FFF779FF234620220021284601F001 -:101BC000E1FF231D02222021284601F0DBFF631DD7 -:101BD00003222221284601F0D5FFA31D032225213F -:101BE000284601F0CFFF04F10803102228212846DF -:101BF00001F0C8FF04F1100308223821284601F043 -:101C0000C1FF04F1110308224021284601F0BAFF68 -:101C100004F1120308224821284601F0B3FF04F121 -:101C2000140320225021284601F0ACFF04F11803D0 -:101C300040227021284601F0A5FF04F1200308226C -:101C4000B021284601F09EFF04F121030822B821AB -:101C5000284601F097FF04F12207C0263B46314693 -:101C600008222846083601F08DFFB6F5A07F07F15F -:101C70000107F3D104F1320308223146284601F06E -:101C800081FF002704F1330A94F832304FEAC70984 -:101C90009F4209F5A47615D3B8F1000F08D131465B -:101CA00004F599730722284601F06CFF09F24F16DC -:101CB000274694F832213B1B93420CD3F01DC008F9 -:101CC000BDE8F0870AEB070308223146284601F0F9 -:101CD00059FF0137D8E707F2331331460822284667 -:101CE00001F050FF08360137E3E7000013B5044662 -:101CF0000846002101602346C0F80310202201900D -:101D000001F040FF0198231D0222202101F03AFF3B -:101D10000198631D0322222101F034FF0198A31DC5 -:101D20000322252101F02EFF019804F1080310225F -:101D3000282101F027FF072002B010BDF7B50023CE -:101D4000047F00910E4607221946054601F0DEFD8C -:101D5000731C0093012200230721284601F0D6FDC1 -:101D6000C4B9B31C0093052223460821284601F07C -:101D7000CDFD0D243746B278BB1B934211D32B7F88 -:101D8000A88A0734E408BBB9844294BF002001202C -:101D900003B0F0BDAB8ADB00083BDB08B37008245E -:101DA000E8E7FB1C0093214600230822284601F0A7 -:101DB000ADFD08340137DEE7201A18BF0120E7E740 -:101DC000F7B50023047F00910E4608221946054608 -:101DD00001F09CFD731CC4B90822009311462346F0 -:101DE000284601F093FD1024012372785F1C013B0B -:101DF000934211D32B7FA88A0734E408BBB98442ED -:101E000094BF0020012003B0F0BDAB8ADB00083B8B -:101E1000DB0873700824E7E7F319009321460023D9 -:101E20000822284601F072FD08343B46DDE7201AFF -:101E300018BF0120E7E70000F8B50E460546144636 -:101E4000002181223046FFF72FFE2B460822002179 -:101E5000304601F097FE7CB96B1C07220821304602 -:101E600001F090FE0F2401236A785F1C013B93422E -:101E700004D3E01DC008F8BD0824F4E7EB1921469F -:101E80000822304601F07EFE08343B46ECE70000B5 -:101E9000F8B50E46054614460021CE223046FFF71F -:101EA00003FE2B4628220021304601F06BFE7CB950 -:101EB00005F1080308222821304601F063FE302492 -:101EC0002F462A7A7B1B934204D3E01DC008F8BD3D -:101ED0002824F5E707F1090321460822304601F0DE -:101EE00051FE08340137ECE7F7B5047F00910E4648 -:101EF000012310220021054601F008FDC4B9B31CDE -:101F00000093092223461021284601F0FFFC1924E2 -:101F100037467288BB1B9A4211D82B7FA88A073498 -:101F2000E408BBB9844294BF0020012003B0F0BD97 -:101F3000AB8ADB00103BDB0873801024E8E73B1D15 -:101F40000093214600230822284601F0DFFC0834D4 -:101F50000137DEE7201A18BF0120E7E730B5094D49 -:101F60000A4491420DD011F8013B5840082340F338 -:101F70000004013B2C4013F0FF0384EA5000F6D12B -:101F8000EFE730BD2083B8EDF7B5384A10685168E7 -:101F90006B4603C36A4636493648082303F066FB9E -:101FA0000446002833D10A25334A106851686B462D -:101FB00003C36A4631492F48082303F057FB044600 -:101FC000002849D00369B3F5EE2F45D8B0F8661064 -:101FD00040F21D4291423FD1294A024402F15C0184 -:101FE0008B4239D35C3B234900209E1AFFF7B6FF92 -:101FF0003246074604F164010020FFF7AFFFA368F3 -:102000009F4229D1E368984208BF002524E0036974 -:10201000B3F5EE2F27D8418B40F21D42914220D1DB -:10202000174A024402F110018B4218D3103B1149A8 -:1020300000209D1AFFF792FF2A46064604F1180178 -:102040000020FFF78BFFA3689E4202D1E36898420D -:1020500001D00D25A8E70025284603B0F0BD1025C6 -:10206000A2E70C25A0E70B259EE700BFE856000875 -:10207000DC6F070000900008F1560008906F070021 -:102080000870FFF710B5037C044613B9006803F02D -:10209000D5FA204610BD00000023BFF35B8FC3605C -:1020A000BFF35B8FBFF35B8F8360BFF35B8F7047C2 -:1020B000BFF35B8F0068BFF35B8F704770B5054659 -:1020C0000C30FFF7F5FF05F1080604463046FFF730 -:1020D000EFFFA04206D930466D68FFF7E9FF2544BF -:1020E000281A70BD3046FFF7E3FF201AF9E7000019 -:1020F00070B50546406898B105F10800FFF7D8FFB4 -:1021000005F10C0604463046FFF7D2FF8442304604 -:1021100094BF6D680025FFF7CBFF013C2C44201ACB -:1021200070BD000038B50C460546FFF7C7FFA0425A -:1021300010D305F10800FFF7BBFF04446868B4FB47 -:10214000F0F100FB1144BFF35B8F0120AC60BFF3E3 -:102150005B8F38BD0020FCE72DE9F04114460746AF -:102160000D46FFF7C5FF844228BF0446D4B1B846E8 -:1021700058F80C6B4046FFF79BFF30442860404600 -:102180007E68FFF795FF331A9C4203D86C600120EC -:10219000BDE8F0816B60A41B3B68AB602044E86045 -:1021A0000220F5E72046F3E738B50C460546FFF771 -:1021B0009FFFA04210D305F10C00FFF779FF044404 -:1021C0006868B4FBF0F100FB1144BFF35B8F0120A2 -:1021D000EC60BFF35B8F38BD0020FCE72DE9FF41C9 -:1021E000884669460746FFF7B7FF6C4606B204EB20 -:1021F000C6060025B44209D06268206808EB0501D4 -:10220000FFF740FC636808341D44F3E7294638466D -:10221000FFF7CAFF284604B0BDE8F081F8B50546CF -:102220000C300F46FFF744FF05F108060446304620 -:10223000FFF73EFFA042304688BF6C68FFF738FFCB -:10224000201A386020B130462C68FFF731FF204457 -:10225000F8BD000073B5144606460D46FFF72EFF85 -:10226000844228BF04460190DCB101A93046FFF743 -:10227000D5FF019B33B93268C5E90233C5E90024B3 -:1022800001200CE09C4238BF0194286001986860EE -:102290008442F5D93368AB60241AEC60022002B0A6 -:1022A00070BD2046FBE700002DE9FF410F4669465F -:1022B000FFF7D0FF6C4600B204EBC0050026AC422D -:1022C00009D0D4F8048054F8081BB8194246FFF727 -:1022D000D9FB4644F3E7304604B0BDE8F081000086 -:1022E00038B50546FFF7E0FF044601462846FFF7EC -:1022F00019FF204638BD0000302383F3118862B6F1 -:1023000070470000002383F3118862B67047000015 -:10231000012070477047000010B41346026814682B -:102320000022A4465DF8044B6047000000F5805091 -:1023300090F859047047000000F5805090F852045E -:102340007047000000F5805090F958047047000075 -:102350005020704700F5805208B5FFF7CDFFD2F846 -:102360009834D2F894041844D2F890341844D2F82F -:1023700078341844D2F888341844D2F88434184495 -:10238000FFF7C0FF08BD000038B5C26A936923F0AB -:1023900001039361044600F087FE0546E36A9B69EA -:1023A000DB0706D500F080FE431BFA2BF6D9002090 -:1023B00004E004F58054012084F8520438BD000084 -:1023C0002DE9F04F0C4600F5805185B01F4691F87D -:1023D0005234BDF83890054690469BB1D1F874341C -:1023E0000133C1F8743423689A0006D4237B082B88 -:1023F0000BD9627B0AB10F2B07D9D1F8783401339E -:10240000C1F878344FF0FF300FE0FFF775FFEB6A4B -:10241000D3F8C42012F4001A0AD0D1F87C34013366 -:10242000C1F87C34FFF76EFF002005B0BDE8F08FE7 -:10243000D3F8C46022686B6AC6F301464FF0480BBC -:10244000002A1BFB063BB4BF42F080429204CBF84B -:10245000002023685B0044BF42F00052CBF800200C -:10246000227B330643EA0243CBF80430607B7201DF -:1024700018B343F44013CBF80430D1F8A43401333B -:10248000C1F8A434AB1803F58353197B41F0200144 -:102490001973207B039200F063FE039A03308010CF -:1024A0005FFA8AF383420AF1010A0DDA04EB830131 -:1024B0000BEB830349689960F2E7AB1803F583538C -:1024C000197B60F34511E3E7EB6A0121B140C3F8E2 -:1024D000CC10AB1803F58253C3E9048705EB461310 -:1024E00003F582532146183304F10C0051F804CB54 -:1024F00043F804CB8142F9D1098819802A4441F27A -:1025000068032846D65002F5805209F0030392F87A -:102510006C1043F0100321F01F010B4382F86C3064 -:10252000FFF7F0FE4246CDF800903B46214600F012 -:10253000DDFD012079E7000013B500F5805401911D -:10254000606CFFF7D5FD1F280AD90199606C202225 -:10255000FFF744FEA0F120035842584102B010BDDD -:102560000020FBE708B500F58050FFF7C5FE406C82 -:10257000FFF792FDBDE80840FFF7C4BE00220260ED -:10258000828142608260704710B500220023C0E95A -:1025900000230023044603810C30FFF7EFFF2046A1 -:1025A00010BD00002DE9F047074688B007F58054BC -:1025B00068469A468846FFF79FFE9146FFF7E4FF7C -:1025C000606CFFF77BFD1F282CD9606C20226946C8 -:1025D000FFF786FE202825D194F8523413B303ADBB -:1025E000444605AB2E4603CE9E42206061603546D0 -:1025F00004F10804F6D130682060B388A380DDE9D7 -:102600000023C9E90023BDF80830AAF80030FFF71D -:1026100079FE4A4653464146384608B0BDE8F04781 -:1026200000F052BDFFF76EFE002008B0BDE8F08755 -:102630002DE9F84F00230646C0E90133294B46F83F -:10264000303B00F5815405468846374610343846FD -:102650002037FFF799FFA742F9D105F580544FF4D1 -:10266000805326630026C4E90D366764012305F50F -:10267000835705F5A359E66384F8403084F8483061 -:10268000103709F110094FF0000A4FF0000B47E92D -:1026900008ABA7F11800FFF771FF203747F8286C47 -:1026A0004F45F4D1B8F1010F84F85884A4F85A6466 -:1026B000A4F85C64A4F85E6484F86064A4F86264BE -:1026C000A4F86464A4F8666484F8686402D90648CF -:1026D00000F0E4FC054B53F82830EB622846BDE8D7 -:1026E000F88F00BF28570008FC560008185700084C -:1026F00010B5044B197804464A1C1A70FFF798FF6E -:10270000204610BDE96300202DE9F04300295FD089 -:102710003048314BB3FBF1F381428CBF0A201120CA -:10272000451EB3FBF0F700FB1730ECB220B1022DD1 -:102730002846F5D8002037E07D1EB5F5806F33D2EE -:10274000C4EBC40808F103034FEAE30EC3F3C70365 -:10275000A4EB030C0EF101094FF47A705FFA8CF6CA -:102760000EFB000E59FA8CFCBEFBFCFCBCF5617F35 -:102770001CDC1FFA8CF4581C56FA80F047431648AC -:10278000B0FBF7F7B942D5D1013BDBB20F2BD1D863 -:10279000711EC9B207294FF0000005D810711480CE -:1027A0005580537191710120BDE8F08308F1FF332A -:1027B0004FEAE30CC3F3C703E41A0CF1010EE6B2CF -:1027C0000CFB00005EFA84F4B0FBF4F4A4B2D2E790 -:1027D0000846E9E73F420F000024F40038B500F551 -:1027E0008053114A93F85834D55C4FF454725543D2 -:1027F00005F1804303F52443044600211846FFF702 -:1028000053F90A4B60612B44A361094B2B44E361EC -:10281000084B2B442362084B2B446362E36A00227B -:10282000C3F8C02038BD00BF1057000870A4004096 -:10283000B0A4004088A5004078A600402DE9F04FE4 -:1028400000F58055994695F85834022B89B0044616 -:102850008A46904604D90027384609B0BDE8F08F73 -:10286000994A52F8231009B942F823009749C4F84D -:102870000CA00B7884F8109093B9FFF73DFD944BB2 -:102880009A6D42F000729A659A6B42F000729A63F8 -:102890009A6B22F000729A6301230B70FFF732FDEE -:1028A00095F85134BBB9FFF727FD8A4A95F858349B -:1028B000D35C012B26D0022B2BD03BB90321152052 -:1028C00001F056FD0321162001F052FD012385F889 -:1028D0005134FFF717FDFFF70FFDE26A936923F00C -:1028E0001003936100F0E0FB0746E36A9E6916F06F -:1028F000080615D000F0D8FBC31BFA2BF5D9FFF75B -:1029000001FDA8E70321562001F032FD03215720E5 -:10291000DAE70321582001F02BFD03215920D3E7EA -:102920009A6942F001029A6100F0BEFB0746E36A31 -:102930009A69D00705D400F0B7FBC31BFA2BF6D970 -:10294000DDE79A6942F002029A61E36A00275F6557 -:10295000FFF7D8FC686CFFF79FFB04F5825B0BF177 -:10296000100B202200216846FFF79EF802A8FFF70F -:1029700005FE06976A460BEB06030DF1180E94460A -:10298000BCE80300F44518605960624603F108038F -:10299000F5D1DCF80000186020369CF804201A718C -:1029A000B6F5806FDDD1002304F5A25285F85034CE -:1029B00085F853341A3251462046FFF7A5FE0746E4 -:1029C00090B9E26A936923F00103936100F06CFB14 -:1029D0000546E36A9B69D9077FF53DAF00F064FBCC -:1029E000431BFA2BF5D936E795F85F6495F85E241A -:1029F000C5F86CA4360246EA426695F86024E36A9C -:102A00001643B5F85C2446EA0246DE61B8F1000FD1 -:102A100029D004F5A352023241462046FFF774FE46 -:102A200090B9E26A936923F00103936100F03CFBE3 -:102A30000546E36A9B69DA077FF50DAF00F034FBCA -:102A4000431BFA2BF5D906E795F8683495F8671417 -:102A5000C5F870841B0143EA0123B5F86414E26AE7 -:102A600043EA0143D3602046FFF7B8FE002385F810 -:102A70005934E36A6FF040421A65E36A164A5A65B0 -:102A8000E36A44229A65E36A0722C3F8DC20E36A1A -:102A900003229145DA653FF4DFAEE26A936923F0E1 -:102AA0000103936100F000FB0646E36A9B69DB07C4 -:102AB00005D500F0F9FA831BFA2BF6D9CBE60123F2 -:102AC00085F85234C8E600BFE0630020E8630020C8 -:102AD00000100240105700089B0008002DE9F04F3D -:102AE000054689B090469946002741F2680A00F5EC -:102AF0008056EB6AD3F8D430FB40D8074AD505EBB3 -:102B0000471252444FEA471B1379190742D4D6F8AB -:102B100080340133C6F8803413799A0648BFD6F85A -:102B2000A83405EB0B0248BF0133524448BFC6F836 -:102B3000A834137943F008031371DB0722D596F804 -:102B40005334FBB105F58254183468465C44FFF7F2 -:102B50001BFD03AB04F1080C206861681A4603C230 -:102B6000083464451346F7D120681060A2889A8023 -:102B70000123ADF808302B68CDE90089DB6B69468D -:102B800028469847D6F8543423B1D6F89C340133FC -:102B9000C6F89C340137202FABD109B0BDE8F08FC7 -:102BA0002DE9F04F8DB004460F4600F07FFA8246C3 -:102BB0008946002F56D1E36AD3F89020920141BF95 -:102BC00004F58051D1F894240132C1F89424D3F84B -:102BD0009020160703D100200DB0BDE8F08FD3F888 -:102BE0009050E669C5F30125482303FB0566E846D6 -:102BF0004046FFF7C3FC326851004ABF22F06043F1 -:102C0000C2F38A4343F00043920048BF43F080433D -:102C10000093736813F400131FBF04F5805201235F -:102C20008DF80D30D2F8AC340EBF8DF80D30013375 -:102C3000C2F8AC34F38803F00F038DF80C304FF07A -:102C4000000B9DF80C0000F08BFA5FFA8BF39842B2 -:102C500020D9F2180CA90B44127A03F82C2C0BF192 -:102C6000010BEEE7012FB6D1E36AD3F89820950166 -:102C700041BF04F58051D1F894240132C1F8942465 -:102C8000D3F898201007A6D0D3F89850266AC5F339 -:102C90000125A9E7EFB9E36AC3F8945004A8FFF748 -:102CA00073FC98E80F0007AD07C52B800023ADF833 -:102CB000183023682046CDE904A9DB6B04A99847A6 -:102CC00004F5805458B1D4F88C340133C4F88C34F2 -:102CD00082E7012F04BFE36AC3F89C50DEE7D4F813 -:102CE00090340133C4F89034012075E7F8B50546F7 -:102CF0000F4600F58054012639462846FFF750FF5D -:102D000010B184F85364F7E7D4F8543423B1D4F8FD -:102D10009C340133C4F89C34F8BD0000F0B5C36A9C -:102D20001A6C12F47F0F2BD000F580541B6CC4F882 -:102D3000A03441F26805002347194FF0010C00EB65 -:102D400043122A445E01117911F0020F15D0490790 -:102D500013D4B959C66AD6F8C8E00CFA01F111EAE1 -:102D60000E0F0AD0C6F8D010117941F0040111718C -:102D7000D4F888240132C4F888240133202BDED112 -:102D8000F0BD00002B4B70B51E561B5C012B2FD8DD -:102D9000294D2A4A55F8233052F826400BB341B347 -:102DA000236D1A060FD58023236500F07FF950EAC2 -:102DB00001020B4602D0013861F10003024655F8CA -:102DC0002600FFF78BFE236D1B032CD555F826300C -:102DD0004FF4002203F580532265012283F8592421 -:102DE00021E001232365082323654FF480632365D5 -:102DF00070BD236DDA0702D4236D9B0706D503232C -:102E000055F8260023650021FFF770FF236D180792 -:102E100002D4236DD90606D5182355F8260023655C -:102E20000121FFF763FF55F82600BDE87040FFF76A -:102E300075BF00BF14570008E06300201857000852 -:102E400008B5FFF759FAFFF769FFBDE80840FFF73B -:102E500059BA0000C36AD3F8C40080F40010C0F36C -:102E60004050704700F5805008B5FFF745FA406CB8 -:102E7000FFF724F9FFF746FA43090CBF01200020B1 -:102E800008BD000000F5805393F8592462B1C16A6F -:102E90008A6922F001028A61D3F898240132C3F8CA -:102EA0009824002283F85924704700002DE9F74345 -:102EB00000F5825198461031FFF71EFA002541F2C5 -:102EC000680E4FF0010900F5805C00EB4514744476 -:102ED00023795E071CD4DB061AD5C36A8E69D3F842 -:102EE000C87009FA06F63E4212D04F6801970F6883 -:102EF0009742019F77EB08070AD2C3F8D060237985 -:102F000043F004032371DCF884340133CCF88434B7 -:102F10000135202D01F12001D7D103B0BDE8F043E8 -:102F2000FFF7F0B9F8B51E46002313700F460546AB -:102F30001446FFF797FF80F0010038701EB1284655 -:102F4000FFF788FF2070F8BD2DE9F04F85B0994656 -:102F5000DDE90EA30D4602931378019391F800B0BA -:102F60008046164600F0A2F82B7804460F4613B9A7 -:102F70003378002B42D022463B464046FFF796FF6F -:102F8000FFF75EFFFFF77EFF4B4632462946FFF70D -:102F9000C9FF2B7833B1BBF1000F03D0012005B07E -:102FA000BDE8F08F337813B1019B002BF6D108F503 -:102FB00080530393029B544577EB03031ED2039B7C -:102FC000D3F85404D0B10368AAEB0401DB6889B2DA -:102FD00098474B46324629464046FFF7A3FF2B78D9 -:102FE00013B1BBF1000FD9D1337813B1019B002B82 -:102FF000D4D100F05BF804460F46DBE70020CEE7B3 -:1030000008B500210846FFF7BDFEBDE8084001F005 -:1030100067B8000008B501210020FFF7B3FEBDE846 -:10302000084001F05DB8000008B500210120FFF75D -:10303000A9FEBDE8084001F053B8000008B5012121 -:103040000846FFF79FFEBDE8084001F049B80000C0 -:1030500000B59BB0EFF3098168226846FEF712FDC8 -:10306000EFF30583014B9B6BFEE700BF00ED00E033 -:1030700008B5FFF7EDFF000000B59BB0EFF3098145 -:1030800068226846FEF7FEFCEFF30583014B5B6B9D -:10309000FEE700BF00ED00E0FEE700000FB408B55A -:1030A000029801F0EBFBFEE701F0FCBE01F0D4BE9C -:1030B00013B56C4684E80600031D94E8030083E81A -:1030C0000500012002B010BD73B58568019155B1AE -:1030D0001B885B0707D4D0E900369B6B9847019AA1 -:1030E000C1B23046A847012002B070BDF0B5866875 -:1030F00089B005460C465EB1BDF838305B070AD48E -:10310000D0E900379B6B98472246C1B23846B0479A -:10311000012009B0F0BD00220023CDE900230023E7 -:10312000ADF808300A4603AB01F108061068516893 -:103130001C4603C40832B2422346F7D1106820600F -:103140009288A280FFF7B2FF0423ADF808302B6805 -:10315000CDE90001DB6B694628469847D8E70000B7 -:10316000082817D909280CD00A280CD00B280CD015 -:103170000C280CD00D280CD00E2814BF4020302075 -:1031800070470C207047102070471420704718209B -:1031900070472020704700002DE9F041456A15B9BD -:1031A0004162BDE8F0814B6823F06047C3F38A4673 -:1031B0004FEAD37EC3F3807816EA230638BF3E4633 -:1031C000AC462B465A68BEEBD27F22F060440AD050 -:1031D000002A18DAA40CB44217D19D420FD10D6019 -:1031E000DEE71346EEE7A74207D102F08044C2F3C0 -:1031F000807242450BD054B1EFE708D2EDE7CCF82E -:1032000000100B60CDE7B44201D0B442E5D81A6893 -:103210009C46002AE5D11960C3E700002DE9F0477C -:10322000089D01F007044FEAD508224405F0070580 -:1032300000EBD1004FF47F49944201D1BDE8F08703 -:1032400004F0070705F0070A57453E4638BF5646C3 -:10325000C6F10806111B8E4228BF0E46E10808EB96 -:10326000D50E415C13F80EC0B94029FA06F721FAD1 -:103270000AF1FFB28CEA010147FA0AF739408CEAF9 -:10328000010C03F80EC034443544D5E780EA012030 -:10329000082341F2210201B24000002980B203F16B -:1032A000FF33B8BF504013F0FF03F4D17047000064 -:1032B00038B50C468D18A54200D138BD14F8011B55 -:1032C000FFF7E4FFF7E7000042684AB11368436084 -:1032D0004389818901339BB29942438138BF8381FD -:1032E0001046704770B588B0202204460D466846E7 -:1032F0000021FEF7D9FB20460495FFF7E5FF0246C3 -:1033000058B16B46054608AE1C4603CCB442286053 -:103310006960234605F10805F6D1104608B070BD76 -:10332000082817D909280CD00A280CD00B280CD053 -:103330000C280CD00D280CD00E2814BF40203020B3 -:1033400070470C20704710207047142070471820D9 -:103350007047202070470000082817D90C280CD986 -:1033600010280CD914280CD918280CD920280CD9CD -:1033700030288CBF0F200E207047092070470A208C -:1033800070470B2070470C2070470D2070470000DD -:103390002DE9F843078C072F04461ED9D0E902987F -:1033A00000254FF6FF73C5F12006A5F1200029FA8C -:1033B00005F108FA06F628FA00F031430143C9B2D4 -:1033C0001846FFF763FF0835402D0346EBD1E1694E -:1033D0003A46BDE8F843FFF76BBF4FF6FF70BDE814 -:1033E000F883000010B54B6823B9CA8A63F3090259 -:1033F000CA8210BD04691A681C600361C38A013B5C -:10340000C3824A60EFE700002DE9F84F1D46CB8AE2 -:103410000F46C3F309010529814692460B4630D079 -:103420000020AAB207F11A049EB2042E1FFA80F8F7 -:103430000FD8904503F1010306D3FB8A0A4462F3D7 -:103440000903FB8201201AE01AF80060E6540130FB -:10345000EAE79045F1D2A1F1050B1C237C68BBFB88 -:10346000F3F203FB12BB1FFA8BF6002C45D1484642 -:10347000FFF72AFF044638B978606FF00200BDE814 -:10348000F88F4FF00008E6E7002606607860ADB2DE -:103490004FF0000B454510D90AEB0803221D13F825 -:1034A000011B9155B1B208F101081B291FFA88F8D8 -:1034B0002BD0454506F10106F1D8FB8AC3F309027A -:1034C000154465F30903BCE7013292B21C46236838 -:1034D000002BF9D16B1F0B441C21B3FBF1F301331B -:1034E0009BB29A42D3D2BBF1000FD0D14846FFF72E -:1034F000EBFE20B9C4F800B0BFE70122E7E7C0F84F -:1035000000B05E4620600446C1E74545D5D948462F -:10351000FFF7DAFE08B92060AFE7C0F800B0002678 -:1035200020600446B6E700002DE9F04F2DED028B38 -:103530001C4683B05B69019207468846002B00F069 -:103540009A80238C2BB1E269002A00F09480072B2B -:1035500035D807F10C00FFF7B7FE054638B96FF014 -:103560000205284603B0BDEC028BBDE8F08F1422A3 -:103570000021FEF799FA228CE16905F10800FEF7B7 -:1035800081FA208C013080B2FFF7E6FEFFF7C8FE1B -:10359000013880B22084013028746369228C1B7842 -:1035A0002A4403F01F0363F03F0348F00041137205 -:1035B000384669602946FFF7EFFD0125D1E700F1A4 -:1035C0000C034FF0000908EE103A4FF0800A4E4607 -:1035D0004D4618EE100AFFF777FE83460028BED04E -:1035E00014220021FEF760FA002E3AD1019BABF8BD -:1035F000083002220BF1080E1FFA82FC0CF10100C8 -:10360000BCF1060F218C80B201D88E422BD3FFF77C -:10361000A3FEFFF785FE62691278013802F01F02EF -:103620008E4208BF4FF0400A42EA49121BFA80F16D -:103630004AEA020A013048F0004281F808A08BF8FB -:103640001000CBF8042059463846FFF7A5FD238C1F -:103650000135B3422DB289F001094FF0000AB8D10B -:103660007FE70022C6E7E169895D0EF802100136A6 -:10367000B6B20132C0E76FF0010572E7F8B5154642 -:103680000E463022002104461F46FEF70DFA069B27 -:103690006360B5F5001F079BA76034BF6A094FF64A -:1036A000FF72A36297B2E66104F1100000239A4210 -:1036B00006D800230360A782E3822383E360F8BD7A -:1036C0000660013330462036F1E7000003781BB96D -:1036D0004BB2002BC8BF01707047000000787047E4 -:1036E000F8B50C46C969074611B9238C002B37D1B0 -:1036F000257E1F2D34D8387828BB228C072A2CD859 -:10370000268A36F003032BD14FF6FF70FFF7D0FD6A -:1037100020F001003102400441EA0561400C41EA19 -:1037200040254FF6FF72234629463846FFF7FCFE38 -:10373000002807DD626913780133DBB21F2B88BFD5 -:1037400000231370F8BD218A2D0645EA01250543A3 -:103750002046FFF71DFE0246E5E76FF00300F1E7A4 -:103760006FF00100EEE7000070B58AB0044616461F -:103770000021282268461D46FEF796F9BDF838302C -:10378000ADF810300F9B05939DF840308DF8183040 -:10379000119B07936946BDF84830ADF820302046AC -:1037A000CDE90265FFF79CFF0AB070BD2DE9F0413D -:1037B000D36905460C4616460BB9138C5BBB377EA6 -:1037C0001F2F28D895F80080B8F1000F26D030467A -:1037D000FFF7DEFD3378210241EAC33141EA0801F7 -:1037E000338A41EA076141EA03410246334641F028 -:1037F00080012846FFF798FE00280ADD3378012B68 -:1038000007D1726913780133DBB21F2B88BF002305 -:103810001370BDE8F0816FF00100FAE76FF003006C -:10382000F7E70000F0B58BB004460D4617460021BF -:10383000282268461E46FEF737F99DF84C305A1E7E -:10384000534253418DF800309DF84030ADF81030B0 -:10385000119B05939DF848308DF81830149B079301 -:103860006A46BDF85430ADF8203029462046CDE9EF -:103870000276FFF79BFF0BB0F0BD0000406A00B17D -:1038800004307047436A1A68426202691A60036131 -:10389000C38A013BC38270472DE9F041D0F82080F4 -:1038A000194E14461D464146002709B9BDE8F0816E -:1038B000D1E90223A21A65EB0303964277EB0303D7 -:1038C0001ED2036A8B420DD1FFF78CFD036A1B6881 -:1038D000036203690B60C38A0161016A013BC38211 -:1038E0008846E2E7FFF77EFD0B68C8F80030036901 -:1038F0000B60C38A0161013BC382D8F80010D4E792 -:1039000088460968D1E700BF80841E002DE9F04F8A -:103910008BB00D46DDF8509014469B46804600283B -:1039200000F01981B9F1000F00F01581531E3F2BF3 -:1039300000F21181012A03D1BBF1000F40F00B818D -:103940000023CDE90833B8F81430B5EBC30F4FEAC4 -:10395000C30703D300200BB0BDE8F08F2B199F42A3 -:10396000D8F80C303ABF7F1BFFB227461BB9D8F8F6 -:103970001030002B7AD0272D4ED8C5F12806B7423B -:103980004FF000032CBFF6B23E4600932946D8F80C -:10399000080008AB3246FFF741FCA7EB060A3544A6 -:1039A0005FFA8AFAB8F8143003F10053053BDB00E4 -:1039B0000493D8F80C3003932821039B13B1BAF178 -:1039C000000F2CD1D8F8100040B1BAF1000F05D08B -:1039D000009608AB5246691AFFF720FC38B2002F58 -:1039E000B8D066070AD00AAB03EBD401624211F8E3 -:1039F000083C02F00702134101F8083C082C3CD9AE -:103A0000102C40F2B580202C40F2B780BBF1000FA3 -:103A100000F09C80082334E0BA460026C2E7049BED -:103A2000E02B28BFE02306930B44AB42059314D947 -:103A30005A1B03980096924534BF5246D2B2691A77 -:103A400008AB04300792FFF7E9FB079A1644AAEB8C -:103A5000020A1544F6B25FFA8AFA049B069A05999F -:103A60009B1A0493039B1B680393A6E70093D8F863 -:103A7000080008AB3A462946AEE7BBF1000F13D069 -:103A80000123B4EBC30F6CD0082C12D89DF8203062 -:103A9000621E23FA02F2D50706D54FF0FF3202FA72 -:103AA00004F423438DF820309DF8203089F800304D -:103AB00051E7102C12D8BDF82030621E23FA02F212 -:103AC000D10706D54FF0FF3202FA04F42343ADF8D4 -:103AD0002030BDF82030A9F800303CE7202C0FD86A -:103AE0000899631E21FA03F3DA0705D54FF0FF3278 -:103AF00002FA04F40C430894089BC9F800302AE742 -:103B0000402C2BD0DDE90865611EC4F12102A4F12F -:103B1000210326FA01F105FA02F225FA03F3114313 -:103B20001943CB0712D50122A4F12003C4F12001CF -:103B300002FA03F322FA01F1A240524243EA0103DE -:103B400063EB430332432B43CDE90823DDE908232C -:103B5000C9E90023FFE66FF00100FCE66FF0080002 -:103B6000F9E6082CA0D9102CB3D9202CEED8C3E745 -:103B7000BBF1000FADD0022383E7BBF1000FBBD038 -:103B800004237EE730B5012A144638BF0124402CB7 -:103B900085B028BF40240025012ACDE9025518D858 -:103BA0001B788DF8083063070AD004AB03EBD4050B -:103BB000624215F8083C02F00702934005F8083C01 -:103BC000009103462246002102A8FFF727FB05B01B -:103BD00030BD082AE4D9102A03D81B88ADF8083074 -:103BE000E1E7202A8DBFD3E900231B680293CDE9CA -:103BF0000223D8E710B5CB681BB98B600B618B82B1 -:103C000010BD04691A681C600361C38A013BC3824A -:103C1000CA60F0E703064CBFC0F3C0300220704713 -:103C200008B50246FFF7F6FF022806D15306C2F395 -:103C30000F2001D100F0030008BDC2F30740FBE7ED -:103C40002DE9F04F93B0CDE903230A6804461046EE -:103C5000FFF7E0FF022814BFC2F306260026002A61 -:103C60000D46824680F2F28112F0C04940F0EE81AA -:103C7000097B002900F0EA81022803D02378B342AF -:103C800040F0E781C2F304630693104602F07F031D -:103C90000593FFF7C5FF059B29444FEA834848EA8F -:103CA0000A4848EA4668CE7800230022CDE9082376 -:103CB000F309834648EA0008029367D0059B009306 -:103CC00002466768534608A92046B847002800F016 -:103CD000C381276A4FB9414604F10C00FFF702FB8C -:103CE000074690B96FF0020054E03B6998450DD04B -:103CF0003F68002FF9D1414604F10C00FFF7F2FABA -:103D000007460028EED0236A3B60276297F817C069 -:103D100006F01F08CCF3840CACEB08001FFA80FE01 -:103D20000028B8BF0EF12000A8EB0C031FFA83FE99 -:103D3000D7E90221B8BF00B2002B0793BEBF0EF136 -:103D400020031BB2079352EA010338D0039BDFF82C -:103D500024E39A1A049B4FF0000C63EB0101964593 -:103D60007CEB01032BD36B7B97F81AE0734519D1D9 -:103D7000029B002B78D0012821DC7868F8B9DFF8A5 -:103D8000F0C2944570EB010316D337E0276A27B9D8 -:103D90006FF00C0013B0BDE8F08F3B699845B5D0CB -:103DA0003F68F4E7B24890427CEB010301D3002066 -:103DB000F0E7029B002BFAD0079B0F2B17DCFA7D54 -:103DC000B30002F0030203F07C031343FB75394692 -:103DD0002046FFF707FB6B7BBB76029B3BB9FB7D65 -:103DE000C3F38402013262F38603FB75D0E76A7B7A -:103DF000BB7E9A42DBD1029B002B35D0B309022B4C -:103E000032D0039BBB60049BFB60142200210DA8F1 -:103E1000FDF74AFE039B0A93049B0B932B1D0C9307 -:103E20002B7BADF83EB0013BDBB2ADF83C30069BDE -:103E30008DF84230059B8DF8433094F82C308DF886 -:103E400040A083F001038DF844308DF84180A368D1 -:103E50000AA920469847FB7DC3F38403013303F08E -:103E60001F039B02FB82A2E7FB7DC6F34012B2EB6D -:103E7000D31F40F0F480C3F38403434540F0F28045 -:103E8000029A2B7BB609002A4DD0F2075DD4032B92 -:103E900040F2EB80039BBB60049BFB602B7BAE1D61 -:103EA000033BDBB23246394604F10C00FFF7ACFAB3 -:103EB00000280CDA39462046FFF794FAFB7DC3F35D -:103EC0008403013303F01F039B02FB820AE7DDE951 -:103ED0000884AB883B834FF6FF73C9F12000A9F13A -:103EE000200228FA09F104FA00F0014324FA02F250 -:103EF00011431846C9B2FFF7C9F909F10809B9F128 -:103F0000400F0346E9D1B8822A7B033AD2B2314648 -:103F1000FFF7CEF9FB7DB882DA43C2F3C01262F339 -:103F2000C713FB7543E786B92E1D013BDBB2324652 -:103F3000394604F10C00FFF767FA0028BADB2A7B48 -:103F4000B88A013AD2B23146E2E7F98AC1F30901EF -:103F5000013B0429DAB25BD8281D002307F11B06B8 -:103F60009A4208D910F801CB06F801C0013101339B -:103F70000529DBB2F4D103990A9104990B9193427C -:103F800007F11B010C9138BF043379680D9134BFE0 -:103F900055FA83F300230E93FB8AADF83EB0C3F3CA -:103FA00009031A44069B8DF84230059B8DF8433077 -:103FB00094F82C30ADF83C2083F001038DF84430A8 -:103FC00000238DF840A08DF841807B602A7BB88A61 -:103FD000013A291DFFF76CF93B8BB882834203D16C -:103FE000A3680AA92046984720460AA9FFF702FEBF -:103FF000FB7DBA8AC3F38403013303F01F039B02E2 -:10400000FB823B8B9A420CBF00206FF01000C1E690 -:104010007B68002BAFD0052001E01C3033461E68C2 -:10402000002EFAD1091A081D2E1D184401EB090CA7 -:10403000BCF11B0F5FFA89F39DD89A429BD916F801 -:10404000013B00F8013B09F10109EFE76FF00900BE -:10405000A0E66FF00A009DE66FF00B009AE66FF0A5 -:104060000D0097E66FF00E0094E66FF00F0091E6FA -:1040700040420F0080841E00EFF3098305494A6B1C -:1040800022F001024A63683383F30988002383F333 -:104090001188704700EF00E0302080F3118862B68D -:1040A0000C4B0D4AD96821F4E0610904090C0A435C -:1040B000DA60D3F8FC20094942F08072C3F8FC2092 -:1040C0000A6842F001020A602022DA7783F82200AF -:1040D000704700BF00ED00E00003FA05001000E0AB -:1040E00010B5302383F311880E4B5B6813F4006323 -:1040F00014D0F1EE103AEFF30984683C4FF080736E -:10410000E361094BDB6B236684F3098800F074FBE1 -:1041100010B1064BA36110BD054BFBE783F311887B -:10412000F9E700BF00ED00E000EF00E04306000803 -:1041300046060008026843681143016003B118474E -:1041400070470000024A136843F0C00313607047D1 -:104150000044004013B50E4C204600F0B3FA04F1C1 -:1041600014000C49009400234FF4807200F070F9A1 -:10417000094B0A4900944FF4807204F1380000F0B2 -:10418000E9F9074A074BC4E9172302B010BD00BF85 -:10419000F06300205C640020454100085C6500205D -:1041A00000440040007A030A30B5037C214C00290A -:1041B00018BF0C46012B0CD11F4B984209D11F4B45 -:1041C0009A6D42F400329A659A6F42F400329A670F -:1041D0009B6F2268036EC16D846603EB5203B3FBD1 -:1041E000F2F36268150442BF23F0070503F00703EA -:1041F00043EA4503CB60A36843F040034B60E368A8 -:1042000043F001038B6042F4967343F001030B60AB -:104210004FF0FF330B62510505D512F0102205D087 -:10422000B2F1805F04D080F8643030BD7F23FAE7BC -:104230003F23F8E768570008F063002000100240B1 -:104240002DE9F047C66D3768F469346221070546E9 -:1042500019D014F0080118BF4FF48071E20748BF6D -:1042600041F02001A30748BF41F04001600748BF6B -:1042700041F08001302383F31188281DFFF75AFF96 -:10428000002383F31188E2050AD5302383F31188D4 -:104290004FF48061281DFFF74DFF002383F3118841 -:1042A0004FF030094FF0000A14F0200838D13B06D7 -:1042B00016D54FF0300905F1380A200610D589F3DC -:1042C0001188504600F07AF9002836DA0821281DB6 -:1042D000FFF730FF27F080033360002383F311885A -:1042E000790614D5620612D5302383F31188D5E9F7 -:1042F00013239A4208D12B6C33B11021281D27F0CB -:104300004007FFF717FF3760002383F31188E306A8 -:1043100018D5AA6E1369ABB1BDE8F04750691847CC -:1043200089F31188736A95F864102846194000F0E3 -:10433000E3F98AF31188F469B6E7B06288F311886B -:10434000F469BAE7BDE8F0874FF0E023002258682F -:104350004FF0FF31930003F1604303F561430132F5 -:104360009042C3F88010C3F88011F3D27047000068 -:1043700000F1604303F561430901C9B283F80013FA -:10438000012200F01F039A4043099B0003F16043A0 -:1043900003F56143C3F880211A607047F8B51546EC -:1043A00082680669AA420B46816938BF8568761A19 -:1043B000B54204460BD218462A46FDF763FBA369B3 -:1043C0002B44A361A3685B1BA3602846F8BD0CD9EE -:1043D00018463246FDF756FBAF1BE1683A463044BB -:1043E000FDF750FBE3683B44EBE718462A46FDF730 -:1043F00049FBE368E5E7000083689342F7B515469B -:10440000044638BF8568D0E90460361AB5420BD23D -:104410002A46FDF737FB63692B446361A36828468E -:104420005B1BA36003B0F0BD0DD932460191FDF7CF -:1044300029FB0199E068AF1B3A463144FDF722FBA6 -:10444000E3683B44E9E72A46FDF71CFBE368E4E741 -:1044500010B50A440024C361029B8460C0E90000D7 -:10446000C0E90511C1600261036210BD08B5D0E961 -:104470000532934201D1826882B98268013282603A -:104480005A1C42611970D0E904329A4224BFC368B1 -:104490004361002100F078FA002008BD4FF0FF30A2 -:1044A000FBE7000070B5302304460E4683F3118805 -:1044B000A568A5B1A368A269013BA360531CA361D1 -:1044C00015782269934224BFE368A361E3690BB1C5 -:1044D00020469847002383F31188284607E0314699 -:1044E000204600F041FA0028E2DA85F3118870BD19 -:1044F0002DE9F74F04460E4617469846D0F81C9013 -:104500004FF0300A8AF311884FF0000B154665B161 -:104510002A4631462046FFF741FF034660B941462F -:10452000204600F021FA0028F1D0002383F31188FF -:10453000781B03B0BDE8F08FB9F1000F03D00190F4 -:104540002046C847019B8BF31188ED1A1E448AF35D -:104550001188DCE7C0E90511C160C3611144009B0B -:104560008260C0E90000016103627047F8B504464B -:104570000D461646302383F31188A768A7B1A368B8 -:10458000013BA36063695A1C62611D70D4E9043267 -:104590009A4224BFE3686361E3690BB12046984700 -:1045A000002080F3118807E03146204600F0DCF956 -:1045B0000028E2DA87F31188F8BD0000D0E905236E -:1045C0009A4210B501D182687AB98268013282605C -:1045D0005A1C82611C7803699A4224BFC3688361B4 -:1045E000002100F0D1F9204610BD4FF0FF30FBE76D -:1045F0002DE9F74F04460E4617469846D0F81C9012 -:104600004FF0300A8AF311884FF0000B154665B160 -:104610002A4631462046FFF7EFFE034660B9414681 -:10462000204600F0A1F90028F1D0002383F311887F -:10463000781B03B0BDE8F08FB9F1000F03D00190F3 -:104640002046C847019B8BF31188ED1A1E448AF35C -:104650001188DCE7026843681143016003B1184721 -:10466000704700001430FFF743BF00004FF0FF33E6 -:104670001430FFF73DBF00003830FFF7B9BF00002E -:104680004FF0FF333830FFF7B3BF00001430FFF7AF -:1046900009BF00004FF0FF311430FFF703BF0000E7 -:1046A0003830FFF763BF00004FF0FF323830FFF7BC -:1046B0005DBF0000012914BF6FF013000020704798 -:1046C000FFF748BD044B03600023C0E90233436099 -:1046D00001230374704700BF8057000810B53023D2 -:1046E000044683F31188FFF75FFD02232374002043 -:1046F00080F3118810BD000038B5C36904460D462B -:104700001BB904210844FFF7A5FF294604F1140052 -:10471000FFF7ACFE002806DA201D4FF40061BDE86B -:104720003840FFF797BF38BD0023037582680369DF -:104730001B6899689142FBD25A680360426010601E -:104740005860704700230375826803691B68996885 -:104750009142FBD85A68036042601060586070470D -:1047600008B50846302383F311880B7D032B05D051 -:10477000042B0DD02BB983F3118808BD8B6900225F -:104780001A604FF0FF338361FFF7CEFF0023F2E79B -:10479000D1E9003213605A60F3E70000FFF7C4BFAD -:1047A000054BD9680875186802681A6053600122C1 -:1047B0000275D860FBF730BF6066002030B50C4B47 -:1047C000DD684B1C87B004460FD02B46094A68466B -:1047D00000F06CF92046FFF7E3FF009B13B1684639 -:1047E00000F06EF9A86907B030BDFFF7D9FFF9E70F -:1047F0006066002061470008044B1A68DB68906817 -:104800009B68984294BF002001207047606600209A -:10481000084B10B51C68D86822681A6053600122E2 -:104820002275DC60FFF78EFF01462046BDE8104090 -:10483000FBF7F2BE60660020044B1A68DB689268E2 -:104840009B689A4201D9FFF7E3BF7047606600207A -:1048500038B5074C074908480123002523706560D7 -:1048600000F01EFC0223237085F3118838BD00BFC1 -:10487000C8680020AC5700086066002008B572B612 -:10488000044B186500F0D4FA00F08CFB024B0322B5 -:104890001A70FEE760660020C868002000F046B984 -:1048A000EFF3118020B9EFF30583302282F31188F2 -:1048B0007047000010B530B9EFF30584C4F3080465 -:1048C00014B180F3118810BDFFF7B6FF84F311888F -:1048D000F9E700008B60022308618B82084670476D -:1048E0008368A3F1840243F8142C026943F8442C32 -:1048F000426943F8402C094A43F8242CC26843F823 -:10490000182C022203F80C2C002203F80B2C044A6A -:1049100043F8102CA3F12000704700BF31060008B7 -:104920006066002008B5FFF7DBFFBDE80840FFF731 -:1049300035BF0000024BDB6898610F20FFF730BFE6 -:1049400060660020302383F31188FFF7F3BF000077 -:1049500008B50146302383F311880820FFF72EFFA6 -:10496000002383F3118808BD064BDB6839B1426828 -:1049700018605A60136043600420FFF71FBF4FF0B8 -:10498000FF307047606600200368984206D01A68BE -:104990000260506099611846FFF700BF7047000041 -:1049A00010B503689C68A2420CD85C688A600B60F2 -:1049B0004C602160596099688A1A9A604FF0FF3301 -:1049C000836010BD1B68121BECE700000A2938BF8A -:1049D0000A2170B504460D460A26601900F05AFBFC -:1049E00000F046FB041BA54203D8751C2E46044666 -:1049F000F3E70A2E04D9BDE87040012000F090BB17 -:104A000070BD0000F8B5144B0D46D96103F11001DB -:104A100041600A2A1969826038BF0A220160486031 -:104A20001861A818144600F027FB0A2700F020FBA5 -:104A3000431BA342064606D37C1C281900F02AFB20 -:104A400027463546F2E70A2F04D9BDE8F840012091 -:104A500000F066BBF8BD00BF60660020F8B50646F2 -:104A60000D4600F005FB0F4A134653F8107F9F4296 -:104A700006D12A4601463046BDE8F840FFF7C2BFDE -:104A8000D169BB68441A2C1928BF2C46A34202D90D -:104A90002946FFF79BFF224631460348BDE8F84010 -:104AA000FFF77EBF606600207066002010B4C0E98A -:104AB000032300235DF8044B4361FFF7CFBF0000E1 -:104AC00010B5194C236998420DD0D0E900328168A5 -:104AD00013605A609A680A449A60002303604FF09A -:104AE000FF33A36110BD2346026843F8102F5360C3 -:104AF0000022026022699A4203D1BDE8104000F012 -:104B0000C3BA936881680B44936000F0B1FA2269DC -:104B1000E1699268441AA242E4D91144BDE8104008 -:104B2000091AFFF753BF00BF606600202DE9F04768 -:104B3000DFF8BC8008F110072C4ED8F8105000F0B8 -:104B400097FAD8F81C40AA68031B9A423ED814442E -:104B5000D5E900324FF00009C8F81C4013605A60D4 -:104B6000C5F80090D8F81030B34201D100F08CFAAB -:104B700089F31188D5E9033128469847302383F318 -:104B800011886B69002BD8D000F072FA6A69A0EB2B -:104B900004094A4582460DD2022000F0C1FA0022E3 -:104BA000D8F81030B34208D151462846BDE8F04746 -:104BB000FFF728BF121A2244F2E712EB090938BFA7 -:104BC0004A4629463846FFF7EBFEB5E7D8F81030DD -:104BD000B34208D01444211AC8F81C00A960BDE8EB -:104BE000F047FFF7F3BEBDE8F08700BF7066002016 -:104BF0006066002000207047FEE70000704700005C -:104C00004FF0FF3070470000BFF34F8F024A136927 -:104C1000DB03FCD4704700BF0020024008B5094BFD -:104C20001B7873B9FFF7F0FF074B5A69002ABFBF23 -:104C3000064A9A6002F188329A601A6822F4806209 -:104C40001A6008BDE068002000200240230167458B -:104C500008B50B4B1B7893B9FFF7D6FF094B5A6980 -:104C600042F000425A611A6842F480521A601A688F -:104C700022F480521A601A6842F480621A6008BDF9 -:104C8000E068002000200240FF289ABF00F5803035 -:104C9000C0020020704700004FF400607047000021 -:104CA0004FF4807070470000FF2808B50BD8FFF75D -:104CB000EBFF00F500630268013204D10430834247 -:104CC000F9D1012008BD0020FCE70000FF2810B545 -:104CD00004461FD8FFF798FFFFF7A0FF0E4BF32203 -:104CE0001A6102225A615A6942EAC0025A615A693B -:104CF00042F480325A61FFF787FF4FF40061FFF7FB -:104D0000C3FF00F04BF9FFF7A3FF2046BDE81040BA -:104D1000FFF7CABF002010BD002002402DE9F84374 -:104D200040EA020313F00703144606D0304B40F26A -:104D300031321A600020BDE8F88385182D4A95426B -:104D40000CD92B4A40F236311160F3E7031D1B6882 -:104D50004A68934208D1083C08300831072C14D91E -:104D600002680B689A42F1D0FFF758FFFFF74CFF3B -:104D7000214E08314FF001084FF00009012CA1F13C -:104D8000080706D8FFF764FF01E0002CECD10120F2 -:104D9000D1E7C6F81480054651F8083C45F8043BB5 -:104DA00051F8043C4360FFF72FFF336943F00103E0 -:104DB0003361C6F81490026851F8083C9A420CD04E -:104DC0000B4B40F25E321A600C4B18600C4B1C60AF -:104DD0000C4B1F60FFF73CFFACE72D6851F8043C1B -:104DE0009D4201F10801EBD1083C0830C6E700BF45 -:104DF000DC6800200000080800200240D068002085 -:104E0000D8680020D4680020084908B50B7828B17C -:104E10001BB9FFF703FF01230B7008BD002BFCD06B -:104E2000BDE808400870FFF713BF00BFE06800202E -:104E300008B54FF4C0314FF0005000F0B1F8BDE8B4 -:104E400008404FF400414FF0805000F0A9B8000036 -:104E5000084600F0F3BB000070B582B0FFF720FDFC -:104E60000E4E054600F004F93268904237BF0C4AF6 -:104E70000B49516814682EBFD1E9004101315160DE -:104E80000419034641F10001284601913360FFF700 -:104E900011FD0199204602B070BD00BFE4680020FA -:104EA000E868002070B582B0FFF7FAFC104E0546A6 -:104EB00000F0DEF83268904237BF0E4A0D49516863 -:104EC00014682EBFD1E9004101315160041941F14C -:104ED00000010346284601913360FFF7EBFC01997E -:104EE0004FF47A7200232046FBF782F902B070BDBE -:104EF000E4680020E86800200244D2B2904200D169 -:104F00007047431C800000F1804000F51450006899 -:104F100041F8040BD8B2F1E7124B10B5D3F890402A -:104F2000240409D4D3F89040C3F89040D3F89040BB -:104F300044F40044C3F890400B4C2368024443F40B -:104F400080732360D2B2904200D110BD431C800018 -:104F500000F1804000F5145051F8044B0460D8B2C1 -:104F6000F1E700BF001002400070004007B50122C9 -:104F700001A90020FFF7C0FF019803B05DF804FB12 -:104F800013B50446FFF7F2FFA04205D0012201A9A4 -:104F900000200194FFF7C0FF02B010BD7047000071 -:104FA0007047000070470000074B45F255521A60E9 -:104FB00002225A6040F6FF729A604CF6CC421A60A8 -:104FC000024B01221A70704700300040F468002044 -:104FD000034B1B781BB1034B4AF6AA221A60704799 -:104FE000F468002000300040054B1A6832B902F125 -:104FF000804202F50432D2F894201A60704700BF54 -:10500000F0680020024B4FF40002C3F89420704770 -:105010000010024008B5FFF7E7FF024B1868C0F325 -:10502000407008BDF068002070470000FEE70000F7 -:105030000A4B0B480B4A90420BD30B4BDA1C121A4B -:10504000C11E22F003028B4238BF00220021FCF770 -:105050002BBD53F8041B40F8041BECE71C59000857 -:1050600078690020786900207869002000F0C2B8D3 -:105070004FF08043586A70474FF0804300225863D6 -:105080001A610222DA6070474FF080430022DA6032 -:10509000704700004FF0804358637047FEE7000000 -:1050A00070B51B4B01630025044686B058608562CD -:1050B0000E46FEF7F1FF04F11003C4E904334FF08C -:1050C000FF33C4E90635C4E90044A560E562FFF793 -:1050D000CFFF2B460246C4E9082304F134010D4AF0 -:1050E000256580232046FFF7F5FB0123E0600A4A8F -:1050F0000375009272680192B268CDE90223074BF2 -:105100006846CDE90435FFF70DFC06B070BD00BF61 -:10511000C8680020B8570008BD5700089D50000817 -:10512000024AD36A1843D062704700BF606600200D -:105130004B6843608B688360CB68C3600B694361D5 -:105140004B6903628B6943620B6803607047000020 -:1051500008B5204BDA6A42F07F02DA62DA6A22F09E -:105160007F02DA62DA6ADA6C42F07F02DA64DA6EBF -:1051700042F07F02DA66184ADB6E11464FF090402B -:10518000FFF7D6FF02F11C0100F58060FFF7D0FFAA -:1051900002F1380100F58060FFF7CAFF02F1540107 -:1051A00000F58060FFF7C4FF02F1700100F5806038 -:1051B000FFF7BEFF02F18C0100F58060FFF7B8FF3A -:1051C00002F1A80100F58060FFF7B2FFBDE80840DA -:1051D00000F050B800100240C457000808B500F0B5 -:1051E000FBF9FFF735FBBDE80840FFF7FDBE000007 -:1051F000704700000F4B9A6D42F001029A659A6F5A -:1052000042F001029A670C4A9B6F936843F00103D6 -:1052100093604FF08043A7229A624FF0FF32DA6228 -:1052200000229A615A63DA605A6001225A611A6058 -:10523000704700BF00100240002004E04FF08042A1 -:1052400008B51169D3680B40D9B2C9439B071161F6 -:1052500007D5302383F31188FFF720FB002383F366 -:10526000118808BD08B5FFF76FF8BDE8084000F0E9 -:105270008BB900004E4B4FF0FF319A6A99629A6ADF -:1052800000229A62986AD86A60F07F00D862D86A71 -:1052900000F07F00D862D86A186B1963186B1A6324 -:1052A000186B986B9963986B9A63986BD86BD963FA -:1052B000D86BDA63D86B186C1964196C1A64196CA2 -:1052C000196E41F001011966D3F8801021F0010137 -:1052D000C3F88010D3F88010996D41F08051996522 -:1052E000996F21F080519967996F32494FF40040CE -:1052F0008860CA600A624A628A62CA620A634A6352 -:105300008A63CA630A644A648A64CA640A654A652D -:105310004A604FF48072C1F880204FF440720A60F6 -:105320004A6912F48062FBD1D3F8901011F4407FE7 -:105330001EBF4FF48031C3F89010C3F89020D3F80B -:10534000982042F00102C3F89820D3F898209207E1 -:10535000FBD51A6842F480321A601A689003FCD5B3 -:10536000D3F8902022F00322C3F89020124ADA608A -:105370001A6842F080721A601A689101FCD50F49D0 -:105380000F4800229A60C3F888100E49C3F89C2089 -:10539000016002684A401207FBD19A6842F003029A -:1053A0009A609A6802F00C020C2AFAD1704700BF8A -:1053B0000010024000700040132A610155010050A6 -:1053C0000020024004070400074A08B5536903F0AF -:1053D0000103536123B1054A13680BB15068984724 -:1053E000BDE80840FEF77CBE00040140F8680020DC -:1053F000074A08B5536903F00203536123B1054A14 -:1054000093680BB1D0689847BDE80840FEF768BEC6 -:1054100000040140F8680020074A08B5536903F00A -:105420000403536123B1054A13690BB150699847CE -:10543000BDE80840FEF754BE00040140F8680020B3 -:10544000074A08B5536903F00803536123B1054ABD -:1054500093690BB1D0699847BDE80840FEF740BE9C -:1054600000040140F8680020074A08B5536903F0BA -:105470001003536123B1054A136A0BB1506A984770 -:10548000BDE80840FEF72CBE00040140F86800208B -:10549000164B10B55C6904F478725A61A30604D502 -:1054A000134A936A0BB1D06A9847600604D5104A34 -:1054B000136B0BB1506B9847210604D50C4A936BC4 -:1054C0000BB1D06B9847E20504D5094A136C0BB1B8 -:1054D000506C9847A30504D5054A936C0BB1D06C6A -:1054E0009847BDE81040FEF7FBBD00BF0004014037 -:1054F000F8680020194B10B55C6904F47C425A61CD -:10550000620504D5164A136D0BB1506D98472305FB -:1055100004D5134A936D0BB1D06D9847E00404D5C0 -:105520000F4A136E0BB1506E9847A10404D50C4A74 -:10553000936E0BB1D06E9847620404D5084A136F7E -:105540000BB1506F9847230404D5054A936F0BB1F4 -:10555000D06F9847BDE81040FEF7C2BD000401407F -:10556000F868002008B50348FEF76AFEBDE8084069 -:10557000FEF7B6BDF063002008B5FFF75FFEBDE89B -:105580000840FEF7ADBD0000062108B50846FEF74D -:10559000EFFE06210720FEF7EBFE06210820FEF7AE -:1055A000E7FE06210920FEF7E3FE06210A20FEF7AA -:1055B000DFFE06211720FEF7DBFE06212820FEF77E -:1055C000D7FE07211C20FEF7D3FEBDE808400C21C2 -:1055D0002620FEF7CDBE000008B5FFF743FE00F021 -:1055E00009F8FFF76DF8FFF703FEBDE80840FFF785 -:1055F0003DBD00000023054A19460133102BC2E9C6 -:10560000001102F10802F8D1704700BFF8680020CD -:105610000B460146184600F003B8000000F00EB833 -:1056200010B5054C13462CB10A4601460220AFF3D3 -:10563000008010BD2046FCE700000000024B014640 -:105640001868FFF705BC00BF2823002010B50139FA -:105650000244904201D1002005E0037811F8014F87 -:10566000A34201D0181B10BD0130F2E72DE9F04133 -:10567000A3B1C91A17780144044603F1FF3C8C42D8 -:10568000204601D9002009E00578BD4204F101045B -:10569000F5D10CEB0405D618A54201D1BDE8F08187 -:1056A00015F8018D16F801EDF045F5D0E7E700009B -:1056B000034611F8012B03F8012B002AF9D170479A -:1056C0006F72672E6172647570696C6F742E486FAB -:1056D0006C7962726F47345F4750530053544D33B7 -:1056E0003247343F3F00000040A2E4F16468910675 -:1056F0000041A3E5F2656992070000004261642061 -:1057000043414E496661636520696E6465782E0089 -:10571000000100000001FF0000640040006800403C -:1057200000000000000000003D28000819230008C8 -:10573000492F000811230008C1230008A5250008EF -:105740008923000851230008552300082D23000851 -:10575000152300086525000839230008B13000082A -:1057600045230008392500080096000000000000CD +:1000000000070020F1010008092E0008C12D00089A +:10001000E92D0008C12D0008E12D0008F3010008BA +:10002000F3010008F3010008F3010008E93D0008AE +:10003000F3010008F3010008F3010008F3010008D0 +:10004000F3010008F3010008F3010008F3010008C0 +:10005000F3010008F3010008F14200081943000809 +:10006000414300086943000891430008F301000878 +:10007000F3010008F3010008F3010008F301000890 +:10008000F3010008F3010008F3010008F301000880 +:10009000F3010008712D0008852D0008B943000800 +:1000A000F3010008F3010008F3010008F301000860 +:1000B000A1440008F3010008F3010008F30100085F +:1000C000F3010008F3010008F3010008F301000840 +:1000D000F3010008F30100088D440008F301000853 +:1000E0001D440008F3010008F3010008F3010008B3 +:1000F000F3010008F3010008F3010008F301000810 +:10010000F3010008F3010008F3010008F3010008FF +:10011000F3010008F3010008F3010008F3010008EF +:10012000F3010008F3010008F3010008F3010008DF +:10013000F3010008F3010008F3010008F3010008CF +:10014000F3010008F3010008F3010008F3010008BF +:10015000F3010008F3010008F3010008F3010008AF +:10016000F3010008F3010008F3010008F30100089F +:10017000F3010008F3010008F3010008F30100088F +:10018000F3010008F3010008F3010008F30100087F +:10019000F3010008F3010008992D0008AD2D0008B7 +:1001A000F3010008F3010008F3010008F30100085F +:1001B000F3010008F3010008F3010008F30100084F +:1001C000F3010008F3010008F3010008F30100083F +:1001D000F3010008F3010008F3010008F30100082F +:1001E0002D150008000000000000000000000000C5 +:1001F00002E000F000F8FEE772B6374880F30888A6 +:10020000364880F3098836483649086040F20000D5 +:10021000CCF200004EF63471CEF200010860BFF35C +:100220004F8FBFF36F8F40F20000C0F2F0004EF628 +:100230008851CEF200010860BFF34F8FBFF36F8F7C +:100240004FF00000E1EE100A4EF63C71CEF20001D4 +:100250000860062080F31488BFF36F8F04F0A2FFBC +:1002600005F082F84FF055301F491B4A91423CBFC0 +:1002700041F8040BFAE71D49184A91423CBF41F886 +:10028000040BFAE71A491B4A1B4B9A423EBF51F82E +:10029000040B42F8040BF8E700201849184A914271 +:1002A0003CBF41F8040BFAE704F080FF05F0A2F828 +:1002B000144C154DAC4203DA54F8041B8847F9E797 +:1002C00000F042F8114C124DAC4203DA54F8041B12 +:1002D0008847F9E704F068BF0007002000230020EA +:1002E0000000000808ED00E00001002000070020E9 +:1002F000E856000800230020B4230020B823002083 +:10030000B4690020E0010008E4010008E4010008ED +:10031000E40100082DE9F04F2DED108AC1F80CD052 +:10032000C3689D46BDEC108ABDE8F08F002383F3BF +:1003300011882846A047002004F0BAFBFEE704F02D +:1003400043FB00DFFEE70000F8B501F061F904F0BF +:10035000CBFE074604F01CFF0546A8BB1F4B9F427F +:1003600032D001339F4232D01D4B27F0FF029A4218 +:1003700030D1F8B200F022FF2E4642F2107400F0A5 +:1003800023FF08B10024264601F070FC20B10320B1 +:1003900000F07AF80024264635B1124B9F4203D074 +:1003A00004F0EEFE00242646002004F0A7FE0EB165 +:1003B00000F080F801F040FA00F038FF204600F02D +:1003C000D1F800F077F8F9E72E460024D7E7044685 +:1003D0000126D4E7064640F6C414D0E7010007B072 +:1003E000000008B0263A09B008B501F0DDF8A0F128 +:1003F00020035842584108BD07B541F212030221BB +:1004000001A8ADF8043001F0EDF803B05DF804FB8D +:1004100038B5302383F31188174803680BB104F013 +:1004200005FC164A144800234FF47A7104F0F4FBDB +:10043000002383F31188124C236813B12368013B16 +:100440002360636813B16368013B63600D4D2B78D3 +:1004500033B963687BB9022001F07CF93223636011 +:100460002B78032B07D163682BB9022001F072F9B6 +:100470004FF47A73636038BDB8230020110400087C +:10048000D8240020D0230020084B187003280CD853 +:10049000DFE800F008050208022001F051B902204F +:1004A00001F044B9024B00225A607047D02300206B +:1004B000D824002010B501F0D9FB30B1234B032222 +:1004C0001A70234B00225A6010BD224B224A1C4650 +:1004D00019680131F8D004339342F9D16268A2421D +:1004E000F2D31E4B9B6803F1006303F510439A425D +:1004F000EAD204F017FE04F029FE002001F0A2F871 +:100500000220FFF7C1FF164B9A6D00229A65996F82 +:100510009A67996FD96DDA65D96FDA67D96F196EF5 +:100520001A66D3F88010C3F88020D3F8803072B6F2 +:100530004FF0E0233021C3F8084DD4E9003281F3B5 +:1005400011889D4683F308881047BDE7D02300201B +:10055000D8240020009000082090000800230020EC +:10056000001002402DE9F04F93B0AC4B00902022D8 +:10057000FF210AA89D6801F009F9A94A1378A3B9D7 +:10058000A848012103601170302383F311880368A8 +:100590000BB104F04BFBA44AA24800234FF47A713C +:1005A00004F03AFB002383F31188009B13B19F4BA7 +:1005B000009A1A609E4A009C1378032B1EBF0023EA +:1005C00013709A4A4FF0000A18BF5360D34656463C +:1005D000D146012001F0B4F824B1944B1B68002BE4 +:1005E00000F01582002000F0DFFF0390039B002B3A +:1005F00001DA00F06FFE039B002BEDDB012001F020 +:1006000095F8039B213B162BE3D801A252F823F067 +:100610006D0600089506000829070008D3050008A4 +:10062000D3050008D3050008B307000883090008B4 +:100630009D080008FF080008270900084D09000868 +:10064000D30500085F090008D3050008D109000898 +:100650000D070008D3050008150A000879060008F0 +:100660000D070008D3050008FF0800080220FFF767 +:10067000BBFE002840F0F581009B0221BAF1000F7B +:1006800008BF1C4605A841F21233ADF8143000F043 +:10069000A9FF9EE74FF47A7000F086FF071EEBDBA0 +:1006A0000220FFF7A1FE0028E6D0013F052F00F24F +:1006B000DA81DFE807F0030A0D10133605230593EE +:1006C000042105A800F08EFF17E054480421F9E743 +:1006D00058480421F6E758480421F3E74FF01C0876 +:1006E000404600F0B1FF08F104080590042105A878 +:1006F00000F078FFB8F12C0FF2D1012000FA07F7D3 +:1007000047EA0B0B5FFA8BFB4FF0000901F08AF808 +:1007100026B10BF00B030B2B08BF0024FFF76CFE78 +:1007200057E746480421CDE7002EA5D00BF00B0378 +:100730000B2BA1D10220FFF757FE074600289BD0C4 +:10074000012000F07FFF0220FFF79EFE00261FFA27 +:1007500086F8404600F086FF044690B100214046EE +:1007600000F098FF01360028F1D1BA46044641F264 +:100770001213022105A8ADF814303E4600F032FFF6 +:1007800027E70120FFF780FE2546244B9B68AB42FC +:1007900007D9284600F058FF013040F06781043542 +:1007A000F3E7234B00251D70204BBA465D603E46A3 +:1007B000ACE7002E3FF460AF0BF00B030B2B7FF484 +:1007C0005BAF0220FFF760FE322000F0EDFEB0F1DB +:1007D0000008FFF651AF18F003077FF44DAF0F4A42 +:1007E000926808EB050393423FF646AFB8F5807F69 +:1007F0003FF742AF124B0193B84523DD4FF47A70B7 +:1008000000F0D2FE0390039A002AFFF635AF019B59 +:10081000039A03F8012B0137EDE700BF0023002006 +:10082000D4240020B823002011040008D82400207C +:10083000D023002004230020082300200C230020C4 +:10084000D4230020C820FFF7CFFD074600283FF43F +:1008500013AF1F2D11D8C5F1200242450AAB25F078 +:10086000030028BF424683490192184400F07CFFF0 +:10087000019A8048FF2100F089FF4FEAA8037D49D3 +:100880000193C8F38702284600F088FF0646002837 +:100890003FF46DAF019B05EB830537E70220FFF7BF +:1008A000A3FD00283FF4E8AE00F006FF00283FF467 +:1008B000E3AE0027B846704B9B68BB4218D91F2F88 +:1008C00011D80A9B01330ED027F0030312AA134458 +:1008D00053F8203C05934046042205A901F0B0F9E5 +:1008E00004378046E7E7384600F0AEFE0590F2E7B1 +:1008F000CDF81480042105A800F074FE06E700235B +:10090000642104A8049300F063FE00287FF4B4AED1 +:100910000220FFF769FD00283FF4AEAE049800F016 +:10092000C1FE0590E6E70023642104A8049300F0CB +:100930004FFE00287FF4A0AE0220FFF755FD0028EF +:100940003FF49AAE049800F0AFFEEAE70220FFF70A +:100950004BFD00283FF490AE00F0BEFEE1E7022020 +:10096000FFF742FD00283FF487AE05A9142000F0F0 +:10097000B9FE04210746049004A800F033FE39466E +:10098000B9E7322000F010FE071EFFF675AEBB0778 +:100990007FF472AE384A926807EB090393423FF640 +:1009A0006BAE0220FFF720FD00283FF465AE27F074 +:1009B00003074F44B9453FF4A9AE484600F044FE52 +:1009C0000421059005A800F00DFE09F10409F1E7E6 +:1009D0004FF47A70FFF708FD00283FF44DAE00F0A9 +:1009E0006BFE002844D00A9B01330BD008220AA9D1 +:1009F000002000F0D3FE00283AD02022FF210AA8D0 +:100A000000F0C4FEFFF7F8FC1C4804F057F813B0E0 +:100A1000BDE8F08F002E3FF42FAE0BF00B030B2B35 +:100A20007FF42AAE0023642105A8059300F0D0FDD1 +:100A3000074600287FF420AE0220FFF7D5FC804651 +:100A400000283FF419AEFFF7D7FC41F2883004F0DC +:100A500035F8059800F0FCFE464600F0E3FE3C4603 +:100A6000B7E5064652E64FF0000905E6BA467EE6CF +:100A700037467CE6D423002000230020A086010016 +:100A8000094A136849F2690099B21B0C00FB013353 +:100A90001360064B186844F2506182B2000C01FBEF +:100AA0000200186080B27047142300201023002039 +:100AB00010B500211022044600F068FE034B03CB62 +:100AC000206061601868A06010BD00BF9075FF1FB6 +:100AD0002DE9F041ADF54E7D0DF134086CAC40F2DE +:100AE000751207460D460EA80021C8F8001000F048 +:100AF0004DFE4FF4C4720021204600F047FE02F084 +:100B00008BF9274B4FF47A72B0FBF2F0186093E840 +:100B10000700022384E807000DF5E9702382FFF740 +:100B2000C7FF41F604531F49238406A804F0CCFCF8 +:100B30001B2384F832310DF2E32206AB0DF1300CA9 +:100B40001E4603CE664510605160334602F108022E +:100B5000F6D13188B3789370118020464146012246 +:100B600000F090FE00230393AB7E029305F119037E +:100B7000019380B20123CDE904800093E97E06A3AE +:100B8000D3E90023384602F005FD0DF54E7DBDE8A2 +:100B9000F08100BFAFF300809E6AC421818A46EED7 +:100BA000E0240020D85400082DE9F0412C4C237A91 +:100BB000DAB080460D465BBB27A9284600F072FFDD +:100BC0000746002842D19DF89D60C82E3ED80146B8 +:100BD0004FF4A662204600F0D9FD4FF48073C4F8AC +:100BE000F8314FF40073C4F80C334FF44073C4F879 +:100BF000203432460DF19E0104F1090000F0B4FDED +:100C000026449DF89C30777223720BB9EB7E2372D9 +:100C10008122002106AC27A800F0B8FD0122214660 +:100C200027A800F07BFF00230393AB7E029305F11E +:100C3000190380B201932823CDE904400093E97E93 +:100C400005A3D3E90023404602F0A4FC5AB0BDE856 +:100C5000F08100BFAFF3008026417272DF25D7B765 +:100C6000A85E0020F0B5254E4FF48A7505FB00659F +:100C7000F1B096F8D83085F8DC300024D82221462F +:100C800085F8E8403AA800F081FD06F1090000F07F +:100C900075FDD5F8E4308DF8F000C2B206AF06F16C +:100CA00009010DF1F100CDE93A3400F05DFD39465E +:100CB00001223AA800F05EFF80B2CDE9047008235B +:100CC0000127CDE9023706F1D803019330230093C1 +:100CD000317A0B4807A3D3E9002302F05BFCA04262 +:100CE00006DD02F099F8C5F8E000384671B0F0BDB5 +:100CF0002046FBE778F6339F93CACD8DA85E00208F +:100D0000F83400202DE9F04F264FDFF8A480264E5E +:100D100087B0384602F06AFC034600283AD0002427 +:100D2000CDE90344ADF81440027B8DF81420996896 +:100D30004068029403AA03C21B681C4D43F00043A1 +:100D40000293A146A2462B68D3F810B002F066F8D1 +:100D500010EB080241F100032846CDF800A002A9DB +:100D6000D84704F5A6640028C8BF49F00109B4F5C6 +:100D7000266F05F5A655E6D1B9F1000F05D0384626 +:100D800002F038FC86F800A0C3E73378072B04D8BC +:100D90000133337007B0BDE8F08F024802F02AFC3F +:100DA000F8E700BFF8340020DD630020283500207C +:100DB00040420F0070B50D4614461E4602F046FB39 +:100DC00050B9022E10D1012C0ED112A3D3E9002369 +:100DD000C5E90023012007E0282C10D005D8012CFC +:100DE00009D0052C0FD0002070BD302CFBD10BA3F7 +:100DF000D3E90023ECE70BA3D3E90023E8E70BA337 +:100E0000D3E90023E4E70BA3D3E90023E0E700BF25 +:100E1000AFF30080401DA12026812A0B78F6339F76 +:100E200093CACD8D9E6AC421818A46EE2641727294 +:100E3000DF25D7B7F017304A39059E5638B5054635 +:100E40000E4C0021013500F025FCA4F82C55B4F817 +:100E50002C0500F007FC78B1B4F82C0500F012FC6A +:100E6000014648B9B4F82C0500F014FCB4F82C3550 +:100E70000133A4F82C35EAE738BD00BFA85E002096 +:100E8000F8B50D4C0D4F0226A4F5805343F8307C85 +:100E9000237E3BB965692DB1284600F065FF2846E1 +:100EA00004F0C8FA204600F05FFF012EA4F5A65416 +:100EB00000D1F8BD0126E7E7185A00204055000888 +:100EC0002DE9F04F8FB000AF05460C4602F0BEFA98 +:100ED000002849D1237E022B1BD1E38A012B18D194 +:100EE00001F09AFF0646FFF7CBFD03464FF4C870AA +:100EF000DFF8C482B3FBF0F206F5167602FB10337E +:100F000016FA83F3C8F80030E37E33B9A34B00220E +:100F10001A703C37BD46BDE8F08F07F1240120462A +:100F200000F07EFD0028F4D107F11400FFF7C0FDAA +:100F300097F8264007F11401224607F1270004F034 +:100F400091FA0028E2D10F2C08D8944B1C70D8F8E5 +:100F50000030A3F51673C8F80030DAE797F82410CC +:100F6000284602F06BFAD4E7E38A282B2BD010D85E +:100F7000012B23D0052BCCD1BFF34F8F8849894B50 +:100F8000CA6802F4E0621343CB60BFF34F8F00BF27 +:100F9000FDE7302BBDD1844EE17E327A9142B8D14B +:100FA000607E3146002291F8DC50854200F0A58039 +:100FB0000132042A01F58A71F5D1AAE721462846B3 +:100FC000FFF786FDA5E721462846FFF7EDFDA0E7E0 +:100FD000B2F8EC507B6005F103094FEA99094FEA3A +:100FE0008902D11DC908A8EBC1039D46EB4600212B +:100FF000584600F0CBFB04F1EE012A463144584636 +:1010000000F0B2FB7B6813B9012000F01BFB96F8DF +:10101000D20000F027FB044630B9307200F04CFBE0 +:10102000204600F00FFBB1E0D6F8D4203AB996F88C +:10103000D200B6F82C25824201D8FFF7FFFED6F881 +:10104000D4202A44944208D296F8D200B6F82C252F +:101050000130824201D8FFF7F1FE70685FFA89F231 +:10106000594600F09BFB08B9C54679E0726896F8CE +:10107000D2002A447260D6F8D42005EB0209C6F8E3 +:10108000D49000F0EFFA814509D396F8D220D6F833 +:10109000D4000132001B86F8D220C6F8D400FF2D00 +:1010A0000FD80024347200F007FB204600F0CAFA83 +:1010B00000F0DCFD3D4B188108B9FFF7FBF9C54690 +:1010C00027E7BB6896F8D9000AFB0362FB68D2F8F1 +:1010D000E41082F8E83001F58061C2F8E030C2F82F +:1010E000E410FFF7BFFDFFF70DFE96F8D92001329F +:1010F00002F0030286F8D920B6E74FF48A7A0AFB99 +:1011000002F505F1EA013144204600F05FFDF86088 +:1011100000287FF4FEAE3544012285F8E82001F076 +:101120007BFED5F8E020D6ED007ADFED216A801A4B +:10113000192838BF192040F6B832904228BF10460F +:10114000B8EE677A07EE900AF8EEE77A67EEA67ACD +:10115000DFED186AE7EE267AFCEEE77AC6ED007A54 +:1011600096F8D930BB60BA6873680AFB02F432198A +:1011700092F8E81059B1D2F8E4108B42E8463FF4F7 +:1011800027AF002182F8E810C2F8E010C546736866 +:10119000064A9B0A01331381BBE600BFF1340020ED +:1011A00000ED00E00400FA05A85E0020E024002025 +:1011B000CDCCCC3D6666663FF4340020014B187000 +:1011C000704700BFEC24002038B54FF00054134B9B +:1011D00022689A4220D1124B627D12481A70237DF8 +:1011E00003724FF48073C0F8F8314FF40073C0F805 +:1011F0000C3300254FF44073C0F820340A49C0F87E +:10120000E450C922093000F0AFFAE0222946204616 +:1012100000F0BCFA012038BD0020FCE79AAD44C5BF +:10122000EC240020A85E00201600002037B500F056 +:101230001DFD1F4C1F4D2049288102236B7123681F +:1012400001225B682046984704F580531A49D3F879 +:10125000C03401225B6804F5A6509847002301932F +:10126000164B174900931748174B4FF4805202F062 +:10127000BDF8164B197811B1124802F0DFF801F0F1 +:10128000CBFD0446FFF7FCFB4FF4C873B0FBF3F251 +:1012900002FB130304F5167010FA83F00C4B186070 +:1012A00003F076FF08B10F232B8103B030BD00BFE0 +:1012B00028350020E024002040420F00B50D000832 +:1012C000F0240020F8340020C10E0008EC24002097 +:1012D000F43400202DE9F04F2DED028B002493B063 +:1012E0000DF12C089FED818BDFF83C92FFF70AFD92 +:1012F0000A94ADF834400B94C8F804400026814DA0 +:10130000DFF804B2374601238DF81C302B688DF8C6 +:101310001D408DED008B0DF11D02D3F808A007A92B +:1013200000232846D0479DF81CA0BAF1000F24D016 +:10133000D9F8143083F48063C9F8143010220021E6 +:101340000EA800F023FA2B6808AA5F690AA90DF11C +:101350001E032846B84798E803000FAB83E8030054 +:101360009DF834308DF844300A9B0E930EA9DDE9C8 +:101370000823584602F01CFB574606F5A666B6F54C +:10138000266F05F5A655BED1002FB7D15E4802F0F5 +:101390005DF800283FD15D4E01F03EFD3368984274 +:1013A00039D301F039FD0546FFF76AFB4FF4C873E6 +:1013B000B0FBF3F202FB130305F5167010FA83F08D +:1013C0003060534E8DF82870377817B901238DF8A7 +:1013D0002830C7F11005EDB20EA8FFF769FB062D06 +:1013E00028BF06250EAB2A46D9190DF1290000F0B9 +:1013F000BBF90AAB0393182302930135454B0193C4 +:10140000EDB201230093404804953AA3D3E90023A9 +:1014100002F062F8347001F0FFFC3F4A3F4D136860 +:10142000C31AB3F57A7F2FD3106001F0F7FC0246A0 +:101430000B46354802F0E8F8334802F007F818B3D5 +:101440002B7A374E002B14BF03230223737101F054 +:10145000E3FC0EAF4FF47A730122B0FBF3F0394690 +:101460003060304600F0B4FA182302932D4B0193FC +:1014700080B240F25513CDE90370009322481FA3B8 +:10148000D3E9002302F028F82B7A93B101F0C4FCD1 +:10149000002607464FF48A7895F8D900304400F0CA +:1014A000030008FB005393F8E82072B10136042EC4 +:1014B000F2D1C82003F002FB2B7A002B7FF410AF8F +:1014C00013B0BDEC028BBDE8F08FD3F8E02042B141 +:1014D0002B68FA2B38BFFA23BA1A0533B2EB430F45 +:1014E000E4D3FFF7BFFB0028E0D1E2E700000000F3 +:1014F00000000000401DA12026812A0BF1C6A7C1D3 +:10150000D068080F28350020F8340020F43400207B +:10151000F1340020F0340020D8630020A85E0020C1 +:10152000E0240020DC6300200008004810B5074CD0 +:10153000204600F04BFF04F5A65000F047FFBDE841 +:101540001040034A0349002003F06EBF28350020F5 +:1015500034640020810E000870B5104B1B780133F5 +:10156000DBB2012B0C4612D80D4B1D6829684FF4D5 +:101570007A730E6AA2FB0332014622462846B04720 +:10158000844204D1074B00221A70012070BD4FF431 +:10159000FA7003F093FA0020F8E700BF1823002048 +:1015A0001C2300202464002007B5002302460121EB +:1015B0000DF107008DF80730FFF7CEFF20B19DF841 +:1015C000070003B05DF804FB4FF0FF30F9E70000BF +:1015D0000A4608B50421FFF7BFFF80F00100C0B242 +:1015E000404208BD30B4074B0A461978064B53F801 +:1015F00021402368DD69054B0146AC46204630BCDE +:10160000604700BF246400201C230020A086010046 +:1016100070B503F00BFC094E094D3080002428689A +:101620003388834208D903F0FDFB2B68044401335F +:10163000B4F5104F2B60F2D370BD00BF26640020BC +:10164000E063002003F0A6BC00F1006000F510404C +:101650000068704700F10060920000F5104003F050 +:1016600023BC0000054B1A68054B1B889B1A83425C +:1016700002D9104403F0D6BB00207047E06300207D +:1016800026640020024B1B68184403F0D3BB00BF44 +:10169000E0630020024B1B68184403F0DDBB00BF71 +:1016A000E06300200020704700F10050A0F51040DA +:1016B000D0F8900570470000064991F8243033B106 +:1016C0000023086A81F824300822FFF7C3BF0120F5 +:1016D000704700BFE4630020014B1868704700BFEB +:1016E000002004E030B50F4B0F4C1B682288C3F379 +:1016F0000B030138934208440BD164680A46013C4D +:10170000824213460BD214F9015F2DB102F8015B3E +:10171000F6E781420B4602D22C2203F8012B581A1D +:1017200030BD00BF002004E020230020022802BFBB +:10173000024B4FF080629A61704700BF000800487A +:10174000022802BF024B4FF480629A61704700BFCB +:1017500000080048022801BF024A536983F48063ED +:10176000536170470008004810B50023934203D02E +:10177000CC5CC4540133F9E710BD000003460246B7 +:10178000D01A12F9011B0029FAD17047024403460E +:10179000934202D003F8011BFAE770472DE9F843A2 +:1017A0001F4D144695F824200746884652BBDFF8A3 +:1017B00070909CB395F824302BB92022FF21484625 +:1017C0002F62FFF7E3FF95F82400C0F10802A24260 +:1017D00028BF2246D6B24146920005EB8000FFF7B3 +:1017E000C3FF95F82430A41B1E44F6B2082E1744FC +:1017F0009044E4B285F82460DBD1FFF75DFF002858 +:10180000D7D108E02B6A03EB82038342CFD0FFF7E6 +:1018100053FF0028CBD10020BDE8F8830120FBE76F +:10182000E4630020024B1A78024B1A70704700BF25 +:10183000246400201823002003494FF461430B6007 +:10184000024B186803F026B80C6400201C2300200B +:10185000094B10B51822044600211846FFF796FFE1 +:10186000064A074B127804600146BDE8104053F861 +:10187000220003F00FB800BF0C6400202464002095 +:101880001C2300202DE9F0470D4604460021904618 +:10189000284640F27912FFF779FF234620220021E3 +:1018A000284602F027F8231D02222021284602F0B4 +:1018B00021F8631D03222221284602F01BF8A31DF4 +:1018C00003222521284602F015F804F1080310220E +:1018D0002821284602F00EF804F1100308223821CE +:1018E000284602F007F804F1110308224021284697 +:1018F00002F000F804F1120308224821284601F002 +:10190000F9FF04F1140320225021284601F0F2FFD0 +:1019100004F1180340227021284601F0EBFF04F186 +:1019200020030822B021284601F0E4FF04F121033E +:101930000822B821284601F0DDFF04F12207C02665 +:101940003B46314608222846083601F0D3FFB6F55B +:10195000A07F07F10107F3D104F1320308223146D9 +:10196000284601F0C7FF002704F1330A94F832300B +:101970004FEAC7099F4209F5A47615D3B8F1000FC5 +:1019800008D1314604F599730722284601F0B2FFC9 +:1019900009F24F16274694F832213B1B93420CD391 +:1019A000F01DC008BDE8F0870AEB070308223146A6 +:1019B000284601F09FFF0137D8E707F2331331467D +:1019C0000822284601F096FF08360137E3E70000B9 +:1019D00013B504460846002101602346C0F80310F1 +:1019E0002022019001F086FF0198231D0222202170 +:1019F00001F080FF0198631D0322222101F07AFF8C +:101A00000198A31D0322252101F074FF019804F120 +:101A100008031022282101F06DFF072002B010BD3D +:101A2000F7B50023047F00910E46072219460546AC +:101A300001F024FE731C0093012200230721284695 +:101A400001F01CFEC4B9B31C0093052223460821F3 +:101A5000284601F013FE0D243746B278BB1B934293 +:101A600011D32B7FA88A0734E408BBB9844294BF02 +:101A70000020012003B0F0BDAB8ADB00083BDB088F +:101A8000B3700824E8E7FB1C0093214600230822DA +:101A9000284601F0F3FD08340137DEE7201A18BFAD +:101AA0000120E7E7F7B50023047F00910E460822E6 +:101AB0001946054601F0E2FD731CC4B908220093E3 +:101AC00011462346284601F0D9FD102401237278DF +:101AD0005F1C013B934211D32B7FA88A0734E40893 +:101AE000BBB9844294BF0020012003B0F0BDAB8A93 +:101AF000DB00083BDB0873700824E7E7F319009369 +:101B0000214600230822284601F0B8FD08343B4650 +:101B1000DDE7201A18BF0120E7E70000F8B50E4600 +:101B200005461446002181223046FFF72FFE2B4642 +:101B300008220021304601F0DDFE7CB96B1C072233 +:101B40000821304601F0D6FE0F2401236A785F1C7D +:101B5000013B934204D3E01DC008F8BD0824F4E71C +:101B6000EB1921460822304601F0C4FE08343B46FA +:101B7000ECE70000F8B50E46054614460021CE22DB +:101B80003046FFF703FE2B4628220021304601F0A5 +:101B9000B1FE7CB905F1080308222821304601F086 +:101BA000A9FE30242F462A7A7B1B934204D3E01DE2 +:101BB000C008F8BD2824F5E707F1090321460822EB +:101BC000304601F097FE08340137ECE7F7B5047FA3 +:101BD00000910E46012310220021054601F04EFD22 +:101BE000C4B9B31C0093092223461021284601F0F2 +:101BF00045FD192437467288BB1B9A4211D82B7FAA +:101C0000A88A0734E408BBB9844294BF00200120AD +:101C100003B0F0BDAB8ADB00103BDB0873801024FF +:101C2000E8E73B1D0093214600230822284601F0E7 +:101C300025FD08340137DEE7201A18BF0120E7E749 +:101C400030B5094D0A4491420DD011F8013B58407E +:101C5000082340F30004013B2C4013F0FF0384EA07 +:101C60005000F6D1EFE730BD2083B8EDF7B5384A24 +:101C7000106851686B4603C36A46364936480823E4 +:101C800003F000FC0446002833D10A25334A1068CB +:101C900051686B4603C36A4631492F48082303F055 +:101CA000F1FB0446002849D00369B3F5EE2F45D86F +:101CB000B0F8661040F21D4291423FD1294A0244D9 +:101CC00002F15C018B4239D35C3B234900209E1A10 +:101CD000FFF7B6FF3246074604F164010020FFF724 +:101CE000AFFFA3689F4229D1E368984208BF00254F +:101CF00024E00369B3F5EE2F27D8418B40F21D4253 +:101D0000914220D1174A024402F110018B4218D3AC +:101D1000103B114900209D1AFFF792FF2A46064604 +:101D200004F118010020FFF78BFFA3689E4202D147 +:101D3000E368984201D00D25A8E70025284603B0A6 +:101D4000F0BD1025A2E70C25A0E70B259EE700BFFC +:101D500000550008DC6F07000090000809550008D6 +:101D6000906F07000870FFF710B5037C044613B9A5 +:101D7000006803F06FFB204610BD00000023BFF396 +:101D80005B8FC360BFF35B8FBFF35B8F8360BFF379 +:101D90005B8F7047BFF35B8F0068BFF35B8F70474B +:101DA00070B505460C30FFF7F5FF05F1080604464F +:101DB0003046FFF7EFFFA04206D930466D68FFF7C7 +:101DC000E9FF2544281A70BD3046FFF7E3FF201ACB +:101DD000F9E7000070B50546406898B105F10800C4 +:101DE000FFF7D8FF05F10C0604463046FFF7D2FF97 +:101DF0008442304694BF6D680025FFF7CBFF013C5D +:101E00002C44201A70BD000038B50C460546FFF77B +:101E1000C7FFA04210D305F10800FFF7BBFF044441 +:101E20006868B4FBF0F100FB1144BFF35B8F012045 +:101E3000AC60BFF35B8F38BD0020FCE72DE9F041BB +:101E4000144607460D46FFF7C5FF844228BF0446E7 +:101E5000D4B1B84658F80C6B4046FFF79BFF3044AE +:101E6000286040467E68FFF795FF331A9C4203D8EE +:101E70006C600120BDE8F0816B60A41B3B68AB6027 +:101E80002044E8600220F5E72046F3E738B50C4629 +:101E90000546FFF79FFFA04210D305F10C00FFF7A6 +:101EA00079FF04446868B4FBF0F100FB1144BFF310 +:101EB0005B8F0120EC60BFF35B8F38BD0020FCE737 +:101EC0002DE9FF41884669460746FFF7B7FF6C4694 +:101ED00006B204EBC6060025B44209D06268206849 +:101EE00008EB0501FFF740FC636808341D44F3E785 +:101EF00029463846FFF7CAFF284604B0BDE8F081FE +:101F0000F8B505460C300F46FFF744FF05F108060B +:101F100004463046FFF73EFFA042304688BF6C685B +:101F2000FFF738FF201A386020B130462C68FFF7E1 +:101F300031FF2044F8BD000073B5144606460D4637 +:101F4000FFF72EFF844228BF04460190DCB101A9AF +:101F50003046FFF7D5FF019B33B93268C5E902333C +:101F6000C5E9002401200CE09C4238BF01942860A0 +:101F7000019868608442F5D93368AB60241AEC603C +:101F8000022002B070BD2046FBE700002DE9FF41B2 +:101F90000F466946FFF7D0FF6C4600B204EBC00560 +:101FA0000026AC4209D0D4F8048054F8081BB819B4 +:101FB0004246FFF7D9FB4644F3E7304604B0BDE89C +:101FC000F081000038B50546FFF7E0FF0446014602 +:101FD0002846FFF719FF204638BD00007047000073 +:101FE00010B41346026814680022A4465DF8044B3E +:101FF0006047000000F5805090F8590470470000D9 +:1020000000F5805090F852047047000000F58050B1 +:1020100090F958047047000050207047302383F334 +:10202000118800F58052D2F89C34D2F898041844F4 +:10203000D2F894341844D2F87C341844D2F88C3452 +:102040001844D2F888341844002383F31188704769 +:1020500000F58050C0F854140120704738B5C26AAA +:10206000936923F001039361044600F0D5FE054611 +:10207000E36A9B69DB0706D500F0CEFE431BFA2B13 +:10208000F6D9002004E004F58054012084F85204BD +:1020900038BD00002DE9F04F0C4600F5805185B0A9 +:1020A0001F4691F85234BDF83890054690469BB1D2 +:1020B000D1F878340133C1F878342368980006D415 +:1020C000237B082B0BD9627B0AB10F2B07D9D1F8E0 +:1020D0007C340133C1F87C344FF0FF3010E0302302 +:1020E00083F31188EB6AD3F8C42012F4001B0AD0E2 +:1020F000D1F880340133C1F88034002080F3118896 +:1021000005B0BDE8F08FD3F8C4302068C3F3014AAE +:102110006B6A4822002812FB0A33B4BF40F08040AB +:10212000800418602268520044BF40F000501860DC +:10213000207B4FEA0A6242EA00425A60607B4FEA23 +:102140004A1610B342F440125A60D1F8B02401325A +:10215000C1F8B024AA1902F58352117B41F0200185 +:102160001173207B039300F0B3FE039B03308010B8 +:102170005FFA8BF282420BF1010B0DDA04EB820164 +:1021800003EB820249689160F2E7AA1902F58352D3 +:10219000117B60F34511E3E7EB6A012202FA0AF2D0 +:1021A000C3F8CC2005EB4A11AB1903F5825301F5B6 +:1021B0008251C3E904871831234604F10C0253F815 +:1021C000040B41F8040B9342F9D11B880B802E4479 +:1021D00041F2680346F803A006F5805609F00303B0 +:1021E00096F86C2043F0100322F01F02134386F888 +:1021F0006C30002383F31188CDF8009042463B46B3 +:102200002146284600F02AFE012079E713B500F5A3 +:1022100080540191606CFFF7DDFD1F280AD90199F8 +:10222000606C2022FFF74CFEA0F120035842584179 +:1022300002B010BD0020FBE708B5302383F31188FE +:1022400000F58050406CFFF799FD002383F311885F +:1022500008BD0000002202608281426082607047F7 +:1022600010B500220023C0E90023002304460381A7 +:102270000C30FFF7EFFF204610BD00002DE9F047BE +:102280009A4688B0074688469146302383F31188E2 +:1022900007F580546846FFF7E3FF606CFFF780FDA9 +:1022A0001F282DD9606C20226946FFF78BFE20285D +:1022B00026D194F852341BB303AD444605AB2E46E9 +:1022C00003CE9E4220606160354604F10804F6D1D9 +:1022D00030682060B388A380DDE90023C9E90023CA +:1022E000BDF80830AAF80030002383F31188534664 +:1022F0004A464146384608B0BDE8F04700F09CBD6C +:10230000002080F3118808B0BDE8F0872DE9F84F70 +:1023100000230646C0E90133294B46F8303B00F55F +:102320008154054688463746103438462037FFF733 +:1023300097FFA742F9D105F580544FF480532663E7 +:102340000026C4E90D366764012305F5835705F5BA +:10235000A359E66384F8403084F84830103709F117 +:1023600010094FF0000A4FF0000B47E908ABA7F146 +:102370001800FFF76FFF203747F8286C4F45F4D15E +:10238000B8F1010F84F85884A4F85A64A4F85C6486 +:10239000A4F85E6484F86064A4F86264A4F86464D9 +:1023A000A4F8666484F8686402D9064800F02EFD3B +:1023B000054B53F82830EB622846BDE8F88F00BF84 +:1023C00040550008145500083055000810B5044B5E +:1023D000197804464A1C1A70FFF798FF204610BD72 +:1023E000316400202DE9F84315460C4600295CD0E5 +:1023F000022001F077FF2E49B0FBF4F78C428CBF2E +:102400000A2111214B1EB7FBF1F601FB1671DAB25E +:1024100021B1022B1946F5D8002032E0731EB3F526 +:10242000806FF9D2C2EBC20808F103014FEAE10E56 +:10243000C1F3C701A2EB010C0EF101094FF47A734D +:102440005FFA8CF70EFB033E59FA8CFCBEFBFCFCDA +:10245000BCF5617F17DC1FFA8CF34A1C57FA82F235 +:102460007243B0FBF2F08442D6D14A1E0F2AD3D871 +:102470007A1E072AD0D801202B806E8028716971BE +:10248000AF71BDE8F88308F1FF314FEAE10CC1F309 +:10249000C701521A0CF1010ED7B20CFB03335EFADE +:1024A00082F2B3FBF2F39BB2D7E70846E9E700BF3D +:1024B0003F420F0030B50D4B0D4D05201C786C438D +:1024C0008C420ED15978518099785171D978917197 +:1024D000197911715B7903EB83035B001380012091 +:1024E00030BD013803F10603E8D1F9E78055000853 +:1024F00040420F0038B500F58053114A93F8583424 +:10250000D55C4FF45472554305F1804303F52443E1 +:10251000044600211846FFF739F90A4B60612B4445 +:10252000A361094B2B44E361084B2B442362084B06 +:102530002B446362E36A0022C3F8C02038BD00BFA9 +:102540002855000870A40040B0A4004088A50040B1 +:1025500078A600402DE9F04F00F580551F4695F80C +:102560005834022B89B004468946904604D9002687 +:10257000304609B0BDE8F08FA64A52F8231009B9D9 +:1025800042F82300A448C4F80C900178277499B944 +:10259000302383F31188A14B9A6D42F000729A6543 +:1025A0009A6B42F000729A639A6B22F000729A63FF +:1025B0000123037081F3118895F85134CBB930238E +:1025C00083F31188964A95F85834D35C012B2AD0AE +:1025D000022B2FD03BB90321152001F0A5FF0321C9 +:1025E000162001F0A1FF012385F85134002383F365 +:1025F0001188302383F31188E26A936923F0100372 +:10260000936100F009FC8246E36A9E6916F00806B1 +:1026100017D000F001FCA0EB0A03FA2BF4D9002636 +:1026200086F31188A4E70321562001F07DFF0321E2 +:102630005720D6E70321582001F076FF03215920C7 +:10264000CFE79A6942F001029A6100F0E5FB824609 +:10265000E36A9A69D00706D400F0DEFBA0EB0A0318 +:10266000FA2BF5D9DBE79A6942F002029A61E36A34 +:102670004FF0000AC3F854A08AF31188686CFFF782 +:102680007DFB04F5825B0BF1100B202200216846D4 +:10269000FFF77CF802A8FFF7DDFDCDF818A06A4629 +:1026A0000BEB06030DF1180E9446BCE80300F4454D +:1026B00018605960624603F10803F5D1DCF80000A8 +:1026C000186020369CF804201A71B6F5806FDCD1B2 +:1026D000002304F5A25285F8503485F853341A3299 +:1026E00049462046FFF77EFE064690B9E26A9369A6 +:1026F00023F00103936100F08FFB0546E36A9B69B9 +:10270000D9077FF534AF00F087FB431BFA2BF5D9CF +:102710002DE795F85E34C5F86C94591E95F85F3432 +:10272000E26A013B1B0243EA416395F860140139F8 +:102730000B43B5F85C14013943EA0143D361B8F1A6 +:10274000000F36D004F5A352023241462046FFF76F +:10275000B1FE90B9E26A936923F00103936100F03E +:102760005BFB0546E36A9B69DA077FF500AF00F083 +:1027700053FB431BFA2BF5D9F9E695F86724C5F806 +:102780007084511E95F86824E36A013A120142EA06 +:10279000012295F8661401390A43B5F86414013929 +:1027A00042EA014242F40002DA60E36A4FF4206236 +:1027B0009A642046FFF79EFE002385F85934E36AA9 +:1027C0006FF040421A65E36A164A5A65E36A44228A +:1027D0009A65E36A0722C3F8DC20E36A0322974282 +:1027E000DA653FF4C5AEE26A936923F001039361B1 +:1027F00000F012FB0746E36A9B69DB0705D500F092 +:102800000BFBC31BFA2BF6D9B1E6012385F8523432 +:10281000AEE600BF286400203064002000100240B3 +:10282000285500089B0008002DE9F04F054689B0A7 +:1028300090469946002741F2680A00F58056EB6AF7 +:10284000D3F8D430FB40D80751D505EB471252449A +:102850004FEA471B1379190749D4D6F8843401335A +:10286000C6F8843405F5A553C3E9008913799A069F +:1028700048BFD6F8B43405EB0B0248BF01335244CD +:1028800048BFC6F8B434137943F008031371DB076B +:1028900022D596F85334FBB105F5825418346846B6 +:1028A0005C44FFF7DDFC03AB04F1080C20686168B1 +:1028B0001A4603C2083464451346F7D120681060F5 +:1028C000A2889A800123ADF808302B68CDE90089F1 +:1028D000DB6B694628469847D6F8A834D6F85404E6 +:1028E0000133C6F8A83410B103681B699847013753 +:1028F000202FA4D109B0BDE8F08F00002DE9F04FE2 +:102900008DB004460F4600F089FA82468946002FB2 +:1029100056D1E36AD3F89020920141BF04F580516B +:10292000D1F898240132C1F89824D3F890201607E2 +:1029300003D100200DB0BDE8F08FD3F89050E669C8 +:10294000C5F30125482303FB0566E8464046FFF72B +:1029500081FC326851004ABF22F06043C2F38A43CF +:1029600043F00043920048BF43F0804300937368F4 +:1029700013F400131FBF04F5805201238DF80D30AE +:10298000D2F8B8340EBF8DF80D300133C2F8B83428 +:10299000F38803F00F038DF80C304FF0000B9DF817 +:1029A0000C0000F095FA5FFA8BF3984220D9F218E8 +:1029B0000CA90B44127A03F82C2C0BF1010BEEE757 +:1029C000012FB6D1E36AD3F89820950141BF04F5F1 +:1029D0008051D1F898240132C1F89824D3F8982076 +:1029E0001007A6D0D3F89850266AC5F30125A9E7A9 +:1029F000EFB9E36AC3F8945004A8FFF731FC98E8F4 +:102A00000F0007AD07C52B800023ADF818302368F1 +:102A10002046CDE904A9DB6B04A9984704F580544E +:102A200058B1D4F890340133C4F8903482E7012FC0 +:102A300004BFE36AC3F89C50DEE7D4F89434013352 +:102A4000C4F89434012075E72DE9F04105460F469E +:102A500000F58054012639462846FFF74FFF10B194 +:102A600084F85364F7E7D4F8A834D4F85404013355 +:102A7000C4F8A83420B10368BDE8F0411B691847C9 +:102A8000BDE8F081F0B5C36A1A6C12F47F0F2BD049 +:102A900000F580541B6CC4F8AC3441F26805002387 +:102AA00047194FF0010C00EB43122A445E011179E3 +:102AB00011F0020F15D0490713D4B959C66AD6F8D8 +:102AC000C8E00CFA01F111EA0E0F0AD0C6F8D010D6 +:102AD000117941F004011171D4F88C240132C4F849 +:102AE0008C240133202BDED1F0BD00002B4B70B5C0 +:102AF0001E561B5C012B2FD8294D2A4A55F823302E +:102B000052F826400BB341B3236D1A060FD580232C +:102B1000236500F083F950EA01020B4602D0013828 +:102B200061F10003024655F82600FFF77DFE236D94 +:102B30001B032CD555F826304FF4002203F58053A3 +:102B40002265012283F8592421E00123236508230B +:102B500023654FF48063236570BD236DDA0702D4CB +:102B6000236D9B0706D5032355F826002365002116 +:102B7000FFF76AFF236D180702D4236DD90606D527 +:102B8000182355F8260023650121FFF75DFF55F84E +:102B90002600BDE87040FFF775BF00BF2C55000848 +:102BA000286400203055000808B5302383F31188CD +:102BB000FFF768FF002383F3118808BDC36AD3F8C9 +:102BC000C40080F40010C0F34050704708B53023B3 +:102BD00083F3118800F58050406CFFF7E1F8002383 +:102BE00083F3118843090CBF0120002008BD0000B9 +:102BF00000F5805393F8592462B1C16A8A6922F0C2 +:102C000001028A61D3F89C240132C3F89C2400227B +:102C100083F85924704700002DE9F743302181F3F0 +:102C2000118800F582511031002541F2680E4FF0F5 +:102C3000010800F5805C00EB4514744426797707A1 +:102C40001CD4F6061AD5D0F82C908E69D9F8C87025 +:102C500008FA06F63E4211D04F6801970F68974276 +:102C6000019F9F410AD2C9F8D060267946F0040638 +:102C70002671DCF888440134CCF888440135202DD5 +:102C800001F12001D7D1002383F3118803B0BDE8FF +:102C9000F0830000F8B51E46002313700F4605466A +:102CA0001446FFF793FF80F0010038701EB12846EC +:102CB000FFF784FF2070F8BD2DE9F04F85B09946ED +:102CC000DDE90EA30D4602931378019391F800B04D +:102CD0008046164600F0A2F82B7804460F4613B93A +:102CE0003378002B41D022463B464046FFF794FF05 +:102CF000FFF75AFFFFF77CFF4B4632462946FFF7A6 +:102D0000C9FF2B7833B1BBF1000F03D0012005B010 +:102D1000BDE8F08F337813B1019B002BF6D108F595 +:102D200080530393029B544577EB03031DD2039B0F +:102D3000D3F85404C8B10368AAEB04011B68984790 +:102D40004B46324629464046FFF7A4FF2B7813B185 +:102D5000BBF1000FDAD1337813B1019B002BD5D131 +:102D600000F05CF804460F46DCE70020CFE70000E7 +:102D700008B500210846FFF7B9FEBDE8084001F09C +:102D800067B8000008B501210020FFF7AFFEBDE8DD +:102D9000084001F05DB8000008B500210120FFF7F0 +:102DA000A5FEBDE8084001F053B8000008B50121B8 +:102DB0000846FFF79BFEBDE8084001F049B8000057 +:102DC00000B59BB0EFF3098168226846FEF7CCFCA2 +:102DD000EFF30583014B9B6BFEE700BF00ED00E0C6 +:102DE00008B5FFF7EDFF000000B59BB0EFF30981D8 +:102DF00068226846FEF7B8FCEFF30583014B5B6B76 +:102E0000FEE700BF00ED00E0FEE700000FB408B5EC +:102E1000029801F003FEFEE702F002B902F0E4B806 +:102E200013B56C4684E80600031D94E8030083E8AC +:102E30000500012002B010BD73B58568019155B140 +:102E40001B885B0707D4D0E900369B6B9847019A33 +:102E5000C1B23046A847012002B070BDF0B5866807 +:102E600089B005460C465EB1BDF838305B070AD420 +:102E7000D0E900379B6B98472246C1B23846B0472D +:102E8000012009B0F0BD00220023CDE9002300237A +:102E9000ADF808300A4603AB01F108061068516826 +:102EA0001C4603C40832B2422346F7D110682060A2 +:102EB0009288A280FFF7B2FF0423ADF808302B6898 +:102EC000CDE90001DB6B694628469847D8E700004A +:102ED000082817D909280CD00A280CD00B280CD0A8 +:102EE0000C280CD00D280CD00E2814BF4020302008 +:102EF00070470C207047102070471420704718202E +:102F000070472020704700002DE9F041456A15B94F +:102F10004162BDE8F0814B6823F06047C3F38A4605 +:102F20004FEAD37EC3F3807816EA230638BF3E46C5 +:102F3000AC462B465A68BEEBD27F22F060440AD0E2 +:102F4000002A18DAA40CB44217D19D420FD10D60AB +:102F5000DEE71346EEE7A74207D102F08044C2F352 +:102F6000807242450BD054B1EFE708D2EDE7CCF8C0 +:102F700000100B60CDE7B44201D0B442E5D81A6826 +:102F80009C46002AE5D11960C3E700002DE9F0470F +:102F9000089D01F007044FEAD508224405F0070513 +:102FA00000EBD1004FF47F49944201D1BDE8F08796 +:102FB00004F0070705F0070A57453E4638BF564656 +:102FC000C6F10806111B8E4228BF0E46E10808EB29 +:102FD000D50E415C13F80EC0B94029FA06F721FA64 +:102FE0000AF1FFB28CEA010147FA0AF739408CEA8C +:102FF000010C03F80EC034443544D5E780EA0120C3 +:10300000082341F2210201B24000002980B203F1FD +:10301000FF33B8BF504013F0FF03F4D170470000F6 +:1030200038B50C468D18A54200D138BD14F8011BE7 +:10303000FFF7E4FFF7E7000042684AB11368436016 +:103040004389818901339BB29942438138BF83818F +:103050001046704770B588B0202204460D46684679 +:103060000021FEF793FB20460495FFF7E5FF02469B +:1030700058B16B46054608AE1C4603CCB4422860E6 +:103080006960234605F10805F6D1104608B070BD09 +:10309000082817D909280CD00A280CD00B280CD0E6 +:1030A0000C280CD00D280CD00E2814BF4020302046 +:1030B00070470C207047102070471420704718206C +:1030C0007047202070470000082817D90C280CD919 +:1030D00010280CD914280CD918280CD920280CD960 +:1030E00030288CBF0F200E207047092070470A201F +:1030F00070470B2070470C2070470D207047000070 +:103100002DE9F843078C072F04461ED9D0E9029811 +:1031100000254FF6FF73C5F12006A5F1200029FA1E +:1031200005F108FA06F628FA00F031430143C9B266 +:103130001846FFF763FF0835402D0346EBD1E169E0 +:103140003A46BDE8F843FFF76BBF4FF6FF70BDE8A6 +:10315000F883000010B54B6823B9CA8A63F30902EB +:10316000CA8210BD04691A681C600361C38A013BEE +:10317000C3824A60EFE700002DE9F84F1D46CB8A75 +:103180000F46C3F309010529814692460B4630D00C +:103190000020AAB207F11A049EB2042E1FFA80F88A +:1031A0000FD8904503F1010306D3FB8A0A4462F36A +:1031B0000903FB8201201AE01AF80060E65401308E +:1031C000EAE79045F1D2A1F1050B1C237C68BBFB1B +:1031D000F3F203FB12BB1FFA8BF6002C45D14846D5 +:1031E000FFF72AFF044638B978606FF00200BDE8A7 +:1031F000F88F4FF00008E6E7002606607860ADB271 +:103200004FF0000B454510D90AEB0803221D13F8B7 +:10321000011B9155B1B208F101081B291FFA88F86A +:103220002BD0454506F10106F1D8FB8AC3F309020C +:10323000154465F30903BCE7013292B21C462368CA +:10324000002BF9D16B1F0B441C21B3FBF1F30133AD +:103250009BB29A42D3D2BBF1000FD0D14846FFF7C0 +:10326000EBFE20B9C4F800B0BFE70122E7E7C0F8E1 +:1032700000B05E4620600446C1E74545D5D94846C2 +:10328000FFF7DAFE08B92060AFE7C0F800B000260B +:1032900020600446B6E700002DE9F04F2DED028BCB +:1032A0001C4683B05B69019207468846002B00F0FC +:1032B0009A80238C2BB1E269002A00F09480072BBE +:1032C00035D807F10C00FFF7B7FE054638B96FF0A7 +:1032D0000205284603B0BDEC028BBDE8F08F142236 +:1032E0000021FEF753FA228CE16905F10800FEF790 +:1032F0003BFA208C013080B2FFF7E6FEFFF7C8FEF4 +:10330000013880B22084013028746369228C1B78D4 +:103310002A4403F01F0363F03F0348F00041137297 +:10332000384669602946FFF7EFFD0125D1E700F136 +:103330000C034FF0000908EE103A4FF0800A4E4699 +:103340004D4618EE100AFFF777FE83460028BED0E0 +:1033500014220021FEF71AFA002E3AD1019BABF895 +:10336000083002220BF1080E1FFA82FC0CF101005A +:10337000BCF1060F218C80B201D88E422BD3FFF70F +:10338000A3FEFFF785FE62691278013802F01F0282 +:103390008E4208BF4FF0400A42EA49121BFA80F100 +:1033A0004AEA020A013048F0004281F808A08BF88E +:1033B0001000CBF8042059463846FFF7A5FD238CB2 +:1033C0000135B3422DB289F001094FF0000AB8D19E +:1033D0007FE70022C6E7E169895D0EF80210013639 +:1033E000B6B20132C0E76FF0010572E7F8B51546D5 +:1033F0000E463022002104461F46FEF7C7F9069B01 +:103400006360B5F5001F079BA76034BF6A094FF6DC +:10341000FF72A36297B2E66104F1100000239A42A2 +:1034200006D800230360A782E3822383E360F8BD0C +:103430000660013330462036F1E7000003781BB9FF +:103440004BB2002BC8BF0170704700000078704776 +:10345000F8B50C46C969074611B9238C002B37D142 +:10346000257E1F2D34D8387828BB228C072A2CD8EB +:10347000268A36F003032BD14FF6FF70FFF7D0FDFD +:1034800020F001003102400441EA0561400C41EAAC +:1034900040254FF6FF72234629463846FFF7FCFECB +:1034A000002807DD626913780133DBB21F2B88BF68 +:1034B00000231370F8BD218A2D0645EA0125054336 +:1034C0002046FFF71DFE0246E5E76FF00300F1E737 +:1034D0006FF00100EEE7000070B58AB004461646B2 +:1034E0000021282268461D46FEF750F9BDF8383005 +:1034F000ADF810300F9B05939DF840308DF81830D3 +:10350000119B07936946BDF84830ADF8203020463E +:10351000CDE90265FFF79CFF0AB070BD2DE9F041CF +:10352000D36905460C4616460BB9138C5BBB377E38 +:103530001F2F28D895F80080B8F1000F26D030460C +:10354000FFF7DEFD3378210241EAC33141EA080189 +:10355000338A41EA076141EA03410246334641F0BA +:1035600080012846FFF798FE00280ADD3378012BFA +:1035700007D1726913780133DBB21F2B88BF002398 +:103580001370BDE8F0816FF00100FAE76FF00300FF +:10359000F7E70000F0B58BB004460D461746002152 +:1035A000282268461E46FEF7F1F89DF84C305A1E58 +:1035B000534253418DF800309DF84030ADF8103043 +:1035C000119B05939DF848308DF81830149B079394 +:1035D0006A46BDF85430ADF8203029462046CDE982 +:1035E0000276FFF79BFF0BB0F0BD0000406A00B110 +:1035F00004307047436A1A68426202691A600361C4 +:10360000C38A013BC38270472DE9F041D0F8208086 +:10361000194E14461D464146002709B9BDE8F08100 +:10362000D1E90223A21A65EB0303964277EB030369 +:103630001ED2036A8B420DD1FFF78CFD036A1B6813 +:10364000036203690B60C38A0161016A013BC382A3 +:103650008846E2E7FFF77EFD0B68C8F80030036993 +:103660000B60C38A0161013BC382D8F80010D4E724 +:1036700088460968D1E700BF80841E002DE9F04F1D +:103680008BB00D46DDF8509014469B4680460028CE +:1036900000F01981B9F1000F00F01581531E3F2B86 +:1036A00000F21181012A03D1BBF1000F40F00B8120 +:1036B0000023CDE90833B8F81430B5EBC30F4FEA57 +:1036C000C30703D300200BB0BDE8F08F2B199F4236 +:1036D000D8F80C303ABF7F1BFFB227461BB9D8F889 +:1036E0001030002B7AD0272D4ED8C5F12806B742CE +:1036F0004FF000032CBFF6B23E4600932946D8F89F +:10370000080008AB3246FFF741FCA7EB060A354438 +:103710005FFA8AFAB8F8143003F10053053BDB0076 +:103720000493D8F80C3003932821039B13B1BAF10A +:10373000000F2CD1D8F8100040B1BAF1000F05D01D +:10374000009608AB5246691AFFF720FC38B2002FEA +:10375000B8D066070AD00AAB03EBD401624211F875 +:10376000083C02F00702134101F8083C082C3CD940 +:10377000102C40F2B580202C40F2B780BBF1000F36 +:1037800000F09C80082334E0BA460026C2E7049B80 +:10379000E02B28BFE02306930B44AB42059314D9DA +:1037A0005A1B03980096924534BF5246D2B2691A0A +:1037B00008AB04300792FFF7E9FB079A1644AAEB1F +:1037C000020A1544F6B25FFA8AFA049B069A059932 +:1037D0009B1A0493039B1B680393A6E70093D8F8F6 +:1037E000080008AB3A462946AEE7BBF1000F13D0FC +:1037F0000123B4EBC30F6CD0082C12D89DF82030F5 +:10380000621E23FA02F2D50706D54FF0FF3202FA04 +:1038100004F423438DF820309DF8203089F80030DF +:1038200051E7102C12D8BDF82030621E23FA02F2A4 +:10383000D10706D54FF0FF3202FA04F42343ADF866 +:103840002030BDF82030A9F800303CE7202C0FD8FC +:103850000899631E21FA03F3DA0705D54FF0FF320A +:1038600002FA04F40C430894089BC9F800302AE7D4 +:10387000402C2BD0DDE90865611EC4F12102A4F1C2 +:10388000210326FA01F105FA02F225FA03F31143A6 +:103890001943CB0712D50122A4F12003C4F1200162 +:1038A00002FA03F322FA01F1A240524243EA010371 +:1038B00063EB430332432B43CDE90823DDE90823BF +:1038C000C9E90023FFE66FF00100FCE66FF0080095 +:1038D000F9E6082CA0D9102CB3D9202CEED8C3E7D8 +:1038E000BBF1000FADD0022383E7BBF1000FBBD0CB +:1038F00004237EE730B5012A144638BF0124402C4A +:1039000085B028BF40240025012ACDE9025518D8EA +:103910001B788DF8083063070AD004AB03EBD4059D +:10392000624215F8083C02F00702934005F8083C93 +:10393000009103462246002102A8FFF727FB05B0AD +:1039400030BD082AE4D9102A03D81B88ADF8083006 +:10395000E1E7202A8DBFD3E900231B680293CDE95C +:103960000223D8E710B5CB681BB98B600B618B8243 +:1039700010BD04691A681C600361C38A013BC382DD +:10398000CA60F0E703064CBFC0F3C03002207047A6 +:1039900008B50246FFF7F6FF022806D15306C2F328 +:1039A0000F2001D100F0030008BDC2F30740FBE780 +:1039B0002DE9F04F93B0CDE903230A680446104681 +:1039C000FFF7E0FF022814BFC2F306260026002AF4 +:1039D0000D46824680F2F28112F0C04940F0EE813D +:1039E000097B002900F0EA81022803D02378B34242 +:1039F00040F0E781C2F304630693104602F07F03B0 +:103A00000593FFF7C5FF059B29444FEA834848EA21 +:103A10000A4848EA4668CE7800230022CDE9082308 +:103A2000F309834648EA0008029367D0059B009398 +:103A300002466768534608A92046B847002800F0A8 +:103A4000C381276A4FB9414604F10C00FFF702FB1E +:103A5000074690B96FF0020054E03B6998450DD0DD +:103A60003F68002FF9D1414604F10C00FFF7F2FA4C +:103A700007460028EED0236A3B60276297F817C0FC +:103A800006F01F08CCF3840CACEB08001FFA80FE94 +:103A90000028B8BF0EF12000A8EB0C031FFA83FE2C +:103AA000D7E90221B8BF00B2002B0793BEBF0EF1C9 +:103AB00020031BB2079352EA010338D0039BDFF8BF +:103AC00024E39A1A049B4FF0000C63EB0101964526 +:103AD0007CEB01032BD36B7B97F81AE0734519D16C +:103AE000029B002B78D0012821DC7868F8B9DFF838 +:103AF000F0C2944570EB010316D337E0276A27B96B +:103B00006FF00C0013B0BDE8F08F3B699845B5D05D +:103B10003F68F4E7B24890427CEB010301D30020F8 +:103B2000F0E7029B002BFAD0079B0F2B17DCFA7DE6 +:103B3000B30002F0030203F07C031343FB75394624 +:103B40002046FFF707FB6B7BBB76029B3BB9FB7DF7 +:103B5000C3F38402013262F38603FB75D0E76A7B0C +:103B6000BB7E9A42DBD1029B002B35D0B309022BDE +:103B700032D0039BBB60049BFB60142200210DA884 +:103B8000FDF704FE039B0A93049B0B932B1D0C93E0 +:103B90002B7BADF83EB0013BDBB2ADF83C30069B71 +:103BA0008DF84230059B8DF8433094F82C308DF819 +:103BB00040A083F001038DF844308DF84180A36864 +:103BC0000AA920469847FB7DC3F38403013303F021 +:103BD0001F039B02FB82A2E7FB7DC6F34012B2EB00 +:103BE000D31F40F0F480C3F38403434540F0F280D8 +:103BF000029A2B7BB609002A4DD0F2075DD4032B25 +:103C000040F2EB80039BBB60049BFB602B7BAE1DF3 +:103C1000033BDBB23246394604F10C00FFF7ACFA45 +:103C200000280CDA39462046FFF794FAFB7DC3F3EF +:103C30008403013303F01F039B02FB820AE7DDE9E3 +:103C40000884AB883B834FF6FF73C9F12000A9F1CC +:103C5000200228FA09F104FA00F0014324FA02F2E2 +:103C600011431846C9B2FFF7C9F909F10809B9F1BA +:103C7000400F0346E9D1B8822A7B033AD2B23146DB +:103C8000FFF7CEF9FB7DB882DA43C2F3C01262F3CC +:103C9000C713FB7543E786B92E1D013BDBB23246E5 +:103CA000394604F10C00FFF767FA0028BADB2A7BDB +:103CB000B88A013AD2B23146E2E7F98AC1F3090182 +:103CC000013B0429DAB25BD8281D002307F11B064B +:103CD0009A4208D910F801CB06F801C0013101332E +:103CE0000529DBB2F4D103990A9104990B9193420F +:103CF00007F11B010C9138BF043379680D9134BF73 +:103D000055FA83F300230E93FB8AADF83EB0C3F35C +:103D100009031A44069B8DF84230059B8DF8433009 +:103D200094F82C30ADF83C2083F001038DF844303A +:103D300000238DF840A08DF841807B602A7BB88AF3 +:103D4000013A291DFFF76CF93B8BB882834203D1FE +:103D5000A3680AA92046984720460AA9FFF702FE51 +:103D6000FB7DBA8AC3F38403013303F01F039B0274 +:103D7000FB823B8B9A420CBF00206FF01000C1E623 +:103D80007B68002BAFD0052001E01C3033461E6855 +:103D9000002EFAD1091A081D2E1D184401EB090C3A +:103DA000BCF11B0F5FFA89F39DD89A429BD916F894 +:103DB000013B00F8013B09F10109EFE76FF0090051 +:103DC000A0E66FF00A009DE66FF00B009AE66FF038 +:103DD0000D0097E66FF00E0094E66FF00F0091E68D +:103DE00040420F0080841E00EFF3098305494A6BAF +:103DF00022F001024A63683383F30988002383F3C6 +:103E00001188704700EF00E0302080F3118862B61F +:103E10000C4B0D4AD96821F4E0610904090C0A43EE +:103E2000DA60D3F8FC20094942F08072C3F8FC2024 +:103E30000A6842F001020A602022DA7783F8220041 +:103E4000704700BF00ED00E00003FA05001000E03D +:103E500010B5302383F311880E4B5B6813F40063B5 +:103E600014D0F1EE103AEFF30984683C4FF0807300 +:103E7000E361094BDB6B236684F3098800F098FD4E +:103E800010B1064BA36110BD054BFBE783F311880E +:103E9000F9E700BF00ED00E000EF00E03F0300089D +:103EA00042030008026843681143016003B11847E8 +:103EB00070470000024A136843F0C0031360704764 +:103EC0000044004013B50F4C204600F0D7FC04F12D +:103ED00014000D49009400234FF4807200F094FB0D +:103EE0000A490B4B00944FF4807204F1380000F043 +:103EF0000DFC084BE365002000F0F4F9206602B0E9 +:103F000010BD00BF38640020A4640020A465002018 +:103F1000B53E00080044004030B5037C214C002928 +:103F200018BF0C46012B0CD11F4B984209D11F4BD7 +:103F30009A6D42F400329A659A6F42F400329A67A1 +:103F40009B6F2268036EC16D846603EB5203B3FB63 +:103F5000F2F36268150442BF23F0070503F007037C +:103F600043EA4503CB60A36843F040034B60E3683A +:103F700043F001038B6042F4967343F001030B603E +:103F80004FF0FF330B62510505D512F0102205D01A +:103F9000B2F1805F04D080F8643030BD7F23FAE74F +:103FA0003F23F8E7A05500083864002000100240C5 +:103FB0002DE9F047C66D3768F4693462210705467C +:103FC00019D014F0080118BF4FF48071E20748BF00 +:103FD00041F02001A30748BF41F04001600748BFFE +:103FE00041F08001302383F31188281DFFF75AFF29 +:103FF000002383F31188E2050AD5302383F3118867 +:104000004FF48061281DFFF74DFF002383F31188D3 +:104010004FF030094FF0000A14F0200838D13B0669 +:1040200016D54FF0300905F1380A200610D589F36E +:104030001188504600F09EFB002836DA0821281D22 +:10404000FFF730FF27F080033360002383F31188EC +:10405000790614D5620612D5302383F31188D5E989 +:1040600013239A4208D12B6C33B11021281D27F05D +:104070004007FFF717FF3760002383F31188E3063B +:1040800018D5AA6E1369ABB1BDE8F047506918475F +:1040900089F31188736A95F864102846194000F076 +:1040A00007FC8AF31188F469B6E7B06288F31188D7 +:1040B000F469BAE7BDE8F087434B4FF4007270B57E +:1040C0001A605A6912F4C06FFBD1404B9A6802F033 +:1040D0000C02042A20D01A6842F480721A601A680E +:1040E0005205FCD501229A609A6802F00C02042A5B +:1040F000FAD13749374A0A600A6812F00F02FBD139 +:10410000C3F8982063221A601A689603FCD42E4ADA +:104110004FF48071C2F88010C468E50306D51A68B0 +:1041200042F480321A601A689103FCD5C269D20742 +:1041300009D5D3F8982042F00102C3F89820D3F8AB +:1041400098209607FBD54269DA6044F480721A60C1 +:1041500004F0807111B11A689501FBD59968026964 +:104160001B4E22F0030501F0030129439960856984 +:104170003560316869400907FBD1134905680D6056 +:1041800046684E608068C1F880006E0417D44869A4 +:104190008505FCD4996802F0030021F00301014376 +:1041A000996092009968514011F00C0FFAD1E20524 +:1041B0005EBF1A6822F480721A60002070BD4869E0 +:1041C0008005FCD5E6E700BF00700040001002400B +:1041D000002002400006040008B500F091F9BDE897 +:1041E000084000F065B9000010B5394C3948A36AA1 +:1041F0004FF0FF32A262A36A0023A362A16AE16AC0 +:1042000061F07F01E162E16A01F07F01E162E16A50 +:10421000216B2263216B2363216BA16BA263A16BD2 +:10422000A363A16BE16BE263E16BE363E16B216C80 +:104230002264226C2364226C226E42F00102226608 +:10424000D4F8802022F00102C4F88020D4F8802025 +:10425000A26D42F08052A265A26F22F08052A26746 +:10426000A26F1D4A4FF400419160D3601362536204 +:104270009362D362136353639363D363136453648E +:104280009364D36413655365116841F480711160C0 +:10429000D4F8902012F4407F1EBF4FF48032C4F84F +:1042A0009020C4F890300D4A0023A360C4F8882001 +:1042B000C4F89C30FFF700FF10B1094800F0AEFBD6 +:1042C000D4F8903023F00323C4F8903010BD00BF21 +:1042D00000100240C0550008007000405501005118 +:1042E000B8550008014B53F82000704728230020E0 +:1042F000074A08B5536903F00103536123B1054A26 +:1043000013680BB150689847BDE80840FFF7A0BD9F +:104310000004014034690020074A08B5536903F0DE +:104320000203536123B1054A93680BB1D0689847E3 +:10433000BDE80840FFF78CBD00040140346900204F +:10434000074A08B5536903F00403536123B1054AD2 +:1043500013690BB150699847BDE80840FFF778BD75 +:104360000004014034690020074A08B5536903F08E +:104370000803536123B1054A93690BB1D06998478B +:10438000BDE80840FFF764BD000401403469002027 +:10439000074A08B5536903F01003536123B1054A76 +:1043A000136A0BB1506A9847BDE80840FFF750BD4B +:1043B0000004014034690020164B10B55C6904F418 +:1043C00078725A61A30604D5134A936A0BB1D06A76 +:1043D0009847600604D5104A136B0BB1506B984791 +:1043E000210604D50C4A936B0BB1D06B9847E205BC +:1043F00004D5094A136C0BB1506C9847A30504D53A +:10440000054A936C0BB1D06C9847BDE81040FFF79C +:104410001FBD00BF0004014034690020194B10B5D6 +:104420005C6904F47C425A61620504D5164A136D36 +:104430000BB1506D9847230504D5134A936D0BB10A +:10444000D06D9847E00404D50F4A136E0BB1506E3F +:104450009847A10404D50C4A936E0BB1D06E9847CF +:10446000620404D5084A136F0BB1506F98472304B8 +:1044700004D5054A936F0BB1D06F9847BDE8104043 +:10448000FFF7E6BC000401403469002008B503488A +:10449000FFF78EFDBDE80840FFF7DABC3864002066 +:1044A00008B500F0DBFEBDE80840FFF7D1BC000016 +:1044B000062108B5084600F037F80621072000F06D +:1044C00033F80621082000F02FF80621092000F01B +:1044D0002BF806210A2000F027F80621172000F00B +:1044E00023F80621282000F01FF807211C2000F0E7 +:1044F0001BF8BDE808400C21262000F015B800008C +:104500004FF0E023002258684FF0FF31930003F191 +:10451000604303F5614301329042C3F88010C3F851 +:104520008011F3D27047000000F1604303F561434E +:104530000901C9B283F80013012200F01F039A4059 +:1045400043099B0003F1604303F56143C3F88021F5 +:104550001A607047F8B5154682680669AA420B468C +:10456000816938BF8568761AB54204460BD2184671 +:104570002A46FDF7F9F8A3692B44A361A3685B1BE6 +:10458000A3602846F8BD0CD918463246FDF7ECF872 +:10459000AF1BE1683A463044FDF7E6F8E3683B4478 +:1045A000EBE718462A46FDF7DFF8E368E5E7000089 +:1045B00083689342F7B51546044638BF8568D0E94D +:1045C0000460361AB5420BD22A46FDF7CDF863696E +:1045D0002B446361A36828465B1BA36003B0F0BD56 +:1045E0000DD932460191FDF7BFF80199E068AF1B84 +:1045F0003A463144FDF7B8F8E3683B44E9E72A4618 +:10460000FDF7B2F8E368E4E710B50A440024C3619B +:10461000029B8460C0E90000C0E90511C16002612D +:10462000036210BD08B5D0E90532934201D182681A +:1046300082B98268013282605A1C42611970D0E9E5 +:1046400004329A4224BFC3684361002100F052FA49 +:10465000002008BD4FF0FF30FBE7000070B53023AD +:1046600004460E4683F31188A568A5B1A368A26924 +:10467000013BA360531CA36115782269934224BFB8 +:10468000E368A361E3690BB120469847002383F3F5 +:104690001188284607E03146204600F01BFA002822 +:1046A000E2DA85F3118870BD2DE9F74F04460E4616 +:1046B00017469846D0F81C904FF0300A8AF31188BC +:1046C0004FF0000B154665B12A4631462046FFF7EC +:1046D00041FF034660B94146204600F0FBF900283F +:1046E000F1D0002383F31188781B03B0BDE8F08F6D +:1046F000B9F1000F03D001902046C847019B8BF30E +:104700001188ED1A1E448AF31188DCE7C0E905110F +:10471000C160C3611144009B8260C0E90000016177 +:1047200003627047F8B504460D461646302383F3FE +:104730001188A768A7B1A368013BA36063695A1CED +:1047400062611D70D4E904329A4224BFE368636158 +:10475000E3690BB120469847002080F3118807E0F9 +:104760003146204600F0B6F90028E2DA87F31188D6 +:10477000F8BD0000D0E905239A4210B501D1826846 +:104780007AB98268013282605A1C82611C7803699E +:104790009A4224BFC3688361002100F0ABF9204630 +:1047A00010BD4FF0FF30FBE72DE9F74F04460E46F2 +:1047B00017469846D0F81C904FF0300A8AF31188BB +:1047C0004FF0000B154665B12A4631462046FFF7EB +:1047D000EFFE034660B94146204600F07BF9002811 +:1047E000F1D0002383F31188781B03B0BDE8F08F6C +:1047F000B9F1000F03D001902046C847019B8BF30D +:104800001188ED1A1E448AF31188DCE702684368B8 +:104810001143016003B11847704700001430FFF7DF +:1048200043BF00004FF0FF331430FFF73DBF0000DF +:104830003830FFF7B9BF00004FF0FF333830FFF7D3 +:10484000B3BF00001430FFF709BF00004FF0FF3185 +:104850001430FFF703BF00003830FFF763BF0000DC +:104860004FF0FF323830FFF75DBF0000012914BF61 +:104870006FF0130000207047FFF724BB044B036068 +:104880000023C0E90233436001230374704700BF73 +:10489000E055000810B53023044683F31188FFF774 +:1048A0003BFB02232374002080F3118810BD00001D +:1048B00038B5C36904460D461BB904210844FFF707 +:1048C000A5FF294604F11400FFF7ACFE002806DA24 +:1048D000201D4FF40061BDE83840FFF797BF38BD99 +:1048E00000230375826803691B6899689142FBD2B3 +:1048F0005A68036042601060586070470023037577 +:10490000826803691B6899689142FBD85A68036002 +:10491000426010605860704708B50846302383F342 +:1049200011880B7D032B05D0042B0DD02BB983F3FD +:10493000118808BD8B6900221A604FF0FF33836134 +:10494000FFF7CEFF0023F2E7D1E9003213605A608F +:10495000F3E70000FFF7C4BF054BD9680875186876 +:1049600002681A60536001220275D860FBF7D2BC5E +:10497000A866002030B50C4BDD684B1C87B00446A0 +:104980000FD02B46094A684600F046F92046FFF74B +:10499000E3FF009B13B1684600F048F9A86907B02F +:1049A00030BDFFF7D9FFF9E7A866002019490008D4 +:1049B000044B1A68DB6890689B68984294BF00209B +:1049C00001207047A8660020084B10B51C68D86805 +:1049D00022681A60536001222275DC60FFF78EFFA7 +:1049E00001462046BDE81040FBF794BCA8660020B5 +:1049F00038B5074C07490848012300252370656036 +:104A000000F05AFC0223237085F3118838BD00BFE3 +:104A1000106900200C560008A866002008B572B680 +:104A2000044B186500F0CAFA00F07AFB024B03222F +:104A30001A70FEE7A86600201069002000F02CB96B +:104A40008B60022308618B82084670478368A3F15C +:104A5000840243F8142C026943F8442C426943F859 +:104A6000402C094A43F8242CC26843F8182C02222F +:104A700003F80C2C002203F80B2C044A43F8102CEA +:104A8000A3F12000704700BF2D030008A866002096 +:104A900008B5FFF7DBFFBDE80840FFF75BBF00008C +:104AA000024BDB6898610F20FFF756BFA866002015 +:104AB000302383F31188FFF7F3BF000008B50146E8 +:104AC000302383F311880820FFF754FF002383F37A +:104AD000118808BD064BDB6839B1426818605A601E +:104AE000136043600420FFF745BF4FF0FF3070476D +:104AF000A86600200368984206D01A6802605060D9 +:104B000099611846FFF726BF7047000010B503688B +:104B10009C68A2420CD85C688A600B604C60216083 +:104B2000596099688A1A9A604FF0FF33836010BD0C +:104B30001B68121BECE700000A2938BF0A2170B578 +:104B400004460D460A26601900F0B0FB00F09CFBFD +:104B5000041BA54203D8751C2E460446F3E70A2E13 +:104B600004D9BDE87040012000F0E6BB70BD000034 +:104B7000F8B5144B0D46D96103F1100141600A2AC2 +:104B80001969826038BF0A22016048601861A8185C +:104B9000144600F07DFB0A2700F076FB431BA3427E +:104BA000064606D37C1C281900F080FB27463546B4 +:104BB000F2E70A2F04D9BDE8F840012000F0BCBBA1 +:104BC000F8BD00BFA8660020F8B506460D4600F007 +:104BD0005BFB0F4A134653F8107F9F4206D12A46CB +:104BE00001463046BDE8F840FFF7C2BFD169BB6857 +:104BF000441A2C1928BF2C46A34202D92946FFF794 +:104C00009BFF224631460348BDE8F840FFF77EBFD0 +:104C1000A8660020B866002010B4C0E90323002372 +:104C20005DF8044B4361FFF7CFBF000010B5194C8E +:104C3000236998420DD0D0E90032816813605A6030 +:104C40009A680A449A60002303604FF0FF33A3611F +:104C500010BD2346026843F8102F53600022026003 +:104C600022699A4203D1BDE8104000F019BB936855 +:104C700081680B44936000F007FB2269E169926848 +:104C8000441AA242E4D91144BDE81040091AFFF7C2 +:104C900053BF00BFA86600202DE9F047DFF8BC80B5 +:104CA00008F110072C4ED8F8105000F0EDFAD8F8A3 +:104CB0001C40AA68031B9A423ED81444D5E900322E +:104CC0004FF00009C8F81C4013605A60C5F8009006 +:104CD000D8F81030B34201D100F0E2FA89F311881C +:104CE000D5E9033128469847302383F311886B694F +:104CF000002BD8D000F0C8FA6A69A0EB04094A4535 +:104D000082460DD2022000F017FB0022D8F81030A6 +:104D1000B34208D151462846BDE8F047FFF728BF07 +:104D2000121A2244F2E712EB090938BF4A46294613 +:104D30003846FFF7EBFEB5E7D8F81030B34208D09D +:104D40001444211AC8F81C00A960BDE8F047FFF719 +:104D5000F3BEBDE8F08700BFB8660020A86600205B +:104D600038B500F091FA054AD2E90845031B181935 +:104D700045F10001C2E9080138BD00BFA866002066 +:104D800000207047FEE70000704700004FF0FF3042 +:104D900070470000BFF34F8F024A1369DB03FCD456 +:104DA000704700BF0020024008B5094B1B7873B95B +:104DB000FFF7F0FF074B5A69002ABFBF064A9A6007 +:104DC00002F188329A601A6822F480621A6008BD83 +:104DD00028690020002002402301674508B50B4BDD +:104DE0001B7893B9FFF7D6FF094B5A6942F000428E +:104DF0005A611A6842F480521A601A6822F480528A +:104E00001A601A6842F480621A6008BD286900209E +:104E100000200240FF289ABF00F58030C002002029 +:104E2000704700004FF40060704700004FF480703E +:104E300070470000FF2808B50BD8FFF7EBFF00F51F +:104E400000630268013204D104308342F9D10120A9 +:104E500008BD0020FCE70000FF2810B504461FD85D +:104E6000FFF798FFFFF7A0FF0E4BF3221A61022213 +:104E70005A615A6942EAC0025A615A6942F4803260 +:104E80005A61FFF787FF4FF40061FFF7C3FF00F09F +:104E900043F9FFF7A3FF2046BDE81040FFF7CABF64 +:104EA000002010BD002002402DE9F84340EA020333 +:104EB00013F00703144606D0304B40F241321A601B +:104EC0000020BDE8F88385182D4A95420CD92B4A5D +:104ED00040F246311160F3E7031D1B684A689342B4 +:104EE00008D1083C08300831072C14D902680B6837 +:104EF0009A42F1D0FFF758FFFFF74CFF214E0831DF +:104F00004FF001084FF00009012CA1F1080706D865 +:104F1000FFF764FF01E0002CECD10120D1E7C6F8D7 +:104F20001480054651F8083C45F8043B51F8043C10 +:104F30004360FFF72FFF336943F001033361C6F885 +:104F40001490026851F8083C9A420CD00B4B40F286 +:104F50006E321A600C4B18600C4B1C600C4B1F60BF +:104F6000FFF73CFFACE72D6851F8043C9D4201F18E +:104F70000801EBD1083C0830C6E700BF24690020D7 +:104F80000000080800200240186900202069002065 +:104F90001C690020084908B50B7828B11BB9FFF738 +:104FA00003FF01230B7008BD002BFCD0BDE80840B7 +:104FB0000870FFF713BF00BF2869002008B5064935 +:104FC000064800F0ABF8BDE808404FF400414FF050 +:104FD000805000F0A3B800BF007F01000001002056 +:104FE000084600F037BA000038B5EFF311859DB9D7 +:104FF000EFF30584C4F30804302334B183F311883C +:10500000FFF7AEFE85F3118838BD83F31188FFF7F3 +:10501000A7FE84F3118838BDBDE83840FFF7A0BE75 +:1050200038B5FFF7E1FF114C114AC00840EA417062 +:10503000A0FB025EC908A0FB040C1CEB050CA1FB45 +:1050400004404FF000035B41A1FB02121CEB040C77 +:1050500043EB000011EB0E0142F10002411842F156 +:105060000000090941EA007038BD00BFCFF753E3E3 +:10507000A59BC4200244D2B2904200D17047431C89 +:10508000800000F1804000F51450006841F8040BE6 +:10509000D8B2F1E7124B10B5D3F89040240409D4EC +:1050A000D3F89040C3F89040D3F8904044F40044C3 +:1050B000C3F890400B4C2368024443F48073236090 +:1050C000D2B2904200D110BD431C800000F180405C +:1050D00000F5145051F8044B0460D8B2F1E700BF5A +:1050E000001002400070004007B5012201A9002015 +:1050F000FFF7C0FF019803B05DF804FB13B5044649 +:10510000FFF7F2FFA04205D0012201A9002001947F +:10511000FFF7C0FF02B010BD7047000070470000ED +:1051200070470000074B45F255521A6002225A6040 +:1051300040F6FF729A604CF6CC421A60024B012294 +:105140001A7070470030004030690020034B1B7814 +:105150001BB1034B4AF6AA221A607047306900203F +:1051600000300040054B1A6832B902F1804202F566 +:105170000432D2F894201A60704700BF2C690020D6 +:10518000024B4FF40002C3F8942070470010024015 +:1051900008B5FFF7E7FF024B1868C0F3407008BD81 +:1051A0002C69002070470000FEE700000A4B0B4806 +:1051B0000B4A90420BD30B4BDA1C121AC11E22F081 +:1051C00003028B4238BF00220021FCF7DFBA53F8FC +:1051D000041B40F8041BECE79C570008B46900204E +:1051E000B4690020B46900200023054A1946013340 +:1051F000102BC2E9001102F10802F8D1704700BF7C +:105200003469002008B5124B9A6D42F001029A658C +:105210009A6F42F001029A670E4A9B6F936843F0BF +:10522000010393600620FFF75DF80B4BB0FBF3F032 +:105230004FF080434FF0FF3201389862DA6200226B +:105240009A615A63DA605A6001225A611A6008BD95 +:1052500000100240002004E040420F004FF0804266 +:1052600008B51169D3680B40D9B2C9439B071161D6 +:1052700007D5302383F31188FFF7E0FB002383F386 +:10528000118808BDFFF7BEBF4FF08043586A7047D2 +:105290004FF08043002258631A610222DA6070479F +:1052A0004FF080430022DA60704700004FF08043E7 +:1052B00058637047FEE7000070B51B4B0163002583 +:1052C000044686B0586085620E46FEF79DFD04F1E7 +:1052D0001003C4E904334FF0FF33C4E90635C4E9D1 +:1052E0000044A560E562FFF7CFFF2B460246C4E904 +:1052F000082304F134010D4A256580232046FFF779 +:105300009FFB0123E0600A4A0375009272680192D4 +:10531000B268CDE90223074B6846CDE90435FFF7B3 +:10532000B7FB06B070BD00BF10690020185600081A +:105330001D560008B5520008024AD36A1843D062CD +:10534000704700BFA86600204B6843608B6883608D +:10535000CB68C3600B6943614B6903628B6943622D +:105360000B6803607047000008B5204BDA6A42F012 +:105370007F02DA62DA6A22F07F02DA62DA6ADA6CD3 +:1053800042F07F02DA64DA6E42F07F02DA66184A8F +:10539000DB6E11464FF09040FFF7D6FF02F11C0183 +:1053A00000F58060FFF7D0FF02F1380100F5806062 +:1053B000FFF7CAFF02F1540100F58060FFF7C4FF58 +:1053C00002F1700100F58060FFF7BEFF02F18C0171 +:1053D00000F58060FFF7B8FF02F1A80100F58060DA +:1053E000FFF7B2FFBDE80840FEF7FEBE0010024026 +:1053F0002456000808B500F009F8FFF7F9FABDE8EF +:105400000840FFF7AFBE00007047000008B5FEF788 +:10541000E3FEFFF7E9FEFFF72FFAFFF7F5FFBDE820 +:105420000840FFF72FBF00000B460146184600F06A +:1054300003B8000000F00EB810B5054C13462CB1AF +:105440000A4601460220AFF3008010BD2046FCE76B +:1054500000000000024B01461868FFF7C1BD00BF05 +:105460005023002010B501390244904201D10020A0 +:1054700005E0037811F8014FA34201D0181B10BDBD +:105480000130F2E72DE9F041A3B1C91A17780144C0 +:10549000044603F1FF3C8C42204601D9002009E07C +:1054A0000578BD4204F10104F5D10CEB0405D618D2 +:1054B000A54201D1BDE8F08115F8018D16F801ED86 +:1054C000F045F5D0E7E70000034611F8012B03F89B +:1054D000012B002AF9D170476F72672E61726475D3 +:1054E00070696C6F742E486F6C7962726F47345FAD +:1054F0004750530053544D333247343F3F00000070 +:1055000040A2E4F1646891060041A3E5F265699266 +:10551000070000004261642043414E4966616365B3 +:1055200020696E6465782E00000100000001FF0014 +:10553000006400400068004000000000000000001F +:1055400055250008E11F0008B92C0008512000086B +:10555000952000087D2200085D2000081920000821 +:105560001D200008F51F0008DD1F00083922000873 +:1055700001200008212E00080D2000080D2200083F +:1055800001040E05054B02020E05054B04010E0534 +:10559000054B05010B04044B0801060303460000FC +:1055A0000096000000000000000000000000000065 +:1055B0000000000000000000636C6B737763000064 +:1055C00000030000000000000001000000000101D5 +:1055D000030000001328310104070400010000004B +:1055E000000000003948000825480008614800080C +:1055F0004D4800085948000845480008314800084F +:105600001D4800086D480008633000000856000877 +:1056100000670020106900206D61696E0069646C8C +:1056200065000000A000802A00000000AAAAAAAA23 +:1056300050000024FFFF00000077000000900900E8 +:105640000400005A00000000AAAAAA9A0400000060 +:10565000FFBF0000000000000000990000111014BE +:1056600000000000AAAAAAA600010010FFDF0000A7 +:10567000000000000000000000000000000000002A +:10568000AAAAAAAA00000000FFFF00000000000074 +:10569000000000000000000000000000AAAAAAAA62 +:1056A00000000000FFFF00000000000000000000FC +:1056B0000000000000000000AAAAAAAA0000000042 +:1056C000FFFF0000000000000000000000000000DC +:1056D00000000000AAAAAAAA00000000FFFF000024 +:1056E00000000000000000001D0400000000000099 +:1056F0000070070000000000FE2A0100D204000034 +:10570000FF0000003864002000000000F45400088E +:10571000006889096D8BB90200B4C4040068890966 +:105720000068890900688909006889090068890991 +:1057300000688909000000005423002000000000D8 +:105740000000000000000000000000000000000059 +:105750000000000000000000000000000000000049 +:105760000000000000000000000000000000000039 :105770000000000000000000000000000000000029 -:1057800000000000814600086D460008A946000898 -:1057900095460008A14600088D4600087946000895 -:1057A00065460008B546000863300000A8570008A9 -:1057B000B8660020C86800206D61696E0069646C7D -:1057C00065000000A000802A00000000AAAAAAAA82 -:1057D00050000024FFFF0000007700000090090047 -:1057E0000400005A00000000AAAAAA9A04000000BF -:1057F000FFBF00000000000000009900001110141D -:1058000000000000AAAAAAA600010010FFDF000005 -:105810000000000000000000000000000000000088 -:10582000AAAAAAAA00000000FFFF000000000000D2 -:10583000000000000000000000000000AAAAAAAAC0 -:1058400000000000FFFF000000000000000000005A -:105850000000000000000000AAAAAAAA00000000A0 -:10586000FFFF00000000000000000000000000003A -:1058700000000000AAAAAAAA00000000FFFF000082 -:10588000000000000000000098A9FF7F0100000058 -:105890001D04000000000000007007000000000070 -:1058A000FE2A0100D2040000FF000000F063002087 -:1058B00000000000DC5600082C230020000000003F -:1058C00000000000000000000000000000000000D8 -:1058D00000000000000000000000000000000000C8 -:1058E00000000000000000000000000000000000B8 -:1058F00000000000000000000000000000000000A8 -:105900000000000000000000000000000000000097 -:0C5910000000000000000000000000008B +:105780000000000000000000000000000000000019 +:0C5790000000000000000000000000000D :00000001FF diff --git a/Tools/bootloaders/HolybroGPS_bl.bin b/Tools/bootloaders/HolybroGPS_bl.bin index 1d0c994218074a..f21faf1163a736 100755 Binary files a/Tools/bootloaders/HolybroGPS_bl.bin and b/Tools/bootloaders/HolybroGPS_bl.bin differ diff --git a/Tools/bootloaders/HolybroGPS_bl.elf b/Tools/bootloaders/HolybroGPS_bl.elf index 6a549f4e5e58c6..f825cb5e4c7fa2 100755 Binary files a/Tools/bootloaders/HolybroGPS_bl.elf and b/Tools/bootloaders/HolybroGPS_bl.elf differ diff --git a/Tools/bootloaders/HolybroGPS_bl.hex b/Tools/bootloaders/HolybroGPS_bl.hex index faba48087fa096..e88d878c8e8565 100644 --- a/Tools/bootloaders/HolybroGPS_bl.hex +++ b/Tools/bootloaders/HolybroGPS_bl.hex @@ -1,1443 +1,1392 @@ :020000040800F2 -:1000000000070020F5040008912F0008492F000880 -:10001000712F0008492F0008692F0008F704000815 -:10002000F7040008F7040008F7040008853F0008FB -:10003000F7040008F7040008F7040008F7040008B4 -:10004000F7040008F7040008F7040008F7040008A4 -:10005000F7040008F704000831530008595300085A -:1000600081530008A9530008D1530008F704000881 -:10007000F7040008F7040008F7040008F704000874 -:10008000F7040008F7040008F7040008D92E000858 -:10009000E92E0008FD2E0008F7040008F9530008B7 -:1000A000F7040008F7040008F7040008F704000844 -:1000B000E1540008F7040008F7040008F7040008FA -:1000C000F7040008F7040008F7040008F704000824 -:1000D000F7040008F7040008CD540008F7040008EE -:1000E0005D540008F7040008F7040008F70400084E -:1000F000F7040008F7040008F7040008F7040008F4 -:10010000F7040008F7040008F7040008F7040008E3 -:10011000F7040008F7040008F7040008F7040008D3 -:10012000F7040008F7040008F7040008F7040008C3 -:10013000F7040008F7040008F7040008112F00086E -:10014000212F0008352F0008F7040008F7040008E5 -:10015000F7040008F7040008F7040008F704000893 -:10016000F7040008F7040008F7040008F704000883 -:10017000F7040008F7040008F7040008F704000873 -:10018000F7040008F7040008F7040008F704000863 -:10019000F7040008F7040008F7040008F704000853 -:1001A000F7040008F7040008F7040008F704000843 -:1001B000F7040008F7040008F7040008F704000833 -:1001C000F7040008F7040008F7040008F704000823 -:1001D000F7040008F7040008F7040008F704000813 -:1001E000A51800080000000000000000000000004A -:1001F00053B94AB9002908BF00281CBF4FF0FF318E -:100200004FF0FF3000F074B9ADF1080C6DE904CE89 -:1002100000F006F8DDF804E0DDE9022304B07047E1 -:100220002DE9F047089D04468E46002B4DD18A42A9 -:10023000944669D9B2FA82F252B101FA02F3C2F1DC -:10024000200120FA01F10CFA02FC41EA030E94406D -:100250004FEA1C48210CBEFBF8F61FFA8CF708FB8E -:1002600016E341EA034306FB07F199420AD91CEB66 -:10027000030306F1FF3080F01F81994240F21C8198 -:10028000023E63445B1AA4B2B3FBF8F008FB1033E0 -:1002900044EA034400FB07F7A7420AD91CEB040415 -:1002A00000F1FF3380F00A81A74240F207816444E5 -:1002B000023840EA0640E41B00261DB1D44000236A -:1002C000C5E900433146BDE8F0878B4209D9002DCE -:1002D00000F0EF800026C5E9000130463146BDE858 -:1002E000F087B3FA83F6002E4AD18B4202D38242C2 -:1002F00000F2F980841A61EB030301209E46002D71 -:10030000E0D0C5E9004EDDE702B9FFDEB2FA82F2C5 -:10031000002A40F09280A1EB0C014FEA1C471FFA23 -:100320008CFE0126200CB1FBF7F307FB131140EA0A -:1003300001410EFB03F0884208D91CEB010103F1D7 -:10034000FF3802D2884200F2CB804346091AA4B299 -:10035000B1FBF7F007FB101144EA01440EFB00FE6D -:10036000A64508D91CEB040400F1FF3102D2A645D2 -:1003700000F2BB800846A4EB0E0440EA03409CE771 -:10038000C6F12007B34022FA07FC4CEA030C20FA1E -:1003900007F401FA06F31C43F9404FEA1C4900FA3E -:1003A00006F3B1FBF9F8200C1FFA8CFE09FB1811BB -:1003B00040EA014108FB0EF0884202FA06F20BD92E -:1003C0001CEB010108F1FF3A80F08880884240F27E -:1003D0008580A8F102086144091AA4B2B1FBF9F0C2 -:1003E00009FB101144EA014100FB0EFE8E4508D9BD -:1003F0001CEB010100F1FF346CD28E456AD9023842 -:10040000614440EA0840A0FB0294A1EB0E01A14226 -:10041000C846A64656D353D05DB1B3EB080261EB94 -:100420000E0101FA07F722FA06F3F1401F43C5E96E -:10043000007100263146BDE8F087C2F12003D840A4 -:100440000CFA02FC21FA03F3914001434FEA1C47E6 -:100450001FFA8CFEB3FBF7F007FB10360B0C43EAD8 -:10046000064300FB0EF69E4204FA02F408D91CEB88 -:10047000030300F1FF382FD29E422DD90238634486 -:100480009B1B89B2B3FBF7F607FB163341EA034126 -:1004900006FB0EF38B4208D91CEB010106F1FF3875 -:1004A00016D28B4214D9023E6144C91A46EA00466C -:1004B00038E72E46284605E70646E3E61846F8E6FE -:1004C0004B45A9D2B9EB020864EB0C0E0138A3E747 -:1004D0004646EAE7204694E74046D1E7D0467BE728 -:1004E000023B614432E7304609E76444023842E7A0 -:1004F000704700BF02E000F000F8FEE772B6374830 -:1005000080F30888364880F3098836483649086001 -:1005100040F20000CCF200004EF63471CEF2000141 -:100520000860BFF34F8FBFF36F8F40F20000C0F23F -:10053000F0004EF68851CEF200010860BFF34F8FF5 -:10054000BFF36F8F4FF00000E1EE100A4EF63C71E2 -:10055000CEF200010860062080F31488BFF36F8F8D -:1005600004F0F0FC04F082FD4FF055301F491B4AA7 -:1005700091423CBF41F8040BFAE71D49184A9142E9 -:100580003CBF41F8040BFAE71A491B4A1B4B9A423D -:100590003EBF51F8040B42F8040BF8E7002018495D -:1005A000184A91423CBF41F8040BFAE704F0CEFC34 -:1005B00004F0AAFD144C154DAC4203DA54F8041BA8 -:1005C0008847F9E700F042F8114C124DAC4203DACB -:1005D00054F8041B8847F9E704F0B6BC0007002074 -:1005E000002300200000000808ED00E000010020CA -:1005F00000070020805900080023002088230020E5 -:1006000088230020C8610020E0010008E401000800 -:10061000E4010008E40100082DE9F04F2DED108AF7 -:10062000C1F80CD0C3689D46BDEC108ABDE8F08FC0 -:10063000002383F311882846A047002004F0F4F833 -:10064000FEE704F057F800DFFEE70000F8B501F020 -:100650003FF904F011FC074604F060FC0546B8BB06 -:10066000204B9F4234D001339F4234D01E4B27F0A1 -:10067000FF029A4232D1F8B200F020FF2E4642F239 -:10068000107400F021FF08B10024264601F002FD9D -:1006900020B1032000F07CF80024264635B1134B2E -:1006A0009F4203D004F032FC00242646002004F0D0 -:1006B000EDFB0EB100F082F801F0A0FA00F070FF3F -:1006C00001F064F9204600F0CDF800F077F8F9E782 -:1006D0002E460024D5E704460126D2E7064640F61A -:1006E000C414CEE7010007B0000008B0263A09B0F4 -:1006F00008B501F017F9A0F120035842584108BD90 -:1007000007B541F21203022101A8ADF8043001F04F -:1007100027F903B05DF804FB38B5302383F3118863 -:10072000174803680BB104F03DF9164A144800233A -:100730004FF47A7104F02CF9002383F31188124CE2 -:10074000236813B12368013B2360636813B16368B6 -:10075000013B63600D4D2B7833B963687BB9022090 -:1007600001F0DAF9322363602B78032B07D1636839 -:100770002BB9022001F0D0F94FF47A73636038BDD1 -:100780008823002019070008A8240020A0230020A7 -:10079000084B187003280CD8DFE800F008050208A1 -:1007A000022001F0AFB9022001F0A2B9024B0022F1 -:1007B0005A607047A0230020A824002010B501F043 -:1007C00069FC30B1204B03221A70204B00225A6082 -:1007D00010BD1F4B1F4A1C4619680131F8D0043365 -:1007E0009342F9D162681C4B9A42F1D91B4B9B682A -:1007F00003F1006303F580339A42E9D204F05AFB17 -:1008000004F06CFB002001F0DBF80220FFF7C0FFD2 -:10081000134B1A6C00221A64196E1A66196E596C01 -:100820005A64596E5A665B6E72B64FF0E0233021FF -:10083000C3F8084DD4E9003281F311889D4683F353 -:1008400008881047C4E700BFA0230020A824002088 -:100850000000010820000108FFFF0008002300201D -:10086000003802402DE9F04F93B0AC4B00902022AD -:10087000FF210AA89D6801F06BF9A94A1378A3B972 -:10088000A848012103601170302383F311880368A5 -:100890000BB104F087F8A44AA24800234FF47A7100 -:1008A00004F076F8002383F31188009B13B19F4B6B -:1008B000009A1A609E4A009C1378032B1EBF0023E7 -:1008C00013709A4A4FF0000A18BF5360D346564639 -:1008D000D146012001F016F924B1944B1B68002B7E -:1008E00000F01582002001F01DF80390039B002BFF -:1008F00001DA00F0A7FE039B002BEDDB012001F0E5 -:10090000F7F8039B213B162BE3D801A252F823F002 -:100910006D09000895090008290A0008D308000895 -:10092000D3080008D3080008B30A0008830C0008A5 -:100930009D0B0008FF0B0008270C00084D0C000859 -:10094000D30800085F0C0008D3080008D10C000889 -:100950000D0A0008D3080008150D000879090008E1 -:100960000D0A0008D3080008FF0B00080220FFF75B -:10097000BFFE002840F0F581009B0221BAF1000F74 -:1009800008BF1C4605A841F21233ADF8143000F040 -:10099000E7FF9EE74FF47A7000F0C4FF071EEBDB21 -:1009A0000220FFF7A5FE0028E6D0013F052F00F248 -:1009B000DA81DFE807F0030A0D10133605230593EB -:1009C000042105A800F0CCFF17E054480421F9E702 -:1009D00058480421F6E758480421F3E74FF01C0873 -:1009E000404600F0EFFF08F104080590042105A837 -:1009F00000F0B6FFB8F12C0FF2D1012000FA07F792 -:100A000047EA0B0B5FFA8BFB4FF0000901F0ECF8A3 -:100A100026B10BF00B030B2B08BF0024FFF770FE71 -:100A200057E746480421CDE7002EA5D00BF00B0375 -:100A30000B2BA1D10220FFF75BFE074600289BD0BD -:100A4000012000F0BDFF0220FFF7A2FE00261FFAE2 -:100A500086F8404600F0C4FF044690B100214046AD -:100A600000F0D6FF01360028F1D1BA46044641F223 -:100A70001213022105A8ADF814303E4600F070FFB5 -:100A800027E70120FFF784FE2546244B9B68AB42F5 -:100A900007D9284600F096FF013040F06781043501 -:100AA000F3E7234B00251D70204BBA465D603E46A0 -:100AB000ACE7002E3FF460AF0BF00B030B2B7FF481 -:100AC0005BAF0220FFF764FE322000F02BFFB0F195 -:100AD0000008FFF651AF18F003077FF44DAF0F4A3F -:100AE000926808EB050393423FF646AFB8F5807F66 -:100AF0003FF742AF124B0193B84523DD4FF47A70B4 -:100B000000F010FF0390039A002AFFF635AF019B17 -:100B1000039A03F8012B0137EDE700BF0023002003 -:100B2000A42400208823002019070008A8240020FE -:100B3000A023002004230020082300200C230020F1 -:100B4000A4230020C820FFF7D3FD074600283FF468 -:100B500013AF1F2D11D8C5F1200242450AAB25F075 -:100B6000030028BF424683490192184400F0DEFF8B -:100B7000019A8048FF2100F0EBFF4FEAA8037D496E -:100B80000193C8F38702284600F0EAFF06460028D2 -:100B90003FF46DAF019B05EB830537E70220FFF7BC -:100BA000A7FD00283FF4E8AE00F052FF00283FF414 -:100BB000E3AE0027B846704B9B68BB4218D91F2F85 -:100BC00011D80A9B01330ED027F0030312AA134455 -:100BD00053F8203C05934046042205A901F012FA7F -:100BE00004378046E7E7384600F0ECFE0590F2E770 -:100BF000CDF81480042105A800F0B2FE06E700231A -:100C0000642104A8049300F0A1FE00287FF4B4AE90 -:100C10000220FFF76DFD00283FF4AEAE049800F00F -:100C2000FFFE0590E6E70023642104A8049300F08A -:100C30008DFE00287FF4A0AE0220FFF759FD0028AA -:100C40003FF49AAE049800F0FBFEEAE70220FFF7BB -:100C50004FFD00283FF490AE00F00AFFE1E70220CC -:100C6000FFF746FD00283FF487AE05A9142000F0E9 -:100C700005FF04210746049004A800F071FE3946E0 -:100C8000B9E7322000F04EFE071EFFF675AEBB0737 -:100C90007FF472AE384A926807EB090393423FF63D -:100CA0006BAE0220FFF724FD00283FF465AE27F06D -:100CB00003074F44B9453FF4A9AE484600F082FE11 -:100CC0000421059005A800F04BFE09F10409F1E7A5 -:100CD0004FF47A70FFF70CFD00283FF44DAE00F0A2 -:100CE000B7FE002844D00A9B01330BD008220AA982 -:100CF000002000F035FF00283AD02022FF210AA86A -:100D000000F026FFFFF7FCFC1C4803F093FD13B036 -:100D1000BDE8F08F002E3FF42FAE0BF00B030B2B32 -:100D20007FF42AAE0023642105A8059300F00EFE8F -:100D3000074600287FF420AE0220FFF7D9FC80464A -:100D400000283FF419AEFFF7DBFC41F2883003F0D6 -:100D500071FD059800F05EFF464600F045FF3C46F9 -:100D6000B7E5064652E64FF0000905E6BA467EE6CC -:100D700037467CE6A423002000230020A086010043 -:100D8000094A136849F2690099B21B0C00FB013350 -:100D90001360064B186844F2506182B2000C01FBEC -:100DA0000200186080B2704718230020142300202E -:100DB00010B500211022044600F0CAFE034B03CBFD -:100DC000206061601868A06010BD00BF107AFF1F2E -:100DD0002DE9F041ADF54E7D0DF134086CAC40F2DB -:100DE000751207460D460EA80021C8F8001000F045 -:100DF000AFFE4FF4C4720021204600F0A9FE02F0BD -:100E0000CFF8254B4FF47A72B0FBF2F0186093E8FC -:100E10000700022384E807000DF5E9702382FFF73D -:100E2000C7FF40F604331D49238406A804F06AFC7A -:100E3000182384F832310DF2E3266B440DF1300CA7 -:100E40001A4603CA624530607160134606F108060F -:100E5000F6D141460122204600F0F6FE002303931E -:100E6000AB7E029305F11903019380B20123CDE912 -:100E700004800093E97E06A3D3E90023384602F0FC -:100E800057FC0DF54E7DBDE8F08100BFAFF300804B -:100E90009E6AC421818A46EEB024002014570008BF -:100EA0002DE9F0412C4C237ADAB080460D465BBB2D -:100EB00027A9284600F0D8FF0746002842D19DF810 -:100EC0009D60C82E3ED801464FF4A662204600F031 -:100ED0003FFE4FF48073C4F8F8314FF40073C4F848 -:100EE0000C334FF44073C4F8203432460DF19E01A8 -:100EF00004F1090000F01AFE26449DF89C30777238 -:100F000023720BB9EB7E23728122002106AC27A845 -:100F100000F01EFE0122214627A800F0E1FF002379 -:100F20000393AB7E029305F1190380B2019328234A -:100F3000CDE904400093E97E05A3D3E900234046B0 -:100F400002F0F6FB5AB0BDE8F08100BFAFF30080BD -:100F500026417272DF25D7B798560020F0B5254E8E -:100F60004FF48A7505FB0065F1B096F8D83085F826 -:100F7000DC300024D822214685F8E8403AA800F069 -:100F8000E7FD06F1090000F0DBFDD5F8E4308DF84F -:100F9000F000C2B206AF06F109010DF1F100CDE992 -:100FA0003A3400F0C3FD394601223AA800F0C4FFEC -:100FB00080B2CDE9047008230127CDE9023706F19C -:100FC000D803019330230093317A0B4807A3D3E968 -:100FD000002302F0ADFBA04206DD01F0E1FFC5F801 -:100FE000E000384671B0F0BD2046FBE778F6339F4D -:100FF00093CACD8D98560020C83400202DE9F04FBB -:10100000274FDFF8A880274E87B0384602F0BCFB98 -:10101000034600283DD00024CDE90344ADF8144038 -:10102000027B8DF8142099684068029403AA03C2D9 -:101030001B681D4D43F000430293A146A2462B6856 -:10104000D3F810B001F0AEFF10EB080241F100033D -:101050002846CDF800A002A9D84704F2344440F64F -:1010600068030028C8BF49F0010905F586559C4270 -:1010700005F11005E3D1B9F1000F05D0384602F0B3 -:1010800087FB86F800A0C0E73378072B04D801332C -:10109000337007B0BDE8F08F014802F079FBF8E744 -:1010A000C8340020CD5B0020F834002040420F00FF -:1010B00070B50D4614461E4602F096FA50B9022E3F -:1010C00010D1012C0ED112A3D3E90023C5E90023CE -:1010D000012007E0282C10D005D8012C09D0052CC0 -:1010E0000FD0002070BD302CFBD10BA3D3E900231F -:1010F000ECE70BA3D3E90023E8E70BA3D3E9002334 -:10110000E4E70BA3D3E90023E0E700BFAFF30080DF -:10111000401DA12026812A0B78F6339F93CACD8DDE -:101120009E6AC421818A46EE26417272DF25D7B7B6 -:10113000F017304A39059E5638B505460E4C002149 -:10114000013500F065FCA4F82C55B4F82C0500F02E -:1011500047FC78B1B4F82C0500F052FC014648B9C0 -:10116000B4F82C0500F054FCB4F82C350133A4F885 -:101170002C35EAE738BD00BF98560020F8B50E4C74 -:101180000E4F0226A4F5805343F8487C237E3BB9DA -:1011900065692DB1284600F0FBFF284604F0F2F9FE -:1011A000204600F0F5FFA4F58654012EA4F11004AA -:1011B00000D1F8BD0126E5E710560020DC570008F5 -:1011C0002DE9F04F8FB000AF05460C4602F00CFA47 -:1011D000002849D1237E022B1BD1E38A012B18D191 -:1011E00001F0DEFE0646FFF7CBFD03464FF4C87064 -:1011F000DFF8C482B3FBF0F206F5167602FB10337B -:1012000016FA83F3C8F80030E37E33B9A34B00220B -:101210001A703C37BD46BDE8F08F07F12401204627 -:1012200000F0E0FD0028F4D107F11400FFF7C0FD45 -:1012300097F8264007F11401224607F1270004F031 -:10124000EBF90028E2D10F2C08D8944B1C70D8F889 -:101250000030A3F51673C8F80030DAE797F82410C9 -:10126000284602F0B9F9D4E7E38A282B2BD010D80E -:10127000012B23D0052BCCD1BFF34F8F8849894B4D -:10128000CA6802F4E0621343CB60BFF34F8F00BF24 -:10129000FDE7302BBDD1844EE17E327A9142B8D148 -:1012A000607E3146002291F8DC50854200F0A58036 -:1012B0000132042A01F58A71F5D1AAE721462846B0 -:1012C000FFF786FDA5E721462846FFF7E9FDA0E7E1 -:1012D000B2F8EC507B6005F103094FEA99094FEA37 -:1012E0008902D11DC908A8EBC1039D46EB46002128 -:1012F000584600F02DFC04F1EE012A4631445846D0 -:1013000000F014FC7B6813B9012000F059FB96F83B -:10131000D20000F065FB044630B9307200F098FB53 -:10132000204600F04DFBB1E0D6F8D4203AB996F84B -:10133000D200B6F82C25824201D8FFF7FDFED6F880 -:10134000D4202A44944208D296F8D200B6F82C252C -:101350000130824201D8FFF7EFFE70685FFA89F230 -:10136000594600F0FDFB08B9C54679E0726896F869 -:10137000D2002A447260D6F8D42005EB0209C6F8E0 -:10138000D49000F02DFB814509D396F8D220D6F8F1 -:10139000D4000132001B86F8D220C6F8D400FF2DFD -:1013A0000FD80024347200F053FB204600F008FBF5 -:1013B00000F070FE3D4B188108B9FFF7FFF9C546F4 -:1013C00027E7BB6896F8D9000AFB0362FB68D2F8EE -:1013D000E41082F8E83001F58061C2F8E030C2F82C -:1013E000E410FFF7BBFDFFF709FE96F8D9200132A4 -:1013F00002F0030286F8D920B6E74FF48A7A0AFB96 -:1014000002F505F1EA013144204600F0C1FDF86023 -:1014100000287FF4FEAE3544012285F8E82001F073 -:10142000BFFDD5F8E020D6ED007ADFED216A801A05 -:10143000192838BF192040F6B832904228BF10460C -:10144000B8EE677A07EE900AF8EEE77A67EEA67ACA -:10145000DFED186AE7EE267AFCEEE77AC6ED007A51 -:1014600096F8D930BB60BA6873680AFB02F4321987 -:1014700092F8E81059B1D2F8E4108B42E8463FF4F4 -:1014800027AF002182F8E810C2F8E010C546736863 -:10149000064A9B0A01331381BBE600BFC13400201A -:1014A00000ED00E00400FA0598560020B02400206A -:1014B000CDCCCC3D6666663FC4340020014B18702D -:1014C000704700BFBC24002030B54FF000542B4BB8 -:1014D00022689A4285B007D003F02AFD044620BB5B -:1014E0000024204605B030BD254B627D25481A708A -:1014F000237D03724FF48073C0F8F8314FF400730A -:10150000C0F80C3300254FF44073C0F820341E4956 -:10151000C0F8E450C922093000F008FB2046E02260 -:10152000294600F015FB0124DBE7184A184D136C1F -:1015300043F000731364AA6D164B9A42D0D12B6E00 -:10154000013B7E2BCCD8144A07CA01AB83E80700C5 -:101550001846032100F06CFD6B6D83424FF00003D1 -:10156000BED12A6D8A4201BFAB65054B2A6E1A7047 -:1015700003BF0A4BEA6D1A601C46B2E79AAD44C538 -:10158000BC2400209856002016000020003802409D -:10159000006600405041A0B0586600401023002073 -:1015A00037B500F077FD1D4D1D4C288102232168C1 -:1015B0001C486B71012201F077FB1B48216850F831 -:1015C000D03F01225B68984700230193174B1849CD -:1015D00000931848184B4FF4805201F0D5FF174B79 -:1015E000197811B1134801F0F7FF01F0D9FC044656 -:1015F000FFF7C6FB4FF4C873B0FBF3F202FB130313 -:1016000004F5167010FA83F00D4B186003F086FC99 -:1016100008B10F232B8103B030BD00BFB0240020E0 -:1016200010230020F8340020F8440020B1100008F6 -:10163000C0240020C8340020C1110008BC240020B0 -:10164000C43400202DE9F04F2DED028BDFF85082DD -:1016500093B00BAF9FED838BFFF7D0FC00230A9371 -:10166000ADF834300B937B600025844CDFF810A27A -:101670002E4601238DF81C3023688DED008B4FF032 -:10168000000BD3F808908DF81DB05B460DF11D02DC -:1016900007A92046C8479DF81C90B9F1000F24D037 -:1016A000D8F8143083F40043C8F814301022594697 -:1016B0000EA800F04DFA236808AA5E690AA90DF188 -:1016C0001E032046B04797E803000FAB83E80300F2 -:1016D0009DF834308DF844300A9B0E930EA9DDE955 -:1016E0000823504602F032FA4E4605F2344540F6E1 -:1016F000680304F586549D4204F11004B9D1002E0C -:10170000B2D15F4801F070FF002840D15D4D01F07B -:1017100047FC2B6898423AD301F042FC0446FFF79D -:101720002FFB4FF4C873B0FBF3F202FB130304F575 -:10173000167010FA83F02860534D8DF828602E78CB -:1017400016B901238DF82830C6F11004E4B20EA8B2 -:10175000FFF72EFB062C28BF06240EAB2246991954 -:101760000DF1290000F0E2F90AAB0393182302936C -:101770000134464B0193E4B20123009340480494A2 -:101780003AA3D3E9002301F075FF00232B7001F089 -:1017900007FC3F4A3F4C1368C31AB3F57A7F2FD337 -:1017A000106001F0FFFB02460B46354801F0FAFFDE -:1017B000334801F019FF18B3237A374D002B14BFBB -:1017C000032302236B7101F0EBFB0EAE4FF47A732F -:1017D0000122B0FBF3F031462860284600F0DAFA27 -:1017E000182302932D4B019380B240F25513CDE99B -:1017F0000360009322481FA3D3E9002301F03AFFBE -:10180000237A93B101F0CCFB002506464FF48A778A -:1018100094F8D900284400F0030007FB004393F834 -:10182000E82072B10135042DF2D1C82003F002F88E -:10183000237A002B7FF40DAF13B0BDEC028BBDE813 -:10184000F08FD3F8E02042B12368FA2B38BFFA2397 -:10185000B21A0533B2EB430FE4D3FFF77FFB002846 -:10186000E0D1E2E70000000000000000401DA120E0 -:1018700026812A0BF1C6A7C1D068080FF8340020D2 -:10188000C8340020C4340020C1340020C0340020FB -:10189000C85B002098560020B0240020CC5B0020BC -:1018A0000004024008B5064800F074FF054800F047 -:1018B00071FFBDE80840044A0449002003F05CBE03 -:1018C000F8340020C8450020205C00207D1100086D -:1018D0007047000070B5104B1B780133DBB2012B51 -:1018E0000C4612D80D4B1D6829684FF47A730E6AA6 -:1018F000A2FB0332014622462846B047844204D167 -:10190000074B00221A70012070BD4FF4FA7002F0EC -:1019100091FF0020F8E700BF1C23002020230020B7 -:10192000105C002007B50023024601210DF10700DD -:101930008DF80730FFF7CEFF20B19DF8070003B008 -:101940005DF804FB4FF0FF30F9E700000A4608B5E8 -:101950000421FFF7BFFF80F00100C0B2404208BD84 -:1019600030B4074B0A461978064B53F821402368D8 -:10197000DD69054B0146AC46204630BC604700BFE0 -:10198000105C002020230020A086010070B503F029 -:1019900015F9094E094D30800024286833888342A8 -:1019A00008D903F005F92B6804440133B4F5803FEE -:1019B0002B60F2D370BD00BF125C0020D05B002012 -:1019C00003F0ACB900F1006000F5803000687047AA -:1019D00000F10060920000F5803003F035B900009E -:1019E000054B1A68054B1B889B1A834202D9104489 -:1019F00003F0DEB800207047D05B0020125C0020AE -:101A0000024B1B68184403F0DBB800BFD05B00201A -:101A1000024B1B68184403F0EBB800BFD05B0020FA -:101A200010F003030AD1B0F5047F05D200F1005095 -:101A3000A0F51040D0F80038184670470023FBE7A7 -:101A400000F10050A0F51040D0F8100A70470000D7 -:101A5000064991F8243033B10023086A81F8243014 -:101A60000822FFF7B5BF0120704700BFD45B0020FC -:101A7000014B1868704700BF002004E070B5194B97 -:101A80001D68194B0138C5F30B0408442D0C0422C2 -:101A90001E88A6420BD15C680A46013C824213466E -:101AA0000FD214F9016F4EB102F8016BF6E7013A5B -:101AB00003F10803ECD181420B4602D22C2203F839 -:101AC000012B0A4A05241688AE4204D1984284BFED -:101AD000967803F8016B013C02F10402F3D1581A25 -:101AE00070BD00BF002004E0705700085C5700087C -:101AF000022802BF024B4FF000429A61704700BFBC -:101B000000040240022802BF024B4FF400429A61D7 -:101B1000704700BF00040240022801BF024A536917 -:101B200083F40043536170470004024010B5002362 -:101B3000934203D0CC5CC4540133F9E710BD0000DC -:101B400003460246D01A12F9011B0029FAD1704748 -:101B500002440346934202D003F8011BFAE77047A0 -:101B60002DE9F8431F4D144695F824200746884672 -:101B700052BBDFF870909CB395F824302BB920222B -:101B8000FF2148462F62FFF7E3FF95F82400C0F1DC -:101B90000802A24228BF2246D6B24146920005EB77 -:101BA0008000FFF7C3FF95F82430A41B1E44F6B253 -:101BB000082E17449044E4B285F82460DBD1FFF787 -:101BC00047FF0028D7D108E02B6A03EB820383424A -:101BD000CFD0FFF73DFF0028CBD10020BDE8F88330 -:101BE0000120FBE7D45B0020024B1A78024B1A70ED -:101BF000704700BF105C00201C23002003494FF4F5 -:101C000061430B60024B186802F0DABCFC5B0020F9 -:101C100020230020094B10B5142204460021184649 -:101C2000FFF796FF064A074B127804600146BDE8AD -:101C3000104053F8220002F0C3BC00BFFC5B002040 -:101C4000105C0020202300202DE9F0470D460446BB -:101C500000219046284640F27912FFF779FF23468B -:101C600020220021284601F013FF231D02222021FB -:101C7000284601F00DFF631D03222221284601F0B2 -:101C800007FFA31D03222521284601F001FF04F1CF -:101C9000080310222821284601F0FAFE04F110035F -:101CA00008223821284601F0F3FE04F1110308222E -:101CB0004021284601F0ECFE04F1120308224821DD -:101CC000284601F0E5FE04F11403202250212846A5 -:101CD00001F0DEFE04F1180340227021284601F0D5 -:101CE000D7FE04F120030822B021284601F0D0FEDF -:101CF00004F121030822B821284601F0C9FE04F1AD -:101D00002207C0263B46314608222846083601F005 -:101D1000BFFEB6F5A07F07F10107F3D104F132034E -:101D200008223146284601F0B3FE002704F1330AA9 -:101D300094F832304FEAC7099F4209F5A47615D3CB -:101D4000B8F1000F08D1314604F5997307222846EF -:101D500001F09EFE09F24F16274694F832213B1BF4 -:101D600093420CD3F01DC008BDE8F0870AEB0703CF -:101D700008223146284601F08BFE0137D8E707F2EA -:101D8000331331460822284601F082FE0836013717 -:101D9000E3E7000013B5044608460021016023462E -:101DA000C0F803102022019001F072FE0198231D5B -:101DB0000222202101F06CFE0198631D03222221E2 -:101DC00001F066FE0198A31D0322252101F060FEAB -:101DD000019804F108031022282101F059FE072080 -:101DE00002B010BDF7B50023047F00910E46072214 -:101DF0001946054601F010FD731C009301220023D3 -:101E00000721284601F008FDC4B9B31C0093052240 -:101E100023460821284601F0FFFC0D243746B278FE -:101E2000BB1B934211D32B7FA88A0734E408BBB9AC -:101E3000844294BF0020012003B0F0BDAB8ADB00D8 -:101E4000083BDB08B3700824E8E7FB1C009321463D -:101E500000230822284601F0DFFC08340137DEE7C2 -:101E6000201A18BF0120E7E7F7B50023047F00918F -:101E70000E4608221946054601F0CEFC731CC4B973 -:101E80000822009311462346284601F0C5FC102481 -:101E9000012372785F1C013B934211D32B7FA88AE8 -:101EA0000734E408BBB9844294BF0020012003B08A -:101EB000F0BDAB8ADB00083BDB0873700824E7E762 -:101EC000F3190093214600230822284601F0A4FCC0 -:101ED00008343B46DDE7201A18BF0120E7E7000081 -:101EE000F8B50E4605461446002181223046FFF71C -:101EF0002FFE2B4608220021304601F0C9FD7CB997 -:101F00006B1C07220821304601F0C2FD0F2401237B -:101F10006A785F1C013B934204D3E01DC008F8BD02 -:101F20000824F4E7EB1921460822304601F0B0FD01 -:101F300008343B46ECE70000F8B50E46054614466B -:101F40000021CE223046FFF703FE2B462822002137 -:101F5000304601F09DFD7CB905F1080308222821D7 -:101F6000304601F095FD30242F462A7A7B1B9342A0 -:101F700004D3E01DC008F8BD2824F5E707F10903E4 -:101F800021460822304601F083FD08340137ECE792 -:101F9000F7B5047F00910E4601231022002105466B -:101FA00001F03AFCC4B9B31C009309222346102166 -:101FB000284601F031FC192437467288BB1B9A422F -:101FC00011D82B7FA88A0734E408BBB9844294BF98 -:101FD0000020012003B0F0BDAB8ADB00103BDB0822 -:101FE00073801024E8E73B1D00932146002308225C -:101FF000284601F011FC08340137DEE7201A18BF2B -:102000000120E7E730B5094D0A4491420DD011F89F -:10201000013B5840082340F30004013B2C4013F0DF -:10202000FF0384EA5000F6D1EFE730BD2083B8ED1E -:10203000F7B54FF0FF33DFF854C0DFF854E000EBA2 -:1020400081011A4688421CD050F8044B019401AF1C -:10205000042417F8015B82EA05620825DB1816469E -:1020600005F1FF355241002EBCBF83EA0C0382EA22 -:102070000E0215F0FF05F1D1013C14F0FF04E8D188 -:10208000E0E7D843D14303B0F0BD00BF9336EAA9DF -:10209000EBE1F042F7B5384A106851686B4603C36C -:1020A0006A4636493648082303F0C6FA0446002833 -:1020B00033D10A25334A106851686B4603C36A4618 -:1020C00031492F48082303F0B7FA0446002849D0C5 -:1020D0000369B3F5E02F45D8B0F8661040F20B4223 -:1020E00091423FD1294A024402F15C018B4239D32B -:1020F0005C3B234900209E1AFFF784FF32460746C7 -:1021000004F164010020FFF77DFFA3689F4229D1FD -:10211000E368984208BF002524E00369B3F5E02F87 -:1021200027D8418B40F20B42914220D1174A0244FA -:1021300002F110018B4218D3103B114900209D1A67 -:10214000FFF760FF2A46064604F118010020FFF75A -:1021500059FFA3689E4202D1E368984201D00D2541 -:10216000A8E70025284603B0F0BD1025A2E70C25FE -:10217000A0E70B259EE700BF90570008DCFF060094 -:10218000000001089957000890FF06000800FFF7BB -:1021900010B5037C044613B9006803F035FA2046F5 -:1021A00010BD00000023BFF35B8FC360BFF35B8FE4 -:1021B000BFF35B8F8360BFF35B8F7047BFF35B8FB1 -:1021C0000068BFF35B8F704770B505460C30FFF7B2 -:1021D000F5FF05F1080604463046FFF7EFFFA04281 -:1021E00006D930466D68FFF7E9FF2544281A70BD0F -:1021F0003046FFF7E3FF201AF9E7000070B5054607 -:10220000406898B105F10800FFF7D8FF05F10C060A -:1022100004463046FFF7D2FF8442304694BF6D68D3 -:102220000025FFF7CBFF013C2C44201A70BD0000B5 -:1022300038B50C460546FFF7C7FFA04210D305F19D -:102240000800FFF7BBFF04446868B4FBF0F100FB33 -:102250001144BFF35B8F0120AC60BFF35B8F38BDCF -:102260000020FCE72DE9F041144607460D46FFF734 -:10227000C5FF844228BF0446D4B1B84658F80C6B59 -:102280004046FFF79BFF3044286040467E68FFF7DA -:1022900095FF331A9C4203D86C600120BDE8F081A1 -:1022A0006B60A41B3B68AB602044E8600220F5E74C -:1022B0002046F3E738B50C460546FFF79FFFA042DE -:1022C00010D305F10C00FFF779FF04446868B4FBF4 -:1022D000F0F100FB1144BFF35B8F0120EC60BFF312 -:1022E0005B8F38BD0020FCE72DE9FF418846694639 -:1022F0000746FFF7B7FF6C4606B204EBC60600259B -:10230000B44209D06268206808EB0501FFF70EFCB3 -:10231000636808341D44F3E729463846FFF7CAFFCF -:10232000284604B0BDE8F081F8B505460C300F46EC -:10233000FFF744FF05F1080604463046FFF73EFF6D -:10234000A042304688BF6C68FFF738FF201A38601B -:1023500020B130462C68FFF731FF2044F8BD000063 -:1023600073B5144606460D46FFF72EFF844228BF7C -:1023700004460190DCB101A93046FFF7D5FF019B6F -:1023800033B93268C5E90233C5E9002401200CE005 -:102390009C4238BF01942860019868608442F5D956 -:1023A0003368AB60241AEC60022002B070BD204696 -:1023B000FBE700002DE9FF410F466946FFF7D0FF1C -:1023C0006C4600B204EBC0050026AC4209D0D4F83C -:1023D000048054F8081BB8194246FFF7A7FB46448F -:1023E000F3E7304604B0BDE8F081000038B505469B -:1023F000FFF7E0FF044601462846FFF719FF204695 -:1024000038BD0000302383F3118862B670470000A6 -:10241000002383F3118862B67047000010B402688D -:1024200054681A4623465DF8044B1847012070474C -:102430000020704700207047704700000020704760 -:102440000E20704700F5805090F8C800C0F340009F -:102450007047000000F5805090F9C90070470000F7 -:10246000F7B50C68BDF8207014F000541E466FD10B -:102470000B7B082B6CD8FFF7C5FF4569AB685B0188 -:102480000CD4AB681B0108D4AC6814F080545DD147 -:10249000FFF7BEFF204603B0F0BD01240B6804F136 -:1024A000180C002BB8BFDB004FEA0C1CB4BF43F084 -:1024B00004035B0545F80C300B680FFA84FC13F03D -:1024C000804F18BF05EB0C1E05EB0C1C1EBFDEF881 -:1024D000803143F00203CEF880310B7BCCF884319D -:1024E00005EB04158B68C5F88C314B68C5F888314D -:1024F000DCF8803143F00103CCF8803100EB441567 -:1025000041F268031D4403EB44130344C5E900266C -:1025100008330D4601F10C0C55F804EB43F804EBBD -:102520006545F9D184342D881D8000EB441407F0F3 -:102530000303257925F00B052B432371FFF768FF73 -:102540000097334600F04EFD0120A4E70224A5E7E2 -:102550004FF0FF309FE7000013B500F58054019164 -:10256000E06DFFF74BFE1F280AD90199E06D20228C -:10257000FFF7BAFEA0F120035842584102B010BD47 -:102580000020FBE708B500F58050FFF73BFFC06D6A -:10259000FFF708FEBDE80840FFF73ABF00220260DF -:1025A000828142608260704710B500220023C0E93A -:1025B00000230023044603810C30FFF7EFFF204681 -:1025C00010BD0000F0B5054600F580500C4690F8AF -:1025D000C83013F0040FC3F3800108BF114661F344 -:1025E000820304F1840680F8C83005EB461389B0F5 -:1025F0001B79D8072ED57AB319072DD46846FFF773 -:10260000D3FF05EB441303F5835303F1180703AA23 -:10261000103318685968144603C40833BB42224675 -:10262000F7D1186820609B88A380DDE90E23CDE9EF -:1026300000230123ADF808302B686946DB6B284680 -:10264000984705EB46152B791A075CBF43F0080342 -:102650002B7101E0002AF4D109B0F0BD2DE9F0475B -:10266000074688B007F5805468469A468846FFF7C3 -:10267000C9FE9146FFF798FFE06DFFF7A5FD1F2803 -:1026800029D9E06D20226946FFF7B0FE202822D12B -:1026900003AD444605AB2E4603CE9E4220606160EA -:1026A000354604F10804F6D130682060B388A38071 -:1026B000DDE90023C9E90023BDF80830AAF800309D -:1026C000FFF7A6FE4A4653464146384608B0BDE8E5 -:1026D000F04700F075BCFFF79BFE002008B0BDE896 -:1026E000F08700002DE9F84F0023C0E90133264BA5 -:1026F000044640F8183B0F46FFF750FF04F128004E -:10270000FFF752FF04F1480804F5825546460835A4 -:1027100030462036FFF748FFAE42F9D104F5805528 -:102720004FF480534FF00009C5E91339C5F84880CC -:102730000123EE6504F5875804F58456C5F85490D6 -:1027400085F8583085F86030083608F108084FF0F1 -:10275000000A4FF0000B46E908ABA6F11800FFF79E -:102760001DFF203646F8289C4645F4D1012F85F8F8 -:10277000C97002D9054800F00DFC054B53F827300D -:1027800063612046BDE8F88FDC570008A4570008B5 -:10279000C057000810B5044B197804464A1C1A703B -:1027A000FFF7A0FF204610BD1C5C00202DE9F0477C -:1027B000002950D0294B2A4FB7FBF1F599428CBF25 -:1027C0000A231123581EB5FBF3FC03FB1C53C4B2B0 -:1027D0002BB102280346F5D80020BDE8F0870CF1A4 -:1027E000FF36B6F5806FF7D2C4EBC40E0EF10303CB -:1027F0004FEAE309C3F3C703A4EB030809F1010A95 -:102800004FF47A755FFA88F009FB05555AFA88F893 -:10281000B5FBF8F5B5F5617FC1BF0EF1FF33C3F32A -:10282000C703E01AC0B25C1C50FA84F40CFB04F439 -:10283000B7FBF4F4A142CFD1013BDBB20F2BCBD8D5 -:102840000138C0B20728C7D80021107116809170D6 -:10285000D3700120C1E70846BFE700BF3F420F0029 -:1028600040787D0170B505460E464FF47A746B6969 -:102870005B6803F00103B34207D04FF47A7001F0B4 -:10288000D9FF013CF3D1204670BD0120FCE70000D8 -:1028900030B54269936913F0700F16D000230B4CCA -:1028A000936103F1840200EB421211794D0709D5BF -:1028B000890707D5416954F823508D60117941F09B -:1028C000040111710133032BEBD130BDC85700084F -:1028D00073B51D46436916469A68D207044609D562 -:1028E0009A6801219960C2F34002CDE90065002198 -:1028F000FFF768FE63699A68D1050BD59A684FF4B3 -:1029000080719960C2F34022CDE900650121204623 -:10291000FFF758FE63699A68D2030BD59A684FF4A3 -:1029200080319960C2F34042CDE900650221204622 -:10293000FFF748FE204602B0BDE87040FFF7A8BF91 -:102940000C4B10B51C561B5C012B11D800F02AFB58 -:1029500050EA0103024602D0421E61F10001064B1B -:1029600053F8240020B1BDE810400B46FFF7B0BF7C -:1029700010BD00BFBC570008145C0020F8B5044629 -:10298000466900296CD106F10C07386880076AD0C7 -:1029900006EB01153868D5F8B00110F0040FD5F832 -:1029A000B0011ABFC00840F00040400DA061D5F84A -:1029B000B0C11CF0020F1CBF40F08040A061D5F8F0 -:1029C000B40106EB011100F00F0084F82400D1F8E7 -:1029D000B8012077D1F8B801000A6077D1F8B801C2 -:1029E000000CA077D1F8B801000EE077D1F8BC0157 -:1029F00084F82000D1F8BC01000A84F82100D1F845 -:102A0000BC01000C84F82200D1F8BC11090E84F836 -:102A100023103821396004F1340004F1180104F165 -:102A2000240551F8046B40F8046BA942F9D10988D8 -:102A30000180C4E90A2321460023238651F8283B5C -:102A40002046DB6B984704F58052204692F8C83048 -:102A500043F0040382F8C830BDE8F840FFF718BF20 -:102A600006F1100791E7F8BD0D4B70B51D561B5CC4 -:102A7000012B0C4612D800F095FA02460B4652EA9A -:102A8000030102D0013A63F10003064951F8250021 -:102A900020B12146BDE87040FFF770BF70BD00BF98 -:102AA000BC570008145C0020F8B500F583511E46A1 -:102AB000FFF7A8FCDFF844C00831002404F18405C6 -:102AC00000EB45152B795F070ED4DB060CD5D1E959 -:102AD00000739742B34107D243695CF824709F604A -:102AE0002B7943F004032B710134032C01F12001F5 -:102AF000E4D1BDE8F840FFF78BBC00BFC857000821 -:102B000008B5FFF77FFCFFF7C3FEBDE80840FFF7FD -:102B10007FBC0000F8B543690546986800F0E050B6 -:102B2000B0F1E05F0F461FD0E8B1FFF76BFC05F591 -:102B300083541034002606F1840305EB43131B79FC -:102B40001A0706D50136032E04F12004F3D1012023 -:102B500007E05B07F6D42146384600F07DFA0028EE -:102B6000F0D1FFF755FCF8BD0120FCE700F58050DF -:102B700008B5FFF747FCC06DFFF726FBFFF748FCE1 -:102B800043090CBF0120002008BD0000F8B51D4618 -:102B9000002313700F4606461446FFF7E7FF80F048 -:102BA0000100387025B129463046FFF7B3FF207089 -:102BB000F8BD00002DE9B8410C4615461F46804679 -:102BC00000F0F0F90B462178024609B9287850B197 -:102BD0004046FFF769FFFFF793FF3B462A46214631 -:102BE000FFF7D4FF0120BDE8B881000038B500F53B -:102BF0008054FFF707FC2A4D94F8C930EB5CDBB139 -:102C0000012B27D0FFF704FC94F8C830DB0746D42B -:102C1000002944D0FFF7F6FB94F8C930EB5C33B3DE -:102C2000012B31D094F8C83043F0010384F8C83048 -:102C3000BDE83840FFF7ECBB1A4B1A6C42F000724B -:102C40001A641A6A42F000721A621A6A22F000725A -:102C50001A62D7E7134B1A6C42F080621A641A6A40 -:102C600042F080621A621A6A22F08062F0E7032161 -:102C7000132001F0D9FA0321142001F0D5FA032121 -:102C8000152001F0D1FACDE703213F2001F0CCFA65 -:102C90000321402001F0C8FA03214120F1E738BDAB -:102CA000B8570008003802402DE9F04700F580557C -:102CB00088B095F8C930022B0446884616467FD85E -:102CC000844F57F823200AB947F82300D7F800A00B -:102CD000C4F80C802674BAF1000F63D095F8C9309F -:102CE000012B6FD001212046FFF780FFFFF78AFB01 -:102CF0006269136823F0020313606269136843F08A -:102D000001031360636900275F6101212046FFF71B -:102D10007FFBFFF7A7FD002800F09580E86DFFF727 -:102D200041FA04F58359BA4609F108092022002125 -:102D30006846FEF70DFF02A8FFF730FCCDF818A09B -:102D40006A4609EB07030DF1180E9446BCE8030030 -:102D5000F44518605960624603F10803F5D1DCF8C8 -:102D60000000186020379CF804201A71602FDDD114 -:102D700095F8C8306FF38203002785F8C8306A469B -:102D800041462046ADF80070ADF802708DF8047031 -:102D9000FFF70CFD636948BB4FF400421A6008B0AE -:102DA000BDE8F08741F2D00002F0EEFB814610B1A1 -:102DB0005146FFF797FCC7F80090B9F1000F8DD18D -:102DC0000020ECE7386803681B6B98470146002831 -:102DD00088D13868FFF70AFF3868036832465B68B5 -:102DE0004146984700287FF47DAFE9E761221A60E9 -:102DF0009DF802309DF803201B06120402F4702295 -:102E000003F040731343BDF80020C2F309021343DB -:102E10009DF804201205022E02F4E0020CBF4FF0D0 -:102E200000410021134362690B43D361636913229C -:102E30005A616269136823F0010313603946204622 -:102E4000FFF710FD08B96369A6E795F8C930002BB4 -:102E500039D16169D1F8002242F00102C1F80022A3 -:102E60006169D1F8002222F47C5222F00E02C1F8EE -:102E700000226169D1F8002242F46062C1F80022A8 -:102E80006269C2F814326269C2F8043262696FF092 -:102E90007841C2F80C126269C2F840326269C2F825 -:102EA00044326269C2F8B0326269C2F8B43263690E -:102EB00044F20102C3F81C226269D2F8003223F006 -:102EC0000103C2F8003295F8C83043F0020385F8D8 -:102ED000C83064E7145C002008B50020FFF730FD1F -:102EE000BDE8084001F082B808B500210846FFF7A8 -:102EF000BBFDBDE8084001F079B8000008B501212C -:102F00000020FFF7B1FDBDE8084001F06FB80000F8 -:102F100008B50120FFF714FDBDE8084001F066B8D0 -:102F200008B500210120FFF79FFDBDE8084001F032 -:102F30005DB8000008B501210846FFF795FDBDE822 -:102F4000084001F053B8000000B59BB0EFF30981D1 -:102F500068226846FEF7EAFDEFF30583014B9B6BA1 -:102F6000FEE700BF00ED00E008B5FFF7EDFF000051 -:102F700000B59BB0EFF3098168226846FEF7D6FDE5 -:102F8000EFF30583014B5B6BFEE700BF00ED00E054 -:102F9000FEE700000FB408B5029801F0E1FBFEE780 -:102FA00001F008BF01F0E0BE13B56C4684E80600EE -:102FB000031D94E8030083E80500012002B010BD62 -:102FC00073B58568019155B11B885B0707D4D0E9BB -:102FD00000369B6B9847019AC1B23046A847012042 -:102FE00002B070BDF0B5866889B005460C465EB18A -:102FF000BDF838305B070AD4D0E900379B6B98479F -:103000002246C1B23846B047012009B0F0BD0022C7 -:103010000023CDE900230023ADF808300A4603ABB6 -:1030200001F10806106851681C4603C40832B24218 -:103030002346F7D1106820609288A280FFF7B2FF84 -:103040000423ADF808302B68CDE90001DB6B69463D -:1030500028469847D8E7000030B503680968DD0FB7 -:10306000B5EBD17F23F0604421F060424FEAD1708C -:103070000BD0002BB8BFA40C0029B8BF920C94420F -:1030800002D034BF0120002030BD944205D1C1F3ED -:103090008070C3F380738342F6D194422CBF00202A -:1030A0000120F1E72DE9F041456A15B94162BDE81B -:1030B000F0814B6823F06047C3F38A464FEAD37E22 -:1030C000C3F3807816EA230638BF3E46AC462B464B -:1030D0005A68BEEBD27F22F060440AD0002A18DA88 -:1030E000A40CB44217D19D420FD10D60DEE7134608 -:1030F000EEE7A74207D102F08044C2F38072424556 -:103100000BD054B1EFE708D2EDE7CCF800100B601C -:10311000CDE7B44201D0B442E5D81A689C46002AF3 -:10312000E5D11960C3E700002DE9F047089D01F0E3 -:1031300007044FEAD508224405F0070500EBD1004B -:103140004FF47F49944201D1BDE8F08704F00707AE -:1031500005F0070A57453E4638BF5646C6F10806F1 -:10316000111B8E4228BF0E46E10808EBD50E415CCC -:1031700013F80EC0B94029FA06F721FA0AF1FFB296 -:103180008CEA010147FA0AF739408CEA010C03F88E -:103190000EC034443544D5E780EA0120082341F2CB -:1031A000210201B24000002980B203F1FF33B8BF11 -:1031B000504013F0FF03F4D17047000038B50C46BF -:1031C0008D18A54200D138BD14F8011BFFF7E4FFAC -:1031D000F7E7000042684AB1136843604389818978 -:1031E00001339BB29942438138BF838110467047B7 -:1031F00070B588B0202204460D4668460021FEF7CF -:10320000A7FC20460495FFF7E5FF024658B16B4640 -:10321000054608AE1C4603CCB442286069602346CC -:1032200005F10805F6D1104608B070BD082817D979 -:1032300009280CD00A280CD00B280CD00C280CD054 -:103240000D280CD00E2814BF4020302070470C20D1 -:1032500070471020704714207047182070472020B6 -:1032600070470000082817D90C280CD910280CD951 -:1032700014280CD918280CD920280CD930288CBF38 -:103280000F200E207047092070470A2070470B203E -:1032900070470C2070470D20704700002DE9F8435F -:1032A000078C072F04461ED9D0E9029800254FF657 -:1032B000FF73C5F12006A5F1200029FA05F108FAEF -:1032C00006F628FA00F031430143C9B21846FFF769 -:1032D00063FF0835402D0346EBD1E1693A46BDE86E -:1032E000F843FFF76BBF4FF6FF70BDE8F8830000AF -:1032F00010B54B6823B9CA8A63F30902CA8210BDAC -:1033000004691A681C600361C38A013BC3824A6076 -:10331000EFE700002DE9F84F1D46CB8A0F46C3F3B7 -:1033200009010529814692460B4630D00020AAB2F9 -:1033300007F11A049EB2042E1FFA80F80FD89045A8 -:1033400003F1010306D3FB8A0A4462F30903FB82FB -:1033500001201AE01AF80060E6540130EAE79045CF -:10336000F1D2A1F1050B1C237C68BBFBF3F203FB3C -:1033700012BB1FFA8BF6002C45D14846FFF72AFFF7 -:10338000044638B978606FF00200BDE8F88F4FF05E -:103390000008E6E7002606607860ADB24FF0000B4B -:1033A000454510D90AEB0803221D13F8011B91555E -:1033B000B1B208F101081B291FFA88F82BD0454546 -:1033C00006F10106F1D8FB8AC3F30902154465F33F -:1033D0000903BCE7013292B21C462368002BF9D1E5 -:1033E0006B1F0B441C21B3FBF1F301339BB29A42D8 -:1033F000D3D2BBF1000FD0D14846FFF7EBFE20B986 -:10340000C4F800B0BFE70122E7E7C0F800B05E46AD -:1034100020600446C1E74545D5D94846FFF7DAFEA6 -:1034200008B92060AFE7C0F800B00026206004466D -:10343000B6E700002DE9F04F2DED028B1C4683B05E -:103440005B69019207468846002B00F09A80238C26 -:103450002BB1E269002A00F09480072B35D807F1E0 -:103460000C00FFF7B7FE054638B96FF00205284695 -:1034700003B0BDEC028BBDE8F08F14220021FEF7F3 -:1034800067FB228CE16905F10800FEF74FFB208CF9 -:10349000013080B2FFF7E6FEFFF7C8FE013880B2C8 -:1034A0002084013028746369228C1B782A4403F03D -:1034B0001F0363F03F0348F0004113723846696010 -:1034C0002946FFF7EFFD0125D1E700F10C034FF08E -:1034D000000908EE103A4FF0800A4E464D4618EEAD -:1034E000100AFFF777FE83460028BED01422002181 -:1034F000FEF72EFB002E3AD1019BABF808300222DA -:103500000BF1080E1FFA82FC0CF10100BCF1060F52 -:10351000218C80B201D88E422BD3FFF7A3FEFFF798 -:1035200085FE62691278013802F01F028E4208BFE0 -:103530004FF0400A42EA49121BFA80F14AEA020AB5 -:10354000013048F0004281F808A08BF81000CBF859 -:10355000042059463846FFF7A5FD238C0135B342B8 -:103560002DB289F001094FF0000AB8D17FE700229F -:10357000C6E7E169895D0EF802100136B6B2013284 -:10358000C0E76FF0010572E7F8B515460E46302228 -:10359000002104461F46FEF7DBFA069B6360B5F583 -:1035A000001F079BA76034BF6A094FF6FF72A36232 -:1035B00097B2E66104F1100000239A4206D8002376 -:1035C0000360A782E3822383E360F8BD06600133D2 -:1035D00030462036F1E7000003781BB94BB2002BD0 -:1035E000C8BF01707047000000787047F8B50C46FE -:1035F000C969074611B9238C002B37D1257E1F2DB1 -:1036000034D8387828BB228C072A2CD8268A36F062 -:1036100003032BD14FF6FF70FFF7D0FD20F0010020 -:103620003102400441EA0561400C41EA40254FF671 -:10363000FF72234629463846FFF7FCFE002807DDC7 -:10364000626913780133DBB21F2B88BF002313702C -:10365000F8BD218A2D0645EA012505432046FFF7DE -:103660001DFE0246E5E76FF00300F1E76FF0010091 -:10367000EEE7000070B58AB0044616460021282205 -:1036800068461D46FEF764FABDF83830ADF81030D4 -:103690000F9B05939DF840308DF81830119B0793D0 -:1036A0006946BDF84830ADF820302046CDE90265C6 -:1036B000FFF79CFF0AB070BD2DE9F041D3690546C4 -:1036C0000C4616460BB9138C5BBB377E1F2F28D8D0 -:1036D00095F80080B8F1000F26D03046FFF7DEFDE8 -:1036E0003378210241EAC33141EA0801338A41EAD1 -:1036F000076141EA03410246334641F08001284612 -:10370000FFF798FE00280ADD3378012B07D1726994 -:1037100013780133DBB21F2B88BF00231370BDE881 -:10372000F0816FF00100FAE76FF00300F7E70000A7 -:10373000F0B58BB004460D46174600212822684696 -:103740001E46FEF705FA9DF84C305A1E534253416F -:103750008DF800309DF84030ADF81030119B059386 -:103760009DF848308DF81830149B07936A46BDF8D1 -:103770005430ADF8203029462046CDE90276FFF7D7 -:103780009BFF0BB0F0BD0000406A00B104307047F1 -:10379000436A1A68426202691A600361C38A013B84 -:1037A000C38270472DE9F041D0F82080194E1446AD -:1037B0001D464146002709B9BDE8F081D1E9022341 -:1037C000A21A65EB0303964277EB03031ED2036A4A -:1037D0008B420DD1FFF78CFD036A1B6803620369FE -:1037E0000B60C38A0161016A013BC3828846E2E73C -:1037F000FFF77EFD0B68C8F8003003690B60C38AD1 -:103800000161013BC382D8F80010D4E788460968FB -:10381000D1E700BF80841E002DE9F04F8BB00D462C -:10382000DDF8509014469B468046002800F0198130 -:10383000B9F1000F00F01581531E3F2B00F21181EA -:10384000012A03D1BBF1000F40F00B810023CDE929 -:103850000833B8F81430B5EBC30F4FEAC30703D3EE -:1038600000200BB0BDE8F08F2B199F42D8F80C3028 -:103870003ABF7F1BFFB227461BB9D8F81030002B88 -:103880007AD0272D4ED8C5F12806B7424FF0000355 -:103890002CBFF6B23E4600932946D8F8080008AB84 -:1038A0003246FFF741FCA7EB060A35445FFA8AFA75 -:1038B000B8F8143003F10053053BDB000493D8F84B -:1038C0000C3003932821039B13B1BAF1000F2CD1C4 -:1038D000D8F8100040B1BAF1000F05D0009608AB3F -:1038E0005246691AFFF720FC38B2002FB8D066079D -:1038F0000AD00AAB03EBD401624211F8083C02F093 -:103900000702134101F8083C082C3CD9102C40F266 -:10391000B580202C40F2B780BBF1000F00F09C80F6 -:10392000082334E0BA460026C2E7049BE02B28BFF8 -:10393000E02306930B44AB42059314D95A1B03981A -:103940000096924534BF5246D2B2691A08AB043091 -:103950000792FFF7E9FB079A1644AAEB020A1544FF -:10396000F6B25FFA8AFA049B069A05999B1A0493A9 -:10397000039B1B680393A6E70093D8F8080008ABE5 -:103980003A462946AEE7BBF1000F13D00123B4EB52 -:10399000C30F6CD0082C12D89DF82030621E23FA79 -:1039A00002F2D50706D54FF0FF3202FA04F42343A2 -:1039B0008DF820309DF8203089F8003051E7102C28 -:1039C00012D8BDF82030621E23FA02F2D10706D5C4 -:1039D0004FF0FF3202FA04F42343ADF82030BDF873 -:1039E0002030A9F800303CE7202C0FD80899631E3E -:1039F00021FA03F3DA0705D54FF0FF3202FA04F497 -:103A00000C430894089BC9F800302AE7402C2BD0BF -:103A1000DDE90865611EC4F12102A4F1210326FA43 -:103A200001F105FA02F225FA03F311431943CB071A -:103A300012D50122A4F12003C4F1200102FA03F3FC -:103A400022FA01F1A240524243EA010363EB43032D -:103A500032432B43CDE90823DDE90823C9E90023DC -:103A6000FFE66FF00100FCE66FF00800F9E6082CB5 -:103A7000A0D9102CB3D9202CEED8C3E7BBF1000F8E -:103A8000ADD0022383E7BBF1000FBBD004237EE758 -:103A900030B5012A144638BF0124402C85B028BF18 -:103AA00040240025012ACDE9025518D81B788DF84D -:103AB000083063070AD004AB03EBD405624215F863 -:103AC000083C02F00702934005F8083C00910346C9 -:103AD0002246002102A8FFF727FB05B030BD082AC7 -:103AE000E4D9102A03D81B88ADF80830E1E7202A72 -:103AF0008DBFD3E900231B680293CDE90223D8E7E9 -:103B000010B5CB681BB98B600B618B8210BD04694B -:103B10001A681C600361C38A013BC382CA60F0E774 -:103B200003064CBFC0F3C0300220704708B5024600 -:103B3000FFF7F6FF022806D15306C2F30F2001D18A -:103B400000F0030008BDC2F30740FBE72DE9F04F8A -:103B500093B0CDE903230A6804461046FFF7E0FF5F -:103B6000022814BFC2F306260026002A0D4682460C -:103B700080F2F28112F0C04940F0EE81097B002909 -:103B800000F0EA81022803D02378B34240F0E781B5 -:103B9000C2F304630693104602F07F030593FFF718 -:103BA000C5FF059B29444FEA834848EA0A4848EA8A -:103BB0004668CE7800230022CDE90823F309834626 -:103BC00048EA0008029367D0059B009302466768A5 -:103BD000534608A92046B847002800F0C381276A49 -:103BE0004FB9414604F10C00FFF702FB074690B9BC -:103BF0006FF0020054E03B6998450DD03F68002FFC -:103C0000F9D1414604F10C00FFF7F2FA074600280B -:103C1000EED0236A3B60276297F817C006F01F08B2 -:103C2000CCF3840CACEB08001FFA80FE0028B8BF70 -:103C30000EF12000A8EB0C031FFA83FED7E9022146 -:103C4000B8BF00B2002B0793BEBF0EF120031BB21A -:103C5000079352EA010338D0039BDFF824E39A1A52 -:103C6000049B4FF0000C63EB010196457CEB0103D4 -:103C70002BD36B7B97F81AE0734519D1029B002B6D -:103C800078D0012821DC7868F8B9DFF8F0C29445D3 -:103C900070EB010316D337E0276A27B96FF00C00E9 -:103CA00013B0BDE8F08F3B699845B5D03F68F4E7A5 -:103CB000B24890427CEB010301D30020F0E7029B65 -:103CC000002BFAD0079B0F2B17DCFA7DB30002F014 -:103CD000030203F07C031343FB7539462046FFF7CC -:103CE00007FB6B7BBB76029B3BB9FB7DC3F3840276 -:103CF000013262F38603FB75D0E76A7BBB7E9A4292 -:103D0000DBD1029B002B35D0B309022B32D0039BB1 -:103D1000BB60049BFB60142200210DA8FDF718FF77 -:103D2000039B0A93049B0B932B1D0C932B7BADF8E9 -:103D30003EB0013BDBB2ADF83C30069B8DF8423023 -:103D4000059B8DF8433094F82C308DF840A083F01B -:103D500001038DF844308DF84180A3680AA92046FC -:103D60009847FB7DC3F38403013303F01F039B02D9 -:103D7000FB82A2E7FB7DC6F34012B2EBD31F40F0FB -:103D8000F480C3F38403434540F0F280029A2B7B16 -:103D9000B609002A4DD0F2075DD4032B40F2EB8028 -:103DA000039BBB60049BFB602B7BAE1D033BDBB224 -:103DB0003246394604F10C00FFF7ACFA00280CDA61 -:103DC00039462046FFF794FAFB7DC3F384030133A1 -:103DD00003F01F039B02FB820AE7DDE90884AB883E -:103DE0003B834FF6FF73C9F12000A9F1200228FAA6 -:103DF00009F104FA00F0014324FA02F211431846D3 -:103E0000C9B2FFF7C9F909F10809B9F1400F034632 -:103E1000E9D1B8822A7B033AD2B23146FFF7CEF914 -:103E2000FB7DB882DA43C2F3C01262F3C713FB759D -:103E300043E786B92E1D013BDBB23246394604F119 -:103E40000C00FFF767FA0028BADB2A7BB88A013A30 -:103E5000D2B23146E2E7F98AC1F30901013B0429F4 -:103E6000DAB25BD8281D002307F11B069A4208D955 -:103E700010F801CB06F801C0013101330529DBB28E -:103E8000F4D103990A9104990B91934207F11B0114 -:103E90000C9138BF043379680D9134BF55FA83F320 -:103EA00000230E93FB8AADF83EB0C3F309031A4416 -:103EB000069B8DF84230059B8DF8433094F82C30EA -:103EC000ADF83C2083F001038DF8443000238DF8D9 -:103ED00040A08DF841807B602A7BB88A013A291D79 -:103EE000FFF76CF93B8BB882834203D1A3680AA920 -:103EF0002046984720460AA9FFF702FEFB7DBA8AB2 -:103F0000C3F38403013303F01F039B02FB823B8B4B -:103F10009A420CBF00206FF01000C1E67B68002BB6 -:103F2000AFD0052001E01C3033461E68002EFAD1C8 -:103F3000091A081D2E1D184401EB090CBCF11B0FBA -:103F40005FFA89F39DD89A429BD916F8013B00F895 -:103F5000013B09F10109EFE76FF00900A0E66FF0FE -:103F60000A009DE66FF00B009AE66FF00D0097E6F1 -:103F70006FF00E0094E66FF00F0091E640420F00E4 -:103F800080841E00EFF3098305494A6B22F0010289 -:103F90004A63683383F30988002383F311887047E9 -:103FA00000EF00E0302080F3118862B60C4B0D4A20 -:103FB000D96821F4E0610904090C0A43DA60D3F8F6 -:103FC000FC20094942F08072C3F8FC200A6842F0E4 -:103FD00001020A602022DA7783F82200704700BFCE -:103FE00000ED00E00003FA05001000E010B53023FA -:103FF00083F311880E4B5B6813F4006314D0F1EE69 -:10400000103AEFF30984683C4FF08073E361094B89 -:10401000DB6B236684F3098800F060FB10B1064B6C -:10402000A36110BD054BFBE783F31188F9E700BFDF -:1040300000ED00E000EF00E043060008460600083F -:10404000026843681143016003B1184770470000DC -:10405000024AD36843F0C003D36070470044004075 -:1040600010B5054C054A0021204600F087FA044AA5 -:10407000044BC4E9972310BD245C00205140000884 -:104080000044004040787D01234A037C002918BF8A -:104090000A46012B30B5C0F868220CD11F4B98425C -:1040A00009D11F4B196C41F400311964196E41F4A8 -:1040B000003119661B6EB2F904501468D0F86032F2 -:1040C000D0F85C12002D03EB5403B3FBF4F3BEBF36 -:1040D00023F0070503F0070343EA450394888B6048 -:1040E000D38843F040030B61138943F001034B6114 -:1040F00044F4045343F02C03CB6004F4A054002395 -:104100000B60B4F5806F0B684B680CBF7F23FF23F7 -:1041100080F8643230BD00BF1C580008245C0020C9 -:10412000003802402DE9F041D0F85C62F76833684E -:10413000DA0504469DB20DD5302383F311884FF480 -:1041400080610430FFF77CFF6FF4807333600023DD -:1041500083F31188302383F3118804F1040815F0E8 -:104160002F033AD183F31188380615D5290613D5C4 -:10417000302383F3118804F1380000F07BF9002824 -:104180004EDA0821201DFFF75BFF4FF67F733B409F -:10419000F360002383F311887A0616D56B0614D5D5 -:1041A000302383F31188D4E913239A420AD1236C74 -:1041B00043B127F040073F041021201D3F0CFFF7BB -:1041C0003FFFF760002383F31188D4F86822D36897 -:1041D00043B3BDE8F041106918472B0714D015F020 -:1041E000080F0CBF00214FF48071E80748BF41F071 -:1041F0002001AA0748BF41F040016B0748BF41F0CA -:1042000080014046FFF71CFFAD06736805D594F8A2 -:1042100064122046194000F0E1F93568ADB29EE71E -:104220007060B6E7BDE8F08100F1604303F56143DB -:104230000901C9B283F80013012200F01F039A405C -:1042400043099B0003F1604303F56143C3F88021F8 -:104250001A607047F8B5154682680669AA420B468F -:10426000816938BF8568761AB54204460BD2184674 -:104270002A46FDF75BFCA3692B44A361A3685B1B83 -:10428000A3602846F8BD0CD918463246FDF74EFC0F -:10429000AF1BE1683A463044FDF748FCE3683B4415 -:1042A000EBE718462A46FDF741FCE368E5E7000026 -:1042B00083689342F7B51546044638BF8568D0E950 -:1042C0000460361AB5420BD22A46FDF72FFC63690B -:1042D0002B446361A36828465B1BA36003B0F0BD59 -:1042E0000DD932460191FDF721FC0199E068AF1B21 -:1042F0003A463144FDF71AFCE3683B44E9E72A46B5 -:10430000FDF714FCE368E4E710B50A440024C36138 -:10431000029B8460C0E90000C0E90511C160026130 -:10432000036210BD08B5D0E90532934201D182681D -:1043300082B98268013282605A1C42611970D0E9E8 -:1043400004329A4224BFC3684361002100F08EFA10 -:10435000002008BD4FF0FF30FBE7000070B53023B0 -:1043600004460E4683F31188A568A5B1A368A26927 -:10437000013BA360531CA36115782269934224BFBB -:10438000E368A361E3690BB120469847002383F3F8 -:104390001188284607E03146204600F057FA0028E9 -:1043A000E2DA85F3118870BD2DE9F74F04460E4619 -:1043B00017469846D0F81C904FF0300A8AF31188BF -:1043C0004FF0000B154665B12A4631462046FFF7EF -:1043D00041FF034660B94146204600F037FA002805 -:1043E000F1D0002383F31188781B03B0BDE8F08F70 -:1043F000B9F1000F03D001902046C847019B8BF311 -:104400001188ED1A1E448AF31188DCE7C0E9051112 -:10441000C160C3611144009B8260C0E9000001617A -:1044200003627047F8B504460D461646302383F301 -:104430001188A768A7B1A368013BA36063695A1CF0 -:1044400062611D70D4E904329A4224BFE36863615B -:10445000E3690BB120469847002080F3118807E0FC -:104460003146204600F0F2F90028E2DA87F311889D -:10447000F8BD0000D0E905239A4210B501D1826849 -:104480007AB98268013282605A1C82611C780369A1 -:104490009A4224BFC3688361002100F0E7F92046F7 -:1044A00010BD4FF0FF30FBE72DE9F74F04460E46F5 -:1044B00017469846D0F81C904FF0300A8AF31188BE -:1044C0004FF0000B154665B12A4631462046FFF7EE -:1044D000EFFE034660B94146204600F0B7F90028D8 -:1044E000F1D0002383F31188781B03B0BDE8F08F6F -:1044F000B9F1000F03D001902046C847019B8BF310 -:104500001188ED1A1E448AF31188DCE702684368BB -:104510001143016003B11847704700001430FFF7E2 -:1045200043BF00004FF0FF331430FFF73DBF0000E2 -:104530003830FFF7B9BF00004FF0FF333830FFF7D6 -:10454000B3BF00001430FFF709BF00004FF0FF3188 -:104550001430FFF703BF00003830FFF763BF0000DF -:104560004FF0FF323830FFF75DBF0000012914BF64 -:104570006FF0130000207047FFF772BD37B5154686 -:104580000E4A026000224260C0E902220122044673 -:1045900002740B46009000F15C014FF480721430FD -:1045A000FFF7B2FE00942B464FF4807204F5AE7113 -:1045B00004F13800FFF72AFF03B030BD305800087F -:1045C00010B53023044683F31188FFF75DFD022305 -:1045D0002374002080F3118810BD000038B5C36932 -:1045E00004460D461BB904210844FFF78FFF2946F6 -:1045F00004F11400FFF796FE002806DA201D4FF4A0 -:104600000061BDE83840FFF781BF38BD0023037566 -:10461000826803691B6899689142FBD25A680360FB -:104620004260106058607047002303758268036918 -:104630001B6899689142FBD85A6803604260106019 -:104640005860704708B50846302383F311880B7D06 -:10465000032B05D0042B0DD02BB983F3118808BD93 -:104660008B6900221A604FF0FF338361FFF7CEFFA2 -:104670000023F2E7D1E9003213605A60F3E700004B -:10468000FFF7C4BF054BD9680875186802681A603F -:10469000536001220275D860FBF7BEBF905E002018 -:1046A00030B50C4BDD684B1C87B004460FD02B4651 -:1046B000094A684600F06CF92046FFF7E3FF009BCB -:1046C00013B1684600F06EF9A86907B030BDFFF776 -:1046D000D9FFF9E7905E002045460008044B1A68B0 -:1046E000DB6890689B68984294BF00200120704767 -:1046F000905E0020084B10B51C68D86822681A60CC -:10470000536001222275DC60FFF78EFF01462046D0 -:10471000BDE81040FBF780BF905E0020044B1A6894 -:10472000DB6892689B689A4201D9FFF7E3BF704744 -:10473000905E002038B5074C074908480123002542 -:104740002370656000F03AFC0223237085F3118822 -:1047500038BD00BFF86000205C580008905E002063 -:1047600008B572B6044B186500F0ECFA00F0A0FB37 -:10477000024B03221A70FEE7905E0020F8600020D2 -:1047800000F046B9EFF3118020B9EFF30583302232 -:1047900082F311887047000010B530B9EFF305843B -:1047A000C4F3080414B180F3118810BDFFF7B6FFFD -:1047B00084F31188F9E700008B60022308618B8283 -:1047C000084670478368A3F1840243F8142C0269F9 -:1047D00043F8442C426943F8402C094A43F8242CFE -:1047E000C26843F8182C022203F80C2C002203F8AC -:1047F0000B2C044A43F8102CA3F12000704700BF93 -:1048000031060008905E002008B5FFF7DBFFBDE829 -:104810000840FFF735BF0000024BDB6898610F20AE -:10482000FFF730BF905E0020302383F31188FFF73D -:10483000F3BF000008B50146302383F31188082038 -:10484000FFF72EFF002383F3118808BD064BDB68BA -:1048500039B1426818605A60136043600420FFF762 -:104860001FBF4FF0FF307047905E002003689842F2 -:1048700006D01A680260506099611846FFF700BFC1 -:104880007047000010B503689C68A2420CD85C68B1 -:104890008A600B604C602160596099688A1A9A603E -:1048A0004FF0FF33836010BD1B68121BECE7000064 -:1048B0000A2938BF0A2170B504460D460A26601938 -:1048C00000F076FB00F062FB041BA54203D8751CC8 -:1048D0002E460446F3E70A2E04D9BDE870400120B5 -:1048E00000F0ACBB70BD0000F8B5144B0D46D961AB -:1048F00003F1100141600A2A1969826038BF0A2257 -:10490000016048601861A818144600F043FB0A27AC -:1049100000F03CFB431BA342064606D37C1C28192F -:1049200000F046FB27463546F2E70A2F04D9BDE8DA -:10493000F840012000F082BBF8BD00BF905E00206F -:10494000F8B506460D4600F021FB0F4A134653F812 -:10495000107F9F4206D12A4601463046BDE8F84006 -:10496000FFF7C2BFD169BB68441A2C1928BF2C4677 -:10497000A34202D92946FFF79BFF2246314603484E -:10498000BDE8F840FFF77EBF905E0020A05E0020EB -:1049900010B4C0E9032300235DF8044B4361FFF723 -:1049A000CFBF000010B5194C236998420DD0D0E953 -:1049B0000032816813605A609A680A449A60002342 -:1049C00003604FF0FF33A36110BD2346026843F834 -:1049D000102F53600022026022699A4203D1BDE881 -:1049E000104000F0DFBA936881680B44936000F0D8 -:1049F000CDFA2269E1699268441AA242E4D91144CD -:104A0000BDE81040091AFFF753BF00BF905E0020B9 -:104A10002DE9F047DFF8BC8008F110072C4ED8F8DC -:104A2000105000F0B3FAD8F81C40AA68031B9A4251 -:104A30003ED81444D5E900324FF00009C8F81C40B4 -:104A400013605A60C5F80090D8F81030B34201D115 -:104A500000F0A8FA89F31188D5E903312846984770 -:104A6000302383F311886B69002BD8D000F08EFAC5 -:104A70006A69A0EB04094A4582460DD2022000F083 -:104A8000DDFA0022D8F81030B34208D1514628464A -:104A9000BDE8F047FFF728BF121A2244F2E712EBF5 -:104AA000090938BF4A4629463846FFF7EBFEB5E705 -:104AB000D8F81030B34208D01444211AC8F81C00AA -:104AC000A960BDE8F047FFF7F3BEBDE8F08700BF7F -:104AD000A05E0020905E002000207047FEE70000EE -:104AE000704700004FF0FF3070470000BFF34F8F5A -:104AF000024AD368DB03FCD4704700BF003C02408D -:104B000008B5094B1B7873B9FFF7F0FF074B1A691B -:104B1000002ABFBF064A5A6002F188325A601A68FA -:104B200022F480621A6008BD00610020003C02404F -:104B30002301674508B50B4B1B7893B9FFF7D6FFE8 -:104B4000094B1A6942F000421A611A6842F4805215 -:104B50001A601A6822F480521A601A6842F480625D -:104B60001A6008BD00610020003C02400728F0B533 -:104B700016D80C4C0C4923787BB90C4D0E460823F3 -:104B80004FF0006255F8047B46F8042B013B13F00C -:104B9000FF033A44F6D10123237051F82000F0BD01 -:104BA0000020FCE724610020046100206858000810 -:104BB000014B53F8200070476858000808207047E0 -:104BC000072810B5044601D9002010BDFFF7CEFF1D -:104BD000064B53F824301844C21A0BB90120F4E7ED -:104BE00012680132F0D1043BF6E700BF68580008B4 -:104BF000072810B5044621D8FFF778FFFFF780FF9C -:104C00000F4AF323D360C300DBB243F4007343F0D5 -:104C100002031361136943F480331361FFF766FFE6 -:104C2000FFF7A4FF074B53F8241000F03DF9FFF7FE -:104C300081FF2046BDE81040FFF7C2BF002010BD35 -:104C4000003C024068580008F8B512F00103144611 -:104C500042D185182E4A954257D82E4B1B6813F027 -:104C6000010352D02C4DFFF74BFFF323EB60FFF70E -:104C70003DFF40F20127032C15D824F001046618EB -:104C8000254C401A40F20117B142236900EB01059F -:104C900024D123F001032361FFF74CFF0120F8BD6D -:104CA000043C0430E7E78307E7D12B6923F4407322 -:104CB0002B612B693B432B6151F8046B0660BFF3FA -:104CC0004F8FFFF713FF03689E42E9D02B6923F053 -:104CD00001032B61FFF72EFF0020E0E723F4407370 -:104CE000236123693B4323610B882B80BFF34F8FE4 -:104CF000FFF7FCFE2D8831F8023BADB2AB42C3D0CA -:104D0000236923F001032361E4E71846C7E700BFE6 -:104D10000000080800380240003C0240084908B57D -:104D20000B7828B11BB9FFF7EBFE01230B7008BD10 -:104D3000002BFCD0BDE808400870FFF7FBBE00BFA9 -:104D4000006100204FF480214FF0005000F0AEB819 -:104D50000846114600F03ABC012000F037BC0000C4 -:104D6000084600F051BC000070B582B0FFF70AFDA4 -:104D70000E4E054600F00AF93268904237BF0C4AE1 -:104D80000B49516814682EBFD1E9004101315160CF -:104D90000419034641F10001284601913360FFF7F1 -:104DA000FBFC0199204602B070BD00BF28610020C5 -:104DB0003061002070B582B0FFF7E4FC104E05466C -:104DC00000F0E4F83268904237BF0E4A0D4951684E -:104DD00014682EBFD1E9004101315160041941F13D -:104DE00000010346284601913360FFF7D5FC019985 -:104DF0004FF47A7200232046FBF7FAF902B070BD37 -:104E0000286100203061002010B50244064BD2B268 -:104E1000904200D110BD441C00B253F8200041F86C -:104E2000040BE0B2F4E700BF502800400F4B30B550 -:104E30001C6F240407D41C6F44F400741C671C6F9F -:104E400044F400441C670A4C236843F480732360D5 -:104E50000244084BD2B2904200D130BD441C00B293 -:104E600051F8045B43F82050E0B2F4E70038024008 -:104E7000007000405028004007B5012201A9002021 -:104E8000FFF7C2FF019803B05DF804FB13B50446B9 -:104E9000FFF7F2FFA04205D0012201A900200194F2 -:104EA000FFF7C4FF02B010BD70470000704700005C -:104EB00070470000074B45F255521A6002225A60B3 -:104EC00040F6FF729A604CF6CC421A60024B012207 -:104ED0001A707047003000403C610020034B1B7883 -:104EE0001BB1034B4AF6AA221A6070473C610020AE -:104EF00000300040034B1A681AB9034AD2F87428EC -:104F00001A6070473861002000300240024B4FF0B9 -:104F10008072C3F8742870470030024008B5FFF76C -:104F2000E9FF024B1868C0F3407008BD38610020EB -:104F300008B5FFF7DFFF024B1868C0F3007008BD2B -:104F40003861002070470000FEE700000A4B0B4864 -:104F50000B4A90420BD30B4BDA1C121AC11E22F0E3 -:104F600003028B4238BF00220021FCF7F1BD53F849 -:104F7000041B40F8041BECE7085A0008C861002035 -:104F8000C8610020C861002000F0CAB84FF080431B -:104F9000586A70474FF08043002258631A6102221A -:104FA000DA6070474FF080430022DA6070470000FB -:104FB0004FF0804358637047FEE7000070B51B4B0D -:104FC00001630025044686B0586085620E46FEF7F0 -:104FD000E9FF04F11003C4E904334FF0FF33C4E9DF -:104FE0000635C4E90044A560E562FFF7CFFF2B4614 -:104FF0000246C4E9082304F134010D4A25658023E3 -:105000002046FFF7D9FB0123E0600A4A03750092AE -:1050100072680192B268CDE90223074B6846CDE978 -:105020000435FFF7F1FB06B070BD00BFF86000204B -:10503000885800088D580008B94F0008024AD36A02 -:105040001843D062704700BF905E00204B684360F9 -:105050008B688360CB68C3600B6943614B690362F3 -:105060008B6943620B6803607047000008B5234BEF -:1050700023481A6942F0FF021A611A6922F0FF02FE -:105080001A611A691A6B42F0FF021A631A6D42F034 -:10509000FF021A651B4A1B6D1146FFF7D7FF02F18D -:1050A0001C0100F58060FFF7D1FF02F1380100F527 -:1050B0008060FFF7CBFF02F1540100F58060FFF73D -:1050C000C5FF02F1700100F58060FFF7BFFF02F13C -:1050D0008C0100F58060FFF7B9FF02F1A80100F52F -:1050E0008060FFF7B3FF02F1C40100F58060FFF7B5 -:1050F000ADFFBDE8084000F08DB800BF00380240A9 -:10510000000002409458000808B500F019FAFFF7B3 -:1051100011FBBDE80840FFF7EDBE0000704700003E -:105120000F4B1A6C42F001021A641A6E42F001022F -:105130001A660C4A1B6E936843F0010393604FF0AC -:10514000804331229A624FF0FF32DA6200229A6184 -:105150005A63DA605A6001225A611A60704700BFD0 -:1051600000380240002004E04FF0804208B5116989 -:10517000D3680B40D9B2C9439B07116107D53023CF -:1051800083F31188FFF7FCFA002383F3118808BD2D -:105190001E4B1A6962F0FF021A611A69D2B21A61D3 -:1051A0004FF0FF301A695A69586100215A695961F4 -:1051B0005A691A6A62F080521A621A6A02F08052C0 -:1051C0001A621A6A5A6A58625A6A59625A6A1A6C98 -:1051D00042F080521A641A6E42F080521A661A6EB9 -:1051E0000B4A106840F480701060186F00F4407033 -:1051F000B0F5007F1EBF4FF4803018671967536801 -:1052000023F40073536000F073B900BF003802400C -:10521000007000403B4B3C4A1A643C4A4FF440410A -:1052200011601A6842F001021A601A689007FCD5F2 -:105230009A6822F003029A60324B9A6812F00C02CC -:10524000FBD1196801F0F90119609A601A6842F4FB -:1052500080321A601A689103FCD55A6F42F001023D -:105260005A67284B5A6F9207FCD5294A5A601A6828 -:1052700042F080721A60254A53685804FCD5214BCD -:105280001A689101FCD5234AC3F884201A6842F0B9 -:1052900080621A601A681201FCD51F4A9A600322C4 -:1052A000C3F88C204FF00062C3F894201B4B1A689F -:1052B0001B4B9A421B4B21D11B4A11681B4A91423E -:1052C0001CD140F203121A60164A136803F00F0350 -:1052D000032BFAD10B4B9A6842F002029A609A684B -:1052E00002F00C02082AFAD15A6C42F480425A6445 -:1052F0005A6E42F480425A665B6E704740F2037207 -:10530000E1E700BF003802400004001000700040D8 -:10531000081940021030002400948838002004E06E -:1053200011640020003C024000ED00E041C20F414A -:10533000074A08B5536903F00103536123B1054AD5 -:1053400013680BB150689847BDE80840FEF74EBEA1 -:10535000003C014040610020074A08B5536903F052 -:105360000203536123B1054A93680BB1D068984793 -:10537000BDE80840FEF73ABE003C01404061002015 -:10538000074A08B5536903F00403536123B1054A82 -:1053900013690BB150699847BDE80840FEF726BE77 -:1053A000003C014040610020074A08B5536903F002 -:1053B0000803536123B1054A93690BB1D06998473B -:1053C000BDE80840FEF712BE003C014040610020ED -:1053D000074A08B5536903F01003536123B1054A26 -:1053E000136A0BB1506A9847BDE80840FEF7FEBD4E -:1053F000003C014040610020164B10B55C6904F48C -:1054000078725A61A30604D5134A936A0BB1D06A25 -:105410009847600604D5104A136B0BB1506B984740 -:10542000210604D50C4A936B0BB1D06B9847E2056B -:1054300004D5094A136C0BB1506C9847A30504D5E9 -:10544000054A936C0BB1D06C9847BDE81040FEF74D -:10545000CDBD00BF003C014040610020194B10B59C -:105460005C6904F47C425A61620504D5164A136DE6 -:105470000BB1506D9847230504D5134A936D0BB1BA -:10548000D06D9847E00404D50F4A136E0BB1506EEF -:105490009847A10404D50C4A936E0BB1D06E98477F -:1054A000620404D5084A136F0BB1506F9847230468 -:1054B00004D5054A936F0BB1D06F9847BDE81040F3 -:1054C000FEF794BD003C01404061002008B5034850 -:1054D000FEF728FEBDE80840FEF788BD245C0020EA -:1054E00008B5FFF741FEBDE80840FEF77FBD0000AC -:1054F000062108B50846FEF797FE06210720FEF7AD -:1055000093FE06210820FEF78FFE06210920FEF7F4 -:105510008BFE06210A20FEF787FE06211720FEF7E4 -:1055200083FE06212820FEF77FFE07211C20FEF7C0 -:105530007BFEBDE808400C212620FEF775BE00006A -:1055400008B5FFF725FE00F009F8FFF715F8FFF79B -:10555000E5FDBDE80840FFF717BD00000023054A40 -:1055600019460133102BC2E9001102F10802F8D1EB -:10557000704700BF406100200B460146184600F00E -:105580002DB8000000F040B8012838BF012010B548 -:105590000446204600F030F830B900F007F808B9AA -:1055A00000F00CF88047F4E710BD0000024B1868CB -:1055B000BFF35B8F704700BFC061002008B50620B5 -:1055C00000F084F80120FFF789FA0000024B0A4638 -:1055D00001461868FFF7BCBB2423002010B5054C1A -:1055E00013462CB10A4601460220AFF3008010BDDD -:1055F0002046FCE700000000024B01461868FFF758 -:10560000ABBB00BF24230020024B01461868FFF704 -:10561000A7BB00BF2423002010B5013902449042EB -:1056200001D1002005E0037811F8014FA34201D019 -:10563000181B10BD0130F2E72DE9F041A3B1C91AE2 -:1056400017780144044603F1FF3C8C42204601D9FF -:10565000002009E00578BD4204F10104F5D10CEB0E -:105660000405D618A54201D1BDE8F08115F8018DD9 -:1056700016F801EDF045F5D0E7E700001F2938B531 -:1056800004460D4604D9162303604FF0FF3038BDA1 -:10569000426C12B152F821304BB9204600F030F87C -:1056A0002A4601462046BDE8384000F017B8012BD5 -:1056B0000AD0591C03D1162303600120E7E7002418 -:1056C00042F82540284698470020E0E7024B014673 -:1056D0001868FFF7D3BF00BF2423002038B5074D5B -:1056E00000230446084611462B60FFF7FBF9431CD4 -:1056F00002D12B6803B1236038BD00BFC461002014 -:10570000FFF7EAB9034611F8012B03F8012B002A31 -:10571000F9D170476F72672E6172647570696C6F32 -:10572000742E486F6C7962726F475053000000000E -:1057300053544D3332463F3F3F0053544D3332466E -:105740003430780053544D33324634327800535459 -:105750004D333246343436585800000001203300AF -:105760000010410001105A000310590007103100C9 -:105770000000000030570008130400003A570008EA -:105780001904000044570008210400004E57000887 -:1057900040A2E4F1646891060041A3E5F2656992D4 -:1057A000070000004261642043414E496661636521 -:1057B00020696E6465782E00000100000001FF0082 -:1057C000006400400068004080000000008000008D -:1057D0000000800000000000000000001D24000800 -:1057E000A92C0008B52B00082D240008612400080E -:1057F0005D260008312400084124000835240008F3 -:105800003D240008392400088525000845240008A7 -:10581000A92F00085524000859250008009600000B -:105820000000000000000000000000000000000078 -:1058300000000000394500082545000861450008C2 -:105840004D45000859450008454500083145000808 -:105850001D4500086D4500086330000058580008D9 -:10586000E85E0020F86000200040000000400000DA -:1058700000400000004000000000010000000200A5 -:1058800000000200000002006D61696E0069646C36 -:1058900065000000A001812A00000000AAA9AAAAB0 -:1058A00050000124EFFF0000007700000090090085 -:1058B0001000004A000000009AAAAAAA00000000F6 -:1058C000FBFF000000000000000099000000000045 -:1058D00000000000AAAAAAAA00000000FFFF000022 -:1058E00000000000000000000000000000000000B8 -:1058F000AAAAAAAA00000000FFFF00000000000002 -:10590000000000000000000000000000AAAAAAAAEF -:1059100000000000FFFF0000000000000000000089 -:105920000000000000000000AAAAAAAA00000000CF -:10593000FFFF000000000000000000000000000069 -:1059400000000000AAAAAAAA00000000FFFF0000B1 -:105950000000000000000000000000000000000047 -:105960000A0000000000000003000000000000002A -:1059700000000000ACA8FF7F010000000000000054 -:105980000B04000000000000000007000000000001 -:1059900040420F00FE2A0100D2040000FF00000078 -:1059A000245C0020282300200000000000000000EC -:1059B00000000000000000000000000000000000E7 -:1059C00000000000000000000000000000000000D7 -:1059D00000000000000000000000000000000000C7 -:1059E00000000000000000000000000000000000B7 -:1059F00000000000000000000000000000000000A7 -:085A000000000000000000009E +:1000000000070020F1010008A92C0008612C00085D +:10001000892C0008612C0008812C0008F3010008DD +:10002000F3010008F3010008F30100089D3C0008FB +:10003000F3010008F3010008F3010008F3010008D0 +:10004000F3010008F3010008F3010008F3010008C0 +:10005000F3010008F30100080D50000835500008B6 +:100060005D50000885500008AD500008F3010008FD +:10007000F3010008F3010008F3010008F301000890 +:10008000F3010008F3010008F3010008F12B000858 +:10009000012C0008152C0008F3010008D5500008B9 +:1000A000F3010008F3010008F3010008F301000860 +:1000B000BD510008F3010008F3010008F301000836 +:1000C000F3010008F3010008F3010008F301000840 +:1000D000F3010008F3010008A9510008F30100082A +:1000E00039510008F3010008F3010008F30100088A +:1000F000F3010008F3010008F3010008F301000810 +:10010000F3010008F3010008F3010008F3010008FF +:10011000F3010008F3010008F3010008F3010008EF +:10012000F3010008F3010008F3010008F3010008DF +:10013000F3010008F3010008F3010008292C00086E +:10014000392C00084D2C0008F3010008F3010008C9 +:10015000F3010008F3010008F3010008F3010008AF +:10016000F3010008F3010008F3010008F30100089F +:10017000F3010008F3010008F3010008F30100088F +:10018000F3010008F3010008F3010008F30100087F +:10019000F3010008F3010008F3010008F30100086F +:1001A000F3010008F3010008F3010008F30100085F +:1001B000F3010008F3010008F3010008F30100084F +:1001C000F3010008F3010008F3010008F30100083F +:1001D000F3010008F3010008F3010008F30100082F +:1001E0009D15000800000000000000000000000055 +:1001F00002E000F000F8FEE772B6374880F30888A6 +:10020000364880F3098836483649086040F20000D5 +:10021000CCF200004EF63471CEF200010860BFF35C +:100220004F8FBFF36F8F40F20000C0F2F0004EF628 +:100230008851CEF200010860BFF34F8FBFF36F8F7C +:100240004FF00000E1EE100A4EF63C71CEF20001D4 +:100250000860062080F31488BFF36F8F04F0E0FC81 +:1002600004F072FD4FF055301F491B4A91423CBFCC +:1002700041F8040BFAE71D49184A91423CBF41F886 +:10028000040BFAE71A491B4A1B4B9A423EBF51F82E +:10029000040B42F8040BF8E700201849184A914271 +:1002A0003CBF41F8040BFAE704F0BEFC04F09AFDF1 +:1002B000144C154DAC4203DA54F8041B8847F9E797 +:1002C00000F042F8114C124DAC4203DA54F8041B12 +:1002D0008847F9E704F0A6BC0007002000230020AF +:1002E0000000000808ED00E00001002000070020E9 +:1002F0005056000800230020882300208823002077 +:10030000C8610020E0010008E4010008E4010008E1 +:10031000E40100082DE9F04F2DED108AC1F80CD052 +:10032000C3689D46BDEC108ABDE8F08F002383F3BF +:1003300011882846A047002004F0DCF8FEE704F00E +:1003400065F800DFFEE70000F8B501F099F904F068 +:1003500001FC074604F050FC0546A8BB1F4B9F421A +:1003600032D001339F4232D01D4B27F0FF029A4218 +:1003700030D1F8B200F01EFF2E4642F2107400F0A9 +:100380001FFF08B10024264601F0FEFC20B1032027 +:1003900000F07AF80024264635B1124B9F4203D074 +:1003A00004F022FC00242646002004F0DDFB0EB100 +:1003B00000F080F801F09CFA00F06EFF204600F09B +:1003C000CDF800F077F8F9E72E460024D7E7044689 +:1003D0000126D4E7064640F6C414D0E7010007B072 +:1003E000000008B0263A09B008B501F015F9A0F1EF +:1003F00020035842584108BD07B541F212030221BB +:1004000001A8ADF8043001F025F903B05DF804FB54 +:1004100038B5302383F31188174803680BB104F013 +:1004200027F9164A144800234FF47A7104F016F99C +:10043000002383F31188124C236813B12368013B16 +:100440002360636813B16368013B63600D4D2B78D3 +:1004500033B963687BB9022001F0D8F932236360B5 +:100460002B78032B07D163682BB9022001F0CEF95A +:100470004FF47A73636038BD8823002011040008AC +:10048000A8240020A0230020084B187003280CD8B3 +:10049000DFE800F008050208022001F0ADB90220F3 +:1004A00001F0A0B9024B00225A607047A02300203F +:1004B000A824002010B501F067FC30B1204B0322C6 +:1004C0001A70204B00225A6010BD1F4B1F4A1C4659 +:1004D00019680131F8D004339342F9D162681C4B9A +:1004E0009A42F1D91B4B9B6803F1006303F58033FB +:1004F0009A42E9D204F04CFB04F05EFB002001F0CC +:10050000D9F80220FFF7C0FF134B1A6C00221A64BF +:10051000196E1A66196E596C5A64596E5A665B6E7A +:1005200072B64FF0E0233021C3F8084DD4E9003211 +:1005300081F311889D4683F308881047C4E700BF04 +:10054000A0230020A82400200000010820000108AA +:10055000FFFF000800230020003802402DE9F04F83 +:1005600093B0AC4B00902022FF210AA89D6801F0B7 +:1005700069F9A94A1378A3B9A84801210360117049 +:10058000302383F3118803680BB104F071F8A44A97 +:10059000A24800234FF47A7104F060F8002383F33B +:1005A0001188009B13B19F4B009A1A609E4A009CD1 +:1005B0001378032B1EBF002313709A4A4FF0000AD2 +:1005C00018BF5360D3465646D146012001F014F9B6 +:1005D00024B1944B1B68002B00F01582002001F021 +:1005E0001BF80390039B002B01DA00F0A7FE039B8E +:1005F000002BEDDB012001F0F5F8039B213B162BCE +:10060000E3D801A252F823F0650600088D06000821 +:1006100021070008CB050008CB050008CB05000822 +:10062000AB0700087B09000895080008F7080008D8 +:100630001F09000845090008CB05000857090008F4 +:10064000CB050008C909000805070008CB0500080C +:100650000D0A00087106000805070008CB05000810 +:10066000F70800080220FFF7BFFE002840F0F581E0 +:10067000009B0221BAF1000F08BF1C4605A841F2F9 +:100680001233ADF8143000F0E5FF9EE74FF47A70B6 +:1006900000F0C2FF071EEBDB0220FFF7A5FE0028DB +:1006A000E6D0013F052F00F2DA81DFE807F0030A08 +:1006B0000D10133605230593042105A800F0CAFF89 +:1006C00017E054480421F9E758480421F6E7584850 +:1006D0000421F3E74FF01C08404600F0EDFF08F15D +:1006E00004080590042105A800F0B4FFB8F12C0F10 +:1006F000F2D1012000FA07F747EA0B0B5FFA8BFBF8 +:100700004FF0000901F0EAF826B10BF00B030B2BB8 +:1007100008BF0024FFF770FE57E746480421CDE7E5 +:10072000002EA5D00BF00B030B2BA1D10220FFF75D +:100730005BFE074600289BD0012000F0BBFF022093 +:10074000FFF7A2FE00261FFA86F8404600F0C2FF1F +:10075000044690B10021404600F0D4FF0136002845 +:10076000F1D1BA46044641F21213022105A8ADF8B0 +:1007700014303E4600F06EFF27E70120FFF784FEAD +:100780002546244B9B68AB4207D9284600F094FFCE +:10079000013040F067810435F3E7234B00251D70DD +:1007A000204BBA465D603E46ACE7002E3FF460AF9A +:1007B0000BF00B030B2B7FF45BAF0220FFF764FE03 +:1007C000322000F029FFB0F10008FFF651AF18F019 +:1007D00003077FF44DAF0F4A926808EB050393427D +:1007E0003FF646AFB8F5807F3FF742AF124B01931B +:1007F000B84523DD4FF47A7000F00EFF0390039AA2 +:10080000002AFFF635AF019B039A03F8012B01374D +:10081000EDE700BF00230020A4240020882300204F +:1008200011040008A8240020A02300200423002095 +:10083000082300200C230020A4230020C820FFF759 +:10084000D3FD074600283FF413AF1F2D11D8C5F183 +:10085000200242450AAB25F0030028BF42468349E7 +:100860000192184400F0DCFF019A8048FF2100F05B +:10087000E9FF4FEAA8037D490193C8F387022846A0 +:1008800000F0E8FF064600283FF46DAF019B05EB42 +:10089000830537E70220FFF7A7FD00283FF4E8AE05 +:1008A00000F050FF00283FF4E3AE0027B846704B3D +:1008B0009B68BB4218D91F2F11D80A9B01330ED059 +:1008C00027F0030312AA134453F8203C0593404633 +:1008D000042205A901F010FA04378046E7E73846FC +:1008E00000F0EAFE0590F2E7CDF81480042105A897 +:1008F00000F0B0FE06E70023642104A8049300F092 +:100900009FFE00287FF4B4AE0220FFF76DFD0028A3 +:100910003FF4AEAE049800F0FDFE0590E6E700233C +:10092000642104A8049300F08BFE00287FF4A0AE9D +:100930000220FFF759FD00283FF49AAE049800F01A +:10094000F9FEEAE70220FFF74FFD00283FF490AEE2 +:1009500000F008FFE1E70220FFF746FD00283FF422 +:1009600087AE05A9142000F003FF04210746049078 +:1009700004A800F06FFE3946B9E7322000F04CFEC3 +:10098000071EFFF675AEBB077FF472AE384A926859 +:1009900007EB090393423FF66BAE0220FFF724FDFD +:1009A00000283FF465AE27F003074F44B9453FF4F4 +:1009B000A9AE484600F080FE0421059005A800F08D +:1009C00049FE09F10409F1E74FF47A70FFF70CFDD5 +:1009D00000283FF44DAE00F0B5FE002844D00A9B3D +:1009E00001330BD008220AA9002000F033FF0028B1 +:1009F0003AD02022FF210AA800F024FFFFF7FCFCD8 +:100A00001C4803F07DFD13B0BDE8F08F002E3FF4CD +:100A10002FAE0BF00B030B2B7FF42AAE00236421C7 +:100A200005A8059300F00CFE074600287FF420AED1 +:100A30000220FFF7D9FC804600283FF419AEFFF7EB +:100A4000DBFC41F2883003F05BFD059800F05CFFB1 +:100A5000464600F043FF3C46B7E5064652E64FF0F7 +:100A6000000905E6BA467EE637467CE6A423002068 +:100A700000230020A0860100094A136849F269009A +:100A800099B21B0C00FB01331360064B186844F24B +:100A9000506182B2000C01FB0200186080B2704706 +:100AA000182300201423002010B500211022044632 +:100AB00000F0C8FE034B03CB206061601868A060A3 +:100AC00010BD00BF107AFF1F2DE9F041ADF54E7D3E +:100AD0000DF134086CAC40F2751207460D460EA8B5 +:100AE0000021C8F8001000F0ADFE4FF4C4720021E0 +:100AF000204600F0A7FE02F0DFF8254B4FF47A7293 +:100B0000B0FBF2F0186093E80700022384E80700C6 +:100B10000DF5E9702382FFF7C7FF40F604331D4946 +:100B2000238406A804F05CFC182384F832310DF20B +:100B3000E3266B440DF1300C1A4603CA624530605F +:100B40007160134606F10806F6D14146012220469F +:100B500000F0F4FE00230393AB7E029305F119032A +:100B6000019380B20123CDE904800093E97E06A3BE +:100B7000D3E90023384602F067FC0DF54E7DBDE851 +:100B8000F08100BFAFF300809E6AC421818A46EEE7 +:100B9000B0240020F05300082DE9F0412C4C237ABA +:100BA000DAB080460D465BBB27A9284600F0D6FF89 +:100BB0000746002842D19DF89D60C82E3ED80146C8 +:100BC0004FF4A662204600F03DFE4FF48073C4F857 +:100BD000F8314FF40073C4F80C334FF44073C4F889 +:100BE000203432460DF19E0104F1090000F018FE98 +:100BF00026449DF89C30777223720BB9EB7E2372EA +:100C00008122002106AC27A800F01CFE012221460B +:100C100027A800F0DFFF00230393AB7E029305F1CA +:100C2000190380B201932823CDE904400093E97EA3 +:100C300005A3D3E90023404602F006FC5AB0BDE804 +:100C4000F08100BFAFF3008026417272DF25D7B775 +:100C5000A8560020F0B5254E4FF48A7505FB0065B7 +:100C6000F1B096F8D83085F8DC300024D82221463F +:100C700085F8E8403AA800F0E5FD06F1090000F02B +:100C8000D9FDD5F8E4308DF8F000C2B206AF06F118 +:100C900009010DF1F100CDE93A3400F0C1FD39460A +:100CA00001223AA800F0C2FF80B2CDE90470082307 +:100CB0000127CDE9023706F1D803019330230093D1 +:100CC000317A0B4807A3D3E9002302F0BDFBA04211 +:100CD00006DD01F0F1FFC5F8E000384671B0F0BD67 +:100CE0002046FBE778F6339F93CACD8DA8560020A7 +:100CF000C83400202DE9F04F274FDFF8A880274E99 +:100D000087B0384602F0CCFB034600283DD00024D3 +:100D1000CDE90344ADF81440027B8DF814209968A6 +:100D20004068029403AA03C21B681D4D43F00043B0 +:100D30000293A146A2462B68D3F810B001F0BEFF83 +:100D400010EB080241F100032846CDF800A002A9EB +:100D5000D84704F2364440F66C030028C8BF49F077 +:100D6000010905F586559C4205F11805E3D1B9F155 +:100D7000000F05D0384602F097FB86F800A0C0E7C8 +:100D80003378072B04D80133337007B0BDE8F08FF8 +:100D9000014802F089FBF8E7C8340020DD5B002041 +:100DA000F834002040420F0070B50D4614461E4630 +:100DB00002F0A6FA50B9022E10D1012C0ED112A3C6 +:100DC000D3E90023C5E90023012007E0282C10D037 +:100DD00005D8012C09D0052C0FD0002070BD302C77 +:100DE000FBD10BA3D3E90023ECE70BA3D3E900234A +:100DF000E8E70BA3D3E90023E4E70BA3D3E900233F +:100E0000E0E700BFAFF30080401DA12026812A0B40 +:100E100078F6339F93CACD8D9E6AC421818A46EEAF +:100E200026417272DF25D7B7F017304A39059E5632 +:100E300038B505460E4C0021013500F063FCA4F8DE +:100E40002C55B4F82C0500F045FC78B1B4F82C050D +:100E500000F050FC014648B9B4F82C0500F052FCF3 +:100E6000B4F82C350133A4F82C35EAE738BD00BFBF +:100E7000A8560020F8B50E4C0E4F0226A4F580535C +:100E800043F8487C237E3BB965692DB1284600F0C4 +:100E9000F9FF284604F0E4F9204600F0F3FFA4F53A +:100EA0008654012EA4F1180400D1F8BD0126E5E70F +:100EB00018560020B85400082DE9F04F8FB000AF4D +:100EC00005460C4602F01CFA002849D1237E022B6D +:100ED0001BD1E38A012B18D101F0EEFE0646FFF785 +:100EE000CBFD03464FF4C870DFF8C482B3FBF0F2C9 +:100EF00006F5167602FB103316FA83F3C8F80030B5 +:100F0000E37E33B9A34B00221A703C37BD46BDE8DF +:100F1000F08F07F12401204600F0DEFD0028F4D117 +:100F200007F11400FFF7C0FD97F8264007F1140100 +:100F3000224607F1270004F0DDF90028E2D10F2C4A +:100F400008D8944B1C70D8F80030A3F51673C8F875 +:100F50000030DAE797F82410284602F0C9F9D4E700 +:100F6000E38A282B2BD010D8012B23D0052BCCD1F2 +:100F7000BFF34F8F8849894BCA6802F4E06213437C +:100F8000CB60BFF34F8F00BFFDE7302BBDD1844E48 +:100F9000E17E327A9142B8D1607E3146002291F8EA +:100FA000DC50854200F0A5800132042A01F58A71E7 +:100FB000F5D1AAE721462846FFF786FDA5E7214699 +:100FC0002846FFF7E9FDA0E7B2F8EC507B6005F199 +:100FD00003094FEA99094FEA8902D11DC908A8EB14 +:100FE000C1039D46EB460021584600F02BFC04F15E +:100FF000EE012A463144584600F012FC7B6813B9D2 +:10100000012000F057FB96F8D20000F063FB044685 +:1010100030B9307200F096FB204600F04BFBB1E097 +:10102000D6F8D4203AB996F8D200B6F82C258242E8 +:1010300001D8FFF7FDFED6F8D4202A44944208D206 +:1010400096F8D200B6F82C250130824201D8FFF77D +:10105000EFFE70685FFA89F2594600F0FBFB08B9B1 +:10106000C54679E0726896F8D2002A447260D6F8D4 +:10107000D42005EB0209C6F8D49000F02BFB814583 +:1010800009D396F8D220D6F8D4000132001B86F896 +:10109000D220C6F8D400FF2D0FD80024347200F0FF +:1010A00051FB204600F006FB00F06EFE3D4B188120 +:1010B00008B9FFF7FFF9C54627E7BB6896F8D900DE +:1010C0000AFB0362FB68D2F8E41082F8E83001F50D +:1010D0008061C2F8E030C2F8E410FFF7BBFDFFF713 +:1010E00009FE96F8D920013202F0030286F8D920D1 +:1010F000B6E74FF48A7A0AFB02F505F1EA013144BA +:10110000204600F0BFFDF86000287FF4FEAE3544B5 +:10111000012285F8E82001F0CFFDD5F8E020D6EDDA +:10112000007ADFED216A801A192838BF192040F6AD +:10113000B832904228BF1046B8EE677A07EE900AA0 +:10114000F8EEE77A67EEA67ADFED186AE7EE267A20 +:10115000FCEEE77AC6ED007A96F8D930BB60BA6843 +:1011600073680AFB02F4321992F8E81059B1D2F808 +:10117000E4108B42E8463FF427AF002182F8E810E4 +:10118000C2F8E010C5467368064A9B0A0133138112 +:10119000BBE600BFC134002000ED00E00400FA050A +:1011A000A8560020B0240020CDCCCC3D6666663F1A +:1011B000C4340020014B1870704700BFBC240020CD +:1011C00030B54FF000542B4B22689A4285B007D0BF +:1011D00003F01CFD044620BB0024204605B030BDB2 +:1011E000254B627D25481A70237D03724FF480736E +:1011F000C0F8F8314FF40073C0F80C3300254FF4F9 +:101200004073C0F820341E49C0F8E450C9220930A8 +:1012100000F006FB2046E022294600F013FB0124E3 +:10122000DBE7184A184D136C43F000731364AA6D82 +:10123000164B9A42D0D12B6E013B7E2BCCD8144A50 +:1012400007CA01AB83E807001846032100F06AFDD6 +:101250006B6D83424FF00003BED12A6D8A4201BFFD +:10126000AB65054B2A6E1A7003BF0A4BEA6D1A6014 +:101270001C46B2E79AAD44C5BC240020A856002005 +:101280001600002000380240006600405041A0B027 +:10129000586600401023002037B500F075FD1D4D45 +:1012A0001D4C2881022321681C486B71012201F02A +:1012B00085FB1B48216850F8D83F01225B6898479E +:1012C00000230193174B184900931848184B4FF40B +:1012D000805201F0E5FF174B197811B1134802F065 +:1012E00007F801F0E9FC0446FFF7C6FB4FF4C873AA +:1012F000B0FBF3F202FB130304F5167010FA83F04F +:101300000D4B186003F078FC08B10F232B8103B05C +:1013100030BD00BFB024002010230020F83400208E +:10132000F8440020A90D0008C0240020C834002083 +:10133000B90E0008BC240020C43400202DE9F04F71 +:101340002DED028BDFF8508293B00BAF9FED838BB6 +:10135000FFF7D0FC00230A93ADF834300B937B6089 +:101360000025844CDFF810A22E4601238DF81C3096 +:1013700023688DED008B4FF0000BD3F808908DF8AB +:101380001DB05B460DF11D0207A92046C8479DF818 +:101390001C90B9F1000F24D0D8F8143083F4004326 +:1013A000C8F81430102259460EA800F04BFA2368F2 +:1013B00008AA5E690AA90DF11E032046B04797E806 +:1013C00003000FAB83E803009DF834308DF8443000 +:1013D0000A9B0E930EA9DDE90823504602F042FA5B +:1013E0004E4605F2364540F66C0304F586549D42A0 +:1013F00004F11804B9D1002EB2D15F4801F080FF8A +:10140000002840D15D4D01F057FC2B6898423AD33B +:1014100001F052FC0446FFF72FFB4FF4C873B0FBFA +:10142000F3F202FB130304F5167010FA83F0286040 +:10143000534D8DF828602E7816B901238DF8283089 +:10144000C6F11004E4B20EA8FFF72EFB062C28BF4D +:1014500006240EAB224699190DF1290000F0E0F99F +:101460000AAB0393182302930134464B0193E4B271 +:1014700001230093404804943AA3D3E9002301F0E8 +:1014800085FF00232B7001F017FC3F4A3F4C136887 +:10149000C31AB3F57A7F2FD3106001F00FFC024618 +:1014A0000B46354802F00AF8334801F029FF18B31B +:1014B000237A374D002B14BF032302236B7101F0F5 +:1014C000FBFB0EAE4FF47A730122B0FBF3F0314612 +:1014D0002860284600F0D8FA182302932D4B019378 +:1014E00080B240F25513CDE90360009322481FA358 +:1014F000D3E9002301F04AFF237A93B101F0DCFB2A +:10150000002506464FF48A7794F8D900284400F065 +:10151000030007FB004393F8E82072B10135042D66 +:10152000F2D1C82002F0ECFF237A002B7FF40DAF3C +:1015300013B0BDEC028BBDE8F08FD3F8E02042B1D0 +:101540002368FA2B38BFFA23B21A0533B2EB430FE4 +:10155000E4D3FFF77FFB0028E0D1E2E700000000C2 +:1015600000000000401DA12026812A0BF1C6A7C162 +:10157000D068080FF8340020C8340020C43400209C +:10158000C1340020C0340020D85B0020A8560020C1 +:10159000B0240020DC5B00200004024008B50648AF +:1015A00000F06EFF054800F06BFFBDE80840044AFC +:1015B0000449002003F04EBEF8340020D04500203E +:1015C000305C0020750E000870B5104B1B7801339D +:1015D000DBB2012B0C4612D80D4B1D6829684FF465 +:1015E0007A730E6AA2FB0332014622462846B047B0 +:1015F000844204D1074B00221A70012070BD4FF4C1 +:10160000FA7002F07DFF0020F8E700BF1C230020E5 +:1016100020230020205C002007B500230246012182 +:101620000DF107008DF80730FFF7CEFF20B19DF8D0 +:10163000070003B05DF804FB4FF0FF30F9E700004E +:101640000A4608B50421FFF7BFFF80F00100C0B2D1 +:10165000404208BD30B4074B0A461978064B53F890 +:1016600021402368DD69054B0146AC46204630BC6D +:10167000604700BF205C002020230020A0860100DE +:1016800070B503F011F9094E094D30800024286827 +:101690003388834208D903F001F92B6804440133ED +:1016A000B4F5803F2B60F2D370BD00BF225C0020F8 +:1016B000E05B002003F0A8B900F1006000F5803085 +:1016C0000068704700F10060920000F5803003F080 +:1016D00031B90000054B1A68054B1B889B1A8342E1 +:1016E00002D9104403F0DAB800207047E05B002014 +:1016F000225C0020024B1B68184403F0D7B800BFDF +:10170000E05B0020024B1B68184403F0E7B800BF01 +:10171000E05B002010F003030AD1B0F5047F05D28E +:1017200000F10050A0F51040D0F80038184670477E +:101730000023FBE700F10050A0F51040D0F8100A9C +:1017400070470000064991F8243033B10023086A3D +:1017500081F824300822FFF7B5BF0120704700BF91 +:10176000E45B0020014B1868704700BF002004E0D4 +:1017700070B5194B1D68194B0138C5F30B040844AB +:101780002D0C04221E88A6420BD15C680A46013C3F +:10179000824213460FD214F9016F4EB102F8016B69 +:1017A000F6E7013A03F10803ECD181420B4602D27D +:1017B0002C2203F8012B0A4A05241688AE4204D1D4 +:1017C000984284BF967803F8016B013C02F1040251 +:1017D000F3D1581A70BD00BF002004E04C5400083B +:1017E00038540008022802BF024B4FF000429A61B1 +:1017F000704700BF00040240022802BF024B4FF4B2 +:1018000000429A61704700BF00040240022801BFF5 +:10181000024A536983F40043536170470004024055 +:1018200010B50023934203D0CC5CC4540133F9E7D4 +:1018300010BD000003460246D01A12F9011B002910 +:10184000FAD1704702440346934202D003F8011BC9 +:10185000FAE770472DE9F8431F4D144695F8242008 +:101860000746884652BBDFF870909CB395F8243049 +:101870002BB92022FF2148462F62FFF7E3FF95F89E +:101880002400C0F10802A24228BF2246D6B2414637 +:10189000920005EB8000FFF7C3FF95F82430A41BEE +:1018A0001E44F6B2082E17449044E4B285F8246032 +:1018B000DBD1FFF747FF0028D7D108E02B6A03EB05 +:1018C00082038342CFD0FFF73DFF0028CBD1002019 +:1018D000BDE8F8830120FBE7E45B0020024B1A78A7 +:1018E000024B1A70704700BF205C00201C230020B0 +:1018F00003494FF461430B60024B186802F0ECBCE3 +:101900000C5C002020230020094B10B51422044653 +:1019100000211846FFF796FF064A074B127804602D +:101920000146BDE8104053F8220002F0D5BC00BFCC +:101930000C5C0020205C0020202300202DE9F047D3 +:101940000D46044600219046284640F27912FFF7E2 +:1019500079FF234620220021284601F025FF231D80 +:1019600002222021284601F01FFF631D03222221AD +:10197000284601F019FFA31D03222521284601F066 +:1019800013FF04F1080310222821284601F00CFF60 +:1019900004F1100308223821284601F005FF04F164 +:1019A000110308224021284601F0FEFE04F1120333 +:1019B00008224821284601F0F7FE04F114032022F2 +:1019C0005021284601F0F0FE04F118034022702156 +:1019D000284601F0E9FE04F120030822B021284640 +:1019E00001F0E2FE04F121030822B821284601F0AB +:1019F000DBFE04F12207C0263B463146082228467A +:101A0000083601F0D1FEB6F5A07F07F10107F3D14A +:101A100004F1320308223146284601F0C5FE0027B2 +:101A200004F1330A94F832304FEAC7099F4209F5AE +:101A3000A47615D3B8F1000F08D1314604F5997397 +:101A40000722284601F0B0FE09F24F16274694F807 +:101A500032213B1B93420CD3F01DC008BDE8F08738 +:101A60000AEB070308223146284601F09DFE0137A4 +:101A7000D8E707F2331331460822284601F094FED6 +:101A800008360137E3E7000013B504460846002195 +:101A900001602346C0F803102022019001F084FE6B +:101AA0000198231D0222202101F07EFE0198631D72 +:101AB0000322222101F078FE0198A31D0322252193 +:101AC00001F072FE019804F108031022282101F0B0 +:101AD0006BFE072002B010BDF7B50023047F009114 +:101AE0000E4607221946054601F022FD731C00939D +:101AF000012200230721284601F01AFDC4B9B31CB6 +:101B00000093052223460821284601F011FD0D24EB +:101B10003746B278BB1B934211D32B7FA88A073478 +:101B2000E408BBB9844294BF0020012003B0F0BD9B +:101B3000AB8ADB00083BDB08B3700824E8E7FB1C3A +:101B40000093214600230822284601F0F1FC0834C6 +:101B50000137DEE7201A18BF0120E7E7F7B50023B9 +:101B6000047F00910E4608221946054601F0E0FC6C +:101B7000731CC4B90822009311462346284601F07D +:101B8000D7FC1024012372785F1C013B934211D3D0 +:101B90002B7FA88A0734E408BBB9844294BF002095 +:101BA000012003B0F0BDAB8ADB00083BDB0873709B +:101BB0000824E7E7F319009321460023082228466A +:101BC00001F0B6FC08343B46DDE7201A18BF0120BF +:101BD000E7E70000F8B50E460546144600218122CD +:101BE0003046FFF72FFE2B4608220021304601F039 +:101BF000DBFD7CB96B1C07220821304601F0D4FDC7 +:101C00000F2401236A785F1C013B934204D3E01D3B +:101C1000C008F8BD0824F4E7EB1921460822304635 +:101C200001F0C2FD08343B46ECE70000F8B50E4673 +:101C3000054614460021CE223046FFF703FE2B4610 +:101C400028220021304601F0AFFD7CB905F10803E0 +:101C500008222821304601F0A7FD30242F462A7A99 +:101C60007B1B934204D3E01DC008F8BD2824F5E790 +:101C700007F1090321460822304601F095FD08349A +:101C80000137ECE7F7B5047F00910E4601231022DF +:101C90000021054601F04CFCC4B9B31C0093092295 +:101CA00023461021284601F043FC19243746728848 +:101CB000BB1B9A4211D82B7FA88A0734E408BBB912 +:101CC000844294BF0020012003B0F0BDAB8ADB004A +:101CD000103BDB0873801024E8E73B1D009321468E +:101CE00000230822284601F023FC08340137DEE7F0 +:101CF000201A18BF0120E7E730B5094D0A44914288 +:101D00000DD011F8013B5840082340F30004013B7B +:101D10002C4013F0FF0384EA5000F6D1EFE730BD0A +:101D20002083B8EDF7B54FF0FF33DFF854C0DFF88C +:101D300054E000EB81011A4688421CD050F8044B55 +:101D4000019401AF042417F8015B82EA05620825BB +:101D5000DB18164605F1FF355241002EBCBF83EA61 +:101D60000C0382EA0E0215F0FF05F1D1013C14F0DC +:101D7000FF04E8D1E0E7D843D14303B0F0BD00BF92 +:101D80009336EAA9EBE1F042F7B5384A106851689A +:101D90006B4603C36A4636493648082303F0BAFA4D +:101DA0000446002833D10A25334A106851686B462F +:101DB00003C36A4631492F48082303F0ABFA0446AF +:101DC000002849D00369B3F5E02F45D8B0F8661074 +:101DD00040F20B4291423FD1294A024402F15C0198 +:101DE0008B4239D35C3B234900209E1AFFF784FFC6 +:101DF0003246074604F164010020FFF77DFFA36827 +:101E00009F4229D1E368984208BF002524E0036976 +:101E1000B3F5E02F27D8418B40F20B42914220D1FD +:101E2000174A024402F110018B4218D3103B1149AA +:101E300000209D1AFFF760FF2A46064604F11801AC +:101E40000020FFF759FFA3689E4202D1E368984241 +:101E500001D00D25A8E70025284603B0F0BD1025C8 +:101E6000A2E70C25A0E70B259EE700BF6C540008F5 +:101E7000DCFF0600000001087554000890FF060012 +:101E80000800FFF710B5037C044613B9006803F09F +:101E900029FA204610BD00000023BFF35B8FC3600A +:101EA000BFF35B8FBFF35B8F8360BFF35B8F7047C4 +:101EB000BFF35B8F0068BFF35B8F704770B505465B +:101EC0000C30FFF7F5FF05F1080604463046FFF732 +:101ED000EFFFA04206D930466D68FFF7E9FF2544C1 +:101EE000281A70BD3046FFF7E3FF201AF9E700001B +:101EF00070B50546406898B105F10800FFF7D8FFB6 +:101F000005F10C0604463046FFF7D2FF8442304606 +:101F100094BF6D680025FFF7CBFF013C2C44201ACD +:101F200070BD000038B50C460546FFF7C7FFA0425C +:101F300010D305F10800FFF7BBFF04446868B4FB49 +:101F4000F0F100FB1144BFF35B8F0120AC60BFF3E5 +:101F50005B8F38BD0020FCE72DE9F04114460746B1 +:101F60000D46FFF7C5FF844228BF0446D4B1B846EA +:101F700058F80C6B4046FFF79BFF30442860404602 +:101F80007E68FFF795FF331A9C4203D86C600120EE +:101F9000BDE8F0816B60A41B3B68AB602044E86047 +:101FA0000220F5E72046F3E738B50C460546FFF773 +:101FB0009FFFA04210D305F10C00FFF779FF044406 +:101FC0006868B4FBF0F100FB1144BFF35B8F0120A4 +:101FD000EC60BFF35B8F38BD0020FCE72DE9FF41CB +:101FE000884669460746FFF7B7FF6C4606B204EB22 +:101FF000C6060025B44209D06268206808EB0501D6 +:10200000FFF70EFC636808341D44F3E729463846A1 +:10201000FFF7CAFF284604B0BDE8F081F8B50546D1 +:102020000C300F46FFF744FF05F108060446304622 +:10203000FFF73EFFA042304688BF6C68FFF738FFCD +:10204000201A386020B130462C68FFF731FF204459 +:10205000F8BD000073B5144606460D46FFF72EFF87 +:10206000844228BF04460190DCB101A93046FFF745 +:10207000D5FF019B33B93268C5E90233C5E90024B5 +:1020800001200CE09C4238BF0194286001986860F0 +:102090008442F5D93368AB60241AEC60022002B0A8 +:1020A00070BD2046FBE700002DE9FF410F46694661 +:1020B000FFF7D0FF6C4600B204EBC0050026AC422F +:1020C00009D0D4F8048054F8081BB8194246FFF729 +:1020D000A7FB4644F3E7304604B0BDE8F0810000BA +:1020E00038B50546FFF7E0FF044601462846FFF7EE +:1020F00019FF204638BD000010B4026854681A4623 +:1021000023465DF8044B18470020704700207047B5 +:1021100070470000002070470E20704700F5805087 +:1021200090F8C800C0F340007047000000F58050F0 +:1021300090F9D0007047000000F58050C0F8CC1036 +:1021400001207047F7B50C68BDF8207014F00054FA +:1021500070D10D7B082D6DD8302585F31188456928 +:10216000AE6876010CD4AC68240108D4AC6814F0D5 +:1021700080545DD184F31188204603B0F0BD012462 +:102180000E6804F1180C002EB8BFF6004FEA0C1CC4 +:10219000B4BF46F00406760545F80C600E680FFAE9 +:1021A00084FC16F0804F18BF05EB0C1E05EB0C1CD1 +:1021B0001EBFDEF8806146F00206CEF880610E7B1D +:1021C000CCF8846105EB04158E68C5F88C614E6807 +:1021D000C5F88861DCF8805145F00105CCF88051E4 +:1021E00000EB441641F268052E4405EB4415054406 +:1021F000C6E9002308350E4601F10C0C56F804EB35 +:1022000045F804EB6645F9D1843436882E8000EB1E +:10221000441407F00305267926F00B063543257193 +:10222000002484F31188009700F068FD0120A4E7E2 +:102230000224A5E74FF0FF309FE7000013B500F53B +:1022400080540191E06DFFF753FE1F280AD90199D0 +:10225000E06D2022FFF7C2FEA0F120035842584152 +:1022600002B010BD0020FBE708B5302383F31188CE +:1022700000F58050C06DFFF70FFE002383F3118837 +:1022800008BD0000002202608281426082607047C7 +:1022900010B500220023C0E9002300230446038177 +:1022A0000C30FFF7EFFF204610BD0000F0B50546EB +:1022B00000F580500C4690F8C83013F0040FC3F3BB +:1022C000800108BF114661F3820304F1840680F89F +:1022D000C83005EB461389B01B79D8072ED57AB3E1 +:1022E00019072DD46846FFF7D3FF05EB441303F518 +:1022F000835303F1180703AA10331868596814466A +:1023000003C40833BB422246F7D1186820609B887B +:10231000A380DDE90E23CDE900230123ADF80830C9 +:102320002B686946DB6B2846984705EB46152B79E9 +:102330001A075CBF43F008032B7101E0002AF4D1B7 +:1023400009B0F0BD2DE9F0479A4688B007468846A7 +:102350009146302383F3118807F580546846FFF7D0 +:1023600097FFE06DFFF7AAFD1F282AD9E06D202214 +:102370006946FFF7B5FE202823D103AD444605ABDF +:102380002E4603CE9E4220606160354604F108046B +:10239000F6D130682060B388A380DDE90023C9E965 +:1023A0000023BDF80830AAF80030002383F3118819 +:1023B00053464A464146384608B0BDE8F04700F06B +:1023C0008BBC002080F3118808B0BDE8F0870000C6 +:1023D0002DE9F84F0023C0E90133264B044640F8AD +:1023E000183B0F46FFF74EFF04F12800FFF750FFA0 +:1023F00004F1480804F58255464608353046203633 +:10240000FFF746FFAE42F9D104F580554FF48053F3 +:102410004FF00009C5E91339C5F848800123EE657E +:1024200004F5875804F58456C5F8549085F858305B +:1024300085F86030083608F108084FF0000A4FF0C0 +:10244000000B46E908ABA6F11800FFF71BFF20368A +:1024500046F8289C4645F4D1012F85F8D07002D962 +:10246000054800F023FC054B53F8273063612046F4 +:10247000BDE8F88FB8540008805400089C54000848 +:1024800010B5044B197804464A1C1A70FFF7A0FFD8 +:10249000204610BD2C5C00202DE9F047002950D0CB +:1024A000294B2A4FB7FBF1F599428CBF0A23112320 +:1024B000581EB5FBF3FC03FB1C53C4B22BB102281E +:1024C0000346F5D80020BDE8F0870CF1FF36B6F5DD +:1024D000806FF7D2C4EBC40E0EF103034FEAE30999 +:1024E000C3F3C703A4EB030809F1010A4FF47A759B +:1024F0005FFA88F009FB05555AFA88F8B5FBF8F53C +:10250000B5F5617FC1BF0EF1FF33C3F3C703E01A16 +:10251000C0B25C1C50FA84F40CFB04F4B7FBF4F476 +:10252000A142CFD1013BDBB20F2BCBD80138C0B2D7 +:102530000728C7D80021107116809170D370012030 +:10254000C1E70846BFE700BF3F420F0040787D016A +:1025500070B505460E464FF47A746B695B6803F0FC +:102560000103B34207D04FF47A7001F0C9FF013C78 +:10257000F3D1204670BD0120FCE7000030B5426970 +:10258000936913F0700F16D000230B4C936103F185 +:10259000840200EB421211794D0709D5890707D54E +:1025A000416954F823508D60117941F00401117193 +:1025B0000133032BEBD130BDA454000873B51D4685 +:1025C000436916469A68D207044609D59A680121DC +:1025D0009960C2F34002CDE900650021FFF766FE75 +:1025E00063699A68D1050BD59A684FF48071996038 +:1025F000C2F34022CDE9006501212046FFF756FED7 +:1026000063699A68D2030BD59A684FF48031996058 +:10261000C2F34042CDE9006502212046FFF746FEA5 +:1026200004F58053D3F8CC0010B103681B699847B8 +:10263000204602B0BDE87040FFF7A0BF0C4B10B5BC +:102640001C561B5C012B11D800F038FB50EA01032B +:10265000024602D0421E61F10001064B53F82400ED +:1026600020B1BDE810400B46FFF7A8BF10BD00BF6A +:1026700098540008245C0020F8B5044646690029F7 +:1026800072D106F10C073868800770D006EB01158F +:102690003868D5F8B00110F0040FD5F8B0011ABFB2 +:1026A000C00840F00040400DA061D5F8B0C11CF05A +:1026B000020F1CBF40F08040A061D5F8B40106EBCA +:1026C000011100F00F0084F82400D1F8B801207740 +:1026D000D1F8B801000A6077D1F8B801000CA077F2 +:1026E000D1F8B801000EE077D1F8BC0184F82000E1 +:1026F000D1F8BC01000A84F82100D1F8BC01000C1B +:1027000084F82200D1F8BC11090E84F82310382176 +:10271000396004F1340004F1180104F1240551F882 +:10272000046B40F8046BA942F9D109880180C4E91F +:102730000A2321460023238651F8283B2046DB6BE1 +:10274000984704F5805393F8C820D3F8CC0042F0A2 +:10275000040283F8C82010B103681B69984720461B +:10276000BDE8F840FFF70ABF06F110078BE7F8BD98 +:102770000D4B70B51D561B5C012B0C4612D800F09A +:102780009DFA02460B4652EA030102D0013A63F178 +:102790000003064951F8250020B12146BDE87040EC +:1027A000FFF76ABF70BD00BF98540008245C00208A +:1027B000F0B5302181F31188DFF848C000F583516E +:1027C0000831002404F1840500EB45152E797707C4 +:1027D0000ED4F6060CD5D1E9007697429E4107D279 +:1027E00046695CF82470B7602E7946F004062E71B5 +:1027F0000134032C01F12001E4D1002383F311887B +:10280000F0BD00BFA454000808B5302383F311883D +:10281000FFF7B4FE002383F3118808BDF8B54369C0 +:102820000546986800F0E050B0F1E05F0F4621D017 +:10283000F8B1302383F3118805F583541034002652 +:1028400006F1840305EB43131B791A0706D50136FD +:10285000032E04F12004F3D1012007E05B07F6D436 +:102860002146384600F084FA0028F0D1002383F393 +:102870001188F8BD0120FCE708B5302383F31188E7 +:1028800000F58050C06DFFF719FB002383F311881A +:1028900043090CBF0120002008BD0000F8B51D460B +:1028A000002313700F4606461446FFF7E5FF80F03D +:1028B0000100387025B129463046FFF7AFFF207080 +:1028C000F8BD00002DE9B8410C4615461F4680466C +:1028D00000F0F4F90B462178024609B9287850B186 +:1028E0004046FFF765FFFFF78FFF3B462A4621462C +:1028F000FFF7D4FF0120BDE8B881000038B53023D0 +:1029000083F3118800F580542A4D94F8D030EB5CA5 +:10291000E3B1012B28D0002383F3118894F8C83049 +:10292000DB0712D489B1302383F3118894F8D030B7 +:10293000EB5C33B3012B31D094F8C83043F0010382 +:1029400084F8C830002383F3118838BD1A4B1A6C01 +:1029500042F000721A641A6A42F000721A621A6A2D +:1029600022F000721A62D6E7134B1A6C42F08062B2 +:102970001A641A6A42F080621A621A6A22F080624D +:10298000F0E70321132001F0DBFA0321142001F00A +:10299000D7FA0321152001F0D3FACDE703213F2018 +:1029A00001F0CEFA0321402001F0CAFA03214120B0 +:1029B000F1E700BF94540008003802402DE9F047C9 +:1029C00000F5805588B095F8D030022B0446884633 +:1029D000164600F28180854F57F823200AB947F840 +:1029E0002300D7F800A0C4F80C802674BAF1000FB9 +:1029F00064D095F8D030012B70D001212046FFF72C +:102A00007DFF302383F311886269136823F002038A +:102A100013606269136843F0010313606369002760 +:102A20005F6187F3118801212046FFF791FD00289F +:102A300000F09580E86DFFF72FFA04F58359BA4648 +:102A400009F10809202200216846FEF7FBFE02A8D2 +:102A5000FFF718FCCDF818A06A4609EB07030DF143 +:102A6000180E9446BCE80300F445186059606246AD +:102A700003F10803F5D1DCF80000186020379CF85A +:102A800004201A71602FDDD195F8C8306FF38203EE +:102A9000002785F8C8306A4641462046ADF80070E8 +:102AA000ADF802708DF80470FFF7F6FC636948BB5F +:102AB0004FF400421A6008B0BDE8F08741F2D80038 +:102AC00002F0D0FB814610B15146FFF781FCC7F8F8 +:102AD0000090B9F1000F8CD10020ECE73868036852 +:102AE0001B6B98470146002887D13868FFF706FF1F +:102AF0003868036832465B684146984700287FF48F +:102B00007CAFE9E761221A609DF802309DF803204E +:102B10001B06120402F4702203F040731343BDF845 +:102B20000020C2F3090213439DF804201205022E6F +:102B300002F4E0020CBF4FF0004100211343626930 +:102B40000B43D361636913225A616269136823F0EE +:102B50000103136039462046FFF7FAFC08B96369A0 +:102B6000A6E795F8D030002B39D16169D1F8002261 +:102B700042F00102C1F800226169D1F8002222F47A +:102B80007C5222F00E02C1F800226169D1F80022C5 +:102B900042F46062C1F800226269C2F814326269CC +:102BA000C2F8043262696FF07841C2F80C126269AF +:102BB000C2F840326269C2F844326269C2F8B03287 +:102BC0006269C2F8B432636944F20102C3F81C229C +:102BD0006269D2F8003223F00103C2F8003295F89E +:102BE000C83043F0020385F8C83064E7245C002055 +:102BF00008B50020FFF722FDBDE8084001F082B8CB +:102C000008B500210846FFF7B3FDBDE8084001F014 +:102C100079B8000008B501210020FFF7A9FDBDE843 +:102C2000084001F06FB8000008B50120FFF706FD6D +:102C3000BDE8084001F066B808B500210120FFF7A3 +:102C400097FDBDE8084001F05DB8000008B501211E +:102C50000846FFF78DFDBDE8084001F053B80000BD +:102C600000B59BB0EFF3098168226846FEF7D8FDF6 +:102C7000EFF30583014B9B6BFEE700BF00ED00E027 +:102C800008B5FFF7EDFF000000B59BB0EFF3098139 +:102C900068226846FEF7C4FDEFF30583014B5B6BCA +:102CA000FEE700BF00ED00E0FEE700000FB408B54E +:102CB000029801F0D5FBFEE701F0EABE01F0CCBEC0 +:102CC00013B56C4684E80600031D94E8030083E80E +:102CD0000500012002B010BD73B58568019155B1A2 +:102CE0001B885B0707D4D0E900369B6B9847019A95 +:102CF000C1B23046A847012002B070BDF0B5866869 +:102D000089B005460C465EB1BDF838305B070AD481 +:102D1000D0E900379B6B98472246C1B23846B0478E +:102D2000012009B0F0BD00220023CDE900230023DB +:102D3000ADF808300A4603AB01F108061068516887 +:102D40001C4603C40832B2422346F7D11068206003 +:102D50009288A280FFF7B2FF0423ADF808302B68F9 +:102D6000CDE90001DB6B694628469847D8E70000AB +:102D700030B503680968DD0FB5EBD17F23F06044FF +:102D800021F060424FEAD1700BD0002BB8BFA40CE9 +:102D90000029B8BF920C944202D034BF0120002019 +:102DA00030BD944205D1C1F38070C3F38073834278 +:102DB000F6D194422CBF00200120F1E72DE9F0412B +:102DC000456A15B94162BDE8F0814B6823F0604760 +:102DD000C3F38A464FEAD37EC3F3807816EA23060C +:102DE00038BF3E46AC462B465A68BEEBD27F22F037 +:102DF00060440AD0002A18DAA40CB44217D19D42CC +:102E00000FD10D60DEE71346EEE7A74207D102F0CF +:102E10008044C2F3807242450BD054B1EFE708D230 +:102E2000EDE7CCF800100B60CDE7B44201D0B4421E +:102E3000E5D81A689C46002AE5D11960C3E700006E +:102E40002DE9F047089D01F007044FEAD508224418 +:102E500005F0070500EBD1004FF47F49944201D102 +:102E6000BDE8F08704F0070705F0070A57453E461E +:102E700038BF5646C6F10806111B8E4228BF0E46C3 +:102E8000E10808EBD50E415C13F80EC0B94029FAF1 +:102E900006F721FA0AF1FFB28CEA010147FA0AF7B4 +:102EA00039408CEA010C03F80EC034443544D5E7B0 +:102EB00080EA0120082341F2210201B240000029EA +:102EC00080B203F1FF33B8BF504013F0FF03F4D1D9 +:102ED0007047000038B50C468D18A54200D138BDAA +:102EE00014F8011BFFF7E4FFF7E7000042684AB15E +:102EF000136843604389818901339BB299424381BE +:102F000038BF83811046704770B588B020220446D0 +:102F10000D4668460021FEF795FC20460495FFF714 +:102F2000E5FF024658B16B46054608AE1C4603CC89 +:102F3000B44228606960234605F10805F6D11046C1 +:102F400008B070BD082817D909280CD00A280CD061 +:102F50000B280CD00C280CD00D280CD00E2814BF38 +:102F60004020302070470C207047102070471420FC +:102F7000704718207047202070470000082817D994 +:102F80000C280CD910280CD914280CD918280CD9C5 +:102F900020280CD930288CBF0F200E207047092024 +:102FA00070470A2070470B2070470C2070470D2097 +:102FB000704700002DE9F843078C072F04461ED9FF +:102FC000D0E9029800254FF6FF73C5F12006A5F160 +:102FD000200029FA05F108FA06F628FA00F0314334 +:102FE0000143C9B21846FFF763FF0835402D034679 +:102FF000EBD1E1693A46BDE8F843FFF76BBF4FF606 +:10300000FF70BDE8F883000010B54B6823B9CA8A89 +:1030100063F30902CA8210BD04691A681C60036167 +:10302000C38A013BC3824A60EFE700002DE9F84FF5 +:103030001D46CB8A0F46C3F30901052981469246F6 +:103040000B4630D00020AAB207F11A049EB2042E1B +:103050001FFA80F80FD8904503F1010306D3FB8ACD +:103060000A4462F30903FB8201201AE01AF80060A7 +:10307000E6540130EAE79045F1D2A1F1050B1C239B +:103080007C68BBFBF3F203FB12BB1FFA8BF6002C30 +:1030900045D14846FFF72AFF044638B978606FF0FB +:1030A0000200BDE8F88F4FF00008E6E70026066052 +:1030B0007860ADB24FF0000B454510D90AEB08031C +:1030C000221D13F8011B9155B1B208F101081B290B +:1030D0001FFA88F82BD0454506F10106F1D8FB8A86 +:1030E000C3F30902154465F30903BCE7013292B248 +:1030F0001C462368002BF9D16B1F0B441C21B3FB2A +:10310000F1F301339BB29A42D3D2BBF1000FD0D17D +:103110004846FFF7EBFE20B9C4F800B0BFE7012234 +:10312000E7E7C0F800B05E4620600446C1E74545C9 +:10313000D5D94846FFF7DAFE08B92060AFE7C0F8F6 +:1031400000B0002620600446B6E700002DE9F04FED +:103150002DED028B1C4683B05B69019207468846C1 +:10316000002B00F09A80238C2BB1E269002A00F03A +:103170009480072B35D807F10C00FFF7B7FE054602 +:1031800038B96FF00205284603B0BDEC028BBDE8EC +:10319000F08F14220021FEF755FB228CE16905F126 +:1031A0000800FEF73DFB208C013080B2FFF7E6FE01 +:1031B000FFF7C8FE013880B22084013028746369AB +:1031C000228C1B782A4403F01F0363F03F0348F06E +:1031D00000411372384669602946FFF7EFFD01256B +:1031E000D1E700F10C034FF0000908EE103A4FF060 +:1031F000800A4E464D4618EE100AFFF777FE8346CA +:103200000028BED014220021FEF71CFB002E3AD16C +:10321000019BABF8083002220BF1080E1FFA82FC6A +:103220000CF10100BCF1060F218C80B201D88E4256 +:103230002BD3FFF7A3FEFFF785FE626912780138F2 +:1032400002F01F028E4208BF4FF0400A42EA4912C4 +:103250001BFA80F14AEA020A013048F0004281F884 +:1032600008A08BF81000CBF8042059463846FFF729 +:10327000A5FD238C0135B3422DB289F001094FF031 +:10328000000AB8D17FE70022C6E7E169895D0EF840 +:1032900002100136B6B20132C0E76FF0010572E7E5 +:1032A000F8B515460E463022002104461F46FEF7AB +:1032B000C9FA069B6360B5F5001F079BA76034BF82 +:1032C0006A094FF6FF72A36297B2E66104F110003B +:1032D00000239A4206D800230360A782E382238357 +:1032E000E360F8BD0660013330462036F1E70000A8 +:1032F00003781BB94BB2002BC8BF017070470000A8 +:1033000000787047F8B50C46C969074611B9238C97 +:10331000002B37D1257E1F2D34D8387828BB228C3E +:10332000072A2CD8268A36F003032BD14FF6FF70DC +:10333000FFF7D0FD20F001003102400441EA0561B1 +:10334000400C41EA40254FF6FF7223462946384695 +:10335000FFF7FCFE002807DD626913780133DBB25A +:103360001F2B88BF00231370F8BD218A2D0645EA64 +:10337000012505432046FFF71DFE0246E5E76FF0F5 +:103380000300F1E76FF00100EEE7000070B58AB0CE +:10339000044616460021282268461D46FEF752FACA +:1033A000BDF83830ADF810300F9B05939DF84030D4 +:1033B0008DF81830119B07936946BDF84830ADF879 +:1033C00020302046CDE90265FFF79CFF0AB070BDB2 +:1033D0002DE9F041D36905460C4616460BB9138C0E +:1033E0005BBB377E1F2F28D895F80080B8F1000FFF +:1033F00026D03046FFF7DEFD3378210241EAC331A3 +:1034000041EA0801338A41EA076141EA0341024681 +:10341000334641F080012846FFF798FE00280ADD78 +:103420003378012B07D1726913780133DBB21F2B7C +:1034300088BF00231370BDE8F0816FF00100FAE748 +:103440006FF00300F7E70000F0B58BB004460D46BF +:1034500017460021282268461E46FEF7F3F99DF81C +:103460004C305A1E534253418DF800309DF8403085 +:10347000ADF81030119B05939DF848308DF8183049 +:10348000149B07936A46BDF85430ADF820302946A6 +:103490002046CDE90276FFF79BFF0BB0F0BD0000A0 +:1034A000406A00B104307047436A1A684262026998 +:1034B0001A600361C38A013BC38270472DE9F04162 +:1034C000D0F82080194E14461D464146002709B900 +:1034D000BDE8F081D1E90223A21A65EB030396420D +:1034E00077EB03031ED2036A8B420DD1FFF78CFDED +:1034F000036A1B68036203690B60C38A0161016A86 +:10350000013BC3828846E2E7FFF77EFD0B68C8F8FF +:10351000003003690B60C38A0161013BC382D8F8A4 +:103520000010D4E788460968D1E700BF80841E00F8 +:103530002DE9F04F8BB00D46DDF8509014469B46B8 +:103540008046002800F01981B9F1000F00F01581C4 +:10355000531E3F2B00F21181012A03D1BBF1000F52 +:1035600040F00B810023CDE90833B8F81430B5EBF7 +:10357000C30F4FEAC30703D300200BB0BDE8F08FA1 +:103580002B199F42D8F80C303ABF7F1BFFB2274659 +:103590001BB9D8F81030002B7AD0272D4ED8C5F1A2 +:1035A0002806B7424FF000032CBFF6B23E46009308 +:1035B0002946D8F8080008AB3246FFF741FCA7EBD4 +:1035C000060A35445FFA8AFAB8F8143003F100535A +:1035D000053BDB000493D8F80C3003932821039BB0 +:1035E00013B1BAF1000F2CD1D8F8100040B1BAF1E4 +:1035F000000F05D0009608AB5246691AFFF720FC71 +:1036000038B2002FB8D066070AD00AAB03EBD4015A +:10361000624211F8083C02F00702134101F8083C2D +:10362000082C3CD9102C40F2B580202C40F2B780F9 +:10363000BBF1000F00F09C80082334E0BA4600265E +:10364000C2E7049BE02B28BFE02306930B44AB4268 +:10365000059314D95A1B03980096924534BF5246DD +:10366000D2B2691A08AB04300792FFF7E9FB079A58 +:103670001644AAEB020A1544F6B25FFA8AFA049BD2 +:10368000069A05999B1A0493039B1B680393A6E76C +:103690000093D8F8080008AB3A462946AEE7BBF1DC +:1036A000000F13D00123B4EBC30F6CD0082C12D839 +:1036B0009DF82030621E23FA02F2D50706D54FF09E +:1036C000FF3202FA04F423438DF820309DF82030B5 +:1036D00089F8003051E7102C12D8BDF82030621E56 +:1036E00023FA02F2D10706D54FF0FF3202FA04F4B2 +:1036F0002343ADF82030BDF82030A9F800303CE776 +:10370000202C0FD80899631E21FA03F3DA0705D598 +:103710004FF0FF3202FA04F40C430894089BC9F8F6 +:1037200000302AE7402C2BD0DDE90865611EC4F18A +:103730002102A4F1210326FA01F105FA02F225FA89 +:1037400003F311431943CB0712D50122A4F120033F +:10375000C4F1200102FA03F322FA01F1A24052421D +:1037600043EA010363EB430332432B43CDE90823D0 +:10377000DDE90823C9E90023FFE66FF00100FCE65C +:103780006FF00800F9E6082CA0D9102CB3D9202C32 +:10379000EED8C3E7BBF1000FADD0022383E7BBF146 +:1037A000000FBBD004237EE730B5012A144638BF92 +:1037B0000124402C85B028BF40240025012ACDE9F2 +:1037C000025518D81B788DF8083063070AD004AB6F +:1037D00003EBD405624215F8083C02F0070293405F +:1037E00005F8083C009103462246002102A8FFF795 +:1037F00027FB05B030BD082AE4D9102A03D81B885E +:10380000ADF80830E1E7202A8DBFD3E900231B681B +:103810000293CDE90223D8E710B5CB681BB98B60C2 +:103820000B618B8210BD04691A681C600361C38A36 +:10383000013BC382CA60F0E703064CBFC0F3C0304F +:103840000220704708B50246FFF7F6FF022806D1AE +:103850005306C2F30F2001D100F0030008BDC2F3EC +:103860000740FBE72DE9F04F93B0CDE903230A6849 +:1038700004461046FFF7E0FF022814BFC2F30626F5 +:103880000026002A0D46824680F2F28112F0C049DD +:1038900040F0EE81097B002900F0EA81022803D084 +:1038A0002378B34240F0E781C2F3046306931046E5 +:1038B00002F07F030593FFF7C5FF059B29444FEAFC +:1038C000834848EA0A4848EA4668CE78002300223E +:1038D000CDE90823F309834648EA0008029367D03C +:1038E000059B009302466768534608A92046B847DF +:1038F000002800F0C381276A4FB9414604F10C004B +:10390000FFF702FB074690B96FF0020054E03B69F5 +:1039100098450DD03F68002FF9D1414604F10C00C5 +:10392000FFF7F2FA07460028EED0236A3B602762D1 +:1039300097F817C006F01F08CCF3840CACEB080016 +:103940001FFA80FE0028B8BF0EF12000A8EB0C0380 +:103950001FFA83FED7E90221B8BF00B2002B0793FC +:10396000BEBF0EF120031BB2079352EA010338D009 +:10397000039BDFF824E39A1A049B4FF0000C63EBDF +:10398000010196457CEB01032BD36B7B97F81AE082 +:10399000734519D1029B002B78D0012821DC78686F +:1039A000F8B9DFF8F0C2944570EB010316D337E0A5 +:1039B000276A27B96FF00C0013B0BDE8F08F3B69A0 +:1039C0009845B5D03F68F4E7B24890427CEB0103DC +:1039D00001D30020F0E7029B002BFAD0079B0F2BAE +:1039E00017DCFA7DB30002F0030203F07C031343FB +:1039F000FB7539462046FFF707FB6B7BBB76029BC6 +:103A00003BB9FB7DC3F38402013262F38603FB758D +:103A1000D0E76A7BBB7E9A42DBD1029B002B35D07C +:103A2000B309022B32D0039BBB60049BFB601422C2 +:103A300000210DA8FDF706FF039B0A93049B0B933F +:103A40002B1D0C932B7BADF83EB0013BDBB2ADF8E8 +:103A50003C30069B8DF84230059B8DF8433094F83E +:103A60002C308DF840A083F001038DF844308DF8A0 +:103A70004180A3680AA920469847FB7DC3F38403CD +:103A8000013303F01F039B02FB82A2E7FB7DC6F319 +:103A90004012B2EBD31F40F0F480C3F384034345DC +:103AA00040F0F280029A2B7BB609002A4DD0F20733 +:103AB0005DD4032B40F2EB80039BBB60049BFB6057 +:103AC0002B7BAE1D033BDBB23246394604F10C00C2 +:103AD000FFF7ACFA00280CDA39462046FFF794FAD3 +:103AE000FB7DC3F38403013303F01F039B02FB82BE +:103AF0000AE7DDE90884AB883B834FF6FF73C9F121 +:103B00002000A9F1200228FA09F104FA00F001438B +:103B100024FA02F211431846C9B2FFF7C9F909F1B4 +:103B20000809B9F1400F0346E9D1B8822A7B033A6C +:103B3000D2B23146FFF7CEF9FB7DB882DA43C2F349 +:103B4000C01262F3C713FB7543E786B92E1D013B14 +:103B5000DBB23246394604F10C00FFF767FA002861 +:103B6000BADB2A7BB88A013AD2B23146E2E7F98A57 +:103B7000C1F30901013B0429DAB25BD8281D0023F7 +:103B800007F11B069A4208D910F801CB06F801C0CC +:103B9000013101330529DBB2F4D103990A9104996B +:103BA0000B91934207F11B010C9138BF04337968E4 +:103BB0000D9134BF55FA83F300230E93FB8AADF8C1 +:103BC0003EB0C3F309031A44069B8DF84230059BAF +:103BD0008DF8433094F82C30ADF83C2083F001038D +:103BE0008DF8443000238DF840A08DF841807B6033 +:103BF0002A7BB88A013A291DFFF76CF93B8BB88202 +:103C0000834203D1A3680AA92046984720460AA9FF +:103C1000FFF702FEFB7DBA8AC3F38403013303F08E +:103C20001F039B02FB823B8B9A420CBF00206FF06C +:103C30001000C1E67B68002BAFD0052001E01C30EE +:103C400033461E68002EFAD1091A081D2E1D18448D +:103C500001EB090CBCF11B0F5FFA89F39DD89A4266 +:103C60009BD916F8013B00F8013B09F10109EFE788 +:103C70006FF00900A0E66FF00A009DE66FF00B0000 +:103C80009AE66FF00D0097E66FF00E0094E66FF085 +:103C90000F0091E640420F0080841E00EFF309837D +:103CA00005494A6B22F001024A63683383F30988AD +:103CB000002383F31188704700EF00E0302080F389 +:103CC000118862B60C4B0D4AD96821F4E0610904F1 +:103CD000090C0A43DA60D3F8FC20094942F08072EB +:103CE000C3F8FC200A6842F001020A602022DA7759 +:103CF00083F82200704700BF00ED00E00003FA05E2 +:103D0000001000E010B5302383F311880E4B5B6880 +:103D100013F4006314D0F1EE103AEFF30984683C19 +:103D20004FF08073E361094BDB6B236684F30988F2 +:103D300000F060FB10B1064BA36110BD054BFBE723 +:103D400083F31188F9E700BF00ED00E000EF00E029 +:103D50003F03000842030008026843681143016002 +:103D600003B1184770470000024AD36843F0C0030C +:103D7000D36070470044004010B5054C054A00214F +:103D8000204600F087FA044A044BC4E9972310BD8B +:103D9000345C0020693D00080044004040787D010B +:103DA000234A037C002918BF0A46012B30B5C0F80E +:103DB00068220CD11F4B984209D11F4B196C41F45A +:103DC00000311964196E41F4003119661B6EB2F9A5 +:103DD00004501468D0F86032D0F85C12002D03EB68 +:103DE0005403B3FBF4F3BEBF23F0070503F007034E +:103DF00043EA450394888B60D38843F040030B610A +:103E0000138943F001034B6144F4045343F02C0342 +:103E1000CB6004F4A05400230B60B4F5806F0B68F2 +:103E20004B680CBF7F23FF2380F8643230BD00BF96 +:103E3000F8540008345C0020003802402DE9F041BD +:103E4000D0F85C62F7683368DA0504469DB20DD598 +:103E5000302383F311884FF480610430FFF77CFF37 +:103E60006FF480733360002383F31188302383F36E +:103E7000118804F1040815F02F033AD183F3118857 +:103E8000380615D5290613D5302383F3118804F19C +:103E9000380000F07BF900284EDA0821201DFFF7DA +:103EA0005BFF4FF67F733B40F360002383F3118881 +:103EB0007A0616D56B0614D5302383F31188D4E91E +:103EC00013239A420AD1236C43B127F040073F04E1 +:103ED0001021201D3F0CFFF73FFFF760002383F305 +:103EE0001188D4F86822D36843B3BDE8F041106963 +:103EF00018472B0714D015F0080F0CBF00214FF402 +:103F00008071E80748BF41F02001AA0748BF41F08F +:103F100040016B0748BF41F080014046FFF71CFF9E +:103F2000AD06736805D594F864122046194000F078 +:103F3000E1F93568ADB29EE77060B6E7BDE8F081A3 +:103F400000F1604303F561430901C9B283F800132E +:103F5000012200F01F039A4043099B0003F16043D4 +:103F600003F56143C3F880211A607047F8B5154620 +:103F700082680669AA420B46816938BF8568761A4D +:103F8000B54204460BD218462A46FDF749FCA36900 +:103F90002B44A361A3685B1BA3602846F8BD0CD922 +:103FA00018463246FDF73CFCAF1BE1683A46304408 +:103FB000FDF736FCE3683B44EBE718462A46FDF77D +:103FC0002FFCE368E5E7000083689342F7B51546E8 +:103FD000044638BF8568D0E90460361AB5420BD272 +:103FE0002A46FDF71DFC63692B446361A3682846DC +:103FF0005B1BA36003B0F0BD0DD932460191FDF704 +:104000000FFC0199E068AF1B3A463144FDF708FC0C +:10401000E3683B44E9E72A46FDF702FCE368E4E78E +:1040200010B50A440024C361029B8460C0E900000B +:10403000C0E90511C1600261036210BD08B5D0E995 +:104040000532934201D1826882B98268013282606E +:104050005A1C42611970D0E904329A4224BFC368E5 +:104060004361002100F068FA002008BD4FF0FF30E6 +:10407000FBE7000070B5302304460E4683F3118839 +:10408000A568A5B1A368A269013BA360531CA36105 +:1040900015782269934224BFE368A361E3690BB1F9 +:1040A00020469847002383F31188284607E03146CD +:1040B000204600F031FA0028E2DA85F3118870BD5D +:1040C0002DE9F74F04460E4617469846D0F81C9047 +:1040D0004FF0300A8AF311884FF0000B154665B196 +:1040E0002A4631462046FFF741FF034660B9414664 +:1040F000204600F011FA0028F1D0002383F3118844 +:10410000781B03B0BDE8F08FB9F1000F03D0019028 +:104110002046C847019B8BF31188ED1A1E448AF391 +:104120001188DCE7C0E90511C160C3611144009B3F +:104130008260C0E90000016103627047F8B504467F +:104140000D461646302383F31188A768A7B1A368EC +:10415000013BA36063695A1C62611D70D4E904329B +:104160009A4224BFE3686361E3690BB12046984734 +:10417000002080F3118807E03146204600F0CCF99A +:104180000028E2DA87F31188F8BD0000D0E90523A2 +:104190009A4210B501D182687AB982680132826090 +:1041A0005A1C82611C7803699A4224BFC3688361E8 +:1041B000002100F0C1F9204610BD4FF0FF30FBE7B1 +:1041C0002DE9F74F04460E4617469846D0F81C9046 +:1041D0004FF0300A8AF311884FF0000B154665B195 +:1041E0002A4631462046FFF7EFFE034660B94146B6 +:1041F000204600F091F90028F1D0002383F31188C4 +:10420000781B03B0BDE8F08FB9F1000F03D0019027 +:104210002046C847019B8BF31188ED1A1E448AF390 +:104220001188DCE7026843681143016003B1184755 +:10423000704700001430FFF743BF00004FF0FF331A +:104240001430FFF73DBF00003830FFF7B9BF000062 +:104250004FF0FF333830FFF7B3BF00001430FFF7E3 +:1042600009BF00004FF0FF311430FFF703BF00001B +:104270003830FFF763BF00004FF0FF323830FFF7F0 +:104280005DBF0000012914BF6FF0130000207047CC +:10429000FFF772BD37B515460E4A02600022426034 +:1042A000C0E902220122044602740B46009000F18C +:1042B0005C014FF480721430FFF7B2FE00942B467D +:1042C0004FF4807204F5AE7104F13800FFF72AFF55 +:1042D00003B030BD0C55000810B53023044683F3FD +:1042E0001188FFF75DFD02232374002080F31188FD +:1042F00010BD000038B5C36904460D461BB9042142 +:104300000844FFF78FFF294604F11400FFF796FEDB +:10431000002806DA201D4FF40061BDE83840FFF7A1 +:1043200081BF38BD00230375826803691B689968E3 +:104330009142FBD25A680360426010605860704737 +:1043400000230375826803691B6899689142FBD852 +:104350005A680360426010605860704708B50846AC +:10436000302383F311880B7D032B05D0042B0DD054 +:104370002BB983F3118808BD8B6900221A604FF0B6 +:10438000FF338361FFF7CEFF0023F2E7D1E900326C +:1043900013605A60F3E70000FFF7C4BF054BD9680C +:1043A0000875186802681A60536001220275D860A7 +:1043B000FBF7B0BFA05E002030B50C4BDD684B1C96 +:1043C00087B004460FD02B46094A684600F046F9EC +:1043D0002046FFF7E3FF009B13B1684600F048F961 +:1043E000A86907B030BDFFF7D9FFF9E7A05E00204C +:1043F0005D430008044B1A68DB6890689B6898422C +:1044000094BF002001207047A05E0020084B10B52B +:104410001C68D86822681A60536001222275DC602B +:10442000FFF78EFF01462046BDE81040FBF772BF44 +:10443000A05E002038B5074C074908480123002535 +:104440002370656000F028FC0223237085F3118837 +:1044500038BD00BF0861002038550008A05E00206C +:1044600008B572B6044B186500F0E2FA00F08EFB56 +:10447000024B03221A70FEE7A05E002008610020B4 +:1044800000F02CB98B60022308618B8208467047CC +:104490008368A3F1840243F8142C026943F8442C86 +:1044A000426943F8402C094A43F8242CC26843F877 +:1044B000182C022203F80C2C002203F80B2C044ABF +:1044C00043F8102CA3F12000704700BF2D03000813 +:1044D000A05E002008B5FFF7DBFFBDE80840FFF74E +:1044E0005BBF0000024BDB6898610F20FFF756BFEF +:1044F000A05E0020302383F31188FFF7F3BF000094 +:1045000008B50146302383F311880820FFF754FFD4 +:10451000002383F3118808BD064BDB6839B142687C +:1045200018605A60136043600420FFF745BF4FF0E6 +:10453000FF307047A05E00200368984206D01A68DA +:104540000260506099611846FFF726BF704700006F +:1045500010B503689C68A2420CD85C688A600B6046 +:104560004C602160596099688A1A9A604FF0FF3355 +:10457000836010BD1B68121BECE700000A2938BFDE +:104580000A2170B504460D460A26601900F07EFB2C +:1045900000F06AFB041BA54203D8751C2E46044696 +:1045A000F3E70A2E04D9BDE87040012000F0B4BB47 +:1045B00070BD0000F8B5144B0D46D96103F1100130 +:1045C00041600A2A1969826038BF0A220160486086 +:1045D0001861A818144600F04BFB0A2700F044FBB2 +:1045E000431BA342064606D37C1C281900F04EFB51 +:1045F00027463546F2E70A2F04D9BDE8F8400120E6 +:1046000000F08ABBF8BD00BFA05E0020F8B50646EA +:104610000D4600F029FB0F4A134653F8107F9F42C6 +:1046200006D12A4601463046BDE8F840FFF7C2BF32 +:10463000D169BB68441A2C1928BF2C46A34202D961 +:104640002946FFF79BFF224631460348BDE8F84064 +:10465000FFF77EBFA05E0020B05E002010B4C0E96E +:10466000032300235DF8044B4361FFF7CFBF000035 +:1046700010B5194C236998420DD0D0E900328168F9 +:1046800013605A609A680A449A60002303604FF0EE +:10469000FF33A36110BD2346026843F8102F536017 +:1046A0000022026022699A4203D1BDE8104000F066 +:1046B000E7BA936881680B44936000F0D5FA2269E9 +:1046C000E1699268441AA242E4D91144BDE810405D +:1046D000091AFFF753BF00BFA05E00202DE9F04785 +:1046E000DFF8BC8008F110072C4ED8F8105000F00D +:1046F000BBFAD8F81C40AA68031B9A423ED814445F +:10470000D5E900324FF00009C8F81C4013605A6028 +:10471000C5F80090D8F81030B34201D100F0B0FADB +:1047200089F31188D5E9033128469847302383F36C +:1047300011886B69002BD8D000F096FA6A69A0EB5B +:1047400004094A4582460DD2022000F0E5FA002213 +:10475000D8F81030B34208D151462846BDE8F0479A +:10476000FFF728BF121A2244F2E712EB090938BFFB +:104770004A4629463846FFF7EBFEB5E7D8F8103031 +:10478000B34208D01444211AC8F81C00A960BDE83F +:10479000F047FFF7F3BEBDE8F08700BFB05E002032 +:1047A000A05E002038B500F05FFA054AD2E908455E +:1047B000031B181945F10001C2E9080138BD00BF0B +:1047C000A05E002000207047FEE700007047000058 +:1047D0004FF0FF3070470000BFF34F8F024AD3689D +:1047E000DB03FCD4704700BF003C024008B5094B16 +:1047F0001B7873B9FFF7F0FF074B1A69002ABFBF98 +:10480000064A5A6002F188325A601A6822F48062BD +:104810001A6008BD10610020003C0240230167457A +:1048200008B50B4B1B7893B9FFF7D6FF094B1A69F4 +:1048300042F000421A611A6842F480521A601A6803 +:1048400022F480521A601A6842F480621A6008BD2D +:1048500010610020003C02400728F0B516D80C4C2F +:104860000C4923787BB90C4D0E4608234FF00062AB +:1048700055F8047B46F8042B013B13F0FF033A4440 +:10488000F6D10123237051F82000F0BD0020FCE791 +:10489000346100201461002044550008014B53F896 +:1048A000200070474455000808207047072810B5BD +:1048B000044601D9002010BDFFF7CEFF064B53F888 +:1048C00024301844C21A0BB90120F4E712680132EF +:1048D000F0D1043BF6E700BF44550008072810B5A7 +:1048E000044621D8FFF778FFFFF780FF0F4AF32334 +:1048F000D360C300DBB243F4007343F002031361DF +:10490000136943F480331361FFF766FFFFF7A4FFD9 +:10491000074B53F8241000F035F9FFF781FF2046CC +:10492000BDE81040FFF7C2BF002010BD003C0240B0 +:1049300044550008F8B512F00103144642D1851819 +:104940002E4A954257D82E4B1B6813F0010352D0C4 +:104950002C4DFFF74BFFF323EB60FFF73DFF40F2D9 +:104960000127032C15D824F001046618254C401AA1 +:1049700040F20117B142236900EB010524D123F075 +:1049800001032361FFF74CFF0120F8BD043C043014 +:10499000E7E78307E7D12B6923F440732B612B6989 +:1049A0003B432B6151F8046B0660BFF34F8FFFF759 +:1049B00013FF03689E42E9D02B6923F001032B61AA +:1049C000FFF72EFF0020E0E723F440732361236903 +:1049D0003B4323610B882B80BFF34F8FFFF7FCFE17 +:1049E0002D8831F8023BADB2AB42C3D0236923F02E +:1049F00001032361E4E71846C7E700BF0000080889 +:104A000000380240003C0240084908B50B7828B144 +:104A10001BB9FFF7EBFE01230B7008BD002BFCD088 +:104A2000BDE808400870FFF7FBBE00BF1061002022 +:104A30000149024800F0A8B800FF0300000100206F +:104A40000846114600F030BC012000F02DBC0000EB +:104A5000084600F047BC000038B5EFF311859DB95A +:104A6000EFF30584C4F30804302334B183F31188D1 +:104A7000FFF798FE85F3118838BD83F31188FFF79F +:104A800091FE84F3118838BDBDE83840FFF78ABE37 +:104A900038B5FFF7E1FF114C114AC00840EA4170F8 +:104AA000A0FB025EC908A0FB040C1CEB050CA1FBDB +:104AB00004404FF000035B41A1FB02121CEB040C0D +:104AC00043EB000011EB0E0142F10002411842F1EC +:104AD0000000090941EA007038BD00BFCFF753E379 +:104AE000A59BC42010B50244064BD2B2904200D11F +:104AF00010BD441C00B253F8200041F8040BE0B292 +:104B0000F4E700BF502800400F4B30B51C6F240461 +:104B100007D41C6F44F400741C671C6F44F40044F9 +:104B20001C670A4C236843F4807323600244084BDB +:104B3000D2B2904200D130BD441C00B251F8045BA7 +:104B400043F82050E0B2F4E7003802400070004023 +:104B50005028004007B5012201A90020FFF7C2FF3D +:104B6000019803B05DF804FB13B50446FFF7F2FFAC +:104B7000A04205D0012201A900200194FFF7C4FF43 +:104B800002B010BD70470000704700007047000081 +:104B9000074B45F255521A6002225A6040F6FF72E6 +:104BA0009A604CF6CC421A60024B01221A70704790 +:104BB000003000403C610020034B1B781BB1034BCD +:104BC0004AF6AA221A6070473C610020003000407B +:104BD000034B1A681AB9034AD2F874281A6070474E +:104BE0003861002000300240024B4FF08072C3F861 +:104BF000742870470030024008B5FFF7E9FF024B08 +:104C00001868C0F3407008BD3861002008B5FFF790 +:104C1000DFFF024B1868C0F3007008BD3861002048 +:104C200070470000FEE700000A4B0B480B4A904219 +:104C30000BD30B4BDA1C121AC11E22F003028B425B +:104C400038BF00220021FCF7FDBD53F8041B40F8DB +:104C5000041BECE7D8560008C8610020C86100209A +:104C6000C861002000F0CAB84FF08043586A70470E +:104C70004FF08043002258631A610222DA607047C5 +:104C80004FF080430022DA60704700004FF080430D +:104C900058637047FEE7000070B51B4B01630025A9 +:104CA000044686B0586085620E46FFF707F804F1A7 +:104CB0001003C4E904334FF0FF33C4E90635C4E9F7 +:104CC0000044A560E562FFF7CFFF2B460246C4E92A +:104CD000082304F134010D4A256580232046FFF79F +:104CE000D1FB0123E0600A4A0375009272680192C9 +:104CF000B268CDE90223074B6846CDE90435FFF7DA +:104D0000E9FB06B070BD00BF0861002064550008D3 +:104D100069550008954C0008024AD36A1843D062CE +:104D2000704700BFA05E00204B6843608B688360C3 +:104D3000CB68C3600B6943614B6903628B69436253 +:104D40000B6803607047000008B5234B23481A69BD +:104D500042F0FF021A611A6922F0FF021A611A6911 +:104D60001A6B42F0FF021A631A6D42F0FF021A65D5 +:104D70001B4A1B6D1146FFF7D7FF02F11C0100F51E +:104D80008060FFF7D1FF02F1380100F58060FFF786 +:104D9000CBFF02F1540100F58060FFF7C5FF02F17F +:104DA000700100F58060FFF7BFFF02F18C0100F594 +:104DB0008060FFF7B9FF02F1A80100F58060FFF7FE +:104DC000B3FF02F1C40100F58060FFF7ADFFBDE85D +:104DD000084000F08DB800BF0038024000000240DB +:104DE0007055000808B500F019FAFFF723FBBDE87D +:104DF0000840FFF7EDBE0000704700000F4B1A6C33 +:104E000042F001021A641A6E42F001021A660C4A5C +:104E10001B6E936843F0010393604FF0804331228F +:104E20009A624FF0FF32DA6200229A615A63DA60C6 +:104E30005A6001225A611A60704700BF0038024070 +:104E4000002004E04FF0804208B51169D3680B40A0 +:104E5000D9B2C9439B07116107D5302383F3118869 +:104E6000FFF70EFB002383F3118808BD1E4B1A6960 +:104E700062F0FF021A611A69D2B21A614FF0FF3074 +:104E80001A695A69586100215A6959615A691A6A3E +:104E900062F080521A621A6A02F080521A621A6A2A +:104EA0005A6A58625A6A59625A6A1A6C42F08052B7 +:104EB0001A641A6E42F080521A661A6E0B4A106813 +:104EC00040F480701060186F00F44070B0F5007FFF +:104ED0001EBF4FF4803018671967536823F40073BE +:104EE000536000F073B900BF00380240007000400A +:104EF0003B4B3C4A1A643C4A4FF4404111601A68EB +:104F000042F001021A601A689007FCD59A6822F0F4 +:104F100003029A60324B9A6812F00C02FBD11968B6 +:104F200001F0F90119609A601A6842F480321A603F +:104F30001A689103FCD55A6F42F001025A67284B58 +:104F40005A6F9207FCD5294A5A601A6842F080725B +:104F50001A60254A53685804FCD5214B1A68910100 +:104F6000FCD5234AC3F884201A6842F080621A6094 +:104F70001A681201FCD51F4A9A600322C3F88C20DC +:104F80004FF00062C3F894201B4B1A681B4B9A42E7 +:104F90001B4B21D11B4A11681B4A91421CD140F284 +:104FA00003121A60164A136803F00F03032BFAD199 +:104FB0000B4B9A6842F002029A609A6802F00C0267 +:104FC000082AFAD15A6C42F480425A645A6E42F46A +:104FD00080425A665B6E704740F20372E1E700BFA1 +:104FE0000038024000040010007000400819400220 +:104FF0001030002400948838002004E01164002060 +:10500000003C024000ED00E041C20F41074A08B5F4 +:10501000536903F00103536123B1054A13680BB1CF +:1050200050689847BDE80840FEF76CBE003C014060 +:1050300040610020074A08B5536903F00203536139 +:1050400023B1054A93680BB1D0689847BDE8084082 +:10505000FEF758BE003C014040610020074A08B5F9 +:10506000536903F00403536123B1054A13690BB17B +:1050700050699847BDE80840FEF744BE003C014037 +:1050800040610020074A08B5536903F008035361E3 +:1050900023B1054A93690BB1D0699847BDE8084030 +:1050A000FEF730BE003C014040610020074A08B5D1 +:1050B000536903F01003536123B1054A136A0BB11E +:1050C000506A9847BDE80840FEF71CBE003C01400E +:1050D00040610020164B10B55C6904F478725A6187 +:1050E000A30604D5134A936A0BB1D06A98476006A9 +:1050F00004D5104A136B0BB1506B9847210604D5A9 +:105100000C4A936B0BB1D06B9847E20504D5094A62 +:10511000136C0BB1506C9847A30504D5054A936CEA +:105120000BB1D06C9847BDE81040FEF7EBBD00BF57 +:10513000003C014040610020194B10B55C6904F44B +:105140007C425A61620504D5164A136D0BB1506D4D +:105150009847230504D5134A936D0BB1D06D98473A +:10516000E00404D50F4A136E0BB1506E9847A104AA +:1051700004D50C4A936E0BB1D06E9847620404D5E7 +:10518000084A136F0BB1506F9847230404D5054AA2 +:10519000936F0BB1D06F9847BDE81040FEF7B2BDDA +:1051A000003C01404061002008B50348FEF746FE80 +:1051B000BDE80840FEF7A6BD345C002008B5FFF747 +:1051C00041FEBDE80840FEF79DBD0000062108B580 +:1051D0000846FEF7B5FE06210720FEF7B1FE0621C0 +:1051E0000820FEF7ADFE06210920FEF7A9FE0621E4 +:1051F0000A20FEF7A5FE06211720FEF7A1FE0621D4 +:105200002820FEF79DFE07211C20FEF799FEBDE831 +:1052100008400C212620FEF793BE000008B5FFF7DA +:1052200025FE00F009F8FFF733F8FFF7E5FDBDE8CC +:105230000840FFF717BD00000023054A1946013357 +:10524000102BC2E9001102F10802F8D1704700BF2B +:10525000406100200B460146184600F02DB80000C2 +:1052600000F040B8012838BF012010B504462046A0 +:1052700000F030F830B900F007F808B900F00CF889 +:105280008047F4E710BD0000024B1868BFF35B8F46 +:10529000704700BFC061002008B5062000F084F808 +:1052A0000120FFF791FA0000024B0A4601461868F8 +:1052B000FFF7C6BB2423002010B5054C13462CB1C4 +:1052C0000A4601460220AFF3008010BD2046FCE7ED +:1052D00000000000024B01461868FFF7B5BB00BF95 +:1052E00024230020024B01461868FFF7B1BB00BF22 +:1052F0002423002010B501390244904201D100203E +:1053000005E0037811F8014FA34201D0181B10BD2E +:105310000130F2E72DE9F041A3B1C91A1778014431 +:10532000044603F1FF3C8C42204601D9002009E0ED +:105330000578BD4204F10104F5D10CEB0405D61843 +:10534000A54201D1BDE8F08115F8018D16F801EDF7 +:10535000F045F5D0E7E700001F2938B504460D46B3 +:1053600004D9162303604FF0FF3038BD426C12B1F0 +:1053700052F821304BB9204600F030F82A46014659 +:105380002046BDE8384000F017B8012B0AD0591C60 +:1053900003D1162303600120E7E7002442F82540EB +:1053A000284698470020E0E7024B01461868FFF7BF +:1053B000D3BF00BF2423002038B5074D0023044687 +:1053C000084611462B60FFF703FA431C02D12B68F5 +:1053D00003B1236038BD00BFC4610020FFF7F2B9FC +:1053E000034611F8012B03F8012B002AF9D170476D +:1053F0006F72672E6172647570696C6F742E486F7E +:105400006C7962726F4750530000000053544D3363 +:1054100032463F3F3F0053544D33324634307800DC +:1054200053544D3332463432780053544D33324660 +:105430003434365858000000012033000010410079 +:1054400001105A000310590007103100000000003D +:105450000C5400081304000016540008190400003E +:1054600020540008210400002A54000840A2E4F15E +:10547000646891060041A3E5F265699207000000A7 +:105480004261642043414E496661636520696E64F0 +:1054900065782E00000100000001FF00006400405C +:1054A00000680040800000000080000000008000D4 +:1054B0000000000000000000F9200008BD290008DD +:1054C000C5280008392100084521000845230008A7 +:1054D00009210008192100080D21000815210008E4 +:1054E00011210008692200081D210008C12C0008B4 +:1054F0002D2100083D220008009600000000000059 +:10550000000000000000000000000000000000009B +:10551000514200083D4200087942000865420008F7 +:10552000714200085D420008494200083542000807 +:10553000854200086330000034550008F85E002002 +:105540000861002000400000004000000040000012 +:105550000040000000000100000002000000020006 +:10556000000002006D61696E0069646C65000000F6 +:10557000A001812A00000000AAA9AAAA50000124C3 +:10558000EFFF000000770000009009001000004AC3 +:10559000000000009AAAAAAA00000000FBFF000079 +:1055A0000000000000009900000000000000000062 +:1055B000AAAAAAAA00000000FFFF00000000000045 +:1055C000000000000000000000000000AAAAAAAA33 +:1055D00000000000FFFF00000000000000000000CD +:1055E0000000000000000000AAAAAAAA0000000013 +:1055F000FFFF0000000000000000000000000000AD +:1056000000000000AAAAAAAA00000000FFFF0000F4 +:10561000000000000000000000000000000000008A +:10562000AAAAAAAA00000000FFFF000000000000D4 +:105630000000000000000000000000000A00000060 +:105640000000000003000000000000000000000057 +:105650000B04000000000000000007000000000034 +:1056600040420F00FE2A0100D2040000FF000000AB +:10567000345C00202823002000000000000000000F +:10568000000000000000000000000000000000001A +:10569000000000000000000000000000000000000A +:1056A00000000000000000000000000000000000FA +:1056B00000000000000000000000000000000000EA +:1056C00000000000000000000000000000000000DA +:0856D0000000000000000000D2 :00000001FF diff --git a/Tools/bootloaders/MatekL431-ADSB_bl.bin b/Tools/bootloaders/MatekL431-ADSB_bl.bin index 017ff999e0d358..fee5d2e5315095 100755 Binary files a/Tools/bootloaders/MatekL431-ADSB_bl.bin and b/Tools/bootloaders/MatekL431-ADSB_bl.bin differ diff --git a/Tools/bootloaders/MatekL431-ADSB_bl.hex b/Tools/bootloaders/MatekL431-ADSB_bl.hex index 5718b9a9ff16fd..e456865cec53c7 100644 --- a/Tools/bootloaders/MatekL431-ADSB_bl.hex +++ b/Tools/bootloaders/MatekL431-ADSB_bl.hex @@ -1,1160 +1,1109 @@ :020000040800F2 -:1000000000090020B5040008C52500087D2500086A -:10001000A52500087D2500089D250008B7040008D7 -:10002000B7040008B7040008B7040008B935000891 -:10003000B7040008B7040008B7040008B7040008B4 -:10004000B7040008B7040008B7040008B7040008A4 -:10005000B7040008B7040008554300087D430008B2 -:10006000A5430008CD430008F5430008B704000885 -:10007000B7040008B7040008B7040008B704000874 -:10008000B7040008B7040008B704000831250008C9 -:100090005D2500086D250008B70400081D44000810 -:1000A000B7040008B7040008B7040008B704000844 -:1000B000F1440008B7040008B7040008B7040008BA -:1000C000B7040008B7040008B7040008B704000824 -:1000D000B7040008B7040008B7040008B704000814 -:1000E00081440008B7040008B7040008B7040008FA -:1000F000B7040008B7040008B7040008B7040008F4 -:10010000B7040008B7040008B7040008B7040008E3 -:10011000B7040008B7040008B7040008B7040008D3 -:10012000B7040008B7040008B7040008B7040008C3 -:10013000B7040008B7040008B7040008B7040008B3 -:10014000B7040008B7040008B7040008B7040008A3 -:10015000B7040008B7040008B7040008B704000893 -:10016000B7040008B7040008B7040008B704000883 -:10017000B7040008B7040008B7040008B704000873 -:10018000B7040008B7040008B7040008B704000863 -:10019000B7040008B7040008B7040008B704000853 -:1001A000091200080000000000000000000000002C -:1001B00053B94AB9002908BF00281CBF4FF0FF31CE -:1001C0004FF0FF3000F074B9ADF1080C6DE904CECA -:1001D00000F006F8DDF804E0DDE9022304B0704722 -:1001E0002DE9F047089D04468E46002B4DD18A42EA -:1001F000944669D9B2FA82F252B101FA02F3C2F11D -:10020000200120FA01F10CFA02FC41EA030E9440AD -:100210004FEA1C48210CBEFBF8F61FFA8CF708FBCE -:1002200016E341EA034306FB07F199420AD91CEBA6 -:10023000030306F1FF3080F01F81994240F21C81D8 -:10024000023E63445B1AA4B2B3FBF8F008FB103320 -:1002500044EA034400FB07F7A7420AD91CEB040455 -:1002600000F1FF3380F00A81A74240F20781644425 -:10027000023840EA0640E41B00261DB1D4400023AA -:10028000C5E900433146BDE8F0878B4209D9002D0E -:1002900000F0EF800026C5E9000130463146BDE898 -:1002A000F087B3FA83F6002E4AD18B4202D3824202 -:1002B00000F2F980841A61EB030301209E46002DB1 -:1002C000E0D0C5E9004EDDE702B9FFDEB2FA82F206 -:1002D000002A40F09280A1EB0C014FEA1C471FFA64 -:1002E0008CFE0126200CB1FBF7F307FB131140EA4B -:1002F00001410EFB03F0884208D91CEB010103F118 -:10030000FF3802D2884200F2CB804346091AA4B2D9 -:10031000B1FBF7F007FB101144EA01440EFB00FEAD -:10032000A64508D91CEB040400F1FF3102D2A64512 -:1003300000F2BB800846A4EB0E0440EA03409CE7B1 -:10034000C6F12007B34022FA07FC4CEA030C20FA5E -:1003500007F401FA06F31C43F9404FEA1C4900FA7E -:1003600006F3B1FBF9F8200C1FFA8CFE09FB1811FB -:1003700040EA014108FB0EF0884202FA06F20BD96E -:100380001CEB010108F1FF3A80F08880884240F2BE -:100390008580A8F102086144091AA4B2B1FBF9F002 -:1003A00009FB101144EA014100FB0EFE8E4508D9FD -:1003B0001CEB010100F1FF346CD28E456AD9023882 -:1003C000614440EA0840A0FB0294A1EB0E01A14267 -:1003D000C846A64656D353D05DB1B3EB080261EBD5 -:1003E0000E0101FA07F722FA06F3F1401F43C5E9AF -:1003F000007100263146BDE8F087C2F12003D840E5 -:100400000CFA02FC21FA03F3914001434FEA1C4726 -:100410001FFA8CFEB3FBF7F007FB10360B0C43EA18 -:10042000064300FB0EF69E4204FA02F408D91CEBC8 -:10043000030300F1FF382FD29E422DD902386344C6 -:100440009B1B89B2B3FBF7F607FB163341EA034166 -:1004500006FB0EF38B4208D91CEB010106F1FF38B5 -:1004600016D28B4214D9023E6144C91A46EA0046AC -:1004700038E72E46284605E70646E3E61846F8E63E -:100480004B45A9D2B9EB020864EB0C0E0138A3E787 -:100490004646EAE7204694E74046D1E7D0467BE768 -:1004A000023B614432E7304609E76444023842E7E0 -:1004B000704700BF02E000F000F8FEE772B6374870 -:1004C00080F30888364880F3098836483649086042 -:1004D00040F20000CCF200004EF63471CEF2000182 -:1004E0000860BFF34F8FBFF36F8F40F20000C0F280 -:1004F000F0004EF68851CEF200010860BFF34F8F36 -:10050000BFF36F8F4FF00000E1EE100A4EF63C7122 -:10051000CEF200010860062080F31488BFF36F8FCD -:1005200003F034FD03F0B6FD4FF055301F491B4A70 -:1005300091423CBF41F8040BFAE71D49184A914229 -:100540003CBF41F8040BFAE71A491B4A1B4B9A427D -:100550003EBF51F8040B42F8040BF8E7002018499D -:10056000184A91423CBF41F8040BFAE703F012FD30 -:1005700003F0E2FD144C154DAC4203DA54F8041BB1 -:100580008847F9E700F042F8114C124DAC4203DA0B -:1005900054F8041B8847F9E703F0FABC000900206F -:1005A000001100200000000808ED00E0000100201C -:1005B00000090020D8470008001100207C1100200D -:1005C00080110020003B0020A0010008A4010008C9 -:1005D000A4010008A40100082DE9F04F2DED108AB8 -:1005E000C1F80CD0C3689D46BDEC108ABDE8F08F01 -:1005F000002383F311882846A047002003F072F9F6 -:10060000FEE703F0D5F800DFFEE70000F8B500F0E4 -:100610000DFE03F05DFC074603F0AEFC0546D0BBC3 -:10062000294B9F4237D001339F4237D0274B27F0C9 -:10063000FF029A4235D1F8B200F03EFC2E4642F25B -:10064000107400F03FFC08B10024264601F0A8F821 -:1006500058B3032000F03EF80024264635B11C4B69 -:100660009F4203D003F080FC00242646002003F0C4 -:1006700039FC0EB100F044F800F056FC00F0D8FD53 -:1006800001F0A8FF0546B4B900F096FC4FF47A706B -:1006900003F02EF9F7E72E460024D2E704460126A0 -:1006A000CFE706464FF47A74CBE7002CD6D04FF450 -:1006B0007A740126D2E701F08DFF431BA342E3D9F0 -:1006C00000F01EF8DCE700BF010007B0000008B032 -:1006D000263A09B0084B187003280CD8DFE800F060 -:1006E00008050208022000F001BE022000F0F4BD5F -:1006F000024B00225A6070478011002084110020B4 -:1007000010B501F04DF830B1234B03221A70234B82 -:1007100000225A6010BD224B224A1C461968013142 -:10072000F8D004339342F9D16268A242F2D31E4B4F -:100730009B6803F1006303F520439A42EAD203F079 -:10074000E5FB03F0F7FB002000F08CFD0220FFF733 -:10075000C1FF164B9A6D00229A65996F9A67996F3F -:10076000D96DDA65D96FDA67D96F196E1A66D3F861 -:100770008010C3F88020D3F8803072B64FF0E023A9 -:100780003021C3F8084DD4E9003281F311889D4629 -:1007900083F308881047BDE78011002084110020F2 -:1007A00000A0000820A00008001100200010024056 -:1007B000094A136849F2690099B21B0C00FB013326 -:1007C0001360064B186844F2506182B2000C01FBC2 -:1007D0000200186080B27047141100201011002030 -:1007E00010B500211022044600F09AFD034B03CB04 -:1007F000206061601868A06010BD00BF9075FF1F89 -:100800002DE9F041ADF5507D0DF13C086EAC40F2A4 -:10081000751207460D4610A80021C8F8001000F018 -:100820007FFD4FF4C4720021204600F079FD01F0F5 -:10083000D1FE254B4FF47A72B0FBF2F0186093E8CA -:100840000700022384E807000DF5ED702382FFF70F -:10085000C7FF42F204631D49238407A803F054FF35 -:100860001C2384F832310DF2EB226B440DF1340C71 -:100870001E4603CE664510605160334602F1080201 -:10088000F6D13068106041460122204600F094FD08 -:1008900000230393AB7E029305F11903019380B209 -:1008A0000123CDE904800093E97E05A3D3E9002369 -:1008B000384602F057FA0DF5507DBDE8F08100BFD3 -:1008C0009E6AC421818A46EE8C11002018470008D8 -:1008D0002DE9F0412C4C237ADAB080460D465BBB03 -:1008E00027A9284600F078FE0746002842D19DF847 -:1008F0009D60C82E3ED801464FF4A662204600F007 -:100900000FFD4FF48073C4F8F8314FF40073C4F84E -:100910000C334FF44073C4F8203432460DF19E017D -:1009200004F1090000F0EAFC26449DF89C3077723F -:1009300023720BB9EB7E23728122002106AC27A81B -:1009400000F0EEFC0122214627A800F081FE0023E2 -:100950000393AB7E029305F1190380B20193282320 -:10096000CDE904400093E97E05A3D3E90023404686 -:1009700002F0F8F95AB0BDE8F08100BFAFF3008093 -:1009800026417272DF25D7B7A8320020F0B5254E78 -:100990004FF48A7505FB0065F1B096F8D83085F8FC -:1009A000DC300024D822214685F8E8403AA800F03F -:1009B000B7FC06F1090000F0ABFCD5F8E4308DF887 -:1009C000F000C2B206AF06F109010DF1F100CDE968 -:1009D0003A3400F093FC394601223AA800F064FE54 -:1009E00080B2CDE9047008230127CDE9023706F172 -:1009F000D803019330230093317A0B4807A3D3E93E -:100A0000002302F0AFF9A04206DD01F0E3FDC5F8D6 -:100A1000E000384671B0F0BD2046FBE778F6339F22 -:100A200093CACD8DA8320020A42100202DE9F041E9 -:100A30001D4D1E4E1E4F86B0284602F0BFF90346DC -:100A400058B30024CDE90344ADF81440027B8DF87F -:100A5000142099684068029403AA03C21B68DFF857 -:100A6000548043F00043029301F0B6FD821941F136 -:100A70000003009402A9384601F078F8A04205DD91 -:100A8000284602F09FF988F80040D5E798F8003032 -:100A9000072B05D8013388F8003006B0BDE8F08197 -:100AA000014802F08FF9F8E7A421002040420F002E -:100AB000D8210020DD37002070B50D4614461E46B3 -:100AC00002F0ACF850B9022E10D1012C0ED112A3B5 -:100AD000D3E90023C5E90023012007E0282C10D02A -:100AE00005D8012C09D0052C0FD0002070BD302C6A -:100AF000FBD10BA3D3E90023ECE70BA3D3E900233D -:100B0000E8E70BA3D3E90023E4E70BA3D3E9002331 -:100B1000E0E700BFAFF30080401DA12026812A0B33 -:100B200078F6339F93CACD8D9E6AC421818A46EEA2 -:100B300026417272DF25D7B7F017304A39059E5625 -:100B400038B505460E4C0021013500F0ADFBA4F888 -:100B50002C55B4F82C0500F08FFB78B1B4F82C05B7 -:100B600000F09AFB014648B9B4F82C0500F09CFB54 -:100B7000B4F82C350133A4F82C35EAE738BD00BFB2 -:100B8000A832002010B50A4B0A4A1A6003F58053B8 -:100B900093F860203AB9DC6D2CB1204600F07EFE5F -:100BA000204603F0F1FCBDE81040034800F076BE9B -:100BB000D821002074470008203200202DE9F04F92 -:100BC0008FB000AF05460C4602F028F8002849D146 -:100BD000237E022B1BD1E38A012B18D101F0FAFCF2 -:100BE0000646FFF7E5FD03464FF4C870DFF8C48200 -:100BF000B3FBF0F206F5167602FB103316FA83F318 -:100C0000C8F80030E37E33B9A34B00221A703C379A -:100C1000BD46BDE8F08F07F12401204600F09AFCA4 -:100C20000028F4D107F11400FFF7DAFD97F8264009 -:100C300007F11401224607F1270003F0EFFC00281A -:100C4000E2D10F2C08D8944B1C70D8F80030A3F5D3 -:100C50001673C8F80030DAE797F82410284601F038 -:100C6000D5FFD4E7E38A282B2BD010D8012B23D033 -:100C7000052BCCD1BFF34F8F8849894BCA6802F44A -:100C8000E0621343CB60BFF34F8F00BFFDE7302B13 -:100C9000BDD1844EE17E327A9142B8D1607E314638 -:100CA000002291F8DC50854200F0A5800132042A30 -:100CB00001F58A71F5D1AAE721462846FFF7A0FD84 -:100CC000A5E721462846FFF703FEA0E7B2F8EC505F -:100CD0007B6005F103094FEA99094FEA8902D11DAA -:100CE000C908A8EBC1039D46EB460021584600F019 -:100CF00017FB04F1EE012A463144584600F0FEFA93 -:100D00007B6813B9012000F0ADFA96F8D20000F02C -:100D1000B3FA044630B9307200F0CEFA204600F043 -:100D2000A1FAB1E0D6F8D4203AB996F8D200B6F8D4 -:100D30002C25824201D8FFF703FFD6F8D4202A449D -:100D4000944208D296F8D200B6F82C25013082429F -:100D500001D8FFF7F5FE70685FFA89F2594600F096 -:100D6000E7FA08B9C54679E0726896F8D2002A44D5 -:100D70007260D6F8D42005EB0209C6F8D49000F0D2 -:100D80007BFA814509D396F8D220D6F8D4000132F7 -:100D9000001B86F8D220C6F8D400FF2D0FD80024FF -:100DA000347200F089FA204600F05CFA00F0F8FC9A -:100DB0003D4B188108B9FFF7A3FCC54627E7BB6880 -:100DC00096F8D9000AFB0362FB68D2F8E41082F8B7 -:100DD000E83001F58061C2F8E030C2F8E410FFF7B6 -:100DE000D5FDFFF723FE96F8D920013202F0030269 -:100DF00086F8D920B6E74FF48A7A0AFB02F505F1A6 -:100E0000EA013144204600F07BFCF86000287FF4C2 -:100E1000FEAE3544012285F8E82001F0DBFBD5F871 -:100E2000E020D6ED007ADFED216A801A192838BF5C -:100E3000192040F6B832904228BF1046B8EE677AC3 -:100E400007EE900AF8EEE77A67EEA67ADFED186A09 -:100E5000E7EE267AFCEEE77AC6ED007A96F8D9300E -:100E6000BB60BA6873680AFB02F4321992F8E810A2 -:100E700059B1D2F8E4108B42E8463FF427AF002185 -:100E800082F8E810C2F8E010C5467368064A9B0A6B -:100E900001331381BBE600BF9D21002000ED00E07F -:100EA0000400FA05A83200208C110020CDCCCC3DE6 -:100EB0006666663FA0210020014B1870704700BF96 -:100EC0009811002038B54FF00054134B22689A4215 -:100ED00020D1124B627D12481A70237D03724FF4A9 -:100EE0008073C0F8F8314FF40073C0F80C3300255C -:100EF0004FF44073C0F820340A49C0F8E450C922C6 -:100F0000093000F0FBF9E0222946204600F008FAFB -:100F1000012038BD0020FCE79AAD44C5981100209F -:100F2000A83200201600002037B500F039FC194D1A -:100F3000194928810223012218486B7101F0E8F950 -:100F400000230193164B174900931748174B4FF492 -:100F5000805201F033FE164B197811B1124801F09E -:100F600055FE01F037FB0446FFF722FC4FF4C8732F -:100F7000B0FBF3F202FB130304F5167010FA83F0D2 -:100F80000C4B186002F0F8FF08B10F232B8103B05F -:100F900030BD00BF8C11002040420F00D82100203E -:100FA000B90A00089C110020A4210020BD0B0008F4 -:100FB00098110020A02100202DE9F04F2DED028B8B -:100FC0000FF23829D9E90089834C93B00BAE9FED1D -:100FD0007E8BFFF72BFD814FDFF828A200230A93B9 -:100FE000ADF834300B9373604FF0000B5B468DED22 -:100FF000008B01250DF11D0207A938468DF81C5004 -:101000008DF81DB001F034F99DF81C30002B40F034 -:10101000A580204601F002FE0646002845D1704F0B -:1010200001F0D8FA3B6898423FD301F0D3FA8246E8 -:10103000FFF7BEFB4FF4C873B0FBF3F202FB1303E0 -:101040000AF5167010FA83F03860664F97F800B012 -:10105000CBF1100ABBF1000F14BF33462B465FFAE9 -:101060008AFA0EA88DF82830FFF7BAFBBAF1060FFE -:1010700028BF4FF0060A0EAB03EB0B0152460DF1F1 -:10108000290000F03BF90AAB0393182302930AF1FD -:101090000102554BD2B2CDE90053049220464CA335 -:1010A000D3E9002301F000FE3E7001F093FA4F4AAD -:1010B0004F4D1368C31AB3F57A7F2ED3106001F039 -:1010C0008BFA02460B46204601F086FE204601F0D0 -:1010D000A5FD10B32B7A474E002B14BF0323022328 -:1010E000737101F077FA0EAF4FF47A730122B0FBFF -:1010F000F3F039463060304600F004FA18230293CA -:101100003D4B019380B240F25513CDE9037000933B -:1011100042464B46204601F0C7FD2B7A93B101F0C1 -:1011200059FA002607464FF48A7A95F8D9003044D8 -:1011300000F003000AFB005393F8E82092B3013655 -:10114000042EF2D1C82002F0D3FB2B7A002B7FF4BF -:101150003DAF13B0BDEC028BBDE8F08FDAF8143070 -:1011600083F00803CAF81430594610220EA800F084 -:10117000D7F80DF11E0308AA0AA9384600F0F4FDBD -:1011800096E803000FAB83E803009DF834308DF838 -:1011900044300A9B0E930EA9DDE90823204601F096 -:1011A000EFFF21E7D3F8E02042B12B68FA2B38BFDC -:1011B000FA23BA1A0533B2EB430FC0D3FFF7E6FBAD -:1011C0000028BCD1BEE700BF000000000000000006 -:1011D000401DA12026812A0BA4210020D821002017 -:1011E000A02100209D2100209C210020D837002034 -:1011F000A83200208C110020DC370020F1C6A7C1E6 -:10120000D068080F0004004808B5054800F046FE05 -:10121000BDE80840034A0449002003F0AFB900BF0D -:10122000D821002018380020850B000870470000E6 -:1012300070B502F0E9FC094E094D308000242868A1 -:101240003388834208D902F0DBFC2B680444013365 -:10125000B4F5204F2B60F2D370BD00BF0C380020D6 -:10126000E037002002F082BD00F10060920000F53E -:10127000204002F005BD0000054B1A68054B1B8895 -:101280009B1A834202D9104402F0BABC0020704776 -:10129000E03700200C380020024B1B68184402F095 -:1012A000B5BC00BFE0370020024B1B68184402F0B9 -:1012B000BFBC00BFE0370020064991F8243033B1AD -:1012C0000023086A81F824300822FFF7CDBF0120EF -:1012D000704700BFE4370020022802BF024B4FF4E2 -:1012E00000229A61704700BF00040048022802BF34 -:1012F000014B08229A6170470004004810B5002392 -:10130000934203D0CC5CC4540133F9E710BD000014 -:1013100003460246D01A12F9011B0029FAD1704780 -:1013200002440346934202D003F8011BFAE77047D8 -:101330002DE9F8431F4D144695F8242007468846AA -:1013400052BBDFF870909CB395F824302BB9202263 -:10135000FF2148462F62FFF7E3FF95F82400C0F114 -:101360000802A24228BF2246D6B24146920005EBAF -:101370008000FFF7C3FF95F82430A41B1E44F6B28B -:10138000082E17449044E4B285F82460DBD1FFF7BF -:1013900093FF0028D7D108E02B6A03EB8203834236 -:1013A000CFD0FFF789FF0028CBD10020BDE8F8831C -:1013B0000120FBE7E43700202DE9F0470D46044605 -:1013C00000219046284640F27912FFF7A9FF2346F4 -:1013D00020220021284601F075FE231D0222202133 -:1013E000284601F06FFE631D03222221284601F0EA -:1013F00069FEA31D03222521284601F063FE04F1A6 -:10140000080310222821284601F05CFE04F1100395 -:1014100008223821284601F055FE04F11103082264 -:101420004021284601F04EFE04F112030822482113 -:10143000284601F047FE04F11403202250212846DB -:1014400001F040FE04F1180340227021284601F00B -:1014500039FE04F120030822B021284601F032FEB3 -:1014600004F121030822B821284601F02BFE04F1E3 -:101470002207C0263B46314608222846083601F09E -:1014800021FEB6F5A07F07F10107F3D104F1320385 -:1014900008223146284601F015FE002704F1330AE0 -:1014A00094F832304FEAC7099F4209F5A47615D364 -:1014B000B8F1000F08D1314604F599730722284688 -:1014C00001F000FE09F24F16274694F832213B1B2B -:1014D00093420CD3F01DC008BDE8F0870AEB070368 -:1014E00008223146284601F0EDFD0137D8E707F222 -:1014F000331331460822284601F0E4FD083601374F -:10150000E3E7000013B504460846002101602346C6 -:10151000C0F803102022019001F0D4FD0198231D92 -:101520000222202101F0CEFD0198631D0322222119 -:1015300001F0C8FD0198A31D0322252101F0C2FD81 -:10154000019804F108031022282101F0BBFD0720B7 -:1015500002B010BDF7B50023047F00910E460722AC -:101560001946054601F072FC731C0093012200230A -:101570000721284601F06AFCC4B9B31C0093052278 -:1015800023460821284601F061FC0D243746B27835 -:10159000BB1B934211D32B7FA88A0734E408BBB945 -:1015A000844294BF0020012003B0F0BDAB8ADB0071 -:1015B000083BDB08B3700824E8E7FB1C00932146D6 -:1015C00000230822284601F041FC08340137DEE7F9 -:1015D000201A18BF0120E7E7F7B50023047F009128 -:1015E0000E4608221946054601F030FC731CC4B9AA -:1015F0000822009311462346284601F027FC1024B8 -:10160000012372785F1C013B934211D32B7FA88A80 -:101610000734E408BBB9844294BF0020012003B022 -:10162000F0BDAB8ADB00083BDB0873700824E7E7FA -:10163000F3190093214600230822284601F006FCF6 -:1016400008343B46DDE7201A18BF0120E7E7000019 -:10165000F8B50E4605461446002181223046FFF7B4 -:101660005FFE2B4608220021304601F02BFD7CB99D -:101670006B1C07220821304601F024FD0F240123B2 -:101680006A785F1C013B934204D3E01DC008F8BD9B -:101690000824F4E7EB1921460822304601F012FD38 -:1016A00008343B46ECE70000F8B50E460546144604 -:1016B0000021CE223046FFF733FE2B4628220021A0 -:1016C000304601F0FFFC7CB905F10803082228210F -:1016D000304601F0F7FC30242F462A7A7B1B9342D8 -:1016E00004D3E01DC008F8BD2824F5E707F109037D -:1016F00021460822304601F0E5FC08340137ECE7CA -:10170000F7B5047F00910E46012310220021054603 -:1017100001F09CFBC4B9B31C00930922234610219D -:10172000284601F093FB192437467288BB1B9A4266 -:1017300011D82B7FA88A0734E408BBB9844294BF30 -:101740000020012003B0F0BDAB8ADB00103BDB08BA -:1017500073801024E8E73B1D0093214600230822F4 -:10176000284601F073FB08340137DEE7201A18BF62 -:101770000120E7E730B5094D0A4491420DD011F838 -:10178000013B5840082340F30004013B2C4013F078 -:10179000FF0384EA5000F6D1EFE730BD2083B8EDB7 -:1017A000F7B5384A106851686B4603C36A46364934 -:1017B0003648082302F042FF0446002833D10A25A8 -:1017C000334A106851686B4603C36A4631492F4853 -:1017D000082302F033FF0446002849D00369B3F51B -:1017E000583F45D8B0F8661040F2264291423FD1AA -:1017F000294A024402F15C018B4239D35C3B234904 -:1018000000209E1AFFF7B6FF3246074604F1640136 -:101810000020FFF7AFFFA3689F4229D1E3689842F9 -:1018200008BF002524E00369B3F5583F27D8418B52 -:1018300040F22642914220D1174A024402F110019F -:101840008B4218D3103B114900209D1AFFF792FFDD -:101850002A46064604F118010020FFF78BFFA36813 -:101860009E4202D1E368984201D00D25A8E70025E9 -:10187000284603B0F0BD1025A2E70C25A0E70B25F4 -:101880009EE700BF38470008DC5F030000A00008A7 -:1018900041470008905F03000860FFF710B5037C24 -:1018A000044613B9006802F0B1FE204610BD0000E6 -:1018B0000023BFF35B8FC360BFF35B8FBFF35B8F0E -:1018C0008360BFF35B8F7047BFF35B8F0068BFF32C -:1018D0005B8F704770B505460C30FFF7F5FF05F1DB -:1018E000080604463046FFF7EFFFA04206D930460F -:1018F0006D68FFF7E9FF2544281A70BD3046FFF7F1 -:10190000E3FF201AF9E7000070B50546406898B17A -:1019100005F10800FFF7D8FF05F10C060446304634 -:10192000FFF7D2FF8442304694BF6D680025FFF771 -:10193000CBFF013C2C44201A70BD000038B50C468A -:101940000546FFF7C7FFA04210D305F10800FFF7D7 -:10195000BBFF04446868B4FBF0F100FB1144BFF323 -:101960005B8F0120AC60BFF35B8F38BD0020FCE7CC -:101970002DE9F041144607460D46FFF7C5FF8442A6 -:1019800028BF0446D4B1B84658F80C6B4046FFF760 -:101990009BFF3044286040467E68FFF795FF331A6E -:1019A0009C4203D86C600120BDE8F0816B60A41BF1 -:1019B0003B68AB602044E8600220F5E72046F3E78F -:1019C00038B50C460546FFF79FFFA04210D305F13E -:1019D0000C00FFF779FF04446868B4FBF0F100FBEA -:1019E0001144BFF35B8F0120EC60BFF35B8F38BD08 -:1019F0000020FCE72DE9FF41884669460746FFF7CE -:101A0000B7FF6C4606B204EBC6060025B44209D007 -:101A10006268206808EB0501FFF770FC6368083412 -:101A20001D44F3E729463846FFF7CAFF284604B0AD -:101A3000BDE8F081F8B505460C300F46FFF744FFCE -:101A400005F1080604463046FFF73EFFA042304647 -:101A500088BF6C68FFF738FF201A386020B1304625 -:101A60002C68FFF731FF2044F8BD000073B5144621 -:101A700006460D46FFF72EFF844228BF044601901C -:101A8000DCB101A93046FFF7D5FF019B33B93268BD -:101A9000C5E90233C5E9002401200CE09C4238BFAF -:101AA00001942860019868608442F5D93368AB607E -:101AB000241AEC60022002B070BD2046FBE7000053 -:101AC0002DE9FF410F466946FFF7D0FF6C4600B293 -:101AD00004EBC0050026AC4209D0D4F8048054F8C9 -:101AE000081BB8194246FFF709FC4644F3E73046A5 -:101AF00004B0BDE8F081000038B50546FFF7E0FF0F -:101B0000044601462846FFF719FF204638BD00006D -:101B1000302383F3118862B670470000002383F3FB -:101B2000118862B67047000010B4026854681A4603 -:101B300023465DF8044B184701207047002070478A -:101B40000020704770470000002070470E2070474B -:101B500000F5805090F8C800C0F3400070470000C6 -:101B600000F5805090F9C90070470000F7B50C6887 -:101B7000BDF8207014F000541E466FD10B7B082B6B -:101B80006CD8FFF7C5FF4569AB685B010CD4AB6847 -:101B90001B0108D4AC6814F080545DD1FFF7BEFF80 -:101BA000204603B0F0BD01240B6804F1180C002B93 -:101BB000B8BFDB004FEA0C1CB4BF43F004035B0565 -:101BC00045F80C300B680FFA84FC13F0804F18BFF7 -:101BD00005EB0C1E05EB0C1C1EBFDEF8803143F03C -:101BE0000203CEF880310B7BCCF8843105EB041571 -:101BF0008B68C5F88C314B68C5F88831DCF88031CA -:101C000043F00103CCF8803100EB441541F2680346 -:101C10001D4403EB44130344C5E9002608330D4675 -:101C200001F10C0C55F804EB43F804EB6545F9D1D0 -:101C300084342D881D8000EB441407F003032579BC -:101C400025F00B052B432371FFF768FF0097334600 -:101C500000F0E2FC0120A4E70224A5E74FF0FF30EA -:101C60009FE7000013B500F580540191E06DFFF788 -:101C70004BFE1F280AD90199E06D2022FFF7BAFE1A -:101C8000A0F120035842584102B010BD0020FBE7EC -:101C900008B500F58050FFF73BFFC06DFFF708FE69 -:101CA000BDE80840FFF73ABF00220260828142602F -:101CB0008260704710B500220023C0E90023002392 -:101CC000044603810C30FFF7EFFF204610BD0000F3 -:101CD000F0B5054600F580500C4690F8C83013F07A -:101CE000040FC3F3800108BF114661F3820304F1BE -:101CF000840680F8C83005EB461389B01B79D807F5 -:101D00002ED57AB319072DD46846FFF7D3FF05EB1C -:101D1000441303F5835303F1180703AA103318681B -:101D20005968144603C40833BB422246F7D11868E9 -:101D300020609B88A380DDE90E23CDE900230123E9 -:101D4000ADF808302B686946DB6B2846984705EBF1 -:101D500046152B791A075CBF43F008032B7101E08D -:101D6000002AF4D109B0F0BD2DE9F047074688B04C -:101D700007F5805468469A468846FFF7C9FE9146A3 -:101D8000FFF798FFE06DFFF7A5FD1F2829D9E06D4B -:101D900020226946FFF7B0FE202822D103AD444639 -:101DA00005AB2E4603CE9E4220606160354604F1AD -:101DB0000804F6D130682060B388A380DDE90023F1 -:101DC000C9E90023BDF80830AAF80030FFF7A6FEE5 -:101DD0004A4653464146384608B0BDE8F04700F051 -:101DE00009BCFFF79BFE002008B0BDE8F0870000AB -:101DF0002DE9F84F0023C0E90133254B044640F894 -:101E0000183B0F46FFF750FF04F12800FFF752FF81 -:101E100004F1480804F58255464608353046203618 -:101E2000FFF748FFAE42F9D104F580554FF48053D7 -:101E30004FF00009C5E91339C5F848800123EE6564 -:101E400004F5875804F58456C5F8549085F8583041 -:101E500085F86030083608F108084FF0000A4FF0A6 -:101E6000000B46E908ABA6F11800FFF71DFF20366E -:101E700046F8289C4645F4D185F8C97017B1054845 -:101E800000F0A2FB044B63612046BDE8F88F00BF61 -:101E9000744700084C4700080064004010B5044B2C -:101EA000197804464A1C1A70FFF7A2FF204610BD9D -:101EB000143800202DE9F047002950D0294B2A4F33 -:101EC000B7FBF1F599428CBF0A231123581EB5FBCD -:101ED000F3FC03FB1C53C4B22BB102280346F5D814 -:101EE0000020BDE8F0870CF1FF36B6F5806FF7D221 -:101EF000C4EBC40E0EF103034FEAE309C3F3C703B7 -:101F0000A4EB030809F1010A4FF47A755FFA88F02F -:101F100009FB05555AFA88F8B5FBF8F5B5F5617F68 -:101F2000C1BF0EF1FF33C3F3C703E01AC0B25C1C9C -:101F300050FA84F40CFB04F4B7FBF4F4A142CFD1C3 -:101F4000013BDBB20F2BCBD80138C0B20728C7D872 -:101F50000021107116809170D3700120C1E70846EE -:101F6000BFE700BF3F420F0000B4C40470B5054690 -:101F70000E464FF47A746B695B6803F00103B34259 -:101F800007D04FF47A7001F0B3FC013CF3D1204646 -:101F900070BD0120FCE7000030B54269936913F081 -:101FA000700F16D000230B4C936103F1840200EBF9 -:101FB000421211794D0709D5890707D5416954F8AF -:101FC00023508D60117941F0040111710133032B0D -:101FD000EBD130BD6047000873B51D464369164616 -:101FE0009A68D207044609D59A6801219960C2F31C -:101FF0004002CDE900650021FFF76AFE63699A6837 -:10200000D1050BD59A684FF480719960C2F34022D4 -:10201000CDE9006501212046FFF75AFE63699A6801 -:10202000D2030BD59A684FF480319960C2F34042D5 -:10203000CDE9006502212046FFF74AFE204602B0A6 -:10204000BDE87040FFF7A8BFF8B50446466900290F -:102050006CD106F10C07386880076AD006EB0115D1 -:102060003868D5F8B00110F0040FD5F8B0011ABFE8 -:10207000C00840F00040400DA061D5F8B0C11CF090 -:10208000020F1CBF40F08040A061D5F8B40106EB00 -:10209000011100F00F0084F82400D1F8B801207776 -:1020A000D1F8B801000A6077D1F8B801000CA07728 -:1020B000D1F8B801000EE077D1F8BC0184F8200017 -:1020C000D1F8BC01000A84F82100D1F8BC01000C51 -:1020D00084F82200D1F8BC11090E84F823103821AD -:1020E000396004F1340004F1180104F1240551F8B9 -:1020F000046B40F8046BA942F9D109880180C4E956 -:102100000A2321460023238651F8283B2046DB6B17 -:10211000984704F58052204692F8C83043F00403F3 -:1021200082F8C830BDE8F840FFF736BF06F1100767 -:1021300091E7F8BD10B5044600F04EFA02460B4692 -:1021400052EA030102D0013A63F10003044908682E -:1021500020B12146BDE81040FFF776BF10BD00BF9B -:1021600010380020F8B500F583511E46FFF7D0FC6B -:10217000DFF844C00831002404F1840500EB451564 -:102180002B795F070ED4DB060CD5D1E9007397429B -:10219000B34107D243695CF824709F602B7943F008 -:1021A00004032B710134032C01F12001E4D1BDE8BB -:1021B000F840FFF7B3BC00BF6047000808B5FFF761 -:1021C000A7FCFFF7E9FEBDE80840FFF7A7BC000049 -:1021D000F8B543690546986800F0E050B0F1E05F5B -:1021E0000F461FD0E8B1FFF793FC05F58354103478 -:1021F000002606F1840305EB43131B791A0706D565 -:102200000136032E04F12004F3D1012007E05B071F -:10221000F6D42146384600F039FA0028F0D1FFF70D -:102220007DFCF8BD0120FCE700F5805008B5FFF704 -:102230006FFCC06DFFF74EFBFFF770FC43090CBF4E -:102240000120002008BD0000F8B51D4600231370D2 -:102250000F4606461446FFF7E7FF80F0010038708E -:1022600025B129463046FFF7B3FF2070F8BD0000C6 -:102270002DE9B8410C4615461F46804600F0ACF9E2 -:102280000B462178024609B9287850B14046FFF73D -:1022900069FFFFF793FF3B462A462146FFF7D4FF2D -:1022A0000120BDE8B881000010B5FFF731FC174BE5 -:1022B0009A6D42F000729A659A6B42F000729A63CE -:1022C0009A6B00F5805422F000729A63FFF726FCA7 -:1022D00094F8C830DB0718D4B9B103211320FFF7F5 -:1022E00017FC01F0DBF90321142001F0D7F90321D9 -:1022F000152001F0D3F994F8C83043F0010384F8B5 -:10230000C830BDE81040FFF709BC10BD0010024006 -:102310002DE9F04700F5805588B095F8C930012BBC -:102320000446884616467FD8804F57F823200AB9BE -:1023300047F82300D7F800A0C4F80C802674BAF13F -:10234000000F63D095F8C930012B6FD001212046D2 -:10235000FFF7AAFFFFF7DCFB6269136823F00203B3 -:1023600013606269136843F0010313606369002717 -:102370005F6101212046FFF7D1FBFFF7F7FD002841 -:1023800000F09580E86DFFF793FA04F58359BA469B -:1023900009F10809202200216846FEF7C1FF02A8C2 -:1023A000FFF782FCCDF818A06A4609EB07030DF190 -:1023B000180E9446BCE80300F44518605960624664 -:1023C00003F10803F5D1DCF80000186020379CF811 -:1023D00004201A71602FDDD195F8C8306FF38203A5 -:1023E000002785F8C8306A4641462046ADF800709F -:1023F000ADF802708DF80470FFF75CFD636948BBAF -:102400004FF400421A6008B0BDE8F08741F2D000F6 -:1024100002F0BCF8814610B15146FFF7E9FCC7F85D -:102420000090B9F1000F8DD10020ECE73868036807 -:102430001B6B98470146002888D13868FFF734FFA6 -:102440003868036832465B684146984700287FF445 -:102450007DAFE9E761221A609DF802309DF8032004 -:102460001B06120402F4702203F040731343BDF8FC -:102470000020C2F3090213439DF804201205022E26 -:1024800002F4E0020CBF4FF00041002113436269E7 -:102490000B43D361636913225A616269136823F0A5 -:1024A0000103136039462046FFF760FD08B96369F0 -:1024B000A6E795F8C93093BB6169D1F8002242F0D4 -:1024C0000102C1F800226169D1F8002222F47C5295 -:1024D00022F00E02C1F800226169D1F8002242F414 -:1024E0006062C1F800226269C2F814326269C2F8FF -:1024F0000432626941F6FF71C2F80C126269C2F8D7 -:1025000040326269C2F8443263690122C3F81C2276 -:102510006269D2F8003223F00103C2F8003295F864 -:10252000C83043F0020385F8C8306CE7103800204B -:1025300008B500F051F850EA0103024602D0421EED -:1025400061F10001044B186810B10B46FFF744FD20 -:10255000BDE8084001F064B81038002008B500203C -:10256000FFF7E8FDBDE8084001F05AB808B50120C2 -:10257000FFF7E0FDBDE8084001F052B800B59BB0A0 -:10258000EFF3098168226846FEF7B8FEEFF3058392 -:10259000014B9B6BFEE700BF00ED00E008B5FFF7C5 -:1025A000EDFF000000B59BB0EFF30981682268469B -:1025B000FEF7A4FEEFF30583014B5B6BFEE700BF64 -:1025C00000ED00E0FEE700000FB408B5029801F04E -:1025D00025F9FEE701F016BC01F0EEBB13B56C4621 -:1025E00084E80600031D94E8030083E80500012049 -:1025F00002B010BD73B58568019155B11B885B07AA -:1026000007D4D0E900369B6B9847019AC1B2304697 -:10261000A847012002B070BDF0B5866889B00546B4 -:102620000C465EB1BDF838305B070AD4D0E90037FC -:102630009B6B98472246C1B23846B047012009B08B -:10264000F0BD00220023CDE900230023ADF80830BF -:102650000A4603AB01F10806106851681C4603C422 -:102660000832B2422346F7D1106820609288A280D7 -:10267000FFF7B2FF0423ADF808302B68CDE9000165 -:10268000DB6B694628469847D8E7000030B50368F9 -:102690000968DD0FB5EBD17F23F0604421F0604283 -:1026A0004FEAD1700BD0002BB8BFA40C0029B8BFE3 -:1026B000920C944202D034BF0120002030BD9442DD -:1026C00005D1C1F38070C3F380738342F6D1944285 -:1026D0002CBF00200120F1E72DE9F041456A15B932 -:1026E0004162BDE8F0814B6823F06047C3F38A463E -:1026F0004FEAD37EC3F3807816EA230638BF3E46FE -:10270000AC462B465A68BEEBD27F22F060440AD01A -:10271000002A18DAA40CB44217D19D420FD10D60E3 -:10272000DEE71346EEE7A74207D102F08044C2F38A -:10273000807242450BD054B1EFE708D2EDE7CCF8F8 -:1027400000100B60CDE7B44201D0B442E5D81A685E -:102750009C46002AE5D11960C3E700002DE9F04747 -:10276000089D01F007044FEAD508224405F007054B -:1027700000EBD1004FF47F49944201D1BDE8F087CE -:1027800004F0070705F0070A57453E4638BF56468E -:10279000C6F10806111B8E4228BF0E46E10808EB61 -:1027A000D50E415C13F80EC0B94029FA06F721FA9C -:1027B0000AF1FFB28CEA010147FA0AF739408CEAC4 -:1027C000010C03F80EC034443544D5E780EA0120FB -:1027D000082341F2210201B24000002980B203F136 -:1027E000FF33B8BF504013F0FF03F4D1704700002F -:1027F00038B50C468D18A54200D138BD14F8011B20 -:10280000FFF7E4FFF7E7000042684AB1136843604E -:102810004389818901339BB29942438138BF8381C7 -:102820001046704770B588B0202204460D466846B1 -:102830000021FEF775FD20460495FFF7E5FF0246EF -:1028400058B16B46054608AE1C4603CCB44228601E -:102850006960234605F10805F6D1104608B070BD41 -:10286000082817D909280CD00A280CD00B280CD01E -:102870000C280CD00D280CD00E2814BF402030207E -:1028800070470C20704710207047142070471820A4 -:102890007047202070470000082817D90C280CD951 -:1028A00010280CD914280CD918280CD920280CD998 -:1028B00030288CBF0F200E207047092070470A2057 -:1028C00070470B2070470C2070470D2070470000A8 -:1028D0002DE9F843078C072F04461ED9D0E902984A -:1028E00000254FF6FF73C5F12006A5F1200029FA57 -:1028F00005F108FA06F628FA00F031430143C9B29F -:102900001846FFF763FF0835402D0346EBD1E16918 -:102910003A46BDE8F843FFF76BBF4FF6FF70BDE8DE -:10292000F883000010B54B6823B9CA8A63F3090223 -:10293000CA8210BD04691A681C600361C38A013B26 -:10294000C3824A60EFE700002DE9F84F1D46CB8AAD -:102950000F46C3F309010529814692460B4630D044 -:102960000020AAB207F11A049EB2042E1FFA80F8C2 -:102970000FD8904503F1010306D3FB8A0A4462F3A2 -:102980000903FB8201201AE01AF80060E6540130C6 -:10299000EAE79045F1D2A1F1050B1C237C68BBFB53 -:1029A000F3F203FB12BB1FFA8BF6002C45D148460D -:1029B000FFF72AFF044638B978606FF00200BDE8DF -:1029C000F88F4FF00008E6E7002606607860ADB2A9 -:1029D0004FF0000B454510D90AEB0803221D13F8F0 -:1029E000011B9155B1B208F101081B291FFA88F8A3 -:1029F0002BD0454506F10106F1D8FB8AC3F3090245 -:102A0000154465F30903BCE7013292B21C46236802 -:102A1000002BF9D16B1F0B441C21B3FBF1F30133E5 -:102A20009BB29A42D3D2BBF1000FD0D14846FFF7F8 -:102A3000EBFE20B9C4F800B0BFE70122E7E7C0F819 -:102A400000B05E4620600446C1E74545D5D94846FA -:102A5000FFF7DAFE08B92060AFE7C0F800B0002643 -:102A600020600446B6E700002DE9F04F2DED028B03 -:102A70001C4683B05B69019207468846002B00F034 -:102A80009A80238C2BB1E269002A00F09480072BF6 -:102A900035D807F10C00FFF7B7FE054638B96FF0DF -:102AA0000205284603B0BDEC028BBDE8F08F14226E -:102AB0000021FEF735FC228CE16905F10800FEF7E4 -:102AC0001DFC208C013080B2FFF7E6FEFFF7C8FE48 -:102AD000013880B22084013028746369228C1B780D -:102AE0002A4403F01F0363F03F0348F000411372D0 -:102AF000384669602946FFF7EFFD0125D1E700F16F -:102B00000C034FF0000908EE103A4FF0800A4E46D1 -:102B10004D4618EE100AFFF777FE83460028BED018 -:102B200014220021FEF7FCFB002E3AD1019BABF8EA -:102B3000083002220BF1080E1FFA82FC0CF1010092 -:102B4000BCF1060F218C80B201D88E422BD3FFF747 -:102B5000A3FEFFF785FE62691278013802F01F02BA -:102B60008E4208BF4FF0400A42EA49121BFA80F138 -:102B70004AEA020A013048F0004281F808A08BF8C6 -:102B80001000CBF8042059463846FFF7A5FD238CEA -:102B90000135B3422DB289F001094FF0000AB8D1D6 -:102BA0007FE70022C6E7E169895D0EF80210013671 -:102BB000B6B20132C0E76FF0010572E7F8B515460D -:102BC0000E463022002104461F46FEF7A9FB069B55 -:102BD0006360B5F5001F079BA76034BF6A094FF615 -:102BE000FF72A36297B2E66104F1100000239A42DB -:102BF00006D800230360A782E3822383E360F8BD45 -:102C00000660013330462036F1E7000003781BB937 -:102C10004BB2002BC8BF01707047000000787047AE -:102C2000F8B50C46C969074611B9238C002B37D17A -:102C3000257E1F2D34D8387828BB228C072A2CD823 -:102C4000268A36F003032BD14FF6FF70FFF7D0FD35 -:102C500020F001003102400441EA0561400C41EAE4 -:102C600040254FF6FF72234629463846FFF7FCFE03 -:102C7000002807DD626913780133DBB21F2B88BFA0 -:102C800000231370F8BD218A2D0645EA012505436E -:102C90002046FFF71DFE0246E5E76FF00300F1E76F -:102CA0006FF00100EEE7000070B58AB004461646EA -:102CB0000021282268461D46FEF732FBBDF8383059 -:102CC000ADF810300F9B05939DF840308DF818300B -:102CD000119B07936946BDF84830ADF82030204677 -:102CE000CDE90265FFF79CFF0AB070BD2DE9F04108 -:102CF000D36905460C4616460BB9138C5BBB377E71 -:102D00001F2F28D895F80080B8F1000F26D0304644 -:102D1000FFF7DEFD3378210241EAC33141EA0801C1 -:102D2000338A41EA076141EA03410246334641F0F2 -:102D300080012846FFF798FE00280ADD3378012B32 -:102D400007D1726913780133DBB21F2B88BF0023D0 -:102D50001370BDE8F0816FF00100FAE76FF0030037 -:102D6000F7E70000F0B58BB004460D46174600218A -:102D7000282268461E46FEF7D3FA9DF84C305A1EAC -:102D8000534253418DF800309DF84030ADF810307B -:102D9000119B05939DF848308DF81830149B0793CC -:102DA0006A46BDF85430ADF8203029462046CDE9BA -:102DB0000276FFF79BFF0BB0F0BD0000406A00B148 -:102DC00004307047436A1A68426202691A600361FC -:102DD000C38A013BC38270472DE9F041D0F82080BF -:102DE000194E14461D464146002709B9BDE8F08139 -:102DF000D1E90223A21A65EB0303964277EB0303A2 -:102E00001ED2036A8B420DD1FFF78CFD036A1B684B -:102E1000036203690B60C38A0161016A013BC382DB -:102E20008846E2E7FFF77EFD0B68C8F800300369CB -:102E30000B60C38A0161013BC382D8F80010D4E75C -:102E400088460968D1E700BF80841E002DE9F04F55 -:102E50008BB00D46DDF8509014469B468046002806 -:102E600000F01981B9F1000F00F01581531E3F2BBE -:102E700000F21181012A03D1BBF1000F40F00B8158 -:102E80000023CDE90833B8F81430B5EBC30F4FEA8F -:102E9000C30703D300200BB0BDE8F08F2B199F426E -:102EA000D8F80C303ABF7F1BFFB227461BB9D8F8C1 -:102EB0001030002B7AD0272D4ED8C5F12806B74206 -:102EC0004FF000032CBFF6B23E4600932946D8F8D7 -:102ED000080008AB3246FFF741FCA7EB060A354471 -:102EE0005FFA8AFAB8F8143003F10053053BDB00AF -:102EF0000493D8F80C3003932821039B13B1BAF143 -:102F0000000F2CD1D8F8100040B1BAF1000F05D055 -:102F1000009608AB5246691AFFF720FC38B2002F22 -:102F2000B8D066070AD00AAB03EBD401624211F8AD -:102F3000083C02F00702134101F8083C082C3CD978 -:102F4000102C40F2B580202C40F2B780BBF1000F6E -:102F500000F09C80082334E0BA460026C2E7049BB8 -:102F6000E02B28BFE02306930B44AB42059314D912 -:102F70005A1B03980096924534BF5246D2B2691A42 -:102F800008AB04300792FFF7E9FB079A1644AAEB57 -:102F9000020A1544F6B25FFA8AFA049B069A05996A -:102FA0009B1A0493039B1B680393A6E70093D8F82E -:102FB000080008AB3A462946AEE7BBF1000F13D034 -:102FC0000123B4EBC30F6CD0082C12D89DF820302D -:102FD000621E23FA02F2D50706D54FF0FF3202FA3D -:102FE00004F423438DF820309DF8203089F8003018 -:102FF00051E7102C12D8BDF82030621E23FA02F2DD -:10300000D10706D54FF0FF3202FA04F42343ADF89E -:103010002030BDF82030A9F800303CE7202C0FD834 -:103020000899631E21FA03F3DA0705D54FF0FF3242 -:1030300002FA04F40C430894089BC9F800302AE70C -:10304000402C2BD0DDE90865611EC4F12102A4F1FA -:10305000210326FA01F105FA02F225FA03F31143DE -:103060001943CB0712D50122A4F12003C4F120019A -:1030700002FA03F322FA01F1A240524243EA0103A9 -:1030800063EB430332432B43CDE90823DDE90823F7 -:10309000C9E90023FFE66FF00100FCE66FF00800CD -:1030A000F9E6082CA0D9102CB3D9202CEED8C3E710 -:1030B000BBF1000FADD0022383E7BBF1000FBBD003 -:1030C00004237EE730B5012A144638BF0124402C82 -:1030D00085B028BF40240025012ACDE9025518D823 -:1030E0001B788DF8083063070AD004AB03EBD405D6 -:1030F000624215F8083C02F00702934005F8083CCC -:10310000009103462246002102A8FFF727FB05B0E5 -:1031100030BD082AE4D9102A03D81B88ADF808303E -:10312000E1E7202A8DBFD3E900231B680293CDE994 -:103130000223D8E710B5CB681BB98B600B618B827B -:1031400010BD04691A681C600361C38A013BC38215 -:10315000CA60F0E703064CBFC0F3C03002207047DE -:1031600008B50246FFF7F6FF022806D15306C2F360 -:103170000F2001D100F0030008BDC2F30740FBE7B8 -:103180002DE9F04F93B0CDE903230A6804461046B9 -:10319000FFF7E0FF022814BFC2F306260026002A2C -:1031A0000D46824680F2F28112F0C04940F0EE8175 -:1031B000097B002900F0EA81022803D02378B3427A -:1031C00040F0E781C2F304630693104602F07F03E8 -:1031D0000593FFF7C5FF059B29444FEA834848EA5A -:1031E0000A4848EA4668CE7800230022CDE9082341 -:1031F000F309834648EA0008029367D0059B0093D1 -:1032000002466768534608A92046B847002800F0E0 -:10321000C381276A4FB9414604F10C00FFF702FB56 -:10322000074690B96FF0020054E03B6998450DD015 -:103230003F68002FF9D1414604F10C00FFF7F2FA84 -:1032400007460028EED0236A3B60276297F817C034 -:1032500006F01F08CCF3840CACEB08001FFA80FECC -:103260000028B8BF0EF12000A8EB0C031FFA83FE64 -:10327000D7E90221B8BF00B2002B0793BEBF0EF101 -:1032800020031BB2079352EA010338D0039BDFF8F7 -:1032900024E39A1A049B4FF0000C63EB010196455E -:1032A0007CEB01032BD36B7B97F81AE0734519D1A4 -:1032B000029B002B78D0012821DC7868F8B9DFF870 -:1032C000F0C2944570EB010316D337E0276A27B9A3 -:1032D0006FF00C0013B0BDE8F08F3B699845B5D096 -:1032E0003F68F4E7B24890427CEB010301D3002031 -:1032F000F0E7029B002BFAD0079B0F2B17DCFA7D1F -:10330000B30002F0030203F07C031343FB7539465C -:103310002046FFF707FB6B7BBB76029B3BB9FB7D2F -:10332000C3F38402013262F38603FB75D0E76A7B44 -:10333000BB7E9A42DBD1029B002B35D0B309022B16 -:1033400032D0039BBB60049BFB60142200210DA8BC -:10335000FDF7E6FF039B0A93049B0B932B1D0C9335 -:103360002B7BADF83EB0013BDBB2ADF83C30069BA9 -:103370008DF84230059B8DF8433094F82C308DF851 -:1033800040A083F001038DF844308DF84180A3689C -:103390000AA920469847FB7DC3F38403013303F059 -:1033A0001F039B02FB82A2E7FB7DC6F34012B2EB38 -:1033B000D31F40F0F480C3F38403434540F0F28010 -:1033C000029A2B7BB609002A4DD0F2075DD4032B5D -:1033D00040F2EB80039BBB60049BFB602B7BAE1D2C -:1033E000033BDBB23246394604F10C00FFF7ACFA7E -:1033F00000280CDA39462046FFF794FAFB7DC3F328 -:103400008403013303F01F039B02FB820AE7DDE91B -:103410000884AB883B834FF6FF73C9F12000A9F104 -:10342000200228FA09F104FA00F0014324FA02F21A -:1034300011431846C9B2FFF7C9F909F10809B9F1F2 -:10344000400F0346E9D1B8822A7B033AD2B2314613 -:10345000FFF7CEF9FB7DB882DA43C2F3C01262F304 -:10346000C713FB7543E786B92E1D013BDBB232461D -:10347000394604F10C00FFF767FA0028BADB2A7B13 -:10348000B88A013AD2B23146E2E7F98AC1F30901BA -:10349000013B0429DAB25BD8281D002307F11B0683 -:1034A0009A4208D910F801CB06F801C00131013366 -:1034B0000529DBB2F4D103990A9104990B91934247 -:1034C00007F11B010C9138BF043379680D9134BFAB -:1034D00055FA83F300230E93FB8AADF83EB0C3F395 -:1034E00009031A44069B8DF84230059B8DF8433042 -:1034F00094F82C30ADF83C2083F001038DF8443073 -:1035000000238DF840A08DF841807B602A7BB88A2B -:10351000013A291DFFF76CF93B8BB882834203D136 -:10352000A3680AA92046984720460AA9FFF702FE89 -:10353000FB7DBA8AC3F38403013303F01F039B02AC -:10354000FB823B8B9A420CBF00206FF01000C1E65B -:103550007B68002BAFD0052001E01C3033461E688D -:10356000002EFAD1091A081D2E1D184401EB090C72 -:10357000BCF11B0F5FFA89F39DD89A429BD916F8CC -:10358000013B00F8013B09F10109EFE76FF0090089 -:10359000A0E66FF00A009DE66FF00B009AE66FF070 -:1035A0000D0097E66FF00E0094E66FF00F0091E6C5 -:1035B00040420F0080841E00EFF3098305494A6BE7 -:1035C00022F001024A63683383F30988002383F3FE -:1035D0001188704700EF00E0302080F3118862B658 -:1035E0000C4B0D4AD96821F4E0610904090C0A4327 -:1035F000DA60D3F8FC20094942F08072C3F8FC205D -:103600000A6842F001020A602022DA7783F8220079 -:10361000704700BF00ED00E00003FA05001000E075 -:1036200010B5302383F311880E4B5B6813F40063ED -:1036300014D0F1EE103AEFF30984683C4FF0807338 -:10364000E361094BDB6B236684F3098800F0A4F87F -:1036500010B1064BA36110BD054BFBE783F3118846 -:10366000F9E700BF00ED00E000EF00E0030600080E -:10367000060600084FF0E023002258684FF0FF31A3 -:10368000930003F1604303F5614301329042C3F8B4 -:103690008010C3F88011F3D27047000000F160433E -:1036A00003F561430901C9B283F80013012200F058 -:1036B0001F039A4043099B0003F1604303F56143F4 -:1036C000C3F880211A60704700230375826803697C -:1036D0001B6899689142FBD25A680360426010608F -:1036E0005860704700230375826803691B689968F6 -:1036F0009142FBD85A68036042601060586070477E -:1037000008B50846302383F311880B7D032B05D0C1 -:10371000042B0DD02BB983F3118808BD8B690022CF -:103720001A604FF0FF338361FFF7CEFF0023F2E70B -:10373000D1E9003213605A60F3E70000FFF7C4BF1D -:10374000054BD9680875186802681A605360012231 -:103750000275D860FCF740BF2038002030B50C4B14 -:10376000DD684B1C87B004460FD02B46094A6846DB -:1037700000F050F92046FFF7E3FF009B13B16846C5 -:1037800000F052F9A86907B030BDFFF7D9FFF9E79B -:103790002038002001370008044B1A68DB68906865 -:1037A0009B68984294BF0020012070472038002079 -:1037B000084B10B51C68D86822681A605360012253 -:1037C0002275DC60FFF78EFF01462046BDE8104001 -:1037D000FCF702BF20380020044B1A68DB689268AF -:1037E0009B689A4201D9FFF7E3BF70472038002059 -:1037F00038B5074C07490848012300252370656048 -:1038000000F000FC0223237085F3118838BD00BF4F -:10381000483A0020B84700082038002008B572B6A2 -:10382000044B186500F0B6FA00F06EFB024B032261 -:103830001A70FEE720380020483A002000F02AB92C -:10384000EFF3118020B9EFF30583302282F3118862 -:103850007047000010B530B9EFF30584C4F30804D5 -:1038600014B180F3118810BDFFF7B6FF84F31188FF -:10387000F9E700008B60022308618B8208467047DD -:103880008368A3F1840243F8142C026943F8442CA2 -:10389000426943F8402C094A43F8242CC26843F893 -:1038A000182C022203F80C2C002203F80B2C044ADB -:1038B00043F8102CA3F12000704700BFF105000869 -:1038C0002038002008B5FFF7DBFFBDE80840FFF710 -:1038D00035BF0000024BDB6898610F20FFF730BF57 -:1038E00020380020302383F31188FFF7F3BF000056 -:1038F00008B50146302383F311880820FFF72EFF17 -:10390000002383F3118808BD10B503689C68A242A8 -:103910000CD85C688A600B604C60216059609968C3 -:103920008A1A9A604FF0FF33836010BD1B68121B28 -:10393000ECE700000A2938BF0A2170B504460D469D -:103940000A26601900F058FB00F044FB041BA54256 -:1039500003D8751C2E460446F3E70A2E04D9BDE8A9 -:103960007040012000F08EBB70BD0000F8B5144B14 -:103970000D46D96103F1100141600A2A196982607C -:1039800038BF0A22016048601861A818144600F088 -:1039900025FB0A2700F01EFB431BA342064606D365 -:1039A0007C1C281900F028FB27463546F2E70A2F31 -:1039B00004D9BDE8F840012000F064BBF8BD00BFA9 -:1039C00020380020F8B506460D4600F003FB0F4AEC -:1039D000134653F8107F9F4206D12A4601463046CF -:1039E000BDE8F840FFF7C2BFD169BB68441A2C1983 -:1039F00028BF2C46A34202D92946FFF79BFF224647 -:103A000031460348BDE8F840FFF77EBF203800206C -:103A10003038002010B4C0E9032300235DF8044BC4 -:103A20004361FFF7CFBF000010B5194C23699842DE -:103A30000DD0D0E90032816813605A609A680A4458 -:103A40009A60002303604FF0FF33A36110BD23464B -:103A5000026843F8102F53600022026022699A42E4 -:103A600003D1BDE8104000F0C1BA936881680B44EF -:103A7000936000F0AFFA2269E1699268441AA242A9 -:103A8000E4D91144BDE81040091AFFF753BF00BF45 -:103A9000203800202DE9F047DFF8BC8008F110073E -:103AA0002C4ED8F8105000F095FAD8F81C40AA68AF -:103AB000031B9A423ED81444D5E900324FF0000966 -:103AC000C8F81C4013605A60C5F80090D8F8103050 -:103AD000B34201D100F08AFA89F31188D5E90331A4 -:103AE00028469847302383F311886B69002BD8D080 -:103AF00000F070FA6A69A0EB04094A4582460DD2CB -:103B0000022000F0BFFA0022D8F81030B34208D1EA -:103B100051462846BDE8F047FFF728BF121A224455 -:103B2000F2E712EB090938BF4A4629463846FFF743 -:103B3000EBFEB5E7D8F81030B34208D01444211A90 -:103B4000C8F81C00A960BDE8F047FFF7F3BEBDE868 -:103B5000F08700BF30380020203800200020704758 -:103B6000FEE70000704700004FF0FF307047000094 -:103B7000BFF34F8F024A1369DB03FCD4704700BFC9 -:103B80000020024008B5094B1B7873B9FFF7F0FF1E -:103B9000074B5A69002ABFBF064A9A6002F1883271 -:103BA0009A601A6822F480621A6008BD603A0020A8 -:103BB000002002402301674508B50B4B1B7893B9E1 -:103BC000FFF7D6FF094B5A6942F000425A611A6862 -:103BD00042F480521A601A6822F480521A601A68FD -:103BE00042F480621A6008BD603A00200020024062 -:103BF0007F289ABF00F58030C00200207047000087 -:103C00004FF4006070470000802070477F2808B59F -:103C10000BD8FFF7EDFF00F500630268013204D115 -:103C200004308342F9D1012008BD0020FCE70000E8 -:103C30007F2810B504461FD8FFF79AFFFFF7A2FFB1 -:103C40000E4BF3221A6102225A615A6942EAC002FB -:103C50005A615A6942F480325A61FFF789FF4FF482 -:103C60000061FFF7C5FF00F04BF9FFF7A5FF204605 -:103C7000BDE81040FFF7CABF002010BD0020024081 -:103C80002DE9F84340EA020313F00703144606D077 -:103C9000304B40F231321A600020BDE8F8838518BD -:103CA0002D4A95420CD92B4A40F236311160F3E788 -:103CB000031D1B684A68934208D1083C083008314C -:103CC000072C14D902680B689A42F1D0FFF75AFF0B -:103CD000FFF74EFF214E08314FF001084FF0000969 -:103CE000012CA1F1080706D8FFF766FF01E0002CC0 -:103CF000ECD10120D1E7C6F81480054651F8083C04 -:103D000045F8043B51F8043C4360FFF731FF336949 -:103D100043F001033361C6F81490026851F8083C7F -:103D20009A420CD00B4B40F25E321A600C4B18607A -:103D30000C4B1C600C4B1F60FFF73EFFACE72D687F -:103D400051F8043C9D4201F10801EBD1083C0830D8 -:103D5000C6E700BF5C3A00200000040800200240D3 -:103D6000503A0020583A0020543A0020084908B53B -:103D70000B7828B11BB9FFF705FF01230B7008BDB5 -:103D8000002BFCD0BDE808400870FFF715BF00BF4E -:103D9000603A00204FF480314FF0005000F0B2B88C -:103DA0000846114600F014BC012000F011BC0000D0 -:103DB000084600F02BBC000070B582B0FFF740FD54 -:103DC0000E4E054600F006F93268904237BF0C4AA5 -:103DD0000B49516814682EBFD1E90041013151608F -:103DE0000419034641F10001284601913360FFF7B1 -:103DF00031FD0199204602B070BD00BF643A002039 -:103E0000683A002070B582B0FFF71AFD104E0546E3 -:103E100000F0E0F83268904237BF0E4A0D49516811 -:103E200014682EBFD1E9004101315160041941F1FC -:103E300000010346284601913360FFF70BFD01990D -:103E40004FF47A7200232046FCF7B2F902B070BD3D -:103E5000643A0020683A002010B50244064BD2B202 -:103E6000904200D110BD441C00B253F8200041F82C -:103E7000040BE0B2F4E700BF50280040114B30B50E -:103E8000D3F89040240409D4D3F89040C3F890406C -:103E9000D3F8904044F40044C3F890400A4C23689F -:103EA00043F4807323600244084BD2B2904200D1A5 -:103EB00030BD441C00B251F8045B43F82050E0B21E -:103EC000F4E700BF0010024000700040502800409E -:103ED00007B5012201A90020FFF7BEFF019803B03A -:103EE0005DF804FB13B50446FFF7F2FFA04205D0CE -:103EF000012201A900200194FFF7C0FF02B010BD0C -:103F0000704700007047000070470000074B45F203 -:103F100055521A6002225A6040F6FF729A604CF6BF -:103F2000CC421A60024B01221A70704700300040E8 -:103F3000743A0020034B1B781BB1034B4AF6AA22AC -:103F40001A607047743A002000300040054B1A6830 -:103F500032B902F1804202F50432D2F894201A609C -:103F6000704700BF703A0020024B4FF40002C3F8C4 -:103F7000942070470010024008B5FFF7E7FF024B9E -:103F80001868C0F3407008BD703A00207047000008 -:103F9000FEE700000A4B0B480B4A90420BD30B4B39 -:103FA000DA1C121AC11E22F003028B4238BF002213 -:103FB0000021FDF7B5B953F8041B40F8041BECE7EA -:103FC00054480008003B0020003B0020003B00203C -:103FD00000F0BEB84FF08043586A70474FF08043FE -:103FE000002258631A610222DA6070474FF0804362 -:103FF0000022DA60704700004FF08043586370473A -:10400000FEE7000070B51B4B01630025044686B037 -:10401000586085620E46FFF7DFFA04F11003C4E929 -:1040200004334FF0FF33C4E90635C4E90044A5600A -:10403000E562FFF7CFFF2B460246C4E9082304F1EF -:1040400034010D4A256580232046FFF713FC012328 -:10405000E0600A4A0375009272680192B268CDE985 -:104060000223074B6846CDE90435FFF72BFC06B069 -:1040700070BD00BF483A0020C4470008C947000887 -:1040800001400008024AD36A1843D062704700BF5B -:1040900020380020244B2548DA6A42F0070210B489 -:1040A000DA62DA6A224C22F00702DA62DA6ADA6C41 -:1040B00042F00702DA64DA6E42F00702DA664FF085 -:1040C0009042DB6E4FF0AA31002353609160D060C4 -:1040D0004FF6FF7050611362536214601024C2F8EF -:1040E0000434C2F80814C2F80C444FF6F774C2F84E -:1040F00014449924C2F82034C2F824440D4CC2F868 -:104100000044C2F80438C2F80818C2F80C38C2F8E3 -:104110001408C2F82038C2F82438C2F800385DF814 -:10412000044B00F055B800BF00100240000100240D -:104130000001002850000A0008B500F005FAFFF75A -:1041400057FBBDE80840FFF701BF000070470000C3 -:104150000F4B9A6D42F001029A659A6F42F001028C -:104160009A670C4A9B6F936843F0010393604FF08A -:1041700080434F229A624FF0FF32DA6200229A6146 -:104180005A63DA605A6001225A611A60704700BFB0 -:1041900000100240002004E04FF0804208B5116991 -:1041A000D3680B40D9B2C9439B07116107D53023AF -:1041B00083F31188FFF742FB002383F3118808BDC6 -:1041C00008B5FFF757FABDE8084000F099B90000BC -:1041D0005A4B4FF0FF319A6A99629A6A00229A62AA -:1041E000986AD86A60F00700D862D86A00F00700C1 -:1041F000D862D86A186B1963186B1A63186B986BBE -:104200009963986B9A63986BD86BD963D86BDA63B0 -:10421000D86B186C1964196C1A641A6C484A4FF4FC -:10422000E06111601A6E474942F001021A66D3F844 -:10423000802022F00102C3F88020D3F880209A6DFC -:1042400042F080529A659A6F22F080529A679A6F74 -:104250004FF440720A604A6912F48062FBD14A60EE -:104260001A6822F0F00242F060021A601A6842F006 -:1042700001021A601A689107FCD500229A609A68B8 -:1042800012F00C02FBD1D3F8901011F4407F1EBF46 -:104290004FF48031C3F89010C3F8902061221A6067 -:1042A0001A689207FCD500229A609A6812F00C0FE7 -:1042B000FBD169221A60D3F8942022F4706242F490 -:1042C000C062C3F894201A6842F480321A601A68F7 -:1042D0009003FCD5D3F8902022F00322C3F890205D -:1042E000194ADA601A6842F080721A601A689101FD -:1042F000FCD5164A1A611A6842F080621A601A6880 -:104300001201FCD500229A600D49114AC3F8882099 -:104310000A6822F0070242F004020A600A6802F00A -:104320000702042AFAD19A6842F003029A609A6856 -:1043300002F00C020C2AFAD1704700BF00100240B4 -:10434000002002400070004003140001000C100027 -:1043500055550134074A08B5536903F00103536109 -:1043600023B1054A13680BB150689847BDE808406F -:10437000FFF756B900040140783A0020074A08B513 -:10438000536903F00203536123B1054A93680BB1EB -:10439000D0689847BDE80840FFF742B900040140E3 -:1043A000783A0020074A08B5536903F004035361C3 -:1043B00023B1054A13690BB150699847BDE808401D -:1043C000FFF72EB900040140783A0020074A08B5EB -:1043D000536903F00803536123B1054A93690BB194 -:1043E000D0699847BDE80840FFF71AB900040140BA -:1043F000783A0020074A08B5536903F01003536167 -:1044000023B1054A136A0BB1506A9847BDE80840CA -:10441000FFF706B900040140783A0020164B10B5AA -:104420005C6904F478725A61A30604D5134A936A4E -:104430000BB1D06A9847600604D5104A136B0BB1D4 -:10444000506B9847210604D50C4A936B0BB1D06B87 -:104450009847E20504D5094A136C0BB1506C984794 -:10446000A30504D5054A936C0BB1D06C9847BDE801 -:104470001040FFF7D5B800BF00040140783A002093 -:10448000194B10B55C6904F47C425A61620504D58D -:10449000164A136D0BB1506D9847230504D5134A86 -:1044A000936D0BB1D06D9847E00404D50F4A136E9D -:1044B0000BB1506E9847A10404D50C4A936E0BB112 -:1044C000D06E9847620404D5084A136F0BB1506F41 -:1044D0009847230404D5054A936F0BB1D06F9847D2 -:1044E000BDE81040FFF79CB800040140783A002076 -:1044F00008B5FFF751FEBDE80840FFF791B800008E -:10450000062108B50846FFF7C9F806210720FFF77E -:10451000C5F806210820FFF7C1F806210920FFF79A -:10452000BDF806210A20FFF7B9F806211720FFF78A -:10453000B5F806212820FFF7B1F8BDE808400721AB -:104540001C20FFF7ABB8000008B5FFF739FE00F0FC -:1045500007F8FFF7FBFDBDE80840FFF739BD000095 -:104560000023054A19460133102BC2E9001102F15C -:104570000802F8D1704700BF783A00200B46014688 -:10458000184600F02DB8000000F040B8012838BFF0 -:10459000012010B50446204600F030F830B900F094 -:1045A00007F808B900F00CF88047F4E710BD0000E8 -:1045B000024B1868BFF35B8F704700BFF83A0020CA -:1045C00008B5062000F084F80120FFF7C9FA0000C2 -:1045D000024B0A4601461868FFF7E2BB181100209B -:1045E00010B5054C13462CB10A4601460220AFF324 -:1045F000008010BD2046FCE700000000024B014691 -:104600001868FFF7D1BB00BF18110020024B01460C -:104610001868FFF7CDBB00BF1811002010B5013995 -:104620000244904201D1002005E0037811F8014FC7 -:10463000A34201D0181B10BD0130F2E72DE9F04173 -:10464000A3B1C91A17780144044603F1FF3C8C4218 -:10465000204601D9002009E00578BD4204F101049B -:10466000F5D10CEB0405D618A54201D1BDE8F081C7 -:1046700015F8018D16F801EDF045F5D0E7E70000DB -:104680001F2938B504460D4604D9162303604FF0A0 -:10469000FF3038BD426C12B152F821304BB9204680 -:1046A00000F030F82A4601462046BDE8384000F0C8 -:1046B00017B8012B0AD0591C03D11623036001201F -:1046C000E7E7002442F82540284698470020E0E725 -:1046D000024B01461868FFF7D3BF00BF1811002036 -:1046E00038B5074D00230446084611462B60FFF7F6 -:1046F0003BFA431C02D12B6803B1236038BD00BFD5 -:10470000FC3A0020FFF72ABA034611F8012B03F800 -:10471000012B002AF9D170476F72672E61726475A0 -:1047200070696C6F742E4D6174656B4C3433312D30 -:10473000414453420000000040A2E4F16468910645 -:104740000041A3E5F2656992070000004261642020 -:1047500043414E496661636520696E6465782E0049 -:1047600080000000008000000000800000000000C9 -:1047700000000000291B0008112300087122000816 -:10478000391B00086D1B0008691D00083D1B00084F -:104790004D1B0008411B0008491B0008451B000871 -:1047A000911C0008511B0008DD250008611B000852 -:1047B000651C000863300000B4470008783800200A -:1047C000483A00206D61696E0069646C6500000004 -:1047D00010BAFF7F01000000260400000000000066 -:1047E0000060030000000000FE2A0100D204000067 -:1047F0001C1100200000000000000000000000006C -:1048000000000000000000000000000000000000A8 -:104810000000000000000000000000000000000098 -:104820000000000000000000000000000000000088 -:104830000000000000000000000000000000000078 -:104840000000000000000000000000000000000068 -:044850000000000064 +:1000000000090020B1010008D9220008912200084F +:10001000B922000891220008B1220008B3010008AB +:10002000B3010008B3010008B3010008CD32000895 +:10003000B3010008B3010008B3010008B3010008D0 +:10004000B3010008B3010008B3010008B3010008C0 +:10005000B3010008B30100082D4000085540000816 +:100060007D400008A5400008CD400008B30100080D +:10007000B3010008B3010008B3010008B301000890 +:10008000B3010008B3010008B301000845220008CD +:100090007122000881220008B3010008F540000821 +:1000A000B3010008B3010008B3010008B301000860 +:1000B000C9410008B3010008B3010008B3010008FA +:1000C000B3010008B3010008B3010008B301000840 +:1000D000B3010008B3010008B3010008B301000830 +:1000E00059410008B3010008B3010008B30100083A +:1000F000B3010008B3010008B3010008B301000810 +:10010000B3010008B3010008B3010008B3010008FF +:10011000B3010008B3010008B3010008B3010008EF +:10012000B3010008B3010008B3010008B3010008DF +:10013000B3010008B3010008B3010008B3010008CF +:10014000B3010008B3010008B3010008B3010008BF +:10015000B3010008B3010008B3010008B3010008AF +:10016000B3010008B3010008B3010008B30100089F +:10017000B3010008B3010008B3010008B30100088F +:10018000B3010008B3010008B3010008B30100087F +:10019000B3010008B3010008B3010008B30100086F +:1001A000FD0E00080000000000000000000000003C +:1001B00002E000F000F8FEE772B6374880F30888E6 +:1001C000364880F3098836483649086040F2000016 +:1001D000CCF200004EF63471CEF200010860BFF39D +:1001E0004F8FBFF36F8F40F20000C0F2F0004EF669 +:1001F0008851CEF200010860BFF34F8FBFF36F8FBD +:100200004FF00000E1EE100A4EF63C71CEF2000114 +:100210000860062080F31488BFF36F8F03F022FD7F +:1002200003F0A4FD4FF055301F491B4A91423CBFDB +:1002300041F8040BFAE71D49184A91423CBF41F8C6 +:10024000040BFAE71A491B4A1B4B9A423EBF51F86E +:10025000040B42F8040BF8E700201849184A9142B1 +:100260003CBF41F8040BFAE703F000FD03F0D0FDBA +:10027000144C154DAC4203DA54F8041B8847F9E7D7 +:1002800000F042F8114C124DAC4203DA54F8041B52 +:100290008847F9E703F0E8BC0009002000110020BE +:1002A0000000000808ED00E0000100200009002027 +:1002B000A8440008001100207C11002080110020BB +:1002C000FC3A0020A0010008A4010008A4010008D5 +:1002D000A40100082DE9F04F2DED108AC1F80CD0D3 +:1002E000C3689D46BDEC108ABDE8F08F002383F300 +:1002F00011882846A047002003F058F9FEE703F0D4 +:10030000E1F800DFFEE70000F8B500F009FE03F0B9 +:100310004BFC074603F09CFC0646C0BB274B9F42A4 +:1003200035D001339F4235D0254B27F0FF029A424A +:1003300033D1F8B200F03AFC354642F2107400F0C6 +:100340003BFC08B10024254601F0A2F848B3032085 +:1003500000F03AF80024254636B11A4B9F4203D0EC +:1003600003F06EFC00242546002003F027FC0DB1AD +:1003700000F040F800F052FC01F0B6FF0546ACB9C1 +:1003800000F094FC4FF47A7003F016F9F7E7354665 +:100390000024D4E704460125D1E705464FF47A74DA +:1003A000CDE7B4F57A7F08BF0125D5E701F09CFFC2 +:1003B000431BA342E4D900F01DF8DDE7010007B0BC +:1003C000000008B0263A09B0084B187003280CD872 +:1003D000DFE800F008050208022000F0FFBD02205F +:1003E00000F0F2BD024B00225A60704780110020DD +:1003F0008411002010B501F04BF830B1234B0322DB +:100400001A70234B00225A6010BD224B224A1C4610 +:1004100019680131F8D004339342F9D16268A242DD +:10042000F2D31E4B9B6803F1006303F520439A420D +:10043000EAD203F0D7FB03F0E9FB002000F08AFDCD +:100440000220FFF7C1FF164B9A6D00229A65996F43 +:100450009A67996FD96DDA65D96FDA67D96F196EB6 +:100460001A66D3F88010C3F88020D3F8803072B6B3 +:100470004FF0E0233021C3F8084DD4E9003281F376 +:1004800011889D4683F308881047BDE7801100203E +:100490008411002000A0000820A000080011002006 +:1004A00000100240094A136849F2690099B21B0C16 +:1004B00000FB01331360064B186844F2506182B2AE +:1004C000000C01FB0200186080B27047141100207C +:1004D0001011002010B500211022044600F098FDF4 +:1004E000034B03CB206061601868A06010BD00BFA3 +:1004F0009075FF1F2DE9F041ADF5507D0DF13C08E1 +:100500006EAC40F2751207460D4610A80021C8F8DF +:10051000001000F07DFD4FF4C4720021204600F071 +:1005200077FD01F0E1FE254B4FF47A72B0FBF2F05B +:10053000186093E80700022384E807000DF5ED70CA +:100540002382FFF7C7FF42F204631D49238407A8F3 +:1005500003F046FF1C2384F832310DF2EB226B448A +:100560000DF1340C1E4603CE6645106051603346D3 +:1005700002F10802F6D1306810604146012220469F +:1005800000F092FD00230393AB7E029305F1190363 +:10059000019380B20123CDE904800093E97E05A395 +:1005A000D3E90023384602F067FA0DF5507DBDE827 +:1005B000F08100BF9E6AC421818A46EE8C11002022 +:1005C000F04300082DE9F0412C4C237ADAB0804644 +:1005D0000D465BBB27A9284600F076FE074600289B +:1005E00042D19DF89D60C82E3ED801464FF4A662C8 +:1005F000204600F00DFD4FF48073C4F8F8314FF43D +:100600000073C4F80C334FF44073C4F820343246FE +:100610000DF19E0104F1090000F0E8FC26449DF86C +:100620009C30777223720BB9EB7E237281220021FA +:1006300006AC27A800F0ECFC0122214627A800F018 +:100640007FFE00230393AB7E029305F1190380B272 +:1006500001932823CDE904400093E97E05A3D3E963 +:100660000023404602F008FA5AB0BDE8F08100BF0E +:10067000AFF3008026417272DF25D7B7B032002079 +:10068000F0B5254E4FF48A7505FB0065F1B096F87C +:10069000D83085F8DC300024D822214685F8E8409F +:1006A0003AA800F0B5FC06F1090000F0A9FCD5F865 +:1006B000E4308DF8F000C2B206AF06F109010DF189 +:1006C000F100CDE93A3400F091FC394601223AA814 +:1006D00000F062FE80B2CDE9047008230127CDE965 +:1006E000023706F1D803019330230093317A0B4887 +:1006F00007A3D3E9002302F0BFF9A04206DD01F011 +:10070000F3FDC5F8E000384671B0F0BD2046FBE7C8 +:1007100078F6339F93CACD8DB0320020A4210020FB +:100720002DE9F0411D4D1E4E1E4F86B0284602F0A9 +:10073000CFF9034658B30024CDE90344ADF8144083 +:10074000027B8DF8142099684068029403AA03C2C2 +:100750001B68DFF8548043F00043029301F0C6FDAC +:10076000821941F10003009402A9384601F06EF8A5 +:10077000A04205DD284602F0AFF988F80040D5E731 +:1007800098F80030072B05D8013388F8003006B000 +:10079000BDE8F081014802F09FF9F8E7A4210020AC +:1007A00040420F00D8210020E537002070B50D46EB +:1007B00014461E4602F0BCF850B9022E10D1012C8E +:1007C0000ED112A3D3E90023C5E90023012007E0DD +:1007D000282C10D005D8012C09D0052C0FD00020D2 +:1007E00070BD302CFBD10BA3D3E90023ECE70BA3A6 +:1007F000D3E90023E8E70BA3D3E90023E4E70BA345 +:10080000D3E90023E0E700BFAFF30080401DA12043 +:1008100026812A0B78F6339F93CACD8D9E6AC42118 +:10082000818A46EE26417272DF25D7B7F017304A2B +:1008300039059E5638B505460E4C0021013500F0AD +:10084000ABFBA4F82C55B4F82C0500F08DFB78B167 +:10085000B4F82C0500F098FB014648B9B4F82C0513 +:1008600000F09AFBB4F82C350133A4F82C35EAE7F4 +:1008700038BD00BFB032002010B50A4B0A4A1A60DA +:1008800003F5805393F860203AB9DC6D2CB1204613 +:1008900000F07CFE204603F0E3FCBDE81040034876 +:1008A00000F074BED82100204C4400082032002003 +:1008B0002DE9F04F8FB000AF05460C4602F038F836 +:1008C000002849D1237E022B1BD1E38A012B18D1AA +:1008D00001F00AFD0646FFF7E5FD03464FF4C87038 +:1008E000DFF8C482B3FBF0F206F5167602FB103394 +:1008F00016FA83F3C8F80030E37E33B9A34B002225 +:100900001A703C37BD46BDE8F08F07F12401204640 +:1009100000F098FC0028F4D107F11400FFF7DAFD8D +:1009200097F8264007F11401224607F1270003F04B +:10093000E1FC0028E2D10F2C08D8944B1C70D8F8A9 +:100940000030A3F51673C8F80030DAE797F82410E2 +:10095000284601F0E5FFD4E7E38A282B2BD010D8F6 +:10096000012B23D0052BCCD1BFF34F8F8849894B66 +:10097000CA6802F4E0621343CB60BFF34F8F00BF3D +:10098000FDE7302BBDD1844EE17E327A9142B8D161 +:10099000607E3146002291F8DC50854200F0A5804F +:1009A0000132042A01F58A71F5D1AAE721462846C9 +:1009B000FFF7A0FDA5E721462846FFF703FEA0E7C5 +:1009C000B2F8EC507B6005F103094FEA99094FEA50 +:1009D0008902D11DC908A8EBC1039D46EB46002141 +:1009E000584600F015FB04F1EE012A463144584602 +:1009F00000F0FCFA7B6813B9012000F0ABFA96F81E +:100A0000D20000F0B1FA044630B9307200F0CCFAEE +:100A1000204600F09FFAB1E0D6F8D4203AB996F813 +:100A2000D200B6F82C25824201D8FFF703FFD6F892 +:100A3000D4202A44944208D296F8D200B6F82C2545 +:100A40000130824201D8FFF7F5FE70685FFA89F243 +:100A5000594600F0E5FA08B9C54679E0726896F89B +:100A6000D2002A447260D6F8D42005EB0209C6F8F9 +:100A7000D49000F079FA814509D396F8D220D6F8BF +:100A8000D4000132001B86F8D220C6F8D400FF2D16 +:100A90000FD80024347200F087FA204600F05AFA8A +:100AA00000F0F6FC3D4B188108B9FFF7A3FCC546E2 +:100AB00027E7BB6896F8D9000AFB0362FB68D2F807 +:100AC000E41082F8E83001F58061C2F8E030C2F845 +:100AD000E410FFF7D5FDFFF723FE96F8D920013289 +:100AE00002F0030286F8D920B6E74FF48A7A0AFBAF +:100AF00002F505F1EA013144204600F079FCF86086 +:100B000000287FF4FEAE3544012285F8E82001F08C +:100B1000EBFBD5F8E020D6ED007ADFED216A801AF4 +:100B2000192838BF192040F6B832904228BF104625 +:100B3000B8EE677A07EE900AF8EEE77A67EEA67AE3 +:100B4000DFED186AE7EE267AFCEEE77AC6ED007A6A +:100B500096F8D930BB60BA6873680AFB02F43219A0 +:100B600092F8E81059B1D2F8E4108B42E8463FF40D +:100B700027AF002182F8E810C2F8E010C54673687C +:100B8000064A9B0A01331381BBE600BF9D2100206A +:100B900000ED00E00400FA05B03200208C110020C6 +:100BA000CDCCCC3D6666663FA0210020014B18707D +:100BB000704700BF9811002038B54FF00054134B18 +:100BC00022689A4220D1124B627D12481A70237D0E +:100BD00003724FF48073C0F8F8314FF40073C0F81B +:100BE0000C3300254FF44073C0F820340A49C0F894 +:100BF000E450C922093000F0F9F9E02229462046E4 +:100C000000F006FA012038BD0020FCE79AAD44C58B +:100C100098110020B03200201600002037B500F0F7 +:100C200037FC194D194928810223012218486B719C +:100C300001F0F6F900230193164B1749009317486A +:100C4000174B4FF4805201F043FE164B197811B147 +:100C5000124801F065FE01F047FB0446FFF722FC55 +:100C60004FF4C873B0FBF3F202FB130304F51670E4 +:100C700010FA83F00C4B186002F0EAFF08B10F2362 +:100C80002B8103B030BD00BF8C11002040420F000B +:100C9000D8210020AD0700089C110020A4210020CD +:100CA000B108000898110020A02100202DE9F04F84 +:100CB0002DED028B0FF23829D9E90089834C93B0CE +:100CC0000BAE9FED7E8BFFF72BFD814FDFF828A247 +:100CD00000230A93ADF834300B9373604FF0000B90 +:100CE0005B468DED008B01250DF11D0207A93846ED +:100CF0008DF81C508DF81DB001F040F99DF81C30A6 +:100D0000002B40F0A580204601F012FE0646002888 +:100D100045D1704F01F0E8FA3B6898423FD301F0AB +:100D2000E3FA8246FFF7BEFB4FF4C873B0FBF3F261 +:100D300002FB13030AF5167010FA83F03860664F51 +:100D400097F800B0CBF1100ABBF1000F14BF334687 +:100D50002B465FFA8AFA0EA88DF82830FFF7BAFB07 +:100D6000BAF1060F28BF4FF0060A0EAB03EB0B01DA +:100D700052460DF1290000F039F90AAB039318230C +:100D800002930AF10102554BD2B2CDE9005304920D +:100D900020464CA3D3E9002301F010FE3E7001F081 +:100DA000A3FA4F4A4F4D1368C31AB3F57A7F2ED377 +:100DB000106001F09BFA02460B46204601F096FEB9 +:100DC000204601F0B5FD10B32B7A474E002B14BF1F +:100DD00003230223737101F087FA0EAF4FF47A7385 +:100DE0000122B0FBF3F039463060304600F002FAE1 +:100DF000182302933D4B019380B240F25513CDE985 +:100E00000370009342464B46204601F0D7FD2B7AF3 +:100E100093B101F069FA002607464FF48A7A95F8F3 +:100E2000D900304400F003000AFB005393F8E82097 +:100E300092B30136042EF2D1C82002F0BDFB2B7A0A +:100E4000002B7FF43DAF13B0BDEC028BBDE8F08FFB +:100E5000DAF8143083F00803CAF814305946102227 +:100E60000EA800F0D5F80DF11E0308AA0AA938460D +:100E700000F0ECFD96E803000FAB83E803009DF85B +:100E800034308DF844300A9B0E930EA9DDE9082317 +:100E9000204601F0FFFF21E7D3F8E02042B12B68A4 +:100EA000FA2B38BFFA23BA1A0533B2EB430FC0D37B +:100EB000FFF7E6FB0028BCD1BEE700BF0000000042 +:100EC00000000000401DA12026812A0BA421002043 +:100ED000D8210020A02100209D2100209C2100205D +:100EE000E0370020B03200208C110020E4370020D1 +:100EF000F1C6A7C1D068080F0004004808B505482E +:100F000000F040FEBDE80840034A0449002003F019 +:100F1000A1B900BFD821002020380020790800089E +:100F200070B502F0E5FC094E094D308000242868B8 +:100F30003388834208D902F0D7FC2B68044401337C +:100F4000B4F5204F2B60F2D370BD00BF14380020E1 +:100F5000E837002002F07EBD00F10060920000F54D +:100F6000204002F001BD0000054B1A68054B1B88AC +:100F70009B1A834202D9104402F0B6BC002070478D +:100F8000E837002014380020024B1B68184402F098 +:100F9000B1BC00BFE8370020024B1B68184402F0C8 +:100FA000BBBC00BFE8370020064991F8243033B1BC +:100FB0000023086A81F824300822FFF7CDBF012002 +:100FC000704700BFEC370020022802BF024B4FF4ED +:100FD00000229A61704700BF00040048022802BF47 +:100FE000014B08229A6170470004004810B50023A5 +:100FF000934203D0CC5CC4540133F9E710BD000028 +:1010000003460246D01A12F9011B0029FAD1704793 +:1010100002440346934202D003F8011BFAE77047EB +:101020002DE9F8431F4D144695F8242007468846BD +:1010300052BBDFF870909CB395F824302BB9202276 +:10104000FF2148462F62FFF7E3FF95F82400C0F127 +:101050000802A24228BF2246D6B24146920005EBC2 +:101060008000FFF7C3FF95F82430A41B1E44F6B29E +:10107000082E17449044E4B285F82460DBD1FFF7D2 +:1010800093FF0028D7D108E02B6A03EB8203834249 +:10109000CFD0FFF789FF0028CBD10020BDE8F8832F +:1010A0000120FBE7EC3700202DE9F0470D46044610 +:1010B00000219046284640F27912FFF7A9FF234607 +:1010C00020220021284601F087FE231D0222202134 +:1010D000284601F081FE631D03222221284601F0EB +:1010E0007BFEA31D03222521284601F075FE04F195 +:1010F000080310222821284601F06EFE04F1100397 +:1011000008223821284601F067FE04F11103082265 +:101110004021284601F060FE04F112030822482114 +:10112000284601F059FE04F11403202250212846DC +:1011300001F052FE04F1180340227021284601F00C +:101140004BFE04F120030822B021284601F044FEA2 +:1011500004F121030822B821284601F03DFE04F1E4 +:101160002207C0263B46314608222846083601F0B1 +:1011700033FEB6F5A07F07F10107F3D104F1320386 +:1011800008223146284601F027FE002704F1330AE1 +:1011900094F832304FEAC7099F4209F5A47615D377 +:1011A000B8F1000F08D1314604F59973072228469B +:1011B00001F012FE09F24F16274694F832213B1B2C +:1011C00093420CD3F01DC008BDE8F0870AEB07037B +:1011D00008223146284601F0FFFD0137D8E707F223 +:1011E000331331460822284601F0F6FD0836013750 +:1011F000E3E7000013B504460846002101602346DA +:10120000C0F803102022019001F0E6FD0198231D93 +:101210000222202101F0E0FD0198631D032222211A +:1012200001F0DAFD0198A31D0322252101F0D4FD70 +:10123000019804F108031022282101F0CDFD0720B8 +:1012400002B010BDF7B50023047F00910E460722BF +:101250001946054601F084FC731C0093012200230B +:101260000721284601F07CFCC4B9B31C0093052279 +:1012700023460821284601F073FC0D243746B27836 +:10128000BB1B934211D32B7FA88A0734E408BBB958 +:10129000844294BF0020012003B0F0BDAB8ADB0084 +:1012A000083BDB08B3700824E8E7FB1C00932146E9 +:1012B00000230822284601F053FC08340137DEE7FA +:1012C000201A18BF0120E7E7F7B50023047F00913B +:1012D0000E4608221946054601F042FC731CC4B9AB +:1012E0000822009311462346284601F039FC1024B9 +:1012F000012372785F1C013B934211D32B7FA88A94 +:101300000734E408BBB9844294BF0020012003B035 +:10131000F0BDAB8ADB00083BDB0873700824E7E70D +:10132000F3190093214600230822284601F018FCF7 +:1013300008343B46DDE7201A18BF0120E7E700002C +:10134000F8B50E4605461446002181223046FFF7C7 +:101350005FFE2B4608220021304601F03DFD7CB99E +:101360006B1C07220821304601F036FD0F240123B3 +:101370006A785F1C013B934204D3E01DC008F8BDAE +:101380000824F4E7EB1921460822304601F024FD39 +:1013900008343B46ECE70000F8B50E460546144617 +:1013A0000021CE223046FFF733FE2B4628220021B3 +:1013B000304601F011FD7CB905F10803082228210F +:1013C000304601F009FD30242F462A7A7B1B9342D8 +:1013D00004D3E01DC008F8BD2824F5E707F1090390 +:1013E00021460822304601F0F7FC08340137ECE7CB +:1013F000F7B5047F00910E46012310220021054617 +:1014000001F0AEFBC4B9B31C00930922234610219E +:10141000284601F0A5FB192437467288BB1B9A4267 +:1014200011D82B7FA88A0734E408BBB9844294BF43 +:101430000020012003B0F0BDAB8ADB00103BDB08CD +:1014400073801024E8E73B1D009321460023082207 +:10145000284601F085FB08340137DEE7201A18BF63 +:101460000120E7E730B5094D0A4491420DD011F84B +:10147000013B5840082340F30004013B2C4013F08B +:10148000FF0384EA5000F6D1EFE730BD2083B8EDCA +:10149000F7B5384A106851686B4603C36A46364947 +:1014A0003648082302F036FF0446002833D10A25C7 +:1014B000334A106851686B4603C36A4631492F4866 +:1014C000082302F027FF0446002849D00369B3F53A +:1014D000583F45D8B0F8661040F2264291423FD1BD +:1014E000294A024402F15C018B4239D35C3B234917 +:1014F00000209E1AFFF7B6FF3246074604F164014A +:101500000020FFF7AFFFA3689F4229D1E36898420C +:1015100008BF002524E00369B3F5583F27D8418B65 +:1015200040F22642914220D1174A024402F11001B2 +:101530008B4218D3103B114900209D1AFFF792FFF0 +:101540002A46064604F118010020FFF78BFFA36826 +:101550009E4202D1E368984201D00D25A8E70025FC +:10156000284603B0F0BD1025A2E70C25A0E70B2507 +:101570009EE700BF10440008DC5F030000A00008E5 +:1015800019440008905F03000860FFF710B5037C62 +:10159000044613B9006802F0A5FE204610BD000005 +:1015A0000023BFF35B8FC360BFF35B8FBFF35B8F21 +:1015B0008360BFF35B8F7047BFF35B8F0068BFF33F +:1015C0005B8F704770B505460C30FFF7F5FF05F1EE +:1015D000080604463046FFF7EFFFA04206D9304622 +:1015E0006D68FFF7E9FF2544281A70BD3046FFF704 +:1015F000E3FF201AF9E7000070B50546406898B18E +:1016000005F10800FFF7D8FF05F10C060446304647 +:10161000FFF7D2FF8442304694BF6D680025FFF784 +:10162000CBFF013C2C44201A70BD000038B50C469D +:101630000546FFF7C7FFA04210D305F10800FFF7EA +:10164000BBFF04446868B4FBF0F100FB1144BFF336 +:101650005B8F0120AC60BFF35B8F38BD0020FCE7DF +:101660002DE9F041144607460D46FFF7C5FF8442B9 +:1016700028BF0446D4B1B84658F80C6B4046FFF773 +:101680009BFF3044286040467E68FFF795FF331A81 +:101690009C4203D86C600120BDE8F0816B60A41B04 +:1016A0003B68AB602044E8600220F5E72046F3E7A2 +:1016B00038B50C460546FFF79FFFA04210D305F151 +:1016C0000C00FFF779FF04446868B4FBF0F100FBFD +:1016D0001144BFF35B8F0120EC60BFF35B8F38BD1B +:1016E0000020FCE72DE9FF41884669460746FFF7E1 +:1016F000B7FF6C4606B204EBC6060025B44209D01B +:101700006268206808EB0501FFF770FC6368083425 +:101710001D44F3E729463846FFF7CAFF284604B0C0 +:10172000BDE8F081F8B505460C300F46FFF744FFE1 +:1017300005F1080604463046FFF73EFFA04230465A +:1017400088BF6C68FFF738FF201A386020B1304638 +:101750002C68FFF731FF2044F8BD000073B5144634 +:1017600006460D46FFF72EFF844228BF044601902F +:10177000DCB101A93046FFF7D5FF019B33B93268D0 +:10178000C5E90233C5E9002401200CE09C4238BFC2 +:1017900001942860019868608442F5D93368AB6091 +:1017A000241AEC60022002B070BD2046FBE7000066 +:1017B0002DE9FF410F466946FFF7D0FF6C4600B2A6 +:1017C00004EBC0050026AC4209D0D4F8048054F8DC +:1017D000081BB8194246FFF709FC4644F3E73046B8 +:1017E00004B0BDE8F081000038B50546FFF7E0FF22 +:1017F000044601462846FFF719FF204638BD000081 +:1018000010B4026854681A4623465DF8044B184722 +:10181000002070470020704770470000002070478C +:101820000E20704700F5805090F8C800C0F34000CB +:101830007047000000F5805090F9D000704700001C +:1018400000F58050C0F8CC1001207047F7B50C6847 +:10185000BDF8207014F0005470D10D7B082D6DD8A8 +:10186000302585F311884569AE6876010CD4AC68E3 +:10187000240108D4AC6814F080545DD184F311883D +:10188000204603B0F0BD01240E6804F1180C002EB0 +:10189000B8BFF6004FEA0C1CB4BF46F0040676054C +:1018A00045F80C600E680FFA84FC16F0804F18BFE4 +:1018B00005EB0C1E05EB0C1C1EBFDEF8806146F02C +:1018C0000206CEF880610E7BCCF8846105EB04152E +:1018D0008E68C5F88C614E68C5F88861DCF8805167 +:1018E00045F00105CCF8805100EB441641F2680543 +:1018F0002E4405EB44150544C6E9002308350E4681 +:1019000001F10C0C56F804EB45F804EB6645F9D1EF +:10191000843436882E8000EB441407F003052679C2 +:1019200026F00B0635432571002484F311880097B7 +:1019300000F0FCFC0120A4E70224A5E74FF0FF30F3 +:101940009FE7000013B500F580540191E06DFFF7AB +:1019500053FE1F280AD90199E06D2022FFF7C2FE2D +:10196000A0F120035842584102B010BD0020FBE70F +:1019700008B5302383F3118800F58050C06DFFF760 +:101980000FFE002383F3118808BD000000220260CF +:10199000828142608260704710B500220023C0E956 +:1019A00000230023044603810C30FFF7EFFF20469D +:1019B00010BD0000F0B5054600F580500C4690F8CB +:1019C000C83013F0040FC3F3800108BF114661F360 +:1019D000820304F1840680F8C83005EB461389B011 +:1019E0001B79D8072ED57AB319072DD46846FFF78F +:1019F000D3FF05EB441303F5835303F1180703AA40 +:101A0000103318685968144603C40833BB42224691 +:101A1000F7D1186820609B88A380DDE90E23CDE90B +:101A200000230123ADF808302B686946DB6B28469C +:101A3000984705EB46152B791A075CBF43F008035E +:101A40002B7101E0002AF4D109B0F0BD2DE9F04777 +:101A50009A4688B0074688469146302383F311881A +:101A600007F580546846FFF797FFE06DFFF7AAFD82 +:101A70001F282AD9E06D20226946FFF7B5FE2028ED +:101A800023D103AD444605AB2E4603CE9E422060D3 +:101A90006160354604F10804F6D130682060B388EF +:101AA000A380DDE90023C9E90023BDF80830AAF8C6 +:101AB0000030002383F3118853464A464146384696 +:101AC00008B0BDE8F04700F01FBC002080F311888B +:101AD00008B0BDE8F08700002DE9F84F0023C0E909 +:101AE0000133254B044640F8183B0F46FFF74EFFE5 +:101AF00004F12800FFF750FF04F1480804F582556F +:101B00004646083530462036FFF746FFAE42F9D14B +:101B100004F580554FF480534FF00009C5E913399F +:101B2000C5F848800123EE6504F5875804F584560E +:101B3000C5F8549085F8583085F86030083608F1BB +:101B400008084FF0000A4FF0000B46E908ABA6F179 +:101B50001800FFF71BFF203646F8289C4645F4D1B5 +:101B600085F8D07017B1054800F0B8FB044B6361ED +:101B70002046BDE8F88F00BF4C440008244400080C +:101B80000064004010B5044B197804464A1C1A70D2 +:101B9000FFF7A2FF204610BD1C3800202DE9F047BA +:101BA000002950D0294B2A4FB7FBF1F599428CBF41 +:101BB0000A231123581EB5FBF3FC03FB1C53C4B2CC +:101BC0002BB102280346F5D80020BDE8F0870CF1C0 +:101BD000FF36B6F5806FF7D2C4EBC40E0EF10303E7 +:101BE0004FEAE309C3F3C703A4EB030809F1010AB1 +:101BF0004FF47A755FFA88F009FB05555AFA88F8B0 +:101C0000B5FBF8F5B5F5617FC1BF0EF1FF33C3F346 +:101C1000C703E01AC0B25C1C50FA84F40CFB04F455 +:101C2000B7FBF4F4A142CFD1013BDBB20F2BCBD8F1 +:101C30000138C0B20728C7D80021107116809170F2 +:101C4000D3700120C1E70846BFE700BF3F420F0045 +:101C500000B4C40470B505460E464FF47A746B693F +:101C60005B6803F00103B34207D04FF47A7001F0D0 +:101C7000A3FC013CF3D1204670BD0120FCE700002D +:101C800030B54269936913F0700F16D000230B4CE6 +:101C9000936103F1840200EB421211794D0709D5DB +:101CA000890707D5416954F823508D60117941F0B7 +:101CB000040111710133032BEBD130BD384400080E +:101CC00073B51D46436916469A68D207044609D57E +:101CD0009A6801219960C2F34002CDE900650021B4 +:101CE000FFF768FE63699A68D1050BD59A684FF4CF +:101CF00080719960C2F34022CDE900650121204640 +:101D0000FFF758FE63699A68D2030BD59A684FF4BF +:101D100080319960C2F34042CDE90065022120463E +:101D2000FFF748FE04F58053D3F8CC0010B10368E8 +:101D30001B699847204602B0BDE87040FFF7A0BF7E +:101D4000F8B504464669002972D106F10C073868D7 +:101D5000800770D006EB01153868D5F8B00110F097 +:101D6000040FD5F8B0011ABFC00840F00040400D84 +:101D7000A061D5F8B0C11CF0020F1CBF40F080403C +:101D8000A061D5F8B40106EB011100F00F0084F852 +:101D90002400D1F8B8012077D1F8B801000A6077A3 +:101DA000D1F8B801000CA077D1F8B801000EE077A7 +:101DB000D1F8BC0184F82000D1F8BC01000A84F8F5 +:101DC0002100D1F8BC01000C84F82200D1F8BC112C +:101DD000090E84F823103821396004F1340004F12D +:101DE000180104F1240551F8046B40F8046BA94272 +:101DF000F9D109880180C4E90A23214600232386FA +:101E000051F8283B2046DB6B984704F5805393F844 +:101E1000C820D3F8CC0042F0040283F8C82010B1E7 +:101E200003681B6998472046BDE8F840FFF728BFC4 +:101E300006F110078BE7F8BD10B5044600F056FA1E +:101E400002460B4652EA030102D0013A63F1000355 +:101E50000449086820B12146BDE81040FFF770BF73 +:101E600010BD00BF18380020F0B5302181F3118873 +:101E7000DFF848C000F583510831002404F18405DF +:101E800000EB45152E7977070ED4F6060CD5D1E96F +:101E9000007697429E4107D246695CF82470B7608D +:101EA0002E7946F004062E710134032C01F1200135 +:101EB000E4D1002383F31188F0BD00BF384400084B +:101EC00008B5302383F31188FFF7DAFE002383F38C +:101ED000118808BDF8B543690546986800F0E050E0 +:101EE000B0F1E05F0F4621D0F8B1302383F31188C1 +:101EF00005F583541034002606F1840305EB4313E3 +:101F00001B791A0706D50136032E04F12004F3D1FC +:101F1000012007E05B07F6D42146384600F040FA7E +:101F20000028F0D1002383F31188F8BD0120FCE7DD +:101F300008B5302383F3118800F58050C06DFFF79A +:101F400041FB002383F3118843090CBF01200020CB +:101F500008BD0000F8B51D46002313700F46064665 +:101F60001446FFF7E5FF80F00100387025B12946DF +:101F70003046FFF7AFFF2070F8BD00002DE9B841F3 +:101F80000C4615461F46804600F0B0F90B462178F6 +:101F9000024609B9287850B14046FFF765FFFFF7C0 +:101FA0008FFF3B462A462146FFF7D4FF0120BDE8BC +:101FB000B881000070B5302686F31188174B9A6DF2 +:101FC00042F000729A659A6B42F000729A639A6BC3 +:101FD00022F000729A63002383F3118800F5805485 +:101FE00094F8C83013F0010516D1A9B186F3118811 +:101FF0000321132001F0DCF90321142001F0D8F9AA +:102000000321152001F0D4F994F8C83043F00103FE +:1020100084F8C83085F3118870BD00BF00100240FD +:102020002DE9F04700F5805588B095F8D030012BA8 +:1020300004468846164600F28180814F57F82320D7 +:102040000AB947F82300D7F800A0C4F80C8026741A +:10205000BAF1000F64D095F8D030012B70D0012177 +:102060002046FFF7A7FF302383F3118862691368C6 +:1020700023F0020313606269136843F001031360E5 +:10208000636900275F6187F3118801212046FFF70C +:10209000E1FD002800F09580E86DFFF781FA04F576 +:1020A0008359BA4609F10809202200216846FEF743 +:1020B000AFFF02A8FFF76AFCCDF818A06A4609EB4B +:1020C00007030DF1180E9446BCE80300F4451860B0 +:1020D0005960624603F10803F5D1DCF8000018608E +:1020E00020379CF804201A71602FDDD195F8C83094 +:1020F0006FF38203002785F8C8306A4641462046C0 +:10210000ADF80070ADF802708DF80470FFF746FD71 +:10211000636948BB4FF400421A6008B0BDE8F0871D +:1021200041F2D80002F09EF8814610B15146FFF707 +:10213000D3FCC7F80090B9F1000F8CD10020ECE778 +:10214000386803681B6B98470146002887D13868B8 +:10215000FFF730FF3868036832465B6841469847AE +:1021600000287FF47CAFE9E761221A609DF8023015 +:102170009DF803201B06120402F4702203F0407342 +:102180001343BDF80020C2F3090213439DF8042055 +:102190001205022E02F4E0020CBF4FF000410021B4 +:1021A000134362690B43D361636913225A61626905 +:1021B000136823F00103136039462046FFF74AFDF8 +:1021C00008B96369A6E795F8D03093BB6169D1F887 +:1021D000002242F00102C1F800226169D1F8002218 +:1021E00022F47C5222F00E02C1F800226169D1F87B +:1021F000002242F46062C1F800226269C2F814321F +:102200006269C2F80432626941F6FF71C2F80C12C9 +:102210006269C2F840326269C2F8443263690122DD +:10222000C3F81C226269D2F8003223F00103C2F81D +:10223000003295F8C83043F0020385F8C8306CE7E7 +:102240001838002008B500F051F850EA01030246A2 +:1022500002D0421E61F10001044B186810B10B4618 +:10226000FFF72EFDBDE8084001F064B818380020E3 +:1022700008B50020FFF7E0FDBDE8084001F05AB8BE +:1022800008B50120FFF7D8FDBDE8084001F052B8BD +:1022900000B59BB0EFF3098168226846FEF7A6FE01 +:1022A000EFF30583014B9B6BFEE700BF00ED00E001 +:1022B00008B5FFF7EDFF000000B59BB0EFF3098113 +:1022C00068226846FEF792FEEFF30583014B5B6BD5 +:1022D000FEE700BF00ED00E0FEE700000FB408B528 +:1022E000029801F019F9FEE701F0F8BB01F0DABB42 +:1022F00013B56C4684E80600031D94E8030083E8E8 +:102300000500012002B010BD73B58568019155B17B +:102310001B885B0707D4D0E900369B6B9847019A6E +:10232000C1B23046A847012002B070BDF0B5866842 +:1023300089B005460C465EB1BDF838305B070AD45B +:10234000D0E900379B6B98472246C1B23846B04768 +:10235000012009B0F0BD00220023CDE900230023B5 +:10236000ADF808300A4603AB01F108061068516861 +:102370001C4603C40832B2422346F7D110682060DD +:102380009288A280FFF7B2FF0423ADF808302B68D3 +:10239000CDE90001DB6B694628469847D8E7000085 +:1023A00030B503680968DD0FB5EBD17F23F06044D9 +:1023B00021F060424FEAD1700BD0002BB8BFA40CC3 +:1023C0000029B8BF920C944202D034BF01200020F3 +:1023D00030BD944205D1C1F38070C3F38073834252 +:1023E000F6D194422CBF00200120F1E72DE9F04105 +:1023F000456A15B94162BDE8F0814B6823F060473A +:10240000C3F38A464FEAD37EC3F3807816EA2306E5 +:1024100038BF3E46AC462B465A68BEEBD27F22F010 +:1024200060440AD0002A18DAA40CB44217D19D42A5 +:102430000FD10D60DEE71346EEE7A74207D102F0A9 +:102440008044C2F3807242450BD054B1EFE708D20A +:10245000EDE7CCF800100B60CDE7B44201D0B442F8 +:10246000E5D81A689C46002AE5D11960C3E7000048 +:102470002DE9F047089D01F007044FEAD5082244F2 +:1024800005F0070500EBD1004FF47F49944201D1DC +:10249000BDE8F08704F0070705F0070A57453E46F8 +:1024A00038BF5646C6F10806111B8E4228BF0E469D +:1024B000E10808EBD50E415C13F80EC0B94029FACB +:1024C00006F721FA0AF1FFB28CEA010147FA0AF78E +:1024D00039408CEA010C03F80EC034443544D5E78A +:1024E00080EA0120082341F2210201B240000029C4 +:1024F00080B203F1FF33B8BF504013F0FF03F4D1B3 +:102500007047000038B50C468D18A54200D138BD83 +:1025100014F8011BFFF7E4FFF7E7000042684AB137 +:10252000136843604389818901339BB29942438197 +:1025300038BF83811046704770B588B020220446AA +:102540000D4668460021FEF763FD20460495FFF71F +:10255000E5FF024658B16B46054608AE1C4603CC63 +:10256000B44228606960234605F10805F6D110469B +:1025700008B070BD082817D909280CD00A280CD03B +:102580000B280CD00C280CD00D280CD00E2814BF12 +:102590004020302070470C207047102070471420D6 +:1025A000704718207047202070470000082817D96E +:1025B0000C280CD910280CD914280CD918280CD99F +:1025C00020280CD930288CBF0F200E2070470920FE +:1025D00070470A2070470B2070470C2070470D2071 +:1025E000704700002DE9F843078C072F04461ED9D9 +:1025F000D0E9029800254FF6FF73C5F12006A5F13A +:10260000200029FA05F108FA06F628FA00F031430D +:102610000143C9B21846FFF763FF0835402D034652 +:10262000EBD1E1693A46BDE8F843FFF76BBF4FF6DF +:10263000FF70BDE8F883000010B54B6823B9CA8A63 +:1026400063F30902CA8210BD04691A681C60036141 +:10265000C38A013BC3824A60EFE700002DE9F84FCF +:102660001D46CB8A0F46C3F30901052981469246D0 +:102670000B4630D00020AAB207F11A049EB2042EF5 +:102680001FFA80F80FD8904503F1010306D3FB8AA7 +:102690000A4462F30903FB8201201AE01AF8006081 +:1026A000E6540130EAE79045F1D2A1F1050B1C2375 +:1026B0007C68BBFBF3F203FB12BB1FFA8BF6002C0A +:1026C00045D14846FFF72AFF044638B978606FF0D5 +:1026D0000200BDE8F88F4FF00008E6E7002606602C +:1026E0007860ADB24FF0000B454510D90AEB0803F6 +:1026F000221D13F8011B9155B1B208F101081B29E5 +:102700001FFA88F82BD0454506F10106F1D8FB8A5F +:10271000C3F30902154465F30903BCE7013292B221 +:102720001C462368002BF9D16B1F0B441C21B3FB03 +:10273000F1F301339BB29A42D3D2BBF1000FD0D157 +:102740004846FFF7EBFE20B9C4F800B0BFE701220E +:10275000E7E7C0F800B05E4620600446C1E74545A3 +:10276000D5D94846FFF7DAFE08B92060AFE7C0F8D0 +:1027700000B0002620600446B6E700002DE9F04FC7 +:102780002DED028B1C4683B05B690192074688469B +:10279000002B00F09A80238C2BB1E269002A00F014 +:1027A0009480072B35D807F10C00FFF7B7FE0546DC +:1027B00038B96FF00205284603B0BDEC028BBDE8C6 +:1027C000F08F14220021FEF723FC228CE16905F131 +:1027D0000800FEF70BFC208C013080B2FFF7E6FE0C +:1027E000FFF7C8FE013880B2208401302874636985 +:1027F000228C1B782A4403F01F0363F03F0348F048 +:1028000000411372384669602946FFF7EFFD012544 +:10281000D1E700F10C034FF0000908EE103A4FF039 +:10282000800A4E464D4618EE100AFFF777FE8346A3 +:102830000028BED014220021FEF7EAFB002E3AD178 +:10284000019BABF8083002220BF1080E1FFA82FC44 +:102850000CF10100BCF1060F218C80B201D88E4230 +:102860002BD3FFF7A3FEFFF785FE626912780138CC +:1028700002F01F028E4208BF4FF0400A42EA49129E +:102880001BFA80F14AEA020A013048F0004281F85E +:1028900008A08BF81000CBF8042059463846FFF703 +:1028A000A5FD238C0135B3422DB289F001094FF00B +:1028B000000AB8D17FE70022C6E7E169895D0EF81A +:1028C00002100136B6B20132C0E76FF0010572E7BF +:1028D000F8B515460E463022002104461F46FEF785 +:1028E00097FB069B6360B5F5001F079BA76034BF8D +:1028F0006A094FF6FF72A36297B2E66104F1100015 +:1029000000239A4206D800230360A782E382238330 +:10291000E360F8BD0660013330462036F1E7000081 +:1029200003781BB94BB2002BC8BF01707047000081 +:1029300000787047F8B50C46C969074611B9238C71 +:10294000002B37D1257E1F2D34D8387828BB228C18 +:10295000072A2CD8268A36F003032BD14FF6FF70B6 +:10296000FFF7D0FD20F001003102400441EA05618B +:10297000400C41EA40254FF6FF722346294638466F +:10298000FFF7FCFE002807DD626913780133DBB234 +:102990001F2B88BF00231370F8BD218A2D0645EA3E +:1029A000012505432046FFF71DFE0246E5E76FF0CF +:1029B0000300F1E76FF00100EEE7000070B58AB0A8 +:1029C000044616460021282268461D46FEF720FBD5 +:1029D000BDF83830ADF810300F9B05939DF84030AE +:1029E0008DF81830119B07936946BDF84830ADF853 +:1029F00020302046CDE90265FFF79CFF0AB070BD8C +:102A00002DE9F041D36905460C4616460BB9138CE7 +:102A10005BBB377E1F2F28D895F80080B8F1000FD8 +:102A200026D03046FFF7DEFD3378210241EAC3317C +:102A300041EA0801338A41EA076141EA034102465B +:102A4000334641F080012846FFF798FE00280ADD52 +:102A50003378012B07D1726913780133DBB21F2B56 +:102A600088BF00231370BDE8F0816FF00100FAE722 +:102A70006FF00300F7E70000F0B58BB004460D4699 +:102A800017460021282268461E46FEF7C1FA9DF827 +:102A90004C305A1E534253418DF800309DF840305F +:102AA000ADF81030119B05939DF848308DF8183023 +:102AB000149B07936A46BDF85430ADF82030294680 +:102AC0002046CDE90276FFF79BFF0BB0F0BD00007A +:102AD000406A00B104307047436A1A684262026972 +:102AE0001A600361C38A013BC38270472DE9F0413C +:102AF000D0F82080194E14461D464146002709B9DA +:102B0000BDE8F081D1E90223A21A65EB03039642E6 +:102B100077EB03031ED2036A8B420DD1FFF78CFDC6 +:102B2000036A1B68036203690B60C38A0161016A5F +:102B3000013BC3828846E2E7FFF77EFD0B68C8F8D9 +:102B4000003003690B60C38A0161013BC382D8F87E +:102B50000010D4E788460968D1E700BF80841E00D2 +:102B60002DE9F04F8BB00D46DDF8509014469B4692 +:102B70008046002800F01981B9F1000F00F015819E +:102B8000531E3F2B00F21181012A03D1BBF1000F2C +:102B900040F00B810023CDE90833B8F81430B5EBD1 +:102BA000C30F4FEAC30703D300200BB0BDE8F08F7B +:102BB0002B199F42D8F80C303ABF7F1BFFB2274633 +:102BC0001BB9D8F81030002B7AD0272D4ED8C5F17C +:102BD0002806B7424FF000032CBFF6B23E460093E2 +:102BE0002946D8F8080008AB3246FFF741FCA7EBAE +:102BF000060A35445FFA8AFAB8F8143003F1005334 +:102C0000053BDB000493D8F80C3003932821039B89 +:102C100013B1BAF1000F2CD1D8F8100040B1BAF1BD +:102C2000000F05D0009608AB5246691AFFF720FC4A +:102C300038B2002FB8D066070AD00AAB03EBD40134 +:102C4000624211F8083C02F00702134101F8083C07 +:102C5000082C3CD9102C40F2B580202C40F2B780D3 +:102C6000BBF1000F00F09C80082334E0BA46002638 +:102C7000C2E7049BE02B28BFE02306930B44AB4242 +:102C8000059314D95A1B03980096924534BF5246B7 +:102C9000D2B2691A08AB04300792FFF7E9FB079A32 +:102CA0001644AAEB020A1544F6B25FFA8AFA049BAC +:102CB000069A05999B1A0493039B1B680393A6E746 +:102CC0000093D8F8080008AB3A462946AEE7BBF1B6 +:102CD000000F13D00123B4EBC30F6CD0082C12D813 +:102CE0009DF82030621E23FA02F2D50706D54FF078 +:102CF000FF3202FA04F423438DF820309DF820308F +:102D000089F8003051E7102C12D8BDF82030621E2F +:102D100023FA02F2D10706D54FF0FF3202FA04F48B +:102D20002343ADF82030BDF82030A9F800303CE74F +:102D3000202C0FD80899631E21FA03F3DA0705D572 +:102D40004FF0FF3202FA04F40C430894089BC9F8D0 +:102D500000302AE7402C2BD0DDE90865611EC4F164 +:102D60002102A4F1210326FA01F105FA02F225FA63 +:102D700003F311431943CB0712D50122A4F1200319 +:102D8000C4F1200102FA03F322FA01F1A2405242F7 +:102D900043EA010363EB430332432B43CDE90823AA +:102DA000DDE90823C9E90023FFE66FF00100FCE636 +:102DB0006FF00800F9E6082CA0D9102CB3D9202C0C +:102DC000EED8C3E7BBF1000FADD0022383E7BBF120 +:102DD000000FBBD004237EE730B5012A144638BF6C +:102DE0000124402C85B028BF40240025012ACDE9CC +:102DF000025518D81B788DF8083063070AD004AB49 +:102E000003EBD405624215F8083C02F00702934038 +:102E100005F8083C009103462246002102A8FFF76E +:102E200027FB05B030BD082AE4D9102A03D81B8837 +:102E3000ADF80830E1E7202A8DBFD3E900231B68F5 +:102E40000293CDE90223D8E710B5CB681BB98B609C +:102E50000B618B8210BD04691A681C600361C38A10 +:102E6000013BC382CA60F0E703064CBFC0F3C03029 +:102E70000220704708B50246FFF7F6FF022806D188 +:102E80005306C2F30F2001D100F0030008BDC2F3C6 +:102E90000740FBE72DE9F04F93B0CDE903230A6823 +:102EA00004461046FFF7E0FF022814BFC2F30626CF +:102EB0000026002A0D46824680F2F28112F0C049B7 +:102EC00040F0EE81097B002900F0EA81022803D05E +:102ED0002378B34240F0E781C2F3046306931046BF +:102EE00002F07F030593FFF7C5FF059B29444FEAD6 +:102EF000834848EA0A4848EA4668CE780023002218 +:102F0000CDE90823F309834648EA0008029367D015 +:102F1000059B009302466768534608A92046B847B8 +:102F2000002800F0C381276A4FB9414604F10C0024 +:102F3000FFF702FB074690B96FF0020054E03B69CF +:102F400098450DD03F68002FF9D1414604F10C009F +:102F5000FFF7F2FA07460028EED0236A3B602762AB +:102F600097F817C006F01F08CCF3840CACEB0800F0 +:102F70001FFA80FE0028B8BF0EF12000A8EB0C035A +:102F80001FFA83FED7E90221B8BF00B2002B0793D6 +:102F9000BEBF0EF120031BB2079352EA010338D0E3 +:102FA000039BDFF824E39A1A049B4FF0000C63EBB9 +:102FB000010196457CEB01032BD36B7B97F81AE05C +:102FC000734519D1029B002B78D0012821DC786849 +:102FD000F8B9DFF8F0C2944570EB010316D337E07F +:102FE000276A27B96FF00C0013B0BDE8F08F3B697A +:102FF0009845B5D03F68F4E7B24890427CEB0103B6 +:1030000001D30020F0E7029B002BFAD0079B0F2B87 +:1030100017DCFA7DB30002F0030203F07C031343D4 +:10302000FB7539462046FFF707FB6B7BBB76029B9F +:103030003BB9FB7DC3F38402013262F38603FB7567 +:10304000D0E76A7BBB7E9A42DBD1029B002B35D056 +:10305000B309022B32D0039BBB60049BFB6014229C +:1030600000210DA8FDF7D4FF039B0A93049B0B934B +:103070002B1D0C932B7BADF83EB0013BDBB2ADF8C2 +:103080003C30069B8DF84230059B8DF8433094F818 +:103090002C308DF840A083F001038DF844308DF87A +:1030A0004180A3680AA920469847FB7DC3F38403A7 +:1030B000013303F01F039B02FB82A2E7FB7DC6F3F3 +:1030C0004012B2EBD31F40F0F480C3F384034345B6 +:1030D00040F0F280029A2B7BB609002A4DD0F2070D +:1030E0005DD4032B40F2EB80039BBB60049BFB6031 +:1030F0002B7BAE1D033BDBB23246394604F10C009C +:10310000FFF7ACFA00280CDA39462046FFF794FAAC +:10311000FB7DC3F38403013303F01F039B02FB8297 +:103120000AE7DDE90884AB883B834FF6FF73C9F1FA +:103130002000A9F1200228FA09F104FA00F0014365 +:1031400024FA02F211431846C9B2FFF7C9F909F18E +:103150000809B9F1400F0346E9D1B8822A7B033A46 +:10316000D2B23146FFF7CEF9FB7DB882DA43C2F323 +:10317000C01262F3C713FB7543E786B92E1D013BEE +:10318000DBB23246394604F10C00FFF767FA00283B +:10319000BADB2A7BB88A013AD2B23146E2E7F98A31 +:1031A000C1F30901013B0429DAB25BD8281D0023D1 +:1031B00007F11B069A4208D910F801CB06F801C0A6 +:1031C000013101330529DBB2F4D103990A91049945 +:1031D0000B91934207F11B010C9138BF04337968BE +:1031E0000D9134BF55FA83F300230E93FB8AADF89B +:1031F0003EB0C3F309031A44069B8DF84230059B89 +:103200008DF8433094F82C30ADF83C2083F0010366 +:103210008DF8443000238DF840A08DF841807B600C +:103220002A7BB88A013A291DFFF76CF93B8BB882DB +:10323000834203D1A3680AA92046984720460AA9D9 +:10324000FFF702FEFB7DBA8AC3F38403013303F068 +:103250001F039B02FB823B8B9A420CBF00206FF046 +:103260001000C1E67B68002BAFD0052001E01C30C8 +:1032700033461E68002EFAD1091A081D2E1D184467 +:1032800001EB090CBCF11B0F5FFA89F39DD89A4240 +:103290009BD916F8013B00F8013B09F10109EFE762 +:1032A0006FF00900A0E66FF00A009DE66FF00B00DA +:1032B0009AE66FF00D0097E66FF00E0094E66FF05F +:1032C0000F0091E640420F0080841E00EFF3098357 +:1032D00005494A6B22F001024A63683383F3098887 +:1032E000002383F31188704700EF00E0302080F363 +:1032F000118862B60C4B0D4AD96821F4E0610904CB +:10330000090C0A43DA60D3F8FC20094942F08072C4 +:10331000C3F8FC200A6842F001020A602022DA7732 +:1033200083F82200704700BF00ED00E00003FA05BB +:10333000001000E010B5302383F311880E4B5B685A +:1033400013F4006314D0F1EE103AEFF30984683CF3 +:103350004FF08073E361094BDB6B236684F30988CC +:1033600000F0A4F810B1064BA36110BD054BFBE7BC +:1033700083F31188F9E700BF00ED00E000EF00E003 +:10338000FF020008020300084FF0E0230022586803 +:103390004FF0FF31930003F1604303F561430132C5 +:1033A0009042C3F88010C3F88011F3D27047000038 +:1033B00000F1604303F561430901C9B283F80013CA +:1033C000012200F01F039A4043099B0003F1604370 +:1033D00003F56143C3F880211A6070470023037529 +:1033E000826803691B6899689142FBD25A6803603E +:1033F000426010605860704700230375826803695B +:103400001B6899689142FBD85A680360426010605B +:103410005860704708B50846302383F311880B7D48 +:10342000032B05D0042B0DD02BB983F3118808BDD5 +:103430008B6900221A604FF0FF338361FFF7CEFFE4 +:103440000023F2E7D1E9003213605A60F3E700008D +:10345000FFF7C4BF054BD9680875186802681A6081 +:10346000536001220275D860FCF734BF2838002071 +:1034700030B50C4BDD684B1C87B004460FD02B4693 +:10348000094A684600F02AF92046FFF7E3FF009B4F +:1034900013B1684600F02CF9A86907B030BDFFF7FA +:1034A000D9FFF9E72838002015340008044B1A68C2 +:1034B000DB6890689B68984294BF002001207047A9 +:1034C00028380020084B10B51C68D86822681A609C +:1034D000536001222275DC60FFF78EFF0146204613 +:1034E000BDE81040FCF7F6BE2838002038B5074C80 +:1034F00007490848012300252370656000F0EEFBB2 +:103500000223237085F3118838BD00BF503A002094 +:10351000904400082838002008B572B6044B18659E +:1035200000F0ACFA00F05CFB024B03221A70FEE7DD +:1035300028380020503A002000F010B98B60022398 +:1035400008618B82084670478368A3F1840243F8C0 +:10355000142C026943F8442C426943F8402C094A70 +:1035600043F8242CC26843F8182C022203F80C2CD0 +:10357000002203F80B2C044A43F8102CA3F120007E +:10358000704700BFED0200082838002008B5FFF79B +:10359000DBFFBDE80840FFF75BBF0000024BDB68C4 +:1035A00098610F20FFF756BF28380020302383F39F +:1035B0001188FFF7F3BF000008B50146302383F3FD +:1035C00011880820FFF754FF002383F3118808BDFA +:1035D00010B503689C68A2420CD85C688A600B60D6 +:1035E0004C602160596099688A1A9A604FF0FF33E5 +:1035F000836010BD1B68121BECE700000A2938BF6E +:103600000A2170B504460D460A26601900F060FBD9 +:1036100000F04CFB041BA54203D8751C2E46044643 +:10362000F3E70A2E04D9BDE87040012000F096BBF4 +:1036300070BD0000F8B5144B0D46D96103F11001BF +:1036400041600A2A1969826038BF0A220160486015 +:103650001861A818144600F02DFB0A2700F026FB7D +:10366000431BA342064606D37C1C281900F030FBFE +:1036700027463546F2E70A2F04D9BDE8F840012075 +:1036800000F06CBBF8BD00BF28380020F8B5064636 +:103690000D4600F00BFB0F4A134653F8107F9F4274 +:1036A00006D12A4601463046BDE8F840FFF7C2BFC2 +:1036B000D169BB68441A2C1928BF2C46A34202D9F1 +:1036C0002946FFF79BFF224631460348BDE8F840F4 +:1036D000FFF77EBF283800203838002010B4C0E93A +:1036E000032300235DF8044B4361FFF7CFBF0000C5 +:1036F00010B5194C236998420DD0D0E90032816889 +:1037000013605A609A680A449A60002303604FF07D +:10371000FF33A36110BD2346026843F8102F5360A6 +:103720000022026022699A4203D1BDE8104000F0F5 +:10373000C9BA936881680B44936000F0B7FA2269B4 +:10374000E1699268441AA242E4D91144BDE81040EC +:10375000091AFFF753BF00BF283800202DE9F047B2 +:10376000DFF8BC8008F110072C4ED8F8105000F09C +:103770009DFAD8F81C40AA68031B9A423ED814440C +:10378000D5E900324FF00009C8F81C4013605A60B8 +:10379000C5F80090D8F81030B34201D100F092FA89 +:1037A00089F31188D5E9033128469847302383F3FC +:1037B00011886B69002BD8D000F078FA6A69A0EB09 +:1037C00004094A4582460DD2022000F0C7FA0022C1 +:1037D000D8F81030B34208D151462846BDE8F0472A +:1037E000FFF728BF121A2244F2E712EB090938BF8B +:1037F0004A4629463846FFF7EBFEB5E7D8F81030C1 +:10380000B34208D01444211AC8F81C00A960BDE8CE +:10381000F047FFF7F3BEBDE8F08700BF383800205F +:103820002838002038B500F041FA054AD2E90845A9 +:10383000031B181945F10001C2E9080138BD00BF9A +:103840002838002000207047FEE700007047000085 +:103850004FF0FF3070470000BFF34F8F024A1369EB +:10386000DB03FCD4704700BF0020024008B5094BC1 +:103870001B7873B9FFF7F0FF074B5A69002ABFBFE7 +:10388000064A9A6002F188329A601A6822F48062CD +:103890001A6008BD683A00200020024023016745F5 +:1038A00008B50B4B1B7893B9FFF7D6FF094B5A6944 +:1038B00042F000425A611A6842F480521A601A6853 +:1038C00022F480521A601A6842F480621A6008BDBD +:1038D000683A0020002002407F289ABF00F580301F +:1038E000C0020020704700004FF4006070470000E5 +:1038F000802070477F2808B50BD8FFF7EDFF00F553 +:1039000000630268013204D104308342F9D10120FE +:1039100008BD0020FCE700007F2810B504461FD832 +:10392000FFF79AFFFFF7A2FF0E4BF3221A61022264 +:103930005A615A6942EAC0025A615A6942F48032B5 +:103940005A61FFF789FF4FF40061FFF7C5FF00F0F0 +:1039500043F9FFF7A5FF2046BDE81040FFF7CABFB7 +:10396000002010BD002002402DE9F84340EA020388 +:1039700013F00703144606D0304B40F241321A6070 +:103980000020BDE8F88385182D4A95420CD92B4AB2 +:1039900040F246311160F3E7031D1B684A68934209 +:1039A00008D1083C08300831072C14D902680B688C +:1039B0009A42F1D0FFF75AFFFFF74EFF214E083130 +:1039C0004FF001084FF00009012CA1F1080706D8BB +:1039D000FFF766FF01E0002CECD10120D1E7C6F82B +:1039E0001480054651F8083C45F8043B51F8043C66 +:1039F0004360FFF731FF336943F001033361C6F8D9 +:103A00001490026851F8083C9A420CD00B4B40F2DB +:103A10006E321A600C4B18600C4B1C600C4B1F6014 +:103A2000FFF73EFFACE72D6851F8043C9D4201F1E1 +:103A30000801EBD1083C0830C6E700BF643A00201B +:103A40000000040800200240583A0020603A00209C +:103A50005C3A0020084908B50B7828B11BB9FFF77C +:103A600005FF01230B7008BD002BFCD0BDE808400A +:103A70000870FFF715BF00BF683A002002484FF4F6 +:103A80007F4100F0ABB800BF00010020084611469E +:103A900000F00ABC012000F007BC0000084600F05E +:103AA00021BC000038B5EFF311859DB9EFF3058413 +:103AB000C4F30804302334B183F31188FFF7B2FE56 +:103AC00085F3118838BD83F31188FFF7ABFE84F3CB +:103AD000118838BDBDE83840FFF7A4BE38B5FFF700 +:103AE000E1FF114C114AC00840EA4170A0FB025EA0 +:103AF000C908A0FB040C1CEB050CA1FB04404FF013 +:103B000000035B41A1FB02121CEB040C43EB000021 +:103B100011EB0E0142F10002411842F100000909C7 +:103B200041EA007038BD00BFCFF753E3A59BC42026 +:103B300010B50244064BD2B2904200D110BD441CD5 +:103B400000B253F8200041F8040BE0B2F4E700BFE4 +:103B500050280040114B30B5D3F89040240409D4CC +:103B6000D3F89040C3F89040D3F8904044F4004418 +:103B7000C3F890400A4C236843F4807323600244E6 +:103B8000084BD2B2904200D130BD441C00B251F873 +:103B9000045B43F82050E0B2F4E700BF001002409D +:103BA000007000405028004007B5012201A9002004 +:103BB000FFF7BEFF019803B05DF804FB13B50446A0 +:103BC000FFF7F2FFA04205D0012201A900200194D5 +:103BD000FFF7C0FF02B010BD704700007047000043 +:103BE00070470000074B45F255521A6002225A6096 +:103BF00040F6FF729A604CF6CC421A60024B0122EA +:103C00001A70704700300040703A0020034B1B7858 +:103C10001BB1034B4AF6AA221A607047703A002083 +:103C200000300040054B1A6832B902F1804202F5BB +:103C30000432D2F894201A60704700BF6C3A00201A +:103C4000024B4FF40002C3F894207047001002406A +:103C500008B5FFF7E7FF024B1868C0F3407008BDD6 +:103C60006C3A002070470000FEE700000A4B0B484A +:103C70000B4A90420BD30B4BDA1C121AC11E22F0D6 +:103C800003028B4238BF00220021FDF7C1B953F86F +:103C9000041B40F8041BECE724450008FC3A002014 +:103CA000FC3A0020FC3A002000F0BEB84FF0804300 +:103CB000586A70474FF08043002258631A6102220D +:103CC000DA6070474FF080430022DA6070470000EE +:103CD0004FF0804358637047FEE7000070B51B4B00 +:103CE00001630025044686B0586085620E46FFF7E2 +:103CF000FDFA04F11003C4E904334FF0FF33C4E9C3 +:103D00000635C4E90044A560E562FFF7CFFF2B4606 +:103D10000246C4E9082304F134010D4A25658023D5 +:103D20002046FFF70BFC0123E0600A4A037500926E +:103D300072680192B268CDE90223074B6846CDE96B +:103D40000435FFF723FC06B070BD00BF503A0020D9 +:103D50009C440008A1440008D93C0008024AD36AE8 +:103D60001843D062704700BF28380020244B2548F4 +:103D7000DA6A42F0070210B4DA62DA6A224C22F000 +:103D80000702DA62DA6ADA6C42F00702DA64DA6EA3 +:103D900042F00702DA664FF09042DB6E4FF0AA3134 +:103DA000002353609160D0604FF6FF705061136242 +:103DB000536214601024C2F80434C2F80814C2F824 +:103DC0000C444FF6F774C2F814449924C2F8203416 +:103DD000C2F824440D4CC2F80044C2F80438C2F8BA +:103DE0000818C2F80C38C2F81408C2F82038C2F813 +:103DF0002438C2F800385DF8044B00F055B800BF15 +:103E000000100240000100240001002850000A00B8 +:103E100008B500F005FAFFF769FBBDE80840FFF7B9 +:103E200001BF0000704700000F4B9A6D42F0010285 +:103E30009A659A6F42F001029A670C4A9B6F9368E9 +:103E400043F0010393604FF080434F229A624FF09A +:103E5000FF32DA6200229A615A63DA605A60012204 +:103E60005A611A60704700BF00100240002004E051 +:103E70004FF0804208B51169D3680B40D9B2C943ED +:103E80009B07116107D5302383F31188FFF754FB9B +:103E9000002383F3118808BD08B5FFF775FABDE864 +:103EA000084000F099B900005A4B4FF0FF319A6A70 +:103EB00099629A6A00229A62986AD86A60F007004A +:103EC000D862D86A00F00700D862D86A186B196304 +:103ED000186B1A63186B986B9963986B9A63986B5D +:103EE000D86BD963D86BDA63D86B186C1964196C0A +:103EF0001A641A6C484A4FF4E06111601A6E47491F +:103F000042F001021A66D3F8802022F00102C3F8C1 +:103F10008020D3F880209A6D42F080529A659A6F83 +:103F200022F080529A679A6F4FF440720A604A6991 +:103F300012F48062FBD14A601A6822F0F00242F06B +:103F400060021A601A6842F001021A601A6891074A +:103F5000FCD500229A609A6812F00C02FBD1D3F8CB +:103F6000901011F4407F1EBF4FF48031C3F89010C1 +:103F7000C3F8902061221A601A689207FCD50022CB +:103F80009A609A6812F00C0FFBD169221A60D3F87C +:103F9000942022F4706242F4C062C3F894201A683C +:103FA00042F480321A601A689003FCD5D3F890204E +:103FB00022F00322C3F89020194ADA601A6842F00E +:103FC00080721A601A689101FCD5164A1A611A6843 +:103FD00042F080621A601A681201FCD500229A60D1 +:103FE0000D49114AC3F888200A6822F0070242F0FE +:103FF00004020A600A6802F00702042AFAD19A68E9 +:1040000042F003029A609A6802F00C020C2AFAD17C +:10401000704700BF001002400020024000700040C6 +:1040200003140001000C100055550134074A08B56F +:10403000536903F00103536123B1054A13680BB1BF +:1040400050689847BDE80840FFF774B90004014084 +:10405000743A0020074A08B5536903F0020353611C +:1040600023B1054A93680BB1D0689847BDE8084072 +:10407000FFF760B900040140743A0020074A08B510 +:10408000536903F00403536123B1054A13690BB16B +:1040900050699847BDE80840FFF74CB9000401405B +:1040A000743A0020074A08B5536903F008035361C6 +:1040B00023B1054A93690BB1D0699847BDE8084020 +:1040C000FFF738B900040140743A0020074A08B5E8 +:1040D000536903F01003536123B1054A136A0BB10E +:1040E000506A9847BDE80840FFF724B90004014032 +:1040F000743A0020164B10B55C6904F478725A616A +:10410000A30604D5134A936A0BB1D06A9847600698 +:1041100004D5104A136B0BB1506B9847210604D598 +:104120000C4A936B0BB1D06B9847E20504D5094A52 +:10413000136C0BB1506C9847A30504D5054A936CDA +:104140000BB1D06C9847BDE81040FFF7F3B800BF43 +:1041500000040140743A0020194B10B55C6904F466 +:104160007C425A61620504D5164A136D0BB1506D3D +:104170009847230504D5134A936D0BB1D06D98472A +:10418000E00404D50F4A136E0BB1506E9847A1049A +:1041900004D50C4A936E0BB1D06E9847620404D5D7 +:1041A000084A136F0BB1506F9847230404D5054A92 +:1041B000936F0BB1D06F9847BDE81040FFF7BAB8C6 +:1041C00000040140743A002008B5FFF751FEBDE835 +:1041D0000840FFF7AFB80000062108B50846FFF712 +:1041E000E7F806210720FFF7E3F806210820FFF78C +:1041F000DFF806210920FFF7DBF806210A20FFF788 +:10420000D7F806211720FFF7D3F806212820FFF75B +:10421000CFF8BDE8084007211C20FFF7C9B800000F +:1042200008B5FFF739FE00F007F8FFF7FBFDBDE822 +:104230000840FFF739BD00000023054A1946013345 +:10424000102BC2E9001102F10802F8D1704700BF3B +:10425000743A00200B460146184600F02DB80000C5 +:1042600000F040B8012838BF012010B504462046B0 +:1042700000F030F830B900F007F808B900F00CF899 +:104280008047F4E710BD0000024B1868BFF35B8F56 +:10429000704700BFF43A002008B5062000F084F80B +:1042A0000120FFF7D1FA0000024B0A4601461868C8 +:1042B000FFF7ECBB1811002010B5054C13462CB1CC +:1042C0000A4601460220AFF3008010BD2046FCE7FD +:1042D00000000000024B01461868FFF7DBBB00BF7F +:1042E00018110020024B01461868FFF7D7BB00BF2A +:1042F0001811002010B501390244904201D100206C +:1043000005E0037811F8014FA34201D0181B10BD3E +:104310000130F2E72DE9F041A3B1C91A1778014441 +:10432000044603F1FF3C8C42204601D9002009E0FD +:104330000578BD4204F10104F5D10CEB0405D61853 +:10434000A54201D1BDE8F08115F8018D16F801ED07 +:10435000F045F5D0E7E700001F2938B504460D46C3 +:1043600004D9162303604FF0FF3038BD426C12B100 +:1043700052F821304BB9204600F030F82A46014669 +:104380002046BDE8384000F017B8012B0AD0591C70 +:1043900003D1162303600120E7E7002442F82540FB +:1043A000284698470020E0E7024B01461868FFF7CF +:1043B000D3BF00BF1811002038B5074D00230446B5 +:1043C000084611462B60FFF743FA431C02D12B68C5 +:1043D00003B1236038BD00BFF83A0020FFF732BABE +:1043E000034611F8012B03F8012B002AF9D170477D +:1043F0006F72672E6172647570696C6F742E4D6197 +:1044000074656B4C3433312D41445342000000003D +:1044100040A2E4F1646891060041A3E5F265699267 +:10442000070000004261642043414E4966616365B4 +:1044300020696E6465782E00800000000080000016 +:1044400000008000000000000000000001180008CB +:10445000212000087D1F0008411800084D180008A1 +:104460004D1A000811180008211800081518000836 +:104470001D180008191800087119000825180008EF +:10448000F1220008351800084519000863300000C3 +:104490008C44000880380020503A00206D61696E1D +:1044A0000069646C65000000260400000000000044 +:1044B0000060030000000000FE2A0100D20400009A +:1044C0001C1100200000000000000000000000009F +:1044D00000000000000000000000000000000000DC +:1044E00000000000000000000000000000000000CC +:1044F00000000000000000000000000000000000BC +:1045000000000000000000000000000000000000AB +:10451000000000000000000000000000000000009B +:044520000000000097 :00000001FF diff --git a/Tools/bootloaders/MatekL431-Airspeed_bl.bin b/Tools/bootloaders/MatekL431-Airspeed_bl.bin index 4b3dbcd326bfa3..5a9ea3b5735558 100755 Binary files a/Tools/bootloaders/MatekL431-Airspeed_bl.bin and b/Tools/bootloaders/MatekL431-Airspeed_bl.bin differ diff --git a/Tools/bootloaders/MatekL431-Airspeed_bl.hex b/Tools/bootloaders/MatekL431-Airspeed_bl.hex index 641e598c7d3506..3032cd0d784b21 100644 --- a/Tools/bootloaders/MatekL431-Airspeed_bl.hex +++ b/Tools/bootloaders/MatekL431-Airspeed_bl.hex @@ -1,1160 +1,1109 @@ :020000040800F2 -:1000000000090020B5040008C52500087D2500086A -:10001000A52500087D2500089D250008B7040008D7 -:10002000B7040008B7040008B7040008B935000891 -:10003000B7040008B7040008B7040008B7040008B4 -:10004000B7040008B7040008B7040008B7040008A4 -:10005000B7040008B7040008554300087D430008B2 -:10006000A5430008CD430008F5430008B704000885 -:10007000B7040008B7040008B7040008B704000874 -:10008000B7040008B7040008B704000831250008C9 -:100090005D2500086D250008B70400081D44000810 -:1000A000B7040008B7040008B7040008B704000844 -:1000B000F1440008B7040008B7040008B7040008BA -:1000C000B7040008B7040008B7040008B704000824 -:1000D000B7040008B7040008B7040008B704000814 -:1000E00081440008B7040008B7040008B7040008FA -:1000F000B7040008B7040008B7040008B7040008F4 -:10010000B7040008B7040008B7040008B7040008E3 -:10011000B7040008B7040008B7040008B7040008D3 -:10012000B7040008B7040008B7040008B7040008C3 -:10013000B7040008B7040008B7040008B7040008B3 -:10014000B7040008B7040008B7040008B7040008A3 -:10015000B7040008B7040008B7040008B704000893 -:10016000B7040008B7040008B7040008B704000883 -:10017000B7040008B7040008B7040008B704000873 -:10018000B7040008B7040008B7040008B704000863 -:10019000B7040008B7040008B7040008B704000853 -:1001A000091200080000000000000000000000002C -:1001B00053B94AB9002908BF00281CBF4FF0FF31CE -:1001C0004FF0FF3000F074B9ADF1080C6DE904CECA -:1001D00000F006F8DDF804E0DDE9022304B0704722 -:1001E0002DE9F047089D04468E46002B4DD18A42EA -:1001F000944669D9B2FA82F252B101FA02F3C2F11D -:10020000200120FA01F10CFA02FC41EA030E9440AD -:100210004FEA1C48210CBEFBF8F61FFA8CF708FBCE -:1002200016E341EA034306FB07F199420AD91CEBA6 -:10023000030306F1FF3080F01F81994240F21C81D8 -:10024000023E63445B1AA4B2B3FBF8F008FB103320 -:1002500044EA034400FB07F7A7420AD91CEB040455 -:1002600000F1FF3380F00A81A74240F20781644425 -:10027000023840EA0640E41B00261DB1D4400023AA -:10028000C5E900433146BDE8F0878B4209D9002D0E -:1002900000F0EF800026C5E9000130463146BDE898 -:1002A000F087B3FA83F6002E4AD18B4202D3824202 -:1002B00000F2F980841A61EB030301209E46002DB1 -:1002C000E0D0C5E9004EDDE702B9FFDEB2FA82F206 -:1002D000002A40F09280A1EB0C014FEA1C471FFA64 -:1002E0008CFE0126200CB1FBF7F307FB131140EA4B -:1002F00001410EFB03F0884208D91CEB010103F118 -:10030000FF3802D2884200F2CB804346091AA4B2D9 -:10031000B1FBF7F007FB101144EA01440EFB00FEAD -:10032000A64508D91CEB040400F1FF3102D2A64512 -:1003300000F2BB800846A4EB0E0440EA03409CE7B1 -:10034000C6F12007B34022FA07FC4CEA030C20FA5E -:1003500007F401FA06F31C43F9404FEA1C4900FA7E -:1003600006F3B1FBF9F8200C1FFA8CFE09FB1811FB -:1003700040EA014108FB0EF0884202FA06F20BD96E -:100380001CEB010108F1FF3A80F08880884240F2BE -:100390008580A8F102086144091AA4B2B1FBF9F002 -:1003A00009FB101144EA014100FB0EFE8E4508D9FD -:1003B0001CEB010100F1FF346CD28E456AD9023882 -:1003C000614440EA0840A0FB0294A1EB0E01A14267 -:1003D000C846A64656D353D05DB1B3EB080261EBD5 -:1003E0000E0101FA07F722FA06F3F1401F43C5E9AF -:1003F000007100263146BDE8F087C2F12003D840E5 -:100400000CFA02FC21FA03F3914001434FEA1C4726 -:100410001FFA8CFEB3FBF7F007FB10360B0C43EA18 -:10042000064300FB0EF69E4204FA02F408D91CEBC8 -:10043000030300F1FF382FD29E422DD902386344C6 -:100440009B1B89B2B3FBF7F607FB163341EA034166 -:1004500006FB0EF38B4208D91CEB010106F1FF38B5 -:1004600016D28B4214D9023E6144C91A46EA0046AC -:1004700038E72E46284605E70646E3E61846F8E63E -:100480004B45A9D2B9EB020864EB0C0E0138A3E787 -:100490004646EAE7204694E74046D1E7D0467BE768 -:1004A000023B614432E7304609E76444023842E7E0 -:1004B000704700BF02E000F000F8FEE772B6374870 -:1004C00080F30888364880F3098836483649086042 -:1004D00040F20000CCF200004EF63471CEF2000182 -:1004E0000860BFF34F8FBFF36F8F40F20000C0F280 -:1004F000F0004EF68851CEF200010860BFF34F8F36 -:10050000BFF36F8F4FF00000E1EE100A4EF63C7122 -:10051000CEF200010860062080F31488BFF36F8FCD -:1005200003F034FD03F0B6FD4FF055301F491B4A70 -:1005300091423CBF41F8040BFAE71D49184A914229 -:100540003CBF41F8040BFAE71A491B4A1B4B9A427D -:100550003EBF51F8040B42F8040BF8E7002018499D -:10056000184A91423CBF41F8040BFAE703F012FD30 -:1005700003F0E2FD144C154DAC4203DA54F8041BB1 -:100580008847F9E700F042F8114C124DAC4203DA0B -:1005900054F8041B8847F9E703F0FABC000900206F -:1005A000001100200000000808ED00E0000100201C -:1005B00000090020E0470008001100207C11002005 -:1005C00080110020003B0020A0010008A4010008C9 -:1005D000A4010008A40100082DE9F04F2DED108AB8 -:1005E000C1F80CD0C3689D46BDEC108ABDE8F08F01 -:1005F000002383F311882846A047002003F072F9F6 -:10060000FEE703F0D5F800DFFEE70000F8B500F0E4 -:100610000DFE03F05DFC074603F0AEFC0546D0BBC3 -:10062000294B9F4237D001339F4237D0274B27F0C9 -:10063000FF029A4235D1F8B200F03EFC2E4642F25B -:10064000107400F03FFC08B10024264601F0A8F821 -:1006500058B3032000F03EF80024264635B11C4B69 -:100660009F4203D003F080FC00242646002003F0C4 -:1006700039FC0EB100F044F800F056FC00F0D8FD53 -:1006800001F0A8FF0546B4B900F096FC4FF47A706B -:1006900003F02EF9F7E72E460024D2E704460126A0 -:1006A000CFE706464FF47A74CBE7002CD6D04FF450 -:1006B0007A740126D2E701F08DFF431BA342E3D9F0 -:1006C00000F01EF8DCE700BF010007B0000008B032 -:1006D000263A09B0084B187003280CD8DFE800F060 -:1006E00008050208022000F001BE022000F0F4BD5F -:1006F000024B00225A6070478011002084110020B4 -:1007000010B501F04DF830B1234B03221A70234B82 -:1007100000225A6010BD224B224A1C461968013142 -:10072000F8D004339342F9D16268A242F2D31E4B4F -:100730009B6803F1006303F520439A42EAD203F079 -:10074000E5FB03F0F7FB002000F08CFD0220FFF733 -:10075000C1FF164B9A6D00229A65996F9A67996F3F -:10076000D96DDA65D96FDA67D96F196E1A66D3F861 -:100770008010C3F88020D3F8803072B64FF0E023A9 -:100780003021C3F8084DD4E9003281F311889D4629 -:1007900083F308881047BDE78011002084110020F2 -:1007A00000A0000820A00008001100200010024056 -:1007B000094A136849F2690099B21B0C00FB013326 -:1007C0001360064B186844F2506182B2000C01FBC2 -:1007D0000200186080B27047141100201011002030 -:1007E00010B500211022044600F09AFD034B03CB04 -:1007F000206061601868A06010BD00BF9075FF1F89 -:100800002DE9F041ADF5507D0DF13C086EAC40F2A4 -:10081000751207460D4610A80021C8F8001000F018 -:100820007FFD4FF4C4720021204600F079FD01F0F5 -:10083000D1FE254B4FF47A72B0FBF2F0186093E8CA -:100840000700022384E807000DF5ED702382FFF70F -:10085000C7FF42F204631D49238406A803F054FF36 -:10086000202384F832310DF2EB2606AB0DF1380C63 -:100870001A4603CA624530607160134606F10806E5 -:10088000F6D141460122204600F096FD0023039355 -:10089000AB7E029305F11903019380B20123CDE9E8 -:1008A00004800093E97E06A3D3E90023384602F0D2 -:1008B00059FA0DF5507DBDE8F08100BFAFF300801F -:1008C0009E6AC421818A46EE8C11002018470008D8 -:1008D0002DE9F0412C4C237ADAB080460D465BBB03 -:1008E00027A9284600F078FE0746002842D19DF847 -:1008F0009D60C82E3ED801464FF4A662204600F007 -:100900000FFD4FF48073C4F8F8314FF40073C4F84E -:100910000C334FF44073C4F8203432460DF19E017D -:1009200004F1090000F0EAFC26449DF89C3077723F -:1009300023720BB9EB7E23728122002106AC27A81B -:1009400000F0EEFC0122214627A800F081FE0023E2 -:100950000393AB7E029305F1190380B20193282320 -:10096000CDE904400093E97E05A3D3E90023404686 -:1009700002F0F8F95AB0BDE8F08100BFAFF3008093 -:1009800026417272DF25D7B7A8320020F0B5254E78 -:100990004FF48A7505FB0065F1B096F8D83085F8FC -:1009A000DC300024D822214685F8E8403AA800F03F -:1009B000B7FC06F1090000F0ABFCD5F8E4308DF887 -:1009C000F000C2B206AF06F109010DF1F100CDE968 -:1009D0003A3400F093FC394601223AA800F064FE54 -:1009E00080B2CDE9047008230127CDE9023706F172 -:1009F000D803019330230093317A0B4807A3D3E93E -:100A0000002302F0AFF9A04206DD01F0E3FDC5F8D6 -:100A1000E000384671B0F0BD2046FBE778F6339F22 -:100A200093CACD8DA8320020A42100202DE9F041E9 -:100A30001D4D1E4E1E4F86B0284602F0BFF90346DC -:100A400058B30024CDE90344ADF81440027B8DF87F -:100A5000142099684068029403AA03C21B68DFF857 -:100A6000548043F00043029301F0B6FD821941F136 -:100A70000003009402A9384601F078F8A04205DD91 -:100A8000284602F09FF988F80040D5E798F8003032 -:100A9000072B05D8013388F8003006B0BDE8F08197 -:100AA000014802F08FF9F8E7A421002040420F002E -:100AB000D8210020DD37002070B50D4614461E46B3 -:100AC00002F0ACF850B9022E10D1012C0ED112A3B5 -:100AD000D3E90023C5E90023012007E0282C10D02A -:100AE00005D8012C09D0052C0FD0002070BD302C6A -:100AF000FBD10BA3D3E90023ECE70BA3D3E900233D -:100B0000E8E70BA3D3E90023E4E70BA3D3E9002331 -:100B1000E0E700BFAFF30080401DA12026812A0B33 -:100B200078F6339F93CACD8D9E6AC421818A46EEA2 -:100B300026417272DF25D7B7F017304A39059E5625 -:100B400038B505460E4C0021013500F0ADFBA4F888 -:100B50002C55B4F82C0500F08FFB78B1B4F82C05B7 -:100B600000F09AFB014648B9B4F82C0500F09CFB54 -:100B7000B4F82C350133A4F82C35EAE738BD00BFB2 -:100B8000A832002010B50A4B0A4A1A6003F58053B8 -:100B900093F860203AB9DC6D2CB1204600F07EFE5F -:100BA000204603F0F1FCBDE81040034800F076BE9B -:100BB000D821002078470008203200202DE9F04F8E -:100BC0008FB000AF05460C4602F028F8002849D146 -:100BD000237E022B1BD1E38A012B18D101F0FAFCF2 -:100BE0000646FFF7E5FD03464FF4C870DFF8C48200 -:100BF000B3FBF0F206F5167602FB103316FA83F318 -:100C0000C8F80030E37E33B9A34B00221A703C379A -:100C1000BD46BDE8F08F07F12401204600F09AFCA4 -:100C20000028F4D107F11400FFF7DAFD97F8264009 -:100C300007F11401224607F1270003F0EFFC00281A -:100C4000E2D10F2C08D8944B1C70D8F80030A3F5D3 -:100C50001673C8F80030DAE797F82410284601F038 -:100C6000D5FFD4E7E38A282B2BD010D8012B23D033 -:100C7000052BCCD1BFF34F8F8849894BCA6802F44A -:100C8000E0621343CB60BFF34F8F00BFFDE7302B13 -:100C9000BDD1844EE17E327A9142B8D1607E314638 -:100CA000002291F8DC50854200F0A5800132042A30 -:100CB00001F58A71F5D1AAE721462846FFF7A0FD84 -:100CC000A5E721462846FFF703FEA0E7B2F8EC505F -:100CD0007B6005F103094FEA99094FEA8902D11DAA -:100CE000C908A8EBC1039D46EB460021584600F019 -:100CF00017FB04F1EE012A463144584600F0FEFA93 -:100D00007B6813B9012000F0ADFA96F8D20000F02C -:100D1000B3FA044630B9307200F0CEFA204600F043 -:100D2000A1FAB1E0D6F8D4203AB996F8D200B6F8D4 -:100D30002C25824201D8FFF703FFD6F8D4202A449D -:100D4000944208D296F8D200B6F82C25013082429F -:100D500001D8FFF7F5FE70685FFA89F2594600F096 -:100D6000E7FA08B9C54679E0726896F8D2002A44D5 -:100D70007260D6F8D42005EB0209C6F8D49000F0D2 -:100D80007BFA814509D396F8D220D6F8D4000132F7 -:100D9000001B86F8D220C6F8D400FF2D0FD80024FF -:100DA000347200F089FA204600F05CFA00F0F8FC9A -:100DB0003D4B188108B9FFF7A3FCC54627E7BB6880 -:100DC00096F8D9000AFB0362FB68D2F8E41082F8B7 -:100DD000E83001F58061C2F8E030C2F8E410FFF7B6 -:100DE000D5FDFFF723FE96F8D920013202F0030269 -:100DF00086F8D920B6E74FF48A7A0AFB02F505F1A6 -:100E0000EA013144204600F07BFCF86000287FF4C2 -:100E1000FEAE3544012285F8E82001F0DBFBD5F871 -:100E2000E020D6ED007ADFED216A801A192838BF5C -:100E3000192040F6B832904228BF1046B8EE677AC3 -:100E400007EE900AF8EEE77A67EEA67ADFED186A09 -:100E5000E7EE267AFCEEE77AC6ED007A96F8D9300E -:100E6000BB60BA6873680AFB02F4321992F8E810A2 -:100E700059B1D2F8E4108B42E8463FF427AF002185 -:100E800082F8E810C2F8E010C5467368064A9B0A6B -:100E900001331381BBE600BF9D21002000ED00E07F -:100EA0000400FA05A83200208C110020CDCCCC3DE6 -:100EB0006666663FA0210020014B1870704700BF96 -:100EC0009811002038B54FF00054134B22689A4215 -:100ED00020D1124B627D12481A70237D03724FF4A9 -:100EE0008073C0F8F8314FF40073C0F80C3300255C -:100EF0004FF44073C0F820340A49C0F8E450C922C6 -:100F0000093000F0FBF9E0222946204600F008FAFB -:100F1000012038BD0020FCE79AAD44C5981100209F -:100F2000A83200201600002037B500F039FC194D1A -:100F3000194928810223012218486B7101F0E8F950 -:100F400000230193164B174900931748174B4FF492 -:100F5000805201F033FE164B197811B1124801F09E -:100F600055FE01F037FB0446FFF722FC4FF4C8732F -:100F7000B0FBF3F202FB130304F5167010FA83F0D2 -:100F80000C4B186002F0F8FF08B10F232B8103B05F -:100F900030BD00BF8C11002040420F00D82100203E -:100FA000B90A00089C110020A4210020BD0B0008F4 -:100FB00098110020A02100202DE9F04F2DED028B8B -:100FC0000FF23829D9E90089834C93B00BAE9FED1D -:100FD0007E8BFFF72BFD814FDFF828A200230A93B9 -:100FE000ADF834300B9373604FF0000B5B468DED22 -:100FF000008B01250DF11D0207A938468DF81C5004 -:101000008DF81DB001F034F99DF81C30002B40F034 -:10101000A580204601F002FE0646002845D1704F0B -:1010200001F0D8FA3B6898423FD301F0D3FA8246E8 -:10103000FFF7BEFB4FF4C873B0FBF3F202FB1303E0 -:101040000AF5167010FA83F03860664F97F800B012 -:10105000CBF1100ABBF1000F14BF33462B465FFAE9 -:101060008AFA0EA88DF82830FFF7BAFBBAF1060FFE -:1010700028BF4FF0060A0EAB03EB0B0152460DF1F1 -:10108000290000F03BF90AAB0393182302930AF1FD -:101090000102554BD2B2CDE90053049220464CA335 -:1010A000D3E9002301F000FE3E7001F093FA4F4AAD -:1010B0004F4D1368C31AB3F57A7F2ED3106001F039 -:1010C0008BFA02460B46204601F086FE204601F0D0 -:1010D000A5FD10B32B7A474E002B14BF0323022328 -:1010E000737101F077FA0EAF4FF47A730122B0FBFF -:1010F000F3F039463060304600F004FA18230293CA -:101100003D4B019380B240F25513CDE9037000933B -:1011100042464B46204601F0C7FD2B7A93B101F0C1 -:1011200059FA002607464FF48A7A95F8D9003044D8 -:1011300000F003000AFB005393F8E82092B3013655 -:10114000042EF2D1C82002F0D3FB2B7A002B7FF4BF -:101150003DAF13B0BDEC028BBDE8F08FDAF8143070 -:1011600083F00803CAF81430594610220EA800F084 -:10117000D7F80DF11E0308AA0AA9384600F0F4FDBD -:1011800096E803000FAB83E803009DF834308DF838 -:1011900044300A9B0E930EA9DDE90823204601F096 -:1011A000EFFF21E7D3F8E02042B12B68FA2B38BFDC -:1011B000FA23BA1A0533B2EB430FC0D3FFF7E6FBAD -:1011C0000028BCD1BEE700BF000000000000000006 -:1011D000401DA12026812A0BA4210020D821002017 -:1011E000A02100209D2100209C210020D837002034 -:1011F000A83200208C110020DC370020F1C6A7C1E6 -:10120000D068080F0004004808B5054800F046FE05 -:10121000BDE80840034A0449002003F0AFB900BF0D -:10122000D821002018380020850B000870470000E6 -:1012300070B502F0E9FC094E094D308000242868A1 -:101240003388834208D902F0DBFC2B680444013365 -:10125000B4F5204F2B60F2D370BD00BF0C380020D6 -:10126000E037002002F082BD00F10060920000F53E -:10127000204002F005BD0000054B1A68054B1B8895 -:101280009B1A834202D9104402F0BABC0020704776 -:10129000E03700200C380020024B1B68184402F095 -:1012A000B5BC00BFE0370020024B1B68184402F0B9 -:1012B000BFBC00BFE0370020064991F8243033B1AD -:1012C0000023086A81F824300822FFF7CDBF0120EF -:1012D000704700BFE4370020022802BF024B4FF4E2 -:1012E00000229A61704700BF00040048022802BF34 -:1012F000014B08229A6170470004004810B5002392 -:10130000934203D0CC5CC4540133F9E710BD000014 -:1013100003460246D01A12F9011B0029FAD1704780 -:1013200002440346934202D003F8011BFAE77047D8 -:101330002DE9F8431F4D144695F8242007468846AA -:1013400052BBDFF870909CB395F824302BB9202263 -:10135000FF2148462F62FFF7E3FF95F82400C0F114 -:101360000802A24228BF2246D6B24146920005EBAF -:101370008000FFF7C3FF95F82430A41B1E44F6B28B -:10138000082E17449044E4B285F82460DBD1FFF7BF -:1013900093FF0028D7D108E02B6A03EB8203834236 -:1013A000CFD0FFF789FF0028CBD10020BDE8F8831C -:1013B0000120FBE7E43700202DE9F0470D46044605 -:1013C00000219046284640F27912FFF7A9FF2346F4 -:1013D00020220021284601F075FE231D0222202133 -:1013E000284601F06FFE631D03222221284601F0EA -:1013F00069FEA31D03222521284601F063FE04F1A6 -:10140000080310222821284601F05CFE04F1100395 -:1014100008223821284601F055FE04F11103082264 -:101420004021284601F04EFE04F112030822482113 -:10143000284601F047FE04F11403202250212846DB -:1014400001F040FE04F1180340227021284601F00B -:1014500039FE04F120030822B021284601F032FEB3 -:1014600004F121030822B821284601F02BFE04F1E3 -:101470002207C0263B46314608222846083601F09E -:1014800021FEB6F5A07F07F10107F3D104F1320385 -:1014900008223146284601F015FE002704F1330AE0 -:1014A00094F832304FEAC7099F4209F5A47615D364 -:1014B000B8F1000F08D1314604F599730722284688 -:1014C00001F000FE09F24F16274694F832213B1B2B -:1014D00093420CD3F01DC008BDE8F0870AEB070368 -:1014E00008223146284601F0EDFD0137D8E707F222 -:1014F000331331460822284601F0E4FD083601374F -:10150000E3E7000013B504460846002101602346C6 -:10151000C0F803102022019001F0D4FD0198231D92 -:101520000222202101F0CEFD0198631D0322222119 -:1015300001F0C8FD0198A31D0322252101F0C2FD81 -:10154000019804F108031022282101F0BBFD0720B7 -:1015500002B010BDF7B50023047F00910E460722AC -:101560001946054601F072FC731C0093012200230A -:101570000721284601F06AFCC4B9B31C0093052278 -:1015800023460821284601F061FC0D243746B27835 -:10159000BB1B934211D32B7FA88A0734E408BBB945 -:1015A000844294BF0020012003B0F0BDAB8ADB0071 -:1015B000083BDB08B3700824E8E7FB1C00932146D6 -:1015C00000230822284601F041FC08340137DEE7F9 -:1015D000201A18BF0120E7E7F7B50023047F009128 -:1015E0000E4608221946054601F030FC731CC4B9AA -:1015F0000822009311462346284601F027FC1024B8 -:10160000012372785F1C013B934211D32B7FA88A80 -:101610000734E408BBB9844294BF0020012003B022 -:10162000F0BDAB8ADB00083BDB0873700824E7E7FA -:10163000F3190093214600230822284601F006FCF6 -:1016400008343B46DDE7201A18BF0120E7E7000019 -:10165000F8B50E4605461446002181223046FFF7B4 -:101660005FFE2B4608220021304601F02BFD7CB99D -:101670006B1C07220821304601F024FD0F240123B2 -:101680006A785F1C013B934204D3E01DC008F8BD9B -:101690000824F4E7EB1921460822304601F012FD38 -:1016A00008343B46ECE70000F8B50E460546144604 -:1016B0000021CE223046FFF733FE2B4628220021A0 -:1016C000304601F0FFFC7CB905F10803082228210F -:1016D000304601F0F7FC30242F462A7A7B1B9342D8 -:1016E00004D3E01DC008F8BD2824F5E707F109037D -:1016F00021460822304601F0E5FC08340137ECE7CA -:10170000F7B5047F00910E46012310220021054603 -:1017100001F09CFBC4B9B31C00930922234610219D -:10172000284601F093FB192437467288BB1B9A4266 -:1017300011D82B7FA88A0734E408BBB9844294BF30 -:101740000020012003B0F0BDAB8ADB00103BDB08BA -:1017500073801024E8E73B1D0093214600230822F4 -:10176000284601F073FB08340137DEE7201A18BF62 -:101770000120E7E730B5094D0A4491420DD011F838 -:10178000013B5840082340F30004013B2C4013F078 -:10179000FF0384EA5000F6D1EFE730BD2083B8EDB7 -:1017A000F7B5384A106851686B4603C36A46364934 -:1017B0003648082302F042FF0446002833D10A25A8 -:1017C000334A106851686B4603C36A4631492F4853 -:1017D000082302F033FF0446002849D00369B3F51B -:1017E000583F45D8B0F8661040F2264291423FD1AA -:1017F000294A024402F15C018B4239D35C3B234904 -:1018000000209E1AFFF7B6FF3246074604F1640136 -:101810000020FFF7AFFFA3689F4229D1E3689842F9 -:1018200008BF002524E00369B3F5583F27D8418B52 -:1018300040F22642914220D1174A024402F110019F -:101840008B4218D3103B114900209D1AFFF792FFDD -:101850002A46064604F118010020FFF78BFFA36813 -:101860009E4202D1E368984201D00D25A8E70025E9 -:10187000284603B0F0BD1025A2E70C25A0E70B25F4 -:101880009EE700BF3C470008DC5F030000A00008A3 -:1018900045470008905F03000860FFF710B5037C20 -:1018A000044613B9006802F0B1FE204610BD0000E6 -:1018B0000023BFF35B8FC360BFF35B8FBFF35B8F0E -:1018C0008360BFF35B8F7047BFF35B8F0068BFF32C -:1018D0005B8F704770B505460C30FFF7F5FF05F1DB -:1018E000080604463046FFF7EFFFA04206D930460F -:1018F0006D68FFF7E9FF2544281A70BD3046FFF7F1 -:10190000E3FF201AF9E7000070B50546406898B17A -:1019100005F10800FFF7D8FF05F10C060446304634 -:10192000FFF7D2FF8442304694BF6D680025FFF771 -:10193000CBFF013C2C44201A70BD000038B50C468A -:101940000546FFF7C7FFA04210D305F10800FFF7D7 -:10195000BBFF04446868B4FBF0F100FB1144BFF323 -:101960005B8F0120AC60BFF35B8F38BD0020FCE7CC -:101970002DE9F041144607460D46FFF7C5FF8442A6 -:1019800028BF0446D4B1B84658F80C6B4046FFF760 -:101990009BFF3044286040467E68FFF795FF331A6E -:1019A0009C4203D86C600120BDE8F0816B60A41BF1 -:1019B0003B68AB602044E8600220F5E72046F3E78F -:1019C00038B50C460546FFF79FFFA04210D305F13E -:1019D0000C00FFF779FF04446868B4FBF0F100FBEA -:1019E0001144BFF35B8F0120EC60BFF35B8F38BD08 -:1019F0000020FCE72DE9FF41884669460746FFF7CE -:101A0000B7FF6C4606B204EBC6060025B44209D007 -:101A10006268206808EB0501FFF770FC6368083412 -:101A20001D44F3E729463846FFF7CAFF284604B0AD -:101A3000BDE8F081F8B505460C300F46FFF744FFCE -:101A400005F1080604463046FFF73EFFA042304647 -:101A500088BF6C68FFF738FF201A386020B1304625 -:101A60002C68FFF731FF2044F8BD000073B5144621 -:101A700006460D46FFF72EFF844228BF044601901C -:101A8000DCB101A93046FFF7D5FF019B33B93268BD -:101A9000C5E90233C5E9002401200CE09C4238BFAF -:101AA00001942860019868608442F5D93368AB607E -:101AB000241AEC60022002B070BD2046FBE7000053 -:101AC0002DE9FF410F466946FFF7D0FF6C4600B293 -:101AD00004EBC0050026AC4209D0D4F8048054F8C9 -:101AE000081BB8194246FFF709FC4644F3E73046A5 -:101AF00004B0BDE8F081000038B50546FFF7E0FF0F -:101B0000044601462846FFF719FF204638BD00006D -:101B1000302383F3118862B670470000002383F3FB -:101B2000118862B67047000010B4026854681A4603 -:101B300023465DF8044B184701207047002070478A -:101B40000020704770470000002070470E2070474B -:101B500000F5805090F8C800C0F3400070470000C6 -:101B600000F5805090F9C90070470000F7B50C6887 -:101B7000BDF8207014F000541E466FD10B7B082B6B -:101B80006CD8FFF7C5FF4569AB685B010CD4AB6847 -:101B90001B0108D4AC6814F080545DD1FFF7BEFF80 -:101BA000204603B0F0BD01240B6804F1180C002B93 -:101BB000B8BFDB004FEA0C1CB4BF43F004035B0565 -:101BC00045F80C300B680FFA84FC13F0804F18BFF7 -:101BD00005EB0C1E05EB0C1C1EBFDEF8803143F03C -:101BE0000203CEF880310B7BCCF8843105EB041571 -:101BF0008B68C5F88C314B68C5F88831DCF88031CA -:101C000043F00103CCF8803100EB441541F2680346 -:101C10001D4403EB44130344C5E9002608330D4675 -:101C200001F10C0C55F804EB43F804EB6545F9D1D0 -:101C300084342D881D8000EB441407F003032579BC -:101C400025F00B052B432371FFF768FF0097334600 -:101C500000F0E2FC0120A4E70224A5E74FF0FF30EA -:101C60009FE7000013B500F580540191E06DFFF788 -:101C70004BFE1F280AD90199E06D2022FFF7BAFE1A -:101C8000A0F120035842584102B010BD0020FBE7EC -:101C900008B500F58050FFF73BFFC06DFFF708FE69 -:101CA000BDE80840FFF73ABF00220260828142602F -:101CB0008260704710B500220023C0E90023002392 -:101CC000044603810C30FFF7EFFF204610BD0000F3 -:101CD000F0B5054600F580500C4690F8C83013F07A -:101CE000040FC3F3800108BF114661F3820304F1BE -:101CF000840680F8C83005EB461389B01B79D807F5 -:101D00002ED57AB319072DD46846FFF7D3FF05EB1C -:101D1000441303F5835303F1180703AA103318681B -:101D20005968144603C40833BB422246F7D11868E9 -:101D300020609B88A380DDE90E23CDE900230123E9 -:101D4000ADF808302B686946DB6B2846984705EBF1 -:101D500046152B791A075CBF43F008032B7101E08D -:101D6000002AF4D109B0F0BD2DE9F047074688B04C -:101D700007F5805468469A468846FFF7C9FE9146A3 -:101D8000FFF798FFE06DFFF7A5FD1F2829D9E06D4B -:101D900020226946FFF7B0FE202822D103AD444639 -:101DA00005AB2E4603CE9E4220606160354604F1AD -:101DB0000804F6D130682060B388A380DDE90023F1 -:101DC000C9E90023BDF80830AAF80030FFF7A6FEE5 -:101DD0004A4653464146384608B0BDE8F04700F051 -:101DE00009BCFFF79BFE002008B0BDE8F0870000AB -:101DF0002DE9F84F0023C0E90133254B044640F894 -:101E0000183B0F46FFF750FF04F12800FFF752FF81 -:101E100004F1480804F58255464608353046203618 -:101E2000FFF748FFAE42F9D104F580554FF48053D7 -:101E30004FF00009C5E91339C5F848800123EE6564 -:101E400004F5875804F58456C5F8549085F8583041 -:101E500085F86030083608F108084FF0000A4FF0A6 -:101E6000000B46E908ABA6F11800FFF71DFF20366E -:101E700046F8289C4645F4D185F8C97017B1054845 -:101E800000F0A2FB044B63612046BDE8F88F00BF61 -:101E900078470008504700080064004010B5044B24 -:101EA000197804464A1C1A70FFF7A2FF204610BD9D -:101EB000143800202DE9F047002950D0294B2A4F33 -:101EC000B7FBF1F599428CBF0A231123581EB5FBCD -:101ED000F3FC03FB1C53C4B22BB102280346F5D814 -:101EE0000020BDE8F0870CF1FF36B6F5806FF7D221 -:101EF000C4EBC40E0EF103034FEAE309C3F3C703B7 -:101F0000A4EB030809F1010A4FF47A755FFA88F02F -:101F100009FB05555AFA88F8B5FBF8F5B5F5617F68 -:101F2000C1BF0EF1FF33C3F3C703E01AC0B25C1C9C -:101F300050FA84F40CFB04F4B7FBF4F4A142CFD1C3 -:101F4000013BDBB20F2BCBD80138C0B20728C7D872 -:101F50000021107116809170D3700120C1E70846EE -:101F6000BFE700BF3F420F0000B4C40470B5054690 -:101F70000E464FF47A746B695B6803F00103B34259 -:101F800007D04FF47A7001F0B3FC013CF3D1204646 -:101F900070BD0120FCE7000030B54269936913F081 -:101FA000700F16D000230B4C936103F1840200EBF9 -:101FB000421211794D0709D5890707D5416954F8AF -:101FC00023508D60117941F0040111710133032B0D -:101FD000EBD130BD6447000873B51D464369164612 -:101FE0009A68D207044609D59A6801219960C2F31C -:101FF0004002CDE900650021FFF76AFE63699A6837 -:10200000D1050BD59A684FF480719960C2F34022D4 -:10201000CDE9006501212046FFF75AFE63699A6801 -:10202000D2030BD59A684FF480319960C2F34042D5 -:10203000CDE9006502212046FFF74AFE204602B0A6 -:10204000BDE87040FFF7A8BFF8B50446466900290F -:102050006CD106F10C07386880076AD006EB0115D1 -:102060003868D5F8B00110F0040FD5F8B0011ABFE8 -:10207000C00840F00040400DA061D5F8B0C11CF090 -:10208000020F1CBF40F08040A061D5F8B40106EB00 -:10209000011100F00F0084F82400D1F8B801207776 -:1020A000D1F8B801000A6077D1F8B801000CA07728 -:1020B000D1F8B801000EE077D1F8BC0184F8200017 -:1020C000D1F8BC01000A84F82100D1F8BC01000C51 -:1020D00084F82200D1F8BC11090E84F823103821AD -:1020E000396004F1340004F1180104F1240551F8B9 -:1020F000046B40F8046BA942F9D109880180C4E956 -:102100000A2321460023238651F8283B2046DB6B17 -:10211000984704F58052204692F8C83043F00403F3 -:1021200082F8C830BDE8F840FFF736BF06F1100767 -:1021300091E7F8BD10B5044600F04EFA02460B4692 -:1021400052EA030102D0013A63F10003044908682E -:1021500020B12146BDE81040FFF776BF10BD00BF9B -:1021600010380020F8B500F583511E46FFF7D0FC6B -:10217000DFF844C00831002404F1840500EB451564 -:102180002B795F070ED4DB060CD5D1E9007397429B -:10219000B34107D243695CF824709F602B7943F008 -:1021A00004032B710134032C01F12001E4D1BDE8BB -:1021B000F840FFF7B3BC00BF6447000808B5FFF75D -:1021C000A7FCFFF7E9FEBDE80840FFF7A7BC000049 -:1021D000F8B543690546986800F0E050B0F1E05F5B -:1021E0000F461FD0E8B1FFF793FC05F58354103478 -:1021F000002606F1840305EB43131B791A0706D565 -:102200000136032E04F12004F3D1012007E05B071F -:10221000F6D42146384600F039FA0028F0D1FFF70D -:102220007DFCF8BD0120FCE700F5805008B5FFF704 -:102230006FFCC06DFFF74EFBFFF770FC43090CBF4E -:102240000120002008BD0000F8B51D4600231370D2 -:102250000F4606461446FFF7E7FF80F0010038708E -:1022600025B129463046FFF7B3FF2070F8BD0000C6 -:102270002DE9B8410C4615461F46804600F0ACF9E2 -:102280000B462178024609B9287850B14046FFF73D -:1022900069FFFFF793FF3B462A462146FFF7D4FF2D -:1022A0000120BDE8B881000010B5FFF731FC174BE5 -:1022B0009A6D42F000729A659A6B42F000729A63CE -:1022C0009A6B00F5805422F000729A63FFF726FCA7 -:1022D00094F8C830DB0718D4B9B103211320FFF7F5 -:1022E00017FC01F0DBF90321142001F0D7F90321D9 -:1022F000152001F0D3F994F8C83043F0010384F8B5 -:10230000C830BDE81040FFF709BC10BD0010024006 -:102310002DE9F04700F5805588B095F8C930012BBC -:102320000446884616467FD8804F57F823200AB9BE -:1023300047F82300D7F800A0C4F80C802674BAF13F -:10234000000F63D095F8C930012B6FD001212046D2 -:10235000FFF7AAFFFFF7DCFB6269136823F00203B3 -:1023600013606269136843F0010313606369002717 -:102370005F6101212046FFF7D1FBFFF7F7FD002841 -:1023800000F09580E86DFFF793FA04F58359BA469B -:1023900009F10809202200216846FEF7C1FF02A8C2 -:1023A000FFF782FCCDF818A06A4609EB07030DF190 -:1023B000180E9446BCE80300F44518605960624664 -:1023C00003F10803F5D1DCF80000186020379CF811 -:1023D00004201A71602FDDD195F8C8306FF38203A5 -:1023E000002785F8C8306A4641462046ADF800709F -:1023F000ADF802708DF80470FFF75CFD636948BBAF -:102400004FF400421A6008B0BDE8F08741F2D000F6 -:1024100002F0BCF8814610B15146FFF7E9FCC7F85D -:102420000090B9F1000F8DD10020ECE73868036807 -:102430001B6B98470146002888D13868FFF734FFA6 -:102440003868036832465B684146984700287FF445 -:102450007DAFE9E761221A609DF802309DF8032004 -:102460001B06120402F4702203F040731343BDF8FC -:102470000020C2F3090213439DF804201205022E26 -:1024800002F4E0020CBF4FF00041002113436269E7 -:102490000B43D361636913225A616269136823F0A5 -:1024A0000103136039462046FFF760FD08B96369F0 -:1024B000A6E795F8C93093BB6169D1F8002242F0D4 -:1024C0000102C1F800226169D1F8002222F47C5295 -:1024D00022F00E02C1F800226169D1F8002242F414 -:1024E0006062C1F800226269C2F814326269C2F8FF -:1024F0000432626941F6FF71C2F80C126269C2F8D7 -:1025000040326269C2F8443263690122C3F81C2276 -:102510006269D2F8003223F00103C2F8003295F864 -:10252000C83043F0020385F8C8306CE7103800204B -:1025300008B500F051F850EA0103024602D0421EED -:1025400061F10001044B186810B10B46FFF744FD20 -:10255000BDE8084001F064B81038002008B500203C -:10256000FFF7E8FDBDE8084001F05AB808B50120C2 -:10257000FFF7E0FDBDE8084001F052B800B59BB0A0 -:10258000EFF3098168226846FEF7B8FEEFF3058392 -:10259000014B9B6BFEE700BF00ED00E008B5FFF7C5 -:1025A000EDFF000000B59BB0EFF30981682268469B -:1025B000FEF7A4FEEFF30583014B5B6BFEE700BF64 -:1025C00000ED00E0FEE700000FB408B5029801F04E -:1025D00025F9FEE701F016BC01F0EEBB13B56C4621 -:1025E00084E80600031D94E8030083E80500012049 -:1025F00002B010BD73B58568019155B11B885B07AA -:1026000007D4D0E900369B6B9847019AC1B2304697 -:10261000A847012002B070BDF0B5866889B00546B4 -:102620000C465EB1BDF838305B070AD4D0E90037FC -:102630009B6B98472246C1B23846B047012009B08B -:10264000F0BD00220023CDE900230023ADF80830BF -:102650000A4603AB01F10806106851681C4603C422 -:102660000832B2422346F7D1106820609288A280D7 -:10267000FFF7B2FF0423ADF808302B68CDE9000165 -:10268000DB6B694628469847D8E7000030B50368F9 -:102690000968DD0FB5EBD17F23F0604421F0604283 -:1026A0004FEAD1700BD0002BB8BFA40C0029B8BFE3 -:1026B000920C944202D034BF0120002030BD9442DD -:1026C00005D1C1F38070C3F380738342F6D1944285 -:1026D0002CBF00200120F1E72DE9F041456A15B932 -:1026E0004162BDE8F0814B6823F06047C3F38A463E -:1026F0004FEAD37EC3F3807816EA230638BF3E46FE -:10270000AC462B465A68BEEBD27F22F060440AD01A -:10271000002A18DAA40CB44217D19D420FD10D60E3 -:10272000DEE71346EEE7A74207D102F08044C2F38A -:10273000807242450BD054B1EFE708D2EDE7CCF8F8 -:1027400000100B60CDE7B44201D0B442E5D81A685E -:102750009C46002AE5D11960C3E700002DE9F04747 -:10276000089D01F007044FEAD508224405F007054B -:1027700000EBD1004FF47F49944201D1BDE8F087CE -:1027800004F0070705F0070A57453E4638BF56468E -:10279000C6F10806111B8E4228BF0E46E10808EB61 -:1027A000D50E415C13F80EC0B94029FA06F721FA9C -:1027B0000AF1FFB28CEA010147FA0AF739408CEAC4 -:1027C000010C03F80EC034443544D5E780EA0120FB -:1027D000082341F2210201B24000002980B203F136 -:1027E000FF33B8BF504013F0FF03F4D1704700002F -:1027F00038B50C468D18A54200D138BD14F8011B20 -:10280000FFF7E4FFF7E7000042684AB1136843604E -:102810004389818901339BB29942438138BF8381C7 -:102820001046704770B588B0202204460D466846B1 -:102830000021FEF775FD20460495FFF7E5FF0246EF -:1028400058B16B46054608AE1C4603CCB44228601E -:102850006960234605F10805F6D1104608B070BD41 -:10286000082817D909280CD00A280CD00B280CD01E -:102870000C280CD00D280CD00E2814BF402030207E -:1028800070470C20704710207047142070471820A4 -:102890007047202070470000082817D90C280CD951 -:1028A00010280CD914280CD918280CD920280CD998 -:1028B00030288CBF0F200E207047092070470A2057 -:1028C00070470B2070470C2070470D2070470000A8 -:1028D0002DE9F843078C072F04461ED9D0E902984A -:1028E00000254FF6FF73C5F12006A5F1200029FA57 -:1028F00005F108FA06F628FA00F031430143C9B29F -:102900001846FFF763FF0835402D0346EBD1E16918 -:102910003A46BDE8F843FFF76BBF4FF6FF70BDE8DE -:10292000F883000010B54B6823B9CA8A63F3090223 -:10293000CA8210BD04691A681C600361C38A013B26 -:10294000C3824A60EFE700002DE9F84F1D46CB8AAD -:102950000F46C3F309010529814692460B4630D044 -:102960000020AAB207F11A049EB2042E1FFA80F8C2 -:102970000FD8904503F1010306D3FB8A0A4462F3A2 -:102980000903FB8201201AE01AF80060E6540130C6 -:10299000EAE79045F1D2A1F1050B1C237C68BBFB53 -:1029A000F3F203FB12BB1FFA8BF6002C45D148460D -:1029B000FFF72AFF044638B978606FF00200BDE8DF -:1029C000F88F4FF00008E6E7002606607860ADB2A9 -:1029D0004FF0000B454510D90AEB0803221D13F8F0 -:1029E000011B9155B1B208F101081B291FFA88F8A3 -:1029F0002BD0454506F10106F1D8FB8AC3F3090245 -:102A0000154465F30903BCE7013292B21C46236802 -:102A1000002BF9D16B1F0B441C21B3FBF1F30133E5 -:102A20009BB29A42D3D2BBF1000FD0D14846FFF7F8 -:102A3000EBFE20B9C4F800B0BFE70122E7E7C0F819 -:102A400000B05E4620600446C1E74545D5D94846FA -:102A5000FFF7DAFE08B92060AFE7C0F800B0002643 -:102A600020600446B6E700002DE9F04F2DED028B03 -:102A70001C4683B05B69019207468846002B00F034 -:102A80009A80238C2BB1E269002A00F09480072BF6 -:102A900035D807F10C00FFF7B7FE054638B96FF0DF -:102AA0000205284603B0BDEC028BBDE8F08F14226E -:102AB0000021FEF735FC228CE16905F10800FEF7E4 -:102AC0001DFC208C013080B2FFF7E6FEFFF7C8FE48 -:102AD000013880B22084013028746369228C1B780D -:102AE0002A4403F01F0363F03F0348F000411372D0 -:102AF000384669602946FFF7EFFD0125D1E700F16F -:102B00000C034FF0000908EE103A4FF0800A4E46D1 -:102B10004D4618EE100AFFF777FE83460028BED018 -:102B200014220021FEF7FCFB002E3AD1019BABF8EA -:102B3000083002220BF1080E1FFA82FC0CF1010092 -:102B4000BCF1060F218C80B201D88E422BD3FFF747 -:102B5000A3FEFFF785FE62691278013802F01F02BA -:102B60008E4208BF4FF0400A42EA49121BFA80F138 -:102B70004AEA020A013048F0004281F808A08BF8C6 -:102B80001000CBF8042059463846FFF7A5FD238CEA -:102B90000135B3422DB289F001094FF0000AB8D1D6 -:102BA0007FE70022C6E7E169895D0EF80210013671 -:102BB000B6B20132C0E76FF0010572E7F8B515460D -:102BC0000E463022002104461F46FEF7A9FB069B55 -:102BD0006360B5F5001F079BA76034BF6A094FF615 -:102BE000FF72A36297B2E66104F1100000239A42DB -:102BF00006D800230360A782E3822383E360F8BD45 -:102C00000660013330462036F1E7000003781BB937 -:102C10004BB2002BC8BF01707047000000787047AE -:102C2000F8B50C46C969074611B9238C002B37D17A -:102C3000257E1F2D34D8387828BB228C072A2CD823 -:102C4000268A36F003032BD14FF6FF70FFF7D0FD35 -:102C500020F001003102400441EA0561400C41EAE4 -:102C600040254FF6FF72234629463846FFF7FCFE03 -:102C7000002807DD626913780133DBB21F2B88BFA0 -:102C800000231370F8BD218A2D0645EA012505436E -:102C90002046FFF71DFE0246E5E76FF00300F1E76F -:102CA0006FF00100EEE7000070B58AB004461646EA -:102CB0000021282268461D46FEF732FBBDF8383059 -:102CC000ADF810300F9B05939DF840308DF818300B -:102CD000119B07936946BDF84830ADF82030204677 -:102CE000CDE90265FFF79CFF0AB070BD2DE9F04108 -:102CF000D36905460C4616460BB9138C5BBB377E71 -:102D00001F2F28D895F80080B8F1000F26D0304644 -:102D1000FFF7DEFD3378210241EAC33141EA0801C1 -:102D2000338A41EA076141EA03410246334641F0F2 -:102D300080012846FFF798FE00280ADD3378012B32 -:102D400007D1726913780133DBB21F2B88BF0023D0 -:102D50001370BDE8F0816FF00100FAE76FF0030037 -:102D6000F7E70000F0B58BB004460D46174600218A -:102D7000282268461E46FEF7D3FA9DF84C305A1EAC -:102D8000534253418DF800309DF84030ADF810307B -:102D9000119B05939DF848308DF81830149B0793CC -:102DA0006A46BDF85430ADF8203029462046CDE9BA -:102DB0000276FFF79BFF0BB0F0BD0000406A00B148 -:102DC00004307047436A1A68426202691A600361FC -:102DD000C38A013BC38270472DE9F041D0F82080BF -:102DE000194E14461D464146002709B9BDE8F08139 -:102DF000D1E90223A21A65EB0303964277EB0303A2 -:102E00001ED2036A8B420DD1FFF78CFD036A1B684B -:102E1000036203690B60C38A0161016A013BC382DB -:102E20008846E2E7FFF77EFD0B68C8F800300369CB -:102E30000B60C38A0161013BC382D8F80010D4E75C -:102E400088460968D1E700BF80841E002DE9F04F55 -:102E50008BB00D46DDF8509014469B468046002806 -:102E600000F01981B9F1000F00F01581531E3F2BBE -:102E700000F21181012A03D1BBF1000F40F00B8158 -:102E80000023CDE90833B8F81430B5EBC30F4FEA8F -:102E9000C30703D300200BB0BDE8F08F2B199F426E -:102EA000D8F80C303ABF7F1BFFB227461BB9D8F8C1 -:102EB0001030002B7AD0272D4ED8C5F12806B74206 -:102EC0004FF000032CBFF6B23E4600932946D8F8D7 -:102ED000080008AB3246FFF741FCA7EB060A354471 -:102EE0005FFA8AFAB8F8143003F10053053BDB00AF -:102EF0000493D8F80C3003932821039B13B1BAF143 -:102F0000000F2CD1D8F8100040B1BAF1000F05D055 -:102F1000009608AB5246691AFFF720FC38B2002F22 -:102F2000B8D066070AD00AAB03EBD401624211F8AD -:102F3000083C02F00702134101F8083C082C3CD978 -:102F4000102C40F2B580202C40F2B780BBF1000F6E -:102F500000F09C80082334E0BA460026C2E7049BB8 -:102F6000E02B28BFE02306930B44AB42059314D912 -:102F70005A1B03980096924534BF5246D2B2691A42 -:102F800008AB04300792FFF7E9FB079A1644AAEB57 -:102F9000020A1544F6B25FFA8AFA049B069A05996A -:102FA0009B1A0493039B1B680393A6E70093D8F82E -:102FB000080008AB3A462946AEE7BBF1000F13D034 -:102FC0000123B4EBC30F6CD0082C12D89DF820302D -:102FD000621E23FA02F2D50706D54FF0FF3202FA3D -:102FE00004F423438DF820309DF8203089F8003018 -:102FF00051E7102C12D8BDF82030621E23FA02F2DD -:10300000D10706D54FF0FF3202FA04F42343ADF89E -:103010002030BDF82030A9F800303CE7202C0FD834 -:103020000899631E21FA03F3DA0705D54FF0FF3242 -:1030300002FA04F40C430894089BC9F800302AE70C -:10304000402C2BD0DDE90865611EC4F12102A4F1FA -:10305000210326FA01F105FA02F225FA03F31143DE -:103060001943CB0712D50122A4F12003C4F120019A -:1030700002FA03F322FA01F1A240524243EA0103A9 -:1030800063EB430332432B43CDE90823DDE90823F7 -:10309000C9E90023FFE66FF00100FCE66FF00800CD -:1030A000F9E6082CA0D9102CB3D9202CEED8C3E710 -:1030B000BBF1000FADD0022383E7BBF1000FBBD003 -:1030C00004237EE730B5012A144638BF0124402C82 -:1030D00085B028BF40240025012ACDE9025518D823 -:1030E0001B788DF8083063070AD004AB03EBD405D6 -:1030F000624215F8083C02F00702934005F8083CCC -:10310000009103462246002102A8FFF727FB05B0E5 -:1031100030BD082AE4D9102A03D81B88ADF808303E -:10312000E1E7202A8DBFD3E900231B680293CDE994 -:103130000223D8E710B5CB681BB98B600B618B827B -:1031400010BD04691A681C600361C38A013BC38215 -:10315000CA60F0E703064CBFC0F3C03002207047DE -:1031600008B50246FFF7F6FF022806D15306C2F360 -:103170000F2001D100F0030008BDC2F30740FBE7B8 -:103180002DE9F04F93B0CDE903230A6804461046B9 -:10319000FFF7E0FF022814BFC2F306260026002A2C -:1031A0000D46824680F2F28112F0C04940F0EE8175 -:1031B000097B002900F0EA81022803D02378B3427A -:1031C00040F0E781C2F304630693104602F07F03E8 -:1031D0000593FFF7C5FF059B29444FEA834848EA5A -:1031E0000A4848EA4668CE7800230022CDE9082341 -:1031F000F309834648EA0008029367D0059B0093D1 -:1032000002466768534608A92046B847002800F0E0 -:10321000C381276A4FB9414604F10C00FFF702FB56 -:10322000074690B96FF0020054E03B6998450DD015 -:103230003F68002FF9D1414604F10C00FFF7F2FA84 -:1032400007460028EED0236A3B60276297F817C034 -:1032500006F01F08CCF3840CACEB08001FFA80FECC -:103260000028B8BF0EF12000A8EB0C031FFA83FE64 -:10327000D7E90221B8BF00B2002B0793BEBF0EF101 -:1032800020031BB2079352EA010338D0039BDFF8F7 -:1032900024E39A1A049B4FF0000C63EB010196455E -:1032A0007CEB01032BD36B7B97F81AE0734519D1A4 -:1032B000029B002B78D0012821DC7868F8B9DFF870 -:1032C000F0C2944570EB010316D337E0276A27B9A3 -:1032D0006FF00C0013B0BDE8F08F3B699845B5D096 -:1032E0003F68F4E7B24890427CEB010301D3002031 -:1032F000F0E7029B002BFAD0079B0F2B17DCFA7D1F -:10330000B30002F0030203F07C031343FB7539465C -:103310002046FFF707FB6B7BBB76029B3BB9FB7D2F -:10332000C3F38402013262F38603FB75D0E76A7B44 -:10333000BB7E9A42DBD1029B002B35D0B309022B16 -:1033400032D0039BBB60049BFB60142200210DA8BC -:10335000FDF7E6FF039B0A93049B0B932B1D0C9335 -:103360002B7BADF83EB0013BDBB2ADF83C30069BA9 -:103370008DF84230059B8DF8433094F82C308DF851 -:1033800040A083F001038DF844308DF84180A3689C -:103390000AA920469847FB7DC3F38403013303F059 -:1033A0001F039B02FB82A2E7FB7DC6F34012B2EB38 -:1033B000D31F40F0F480C3F38403434540F0F28010 -:1033C000029A2B7BB609002A4DD0F2075DD4032B5D -:1033D00040F2EB80039BBB60049BFB602B7BAE1D2C -:1033E000033BDBB23246394604F10C00FFF7ACFA7E -:1033F00000280CDA39462046FFF794FAFB7DC3F328 -:103400008403013303F01F039B02FB820AE7DDE91B -:103410000884AB883B834FF6FF73C9F12000A9F104 -:10342000200228FA09F104FA00F0014324FA02F21A -:1034300011431846C9B2FFF7C9F909F10809B9F1F2 -:10344000400F0346E9D1B8822A7B033AD2B2314613 -:10345000FFF7CEF9FB7DB882DA43C2F3C01262F304 -:10346000C713FB7543E786B92E1D013BDBB232461D -:10347000394604F10C00FFF767FA0028BADB2A7B13 -:10348000B88A013AD2B23146E2E7F98AC1F30901BA -:10349000013B0429DAB25BD8281D002307F11B0683 -:1034A0009A4208D910F801CB06F801C00131013366 -:1034B0000529DBB2F4D103990A9104990B91934247 -:1034C00007F11B010C9138BF043379680D9134BFAB -:1034D00055FA83F300230E93FB8AADF83EB0C3F395 -:1034E00009031A44069B8DF84230059B8DF8433042 -:1034F00094F82C30ADF83C2083F001038DF8443073 -:1035000000238DF840A08DF841807B602A7BB88A2B -:10351000013A291DFFF76CF93B8BB882834203D136 -:10352000A3680AA92046984720460AA9FFF702FE89 -:10353000FB7DBA8AC3F38403013303F01F039B02AC -:10354000FB823B8B9A420CBF00206FF01000C1E65B -:103550007B68002BAFD0052001E01C3033461E688D -:10356000002EFAD1091A081D2E1D184401EB090C72 -:10357000BCF11B0F5FFA89F39DD89A429BD916F8CC -:10358000013B00F8013B09F10109EFE76FF0090089 -:10359000A0E66FF00A009DE66FF00B009AE66FF070 -:1035A0000D0097E66FF00E0094E66FF00F0091E6C5 -:1035B00040420F0080841E00EFF3098305494A6BE7 -:1035C00022F001024A63683383F30988002383F3FE -:1035D0001188704700EF00E0302080F3118862B658 -:1035E0000C4B0D4AD96821F4E0610904090C0A4327 -:1035F000DA60D3F8FC20094942F08072C3F8FC205D -:103600000A6842F001020A602022DA7783F8220079 -:10361000704700BF00ED00E00003FA05001000E075 -:1036200010B5302383F311880E4B5B6813F40063ED -:1036300014D0F1EE103AEFF30984683C4FF0807338 -:10364000E361094BDB6B236684F3098800F0A4F87F -:1036500010B1064BA36110BD054BFBE783F3118846 -:10366000F9E700BF00ED00E000EF00E0030600080E -:10367000060600084FF0E023002258684FF0FF31A3 -:10368000930003F1604303F5614301329042C3F8B4 -:103690008010C3F88011F3D27047000000F160433E -:1036A00003F561430901C9B283F80013012200F058 -:1036B0001F039A4043099B0003F1604303F56143F4 -:1036C000C3F880211A60704700230375826803697C -:1036D0001B6899689142FBD25A680360426010608F -:1036E0005860704700230375826803691B689968F6 -:1036F0009142FBD85A68036042601060586070477E -:1037000008B50846302383F311880B7D032B05D0C1 -:10371000042B0DD02BB983F3118808BD8B690022CF -:103720001A604FF0FF338361FFF7CEFF0023F2E70B -:10373000D1E9003213605A60F3E70000FFF7C4BF1D -:10374000054BD9680875186802681A605360012231 -:103750000275D860FCF740BF2038002030B50C4B14 -:10376000DD684B1C87B004460FD02B46094A6846DB -:1037700000F050F92046FFF7E3FF009B13B16846C5 -:1037800000F052F9A86907B030BDFFF7D9FFF9E79B -:103790002038002001370008044B1A68DB68906865 -:1037A0009B68984294BF0020012070472038002079 -:1037B000084B10B51C68D86822681A605360012253 -:1037C0002275DC60FFF78EFF01462046BDE8104001 -:1037D000FCF702BF20380020044B1A68DB689268AF -:1037E0009B689A4201D9FFF7E3BF70472038002059 -:1037F00038B5074C07490848012300252370656048 -:1038000000F000FC0223237085F3118838BD00BF4F -:10381000483A0020BC4700082038002008B572B69E -:10382000044B186500F0B6FA00F06EFB024B032261 -:103830001A70FEE720380020483A002000F02AB92C -:10384000EFF3118020B9EFF30583302282F3118862 -:103850007047000010B530B9EFF30584C4F30804D5 -:1038600014B180F3118810BDFFF7B6FF84F31188FF -:10387000F9E700008B60022308618B8208467047DD -:103880008368A3F1840243F8142C026943F8442CA2 -:10389000426943F8402C094A43F8242CC26843F893 -:1038A000182C022203F80C2C002203F80B2C044ADB -:1038B00043F8102CA3F12000704700BFF105000869 -:1038C0002038002008B5FFF7DBFFBDE80840FFF710 -:1038D00035BF0000024BDB6898610F20FFF730BF57 -:1038E00020380020302383F31188FFF7F3BF000056 -:1038F00008B50146302383F311880820FFF72EFF17 -:10390000002383F3118808BD10B503689C68A242A8 -:103910000CD85C688A600B604C60216059609968C3 -:103920008A1A9A604FF0FF33836010BD1B68121B28 -:10393000ECE700000A2938BF0A2170B504460D469D -:103940000A26601900F058FB00F044FB041BA54256 -:1039500003D8751C2E460446F3E70A2E04D9BDE8A9 -:103960007040012000F08EBB70BD0000F8B5144B14 -:103970000D46D96103F1100141600A2A196982607C -:1039800038BF0A22016048601861A818144600F088 -:1039900025FB0A2700F01EFB431BA342064606D365 -:1039A0007C1C281900F028FB27463546F2E70A2F31 -:1039B00004D9BDE8F840012000F064BBF8BD00BFA9 -:1039C00020380020F8B506460D4600F003FB0F4AEC -:1039D000134653F8107F9F4206D12A4601463046CF -:1039E000BDE8F840FFF7C2BFD169BB68441A2C1983 -:1039F00028BF2C46A34202D92946FFF79BFF224647 -:103A000031460348BDE8F840FFF77EBF203800206C -:103A10003038002010B4C0E9032300235DF8044BC4 -:103A20004361FFF7CFBF000010B5194C23699842DE -:103A30000DD0D0E90032816813605A609A680A4458 -:103A40009A60002303604FF0FF33A36110BD23464B -:103A5000026843F8102F53600022026022699A42E4 -:103A600003D1BDE8104000F0C1BA936881680B44EF -:103A7000936000F0AFFA2269E1699268441AA242A9 -:103A8000E4D91144BDE81040091AFFF753BF00BF45 -:103A9000203800202DE9F047DFF8BC8008F110073E -:103AA0002C4ED8F8105000F095FAD8F81C40AA68AF -:103AB000031B9A423ED81444D5E900324FF0000966 -:103AC000C8F81C4013605A60C5F80090D8F8103050 -:103AD000B34201D100F08AFA89F31188D5E90331A4 -:103AE00028469847302383F311886B69002BD8D080 -:103AF00000F070FA6A69A0EB04094A4582460DD2CB -:103B0000022000F0BFFA0022D8F81030B34208D1EA -:103B100051462846BDE8F047FFF728BF121A224455 -:103B2000F2E712EB090938BF4A4629463846FFF743 -:103B3000EBFEB5E7D8F81030B34208D01444211A90 -:103B4000C8F81C00A960BDE8F047FFF7F3BEBDE868 -:103B5000F08700BF30380020203800200020704758 -:103B6000FEE70000704700004FF0FF307047000094 -:103B7000BFF34F8F024A1369DB03FCD4704700BFC9 -:103B80000020024008B5094B1B7873B9FFF7F0FF1E -:103B9000074B5A69002ABFBF064A9A6002F1883271 -:103BA0009A601A6822F480621A6008BD603A0020A8 -:103BB000002002402301674508B50B4B1B7893B9E1 -:103BC000FFF7D6FF094B5A6942F000425A611A6862 -:103BD00042F480521A601A6822F480521A601A68FD -:103BE00042F480621A6008BD603A00200020024062 -:103BF0007F289ABF00F58030C00200207047000087 -:103C00004FF4006070470000802070477F2808B59F -:103C10000BD8FFF7EDFF00F500630268013204D115 -:103C200004308342F9D1012008BD0020FCE70000E8 -:103C30007F2810B504461FD8FFF79AFFFFF7A2FFB1 -:103C40000E4BF3221A6102225A615A6942EAC002FB -:103C50005A615A6942F480325A61FFF789FF4FF482 -:103C60000061FFF7C5FF00F04BF9FFF7A5FF204605 -:103C7000BDE81040FFF7CABF002010BD0020024081 -:103C80002DE9F84340EA020313F00703144606D077 -:103C9000304B40F231321A600020BDE8F8838518BD -:103CA0002D4A95420CD92B4A40F236311160F3E788 -:103CB000031D1B684A68934208D1083C083008314C -:103CC000072C14D902680B689A42F1D0FFF75AFF0B -:103CD000FFF74EFF214E08314FF001084FF0000969 -:103CE000012CA1F1080706D8FFF766FF01E0002CC0 -:103CF000ECD10120D1E7C6F81480054651F8083C04 -:103D000045F8043B51F8043C4360FFF731FF336949 -:103D100043F001033361C6F81490026851F8083C7F -:103D20009A420CD00B4B40F25E321A600C4B18607A -:103D30000C4B1C600C4B1F60FFF73EFFACE72D687F -:103D400051F8043C9D4201F10801EBD1083C0830D8 -:103D5000C6E700BF5C3A00200000040800200240D3 -:103D6000503A0020583A0020543A0020084908B53B -:103D70000B7828B11BB9FFF705FF01230B7008BDB5 -:103D8000002BFCD0BDE808400870FFF715BF00BF4E -:103D9000603A00204FF480314FF0005000F0B2B88C -:103DA0000846114600F014BC012000F011BC0000D0 -:103DB000084600F02BBC000070B582B0FFF740FD54 -:103DC0000E4E054600F006F93268904237BF0C4AA5 -:103DD0000B49516814682EBFD1E90041013151608F -:103DE0000419034641F10001284601913360FFF7B1 -:103DF00031FD0199204602B070BD00BF643A002039 -:103E0000683A002070B582B0FFF71AFD104E0546E3 -:103E100000F0E0F83268904237BF0E4A0D49516811 -:103E200014682EBFD1E9004101315160041941F1FC -:103E300000010346284601913360FFF70BFD01990D -:103E40004FF47A7200232046FCF7B2F902B070BD3D -:103E5000643A0020683A002010B50244064BD2B202 -:103E6000904200D110BD441C00B253F8200041F82C -:103E7000040BE0B2F4E700BF50280040114B30B50E -:103E8000D3F89040240409D4D3F89040C3F890406C -:103E9000D3F8904044F40044C3F890400A4C23689F -:103EA00043F4807323600244084BD2B2904200D1A5 -:103EB00030BD441C00B251F8045B43F82050E0B21E -:103EC000F4E700BF0010024000700040502800409E -:103ED00007B5012201A90020FFF7BEFF019803B03A -:103EE0005DF804FB13B50446FFF7F2FFA04205D0CE -:103EF000012201A900200194FFF7C0FF02B010BD0C -:103F0000704700007047000070470000074B45F203 -:103F100055521A6002225A6040F6FF729A604CF6BF -:103F2000CC421A60024B01221A70704700300040E8 -:103F3000743A0020034B1B781BB1034B4AF6AA22AC -:103F40001A607047743A002000300040054B1A6830 -:103F500032B902F1804202F50432D2F894201A609C -:103F6000704700BF703A0020024B4FF40002C3F8C4 -:103F7000942070470010024008B5FFF7E7FF024B9E -:103F80001868C0F3407008BD703A00207047000008 -:103F9000FEE700000A4B0B480B4A90420BD30B4B39 -:103FA000DA1C121AC11E22F003028B4238BF002213 -:103FB0000021FDF7B5B953F8041B40F8041BECE7EA -:103FC0005C480008003B0020003B0020003B002034 -:103FD00000F0BEB84FF08043586A70474FF08043FE -:103FE000002258631A610222DA6070474FF0804362 -:103FF0000022DA60704700004FF08043586370473A -:10400000FEE7000070B51B4B01630025044686B037 -:10401000586085620E46FFF7DFFA04F11003C4E929 -:1040200004334FF0FF33C4E90635C4E90044A5600A -:10403000E562FFF7CFFF2B460246C4E9082304F1EF -:1040400034010D4A256580232046FFF713FC012328 -:10405000E0600A4A0375009272680192B268CDE985 -:104060000223074B6846CDE90435FFF72BFC06B069 -:1040700070BD00BF483A0020C8470008CD4700087F -:1040800001400008024AD36A1843D062704700BF5B -:1040900020380020244B2548DA6A42F0070210B489 -:1040A000DA62DA6A224C22F00702DA62DA6ADA6C41 -:1040B00042F00702DA64DA6E42F00702DA664FF085 -:1040C0009042DB6E4FF0AA31002353609160D060C4 -:1040D0004FF6FF7050611362536214601024C2F8EF -:1040E0000434C2F80814C2F80C444FF6F774C2F84E -:1040F00014449924C2F82034C2F824440D4CC2F868 -:104100000044C2F80438C2F80818C2F80C38C2F8E3 -:104110001408C2F82038C2F82438C2F800385DF814 -:10412000044B00F055B800BF00100240000100240D -:104130000001002850000A0008B500F005FAFFF75A -:1041400057FBBDE80840FFF701BF000070470000C3 -:104150000F4B9A6D42F001029A659A6F42F001028C -:104160009A670C4A9B6F936843F0010393604FF08A -:1041700080434F229A624FF0FF32DA6200229A6146 -:104180005A63DA605A6001225A611A60704700BFB0 -:1041900000100240002004E04FF0804208B5116991 -:1041A000D3680B40D9B2C9439B07116107D53023AF -:1041B00083F31188FFF742FB002383F3118808BDC6 -:1041C00008B5FFF757FABDE8084000F099B90000BC -:1041D0005A4B4FF0FF319A6A99629A6A00229A62AA -:1041E000986AD86A60F00700D862D86A00F00700C1 -:1041F000D862D86A186B1963186B1A63186B986BBE -:104200009963986B9A63986BD86BD963D86BDA63B0 -:10421000D86B186C1964196C1A641A6C484A4FF4FC -:10422000E06111601A6E474942F001021A66D3F844 -:10423000802022F00102C3F88020D3F880209A6DFC -:1042400042F080529A659A6F22F080529A679A6F74 -:104250004FF440720A604A6912F48062FBD14A60EE -:104260001A6822F0F00242F060021A601A6842F006 -:1042700001021A601A689107FCD500229A609A68B8 -:1042800012F00C02FBD1D3F8901011F4407F1EBF46 -:104290004FF48031C3F89010C3F8902061221A6067 -:1042A0001A689207FCD500229A609A6812F00C0FE7 -:1042B000FBD169221A60D3F8942022F4706242F490 -:1042C000C062C3F894201A6842F480321A601A68F7 -:1042D0009003FCD5D3F8902022F00322C3F890205D -:1042E000194ADA601A6842F080721A601A689101FD -:1042F000FCD5164A1A611A6842F080621A601A6880 -:104300001201FCD500229A600D49114AC3F8882099 -:104310000A6822F0070242F004020A600A6802F00A -:104320000702042AFAD19A6842F003029A609A6856 -:1043300002F00C020C2AFAD1704700BF00100240B4 -:10434000002002400070004003140001000C100027 -:1043500055550134074A08B5536903F00103536109 -:1043600023B1054A13680BB150689847BDE808406F -:10437000FFF756B900040140783A0020074A08B513 -:10438000536903F00203536123B1054A93680BB1EB -:10439000D0689847BDE80840FFF742B900040140E3 -:1043A000783A0020074A08B5536903F004035361C3 -:1043B00023B1054A13690BB150699847BDE808401D -:1043C000FFF72EB900040140783A0020074A08B5EB -:1043D000536903F00803536123B1054A93690BB194 -:1043E000D0699847BDE80840FFF71AB900040140BA -:1043F000783A0020074A08B5536903F01003536167 -:1044000023B1054A136A0BB1506A9847BDE80840CA -:10441000FFF706B900040140783A0020164B10B5AA -:104420005C6904F478725A61A30604D5134A936A4E -:104430000BB1D06A9847600604D5104A136B0BB1D4 -:10444000506B9847210604D50C4A936B0BB1D06B87 -:104450009847E20504D5094A136C0BB1506C984794 -:10446000A30504D5054A936C0BB1D06C9847BDE801 -:104470001040FFF7D5B800BF00040140783A002093 -:10448000194B10B55C6904F47C425A61620504D58D -:10449000164A136D0BB1506D9847230504D5134A86 -:1044A000936D0BB1D06D9847E00404D50F4A136E9D -:1044B0000BB1506E9847A10404D50C4A936E0BB112 -:1044C000D06E9847620404D5084A136F0BB1506F41 -:1044D0009847230404D5054A936F0BB1D06F9847D2 -:1044E000BDE81040FFF79CB800040140783A002076 -:1044F00008B5FFF751FEBDE80840FFF791B800008E -:10450000062108B50846FFF7C9F806210720FFF77E -:10451000C5F806210820FFF7C1F806210920FFF79A -:10452000BDF806210A20FFF7B9F806211720FFF78A -:10453000B5F806212820FFF7B1F8BDE808400721AB -:104540001C20FFF7ABB8000008B5FFF739FE00F0FC -:1045500007F8FFF7FBFDBDE80840FFF739BD000095 -:104560000023054A19460133102BC2E9001102F15C -:104570000802F8D1704700BF783A00200B46014688 -:10458000184600F02DB8000000F040B8012838BFF0 -:10459000012010B50446204600F030F830B900F094 -:1045A00007F808B900F00CF88047F4E710BD0000E8 -:1045B000024B1868BFF35B8F704700BFF83A0020CA -:1045C00008B5062000F084F80120FFF7C9FA0000C2 -:1045D000024B0A4601461868FFF7E2BB181100209B -:1045E00010B5054C13462CB10A4601460220AFF324 -:1045F000008010BD2046FCE700000000024B014691 -:104600001868FFF7D1BB00BF18110020024B01460C -:104610001868FFF7CDBB00BF1811002010B5013995 -:104620000244904201D1002005E0037811F8014FC7 -:10463000A34201D0181B10BD0130F2E72DE9F04173 -:10464000A3B1C91A17780144044603F1FF3C8C4218 -:10465000204601D9002009E00578BD4204F101049B -:10466000F5D10CEB0405D618A54201D1BDE8F081C7 -:1046700015F8018D16F801EDF045F5D0E7E70000DB -:104680001F2938B504460D4604D9162303604FF0A0 -:10469000FF3038BD426C12B152F821304BB9204680 -:1046A00000F030F82A4601462046BDE8384000F0C8 -:1046B00017B8012B0AD0591C03D11623036001201F -:1046C000E7E7002442F82540284698470020E0E725 -:1046D000024B01461868FFF7D3BF00BF1811002036 -:1046E00038B5074D00230446084611462B60FFF7F6 -:1046F0003BFA431C02D12B6803B1236038BD00BFD5 -:10470000FC3A0020FFF72ABA034611F8012B03F800 -:10471000012B002AF9D170476F72672E61726475A0 -:1047200070696C6F742E4D6174656B4C3433312D30 -:1047300041697273706565640000000040A2E4F195 -:10474000646891060041A3E5F265699207000000E4 -:104750004261642043414E496661636520696E642D -:1047600065782E00800000000080000000008000BE -:104770000000000000000000291B000811230008B1 -:1047800071220008391B00086D1B0008691D000814 -:104790003D1B00084D1B0008411B0008491B000879 -:1047A000451B0008911C0008511B0008DD2500086E -:1047B000611B0008651C000863300000B847000852 -:1047C00078380020483A00206D61696E0069646C99 -:1047D000650000000CBAFF7F01000000000000002F -:1047E000260400000000000000600300000000003C -:1047F000FE2A0100D20400001C110020000000006D -:1048000000000000000000000000000000000000A8 -:104810000000000000000000000000000000000098 -:104820000000000000000000000000000000000088 -:104830000000000000000000000000000000000078 -:104840000000000000000000000000000000000068 -:0C4850000000000000000000000000005C +:1000000000090020B1010008D9220008912200084F +:10001000B922000891220008B1220008B3010008AB +:10002000B3010008B3010008B3010008CD32000895 +:10003000B3010008B3010008B3010008B3010008D0 +:10004000B3010008B3010008B3010008B3010008C0 +:10005000B3010008B30100082D4000085540000816 +:100060007D400008A5400008CD400008B30100080D +:10007000B3010008B3010008B3010008B301000890 +:10008000B3010008B3010008B301000845220008CD +:100090007122000881220008B3010008F540000821 +:1000A000B3010008B3010008B3010008B301000860 +:1000B000C9410008B3010008B3010008B3010008FA +:1000C000B3010008B3010008B3010008B301000840 +:1000D000B3010008B3010008B3010008B301000830 +:1000E00059410008B3010008B3010008B30100083A +:1000F000B3010008B3010008B3010008B301000810 +:10010000B3010008B3010008B3010008B3010008FF +:10011000B3010008B3010008B3010008B3010008EF +:10012000B3010008B3010008B3010008B3010008DF +:10013000B3010008B3010008B3010008B3010008CF +:10014000B3010008B3010008B3010008B3010008BF +:10015000B3010008B3010008B3010008B3010008AF +:10016000B3010008B3010008B3010008B30100089F +:10017000B3010008B3010008B3010008B30100088F +:10018000B3010008B3010008B3010008B30100087F +:10019000B3010008B3010008B3010008B30100086F +:1001A000FD0E00080000000000000000000000003C +:1001B00002E000F000F8FEE772B6374880F30888E6 +:1001C000364880F3098836483649086040F2000016 +:1001D000CCF200004EF63471CEF200010860BFF39D +:1001E0004F8FBFF36F8F40F20000C0F2F0004EF669 +:1001F0008851CEF200010860BFF34F8FBFF36F8FBD +:100200004FF00000E1EE100A4EF63C71CEF2000114 +:100210000860062080F31488BFF36F8F03F022FD7F +:1002200003F0A4FD4FF055301F491B4A91423CBFDB +:1002300041F8040BFAE71D49184A91423CBF41F8C6 +:10024000040BFAE71A491B4A1B4B9A423EBF51F86E +:10025000040B42F8040BF8E700201849184A9142B1 +:100260003CBF41F8040BFAE703F000FD03F0D0FDBA +:10027000144C154DAC4203DA54F8041B8847F9E7D7 +:1002800000F042F8114C124DAC4203DA54F8041B52 +:100290008847F9E703F0E8BC0009002000110020BE +:1002A0000000000808ED00E0000100200009002027 +:1002B000B0440008001100207C11002080110020B3 +:1002C000FC3A0020A0010008A4010008A4010008D5 +:1002D000A40100082DE9F04F2DED108AC1F80CD0D3 +:1002E000C3689D46BDEC108ABDE8F08F002383F300 +:1002F00011882846A047002003F058F9FEE703F0D4 +:10030000E1F800DFFEE70000F8B500F009FE03F0B9 +:100310004BFC074603F09CFC0646C0BB274B9F42A4 +:1003200035D001339F4235D0254B27F0FF029A424A +:1003300033D1F8B200F03AFC354642F2107400F0C6 +:100340003BFC08B10024254601F0A2F848B3032085 +:1003500000F03AF80024254636B11A4B9F4203D0EC +:1003600003F06EFC00242546002003F027FC0DB1AD +:1003700000F040F800F052FC01F0B6FF0546ACB9C1 +:1003800000F094FC4FF47A7003F016F9F7E7354665 +:100390000024D4E704460125D1E705464FF47A74DA +:1003A000CDE7B4F57A7F08BF0125D5E701F09CFFC2 +:1003B000431BA342E4D900F01DF8DDE7010007B0BC +:1003C000000008B0263A09B0084B187003280CD872 +:1003D000DFE800F008050208022000F0FFBD02205F +:1003E00000F0F2BD024B00225A60704780110020DD +:1003F0008411002010B501F04BF830B1234B0322DB +:100400001A70234B00225A6010BD224B224A1C4610 +:1004100019680131F8D004339342F9D16268A242DD +:10042000F2D31E4B9B6803F1006303F520439A420D +:10043000EAD203F0D7FB03F0E9FB002000F08AFDCD +:100440000220FFF7C1FF164B9A6D00229A65996F43 +:100450009A67996FD96DDA65D96FDA67D96F196EB6 +:100460001A66D3F88010C3F88020D3F8803072B6B3 +:100470004FF0E0233021C3F8084DD4E9003281F376 +:1004800011889D4683F308881047BDE7801100203E +:100490008411002000A0000820A000080011002006 +:1004A00000100240094A136849F2690099B21B0C16 +:1004B00000FB01331360064B186844F2506182B2AE +:1004C000000C01FB0200186080B27047141100207C +:1004D0001011002010B500211022044600F098FDF4 +:1004E000034B03CB206061601868A06010BD00BFA3 +:1004F0009075FF1F2DE9F041ADF5507D0DF13C08E1 +:100500006EAC40F2751207460D4610A80021C8F8DF +:10051000001000F07DFD4FF4C4720021204600F071 +:1005200077FD01F0E1FE254B4FF47A72B0FBF2F05B +:10053000186093E80700022384E807000DF5ED70CA +:100540002382FFF7C7FF42F204631D49238406A8F4 +:1005500003F046FF202384F832310DF2EB2606AB80 +:100560000DF1380C1A4603CA6245306071601346BB +:1005700006F10806F6D141460122204600F094FD1E +:1005800000230393AB7E029305F11903019380B21C +:100590000123CDE904800093E97E06A3D3E900237B +:1005A000384602F069FA0DF5507DBDE8F08100BFD4 +:1005B000AFF300809E6AC421818A46EE8C11002030 +:1005C000F04300082DE9F0412C4C237ADAB0804644 +:1005D0000D465BBB27A9284600F076FE074600289B +:1005E00042D19DF89D60C82E3ED801464FF4A662C8 +:1005F000204600F00DFD4FF48073C4F8F8314FF43D +:100600000073C4F80C334FF44073C4F820343246FE +:100610000DF19E0104F1090000F0E8FC26449DF86C +:100620009C30777223720BB9EB7E237281220021FA +:1006300006AC27A800F0ECFC0122214627A800F018 +:100640007FFE00230393AB7E029305F1190380B272 +:1006500001932823CDE904400093E97E05A3D3E963 +:100660000023404602F008FA5AB0BDE8F08100BF0E +:10067000AFF3008026417272DF25D7B7B032002079 +:10068000F0B5254E4FF48A7505FB0065F1B096F87C +:10069000D83085F8DC300024D822214685F8E8409F +:1006A0003AA800F0B5FC06F1090000F0A9FCD5F865 +:1006B000E4308DF8F000C2B206AF06F109010DF189 +:1006C000F100CDE93A3400F091FC394601223AA814 +:1006D00000F062FE80B2CDE9047008230127CDE965 +:1006E000023706F1D803019330230093317A0B4887 +:1006F00007A3D3E9002302F0BFF9A04206DD01F011 +:10070000F3FDC5F8E000384671B0F0BD2046FBE7C8 +:1007100078F6339F93CACD8DB0320020A4210020FB +:100720002DE9F0411D4D1E4E1E4F86B0284602F0A9 +:10073000CFF9034658B30024CDE90344ADF8144083 +:10074000027B8DF8142099684068029403AA03C2C2 +:100750001B68DFF8548043F00043029301F0C6FDAC +:10076000821941F10003009402A9384601F06EF8A5 +:10077000A04205DD284602F0AFF988F80040D5E731 +:1007800098F80030072B05D8013388F8003006B000 +:10079000BDE8F081014802F09FF9F8E7A4210020AC +:1007A00040420F00D8210020E537002070B50D46EB +:1007B00014461E4602F0BCF850B9022E10D1012C8E +:1007C0000ED112A3D3E90023C5E90023012007E0DD +:1007D000282C10D005D8012C09D0052C0FD00020D2 +:1007E00070BD302CFBD10BA3D3E90023ECE70BA3A6 +:1007F000D3E90023E8E70BA3D3E90023E4E70BA345 +:10080000D3E90023E0E700BFAFF30080401DA12043 +:1008100026812A0B78F6339F93CACD8D9E6AC42118 +:10082000818A46EE26417272DF25D7B7F017304A2B +:1008300039059E5638B505460E4C0021013500F0AD +:10084000ABFBA4F82C55B4F82C0500F08DFB78B167 +:10085000B4F82C0500F098FB014648B9B4F82C0513 +:1008600000F09AFBB4F82C350133A4F82C35EAE7F4 +:1008700038BD00BFB032002010B50A4B0A4A1A60DA +:1008800003F5805393F860203AB9DC6D2CB1204613 +:1008900000F07CFE204603F0E3FCBDE81040034876 +:1008A00000F074BED82100205044000820320020FF +:1008B0002DE9F04F8FB000AF05460C4602F038F836 +:1008C000002849D1237E022B1BD1E38A012B18D1AA +:1008D00001F00AFD0646FFF7E5FD03464FF4C87038 +:1008E000DFF8C482B3FBF0F206F5167602FB103394 +:1008F00016FA83F3C8F80030E37E33B9A34B002225 +:100900001A703C37BD46BDE8F08F07F12401204640 +:1009100000F098FC0028F4D107F11400FFF7DAFD8D +:1009200097F8264007F11401224607F1270003F04B +:10093000E1FC0028E2D10F2C08D8944B1C70D8F8A9 +:100940000030A3F51673C8F80030DAE797F82410E2 +:10095000284601F0E5FFD4E7E38A282B2BD010D8F6 +:10096000012B23D0052BCCD1BFF34F8F8849894B66 +:10097000CA6802F4E0621343CB60BFF34F8F00BF3D +:10098000FDE7302BBDD1844EE17E327A9142B8D161 +:10099000607E3146002291F8DC50854200F0A5804F +:1009A0000132042A01F58A71F5D1AAE721462846C9 +:1009B000FFF7A0FDA5E721462846FFF703FEA0E7C5 +:1009C000B2F8EC507B6005F103094FEA99094FEA50 +:1009D0008902D11DC908A8EBC1039D46EB46002141 +:1009E000584600F015FB04F1EE012A463144584602 +:1009F00000F0FCFA7B6813B9012000F0ABFA96F81E +:100A0000D20000F0B1FA044630B9307200F0CCFAEE +:100A1000204600F09FFAB1E0D6F8D4203AB996F813 +:100A2000D200B6F82C25824201D8FFF703FFD6F892 +:100A3000D4202A44944208D296F8D200B6F82C2545 +:100A40000130824201D8FFF7F5FE70685FFA89F243 +:100A5000594600F0E5FA08B9C54679E0726896F89B +:100A6000D2002A447260D6F8D42005EB0209C6F8F9 +:100A7000D49000F079FA814509D396F8D220D6F8BF +:100A8000D4000132001B86F8D220C6F8D400FF2D16 +:100A90000FD80024347200F087FA204600F05AFA8A +:100AA00000F0F6FC3D4B188108B9FFF7A3FCC546E2 +:100AB00027E7BB6896F8D9000AFB0362FB68D2F807 +:100AC000E41082F8E83001F58061C2F8E030C2F845 +:100AD000E410FFF7D5FDFFF723FE96F8D920013289 +:100AE00002F0030286F8D920B6E74FF48A7A0AFBAF +:100AF00002F505F1EA013144204600F079FCF86086 +:100B000000287FF4FEAE3544012285F8E82001F08C +:100B1000EBFBD5F8E020D6ED007ADFED216A801AF4 +:100B2000192838BF192040F6B832904228BF104625 +:100B3000B8EE677A07EE900AF8EEE77A67EEA67AE3 +:100B4000DFED186AE7EE267AFCEEE77AC6ED007A6A +:100B500096F8D930BB60BA6873680AFB02F43219A0 +:100B600092F8E81059B1D2F8E4108B42E8463FF40D +:100B700027AF002182F8E810C2F8E010C54673687C +:100B8000064A9B0A01331381BBE600BF9D2100206A +:100B900000ED00E00400FA05B03200208C110020C6 +:100BA000CDCCCC3D6666663FA0210020014B18707D +:100BB000704700BF9811002038B54FF00054134B18 +:100BC00022689A4220D1124B627D12481A70237D0E +:100BD00003724FF48073C0F8F8314FF40073C0F81B +:100BE0000C3300254FF44073C0F820340A49C0F894 +:100BF000E450C922093000F0F9F9E02229462046E4 +:100C000000F006FA012038BD0020FCE79AAD44C58B +:100C100098110020B03200201600002037B500F0F7 +:100C200037FC194D194928810223012218486B719C +:100C300001F0F6F900230193164B1749009317486A +:100C4000174B4FF4805201F043FE164B197811B147 +:100C5000124801F065FE01F047FB0446FFF722FC55 +:100C60004FF4C873B0FBF3F202FB130304F51670E4 +:100C700010FA83F00C4B186002F0EAFF08B10F2362 +:100C80002B8103B030BD00BF8C11002040420F000B +:100C9000D8210020AD0700089C110020A4210020CD +:100CA000B108000898110020A02100202DE9F04F84 +:100CB0002DED028B0FF23829D9E90089834C93B0CE +:100CC0000BAE9FED7E8BFFF72BFD814FDFF828A247 +:100CD00000230A93ADF834300B9373604FF0000B90 +:100CE0005B468DED008B01250DF11D0207A93846ED +:100CF0008DF81C508DF81DB001F040F99DF81C30A6 +:100D0000002B40F0A580204601F012FE0646002888 +:100D100045D1704F01F0E8FA3B6898423FD301F0AB +:100D2000E3FA8246FFF7BEFB4FF4C873B0FBF3F261 +:100D300002FB13030AF5167010FA83F03860664F51 +:100D400097F800B0CBF1100ABBF1000F14BF334687 +:100D50002B465FFA8AFA0EA88DF82830FFF7BAFB07 +:100D6000BAF1060F28BF4FF0060A0EAB03EB0B01DA +:100D700052460DF1290000F039F90AAB039318230C +:100D800002930AF10102554BD2B2CDE9005304920D +:100D900020464CA3D3E9002301F010FE3E7001F081 +:100DA000A3FA4F4A4F4D1368C31AB3F57A7F2ED377 +:100DB000106001F09BFA02460B46204601F096FEB9 +:100DC000204601F0B5FD10B32B7A474E002B14BF1F +:100DD00003230223737101F087FA0EAF4FF47A7385 +:100DE0000122B0FBF3F039463060304600F002FAE1 +:100DF000182302933D4B019380B240F25513CDE985 +:100E00000370009342464B46204601F0D7FD2B7AF3 +:100E100093B101F069FA002607464FF48A7A95F8F3 +:100E2000D900304400F003000AFB005393F8E82097 +:100E300092B30136042EF2D1C82002F0BDFB2B7A0A +:100E4000002B7FF43DAF13B0BDEC028BBDE8F08FFB +:100E5000DAF8143083F00803CAF814305946102227 +:100E60000EA800F0D5F80DF11E0308AA0AA938460D +:100E700000F0ECFD96E803000FAB83E803009DF85B +:100E800034308DF844300A9B0E930EA9DDE9082317 +:100E9000204601F0FFFF21E7D3F8E02042B12B68A4 +:100EA000FA2B38BFFA23BA1A0533B2EB430FC0D37B +:100EB000FFF7E6FB0028BCD1BEE700BF0000000042 +:100EC00000000000401DA12026812A0BA421002043 +:100ED000D8210020A02100209D2100209C2100205D +:100EE000E0370020B03200208C110020E4370020D1 +:100EF000F1C6A7C1D068080F0004004808B505482E +:100F000000F040FEBDE80840034A0449002003F019 +:100F1000A1B900BFD821002020380020790800089E +:100F200070B502F0E5FC094E094D308000242868B8 +:100F30003388834208D902F0D7FC2B68044401337C +:100F4000B4F5204F2B60F2D370BD00BF14380020E1 +:100F5000E837002002F07EBD00F10060920000F54D +:100F6000204002F001BD0000054B1A68054B1B88AC +:100F70009B1A834202D9104402F0B6BC002070478D +:100F8000E837002014380020024B1B68184402F098 +:100F9000B1BC00BFE8370020024B1B68184402F0C8 +:100FA000BBBC00BFE8370020064991F8243033B1BC +:100FB0000023086A81F824300822FFF7CDBF012002 +:100FC000704700BFEC370020022802BF024B4FF4ED +:100FD00000229A61704700BF00040048022802BF47 +:100FE000014B08229A6170470004004810B50023A5 +:100FF000934203D0CC5CC4540133F9E710BD000028 +:1010000003460246D01A12F9011B0029FAD1704793 +:1010100002440346934202D003F8011BFAE77047EB +:101020002DE9F8431F4D144695F8242007468846BD +:1010300052BBDFF870909CB395F824302BB9202276 +:10104000FF2148462F62FFF7E3FF95F82400C0F127 +:101050000802A24228BF2246D6B24146920005EBC2 +:101060008000FFF7C3FF95F82430A41B1E44F6B29E +:10107000082E17449044E4B285F82460DBD1FFF7D2 +:1010800093FF0028D7D108E02B6A03EB8203834249 +:10109000CFD0FFF789FF0028CBD10020BDE8F8832F +:1010A0000120FBE7EC3700202DE9F0470D46044610 +:1010B00000219046284640F27912FFF7A9FF234607 +:1010C00020220021284601F087FE231D0222202134 +:1010D000284601F081FE631D03222221284601F0EB +:1010E0007BFEA31D03222521284601F075FE04F195 +:1010F000080310222821284601F06EFE04F1100397 +:1011000008223821284601F067FE04F11103082265 +:101110004021284601F060FE04F112030822482114 +:10112000284601F059FE04F11403202250212846DC +:1011300001F052FE04F1180340227021284601F00C +:101140004BFE04F120030822B021284601F044FEA2 +:1011500004F121030822B821284601F03DFE04F1E4 +:101160002207C0263B46314608222846083601F0B1 +:1011700033FEB6F5A07F07F10107F3D104F1320386 +:1011800008223146284601F027FE002704F1330AE1 +:1011900094F832304FEAC7099F4209F5A47615D377 +:1011A000B8F1000F08D1314604F59973072228469B +:1011B00001F012FE09F24F16274694F832213B1B2C +:1011C00093420CD3F01DC008BDE8F0870AEB07037B +:1011D00008223146284601F0FFFD0137D8E707F223 +:1011E000331331460822284601F0F6FD0836013750 +:1011F000E3E7000013B504460846002101602346DA +:10120000C0F803102022019001F0E6FD0198231D93 +:101210000222202101F0E0FD0198631D032222211A +:1012200001F0DAFD0198A31D0322252101F0D4FD70 +:10123000019804F108031022282101F0CDFD0720B8 +:1012400002B010BDF7B50023047F00910E460722BF +:101250001946054601F084FC731C0093012200230B +:101260000721284601F07CFCC4B9B31C0093052279 +:1012700023460821284601F073FC0D243746B27836 +:10128000BB1B934211D32B7FA88A0734E408BBB958 +:10129000844294BF0020012003B0F0BDAB8ADB0084 +:1012A000083BDB08B3700824E8E7FB1C00932146E9 +:1012B00000230822284601F053FC08340137DEE7FA +:1012C000201A18BF0120E7E7F7B50023047F00913B +:1012D0000E4608221946054601F042FC731CC4B9AB +:1012E0000822009311462346284601F039FC1024B9 +:1012F000012372785F1C013B934211D32B7FA88A94 +:101300000734E408BBB9844294BF0020012003B035 +:10131000F0BDAB8ADB00083BDB0873700824E7E70D +:10132000F3190093214600230822284601F018FCF7 +:1013300008343B46DDE7201A18BF0120E7E700002C +:10134000F8B50E4605461446002181223046FFF7C7 +:101350005FFE2B4608220021304601F03DFD7CB99E +:101360006B1C07220821304601F036FD0F240123B3 +:101370006A785F1C013B934204D3E01DC008F8BDAE +:101380000824F4E7EB1921460822304601F024FD39 +:1013900008343B46ECE70000F8B50E460546144617 +:1013A0000021CE223046FFF733FE2B4628220021B3 +:1013B000304601F011FD7CB905F10803082228210F +:1013C000304601F009FD30242F462A7A7B1B9342D8 +:1013D00004D3E01DC008F8BD2824F5E707F1090390 +:1013E00021460822304601F0F7FC08340137ECE7CB +:1013F000F7B5047F00910E46012310220021054617 +:1014000001F0AEFBC4B9B31C00930922234610219E +:10141000284601F0A5FB192437467288BB1B9A4267 +:1014200011D82B7FA88A0734E408BBB9844294BF43 +:101430000020012003B0F0BDAB8ADB00103BDB08CD +:1014400073801024E8E73B1D009321460023082207 +:10145000284601F085FB08340137DEE7201A18BF63 +:101460000120E7E730B5094D0A4491420DD011F84B +:10147000013B5840082340F30004013B2C4013F08B +:10148000FF0384EA5000F6D1EFE730BD2083B8EDCA +:10149000F7B5384A106851686B4603C36A46364947 +:1014A0003648082302F036FF0446002833D10A25C7 +:1014B000334A106851686B4603C36A4631492F4866 +:1014C000082302F027FF0446002849D00369B3F53A +:1014D000583F45D8B0F8661040F2264291423FD1BD +:1014E000294A024402F15C018B4239D35C3B234917 +:1014F00000209E1AFFF7B6FF3246074604F164014A +:101500000020FFF7AFFFA3689F4229D1E36898420C +:1015100008BF002524E00369B3F5583F27D8418B65 +:1015200040F22642914220D1174A024402F11001B2 +:101530008B4218D3103B114900209D1AFFF792FFF0 +:101540002A46064604F118010020FFF78BFFA36826 +:101550009E4202D1E368984201D00D25A8E70025FC +:10156000284603B0F0BD1025A2E70C25A0E70B2507 +:101570009EE700BF14440008DC5F030000A00008E1 +:101580001D440008905F03000860FFF710B5037C5E +:10159000044613B9006802F0A5FE204610BD000005 +:1015A0000023BFF35B8FC360BFF35B8FBFF35B8F21 +:1015B0008360BFF35B8F7047BFF35B8F0068BFF33F +:1015C0005B8F704770B505460C30FFF7F5FF05F1EE +:1015D000080604463046FFF7EFFFA04206D9304622 +:1015E0006D68FFF7E9FF2544281A70BD3046FFF704 +:1015F000E3FF201AF9E7000070B50546406898B18E +:1016000005F10800FFF7D8FF05F10C060446304647 +:10161000FFF7D2FF8442304694BF6D680025FFF784 +:10162000CBFF013C2C44201A70BD000038B50C469D +:101630000546FFF7C7FFA04210D305F10800FFF7EA +:10164000BBFF04446868B4FBF0F100FB1144BFF336 +:101650005B8F0120AC60BFF35B8F38BD0020FCE7DF +:101660002DE9F041144607460D46FFF7C5FF8442B9 +:1016700028BF0446D4B1B84658F80C6B4046FFF773 +:101680009BFF3044286040467E68FFF795FF331A81 +:101690009C4203D86C600120BDE8F0816B60A41B04 +:1016A0003B68AB602044E8600220F5E72046F3E7A2 +:1016B00038B50C460546FFF79FFFA04210D305F151 +:1016C0000C00FFF779FF04446868B4FBF0F100FBFD +:1016D0001144BFF35B8F0120EC60BFF35B8F38BD1B +:1016E0000020FCE72DE9FF41884669460746FFF7E1 +:1016F000B7FF6C4606B204EBC6060025B44209D01B +:101700006268206808EB0501FFF770FC6368083425 +:101710001D44F3E729463846FFF7CAFF284604B0C0 +:10172000BDE8F081F8B505460C300F46FFF744FFE1 +:1017300005F1080604463046FFF73EFFA04230465A +:1017400088BF6C68FFF738FF201A386020B1304638 +:101750002C68FFF731FF2044F8BD000073B5144634 +:1017600006460D46FFF72EFF844228BF044601902F +:10177000DCB101A93046FFF7D5FF019B33B93268D0 +:10178000C5E90233C5E9002401200CE09C4238BFC2 +:1017900001942860019868608442F5D93368AB6091 +:1017A000241AEC60022002B070BD2046FBE7000066 +:1017B0002DE9FF410F466946FFF7D0FF6C4600B2A6 +:1017C00004EBC0050026AC4209D0D4F8048054F8DC +:1017D000081BB8194246FFF709FC4644F3E73046B8 +:1017E00004B0BDE8F081000038B50546FFF7E0FF22 +:1017F000044601462846FFF719FF204638BD000081 +:1018000010B4026854681A4623465DF8044B184722 +:10181000002070470020704770470000002070478C +:101820000E20704700F5805090F8C800C0F34000CB +:101830007047000000F5805090F9D000704700001C +:1018400000F58050C0F8CC1001207047F7B50C6847 +:10185000BDF8207014F0005470D10D7B082D6DD8A8 +:10186000302585F311884569AE6876010CD4AC68E3 +:10187000240108D4AC6814F080545DD184F311883D +:10188000204603B0F0BD01240E6804F1180C002EB0 +:10189000B8BFF6004FEA0C1CB4BF46F0040676054C +:1018A00045F80C600E680FFA84FC16F0804F18BFE4 +:1018B00005EB0C1E05EB0C1C1EBFDEF8806146F02C +:1018C0000206CEF880610E7BCCF8846105EB04152E +:1018D0008E68C5F88C614E68C5F88861DCF8805167 +:1018E00045F00105CCF8805100EB441641F2680543 +:1018F0002E4405EB44150544C6E9002308350E4681 +:1019000001F10C0C56F804EB45F804EB6645F9D1EF +:10191000843436882E8000EB441407F003052679C2 +:1019200026F00B0635432571002484F311880097B7 +:1019300000F0FCFC0120A4E70224A5E74FF0FF30F3 +:101940009FE7000013B500F580540191E06DFFF7AB +:1019500053FE1F280AD90199E06D2022FFF7C2FE2D +:10196000A0F120035842584102B010BD0020FBE70F +:1019700008B5302383F3118800F58050C06DFFF760 +:101980000FFE002383F3118808BD000000220260CF +:10199000828142608260704710B500220023C0E956 +:1019A00000230023044603810C30FFF7EFFF20469D +:1019B00010BD0000F0B5054600F580500C4690F8CB +:1019C000C83013F0040FC3F3800108BF114661F360 +:1019D000820304F1840680F8C83005EB461389B011 +:1019E0001B79D8072ED57AB319072DD46846FFF78F +:1019F000D3FF05EB441303F5835303F1180703AA40 +:101A0000103318685968144603C40833BB42224691 +:101A1000F7D1186820609B88A380DDE90E23CDE90B +:101A200000230123ADF808302B686946DB6B28469C +:101A3000984705EB46152B791A075CBF43F008035E +:101A40002B7101E0002AF4D109B0F0BD2DE9F04777 +:101A50009A4688B0074688469146302383F311881A +:101A600007F580546846FFF797FFE06DFFF7AAFD82 +:101A70001F282AD9E06D20226946FFF7B5FE2028ED +:101A800023D103AD444605AB2E4603CE9E422060D3 +:101A90006160354604F10804F6D130682060B388EF +:101AA000A380DDE90023C9E90023BDF80830AAF8C6 +:101AB0000030002383F3118853464A464146384696 +:101AC00008B0BDE8F04700F01FBC002080F311888B +:101AD00008B0BDE8F08700002DE9F84F0023C0E909 +:101AE0000133254B044640F8183B0F46FFF74EFFE5 +:101AF00004F12800FFF750FF04F1480804F582556F +:101B00004646083530462036FFF746FFAE42F9D14B +:101B100004F580554FF480534FF00009C5E913399F +:101B2000C5F848800123EE6504F5875804F584560E +:101B3000C5F8549085F8583085F86030083608F1BB +:101B400008084FF0000A4FF0000B46E908ABA6F179 +:101B50001800FFF71BFF203646F8289C4645F4D1B5 +:101B600085F8D07017B1054800F0B8FB044B6361ED +:101B70002046BDE8F88F00BF504400082844000804 +:101B80000064004010B5044B197804464A1C1A70D2 +:101B9000FFF7A2FF204610BD1C3800202DE9F047BA +:101BA000002950D0294B2A4FB7FBF1F599428CBF41 +:101BB0000A231123581EB5FBF3FC03FB1C53C4B2CC +:101BC0002BB102280346F5D80020BDE8F0870CF1C0 +:101BD000FF36B6F5806FF7D2C4EBC40E0EF10303E7 +:101BE0004FEAE309C3F3C703A4EB030809F1010AB1 +:101BF0004FF47A755FFA88F009FB05555AFA88F8B0 +:101C0000B5FBF8F5B5F5617FC1BF0EF1FF33C3F346 +:101C1000C703E01AC0B25C1C50FA84F40CFB04F455 +:101C2000B7FBF4F4A142CFD1013BDBB20F2BCBD8F1 +:101C30000138C0B20728C7D80021107116809170F2 +:101C4000D3700120C1E70846BFE700BF3F420F0045 +:101C500000B4C40470B505460E464FF47A746B693F +:101C60005B6803F00103B34207D04FF47A7001F0D0 +:101C7000A3FC013CF3D1204670BD0120FCE700002D +:101C800030B54269936913F0700F16D000230B4CE6 +:101C9000936103F1840200EB421211794D0709D5DB +:101CA000890707D5416954F823508D60117941F0B7 +:101CB000040111710133032BEBD130BD3C4400080A +:101CC00073B51D46436916469A68D207044609D57E +:101CD0009A6801219960C2F34002CDE900650021B4 +:101CE000FFF768FE63699A68D1050BD59A684FF4CF +:101CF00080719960C2F34022CDE900650121204640 +:101D0000FFF758FE63699A68D2030BD59A684FF4BF +:101D100080319960C2F34042CDE90065022120463E +:101D2000FFF748FE04F58053D3F8CC0010B10368E8 +:101D30001B699847204602B0BDE87040FFF7A0BF7E +:101D4000F8B504464669002972D106F10C073868D7 +:101D5000800770D006EB01153868D5F8B00110F097 +:101D6000040FD5F8B0011ABFC00840F00040400D84 +:101D7000A061D5F8B0C11CF0020F1CBF40F080403C +:101D8000A061D5F8B40106EB011100F00F0084F852 +:101D90002400D1F8B8012077D1F8B801000A6077A3 +:101DA000D1F8B801000CA077D1F8B801000EE077A7 +:101DB000D1F8BC0184F82000D1F8BC01000A84F8F5 +:101DC0002100D1F8BC01000C84F82200D1F8BC112C +:101DD000090E84F823103821396004F1340004F12D +:101DE000180104F1240551F8046B40F8046BA94272 +:101DF000F9D109880180C4E90A23214600232386FA +:101E000051F8283B2046DB6B984704F5805393F844 +:101E1000C820D3F8CC0042F0040283F8C82010B1E7 +:101E200003681B6998472046BDE8F840FFF728BFC4 +:101E300006F110078BE7F8BD10B5044600F056FA1E +:101E400002460B4652EA030102D0013A63F1000355 +:101E50000449086820B12146BDE81040FFF770BF73 +:101E600010BD00BF18380020F0B5302181F3118873 +:101E7000DFF848C000F583510831002404F18405DF +:101E800000EB45152E7977070ED4F6060CD5D1E96F +:101E9000007697429E4107D246695CF82470B7608D +:101EA0002E7946F004062E710134032C01F1200135 +:101EB000E4D1002383F31188F0BD00BF3C44000847 +:101EC00008B5302383F31188FFF7DAFE002383F38C +:101ED000118808BDF8B543690546986800F0E050E0 +:101EE000B0F1E05F0F4621D0F8B1302383F31188C1 +:101EF00005F583541034002606F1840305EB4313E3 +:101F00001B791A0706D50136032E04F12004F3D1FC +:101F1000012007E05B07F6D42146384600F040FA7E +:101F20000028F0D1002383F31188F8BD0120FCE7DD +:101F300008B5302383F3118800F58050C06DFFF79A +:101F400041FB002383F3118843090CBF01200020CB +:101F500008BD0000F8B51D46002313700F46064665 +:101F60001446FFF7E5FF80F00100387025B12946DF +:101F70003046FFF7AFFF2070F8BD00002DE9B841F3 +:101F80000C4615461F46804600F0B0F90B462178F6 +:101F9000024609B9287850B14046FFF765FFFFF7C0 +:101FA0008FFF3B462A462146FFF7D4FF0120BDE8BC +:101FB000B881000070B5302686F31188174B9A6DF2 +:101FC00042F000729A659A6B42F000729A639A6BC3 +:101FD00022F000729A63002383F3118800F5805485 +:101FE00094F8C83013F0010516D1A9B186F3118811 +:101FF0000321132001F0DCF90321142001F0D8F9AA +:102000000321152001F0D4F994F8C83043F00103FE +:1020100084F8C83085F3118870BD00BF00100240FD +:102020002DE9F04700F5805588B095F8D030012BA8 +:1020300004468846164600F28180814F57F82320D7 +:102040000AB947F82300D7F800A0C4F80C8026741A +:10205000BAF1000F64D095F8D030012B70D0012177 +:102060002046FFF7A7FF302383F3118862691368C6 +:1020700023F0020313606269136843F001031360E5 +:10208000636900275F6187F3118801212046FFF70C +:10209000E1FD002800F09580E86DFFF781FA04F576 +:1020A0008359BA4609F10809202200216846FEF743 +:1020B000AFFF02A8FFF76AFCCDF818A06A4609EB4B +:1020C00007030DF1180E9446BCE80300F4451860B0 +:1020D0005960624603F10803F5D1DCF8000018608E +:1020E00020379CF804201A71602FDDD195F8C83094 +:1020F0006FF38203002785F8C8306A4641462046C0 +:10210000ADF80070ADF802708DF80470FFF746FD71 +:10211000636948BB4FF400421A6008B0BDE8F0871D +:1021200041F2D80002F09EF8814610B15146FFF707 +:10213000D3FCC7F80090B9F1000F8CD10020ECE778 +:10214000386803681B6B98470146002887D13868B8 +:10215000FFF730FF3868036832465B6841469847AE +:1021600000287FF47CAFE9E761221A609DF8023015 +:102170009DF803201B06120402F4702203F0407342 +:102180001343BDF80020C2F3090213439DF8042055 +:102190001205022E02F4E0020CBF4FF000410021B4 +:1021A000134362690B43D361636913225A61626905 +:1021B000136823F00103136039462046FFF74AFDF8 +:1021C00008B96369A6E795F8D03093BB6169D1F887 +:1021D000002242F00102C1F800226169D1F8002218 +:1021E00022F47C5222F00E02C1F800226169D1F87B +:1021F000002242F46062C1F800226269C2F814321F +:102200006269C2F80432626941F6FF71C2F80C12C9 +:102210006269C2F840326269C2F8443263690122DD +:10222000C3F81C226269D2F8003223F00103C2F81D +:10223000003295F8C83043F0020385F8C8306CE7E7 +:102240001838002008B500F051F850EA01030246A2 +:1022500002D0421E61F10001044B186810B10B4618 +:10226000FFF72EFDBDE8084001F064B818380020E3 +:1022700008B50020FFF7E0FDBDE8084001F05AB8BE +:1022800008B50120FFF7D8FDBDE8084001F052B8BD +:1022900000B59BB0EFF3098168226846FEF7A6FE01 +:1022A000EFF30583014B9B6BFEE700BF00ED00E001 +:1022B00008B5FFF7EDFF000000B59BB0EFF3098113 +:1022C00068226846FEF792FEEFF30583014B5B6BD5 +:1022D000FEE700BF00ED00E0FEE700000FB408B528 +:1022E000029801F019F9FEE701F0F8BB01F0DABB42 +:1022F00013B56C4684E80600031D94E8030083E8E8 +:102300000500012002B010BD73B58568019155B17B +:102310001B885B0707D4D0E900369B6B9847019A6E +:10232000C1B23046A847012002B070BDF0B5866842 +:1023300089B005460C465EB1BDF838305B070AD45B +:10234000D0E900379B6B98472246C1B23846B04768 +:10235000012009B0F0BD00220023CDE900230023B5 +:10236000ADF808300A4603AB01F108061068516861 +:102370001C4603C40832B2422346F7D110682060DD +:102380009288A280FFF7B2FF0423ADF808302B68D3 +:10239000CDE90001DB6B694628469847D8E7000085 +:1023A00030B503680968DD0FB5EBD17F23F06044D9 +:1023B00021F060424FEAD1700BD0002BB8BFA40CC3 +:1023C0000029B8BF920C944202D034BF01200020F3 +:1023D00030BD944205D1C1F38070C3F38073834252 +:1023E000F6D194422CBF00200120F1E72DE9F04105 +:1023F000456A15B94162BDE8F0814B6823F060473A +:10240000C3F38A464FEAD37EC3F3807816EA2306E5 +:1024100038BF3E46AC462B465A68BEEBD27F22F010 +:1024200060440AD0002A18DAA40CB44217D19D42A5 +:102430000FD10D60DEE71346EEE7A74207D102F0A9 +:102440008044C2F3807242450BD054B1EFE708D20A +:10245000EDE7CCF800100B60CDE7B44201D0B442F8 +:10246000E5D81A689C46002AE5D11960C3E7000048 +:102470002DE9F047089D01F007044FEAD5082244F2 +:1024800005F0070500EBD1004FF47F49944201D1DC +:10249000BDE8F08704F0070705F0070A57453E46F8 +:1024A00038BF5646C6F10806111B8E4228BF0E469D +:1024B000E10808EBD50E415C13F80EC0B94029FACB +:1024C00006F721FA0AF1FFB28CEA010147FA0AF78E +:1024D00039408CEA010C03F80EC034443544D5E78A +:1024E00080EA0120082341F2210201B240000029C4 +:1024F00080B203F1FF33B8BF504013F0FF03F4D1B3 +:102500007047000038B50C468D18A54200D138BD83 +:1025100014F8011BFFF7E4FFF7E7000042684AB137 +:10252000136843604389818901339BB29942438197 +:1025300038BF83811046704770B588B020220446AA +:102540000D4668460021FEF763FD20460495FFF71F +:10255000E5FF024658B16B46054608AE1C4603CC63 +:10256000B44228606960234605F10805F6D110469B +:1025700008B070BD082817D909280CD00A280CD03B +:102580000B280CD00C280CD00D280CD00E2814BF12 +:102590004020302070470C207047102070471420D6 +:1025A000704718207047202070470000082817D96E +:1025B0000C280CD910280CD914280CD918280CD99F +:1025C00020280CD930288CBF0F200E2070470920FE +:1025D00070470A2070470B2070470C2070470D2071 +:1025E000704700002DE9F843078C072F04461ED9D9 +:1025F000D0E9029800254FF6FF73C5F12006A5F13A +:10260000200029FA05F108FA06F628FA00F031430D +:102610000143C9B21846FFF763FF0835402D034652 +:10262000EBD1E1693A46BDE8F843FFF76BBF4FF6DF +:10263000FF70BDE8F883000010B54B6823B9CA8A63 +:1026400063F30902CA8210BD04691A681C60036141 +:10265000C38A013BC3824A60EFE700002DE9F84FCF +:102660001D46CB8A0F46C3F30901052981469246D0 +:102670000B4630D00020AAB207F11A049EB2042EF5 +:102680001FFA80F80FD8904503F1010306D3FB8AA7 +:102690000A4462F30903FB8201201AE01AF8006081 +:1026A000E6540130EAE79045F1D2A1F1050B1C2375 +:1026B0007C68BBFBF3F203FB12BB1FFA8BF6002C0A +:1026C00045D14846FFF72AFF044638B978606FF0D5 +:1026D0000200BDE8F88F4FF00008E6E7002606602C +:1026E0007860ADB24FF0000B454510D90AEB0803F6 +:1026F000221D13F8011B9155B1B208F101081B29E5 +:102700001FFA88F82BD0454506F10106F1D8FB8A5F +:10271000C3F30902154465F30903BCE7013292B221 +:102720001C462368002BF9D16B1F0B441C21B3FB03 +:10273000F1F301339BB29A42D3D2BBF1000FD0D157 +:102740004846FFF7EBFE20B9C4F800B0BFE701220E +:10275000E7E7C0F800B05E4620600446C1E74545A3 +:10276000D5D94846FFF7DAFE08B92060AFE7C0F8D0 +:1027700000B0002620600446B6E700002DE9F04FC7 +:102780002DED028B1C4683B05B690192074688469B +:10279000002B00F09A80238C2BB1E269002A00F014 +:1027A0009480072B35D807F10C00FFF7B7FE0546DC +:1027B00038B96FF00205284603B0BDEC028BBDE8C6 +:1027C000F08F14220021FEF723FC228CE16905F131 +:1027D0000800FEF70BFC208C013080B2FFF7E6FE0C +:1027E000FFF7C8FE013880B2208401302874636985 +:1027F000228C1B782A4403F01F0363F03F0348F048 +:1028000000411372384669602946FFF7EFFD012544 +:10281000D1E700F10C034FF0000908EE103A4FF039 +:10282000800A4E464D4618EE100AFFF777FE8346A3 +:102830000028BED014220021FEF7EAFB002E3AD178 +:10284000019BABF8083002220BF1080E1FFA82FC44 +:102850000CF10100BCF1060F218C80B201D88E4230 +:102860002BD3FFF7A3FEFFF785FE626912780138CC +:1028700002F01F028E4208BF4FF0400A42EA49129E +:102880001BFA80F14AEA020A013048F0004281F85E +:1028900008A08BF81000CBF8042059463846FFF703 +:1028A000A5FD238C0135B3422DB289F001094FF00B +:1028B000000AB8D17FE70022C6E7E169895D0EF81A +:1028C00002100136B6B20132C0E76FF0010572E7BF +:1028D000F8B515460E463022002104461F46FEF785 +:1028E00097FB069B6360B5F5001F079BA76034BF8D +:1028F0006A094FF6FF72A36297B2E66104F1100015 +:1029000000239A4206D800230360A782E382238330 +:10291000E360F8BD0660013330462036F1E7000081 +:1029200003781BB94BB2002BC8BF01707047000081 +:1029300000787047F8B50C46C969074611B9238C71 +:10294000002B37D1257E1F2D34D8387828BB228C18 +:10295000072A2CD8268A36F003032BD14FF6FF70B6 +:10296000FFF7D0FD20F001003102400441EA05618B +:10297000400C41EA40254FF6FF722346294638466F +:10298000FFF7FCFE002807DD626913780133DBB234 +:102990001F2B88BF00231370F8BD218A2D0645EA3E +:1029A000012505432046FFF71DFE0246E5E76FF0CF +:1029B0000300F1E76FF00100EEE7000070B58AB0A8 +:1029C000044616460021282268461D46FEF720FBD5 +:1029D000BDF83830ADF810300F9B05939DF84030AE +:1029E0008DF81830119B07936946BDF84830ADF853 +:1029F00020302046CDE90265FFF79CFF0AB070BD8C +:102A00002DE9F041D36905460C4616460BB9138CE7 +:102A10005BBB377E1F2F28D895F80080B8F1000FD8 +:102A200026D03046FFF7DEFD3378210241EAC3317C +:102A300041EA0801338A41EA076141EA034102465B +:102A4000334641F080012846FFF798FE00280ADD52 +:102A50003378012B07D1726913780133DBB21F2B56 +:102A600088BF00231370BDE8F0816FF00100FAE722 +:102A70006FF00300F7E70000F0B58BB004460D4699 +:102A800017460021282268461E46FEF7C1FA9DF827 +:102A90004C305A1E534253418DF800309DF840305F +:102AA000ADF81030119B05939DF848308DF8183023 +:102AB000149B07936A46BDF85430ADF82030294680 +:102AC0002046CDE90276FFF79BFF0BB0F0BD00007A +:102AD000406A00B104307047436A1A684262026972 +:102AE0001A600361C38A013BC38270472DE9F0413C +:102AF000D0F82080194E14461D464146002709B9DA +:102B0000BDE8F081D1E90223A21A65EB03039642E6 +:102B100077EB03031ED2036A8B420DD1FFF78CFDC6 +:102B2000036A1B68036203690B60C38A0161016A5F +:102B3000013BC3828846E2E7FFF77EFD0B68C8F8D9 +:102B4000003003690B60C38A0161013BC382D8F87E +:102B50000010D4E788460968D1E700BF80841E00D2 +:102B60002DE9F04F8BB00D46DDF8509014469B4692 +:102B70008046002800F01981B9F1000F00F015819E +:102B8000531E3F2B00F21181012A03D1BBF1000F2C +:102B900040F00B810023CDE90833B8F81430B5EBD1 +:102BA000C30F4FEAC30703D300200BB0BDE8F08F7B +:102BB0002B199F42D8F80C303ABF7F1BFFB2274633 +:102BC0001BB9D8F81030002B7AD0272D4ED8C5F17C +:102BD0002806B7424FF000032CBFF6B23E460093E2 +:102BE0002946D8F8080008AB3246FFF741FCA7EBAE +:102BF000060A35445FFA8AFAB8F8143003F1005334 +:102C0000053BDB000493D8F80C3003932821039B89 +:102C100013B1BAF1000F2CD1D8F8100040B1BAF1BD +:102C2000000F05D0009608AB5246691AFFF720FC4A +:102C300038B2002FB8D066070AD00AAB03EBD40134 +:102C4000624211F8083C02F00702134101F8083C07 +:102C5000082C3CD9102C40F2B580202C40F2B780D3 +:102C6000BBF1000F00F09C80082334E0BA46002638 +:102C7000C2E7049BE02B28BFE02306930B44AB4242 +:102C8000059314D95A1B03980096924534BF5246B7 +:102C9000D2B2691A08AB04300792FFF7E9FB079A32 +:102CA0001644AAEB020A1544F6B25FFA8AFA049BAC +:102CB000069A05999B1A0493039B1B680393A6E746 +:102CC0000093D8F8080008AB3A462946AEE7BBF1B6 +:102CD000000F13D00123B4EBC30F6CD0082C12D813 +:102CE0009DF82030621E23FA02F2D50706D54FF078 +:102CF000FF3202FA04F423438DF820309DF820308F +:102D000089F8003051E7102C12D8BDF82030621E2F +:102D100023FA02F2D10706D54FF0FF3202FA04F48B +:102D20002343ADF82030BDF82030A9F800303CE74F +:102D3000202C0FD80899631E21FA03F3DA0705D572 +:102D40004FF0FF3202FA04F40C430894089BC9F8D0 +:102D500000302AE7402C2BD0DDE90865611EC4F164 +:102D60002102A4F1210326FA01F105FA02F225FA63 +:102D700003F311431943CB0712D50122A4F1200319 +:102D8000C4F1200102FA03F322FA01F1A2405242F7 +:102D900043EA010363EB430332432B43CDE90823AA +:102DA000DDE90823C9E90023FFE66FF00100FCE636 +:102DB0006FF00800F9E6082CA0D9102CB3D9202C0C +:102DC000EED8C3E7BBF1000FADD0022383E7BBF120 +:102DD000000FBBD004237EE730B5012A144638BF6C +:102DE0000124402C85B028BF40240025012ACDE9CC +:102DF000025518D81B788DF8083063070AD004AB49 +:102E000003EBD405624215F8083C02F00702934038 +:102E100005F8083C009103462246002102A8FFF76E +:102E200027FB05B030BD082AE4D9102A03D81B8837 +:102E3000ADF80830E1E7202A8DBFD3E900231B68F5 +:102E40000293CDE90223D8E710B5CB681BB98B609C +:102E50000B618B8210BD04691A681C600361C38A10 +:102E6000013BC382CA60F0E703064CBFC0F3C03029 +:102E70000220704708B50246FFF7F6FF022806D188 +:102E80005306C2F30F2001D100F0030008BDC2F3C6 +:102E90000740FBE72DE9F04F93B0CDE903230A6823 +:102EA00004461046FFF7E0FF022814BFC2F30626CF +:102EB0000026002A0D46824680F2F28112F0C049B7 +:102EC00040F0EE81097B002900F0EA81022803D05E +:102ED0002378B34240F0E781C2F3046306931046BF +:102EE00002F07F030593FFF7C5FF059B29444FEAD6 +:102EF000834848EA0A4848EA4668CE780023002218 +:102F0000CDE90823F309834648EA0008029367D015 +:102F1000059B009302466768534608A92046B847B8 +:102F2000002800F0C381276A4FB9414604F10C0024 +:102F3000FFF702FB074690B96FF0020054E03B69CF +:102F400098450DD03F68002FF9D1414604F10C009F +:102F5000FFF7F2FA07460028EED0236A3B602762AB +:102F600097F817C006F01F08CCF3840CACEB0800F0 +:102F70001FFA80FE0028B8BF0EF12000A8EB0C035A +:102F80001FFA83FED7E90221B8BF00B2002B0793D6 +:102F9000BEBF0EF120031BB2079352EA010338D0E3 +:102FA000039BDFF824E39A1A049B4FF0000C63EBB9 +:102FB000010196457CEB01032BD36B7B97F81AE05C +:102FC000734519D1029B002B78D0012821DC786849 +:102FD000F8B9DFF8F0C2944570EB010316D337E07F +:102FE000276A27B96FF00C0013B0BDE8F08F3B697A +:102FF0009845B5D03F68F4E7B24890427CEB0103B6 +:1030000001D30020F0E7029B002BFAD0079B0F2B87 +:1030100017DCFA7DB30002F0030203F07C031343D4 +:10302000FB7539462046FFF707FB6B7BBB76029B9F +:103030003BB9FB7DC3F38402013262F38603FB7567 +:10304000D0E76A7BBB7E9A42DBD1029B002B35D056 +:10305000B309022B32D0039BBB60049BFB6014229C +:1030600000210DA8FDF7D4FF039B0A93049B0B934B +:103070002B1D0C932B7BADF83EB0013BDBB2ADF8C2 +:103080003C30069B8DF84230059B8DF8433094F818 +:103090002C308DF840A083F001038DF844308DF87A +:1030A0004180A3680AA920469847FB7DC3F38403A7 +:1030B000013303F01F039B02FB82A2E7FB7DC6F3F3 +:1030C0004012B2EBD31F40F0F480C3F384034345B6 +:1030D00040F0F280029A2B7BB609002A4DD0F2070D +:1030E0005DD4032B40F2EB80039BBB60049BFB6031 +:1030F0002B7BAE1D033BDBB23246394604F10C009C +:10310000FFF7ACFA00280CDA39462046FFF794FAAC +:10311000FB7DC3F38403013303F01F039B02FB8297 +:103120000AE7DDE90884AB883B834FF6FF73C9F1FA +:103130002000A9F1200228FA09F104FA00F0014365 +:1031400024FA02F211431846C9B2FFF7C9F909F18E +:103150000809B9F1400F0346E9D1B8822A7B033A46 +:10316000D2B23146FFF7CEF9FB7DB882DA43C2F323 +:10317000C01262F3C713FB7543E786B92E1D013BEE +:10318000DBB23246394604F10C00FFF767FA00283B +:10319000BADB2A7BB88A013AD2B23146E2E7F98A31 +:1031A000C1F30901013B0429DAB25BD8281D0023D1 +:1031B00007F11B069A4208D910F801CB06F801C0A6 +:1031C000013101330529DBB2F4D103990A91049945 +:1031D0000B91934207F11B010C9138BF04337968BE +:1031E0000D9134BF55FA83F300230E93FB8AADF89B +:1031F0003EB0C3F309031A44069B8DF84230059B89 +:103200008DF8433094F82C30ADF83C2083F0010366 +:103210008DF8443000238DF840A08DF841807B600C +:103220002A7BB88A013A291DFFF76CF93B8BB882DB +:10323000834203D1A3680AA92046984720460AA9D9 +:10324000FFF702FEFB7DBA8AC3F38403013303F068 +:103250001F039B02FB823B8B9A420CBF00206FF046 +:103260001000C1E67B68002BAFD0052001E01C30C8 +:1032700033461E68002EFAD1091A081D2E1D184467 +:1032800001EB090CBCF11B0F5FFA89F39DD89A4240 +:103290009BD916F8013B00F8013B09F10109EFE762 +:1032A0006FF00900A0E66FF00A009DE66FF00B00DA +:1032B0009AE66FF00D0097E66FF00E0094E66FF05F +:1032C0000F0091E640420F0080841E00EFF3098357 +:1032D00005494A6B22F001024A63683383F3098887 +:1032E000002383F31188704700EF00E0302080F363 +:1032F000118862B60C4B0D4AD96821F4E0610904CB +:10330000090C0A43DA60D3F8FC20094942F08072C4 +:10331000C3F8FC200A6842F001020A602022DA7732 +:1033200083F82200704700BF00ED00E00003FA05BB +:10333000001000E010B5302383F311880E4B5B685A +:1033400013F4006314D0F1EE103AEFF30984683CF3 +:103350004FF08073E361094BDB6B236684F30988CC +:1033600000F0A4F810B1064BA36110BD054BFBE7BC +:1033700083F31188F9E700BF00ED00E000EF00E003 +:10338000FF020008020300084FF0E0230022586803 +:103390004FF0FF31930003F1604303F561430132C5 +:1033A0009042C3F88010C3F88011F3D27047000038 +:1033B00000F1604303F561430901C9B283F80013CA +:1033C000012200F01F039A4043099B0003F1604370 +:1033D00003F56143C3F880211A6070470023037529 +:1033E000826803691B6899689142FBD25A6803603E +:1033F000426010605860704700230375826803695B +:103400001B6899689142FBD85A680360426010605B +:103410005860704708B50846302383F311880B7D48 +:10342000032B05D0042B0DD02BB983F3118808BDD5 +:103430008B6900221A604FF0FF338361FFF7CEFFE4 +:103440000023F2E7D1E9003213605A60F3E700008D +:10345000FFF7C4BF054BD9680875186802681A6081 +:10346000536001220275D860FCF734BF2838002071 +:1034700030B50C4BDD684B1C87B004460FD02B4693 +:10348000094A684600F02AF92046FFF7E3FF009B4F +:1034900013B1684600F02CF9A86907B030BDFFF7FA +:1034A000D9FFF9E72838002015340008044B1A68C2 +:1034B000DB6890689B68984294BF002001207047A9 +:1034C00028380020084B10B51C68D86822681A609C +:1034D000536001222275DC60FFF78EFF0146204613 +:1034E000BDE81040FCF7F6BE2838002038B5074C80 +:1034F00007490848012300252370656000F0EEFBB2 +:103500000223237085F3118838BD00BF503A002094 +:10351000944400082838002008B572B6044B18659A +:1035200000F0ACFA00F05CFB024B03221A70FEE7DD +:1035300028380020503A002000F010B98B60022398 +:1035400008618B82084670478368A3F1840243F8C0 +:10355000142C026943F8442C426943F8402C094A70 +:1035600043F8242CC26843F8182C022203F80C2CD0 +:10357000002203F80B2C044A43F8102CA3F120007E +:10358000704700BFED0200082838002008B5FFF79B +:10359000DBFFBDE80840FFF75BBF0000024BDB68C4 +:1035A00098610F20FFF756BF28380020302383F39F +:1035B0001188FFF7F3BF000008B50146302383F3FD +:1035C00011880820FFF754FF002383F3118808BDFA +:1035D00010B503689C68A2420CD85C688A600B60D6 +:1035E0004C602160596099688A1A9A604FF0FF33E5 +:1035F000836010BD1B68121BECE700000A2938BF6E +:103600000A2170B504460D460A26601900F060FBD9 +:1036100000F04CFB041BA54203D8751C2E46044643 +:10362000F3E70A2E04D9BDE87040012000F096BBF4 +:1036300070BD0000F8B5144B0D46D96103F11001BF +:1036400041600A2A1969826038BF0A220160486015 +:103650001861A818144600F02DFB0A2700F026FB7D +:10366000431BA342064606D37C1C281900F030FBFE +:1036700027463546F2E70A2F04D9BDE8F840012075 +:1036800000F06CBBF8BD00BF28380020F8B5064636 +:103690000D4600F00BFB0F4A134653F8107F9F4274 +:1036A00006D12A4601463046BDE8F840FFF7C2BFC2 +:1036B000D169BB68441A2C1928BF2C46A34202D9F1 +:1036C0002946FFF79BFF224631460348BDE8F840F4 +:1036D000FFF77EBF283800203838002010B4C0E93A +:1036E000032300235DF8044B4361FFF7CFBF0000C5 +:1036F00010B5194C236998420DD0D0E90032816889 +:1037000013605A609A680A449A60002303604FF07D +:10371000FF33A36110BD2346026843F8102F5360A6 +:103720000022026022699A4203D1BDE8104000F0F5 +:10373000C9BA936881680B44936000F0B7FA2269B4 +:10374000E1699268441AA242E4D91144BDE81040EC +:10375000091AFFF753BF00BF283800202DE9F047B2 +:10376000DFF8BC8008F110072C4ED8F8105000F09C +:103770009DFAD8F81C40AA68031B9A423ED814440C +:10378000D5E900324FF00009C8F81C4013605A60B8 +:10379000C5F80090D8F81030B34201D100F092FA89 +:1037A00089F31188D5E9033128469847302383F3FC +:1037B00011886B69002BD8D000F078FA6A69A0EB09 +:1037C00004094A4582460DD2022000F0C7FA0022C1 +:1037D000D8F81030B34208D151462846BDE8F0472A +:1037E000FFF728BF121A2244F2E712EB090938BF8B +:1037F0004A4629463846FFF7EBFEB5E7D8F81030C1 +:10380000B34208D01444211AC8F81C00A960BDE8CE +:10381000F047FFF7F3BEBDE8F08700BF383800205F +:103820002838002038B500F041FA054AD2E90845A9 +:10383000031B181945F10001C2E9080138BD00BF9A +:103840002838002000207047FEE700007047000085 +:103850004FF0FF3070470000BFF34F8F024A1369EB +:10386000DB03FCD4704700BF0020024008B5094BC1 +:103870001B7873B9FFF7F0FF074B5A69002ABFBFE7 +:10388000064A9A6002F188329A601A6822F48062CD +:103890001A6008BD683A00200020024023016745F5 +:1038A00008B50B4B1B7893B9FFF7D6FF094B5A6944 +:1038B00042F000425A611A6842F480521A601A6853 +:1038C00022F480521A601A6842F480621A6008BDBD +:1038D000683A0020002002407F289ABF00F580301F +:1038E000C0020020704700004FF4006070470000E5 +:1038F000802070477F2808B50BD8FFF7EDFF00F553 +:1039000000630268013204D104308342F9D10120FE +:1039100008BD0020FCE700007F2810B504461FD832 +:10392000FFF79AFFFFF7A2FF0E4BF3221A61022264 +:103930005A615A6942EAC0025A615A6942F48032B5 +:103940005A61FFF789FF4FF40061FFF7C5FF00F0F0 +:1039500043F9FFF7A5FF2046BDE81040FFF7CABFB7 +:10396000002010BD002002402DE9F84340EA020388 +:1039700013F00703144606D0304B40F241321A6070 +:103980000020BDE8F88385182D4A95420CD92B4AB2 +:1039900040F246311160F3E7031D1B684A68934209 +:1039A00008D1083C08300831072C14D902680B688C +:1039B0009A42F1D0FFF75AFFFFF74EFF214E083130 +:1039C0004FF001084FF00009012CA1F1080706D8BB +:1039D000FFF766FF01E0002CECD10120D1E7C6F82B +:1039E0001480054651F8083C45F8043B51F8043C66 +:1039F0004360FFF731FF336943F001033361C6F8D9 +:103A00001490026851F8083C9A420CD00B4B40F2DB +:103A10006E321A600C4B18600C4B1C600C4B1F6014 +:103A2000FFF73EFFACE72D6851F8043C9D4201F1E1 +:103A30000801EBD1083C0830C6E700BF643A00201B +:103A40000000040800200240583A0020603A00209C +:103A50005C3A0020084908B50B7828B11BB9FFF77C +:103A600005FF01230B7008BD002BFCD0BDE808400A +:103A70000870FFF715BF00BF683A002002484FF4F6 +:103A80007F4100F0ABB800BF00010020084611469E +:103A900000F00ABC012000F007BC0000084600F05E +:103AA00021BC000038B5EFF311859DB9EFF3058413 +:103AB000C4F30804302334B183F31188FFF7B2FE56 +:103AC00085F3118838BD83F31188FFF7ABFE84F3CB +:103AD000118838BDBDE83840FFF7A4BE38B5FFF700 +:103AE000E1FF114C114AC00840EA4170A0FB025EA0 +:103AF000C908A0FB040C1CEB050CA1FB04404FF013 +:103B000000035B41A1FB02121CEB040C43EB000021 +:103B100011EB0E0142F10002411842F100000909C7 +:103B200041EA007038BD00BFCFF753E3A59BC42026 +:103B300010B50244064BD2B2904200D110BD441CD5 +:103B400000B253F8200041F8040BE0B2F4E700BFE4 +:103B500050280040114B30B5D3F89040240409D4CC +:103B6000D3F89040C3F89040D3F8904044F4004418 +:103B7000C3F890400A4C236843F4807323600244E6 +:103B8000084BD2B2904200D130BD441C00B251F873 +:103B9000045B43F82050E0B2F4E700BF001002409D +:103BA000007000405028004007B5012201A9002004 +:103BB000FFF7BEFF019803B05DF804FB13B50446A0 +:103BC000FFF7F2FFA04205D0012201A900200194D5 +:103BD000FFF7C0FF02B010BD704700007047000043 +:103BE00070470000074B45F255521A6002225A6096 +:103BF00040F6FF729A604CF6CC421A60024B0122EA +:103C00001A70704700300040703A0020034B1B7858 +:103C10001BB1034B4AF6AA221A607047703A002083 +:103C200000300040054B1A6832B902F1804202F5BB +:103C30000432D2F894201A60704700BF6C3A00201A +:103C4000024B4FF40002C3F894207047001002406A +:103C500008B5FFF7E7FF024B1868C0F3407008BDD6 +:103C60006C3A002070470000FEE700000A4B0B484A +:103C70000B4A90420BD30B4BDA1C121AC11E22F0D6 +:103C800003028B4238BF00220021FDF7C1B953F86F +:103C9000041B40F8041BECE72C450008FC3A00200C +:103CA000FC3A0020FC3A002000F0BEB84FF0804300 +:103CB000586A70474FF08043002258631A6102220D +:103CC000DA6070474FF080430022DA6070470000EE +:103CD0004FF0804358637047FEE7000070B51B4B00 +:103CE00001630025044686B0586085620E46FFF7E2 +:103CF000FDFA04F11003C4E904334FF0FF33C4E9C3 +:103D00000635C4E90044A560E562FFF7CFFF2B4606 +:103D10000246C4E9082304F134010D4A25658023D5 +:103D20002046FFF70BFC0123E0600A4A037500926E +:103D300072680192B268CDE90223074B6846CDE96B +:103D40000435FFF723FC06B070BD00BF503A0020D9 +:103D5000A0440008A5440008D93C0008024AD36AE0 +:103D60001843D062704700BF28380020244B2548F4 +:103D7000DA6A42F0070210B4DA62DA6A224C22F000 +:103D80000702DA62DA6ADA6C42F00702DA64DA6EA3 +:103D900042F00702DA664FF09042DB6E4FF0AA3134 +:103DA000002353609160D0604FF6FF705061136242 +:103DB000536214601024C2F80434C2F80814C2F824 +:103DC0000C444FF6F774C2F814449924C2F8203416 +:103DD000C2F824440D4CC2F80044C2F80438C2F8BA +:103DE0000818C2F80C38C2F81408C2F82038C2F813 +:103DF0002438C2F800385DF8044B00F055B800BF15 +:103E000000100240000100240001002850000A00B8 +:103E100008B500F005FAFFF769FBBDE80840FFF7B9 +:103E200001BF0000704700000F4B9A6D42F0010285 +:103E30009A659A6F42F001029A670C4A9B6F9368E9 +:103E400043F0010393604FF080434F229A624FF09A +:103E5000FF32DA6200229A615A63DA605A60012204 +:103E60005A611A60704700BF00100240002004E051 +:103E70004FF0804208B51169D3680B40D9B2C943ED +:103E80009B07116107D5302383F31188FFF754FB9B +:103E9000002383F3118808BD08B5FFF775FABDE864 +:103EA000084000F099B900005A4B4FF0FF319A6A70 +:103EB00099629A6A00229A62986AD86A60F007004A +:103EC000D862D86A00F00700D862D86A186B196304 +:103ED000186B1A63186B986B9963986B9A63986B5D +:103EE000D86BD963D86BDA63D86B186C1964196C0A +:103EF0001A641A6C484A4FF4E06111601A6E47491F +:103F000042F001021A66D3F8802022F00102C3F8C1 +:103F10008020D3F880209A6D42F080529A659A6F83 +:103F200022F080529A679A6F4FF440720A604A6991 +:103F300012F48062FBD14A601A6822F0F00242F06B +:103F400060021A601A6842F001021A601A6891074A +:103F5000FCD500229A609A6812F00C02FBD1D3F8CB +:103F6000901011F4407F1EBF4FF48031C3F89010C1 +:103F7000C3F8902061221A601A689207FCD50022CB +:103F80009A609A6812F00C0FFBD169221A60D3F87C +:103F9000942022F4706242F4C062C3F894201A683C +:103FA00042F480321A601A689003FCD5D3F890204E +:103FB00022F00322C3F89020194ADA601A6842F00E +:103FC00080721A601A689101FCD5164A1A611A6843 +:103FD00042F080621A601A681201FCD500229A60D1 +:103FE0000D49114AC3F888200A6822F0070242F0FE +:103FF00004020A600A6802F00702042AFAD19A68E9 +:1040000042F003029A609A6802F00C020C2AFAD17C +:10401000704700BF001002400020024000700040C6 +:1040200003140001000C100055550134074A08B56F +:10403000536903F00103536123B1054A13680BB1BF +:1040400050689847BDE80840FFF774B90004014084 +:10405000743A0020074A08B5536903F0020353611C +:1040600023B1054A93680BB1D0689847BDE8084072 +:10407000FFF760B900040140743A0020074A08B510 +:10408000536903F00403536123B1054A13690BB16B +:1040900050699847BDE80840FFF74CB9000401405B +:1040A000743A0020074A08B5536903F008035361C6 +:1040B00023B1054A93690BB1D0699847BDE8084020 +:1040C000FFF738B900040140743A0020074A08B5E8 +:1040D000536903F01003536123B1054A136A0BB10E +:1040E000506A9847BDE80840FFF724B90004014032 +:1040F000743A0020164B10B55C6904F478725A616A +:10410000A30604D5134A936A0BB1D06A9847600698 +:1041100004D5104A136B0BB1506B9847210604D598 +:104120000C4A936B0BB1D06B9847E20504D5094A52 +:10413000136C0BB1506C9847A30504D5054A936CDA +:104140000BB1D06C9847BDE81040FFF7F3B800BF43 +:1041500000040140743A0020194B10B55C6904F466 +:104160007C425A61620504D5164A136D0BB1506D3D +:104170009847230504D5134A936D0BB1D06D98472A +:10418000E00404D50F4A136E0BB1506E9847A1049A +:1041900004D50C4A936E0BB1D06E9847620404D5D7 +:1041A000084A136F0BB1506F9847230404D5054A92 +:1041B000936F0BB1D06F9847BDE81040FFF7BAB8C6 +:1041C00000040140743A002008B5FFF751FEBDE835 +:1041D0000840FFF7AFB80000062108B50846FFF712 +:1041E000E7F806210720FFF7E3F806210820FFF78C +:1041F000DFF806210920FFF7DBF806210A20FFF788 +:10420000D7F806211720FFF7D3F806212820FFF75B +:10421000CFF8BDE8084007211C20FFF7C9B800000F +:1042200008B5FFF739FE00F007F8FFF7FBFDBDE822 +:104230000840FFF739BD00000023054A1946013345 +:10424000102BC2E9001102F10802F8D1704700BF3B +:10425000743A00200B460146184600F02DB80000C5 +:1042600000F040B8012838BF012010B504462046B0 +:1042700000F030F830B900F007F808B900F00CF899 +:104280008047F4E710BD0000024B1868BFF35B8F56 +:10429000704700BFF43A002008B5062000F084F80B +:1042A0000120FFF7D1FA0000024B0A4601461868C8 +:1042B000FFF7ECBB1811002010B5054C13462CB1CC +:1042C0000A4601460220AFF3008010BD2046FCE7FD +:1042D00000000000024B01461868FFF7DBBB00BF7F +:1042E00018110020024B01461868FFF7D7BB00BF2A +:1042F0001811002010B501390244904201D100206C +:1043000005E0037811F8014FA34201D0181B10BD3E +:104310000130F2E72DE9F041A3B1C91A1778014441 +:10432000044603F1FF3C8C42204601D9002009E0FD +:104330000578BD4204F10104F5D10CEB0405D61853 +:10434000A54201D1BDE8F08115F8018D16F801ED07 +:10435000F045F5D0E7E700001F2938B504460D46C3 +:1043600004D9162303604FF0FF3038BD426C12B100 +:1043700052F821304BB9204600F030F82A46014669 +:104380002046BDE8384000F017B8012B0AD0591C70 +:1043900003D1162303600120E7E7002442F82540FB +:1043A000284698470020E0E7024B01461868FFF7CF +:1043B000D3BF00BF1811002038B5074D00230446B5 +:1043C000084611462B60FFF743FA431C02D12B68C5 +:1043D00003B1236038BD00BFF83A0020FFF732BABE +:1043E000034611F8012B03F8012B002AF9D170477D +:1043F0006F72672E6172647570696C6F742E4D6197 +:1044000074656B4C3433312D41697273706565642A +:104410000000000040A2E4F1646891060041A3E5B9 +:10442000F2656992070000004261642043414E49F1 +:104430006661636520696E6465782E008000000007 +:10444000008000000000800000000000000000006C +:1044500001180008212000087D1F000841180008ED +:104460004D1800084D1A00081118000821180008FE +:10447000151800081D1800081918000871190008FF +:1044800025180008F1220008351800084519000811 +:10449000633000009044000880380020503A00202B +:1044A0006D61696E0069646C6500000000000000C9 +:1044B000260400000000000000600300000000006F +:1044C000FE2A0100D20400001C11002000000000A0 +:1044D00000000000000000000000000000000000DC +:1044E00000000000000000000000000000000000CC +:1044F00000000000000000000000000000000000BC +:1045000000000000000000000000000000000000AB +:10451000000000000000000000000000000000009B +:0C4520000000000000000000000000008F :00000001FF diff --git a/Tools/bootloaders/MatekL431-BattMon_bl.bin b/Tools/bootloaders/MatekL431-BattMon_bl.bin index f7b0d44adc7248..f4848018aea28e 100755 Binary files a/Tools/bootloaders/MatekL431-BattMon_bl.bin and b/Tools/bootloaders/MatekL431-BattMon_bl.bin differ diff --git a/Tools/bootloaders/MatekL431-DShot_bl.bin b/Tools/bootloaders/MatekL431-DShot_bl.bin index 7120c1086811fe..9c60044eeadc0f 100755 Binary files a/Tools/bootloaders/MatekL431-DShot_bl.bin and b/Tools/bootloaders/MatekL431-DShot_bl.bin differ diff --git a/Tools/bootloaders/MatekL431-EFI_bl.bin b/Tools/bootloaders/MatekL431-EFI_bl.bin index f68f10dc363bad..d6a79d5a2b424e 100755 Binary files a/Tools/bootloaders/MatekL431-EFI_bl.bin and b/Tools/bootloaders/MatekL431-EFI_bl.bin differ diff --git a/Tools/bootloaders/MatekL431-GPS_bl.bin b/Tools/bootloaders/MatekL431-GPS_bl.bin index 266291e731af4c..61041d64f69345 100755 Binary files a/Tools/bootloaders/MatekL431-GPS_bl.bin and b/Tools/bootloaders/MatekL431-GPS_bl.bin differ diff --git a/Tools/bootloaders/MatekL431-Periph_bl.bin b/Tools/bootloaders/MatekL431-Periph_bl.bin index c7798ec3909c68..67f6620fef0afe 100755 Binary files a/Tools/bootloaders/MatekL431-Periph_bl.bin and b/Tools/bootloaders/MatekL431-Periph_bl.bin differ diff --git a/Tools/bootloaders/MatekL431-Periph_bl.hex b/Tools/bootloaders/MatekL431-Periph_bl.hex index 9166fa5402b711..65523f87d58768 100644 --- a/Tools/bootloaders/MatekL431-Periph_bl.hex +++ b/Tools/bootloaders/MatekL431-Periph_bl.hex @@ -1,1160 +1,1109 @@ :020000040800F2 -:1000000000090020B5040008CD250008852500085A -:10001000AD25000885250008A5250008B7040008BF -:10002000B7040008B7040008B7040008C135000889 -:10003000B7040008B7040008B7040008B7040008B4 -:10004000B7040008B7040008B7040008B7040008A4 -:10005000B7040008B70400085D43000885430008A2 -:10006000AD430008D5430008FD430008B70400086D -:10007000B7040008B7040008B7040008B704000874 -:10008000B7040008B7040008B704000839250008C1 -:100090006525000875250008B704000825440008F8 -:1000A000B7040008B7040008B7040008B704000844 -:1000B000F9440008B7040008B7040008B7040008B2 -:1000C000B7040008B7040008B7040008B704000824 -:1000D000B7040008B7040008B7040008B704000814 -:1000E00089440008B7040008B7040008B7040008F2 -:1000F000B7040008B7040008B7040008B7040008F4 -:10010000B7040008B7040008B7040008B7040008E3 -:10011000B7040008B7040008B7040008B7040008D3 -:10012000B7040008B7040008B7040008B7040008C3 -:10013000B7040008B7040008B7040008B7040008B3 -:10014000B7040008B7040008B7040008B7040008A3 -:10015000B7040008B7040008B7040008B704000893 -:10016000B7040008B7040008B7040008B704000883 -:10017000B7040008B7040008B7040008B704000873 -:10018000B7040008B7040008B7040008B704000863 -:10019000B7040008B7040008B7040008B704000853 -:1001A0001112000800000000000000000000000024 -:1001B00053B94AB9002908BF00281CBF4FF0FF31CE -:1001C0004FF0FF3000F074B9ADF1080C6DE904CECA -:1001D00000F006F8DDF804E0DDE9022304B0704722 -:1001E0002DE9F047089D04468E46002B4DD18A42EA -:1001F000944669D9B2FA82F252B101FA02F3C2F11D -:10020000200120FA01F10CFA02FC41EA030E9440AD -:100210004FEA1C48210CBEFBF8F61FFA8CF708FBCE -:1002200016E341EA034306FB07F199420AD91CEBA6 -:10023000030306F1FF3080F01F81994240F21C81D8 -:10024000023E63445B1AA4B2B3FBF8F008FB103320 -:1002500044EA034400FB07F7A7420AD91CEB040455 -:1002600000F1FF3380F00A81A74240F20781644425 -:10027000023840EA0640E41B00261DB1D4400023AA -:10028000C5E900433146BDE8F0878B4209D9002D0E -:1002900000F0EF800026C5E9000130463146BDE898 -:1002A000F087B3FA83F6002E4AD18B4202D3824202 -:1002B00000F2F980841A61EB030301209E46002DB1 -:1002C000E0D0C5E9004EDDE702B9FFDEB2FA82F206 -:1002D000002A40F09280A1EB0C014FEA1C471FFA64 -:1002E0008CFE0126200CB1FBF7F307FB131140EA4B -:1002F00001410EFB03F0884208D91CEB010103F118 -:10030000FF3802D2884200F2CB804346091AA4B2D9 -:10031000B1FBF7F007FB101144EA01440EFB00FEAD -:10032000A64508D91CEB040400F1FF3102D2A64512 -:1003300000F2BB800846A4EB0E0440EA03409CE7B1 -:10034000C6F12007B34022FA07FC4CEA030C20FA5E -:1003500007F401FA06F31C43F9404FEA1C4900FA7E -:1003600006F3B1FBF9F8200C1FFA8CFE09FB1811FB -:1003700040EA014108FB0EF0884202FA06F20BD96E -:100380001CEB010108F1FF3A80F08880884240F2BE -:100390008580A8F102086144091AA4B2B1FBF9F002 -:1003A00009FB101144EA014100FB0EFE8E4508D9FD -:1003B0001CEB010100F1FF346CD28E456AD9023882 -:1003C000614440EA0840A0FB0294A1EB0E01A14267 -:1003D000C846A64656D353D05DB1B3EB080261EBD5 -:1003E0000E0101FA07F722FA06F3F1401F43C5E9AF -:1003F000007100263146BDE8F087C2F12003D840E5 -:100400000CFA02FC21FA03F3914001434FEA1C4726 -:100410001FFA8CFEB3FBF7F007FB10360B0C43EA18 -:10042000064300FB0EF69E4204FA02F408D91CEBC8 -:10043000030300F1FF382FD29E422DD902386344C6 -:100440009B1B89B2B3FBF7F607FB163341EA034166 -:1004500006FB0EF38B4208D91CEB010106F1FF38B5 -:1004600016D28B4214D9023E6144C91A46EA0046AC -:1004700038E72E46284605E70646E3E61846F8E63E -:100480004B45A9D2B9EB020864EB0C0E0138A3E787 -:100490004646EAE7204694E74046D1E7D0467BE768 -:1004A000023B614432E7304609E76444023842E7E0 -:1004B000704700BF02E000F000F8FEE772B6374870 -:1004C00080F30888364880F3098836483649086042 -:1004D00040F20000CCF200004EF63471CEF2000182 -:1004E0000860BFF34F8FBFF36F8F40F20000C0F280 -:1004F000F0004EF68851CEF200010860BFF34F8F36 -:10050000BFF36F8F4FF00000E1EE100A4EF63C7122 -:10051000CEF200010860062080F31488BFF36F8FCD -:1005200003F038FD03F0BAFD4FF055301F491B4A68 -:1005300091423CBF41F8040BFAE71D49184A914229 -:100540003CBF41F8040BFAE71A491B4A1B4B9A427D -:100550003EBF51F8040B42F8040BF8E7002018499D -:10056000184A91423CBF41F8040BFAE703F016FD2C -:1005700003F0E6FD144C154DAC4203DA54F8041BAD -:100580008847F9E700F042F8114C124DAC4203DA0B -:1005900054F8041B8847F9E703F0FEBC000900206B -:1005A000001100200000000808ED00E0000100201C -:1005B00000090020E0470008001100207C11002005 -:1005C00080110020003B0020A0010008A4010008C9 -:1005D000A4010008A40100082DE9F04F2DED108AB8 -:1005E000C1F80CD0C3689D46BDEC108ABDE8F08F01 -:1005F000002383F311882846A047002003F076F9F2 -:10060000FEE703F0D9F800DFFEE70000F8B500F0E0 -:1006100011FE03F061FC074603F0B2FC0546D0BBB7 -:10062000294B9F4237D001339F4237D0274B27F0C9 -:10063000FF029A4235D1F8B200F042FC2E4642F257 -:10064000107400F043FC08B10024264601F0ACF819 -:1006500058B3032000F03EF80024264635B11C4B69 -:100660009F4203D003F084FC00242646002003F0C0 -:100670003DFC0EB100F044F800F05AFC00F0DCFD47 -:1006800001F0ACFF0546B4B900F09AFC4FF47A7063 -:1006900003F032F9F7E72E460024D2E7044601269C -:1006A000CFE706464FF47A74CBE7002CD6D04FF450 -:1006B0007A740126D2E701F091FF431BA342E3D9EC -:1006C00000F01EF8DCE700BF010007B0000008B032 -:1006D000263A09B0084B187003280CD8DFE800F060 -:1006E00008050208022000F005BE022000F0F8BD57 -:1006F000024B00225A6070478011002084110020B4 -:1007000010B501F051F830B1234B03221A70234B7E -:1007100000225A6010BD224B224A1C461968013142 -:10072000F8D004339342F9D16268A242F2D31E4B4F -:100730009B6803F1006303F520439A42EAD203F079 -:10074000E9FB03F0FBFB002000F090FD0220FFF727 -:10075000C1FF164B9A6D00229A65996F9A67996F3F -:10076000D96DDA65D96FDA67D96F196E1A66D3F861 -:100770008010C3F88020D3F8803072B64FF0E023A9 -:100780003021C3F8084DD4E9003281F311889D4629 -:1007900083F308881047BDE78011002084110020F2 -:1007A00000A0000820A00008001100200010024056 -:1007B000094A136849F2690099B21B0C00FB013326 -:1007C0001360064B186844F2506182B2000C01FBC2 -:1007D0000200186080B27047141100201011002030 -:1007E00010B500211022044600F09EFD034B03CB00 -:1007F000206061601868A06010BD00BF9075FF1F89 -:100800002DE9F041ADF5507D0DF13C086EAC40F2A4 -:10081000751207460D4610A80021C8F8001000F018 -:1008200083FD4FF4C4720021204600F07DFD01F0ED -:10083000D5FE274B4FF47A72B0FBF2F0186093E8C4 -:100840000700022384E807000DF5ED702382FFF70F -:10085000C7FF42F204631F49238407A803F058FF2F -:100860001E2384F832310DF2EB2207AB0DF1340C6C -:100870001E4603CE664510605160334602F1080201 -:10088000F6D130681060B38893804146012220463B -:1008900000F096FD00230393AB7E029305F119034C -:1008A000019380B20123CDE904800093E97E06A381 -:1008B000D3E90023384602F059FA0DF5507DBDE822 -:1008C000F08100BFAFF300809E6AC421818A46EEAA -:1008D0008C110020204700082DE9F0412C4C237A90 -:1008E000DAB080460D465BBB27A9284600F078FEAB -:1008F0000746002842D19DF89D60C82E3ED801468B -:100900004FF4A662204600F00FFD4FF48073C4F848 -:10091000F8314FF40073C4F80C334FF44073C4F84B -:10092000203432460DF19E0104F1090000F0EAFC8A -:1009300026449DF89C30777223720BB9EB7E2372AC -:100940008122002106AC27A800F0EEFC01222146FE -:1009500027A800F081FE00230393AB7E029305F1EC -:10096000190380B201932823CDE904400093E97E66 -:1009700005A3D3E90023404602F0F8F95AB0BDE8D8 -:10098000F08100BFAFF3008026417272DF25D7B738 -:10099000A8320020F0B5254E4FF48A7505FB00659E -:1009A000F1B096F8D83085F8DC300024D822214602 -:1009B00085F8E8403AA800F0B7FC06F1090000F01D -:1009C000ABFCD5F8E4308DF8F000C2B206AF06F10A -:1009D00009010DF1F100CDE93A3400F093FC3946FC -:1009E00001223AA800F064FE80B2CDE90470082329 -:1009F0000127CDE9023706F1D80301933023009394 -:100A0000317A0B4807A3D3E9002302F0AFF9A042E3 -:100A100006DD01F0E3FDC5F8E000384671B0F0BD39 -:100A20002046FBE778F6339F93CACD8DA83200208D -:100A3000A42100202DE9F0411D4D1E4E1E4F86B011 -:100A4000284602F0BFF9034658B30024CDE9034419 -:100A5000ADF81440027B8DF8142099684068029428 -:100A600003AA03C21B68DFF8548043F000430293DB -:100A700001F0B6FD821941F10003009402A9384645 -:100A800001F078F8A04205DD284602F09FF988F8C9 -:100A90000040D5E798F80030072B05D8013388F8D7 -:100AA000003006B0BDE8F081014802F08FF9F8E7A8 -:100AB000A421002040420F00D8210020DD37002073 -:100AC00070B50D4614461E4602F0ACF850B9022E21 -:100AD00010D1012C0ED112A3D3E90023C5E90023C4 -:100AE000012007E0282C10D005D8012C09D0052CB6 -:100AF0000FD0002070BD302CFBD10BA3D3E9002315 -:100B0000ECE70BA3D3E90023E8E70BA3D3E9002329 -:100B1000E4E70BA3D3E90023E0E700BFAFF30080D5 -:100B2000401DA12026812A0B78F6339F93CACD8DD4 -:100B30009E6AC421818A46EE26417272DF25D7B7AC -:100B4000F017304A39059E5638B505460E4C00213F -:100B5000013500F0ADFBA4F82C55B4F82C0500F0DD -:100B60008FFB78B1B4F82C0500F09AFB014648B928 -:100B7000B4F82C0500F09CFBB4F82C350133A4F834 -:100B80002C35EAE738BD00BFA832002010B50A4B6B -:100B90000A4A1A6003F5805393F860203AB9DC6D75 -:100BA0002CB1204600F07EFE204603F0F1FCBDE8AB -:100BB0001040034800F076BED82100207C47000892 -:100BC000203200202DE9F04F8FB000AF05460C46D3 -:100BD00002F028F8002849D1237E022B1BD1E38A9A -:100BE000012B18D101F0FAFC0646FFF7E1FD0346A0 -:100BF0004FF4C870DFF8C482B3FBF0F206F5167646 -:100C000002FB103316FA83F3C8F80030E37E33B9E1 -:100C1000A34B00221A703C37BD46BDE8F08F07F1A8 -:100C20002401204600F09AFC0028F4D107F11400BA -:100C3000FFF7D6FD97F8264007F11401224607F189 -:100C4000270003F0EFFC0028E2D10F2C08D8944BCA -:100C50001C70D8F80030A3F51673C8F80030DAE736 -:100C600097F82410284601F0D5FFD4E7E38A282B13 -:100C70002BD010D8012B23D0052BCCD1BFF34F8F15 -:100C80008849894BCA6802F4E0621343CB60BFF322 -:100C90004F8F00BFFDE7302BBDD1844EE17E327A0D -:100CA0009142B8D1607E3146002291F8DC508542F5 -:100CB00000F0A5800132042A01F58A71F5D1AAE776 -:100CC00021462846FFF79CFDA5E721462846FFF769 -:100CD00003FEA0E7B2F8EC507B6005F103094FEA90 -:100CE00099094FEA8902D11DC908A8EBC1039D46A5 -:100CF000EB460021584600F017FB04F1EE012A46AE -:100D00003144584600F0FEFA7B6813B9012000F028 -:100D1000ADFA96F8D20000F0B3FA044630B930725A -:100D200000F0CEFA204600F0A1FAB1E0D6F8D420C7 -:100D30003AB996F8D200B6F82C25824201D8FFF7CE -:100D400003FFD6F8D4202A44944208D296F8D20061 -:100D5000B6F82C250130824201D8FFF7F5FE706805 -:100D60005FFA89F2594600F0E7FA08B9C54679E01A -:100D7000726896F8D2002A447260D6F8D42005EB47 -:100D80000209C6F8D49000F07BFA814509D396F8A1 -:100D9000D220D6F8D4000132001B86F8D220C6F843 -:100DA000D400FF2D0FD80024347200F089FA2046B9 -:100DB00000F05CFA00F0F8FC3D4B188108B9FFF731 -:100DC0009FFCC54627E7BB6896F8D9000AFB03627B -:100DD000FB68D2F8E41082F8E83001F58061C2F8CF -:100DE000E030C2F8E410FFF7D5FDFFF723FE96F8D8 -:100DF000D920013202F0030286F8D920B6E74FF479 -:100E00008A7A0AFB02F505F1EA013144204600F036 -:100E10007BFCF86000287FF4FEAE3544012285F8A3 -:100E2000E82001F0DBFBD5F8E020D6ED007ADFED1D -:100E3000216A801A192838BF192040F6B83290422A -:100E400028BF1046B8EE677A07EE900AF8EEE77A08 -:100E500067EEA67ADFED186AE7EE267AFCEEE77A0F -:100E6000C6ED007A96F8D930BB60BA6873680AFBA1 -:100E700002F4321992F8E81059B1D2F8E4108B421A -:100E8000E8463FF427AF002182F8E810C2F8E010EE -:100E9000C5467368064A9B0A01331381BBE600BF4F -:100EA0009D21002000ED00E00400FA05A83200209A -:100EB0008C110020CDCCCC3D6666663FA021002081 -:100EC000014B1870704700BF9811002038B54FF0E3 -:100ED0000054134B22689A4220D1124B627D124873 -:100EE0001A70237D03724FF48073C0F8F8314FF409 -:100EF0000073C0F80C3300254FF44073C0F8203461 -:100F00000A49C0F8E450C922093000F0FBF9E02298 -:100F10002946204600F008FA012038BD0020FCE7F1 -:100F20009AAD44C598110020A83200201600002078 -:100F300037B500F039FC194D1949288102230122E7 -:100F400018486B7101F0E8F900230193164B17491B -:100F500000931748174B4FF4805201F033FE164BA5 -:100F6000197811B1124801F055FE01F037FB044623 -:100F7000FFF71EFC4FF4C873B0FBF3F202FB130340 -:100F800004F5167010FA83F00C4B186002F0F8FFAD -:100F900008B10F232B8103B030BD00BF8C1100209E -:100FA00040420F00D8210020C10A00089C110020F7 -:100FB000A4210020C50B000898110020A0210020CA -:100FC0002DE9F04F2DED028B0FF23829D9E9008978 -:100FD000834C93B00BAE9FED7E8BFFF72BFD814FC3 -:100FE000DFF828A200230A93ADF834300B93736026 -:100FF0004FF0000B5B468DED008B01250DF11D02BE -:1010000007A938468DF81C508DF81DB001F034F951 -:101010009DF81C30002B40F0A580204601F002FE18 -:101020000646002845D1704F01F0D8FA3B68984237 -:101030003FD301F0D3FA8246FFF7BAFB4FF4C873EF -:10104000B0FBF3F202FB13030AF5167010FA83F0FB -:101050003860664F97F800B0CBF1100ABBF1000F73 -:1010600014BF33462B465FFA8AFA0EA88DF8283053 -:10107000FFF7B6FBBAF1060F28BF4FF0060A0EAB1A -:1010800003EB0B0152460DF1290000F03BF90AABCE -:101090000393182302930AF10102554BD2B2CDE912 -:1010A0000053049220464CA3D3E9002301F000FE34 -:1010B0003E7001F093FA4F4A4F4D1368C31AB3F5CF -:1010C0007A7F2ED3106001F08BFA02460B46204641 -:1010D00001F086FE204601F0A5FD10B32B7A474EA5 -:1010E000002B14BF03230223737101F077FA0EAFB4 -:1010F0004FF47A730122B0FBF3F03946306030468A -:1011000000F004FA182302933D4B019380B240F2A1 -:101110005513CDE90370009342464B46204601F03B -:10112000C7FD2B7A93B101F059FA002607464FF418 -:101130008A7A95F8D900304400F003000AFB005386 -:1011400093F8E82092B30136042EF2D1C82002F0C1 -:10115000D3FB2B7A002B7FF43DAF13B0BDEC028B99 -:10116000BDE8F08FDAF8143083F00803CAF81430C1 -:10117000594610220EA800F0D7F80DF11E0308AA58 -:101180000AA9384600F0F4FD96E803000FAB83E8A7 -:1011900003009DF834308DF844300A9B0E930EA95D -:1011A000DDE90823204601F0EFFF21E7D3F8E02036 -:1011B00042B12B68FA2B38BFFA23BA1A0533B2EBC7 -:1011C000430FC0D3FFF7E6FB0028BCD1BEE700BF4A -:1011D0000000000000000000401DA12026812A0B15 -:1011E000A4210020D8210020A02100209D21002042 -:1011F0009C210020D8370020A83200208C1100202C -:10120000DC370020F1C6A7C1D068080F00040048F1 -:1012100008B5054800F046FEBDE80840034A044909 -:10122000002003F0AFB900BFD821002018380020FB -:101230008D0B00087047000070B502F0E9FC094E04 -:10124000094D3080002428683388834208D902F091 -:10125000DBFC2B6804440133B4F5204F2B60F2D340 -:1012600070BD00BF0C380020E037002002F082BDC6 -:1012700000F10060920000F5204002F005BD000082 -:10128000054B1A68054B1B889B1A834202D91044F0 -:1012900002F0BABC00207047E03700200C38002074 -:1012A000024B1B68184402F0B5BC00BFE0370020B9 -:1012B000024B1B68184402F0BFBC00BFE03700209F -:1012C000064991F8243033B10023086A81F82430AC -:1012D0000822FFF7CDBF0120704700BFE437002090 -:1012E000022802BF024B4FF400229A61704700BFF0 -:1012F00000040048022802BF014B08229A6170478F -:101300000004004810B50023934203D0CC5CC454C1 -:101310000133F9E710BD000003460246D01A12F966 -:10132000011B0029FAD1704702440346934202D0C0 -:1013300003F8011BFAE770472DE9F8431F4D1446E7 -:1013400095F824200746884652BBDFF870909CB37E -:1013500095F824302BB92022FF2148462F62FFF751 -:10136000E3FF95F82400C0F10802A24228BF2246FC -:10137000D6B24146920005EB8000FFF7C3FF95F817 -:101380002430A41B1E44F6B2082E17449044E4B245 -:1013900085F82460DBD1FFF793FF0028D7D108E060 -:1013A0002B6A03EB82038342CFD0FFF789FF00282B -:1013B000CBD10020BDE8F8830120FBE7E437002013 -:1013C0002DE9F0470D46044600219046284640F29C -:1013D0007912FFF7A9FF234620220021284601F0B9 -:1013E00075FE231D02222021284601F06FFE631D99 -:1013F00003222221284601F069FEA31D0322252194 -:10140000284601F063FE04F1080310222821284633 -:1014100001F05CFE04F1100308223821284601F097 -:1014200055FE04F1110308224021284601F04EFE2A -:1014300004F1120308224821284601F047FE04F176 -:10144000140320225021284601F040FE04F1180325 -:1014500040227021284601F039FE04F120030822C1 -:10146000B021284601F032FE04F121030822B82100 -:10147000284601F02BFE04F12207C0263B463146E8 -:1014800008222846083601F021FEB6F5A07F07F1B4 -:101490000107F3D104F1320308223146284601F056 -:1014A00015FE002704F1330A94F832304FEAC709D9 -:1014B0009F4209F5A47615D3B8F1000F08D1314643 -:1014C00004F599730722284601F000FE09F24F1631 -:1014D000274694F832213B1B93420CD3F01DC008E1 -:1014E000BDE8F0870AEB070308223146284601F0E1 -:1014F000EDFD0137D8E707F23313314608222846BD -:1015000001F0E4FD08360137E3E7000013B50446B7 -:101510000846002101602346C0F8031020220190F4 -:1015200001F0D4FD0198231D0222202101F0CEFDFF -:101530000198631D0322222101F0C8FD0198A31D1B -:101540000322252101F0C2FD019804F108031022B5 -:10155000282101F0BBFD072002B010BDF7B5002324 -:10156000047F00910E4607221946054601F072FCE1 -:10157000731C0093012200230721284601F06AFC16 -:10158000C4B9B31C0093052223460821284601F064 -:1015900061FC0D243746B278BB1B934211D32B7FDD -:1015A000A88A0734E408BBB9844294BF0020012014 -:1015B00003B0F0BDAB8ADB00083BDB08B370082446 -:1015C000E8E7FB1C0093214600230822284601F08F -:1015D00041FC08340137DEE7201A18BF0120E7E795 -:1015E000F7B50023047F00910E46082219460546F0 -:1015F00001F030FC731CC4B9082200931146234645 -:10160000284601F027FC1024012372785F1C013B5F -:10161000934211D32B7FA88A0734E408BBB98442D4 -:1016200094BF0020012003B0F0BDAB8ADB00083B73 -:10163000DB0873700824E7E7F319009321460023C1 -:101640000822284601F006FC08343B46DDE7201A54 -:1016500018BF0120E7E70000F8B50E46054614461E -:10166000002181223046FFF75FFE2B460822002131 -:10167000304601F02BFD7CB96B1C07220821304657 -:1016800001F024FD0F2401236A785F1C013B934283 -:1016900004D3E01DC008F8BD0824F4E7EB19214687 -:1016A0000822304601F012FD08343B46ECE700000A -:1016B000F8B50E46054614460021CE223046FFF707 -:1016C00033FE2B4628220021304601F0FFFC7CB976 -:1016D00005F1080308222821304601F0F7FC3024E8 -:1016E0002F462A7A7B1B934204D3E01DC008F8BD25 -:1016F0002824F5E707F1090321460822304601F0C6 -:10170000E5FC08340137ECE7F7B5047F00910E469D -:10171000012310220021054601F09CFBC4B9B31C33 -:101720000093092223461021284601F093FB192437 -:1017300037467288BB1B9A4211D82B7FA88A073480 -:10174000E408BBB9844294BF0020012003B0F0BD7F -:10175000AB8ADB00103BDB0873801024E8E73B1DFD -:101760000093214600230822284601F073FB083429 -:101770000137DEE7201A18BF0120E7E730B5094D31 -:101780000A4491420DD011F8013B5840082340F320 -:101790000004013B2C4013F0FF0384EA5000F6D113 -:1017A000EFE730BD2083B8EDF7B5384A10685168CF -:1017B0006B4603C36A4636493648082302F042FFA7 -:1017C0000446002833D10A25334A106851686B4615 -:1017D00003C36A4631492F48082302F033FF044609 -:1017E000002849D00369B3F5583F45D8B0F86610D2 -:1017F00040F2264291423FD1294A024402F15C0163 -:101800008B4239D35C3B234900209E1AFFF7B6FF79 -:101810003246074604F164010020FFF7AFFFA368DA -:101820009F4229D1E368984208BF002524E003695C -:10183000B3F5583F27D8418B40F22642914220D140 -:10184000174A024402F110018B4218D3103B114990 -:1018500000209D1AFFF792FF2A46064604F1180160 -:101860000020FFF78BFFA3689E4202D1E3689842F5 -:1018700001D00D25A8E70025284603B0F0BD1025AE -:10188000A2E70C25A0E70B259EE700BF4047000814 -:10189000DC5F030000A0000849470008905F0300D8 -:1018A0000860FFF710B5037C044613B9006802F026 -:1018B000B1FE204610BD00000023BFF35B8FC36064 -:1018C000BFF35B8FBFF35B8F8360BFF35B8F7047AA -:1018D000BFF35B8F0068BFF35B8F704770B5054641 -:1018E0000C30FFF7F5FF05F1080604463046FFF718 -:1018F000EFFFA04206D930466D68FFF7E9FF2544A7 -:10190000281A70BD3046FFF7E3FF201AF9E7000000 -:1019100070B50546406898B105F10800FFF7D8FF9B -:1019200005F10C0604463046FFF7D2FF84423046EC -:1019300094BF6D680025FFF7CBFF013C2C44201AB3 -:1019400070BD000038B50C460546FFF7C7FFA04242 -:1019500010D305F10800FFF7BBFF04446868B4FB2F -:10196000F0F100FB1144BFF35B8F0120AC60BFF3CB -:101970005B8F38BD0020FCE72DE9F0411446074697 -:101980000D46FFF7C5FF844228BF0446D4B1B846D0 -:1019900058F80C6B4046FFF79BFF304428604046E8 -:1019A0007E68FFF795FF331A9C4203D86C600120D4 -:1019B000BDE8F0816B60A41B3B68AB602044E8602D -:1019C0000220F5E72046F3E738B50C460546FFF759 -:1019D0009FFFA04210D305F10C00FFF779FF0444EC -:1019E0006868B4FBF0F100FB1144BFF35B8F01208A -:1019F000EC60BFF35B8F38BD0020FCE72DE9FF41B1 -:101A0000884669460746FFF7B7FF6C4606B204EB07 -:101A1000C6060025B44209D06268206808EB0501BB -:101A2000FFF770FC636808341D44F3E72946384625 -:101A3000FFF7CAFF284604B0BDE8F081F8B50546B7 -:101A40000C300F46FFF744FF05F108060446304608 -:101A5000FFF73EFFA042304688BF6C68FFF738FFB3 -:101A6000201A386020B130462C68FFF731FF20443F -:101A7000F8BD000073B5144606460D46FFF72EFF6D -:101A8000844228BF04460190DCB101A93046FFF72B -:101A9000D5FF019B33B93268C5E90233C5E900249B -:101AA00001200CE09C4238BF0194286001986860D6 -:101AB0008442F5D93368AB60241AEC60022002B08E -:101AC00070BD2046FBE700002DE9FF410F46694647 -:101AD000FFF7D0FF6C4600B204EBC0050026AC4215 -:101AE00009D0D4F8048054F8081BB8194246FFF70F -:101AF00009FC4644F3E7304604B0BDE8F08100003D -:101B000038B50546FFF7E0FF044601462846FFF7D3 -:101B100019FF204638BD0000302383F3118862B6D8 -:101B200070470000002383F3118862B670470000FD -:101B300010B4026854681A4623465DF8044B1847EF -:101B40000120704700207047002070477047000058 -:101B5000002070470E20704700F5805090F8C800B4 -:101B6000C0F340007047000000F5805090F9C900B4 -:101B700070470000F7B50C68BDF8207014F00054F1 -:101B80001E466FD10B7B082B6CD8FFF7C5FF45694C -:101B9000AB685B010CD4AB681B0108D4AC6814F0D3 -:101BA00080545DD1FFF7BEFF204603B0F0BD012495 -:101BB0000B6804F1180C002BB8BFDB004FEA0C1CBB -:101BC000B4BF43F004035B0545F80C300B680FFA13 -:101BD00084FC13F0804F18BF05EB0C1E05EB0C1CAA -:101BE0001EBFDEF8803143F00203CEF880310B7B5C -:101BF000CCF8843105EB04158B68C5F88C314B6843 -:101C0000C5F88831DCF8803143F00103CCF880312D -:101C100000EB441541F268031D4403EB44130344F5 -:101C2000C5E9002608330D4601F10C0C55F804EB0C -:101C300043F804EB6545F9D184342D881D8000EB11 -:101C4000441407F00303257925F00B052B4323717A -:101C5000FFF768FF0097334600F0E2FC0120A4E79D -:101C60000224A5E74FF0FF309FE7000013B500F511 -:101C700080540191E06DFFF74BFE1F280AD90199AE -:101C8000E06D2022FFF7BAFEA0F120035842584130 -:101C900002B010BD0020FBE708B500F58050FFF74B -:101CA0003BFFC06DFFF708FEBDE80840FFF73ABFF5 -:101CB00000220260828142608260704710B500227B -:101CC0000023C0E900230023044603810C30FFF702 -:101CD000EFFF204610BD0000F0B5054600F580502E -:101CE0000C4690F8C83013F0040FC3F3800108BF0E -:101CF000114661F3820304F1840680F8C83005EBD5 -:101D0000461389B01B79D8072ED57AB319072DD47D -:101D10006846FFF7D3FF05EB441303F5835303F144 -:101D2000180703AA103318685968144603C4083307 -:101D3000BB422246F7D1186820609B88A380DDE96A -:101D40000E23CDE900230123ADF808302B68694646 -:101D5000DB6B2846984705EB46152B791A075CBFC5 -:101D600043F008032B7101E0002AF4D109B0F0BD63 -:101D70002DE9F047074688B007F5805468469A4633 -:101D80008846FFF7C9FE9146FFF798FFE06DFFF721 -:101D9000A5FD1F2829D9E06D20226946FFF7B0FE76 -:101DA000202822D103AD444605AB2E4603CE9E42E9 -:101DB00020606160354604F10804F6D13068206087 -:101DC000B388A380DDE90023C9E90023BDF808300A -:101DD000AAF80030FFF7A6FE4A4653464146384669 -:101DE00008B0BDE8F04700F009BCFFF79BFE0020FB -:101DF00008B0BDE8F08700002DE9F84F0023C0E9E6 -:101E00000133254B044640F8183B0F46FFF750FFBF -:101E100004F12800FFF752FF04F1480804F5825549 -:101E20004646083530462036FFF748FFAE42F9D126 -:101E300004F580554FF480534FF00009C5E913397C -:101E4000C5F848800123EE6504F5875804F58456EB -:101E5000C5F8549085F8583085F86030083608F198 -:101E600008084FF0000A4FF0000B46E908ABA6F156 -:101E70001800FFF71DFF203646F8289C4645F4D190 -:101E800085F8C97017B1054800F0A2FB044B6361E7 -:101E90002046BDE8F88F00BF7C4700085447000883 -:101EA0000064004010B5044B197804464A1C1A70AF -:101EB000FFF7A2FF204610BD143800202DE9F0479F -:101EC000002950D0294B2A4FB7FBF1F599428CBF1E -:101ED0000A231123581EB5FBF3FC03FB1C53C4B2A9 -:101EE0002BB102280346F5D80020BDE8F0870CF19D -:101EF000FF36B6F5806FF7D2C4EBC40E0EF10303C4 -:101F00004FEAE309C3F3C703A4EB030809F1010A8D -:101F10004FF47A755FFA88F009FB05555AFA88F88C -:101F2000B5FBF8F5B5F5617FC1BF0EF1FF33C3F323 -:101F3000C703E01AC0B25C1C50FA84F40CFB04F432 -:101F4000B7FBF4F4A142CFD1013BDBB20F2BCBD8CE -:101F50000138C0B20728C7D80021107116809170CF -:101F6000D3700120C1E70846BFE700BF3F420F0022 -:101F700000B4C40470B505460E464FF47A746B691C -:101F80005B6803F00103B34207D04FF47A7001F0AD -:101F9000B3FC013CF3D1204670BD0120FCE70000FA -:101FA00030B54269936913F0700F16D000230B4CC3 -:101FB000936103F1840200EB421211794D0709D5B8 -:101FC000890707D5416954F823508D60117941F094 -:101FD000040111710133032BEBD130BD68470008B8 -:101FE00073B51D46436916469A68D207044609D55B -:101FF0009A6801219960C2F34002CDE90065002191 -:10200000FFF76AFE63699A68D1050BD59A684FF4A9 -:1020100080719960C2F34022CDE90065012120461C -:10202000FFF75AFE63699A68D2030BD59A684FF49A -:1020300080319960C2F34042CDE90065022120461B -:10204000FFF74AFE204602B0BDE87040FFF7A8BF88 -:10205000F8B50446466900296CD106F10C073868CA -:1020600080076AD006EB01153868D5F8B00110F08A -:10207000040FD5F8B0011ABFC00840F00040400D71 -:10208000A061D5F8B0C11CF0020F1CBF40F0804029 -:10209000A061D5F8B40106EB011100F00F0084F83F -:1020A0002400D1F8B8012077D1F8B801000A607790 -:1020B000D1F8B801000CA077D1F8B801000EE07794 -:1020C000D1F8BC0184F82000D1F8BC01000A84F8E2 -:1020D0002100D1F8BC01000C84F82200D1F8BC1119 -:1020E000090E84F823103821396004F1340004F11A -:1020F000180104F1240551F8046B40F8046BA9425F -:10210000F9D109880180C4E90A23214600232386E6 -:1021100051F8283B2046DB6B984704F58052204657 -:1021200092F8C83043F0040382F8C830BDE8F840A4 -:10213000FFF736BF06F1100791E7F8BD10B504466A -:1021400000F04EFA02460B4652EA030102D0013A71 -:1021500063F100030449086820B12146BDE810403E -:10216000FFF776BF10BD00BF10380020F8B500F5AE -:1021700083511E46FFF7D0FCDFF844C0083100242D -:1021800004F1840500EB45152B795F070ED4DB06BF -:102190000CD5D1E900739742B34107D243695CF88B -:1021A00024709F602B7943F004032B710134032CBE -:1021B00001F12001E4D1BDE8F840FFF7B3BC00BF56 -:1021C0006847000808B5FFF7A7FCFFF7E9FEBDE880 -:1021D0000840FFF7A7BC0000F8B5436905469868BA -:1021E00000F0E050B0F1E05F0F461FD0E8B1FFF71C -:1021F00093FC05F583541034002606F1840305EBA7 -:1022000043131B791A0706D50136032E04F1200467 -:10221000F3D1012007E05B07F6D42146384600F0F1 -:1022200039FA0028F0D1FFF77DFCF8BD0120FCE76A -:1022300000F5805008B5FFF76FFCC06DFFF74EFB4F -:10224000FFF770FC43090CBF0120002008BD00000F -:10225000F8B51D46002313700F4606461446FFF7D7 -:10226000E7FF80F00100387025B129463046FFF7BE -:10227000B3FF2070F8BD00002DE9B8410C461546AB -:102280001F46804600F0ACF90B462178024609B99A -:10229000287850B14046FFF769FFFFF793FF3B46B0 -:1022A0002A462146FFF7D4FF0120BDE8B88100008F -:1022B00010B5FFF731FC174B9A6D42F000729A652A -:1022C0009A6B42F000729A639A6B00F5805422F088 -:1022D00000729A63FFF726FC94F8C830DB0718D425 -:1022E000B9B103211320FFF717FC01F0DBF903213B -:1022F000142001F0D7F90321152001F0D3F994F847 -:10230000C83043F0010384F8C830BDE81040FFF73F -:1023100009BC10BD001002402DE9F04700F58055C2 -:1023200088B095F8C930012B0446884616467FD8F8 -:10233000804F57F823200AB947F82300D7F800A0A8 -:10234000C4F80C802674BAF1000F63D095F8C93038 -:10235000012B6FD001212046FFF7AAFFFFF7DCFB1E -:102360006269136823F0020313606269136843F023 -:1023700001031360636900275F6101212046FFF7B5 -:10238000D1FBFFF7F7FD002800F09580E86DFFF71F -:1023900093FA04F58359BA4609F10809202200216D -:1023A0006846FEF7C1FF02A8FFF782FCCDF818A02F -:1023B0006A4609EB07030DF1180E9446BCE80300CA -:1023C000F44518605960624603F10803F5D1DCF862 -:1023D0000000186020379CF804201A71602FDDD1AE -:1023E00095F8C8306FF38203002785F8C8306A4635 -:1023F00041462046ADF80070ADF802708DF80470CB -:10240000FFF75CFD636948BB4FF400421A6008B0F7 -:10241000BDE8F08741F2D00002F0BCF8814610B16F -:102420005146FFF7E9FCC7F80090B9F1000F8DD1D4 -:102430000020ECE7386803681B6B984701460028CA -:1024400088D13868FFF734FF3868036832465B6824 -:102450004146984700287FF47DAFE9E761221A6082 -:102460009DF802309DF803201B06120402F470222E -:1024700003F040731343BDF80020C2F30902134375 -:102480009DF804201205022E02F4E0020CBF4FF06A -:1024900000410021134362690B43D3616369132236 -:1024A0005A616269136823F00103136039462046BC -:1024B000FFF760FD08B96369A6E795F8C93093BBDB -:1024C0006169D1F8002242F00102C1F8002261697D -:1024D000D1F8002222F47C5222F00E02C1F8002230 -:1024E0006169D1F8002242F46062C1F80022626999 -:1024F000C2F814326269C2F80432626941F6FF71AF -:10250000C2F80C126269C2F840326269C2F8443201 -:1025100063690122C3F81C226269D2F8003223F0F9 -:102520000103C2F8003295F8C83043F0020385F881 -:10253000C8306CE71038002008B500F051F850EAB8 -:102540000103024602D0421E61F10001044B1868EB -:1025500010B10B46FFF744FDBDE8084001F064B838 -:102560001038002008B50020FFF7E8FDBDE808405E -:1025700001F05AB808B50120FFF7E0FDBDE80840BA -:1025800001F052B800B59BB0EFF3098168226846AC -:10259000FEF7B8FEEFF30583014B9B6BFEE700BF30 -:1025A00000ED00E008B5FFF7EDFF000000B59BB0BF -:1025B000EFF3098168226846FEF7A4FEEFF3058376 -:1025C000014B5B6BFEE700BF00ED00E0FEE70000A3 -:1025D0000FB408B5029801F025F9FEE701F016BC2A -:1025E00001F0EEBB13B56C4684E80600031D94E8C9 -:1025F000030083E80500012002B010BD73B58568B3 -:10260000019155B11B885B0707D4D0E900369B6B5D -:102610009847019AC1B23046A847012002B070BD68 -:10262000F0B5866889B005460C465EB1BDF8383015 -:102630005B070AD4D0E900379B6B98472246C1B2AA -:102640003846B047012009B0F0BD00220023CDE993 -:1026500000230023ADF808300A4603AB01F1080659 -:10266000106851681C4603C40832B2422346F7D1B1 -:10267000106820609288A280FFF7B2FF0423ADF8B3 -:1026800008302B68CDE90001DB6B69462846984786 -:10269000D8E7000030B503680968DD0FB5EBD17FDE -:1026A00023F0604421F060424FEAD1700BD0002B40 -:1026B000B8BFA40C0029B8BF920C944202D034BF1A -:1026C0000120002030BD944205D1C1F38070C3F3D6 -:1026D00080738342F6D194422CBF00200120F1E7A1 -:1026E0002DE9F041456A15B94162BDE8F0814B68BA -:1026F00023F06047C3F38A464FEAD37EC3F3807862 -:1027000016EA230638BF3E46AC462B465A68BEEB57 -:10271000D27F22F060440AD0002A18DAA40CB44216 -:1027200017D19D420FD10D60DEE71346EEE7A742B9 -:1027300007D102F08044C2F3807242450BD054B1FD -:10274000EFE708D2EDE7CCF800100B60CDE7B4421C -:1027500001D0B442E5D81A689C46002AE5D1196038 -:10276000C3E700002DE9F047089D01F007044FEA98 -:10277000D508224405F0070500EBD1004FF47F494E -:10278000944201D1BDE8F08704F0070705F0070A7D -:1027900057453E4638BF5646C6F10806111B8E42C5 -:1027A00028BF0E46E10808EBD50E415C13F80EC0B9 -:1027B000B94029FA06F721FA0AF1FFB28CEA0101C1 -:1027C00047FA0AF739408CEA010C03F80EC034448A -:1027D0003544D5E780EA0120082341F2210201B205 -:1027E0004000002980B203F1FF33B8BF504013F01E -:1027F000FF03F4D17047000038B50C468D18A54290 -:1028000000D138BD14F8011BFFF7E4FFF7E7000023 -:1028100042684AB1136843604389818901339BB29E -:102820009942438138BF83811046704770B588B0A4 -:10283000202204460D4668460021FEF775FD20461D -:102840000495FFF7E5FF024658B16B46054608AE12 -:102850001C4603CCB44228606960234605F1080594 -:10286000F6D1104608B070BD082817D909280CD039 -:102870000A280CD00B280CD00C280CD00D280CD01A -:102880000E2814BF4020302070470C2070471020C5 -:1028900070471420704718207047202070470000B0 -:1028A000082817D90C280CD910280CD914280CD9B1 -:1028B00018280CD920280CD930288CBF0F200E20C6 -:1028C0007047092070470A2070470B2070470C2082 -:1028D00070470D20704700002DE9F843078C072F43 -:1028E00004461ED9D0E9029800254FF6FF73C5F1C2 -:1028F0002006A5F1200029FA05F108FA06F628FAC3 -:1029000000F031430143C9B21846FFF763FF0835B1 -:10291000402D0346EBD1E1693A46BDE8F843FFF7A5 -:102920006BBF4FF6FF70BDE8F883000010B54B6831 -:1029300023B9CA8A63F30902CA8210BD04691A68FE -:102940001C600361C38A013BC3824A60EFE7000059 -:102950002DE9F84F1D46CB8A0F46C3F3090105291F -:10296000814692460B4630D00020AAB207F11A04E5 -:102970009EB2042E1FFA80F80FD8904503F1010390 -:1029800006D3FB8A0A4462F30903FB8201201AE0A2 -:102990001AF80060E6540130EAE79045F1D2A1F15F -:1029A000050B1C237C68BBFBF3F203FB12BB1FFA75 -:1029B0008BF6002C45D14846FFF72AFF044638B96C -:1029C00078606FF00200BDE8F88F4FF00008E6E78E -:1029D000002606607860ADB24FF0000B454510D977 -:1029E0000AEB0803221D13F8011B9155B1B208F13F -:1029F00001081B291FFA88F82BD0454506F101066E -:102A0000F1D8FB8AC3F30902154465F30903BCE757 -:102A1000013292B21C462368002BF9D16B1F0B4484 -:102A20001C21B3FBF1F301339BB29A42D3D2BBF129 -:102A3000000FD0D14846FFF7EBFE20B9C4F800B034 -:102A4000BFE70122E7E7C0F800B05E462060044619 -:102A5000C1E74545D5D94846FFF7DAFE08B92060F9 -:102A6000AFE7C0F800B0002620600446B6E70000DB -:102A70002DE9F04F2DED028B1C4683B05B6901926E -:102A800007468846002B00F09A80238C2BB1E26920 -:102A9000002A00F09480072B35D807F10C00FFF7CF -:102AA000B7FE054638B96FF00205284603B0BDEC05 -:102AB000028BBDE8F08F14220021FEF735FC228C3A -:102AC000E16905F10800FEF71DFC208C013080B2A1 -:102AD000FFF7E6FEFFF7C8FE013880B22084013020 -:102AE00028746369228C1B782A4403F01F0363F067 -:102AF0003F0348F000411372384669602946FFF7EA -:102B0000EFFD0125D1E700F10C034FF0000908EEBD -:102B1000103A4FF0800A4E464D4618EE100AFFF765 -:102B200077FE83460028BED014220021FEF7FCFB6E -:102B3000002E3AD1019BABF8083002220BF1080EAF -:102B40001FFA82FC0CF10100BCF1060F218C80B24F -:102B500001D88E422BD3FFF7A3FEFFF785FE6269F3 -:102B60001278013802F01F028E4208BF4FF0400A6F -:102B700042EA49121BFA80F14AEA020A013048F09F -:102B8000004281F808A08BF81000CBF804205946C9 -:102B90003846FFF7A5FD238C0135B3422DB289F0ED -:102BA00001094FF0000AB8D17FE70022C6E7E169CA -:102BB000895D0EF802100136B6B20132C0E76FF03F -:102BC000010572E7F8B515460E463022002104468D -:102BD0001F46FEF7A9FB069B6360B5F5001F079B28 -:102BE000A76034BF6A094FF6FF72A36297B2E6612D -:102BF00004F1100000239A4206D800230360A78244 -:102C0000E3822383E360F8BD06600133304620365B -:102C1000F1E7000003781BB94BB2002BC8BF01706D -:102C20007047000000787047F8B50C46C969074640 -:102C300011B9238C002B37D1257E1F2D34D838783D -:102C400028BB228C072A2CD8268A36F003032BD1E6 -:102C50004FF6FF70FFF7D0FD20F001003102400475 -:102C600041EA0561400C41EA40254FF6FF722346D8 -:102C700029463846FFF7FCFE002807DD6269137815 -:102C80000133DBB21F2B88BF00231370F8BD218AEC -:102C90002D0645EA012505432046FFF71DFE0246A5 -:102CA000E5E76FF00300F1E76FF00100EEE70000E9 -:102CB00070B58AB0044616460021282268461D4693 -:102CC000FEF732FBBDF83830ADF810300F9B05939E -:102CD0009DF840308DF81830119B07936946BDF878 -:102CE0004830ADF820302046CDE90265FFF79CFF63 -:102CF0000AB070BD2DE9F041D36905460C46164671 -:102D00000BB9138C5BBB377E1F2F28D895F800803A -:102D1000B8F1000F26D03046FFF7DEFD33782102F0 -:102D200041EAC33141EA0801338A41EA076141EAD5 -:102D300003410246334641F080012846FFF798FEE2 -:102D400000280ADD3378012B07D17269137801332B -:102D5000DBB21F2B88BF00231370BDE8F0816FF03A -:102D60000100FAE76FF00300F7E70000F0B58BB061 -:102D700004460D4617460021282268461E46FEF7E7 -:102D8000D3FA9DF84C305A1E534253418DF800300F -:102D90009DF84030ADF81030119B05939DF84830F8 -:102DA0008DF81830149B07936A46BDF85430ADF87F -:102DB000203029462046CDE90276FFF79BFF0BB075 -:102DC000F0BD0000406A00B104307047436A1A68E1 -:102DD000426202691A600361C38A013BC382704781 -:102DE0002DE9F041D0F82080194E14461D46414689 -:102DF000002709B9BDE8F081D1E90223A21A65EBE9 -:102E00000303964277EB03031ED2036A8B420DD174 -:102E1000FFF78CFD036A1B68036203690B60C38ABA -:102E20000161016A013BC3828846E2E7FFF77EFD4C -:102E30000B68C8F8003003690B60C38A0161013B6D -:102E4000C382D8F80010D4E788460968D1E700BFEC -:102E500080841E002DE9F04F8BB00D46DDF85090B8 -:102E600014469B468046002800F01981B9F1000FF6 -:102E700000F01581531E3F2B00F21181012A03D16E -:102E8000BBF1000F40F00B810023CDE90833B8F807 -:102E90001430B5EBC30F4FEAC30703D300200BB0C8 -:102EA000BDE8F08F2B199F42D8F80C303ABF7F1B3A -:102EB000FFB227461BB9D8F81030002B7AD0272D47 -:102EC0004ED8C5F12806B7424FF000032CBFF6B22A -:102ED0003E4600932946D8F8080008AB3246FFF773 -:102EE00041FCA7EB060A35445FFA8AFAB8F81430B9 -:102EF00003F10053053BDB000493D8F80C30039337 -:102F00002821039B13B1BAF1000F2CD1D8F810007F -:102F100040B1BAF1000F05D0009608AB5246691ACD -:102F2000FFF720FC38B2002FB8D066070AD00AABF2 -:102F300003EBD401624211F8083C02F0070213418E -:102F400001F8083C082C3CD9102C40F2B580202C0C -:102F500040F2B780BBF1000F00F09C80082334E002 -:102F6000BA460026C2E7049BE02B28BFE023069365 -:102F70000B44AB42059314D95A1B03980096924513 -:102F800034BF5246D2B2691A08AB04300792FFF739 -:102F9000E9FB079A1644AAEB020A1544F6B25FFA57 -:102FA0008AFA049B069A05999B1A0493039B1B6853 -:102FB0000393A6E70093D8F8080008AB3A462946E1 -:102FC000AEE7BBF1000F13D00123B4EBC30F6CD0FD -:102FD000082C12D89DF82030621E23FA02F2D50781 -:102FE00006D54FF0FF3202FA04F423438DF8203067 -:102FF0009DF8203089F8003051E7102C12D8BDF828 -:103000002030621E23FA02F2D10706D54FF0FF32BC -:1030100002FA04F42343ADF82030BDF82030A9F8BB -:1030200000303CE7202C0FD80899631E21FA03F3E7 -:10303000DA0705D54FF0FF3202FA04F40C43089486 -:10304000089BC9F800302AE7402C2BD0DDE9086541 -:10305000611EC4F12102A4F1210326FA01F105FA4F -:1030600002F225FA03F311431943CB0712D50122CB -:10307000A4F12003C4F1200102FA03F322FA01F1C2 -:10308000A240524243EA010363EB430332432B4322 -:10309000CDE90823DDE90823C9E90023FFE66FF045 -:1030A0000100FCE66FF00800F9E6082CA0D9102C0E -:1030B000B3D9202CEED8C3E7BBF1000FADD002236B -:1030C00083E7BBF1000FBBD004237EE730B5012AB4 -:1030D000144638BF0124402C85B028BF4024002569 -:1030E000012ACDE9025518D81B788DF808306307FE -:1030F0000AD004AB03EBD405624215F8083C02F099 -:103100000702934005F8083C00910346224600213F -:1031100002A8FFF727FB05B030BD082AE4D9102A22 -:1031200003D81B88ADF80830E1E7202A8DBFD3E92A -:1031300000231B680293CDE90223D8E710B5CB68C2 -:103140001BB98B600B618B8210BD04691A681C600F -:103150000361C38A013BC382CA60F0E703064CBF28 -:10316000C0F3C0300220704708B50246FFF7F6FFF3 -:10317000022806D15306C2F30F2001D100F003004C -:1031800008BDC2F30740FBE72DE9F04F93B0CDE94E -:1031900003230A6804461046FFF7E0FF022814BF25 -:1031A000C2F306260026002A0D46824680F2F281EE -:1031B00012F0C04940F0EE81097B002900F0EA815D -:1031C000022803D02378B34240F0E781C2F30463BE -:1031D0000693104602F07F030593FFF7C5FF059B9A -:1031E00029444FEA834848EA0A4848EA4668CE78C4 -:1031F00000230022CDE90823F309834648EA0008AA -:10320000029367D0059B009302466768534608A95E -:103210002046B847002800F0C381276A4FB94146CD -:1032200004F10C00FFF702FB074690B96FF00200B3 -:1032300054E03B6998450DD03F68002FF9D14146D5 -:1032400004F10C00FFF7F2FA07460028EED0236ADB -:103250003B60276297F817C006F01F08CCF3840C78 -:10326000ACEB08001FFA80FE0028B8BF0EF120006A -:10327000A8EB0C031FFA83FED7E90221B8BF00B206 -:10328000002B0793BEBF0EF120031BB2079352EA37 -:10329000010338D0039BDFF824E39A1A049B4FF014 -:1032A000000C63EB010196457CEB01032BD36B7B98 -:1032B00097F81AE0734519D1029B002B78D00128AA -:1032C00021DC7868F8B9DFF8F0C2944570EB0103AF -:1032D00016D337E0276A27B96FF00C0013B0BDE8AA -:1032E000F08F3B699845B5D03F68F4E7B24890420B -:1032F0007CEB010301D30020F0E7029B002BFAD006 -:10330000079B0F2B17DCFA7DB30002F0030203F0DA -:103310007C031343FB7539462046FFF707FB6B7BA5 -:10332000BB76029B3BB9FB7DC3F38402013262F39F -:103330008603FB75D0E76A7BBB7E9A42DBD1029B9A -:10334000002B35D0B309022B32D0039BBB60049B0A -:10335000FB60142200210DA8FDF7E6FF039B0A93F2 -:10336000049B0B932B1D0C932B7BADF83EB0013BC4 -:10337000DBB2ADF83C30069B8DF84230059B8DF8F2 -:10338000433094F82C308DF840A083F001038DF881 -:1033900044308DF84180A3680AA920469847FB7DF8 -:1033A000C3F38403013303F01F039B02FB82A2E7F4 -:1033B000FB7DC6F34012B2EBD31F40F0F480C3F3A1 -:1033C0008403434540F0F280029A2B7BB609002A21 -:1033D0004DD0F2075DD4032B40F2EB80039BBB6022 -:1033E000049BFB602B7BAE1D033BDBB232463946B0 -:1033F00004F10C00FFF7ACFA00280CDA394620463D -:10340000FFF794FAFB7DC3F38403013303F01F033A -:103410009B02FB820AE7DDE90884AB883B834FF619 -:10342000FF73C9F12000A9F1200228FA09F104FA7A -:1034300000F0014324FA02F211431846C9B2FFF723 -:10344000C9F909F10809B9F1400F0346E9D1B88279 -:103450002A7B033AD2B23146FFF7CEF9FB7DB88220 -:10346000DA43C2F3C01262F3C713FB7543E786B9B0 -:103470002E1D013BDBB23246394604F10C00FFF74A -:1034800067FA0028BADB2A7BB88A013AD2B2314601 -:10349000E2E7F98AC1F30901013B0429DAB25BD8FA -:1034A000281D002307F11B069A4208D910F801CB0A -:1034B00006F801C0013101330529DBB2F4D10399CB -:1034C0000A9104990B91934207F11B010C9138BFAB -:1034D000043379680D9134BF55FA83F300230E93BA -:1034E000FB8AADF83EB0C3F309031A44069B8DF87E -:1034F0004230059B8DF8433094F82C30ADF83C20D9 -:1035000083F001038DF8443000238DF840A08DF83E -:1035100041807B602A7BB88A013A291DFFF76CF94C -:103520003B8BB882834203D1A3680AA920469847FF -:1035300020460AA9FFF702FEFB7DBA8AC3F3840383 -:10354000013303F01F039B02FB823B8B9A420CBFAB -:1035500000206FF01000C1E67B68002BAFD0052083 -:1035600001E01C3033461E68002EFAD1091A081DEE -:103570002E1D184401EB090CBCF11B0F5FFA89F3F7 -:103580009DD89A429BD916F8013B00F8013B09F1FE -:103590000109EFE76FF00900A0E66FF00A009DE671 -:1035A0006FF00B009AE66FF00D0097E66FF00E00DB -:1035B00094E66FF00F0091E640420F0080841E00F9 -:1035C000EFF3098305494A6B22F001024A6368332D -:1035D00083F30988002383F31188704700EF00E02C -:1035E000302080F3118862B60C4B0D4AD96821F463 -:1035F000E0610904090C0A43DA60D3F8FC200949A8 -:1036000042F08072C3F8FC200A6842F001020A60AE -:103610002022DA7783F82200704700BF00ED00E037 -:103620000003FA05001000E010B5302383F3118881 -:103630000E4B5B6813F4006314D0F1EE103AEFF315 -:103640000984683C4FF08073E361094BDB6B2366B0 -:1036500084F3098800F0A4F810B1064BA36110BDF3 -:10366000054BFBE783F31188F9E700BF00ED00E0AD -:1036700000EF00E003060008060600084FF0E02314 -:10368000002258684FF0FF31930003F1604303F5C7 -:10369000614301329042C3F88010C3F88011F3D225 -:1036A0007047000000F1604303F561430901C9B2AE -:1036B00083F80013012200F01F039A4043099B0086 -:1036C00003F1604303F56143C3F880211A6070473A -:1036D00000230375826803691B6899689142FBD2D5 -:1036E0005A68036042601060586070470023037599 -:1036F000826803691B6899689142FBD85A68036025 -:10370000426010605860704708B50846302383F364 -:1037100011880B7D032B05D0042B0DD02BB983F31F -:10372000118808BD8B6900221A604FF0FF33836156 -:10373000FFF7CEFF0023F2E7D1E9003213605A60B1 -:10374000F3E70000FFF7C4BF054BD9680875186898 -:1037500002681A60536001220275D860FCF73CBF12 -:103760002038002030B50C4BDD684B1C87B0044678 -:103770000FD02B46094A684600F050F92046FFF763 -:10378000E3FF009B13B1684600F052F9A86907B047 -:1037900030BDFFF7D9FFF9E72038002009370008CE -:1037A000044B1A68DB6890689B68984294BF0020BD -:1037B0000120704720380020084B10B51C68D868DD -:1037C00022681A60536001222275DC60FFF78EFFC9 -:1037D00001462046BDE81040FCF7FEBE2038002020 -:1037E000044B1A68DB6892689B689A4201D9FFF71C -:1037F000E3BF70472038002038B5074C0749084818 -:10380000012300252370656000F000FC0223237073 -:1038100085F3118838BD00BF483A0020C047000832 -:103820002038002008B572B6044B186500F0B6FACF -:1038300000F06EFB024B03221A70FEE720380020D6 -:10384000483A002000F02AB9EFF3118020B9EFF3D5 -:103850000583302282F311887047000010B530B91B -:10386000EFF30584C4F3080414B180F3118810BD8C -:10387000FFF7B6FF84F31188F9E700008B6002239D -:1038800008618B82084670478368A3F1840243F87D -:10389000142C026943F8442C426943F8402C094A2D -:1038A00043F8242CC26843F8182C022203F80C2C8D -:1038B000002203F80B2C044A43F8102CA3F120003B -:1038C000704700BFF10500082038002008B5FFF759 -:1038D000DBFFBDE80840FFF735BF0000024BDB68A7 -:1038E00098610F20FFF730BF20380020302383F38A -:1038F0001188FFF7F3BF000008B50146302383F3BA -:1039000011880820FFF72EFF002383F3118808BDDC -:1039100010B503689C68A2420CD85C688A600B6092 -:103920004C602160596099688A1A9A604FF0FF33A1 -:10393000836010BD1B68121BECE700000A2938BF2A -:103940000A2170B504460D460A26601900F058FB9E -:1039500000F044FB041BA54203D8751C2E46044608 -:10396000F3E70A2E04D9BDE87040012000F08EBBB9 -:1039700070BD0000F8B5144B0D46D96103F110017C -:1039800041600A2A1969826038BF0A2201604860D2 -:103990001861A818144600F025FB0A2700F01EFB4A -:1039A000431BA342064606D37C1C281900F028FBC3 -:1039B00027463546F2E70A2F04D9BDE8F840012032 -:1039C00000F064BBF8BD00BF20380020F8B5064603 -:1039D0000D4600F003FB0F4A134653F8107F9F4239 -:1039E00006D12A4601463046BDE8F840FFF7C2BF7F -:1039F000D169BB68441A2C1928BF2C46A34202D9AE -:103A00002946FFF79BFF224631460348BDE8F840B0 -:103A1000FFF77EBF203800203038002010B4C0E906 -:103A2000032300235DF8044B4361FFF7CFBF000081 -:103A300010B5194C236998420DD0D0E90032816845 -:103A400013605A609A680A449A60002303604FF03A -:103A5000FF33A36110BD2346026843F8102F536063 -:103A60000022026022699A4203D1BDE8104000F0B2 -:103A7000C1BA936881680B44936000F0AFFA226981 -:103A8000E1699268441AA242E4D91144BDE81040A9 -:103A9000091AFFF753BF00BF203800202DE9F04777 -:103AA000DFF8BC8008F110072C4ED8F8105000F059 -:103AB00095FAD8F81C40AA68031B9A423ED81444D1 -:103AC000D5E900324FF00009C8F81C4013605A6075 -:103AD000C5F80090D8F81030B34201D100F08AFA4E -:103AE00089F31188D5E9033128469847302383F3B9 -:103AF00011886B69002BD8D000F070FA6A69A0EBCE -:103B000004094A4582460DD2022000F0BFFA002285 -:103B1000D8F81030B34208D151462846BDE8F047E6 -:103B2000FFF728BF121A2244F2E712EB090938BF47 -:103B30004A4629463846FFF7EBFEB5E7D8F810307D -:103B4000B34208D01444211AC8F81C00A960BDE88B -:103B5000F047FFF7F3BEBDE8F08700BF3038002024 -:103B60002038002000207047FEE70000704700006A -:103B70004FF0FF3070470000BFF34F8F024A1369C8 -:103B8000DB03FCD4704700BF0020024008B5094B9E -:103B90001B7873B9FFF7F0FF074B5A69002ABFBFC4 -:103BA000064A9A6002F188329A601A6822F48062AA -:103BB0001A6008BD603A00200020024023016745DA -:103BC00008B50B4B1B7893B9FFF7D6FF094B5A6921 -:103BD00042F000425A611A6842F480521A601A6830 -:103BE00022F480521A601A6842F480621A6008BD9A -:103BF000603A0020002002407F289ABF00F5803004 -:103C0000C0020020704700004FF4006070470000C1 -:103C1000802070477F2808B50BD8FFF7EDFF00F52F -:103C200000630268013204D104308342F9D10120DB -:103C300008BD0020FCE700007F2810B504461FD80F -:103C4000FFF79AFFFFF7A2FF0E4BF3221A61022241 -:103C50005A615A6942EAC0025A615A6942F4803292 -:103C60005A61FFF789FF4FF40061FFF7C5FF00F0CD -:103C70004BF9FFF7A5FF2046BDE81040FFF7CABF8C -:103C8000002010BD002002402DE9F84340EA020365 -:103C900013F00703144606D0304B40F231321A605D -:103CA0000020BDE8F88385182D4A95420CD92B4A8F -:103CB00040F236311160F3E7031D1B684A689342F6 -:103CC00008D1083C08300831072C14D902680B6869 -:103CD0009A42F1D0FFF75AFFFFF74EFF214E08310D -:103CE0004FF001084FF00009012CA1F1080706D898 -:103CF000FFF766FF01E0002CECD10120D1E7C6F808 -:103D00001480054651F8083C45F8043B51F8043C42 -:103D10004360FFF731FF336943F001033361C6F8B5 -:103D20001490026851F8083C9A420CD00B4B40F2B8 -:103D30005E321A600C4B18600C4B1C600C4B1F6001 -:103D4000FFF73EFFACE72D6851F8043C9D4201F1BE -:103D50000801EBD1083C0830C6E700BF5C3A002000 -:103D60000000040800200240503A0020583A002089 -:103D7000543A0020084908B50B7828B11BB9FFF761 -:103D800005FF01230B7008BD002BFCD0BDE80840E7 -:103D90000870FFF715BF00BF603A00204FF4803174 -:103DA0004FF0005000F0B2B80846114600F014BCC5 -:103DB000012000F011BC0000084600F02BBC000000 -:103DC00070B582B0FFF740FD0E4E054600F006F9D3 -:103DD0003268904237BF0C4A0B49516814682EBFB5 -:103DE000D1E90041013151600419034641F100015C -:103DF000284601913360FFF731FD0199204602B05A -:103E000070BD00BF643A0020683A002070B582B0EF -:103E1000FFF71AFD104E054600F0E0F832689042B8 -:103E200037BF0E4A0D49516814682EBFD1E90041D1 -:103E300001315160041941F1000103462846019106 -:103E40003360FFF70BFD01994FF47A72002320468F -:103E5000FCF7AEF902B070BD643A0020683A002069 -:103E600010B50244064BD2B2904200D110BD441CA2 -:103E700000B253F8200041F8040BE0B2F4E700BFB1 -:103E800050280040114B30B5D3F89040240409D499 -:103E9000D3F89040C3F89040D3F8904044F40044E5 -:103EA000C3F890400A4C236843F4807323600244B3 -:103EB000084BD2B2904200D130BD441C00B251F840 -:103EC000045B43F82050E0B2F4E700BF001002406A -:103ED000007000405028004007B5012201A90020D1 -:103EE000FFF7BEFF019803B05DF804FB13B504466D -:103EF000FFF7F2FFA04205D0012201A900200194A2 -:103F0000FFF7C0FF02B010BD70470000704700000F -:103F100070470000074B45F255521A6002225A6062 -:103F200040F6FF729A604CF6CC421A60024B0122B6 -:103F30001A70704700300040743A0020034B1B7821 -:103F40001BB1034B4AF6AA221A607047743A00204C -:103F500000300040054B1A6832B902F1804202F588 -:103F60000432D2F894201A60704700BF703A0020E3 -:103F7000024B4FF40002C3F8942070470010024037 -:103F800008B5FFF7E7FF024B1868C0F3407008BDA3 -:103F9000703A002070470000FEE700000A4B0B4813 -:103FA0000B4A90420BD30B4BDA1C121AC11E22F0A3 -:103FB00003028B4238BF00220021FDF7B5B953F848 -:103FC000041B40F8041BECE75C480008003B0020A1 -:103FD000003B0020003B002000F0BEB84FF08043C3 -:103FE000586A70474FF08043002258631A610222DA -:103FF000DA6070474FF080430022DA6070470000BB -:104000004FF0804358637047FEE7000070B51B4BCC -:1040100001630025044686B0586085620E46FFF7AE -:10402000DFFA04F11003C4E904334FF0FF33C4E9AD -:104030000635C4E90044A560E562FFF7CFFF2B46D3 -:104040000246C4E9082304F134010D4A25658023A2 -:104050002046FFF713FC0123E0600A4A0375009233 -:1040600072680192B268CDE90223074B6846CDE938 -:104070000435FFF72BFC06B070BD00BF483A0020A6 -:10408000CC470008D147000809400008024AD36A1B -:104090001843D062704700BF20380020244B2548C9 -:1040A000DA6A42F0070210B4DA62DA6A224C22F0CD -:1040B0000702DA62DA6ADA6C42F00702DA64DA6E70 -:1040C00042F00702DA664FF09042DB6E4FF0AA3101 -:1040D000002353609160D0604FF6FF70506113620F -:1040E000536214601024C2F80434C2F80814C2F8F1 -:1040F0000C444FF6F774C2F814449924C2F82034E3 -:10410000C2F824440D4CC2F80044C2F80438C2F886 -:104110000818C2F80C38C2F81408C2F82038C2F8DF -:104120002438C2F800385DF8044B00F055B800BFE1 -:1041300000100240000100240001002850000A0085 -:1041400008B500F005FAFFF757FBBDE80840FFF798 -:1041500001BF0000704700000F4B9A6D42F0010252 -:104160009A659A6F42F001029A670C4A9B6F9368B6 -:1041700043F0010393604FF080434F229A624FF067 -:10418000FF32DA6200229A615A63DA605A600122D1 -:104190005A611A60704700BF00100240002004E01E -:1041A0004FF0804208B51169D3680B40D9B2C943BA -:1041B0009B07116107D5302383F31188FFF742FB7A -:1041C000002383F3118808BD08B5FFF757FABDE84F -:1041D000084000F099B900005A4B4FF0FF319A6A3D -:1041E00099629A6A00229A62986AD86A60F0070017 -:1041F000D862D86A00F00700D862D86A186B1963D1 -:10420000186B1A63186B986B9963986B9A63986B29 -:10421000D86BD963D86BDA63D86B186C1964196CD6 -:104220001A641A6C484A4FF4E06111601A6E4749EB -:1042300042F001021A66D3F8802022F00102C3F88E -:104240008020D3F880209A6D42F080529A659A6F50 -:1042500022F080529A679A6F4FF440720A604A695E -:1042600012F48062FBD14A601A6822F0F00242F038 -:1042700060021A601A6842F001021A601A68910717 -:10428000FCD500229A609A6812F00C02FBD1D3F898 -:10429000901011F4407F1EBF4FF48031C3F890108E -:1042A000C3F8902061221A601A689207FCD5002298 -:1042B0009A609A6812F00C0FFBD169221A60D3F849 -:1042C000942022F4706242F4C062C3F894201A6809 -:1042D00042F480321A601A689003FCD5D3F890201B -:1042E00022F00322C3F89020194ADA601A6842F0DB -:1042F00080721A601A689101FCD5164A1A611A6810 -:1043000042F080621A601A681201FCD500229A609D -:104310000D49114AC3F888200A6822F0070242F0CA -:1043200004020A600A6802F00702042AFAD19A68B5 -:1043300042F003029A609A6802F00C020C2AFAD149 -:10434000704700BF00100240002002400070004093 -:1043500003140001000C100055550134074A08B53C -:10436000536903F00103536123B1054A13680BB18C -:1043700050689847BDE80840FFF756B9000401406F -:10438000783A0020074A08B5536903F002035361E5 -:1043900023B1054A93680BB1D0689847BDE808403F -:1043A000FFF742B900040140783A0020074A08B5F7 -:1043B000536903F00403536123B1054A13690BB138 -:1043C00050699847BDE80840FFF72EB90004014046 -:1043D000783A0020074A08B5536903F0080353618F -:1043E00023B1054A93690BB1D0699847BDE80840ED -:1043F000FFF71AB900040140783A0020074A08B5CF -:10440000536903F01003536123B1054A136A0BB1DA -:10441000506A9847BDE80840FFF706B9000401401C -:10442000783A0020164B10B55C6904F478725A6132 -:10443000A30604D5134A936A0BB1D06A9847600665 -:1044400004D5104A136B0BB1506B9847210604D565 -:104450000C4A936B0BB1D06B9847E20504D5094A1F -:10446000136C0BB1506C9847A30504D5054A936CA7 -:104470000BB1D06C9847BDE81040FFF7D5B800BF2E -:1044800000040140783A0020194B10B55C6904F42F -:104490007C425A61620504D5164A136D0BB1506D0A -:1044A0009847230504D5134A936D0BB1D06D9847F7 -:1044B000E00404D50F4A136E0BB1506E9847A10467 -:1044C00004D50C4A936E0BB1D06E9847620404D5A4 -:1044D000084A136F0BB1506F9847230404D5054A5F -:1044E000936F0BB1D06F9847BDE81040FFF79CB8B1 -:1044F00000040140783A002008B5FFF751FEBDE8FE -:104500000840FFF791B80000062108B50846FFF7FC -:10451000C9F806210720FFF7C5F806210820FFF794 -:10452000C1F806210920FFF7BDF806210A20FFF790 -:10453000B9F806211720FFF7B5F806212820FFF764 -:10454000B1F8BDE8084007211C20FFF7ABB8000018 -:1045500008B5FFF739FE00F007F8FFF7FBFDBDE8EF -:104560000840FFF739BD00000023054A1946013312 -:10457000102BC2E9001102F10802F8D1704700BF08 -:10458000783A00200B460146184600F02DB800008E -:1045900000F040B8012838BF012010B5044620467D -:1045A00000F030F830B900F007F808B900F00CF866 -:1045B0008047F4E710BD0000024B1868BFF35B8F23 -:1045C000704700BFF83A002008B5062000F084F8D4 -:1045D0000120FFF7C9FA0000024B0A46014618689D -:1045E000FFF7E2BB1811002010B5054C13462CB1A3 -:1045F0000A4601460220AFF3008010BD2046FCE7CA -:1046000000000000024B01461868FFF7D1BB00BF55 -:1046100018110020024B01461868FFF7CDBB00BF00 -:104620001811002010B501390244904201D1002038 -:1046300005E0037811F8014FA34201D0181B10BD0B -:104640000130F2E72DE9F041A3B1C91A177801440E -:10465000044603F1FF3C8C42204601D9002009E0CA -:104660000578BD4204F10104F5D10CEB0405D61820 -:10467000A54201D1BDE8F08115F8018D16F801EDD4 -:10468000F045F5D0E7E700001F2938B504460D4690 -:1046900004D9162303604FF0FF3038BD426C12B1CD -:1046A00052F821304BB9204600F030F82A46014636 -:1046B0002046BDE8384000F017B8012B0AD0591C3D -:1046C00003D1162303600120E7E7002442F82540C8 -:1046D000284698470020E0E7024B01461868FFF79C -:1046E000D3BF00BF1811002038B5074D0023044682 -:1046F000084611462B60FFF73BFA431C02D12B689A -:1047000003B1236038BD00BFFC3A0020FFF72ABA8E -:10471000034611F8012B03F8012B002AF9D1704749 -:104720006F72672E6172647570696C6F742E4D6163 -:1047300074656B4C3433312D5065726970680000BC -:1047400040A2E4F1646891060041A3E5F265699234 -:10475000070000004261642043414E496661636581 -:1047600020696E6465782E008000000000800000E3 -:10477000000080000000000000000000311B000865 -:104780001923000879220008411B0008751B000846 -:10479000711D0008451B0008551B0008491B000837 -:1047A000511B00084D1B0008991C0008591B0008EC -:1047B000E5250008691B00086D1C00086330000037 -:1047C000BC47000878380020483A00206D61696EC7 -:1047D0000069646C6500000008BAFF7F01000000FA -:1047E000260400000000000000600300000000003C -:1047F000FE2A0100D20400001C110020000000006D -:1048000000000000000000000000000000000000A8 -:104810000000000000000000000000000000000098 -:104820000000000000000000000000000000000088 -:104830000000000000000000000000000000000078 -:104840000000000000000000000000000000000068 -:0C4850000000000000000000000000005C +:1000000000090020B1010008E1220008992200083F +:10001000C122000899220008B9220008B301000893 +:10002000B3010008B3010008B3010008D53200088D +:10003000B3010008B3010008B3010008B3010008D0 +:10004000B3010008B3010008B3010008B3010008C0 +:10005000B3010008B3010008354000085D40000806 +:1000600085400008AD400008D5400008B3010008F5 +:10007000B3010008B3010008B3010008B301000890 +:10008000B3010008B3010008B30100084D220008C5 +:100090007922000889220008B3010008FD40000809 +:1000A000B3010008B3010008B3010008B301000860 +:1000B000D1410008B3010008B3010008B3010008F2 +:1000C000B3010008B3010008B3010008B301000840 +:1000D000B3010008B3010008B3010008B301000830 +:1000E00061410008B3010008B3010008B301000832 +:1000F000B3010008B3010008B3010008B301000810 +:10010000B3010008B3010008B3010008B3010008FF +:10011000B3010008B3010008B3010008B3010008EF +:10012000B3010008B3010008B3010008B3010008DF +:10013000B3010008B3010008B3010008B3010008CF +:10014000B3010008B3010008B3010008B3010008BF +:10015000B3010008B3010008B3010008B3010008AF +:10016000B3010008B3010008B3010008B30100089F +:10017000B3010008B3010008B3010008B30100088F +:10018000B3010008B3010008B3010008B30100087F +:10019000B3010008B3010008B3010008B30100086F +:1001A000050F000800000000000000000000000033 +:1001B00002E000F000F8FEE772B6374880F30888E6 +:1001C000364880F3098836483649086040F2000016 +:1001D000CCF200004EF63471CEF200010860BFF39D +:1001E0004F8FBFF36F8F40F20000C0F2F0004EF669 +:1001F0008851CEF200010860BFF34F8FBFF36F8FBD +:100200004FF00000E1EE100A4EF63C71CEF2000114 +:100210000860062080F31488BFF36F8F03F026FD7B +:1002200003F0A8FD4FF055301F491B4A91423CBFD7 +:1002300041F8040BFAE71D49184A91423CBF41F8C6 +:10024000040BFAE71A491B4A1B4B9A423EBF51F86E +:10025000040B42F8040BF8E700201849184A9142B1 +:100260003CBF41F8040BFAE703F004FD03F0D4FDB2 +:10027000144C154DAC4203DA54F8041B8847F9E7D7 +:1002800000F042F8114C124DAC4203DA54F8041B52 +:100290008847F9E703F0ECBC0009002000110020BA +:1002A0000000000808ED00E0000100200009002027 +:1002B000B0440008001100207C11002080110020B3 +:1002C000FC3A0020A0010008A4010008A4010008D5 +:1002D000A40100082DE9F04F2DED108AC1F80CD0D3 +:1002E000C3689D46BDEC108ABDE8F08F002383F300 +:1002F00011882846A047002003F05CF9FEE703F0D0 +:10030000E5F800DFFEE70000F8B500F00DFE03F0B1 +:100310004FFC074603F0A0FC0646C0BB274B9F429C +:1003200035D001339F4235D0254B27F0FF029A424A +:1003300033D1F8B200F03EFC354642F2107400F0C2 +:100340003FFC08B10024254601F0A6F848B303207D +:1003500000F03AF80024254636B11A4B9F4203D0EC +:1003600003F072FC00242546002003F02BFC0DB1A5 +:1003700000F040F800F056FC01F0BAFF0546ACB9B9 +:1003800000F098FC4FF47A7003F01AF9F7E735465D +:100390000024D4E704460125D1E705464FF47A74DA +:1003A000CDE7B4F57A7F08BF0125D5E701F0A0FFBE +:1003B000431BA342E4D900F01DF8DDE7010007B0BC +:1003C000000008B0263A09B0084B187003280CD872 +:1003D000DFE800F008050208022000F003BE02205A +:1003E00000F0F6BD024B00225A60704780110020D9 +:1003F0008411002010B501F04FF830B1234B0322D7 +:100400001A70234B00225A6010BD224B224A1C4610 +:1004100019680131F8D004339342F9D16268A242DD +:10042000F2D31E4B9B6803F1006303F520439A420D +:10043000EAD203F0DBFB03F0EDFB002000F08EFDC1 +:100440000220FFF7C1FF164B9A6D00229A65996F43 +:100450009A67996FD96DDA65D96FDA67D96F196EB6 +:100460001A66D3F88010C3F88020D3F8803072B6B3 +:100470004FF0E0233021C3F8084DD4E9003281F376 +:1004800011889D4683F308881047BDE7801100203E +:100490008411002000A0000820A000080011002006 +:1004A00000100240094A136849F2690099B21B0C16 +:1004B00000FB01331360064B186844F2506182B2AE +:1004C000000C01FB0200186080B27047141100207C +:1004D0001011002010B500211022044600F09CFDF0 +:1004E000034B03CB206061601868A06010BD00BFA3 +:1004F0009075FF1F2DE9F041ADF5507D0DF13C08E1 +:100500006EAC40F2751207460D4610A80021C8F8DF +:10051000001000F081FD4FF4C4720021204600F06D +:100520007BFD01F0E5FE274B4FF47A72B0FBF2F051 +:10053000186093E80700022384E807000DF5ED70CA +:100540002382FFF7C7FF42F204631F49238407A8F1 +:1005500003F04AFF1E2384F832310DF2EB2207AB81 +:100560000DF1340C1E4603CE6645106051603346D3 +:1005700002F10802F6D130681060B38893804146DA +:100580000122204600F094FD00230393AB7E0293EA +:1005900005F11903019380B20123CDE90480009392 +:1005A000E97E06A3D3E90023384602F069FA0DF587 +:1005B000507DBDE8F08100BFAFF300809E6AC4218A +:1005C000818A46EE8C110020F84300082DE9F041A5 +:1005D0002C4C237ADAB080460D465BBB27A928460F +:1005E00000F076FE0746002842D19DF89D60C82E97 +:1005F0003ED801464FF4A662204600F00DFD4FF4B0 +:100600008073C4F8F8314FF40073C4F80C334FF41E +:100610004073C4F8203432460DF19E0104F1090004 +:1006200000F0E8FC26449DF89C30777223720BB9E9 +:10063000EB7E23728122002106AC27A800F0ECFC9F +:100640000122214627A800F07FFE00230393AB7E02 +:10065000029305F1190380B201932823CDE90440E8 +:100660000093E97E05A3D3E90023404602F008FA8F +:100670005AB0BDE8F08100BFAFF30080264172722E +:10068000DF25D7B7B0320020F0B5254E4FF48A757C +:1006900005FB0065F1B096F8D83085F8DC30002411 +:1006A000D822214685F8E8403AA800F0B5FC06F1CA +:1006B000090000F0A9FCD5F8E4308DF8F000C2B2D2 +:1006C00006AF06F109010DF1F100CDE93A3400F071 +:1006D00091FC394601223AA800F062FE80B2CDE9D1 +:1006E000047008230127CDE9023706F1D8030193EE +:1006F00030230093317A0B4807A3D3E9002302F09B +:10070000BFF9A04206DD01F0F3FDC5F8E000384670 +:1007100071B0F0BD2046FBE778F6339F93CACD8DCC +:10072000B0320020A42100202DE9F0411D4D1E4EC5 +:100730001E4F86B0284602F0CFF9034658B3002476 +:10074000CDE90344ADF81440027B8DF8142099687C +:100750004068029403AA03C21B68DFF8548043F088 +:100760000043029301F0C6FD821941F10003009499 +:1007700002A9384601F06EF8A04205DD284602F0D5 +:10078000AFF988F80040D5E798F80030072B05D876 +:10079000013388F8003006B0BDE8F081014802F06E +:1007A0009FF9F8E7A421002040420F00D821002043 +:1007B000E537002070B50D4614461E4602F0BCF821 +:1007C00050B9022E10D1012C0ED112A3D3E900236F +:1007D000C5E90023012007E0282C10D005D8012C02 +:1007E00009D0052C0FD0002070BD302CFBD10BA3FD +:1007F000D3E90023ECE70BA3D3E90023E8E70BA33D +:10080000D3E90023E4E70BA3D3E90023E0E700BF2B +:10081000AFF30080401DA12026812A0B78F6339F7C +:1008200093CACD8D9E6AC421818A46EE264172729A +:10083000DF25D7B7F017304A39059E5638B505463B +:100840000E4C0021013500F0ABFBA4F82C55B4F898 +:100850002C0500F08DFB78B1B4F82C0500F098FB66 +:10086000014648B9B4F82C0500F09AFBB4F82C35D1 +:100870000133A4F82C35EAE738BD00BFB0320020C0 +:1008800010B50A4B0A4A1A6003F5805393F86020AA +:100890003AB9DC6D2CB1204600F07CFE204603F016 +:1008A000E3FCBDE81040034800F074BED8210020EE +:1008B00054440008203200202DE9F04F8FB000AFE3 +:1008C00005460C4602F038F8002849D1237E022B59 +:1008D0001BD1E38A012B18D101F00AFD0646FFF770 +:1008E000E1FD03464FF4C870DFF8C482B3FBF0F2B9 +:1008F00006F5167602FB103316FA83F3C8F80030BB +:10090000E37E33B9A34B00221A703C37BD46BDE8E5 +:10091000F08F07F12401204600F098FC0028F4D164 +:1009200007F11400FFF7D6FD97F8264007F11401F0 +:10093000224607F1270003F0E1FC0028E2D10F2C4A +:1009400008D8944B1C70D8F80030A3F51673C8F87B +:100950000030DAE797F82410284601F0E5FFD4E7E5 +:10096000E38A282B2BD010D8012B23D0052BCCD1F8 +:10097000BFF34F8F8849894BCA6802F4E062134382 +:10098000CB60BFF34F8F00BFFDE7302BBDD1844E4E +:10099000E17E327A9142B8D1607E3146002291F8F0 +:1009A000DC50854200F0A5800132042A01F58A71ED +:1009B000F5D1AAE721462846FFF79CFDA5E7214689 +:1009C0002846FFF703FEA0E7B2F8EC507B6005F184 +:1009D00003094FEA99094FEA8902D11DC908A8EB1A +:1009E000C1039D46EB460021584600F015FB04F17B +:1009F000EE012A463144584600F0FCFA7B6813B9F0 +:100A0000012000F0ABFA96F8D20000F0B1FA0446EB +:100A100030B9307200F0CCFA204600F09FFAB1E015 +:100A2000D6F8D4203AB996F8D200B6F82C258242EE +:100A300001D8FFF703FFD6F8D4202A44944208D205 +:100A400096F8D200B6F82C250130824201D8FFF783 +:100A5000F5FE70685FFA89F2594600F0E5FA08B9C8 +:100A6000C54679E0726896F8D2002A447260D6F8DA +:100A7000D42005EB0209C6F8D49000F079FA81453C +:100A800009D396F8D220D6F8D4000132001B86F89C +:100A9000D220C6F8D400FF2D0FD80024347200F005 +:100AA00087FA204600F05AFA00F0F6FC3D4B188118 +:100AB00008B9FFF79FFCC54627E7BB6896F8D90041 +:100AC0000AFB0362FB68D2F8E41082F8E83001F513 +:100AD0008061C2F8E030C2F8E410FFF7D5FDFFF7FF +:100AE00023FE96F8D920013202F0030286F8D920BD +:100AF000B6E74FF48A7A0AFB02F505F1EA013144C0 +:100B0000204600F079FCF86000287FF4FEAE354402 +:100B1000012285F8E82001F0EBFBD5F8E020D6EDC6 +:100B2000007ADFED216A801A192838BF192040F6B3 +:100B3000B832904228BF1046B8EE677A07EE900AA6 +:100B4000F8EEE77A67EEA67ADFED186AE7EE267A26 +:100B5000FCEEE77AC6ED007A96F8D930BB60BA6849 +:100B600073680AFB02F4321992F8E81059B1D2F80E +:100B7000E4108B42E8463FF427AF002182F8E810EA +:100B8000C2F8E010C5467368064A9B0A0133138118 +:100B9000BBE600BF9D21002000ED00E00400FA0547 +:100BA000B03200208C110020CDCCCC3D6666663F73 +:100BB000A0210020014B1870704700BF9811002041 +:100BC00038B54FF00054134B22689A4220D1124B93 +:100BD000627D12481A70237D03724FF48073C0F84F +:100BE000F8314FF40073C0F80C3300254FF4407314 +:100BF000C0F820340A49C0F8E450C922093000F096 +:100C0000F9F9E0222946204600F006FA012038BD15 +:100C10000020FCE79AAD44C598110020B0320020B6 +:100C20001600002037B500F037FC194D194928810E +:100C30000223012218486B7101F0F6F90023019399 +:100C4000164B174900931748174B4FF4805201F089 +:100C500043FE164B197811B1124801F065FE01F000 +:100C600047FB0446FFF71EFC4FF4C873B0FBF3F2DA +:100C700002FB130304F5167010FA83F00C4B186096 +:100C800002F0EAFF08B10F232B8103B030BD00BF93 +:100C90008C11002040420F00D8210020B507000829 +:100CA0009C110020A4210020B90800089811002000 +:100CB000A02100202DE9F04F2DED028B0FF23829F5 +:100CC000D9E90089834C93B00BAE9FED7E8BFFF783 +:100CD0002BFD814FDFF828A200230A93ADF83430B2 +:100CE0000B9373604FF0000B5B468DED008B01257D +:100CF0000DF11D0207A938468DF81C508DF81DB066 +:100D000001F040F99DF81C30002B40F0A5802046F2 +:100D100001F012FE0646002845D1704F01F0E8FAB6 +:100D20003B6898423FD301F0E3FA8246FFF7BAFBF3 +:100D30004FF4C873B0FBF3F202FB13030AF516700D +:100D400010FA83F03860664F97F800B0CBF1100AC4 +:100D5000BBF1000F14BF33462B465FFA8AFA0EA888 +:100D60008DF82830FFF7B6FBBAF1060F28BF4FF019 +:100D7000060A0EAB03EB0B0152460DF1290000F001 +:100D800039F90AAB0393182302930AF10102554B78 +:100D9000D2B2CDE90053049220464CA3D3E90023FC +:100DA00001F010FE3E7001F0A3FA4F4A4F4D136858 +:100DB000C31AB3F57A7F2ED3106001F09BFA024676 +:100DC0000B46204601F096FE204601F0B5FD10B31B +:100DD0002B7A474E002B14BF03230223737101F0BB +:100DE00087FA0EAF4FF47A730122B0FBF3F0394665 +:100DF0003060304600F002FA182302933D4B019315 +:100E000080B240F25513CDE90370009342464B4641 +:100E1000204601F0D7FD2B7A93B101F069FA002644 +:100E200007464FF48A7A95F8D900304400F0030061 +:100E30000AFB005393F8E82092B30136042EF2D156 +:100E4000C82002F0BDFB2B7A002B7FF43DAF13B01E +:100E5000BDEC028BBDE8F08FDAF8143083F00803A4 +:100E6000CAF81430594610220EA800F0D5F80DF13A +:100E70001E0308AA0AA9384600F0ECFD96E8030014 +:100E80000FAB83E803009DF834308DF844300A9BA3 +:100E90000E930EA9DDE90823204601F0FFFF21E7AC +:100EA000D3F8E02042B12B68FA2B38BFFA23BA1AE4 +:100EB0000533B2EB430FC0D3FFF7E6FB0028BCD1EC +:100EC000BEE700BF0000000000000000401DA120A0 +:100ED00026812A0BA4210020D8210020A021002057 +:100EE0009D2100209C210020E0370020B03200200E +:100EF0008C110020E4370020F1C6A7C1D068080F8C +:100F00000004004808B5054800F040FEBDE8084070 +:100F1000034A0449002003F0A1B900BFD8210020F2 +:100F2000203800208108000870B502F0E5FC094E69 +:100F3000094D3080002428683388834208D902F0A4 +:100F4000D7FC2B6804440133B4F5204F2B60F2D357 +:100F500070BD00BF14380020E837002002F07EBDCD +:100F600000F10060920000F5204002F001BD000099 +:100F7000054B1A68054B1B889B1A834202D9104403 +:100F800002F0B6BC00207047E8370020143800207B +:100F9000024B1B68184402F0B1BC00BFE8370020C8 +:100FA000024B1B68184402F0BBBC00BFE8370020AE +:100FB000064991F8243033B10023086A81F82430BF +:100FC0000822FFF7CDBF0120704700BFEC3700209B +:100FD000022802BF024B4FF400229A61704700BF03 +:100FE00000040048022802BF014B08229A617047A2 +:100FF0000004004810B50023934203D0CC5CC454D5 +:101000000133F9E710BD000003460246D01A12F979 +:10101000011B0029FAD1704702440346934202D0D3 +:1010200003F8011BFAE770472DE9F8431F4D1446FA +:1010300095F824200746884652BBDFF870909CB391 +:1010400095F824302BB92022FF2148462F62FFF764 +:10105000E3FF95F82400C0F10802A24228BF22460F +:10106000D6B24146920005EB8000FFF7C3FF95F82A +:101070002430A41B1E44F6B2082E17449044E4B258 +:1010800085F82460DBD1FFF793FF0028D7D108E073 +:101090002B6A03EB82038342CFD0FFF789FF00283E +:1010A000CBD10020BDE8F8830120FBE7EC3700201E +:1010B0002DE9F0470D46044600219046284640F2AF +:1010C0007912FFF7A9FF234620220021284601F0CC +:1010D00087FE231D02222021284601F081FE631D88 +:1010E00003222221284601F07BFEA31D0322252195 +:1010F000284601F075FE04F1080310222821284635 +:1011000001F06EFE04F1100308223821284601F098 +:1011100067FE04F1110308224021284601F060FE19 +:1011200004F1120308224821284601F059FE04F177 +:10113000140320225021284601F052FE04F1180326 +:1011400040227021284601F04BFE04F120030822C2 +:10115000B021284601F044FE04F121030822B82101 +:10116000284601F03DFE04F12207C0263B463146E9 +:1011700008222846083601F033FEB6F5A07F07F1B5 +:101180000107F3D104F1320308223146284601F069 +:1011900027FE002704F1330A94F832304FEAC709DA +:1011A0009F4209F5A47615D3B8F1000F08D1314656 +:1011B00004F599730722284601F012FE09F24F1632 +:1011C000274694F832213B1B93420CD3F01DC008F4 +:1011D000BDE8F0870AEB070308223146284601F0F4 +:1011E000FFFD0137D8E707F23313314608222846BE +:1011F00001F0F6FD08360137E3E7000013B50446B9 +:101200000846002101602346C0F803102022019007 +:1012100001F0E6FD0198231D0222202101F0E0FDEE +:101220000198631D0322222101F0DAFD0198A31D1C +:101230000322252101F0D4FD019804F108031022B6 +:10124000282101F0CDFD072002B010BDF7B5002325 +:10125000047F00910E4607221946054601F084FCE2 +:10126000731C0093012200230721284601F07CFC17 +:10127000C4B9B31C0093052223460821284601F077 +:1012800073FC0D243746B278BB1B934211D32B7FDE +:10129000A88A0734E408BBB9844294BF0020012027 +:1012A00003B0F0BDAB8ADB00083BDB08B370082459 +:1012B000E8E7FB1C0093214600230822284601F0A2 +:1012C00053FC08340137DEE7201A18BF0120E7E796 +:1012D000F7B50023047F00910E4608221946054603 +:1012E00001F042FC731CC4B9082200931146234646 +:1012F000284601F039FC1024012372785F1C013B61 +:10130000934211D32B7FA88A0734E408BBB98442E7 +:1013100094BF0020012003B0F0BDAB8ADB00083B86 +:10132000DB0873700824E7E7F319009321460023D4 +:101330000822284601F018FC08343B46DDE7201A55 +:1013400018BF0120E7E70000F8B50E460546144631 +:10135000002181223046FFF75FFE2B460822002144 +:10136000304601F03DFD7CB96B1C07220821304658 +:1013700001F036FD0F2401236A785F1C013B934284 +:1013800004D3E01DC008F8BD0824F4E7EB1921469A +:101390000822304601F024FD08343B46ECE700000B +:1013A000F8B50E46054614460021CE223046FFF71A +:1013B00033FE2B4628220021304601F011FD7CB976 +:1013C00005F1080308222821304601F009FD3024E8 +:1013D0002F462A7A7B1B934204D3E01DC008F8BD38 +:1013E0002824F5E707F1090321460822304601F0D9 +:1013F000F7FC08340137ECE7F7B5047F00910E469F +:10140000012310220021054601F0AEFBC4B9B31C34 +:101410000093092223461021284601F0A5FB192438 +:1014200037467288BB1B9A4211D82B7FA88A073493 +:10143000E408BBB9844294BF0020012003B0F0BD92 +:10144000AB8ADB00103BDB0873801024E8E73B1D10 +:101450000093214600230822284601F085FB08342A +:101460000137DEE7201A18BF0120E7E730B5094D44 +:101470000A4491420DD011F8013B5840082340F333 +:101480000004013B2C4013F0FF0384EA5000F6D126 +:10149000EFE730BD2083B8EDF7B5384A10685168E2 +:1014A0006B4603C36A4636493648082302F036FFC6 +:1014B0000446002833D10A25334A106851686B4628 +:1014C00003C36A4631492F48082302F027FF044628 +:1014D000002849D00369B3F5583F45D8B0F86610E5 +:1014E00040F2264291423FD1294A024402F15C0176 +:1014F0008B4239D35C3B234900209E1AFFF7B6FF8D +:101500003246074604F164010020FFF7AFFFA368ED +:101510009F4229D1E368984208BF002524E003696F +:10152000B3F5583F27D8418B40F22642914220D153 +:10153000174A024402F110018B4218D3103B1149A3 +:1015400000209D1AFFF792FF2A46064604F1180173 +:101550000020FFF78BFFA3689E4202D1E368984208 +:1015600001D00D25A8E70025284603B0F0BD1025C1 +:10157000A2E70C25A0E70B259EE700BF1844000852 +:10158000DC5F030000A0000821440008905F030016 +:101590000860FFF710B5037C044613B9006802F039 +:1015A000A5FE204610BD00000023BFF35B8FC36083 +:1015B000BFF35B8FBFF35B8F8360BFF35B8F7047BD +:1015C000BFF35B8F0068BFF35B8F704770B5054654 +:1015D0000C30FFF7F5FF05F1080604463046FFF72B +:1015E000EFFFA04206D930466D68FFF7E9FF2544BA +:1015F000281A70BD3046FFF7E3FF201AF9E7000014 +:1016000070B50546406898B105F10800FFF7D8FFAE +:1016100005F10C0604463046FFF7D2FF84423046FF +:1016200094BF6D680025FFF7CBFF013C2C44201AC6 +:1016300070BD000038B50C460546FFF7C7FFA04255 +:1016400010D305F10800FFF7BBFF04446868B4FB42 +:10165000F0F100FB1144BFF35B8F0120AC60BFF3DE +:101660005B8F38BD0020FCE72DE9F04114460746AA +:101670000D46FFF7C5FF844228BF0446D4B1B846E3 +:1016800058F80C6B4046FFF79BFF304428604046FB +:101690007E68FFF795FF331A9C4203D86C600120E7 +:1016A000BDE8F0816B60A41B3B68AB602044E86040 +:1016B0000220F5E72046F3E738B50C460546FFF76C +:1016C0009FFFA04210D305F10C00FFF779FF0444FF +:1016D0006868B4FBF0F100FB1144BFF35B8F01209D +:1016E000EC60BFF35B8F38BD0020FCE72DE9FF41C4 +:1016F000884669460746FFF7B7FF6C4606B204EB1B +:10170000C6060025B44209D06268206808EB0501CE +:10171000FFF770FC636808341D44F3E72946384638 +:10172000FFF7CAFF284604B0BDE8F081F8B50546CA +:101730000C300F46FFF744FF05F10806044630461B +:10174000FFF73EFFA042304688BF6C68FFF738FFC6 +:10175000201A386020B130462C68FFF731FF204452 +:10176000F8BD000073B5144606460D46FFF72EFF80 +:10177000844228BF04460190DCB101A93046FFF73E +:10178000D5FF019B33B93268C5E90233C5E90024AE +:1017900001200CE09C4238BF0194286001986860E9 +:1017A0008442F5D93368AB60241AEC60022002B0A1 +:1017B00070BD2046FBE700002DE9FF410F4669465A +:1017C000FFF7D0FF6C4600B204EBC0050026AC4228 +:1017D00009D0D4F8048054F8081BB8194246FFF722 +:1017E00009FC4644F3E7304604B0BDE8F081000050 +:1017F00038B50546FFF7E0FF044601462846FFF7E7 +:1018000019FF204638BD000010B4026854681A461B +:1018100023465DF8044B18470020704700207047AE +:1018200070470000002070470E20704700F5805080 +:1018300090F8C800C0F340007047000000F58050E9 +:1018400090F9D0007047000000F58050C0F8CC102F +:1018500001207047F7B50C68BDF8207014F00054F3 +:1018600070D10D7B082D6DD8302585F31188456921 +:10187000AE6876010CD4AC68240108D4AC6814F0CE +:1018800080545DD184F31188204603B0F0BD01245B +:101890000E6804F1180C002EB8BFF6004FEA0C1CBD +:1018A000B4BF46F00406760545F80C600E680FFAE2 +:1018B00084FC16F0804F18BF05EB0C1E05EB0C1CCA +:1018C0001EBFDEF8806146F00206CEF880610E7B16 +:1018D000CCF8846105EB04158E68C5F88C614E6800 +:1018E000C5F88861DCF8805145F00105CCF88051DD +:1018F00000EB441641F268052E4405EB44150544FF +:10190000C6E9002308350E4601F10C0C56F804EB2D +:1019100045F804EB6645F9D1843436882E8000EB17 +:10192000441407F00305267926F00B06354325718C +:10193000002484F31188009700F0FCFC0120A4E748 +:101940000224A5E74FF0FF309FE7000013B500F534 +:1019500080540191E06DFFF753FE1F280AD90199C9 +:10196000E06D2022FFF7C2FEA0F12003584258414B +:1019700002B010BD0020FBE708B5302383F31188C7 +:1019800000F58050C06DFFF70FFE002383F3118830 +:1019900008BD0000002202608281426082607047C0 +:1019A00010B500220023C0E9002300230446038170 +:1019B0000C30FFF7EFFF204610BD0000F0B50546E4 +:1019C00000F580500C4690F8C83013F0040FC3F3B4 +:1019D000800108BF114661F3820304F1840680F898 +:1019E000C83005EB461389B01B79D8072ED57AB3DA +:1019F00019072DD46846FFF7D3FF05EB441303F511 +:101A0000835303F1180703AA103318685968144662 +:101A100003C40833BB422246F7D1186820609B8874 +:101A2000A380DDE90E23CDE900230123ADF80830C2 +:101A30002B686946DB6B2846984705EB46152B79E2 +:101A40001A075CBF43F008032B7101E0002AF4D1B0 +:101A500009B0F0BD2DE9F0479A4688B007468846A0 +:101A60009146302383F3118807F580546846FFF7C9 +:101A700097FFE06DFFF7AAFD1F282AD9E06D20220D +:101A80006946FFF7B5FE202823D103AD444605ABD8 +:101A90002E4603CE9E4220606160354604F1080464 +:101AA000F6D130682060B388A380DDE90023C9E95E +:101AB0000023BDF80830AAF80030002383F3118812 +:101AC00053464A464146384608B0BDE8F04700F064 +:101AD0001FBC002080F3118808B0BDE8F08700002B +:101AE0002DE9F84F0023C0E90133254B044640F8A7 +:101AF000183B0F46FFF74EFF04F12800FFF750FF99 +:101B000004F1480804F5825546460835304620362B +:101B1000FFF746FFAE42F9D104F580554FF48053EC +:101B20004FF00009C5E91339C5F848800123EE6577 +:101B300004F5875804F58456C5F8549085F8583054 +:101B400085F86030083608F108084FF0000A4FF0B9 +:101B5000000B46E908ABA6F11800FFF71BFF203683 +:101B600046F8289C4645F4D185F8D07017B1054851 +:101B700000F0B8FB044B63612046BDE8F88F00BF5E +:101B8000544400082C4400080064004010B5044B85 +:101B9000197804464A1C1A70FFF7A2FF204610BDB0 +:101BA0001C3800202DE9F047002950D0294B2A4F3E +:101BB000B7FBF1F599428CBF0A231123581EB5FBE0 +:101BC000F3FC03FB1C53C4B22BB102280346F5D827 +:101BD0000020BDE8F0870CF1FF36B6F5806FF7D234 +:101BE000C4EBC40E0EF103034FEAE309C3F3C703CA +:101BF000A4EB030809F1010A4FF47A755FFA88F043 +:101C000009FB05555AFA88F8B5FBF8F5B5F5617F7B +:101C1000C1BF0EF1FF33C3F3C703E01AC0B25C1CAF +:101C200050FA84F40CFB04F4B7FBF4F4A142CFD1D6 +:101C3000013BDBB20F2BCBD80138C0B20728C7D885 +:101C40000021107116809170D3700120C1E7084601 +:101C5000BFE700BF3F420F0000B4C40470B50546A3 +:101C60000E464FF47A746B695B6803F00103B3426C +:101C700007D04FF47A7001F0A3FC013CF3D1204669 +:101C800070BD0120FCE7000030B54269936913F094 +:101C9000700F16D000230B4C936103F1840200EB0C +:101CA000421211794D0709D5890707D5416954F8C2 +:101CB00023508D60117941F0040111710133032B20 +:101CC000EBD130BD4044000873B51D46436916464C +:101CD0009A68D207044609D59A6801219960C2F32F +:101CE0004002CDE900650021FFF768FE63699A684C +:101CF000D1050BD59A684FF480719960C2F34022E8 +:101D0000CDE9006501212046FFF758FE63699A6816 +:101D1000D2030BD59A684FF480319960C2F34042E8 +:101D2000CDE9006502212046FFF748FE04F5805307 +:101D3000D3F8CC0010B103681B699847204602B065 +:101D4000BDE87040FFF7A0BFF8B50446466900291A +:101D500072D106F10C073868800770D006EB0115C8 +:101D60003868D5F8B00110F0040FD5F8B0011ABFEB +:101D7000C00840F00040400DA061D5F8B0C11CF093 +:101D8000020F1CBF40F08040A061D5F8B40106EB03 +:101D9000011100F00F0084F82400D1F8B801207779 +:101DA000D1F8B801000A6077D1F8B801000CA0772B +:101DB000D1F8B801000EE077D1F8BC0184F820001A +:101DC000D1F8BC01000A84F82100D1F8BC01000C54 +:101DD00084F82200D1F8BC11090E84F823103821B0 +:101DE000396004F1340004F1180104F1240551F8BC +:101DF000046B40F8046BA942F9D109880180C4E959 +:101E00000A2321460023238651F8283B2046DB6B1A +:101E1000984704F5805393F8C820D3F8CC0042F0DB +:101E2000040283F8C82010B103681B699847204654 +:101E3000BDE8F840FFF728BF06F110078BE7F8BDB3 +:101E400010B5044600F056FA02460B4652EA03016A +:101E500002D0013A63F100030449086820B1214629 +:101E6000BDE81040FFF770BF10BD00BF183800205C +:101E7000F0B5302181F31188DFF848C000F58351B7 +:101E80000831002404F1840500EB45152E7977070D +:101E90000ED4F6060CD5D1E9007697429E4107D2C2 +:101EA00046695CF82470B7602E7946F004062E71FE +:101EB0000134032C01F12001E4D1002383F31188C4 +:101EC000F0BD00BF4044000808B5302383F31188FB +:101ED000FFF7DAFE002383F3118808BDF8B54369E4 +:101EE0000546986800F0E050B0F1E05F0F4621D061 +:101EF000F8B1302383F3118805F58354103400269C +:101F000006F1840305EB43131B791A0706D5013646 +:101F1000032E04F12004F3D1012007E05B07F6D47F +:101F20002146384600F040FA0028F0D1002383F320 +:101F30001188F8BD0120FCE708B5302383F3118830 +:101F400000F58050C06DFFF741FB002383F311883B +:101F500043090CBF0120002008BD0000F8B51D4654 +:101F6000002313700F4606461446FFF7E5FF80F086 +:101F70000100387025B129463046FFF7AFFF2070C9 +:101F8000F8BD00002DE9B8410C4615461F468046B5 +:101F900000F0B0F90B462178024609B9287850B113 +:101FA0004046FFF765FFFFF78FFF3B462A46214675 +:101FB000FFF7D4FF0120BDE8B881000070B53026DE +:101FC00086F31188174B9A6D42F000729A659A6BEE +:101FD00042F000729A639A6B22F000729A630023B7 +:101FE00083F3118800F5805494F8C83013F001058C +:101FF00016D1A9B186F311880321132001F0DCF971 +:102000000321142001F0D8F90321152001F0D4F99F +:1020100094F8C83043F0010384F8C83085F3118880 +:1020200070BD00BF001002402DE9F04700F580555B +:1020300088B095F8D030012B04468846164600F249 +:102040008180814F57F823200AB947F82300D7F839 +:1020500000A0C4F80C802674BAF1000F64D095F883 +:10206000D030012B70D001212046FFF7A7FF30238D +:1020700083F311886269136823F0020313606269B5 +:10208000136843F001031360636900275F6187F3FE +:10209000118801212046FFF7E1FD002800F095801E +:1020A000E86DFFF781FA04F58359BA4609F108098A +:1020B000202200216846FEF7AFFF02A8FFF76AFC66 +:1020C000CDF818A06A4609EB07030DF1180E9446E7 +:1020D000BCE80300F44518605960624603F1080348 +:1020E000F5D1DCF80000186020379CF804201A7144 +:1020F000602FDDD195F8C8306FF38203002785F893 +:10210000C8306A4641462046ADF80070ADF802700E +:102110008DF80470FFF746FD636948BB4FF4004239 +:102120001A6008B0BDE8F08741F2D80002F09EF8CE +:10213000814610B15146FFF7D3FCC7F80090B9F1C2 +:10214000000F8CD10020ECE7386803681B6B9847C0 +:102150000146002887D13868FFF730FF38680368E8 +:1021600032465B684146984700287FF47CAFE9E738 +:1021700061221A609DF802309DF803201B061204AC +:1021800002F4702203F040731343BDF80020C2F341 +:10219000090213439DF804201205022E02F4E00206 +:1021A0000CBF4FF000410021134362690B43D36120 +:1021B000636913225A616269136823F00103136093 +:1021C00039462046FFF74AFD08B96369A6E795F846 +:1021D000D03093BB6169D1F8002242F00102C1F80E +:1021E00000226169D1F8002222F47C5222F00E0212 +:1021F000C1F800226169D1F8002242F46062C1F89E +:1022000000226269C2F814326269C2F8043262695B +:1022100041F6FF71C2F80C126269C2F8403262697D +:10222000C2F8443263690122C3F81C226269D2F801 +:10223000003223F00103C2F8003295F8C83043F0B1 +:10224000020385F8C8306CE71838002008B500F0A4 +:1022500051F850EA0103024602D0421E61F100012A +:10226000044B186810B10B46FFF72EFDBDE808407F +:1022700001F064B81838002008B50020FFF7E0FD31 +:10228000BDE8084001F05AB808B50120FFF7D8FDB5 +:10229000BDE8084001F052B800B59BB0EFF30981EA +:1022A00068226846FEF7A6FEEFF30583014B9B6BA1 +:1022B000FEE700BF00ED00E008B5FFF7EDFF00000E +:1022C00000B59BB0EFF3098168226846FEF792FEE5 +:1022D000EFF30583014B5B6BFEE700BF00ED00E011 +:1022E000FEE700000FB408B5029801F019F9FEE707 +:1022F00001F0F8BB01F0DABB13B56C4684E80600C8 +:10230000031D94E8030083E80500012002B010BD1E +:1023100073B58568019155B11B885B0707D4D0E977 +:1023200000369B6B9847019AC1B23046A8470120FE +:1023300002B070BDF0B5866889B005460C465EB146 +:10234000BDF838305B070AD4D0E900379B6B98475B +:102350002246C1B23846B047012009B0F0BD002284 +:102360000023CDE900230023ADF808300A4603AB73 +:1023700001F10806106851681C4603C40832B242D5 +:102380002346F7D1106820609288A280FFF7B2FF41 +:102390000423ADF808302B68CDE90001DB6B6946FA +:1023A00028469847D8E7000030B503680968DD0F74 +:1023B000B5EBD17F23F0604421F060424FEAD17049 +:1023C0000BD0002BB8BFA40C0029B8BF920C9442CC +:1023D00002D034BF0120002030BD944205D1C1F3AA +:1023E0008070C3F380738342F6D194422CBF0020E7 +:1023F0000120F1E72DE9F041456A15B94162BDE8D8 +:10240000F0814B6823F06047C3F38A464FEAD37EDE +:10241000C3F3807816EA230638BF3E46AC462B4607 +:102420005A68BEEBD27F22F060440AD0002A18DA44 +:10243000A40CB44217D19D420FD10D60DEE71346C4 +:10244000EEE7A74207D102F08044C2F38072424512 +:102450000BD054B1EFE708D2EDE7CCF800100B60D9 +:10246000CDE7B44201D0B442E5D81A689C46002AB0 +:10247000E5D11960C3E700002DE9F047089D01F0A0 +:1024800007044FEAD508224405F0070500EBD10008 +:102490004FF47F49944201D1BDE8F08704F007076B +:1024A00005F0070A57453E4638BF5646C6F10806AE +:1024B000111B8E4228BF0E46E10808EBD50E415C89 +:1024C00013F80EC0B94029FA06F721FA0AF1FFB253 +:1024D0008CEA010147FA0AF739408CEA010C03F84B +:1024E0000EC034443544D5E780EA0120082341F288 +:1024F000210201B24000002980B203F1FF33B8BFCE +:10250000504013F0FF03F4D17047000038B50C467B +:102510008D18A54200D138BD14F8011BFFF7E4FF68 +:10252000F7E7000042684AB1136843604389818934 +:1025300001339BB29942438138BF83811046704773 +:1025400070B588B0202204460D4668460021FEF78B +:1025500063FD20460495FFF7E5FF024658B16B4640 +:10256000054608AE1C4603CCB44228606960234689 +:1025700005F10805F6D1104608B070BD082817D936 +:1025800009280CD00A280CD00B280CD00C280CD011 +:102590000D280CD00E2814BF4020302070470C208E +:1025A0007047102070471420704718207047202073 +:1025B00070470000082817D90C280CD910280CD90E +:1025C00014280CD918280CD920280CD930288CBFF5 +:1025D0000F200E207047092070470A2070470B20FB +:1025E00070470C2070470D20704700002DE9F8431C +:1025F000078C072F04461ED9D0E9029800254FF614 +:10260000FF73C5F12006A5F1200029FA05F108FAAB +:1026100006F628FA00F031430143C9B21846FFF725 +:1026200063FF0835402D0346EBD1E1693A46BDE82A +:10263000F843FFF76BBF4FF6FF70BDE8F88300006B +:1026400010B54B6823B9CA8A63F30902CA8210BD68 +:1026500004691A681C600361C38A013BC3824A6033 +:10266000EFE700002DE9F84F1D46CB8A0F46C3F374 +:1026700009010529814692460B4630D00020AAB2B6 +:1026800007F11A049EB2042E1FFA80F80FD8904565 +:1026900003F1010306D3FB8A0A4462F30903FB82B8 +:1026A00001201AE01AF80060E6540130EAE790458C +:1026B000F1D2A1F1050B1C237C68BBFBF3F203FBF9 +:1026C00012BB1FFA8BF6002C45D14846FFF72AFFB4 +:1026D000044638B978606FF00200BDE8F88F4FF01B +:1026E0000008E6E7002606607860ADB24FF0000B08 +:1026F000454510D90AEB0803221D13F8011B91551B +:10270000B1B208F101081B291FFA88F82BD0454502 +:1027100006F10106F1D8FB8AC3F30902154465F3FB +:102720000903BCE7013292B21C462368002BF9D1A1 +:102730006B1F0B441C21B3FBF1F301339BB29A4294 +:10274000D3D2BBF1000FD0D14846FFF7EBFE20B942 +:10275000C4F800B0BFE70122E7E7C0F800B05E466A +:1027600020600446C1E74545D5D94846FFF7DAFE63 +:1027700008B92060AFE7C0F800B00026206004462A +:10278000B6E700002DE9F04F2DED028B1C4683B01B +:102790005B69019207468846002B00F09A80238CE3 +:1027A0002BB1E269002A00F09480072B35D807F19D +:1027B0000C00FFF7B7FE054638B96FF00205284652 +:1027C00003B0BDEC028BBDE8F08F14220021FEF7B0 +:1027D00023FC228CE16905F10800FEF70BFC208C3C +:1027E000013080B2FFF7E6FEFFF7C8FE013880B285 +:1027F0002084013028746369228C1B782A4403F0FA +:102800001F0363F03F0348F00041137238466960CC +:102810002946FFF7EFFD0125D1E700F10C034FF04A +:10282000000908EE103A4FF0800A4E464D4618EE69 +:10283000100AFFF777FE83460028BED0142200213D +:10284000FEF7EAFB002E3AD1019BABF808300222DA +:102850000BF1080E1FFA82FC0CF10100BCF1060F0F +:10286000218C80B201D88E422BD3FFF7A3FEFFF755 +:1028700085FE62691278013802F01F028E4208BF9D +:102880004FF0400A42EA49121BFA80F14AEA020A72 +:10289000013048F0004281F808A08BF81000CBF816 +:1028A000042059463846FFF7A5FD238C0135B34275 +:1028B0002DB289F001094FF0000AB8D17FE700225C +:1028C000C6E7E169895D0EF802100136B6B2013241 +:1028D000C0E76FF0010572E7F8B515460E463022E5 +:1028E000002104461F46FEF797FB069B6360B5F583 +:1028F000001F079BA76034BF6A094FF6FF72A362EF +:1029000097B2E66104F1100000239A4206D8002332 +:102910000360A782E3822383E360F8BD066001338E +:1029200030462036F1E7000003781BB94BB2002B8C +:10293000C8BF01707047000000787047F8B50C46BA +:10294000C969074611B9238C002B37D1257E1F2D6D +:1029500034D8387828BB228C072A2CD8268A36F01F +:1029600003032BD14FF6FF70FFF7D0FD20F00100DD +:102970003102400441EA0561400C41EA40254FF62E +:10298000FF72234629463846FFF7FCFE002807DD84 +:10299000626913780133DBB21F2B88BF00231370E9 +:1029A000F8BD218A2D0645EA012505432046FFF79B +:1029B0001DFE0246E5E76FF00300F1E76FF001004E +:1029C000EEE7000070B58AB00446164600212822C2 +:1029D00068461D46FEF720FBBDF83830ADF81030D4 +:1029E0000F9B05939DF840308DF81830119B07938D +:1029F0006946BDF84830ADF820302046CDE9026583 +:102A0000FFF79CFF0AB070BD2DE9F041D369054680 +:102A10000C4616460BB9138C5BBB377E1F2F28D88C +:102A200095F80080B8F1000F26D03046FFF7DEFDA4 +:102A30003378210241EAC33141EA0801338A41EA8D +:102A4000076141EA03410246334641F080012846CE +:102A5000FFF798FE00280ADD3378012B07D1726951 +:102A600013780133DBB21F2B88BF00231370BDE83E +:102A7000F0816FF00100FAE76FF00300F7E7000064 +:102A8000F0B58BB004460D46174600212822684653 +:102A90001E46FEF7C1FA9DF84C305A1E5342534170 +:102AA0008DF800309DF84030ADF81030119B059343 +:102AB0009DF848308DF81830149B07936A46BDF88E +:102AC0005430ADF8203029462046CDE90276FFF794 +:102AD0009BFF0BB0F0BD0000406A00B104307047AE +:102AE000436A1A68426202691A600361C38A013B41 +:102AF000C38270472DE9F041D0F82080194E14466A +:102B00001D464146002709B9BDE8F081D1E90223FD +:102B1000A21A65EB0303964277EB03031ED2036A06 +:102B20008B420DD1FFF78CFD036A1B6803620369BA +:102B30000B60C38A0161016A013BC3828846E2E7F8 +:102B4000FFF77EFD0B68C8F8003003690B60C38A8D +:102B50000161013BC382D8F80010D4E788460968B8 +:102B6000D1E700BF80841E002DE9F04F8BB00D46E9 +:102B7000DDF8509014469B468046002800F01981ED +:102B8000B9F1000F00F01581531E3F2B00F21181A7 +:102B9000012A03D1BBF1000F40F00B810023CDE9E6 +:102BA0000833B8F81430B5EBC30F4FEAC30703D3AB +:102BB00000200BB0BDE8F08F2B199F42D8F80C30E5 +:102BC0003ABF7F1BFFB227461BB9D8F81030002B45 +:102BD0007AD0272D4ED8C5F12806B7424FF0000312 +:102BE0002CBFF6B23E4600932946D8F8080008AB41 +:102BF0003246FFF741FCA7EB060A35445FFA8AFA32 +:102C0000B8F8143003F10053053BDB000493D8F807 +:102C10000C3003932821039B13B1BAF1000F2CD180 +:102C2000D8F8100040B1BAF1000F05D0009608ABFB +:102C30005246691AFFF720FC38B2002FB8D0660759 +:102C40000AD00AAB03EBD401624211F8083C02F04F +:102C50000702134101F8083C082C3CD9102C40F223 +:102C6000B580202C40F2B780BBF1000F00F09C80B3 +:102C7000082334E0BA460026C2E7049BE02B28BFB5 +:102C8000E02306930B44AB42059314D95A1B0398D7 +:102C90000096924534BF5246D2B2691A08AB04304E +:102CA0000792FFF7E9FB079A1644AAEB020A1544BC +:102CB000F6B25FFA8AFA049B069A05999B1A049366 +:102CC000039B1B680393A6E70093D8F8080008ABA2 +:102CD0003A462946AEE7BBF1000F13D00123B4EB0F +:102CE000C30F6CD0082C12D89DF82030621E23FA36 +:102CF00002F2D50706D54FF0FF3202FA04F423435F +:102D00008DF820309DF8203089F8003051E7102CE4 +:102D100012D8BDF82030621E23FA02F2D10706D580 +:102D20004FF0FF3202FA04F42343ADF82030BDF82F +:102D30002030A9F800303CE7202C0FD80899631EFA +:102D400021FA03F3DA0705D54FF0FF3202FA04F453 +:102D50000C430894089BC9F800302AE7402C2BD07C +:102D6000DDE90865611EC4F12102A4F1210326FA00 +:102D700001F105FA02F225FA03F311431943CB07D7 +:102D800012D50122A4F12003C4F1200102FA03F3B9 +:102D900022FA01F1A240524243EA010363EB4303EA +:102DA00032432B43CDE90823DDE90823C9E9002399 +:102DB000FFE66FF00100FCE66FF00800F9E6082C72 +:102DC000A0D9102CB3D9202CEED8C3E7BBF1000F4B +:102DD000ADD0022383E7BBF1000FBBD004237EE715 +:102DE00030B5012A144638BF0124402C85B028BFD5 +:102DF00040240025012ACDE9025518D81B788DF80A +:102E0000083063070AD004AB03EBD405624215F81F +:102E1000083C02F00702934005F8083C0091034685 +:102E20002246002102A8FFF727FB05B030BD082A83 +:102E3000E4D9102A03D81B88ADF80830E1E7202A2E +:102E40008DBFD3E900231B680293CDE90223D8E7A5 +:102E500010B5CB681BB98B600B618B8210BD046908 +:102E60001A681C600361C38A013BC382CA60F0E731 +:102E700003064CBFC0F3C0300220704708B50246BD +:102E8000FFF7F6FF022806D15306C2F30F2001D147 +:102E900000F0030008BDC2F30740FBE72DE9F04F47 +:102EA00093B0CDE903230A6804461046FFF7E0FF1C +:102EB000022814BFC2F306260026002A0D468246C9 +:102EC00080F2F28112F0C04940F0EE81097B0029C6 +:102ED00000F0EA81022803D02378B34240F0E78172 +:102EE000C2F304630693104602F07F030593FFF7D5 +:102EF000C5FF059B29444FEA834848EA0A4848EA47 +:102F00004668CE7800230022CDE90823F3098346E2 +:102F100048EA0008029367D0059B00930246676861 +:102F2000534608A92046B847002800F0C381276A05 +:102F30004FB9414604F10C00FFF702FB074690B978 +:102F40006FF0020054E03B6998450DD03F68002FB8 +:102F5000F9D1414604F10C00FFF7F2FA07460028C8 +:102F6000EED0236A3B60276297F817C006F01F086F +:102F7000CCF3840CACEB08001FFA80FE0028B8BF2D +:102F80000EF12000A8EB0C031FFA83FED7E9022103 +:102F9000B8BF00B2002B0793BEBF0EF120031BB2D7 +:102FA000079352EA010338D0039BDFF824E39A1A0F +:102FB000049B4FF0000C63EB010196457CEB010391 +:102FC0002BD36B7B97F81AE0734519D1029B002B2A +:102FD00078D0012821DC7868F8B9DFF8F0C2944590 +:102FE00070EB010316D337E0276A27B96FF00C00A6 +:102FF00013B0BDE8F08F3B699845B5D03F68F4E762 +:10300000B24890427CEB010301D30020F0E7029B21 +:10301000002BFAD0079B0F2B17DCFA7DB30002F0D0 +:10302000030203F07C031343FB7539462046FFF788 +:1030300007FB6B7BBB76029B3BB9FB7DC3F3840232 +:10304000013262F38603FB75D0E76A7BBB7E9A424E +:10305000DBD1029B002B35D0B309022B32D0039B6E +:10306000BB60049BFB60142200210DA8FDF7D4FF78 +:10307000039B0A93049B0B932B1D0C932B7BADF8A6 +:103080003EB0013BDBB2ADF83C30069B8DF84230E0 +:10309000059B8DF8433094F82C308DF840A083F0D8 +:1030A00001038DF844308DF84180A3680AA92046B9 +:1030B0009847FB7DC3F38403013303F01F039B0296 +:1030C000FB82A2E7FB7DC6F34012B2EBD31F40F0B8 +:1030D000F480C3F38403434540F0F280029A2B7BD3 +:1030E000B609002A4DD0F2075DD4032B40F2EB80E5 +:1030F000039BBB60049BFB602B7BAE1D033BDBB2E1 +:103100003246394604F10C00FFF7ACFA00280CDA1D +:1031100039462046FFF794FAFB7DC3F3840301335D +:1031200003F01F039B02FB820AE7DDE90884AB88FA +:103130003B834FF6FF73C9F12000A9F1200228FA62 +:1031400009F104FA00F0014324FA02F2114318468F +:10315000C9B2FFF7C9F909F10809B9F1400F0346EF +:10316000E9D1B8822A7B033AD2B23146FFF7CEF9D1 +:10317000FB7DB882DA43C2F3C01262F3C713FB755A +:1031800043E786B92E1D013BDBB23246394604F1D6 +:103190000C00FFF767FA0028BADB2A7BB88A013AED +:1031A000D2B23146E2E7F98AC1F30901013B0429B1 +:1031B000DAB25BD8281D002307F11B069A4208D912 +:1031C00010F801CB06F801C0013101330529DBB24B +:1031D000F4D103990A9104990B91934207F11B01D1 +:1031E0000C9138BF043379680D9134BF55FA83F3DD +:1031F00000230E93FB8AADF83EB0C3F309031A44D3 +:10320000069B8DF84230059B8DF8433094F82C30A6 +:10321000ADF83C2083F001038DF8443000238DF895 +:1032200040A08DF841807B602A7BB88A013A291D35 +:10323000FFF76CF93B8BB882834203D1A3680AA9DC +:103240002046984720460AA9FFF702FEFB7DBA8A6E +:10325000C3F38403013303F01F039B02FB823B8B08 +:103260009A420CBF00206FF01000C1E67B68002B73 +:10327000AFD0052001E01C3033461E68002EFAD185 +:10328000091A081D2E1D184401EB090CBCF11B0F77 +:103290005FFA89F39DD89A429BD916F8013B00F852 +:1032A000013B09F10109EFE76FF00900A0E66FF0BB +:1032B0000A009DE66FF00B009AE66FF00D0097E6AE +:1032C0006FF00E0094E66FF00F0091E640420F00A1 +:1032D00080841E00EFF3098305494A6B22F0010246 +:1032E0004A63683383F30988002383F311887047A6 +:1032F00000EF00E0302080F3118862B60C4B0D4ADD +:10330000D96821F4E0610904090C0A43DA60D3F8B2 +:10331000FC20094942F08072C3F8FC200A6842F0A0 +:1033200001020A602022DA7783F82200704700BF8A +:1033300000ED00E00003FA05001000E010B53023B6 +:1033400083F311880E4B5B6813F4006314D0F1EE25 +:10335000103AEFF30984683C4FF08073E361094B46 +:10336000DB6B236684F3098800F0A4F810B1064BE8 +:10337000A36110BD054BFBE783F31188F9E700BF9C +:1033800000ED00E000EF00E0FF020008020300088B +:103390004FF0E023002258684FF0FF31930003F113 +:1033A000604303F5614301329042C3F88010C3F8D3 +:1033B0008011F3D27047000000F1604303F56143D0 +:1033C0000901C9B283F80013012200F01F039A40DB +:1033D00043099B0003F1604303F56143C3F8802177 +:1033E0001A60704700230375826803691B68996837 +:1033F0009142FBD25A680360426010605860704787 +:1034000000230375826803691B6899689142FBD8A1 +:103410005A680360426010605860704708B50846FB +:10342000302383F311880B7D032B05D0042B0DD0A3 +:103430002BB983F3118808BD8B6900221A604FF005 +:10344000FF338361FFF7CEFF0023F2E7D1E90032BB +:1034500013605A60F3E70000FFF7C4BF054BD9685B +:103460000875186802681A60536001220275D860F6 +:10347000FCF730BF2838002030B50C4BDD684B1C02 +:1034800087B004460FD02B46094A684600F02AF957 +:103490002046FFF7E3FF009B13B1684600F02CF9CC +:1034A000A86907B030BDFFF7D9FFF9E72838002039 +:1034B0001D340008044B1A68DB6890689B689842CA +:1034C00094BF00200120704728380020084B10B519 +:1034D0001C68D86822681A60536001222275DC607B +:1034E000FFF78EFF01462046BDE81040FCF7F2BE14 +:1034F0002838002038B5074C074908480123002523 +:103500002370656000F0EEFB0223237085F31188C1 +:1035100038BD00BF503A00209844000828380020E9 +:1035200008B572B6044B186500F0ACFA00F05CFB0D +:10353000024B03221A70FEE728380020503A002080 +:1035400000F010B98B60022308618B820846704737 +:103550008368A3F1840243F8142C026943F8442CD5 +:10356000426943F8402C094A43F8242CC26843F8C6 +:10357000182C022203F80C2C002203F80B2C044A0E +:1035800043F8102CA3F12000704700BFED020008A3 +:103590002838002008B5FFF7DBFFBDE80840FFF73B +:1035A0005BBF0000024BDB6898610F20FFF756BF3E +:1035B00028380020302383F31188FFF7F3BF000081 +:1035C00008B50146302383F311880820FFF754FF24 +:1035D000002383F3118808BD10B503689C68A242DC +:1035E0000CD85C688A600B604C60216059609968F7 +:1035F0008A1A9A604FF0FF33836010BD1B68121B5C +:10360000ECE700000A2938BF0A2170B504460D46D0 +:103610000A26601900F060FB00F04CFB041BA54279 +:1036200003D8751C2E460446F3E70A2E04D9BDE8DC +:103630007040012000F096BB70BD0000F8B5144B3F +:103640000D46D96103F1100141600A2A19698260AF +:1036500038BF0A22016048601861A818144600F0BB +:103660002DFB0A2700F026FB431BA342064606D388 +:103670007C1C281900F030FB27463546F2E70A2F5C +:1036800004D9BDE8F840012000F06CBBF8BD00BFD4 +:1036900028380020F8B506460D4600F00BFB0F4A0F +:1036A000134653F8107F9F4206D12A460146304602 +:1036B000BDE8F840FFF7C2BFD169BB68441A2C19B6 +:1036C00028BF2C46A34202D92946FFF79BFF22467A +:1036D00031460348BDE8F840FFF77EBF2838002098 +:1036E0003838002010B4C0E9032300235DF8044BF0 +:1036F0004361FFF7CFBF000010B5194C2369984212 +:103700000DD0D0E90032816813605A609A680A448B +:103710009A60002303604FF0FF33A36110BD23467E +:10372000026843F8102F53600022026022699A4217 +:1037300003D1BDE8104000F0C9BA936881680B441A +:10374000936000F0B7FA2269E1699268441AA242D4 +:10375000E4D91144BDE81040091AFFF753BF00BF78 +:10376000283800202DE9F047DFF8BC8008F1100769 +:103770002C4ED8F8105000F09DFAD8F81C40AA68DA +:10378000031B9A423ED81444D5E900324FF0000999 +:10379000C8F81C4013605A60C5F80090D8F8103083 +:1037A000B34201D100F092FA89F31188D5E90331CF +:1037B00028469847302383F311886B69002BD8D0B3 +:1037C00000F078FA6A69A0EB04094A4582460DD2F6 +:1037D000022000F0C7FA0022D8F81030B34208D116 +:1037E00051462846BDE8F047FFF728BF121A224489 +:1037F000F2E712EB090938BF4A4629463846FFF777 +:10380000EBFEB5E7D8F81030B34208D01444211AC3 +:10381000C8F81C00A960BDE8F047FFF7F3BEBDE89B +:10382000F08700BF383800202838002038B500F075 +:1038300041FA054AD2E90845031B181945F1000170 +:10384000C2E9080138BD00BF2838002000207047B9 +:10385000FEE70000704700004FF0FF3070470000A7 +:10386000BFF34F8F024A1369DB03FCD4704700BFDC +:103870000020024008B5094B1B7873B9FFF7F0FF31 +:10388000074B5A69002ABFBF064A9A6002F1883284 +:103890009A601A6822F480621A6008BD683A0020B3 +:1038A000002002402301674508B50B4B1B7893B9F4 +:1038B000FFF7D6FF094B5A6942F000425A611A6875 +:1038C00042F480521A601A6822F480521A601A6810 +:1038D00042F480621A6008BD683A0020002002406D +:1038E0007F289ABF00F58030C0020020704700009A +:1038F0004FF4006070470000802070477F2808B5B3 +:103900000BD8FFF7EDFF00F500630268013204D128 +:1039100004308342F9D1012008BD0020FCE70000FB +:103920007F2810B504461FD8FFF79AFFFFF7A2FFC4 +:103930000E4BF3221A6102225A615A6942EAC0020E +:103940005A615A6942F480325A61FFF789FF4FF495 +:103950000061FFF7C5FF00F043F9FFF7A5FF204620 +:10396000BDE81040FFF7CABF002010BD0020024094 +:103970002DE9F84340EA020313F00703144606D08A +:10398000304B40F241321A600020BDE8F8838518C0 +:103990002D4A95420CD92B4A40F246311160F3E78B +:1039A000031D1B684A68934208D1083C083008315F +:1039B000072C14D902680B689A42F1D0FFF75AFF1E +:1039C000FFF74EFF214E08314FF001084FF000097C +:1039D000012CA1F1080706D8FFF766FF01E0002CD3 +:1039E000ECD10120D1E7C6F81480054651F8083C17 +:1039F00045F8043B51F8043C4360FFF731FF33695D +:103A000043F001033361C6F81490026851F8083C92 +:103A10009A420CD00B4B40F26E321A600C4B18607D +:103A20000C4B1C600C4B1F60FFF73EFFACE72D6892 +:103A300051F8043C9D4201F10801EBD1083C0830EB +:103A4000C6E700BF643A00200000040800200240DE +:103A5000583A0020603A00205C3A0020084908B536 +:103A60000B7828B11BB9FFF705FF01230B7008BDC8 +:103A7000002BFCD0BDE808400870FFF715BF00BF61 +:103A8000683A002002484FF47F4100F0ABB800BF15 +:103A9000000100200846114600F00ABC012000F099 +:103AA00007BC0000084600F021BC000038B5EFF369 +:103AB00011859DB9EFF30584C4F30804302334B1B4 +:103AC00083F31188FFF7B2FE85F3118838BD83F3C5 +:103AD0001188FFF7ABFE84F3118838BDBDE838408C +:103AE000FFF7A4BE38B5FFF7E1FF114C114AC0083B +:103AF00040EA4170A0FB025EC908A0FB040C1CEB6D +:103B0000050CA1FB04404FF000035B41A1FB021236 +:103B10001CEB040C43EB000011EB0E0142F1000220 +:103B2000411842F10000090941EA007038BD00BFA8 +:103B3000CFF753E3A59BC42010B50244064BD2B285 +:103B4000904200D110BD441C00B253F8200041F84F +:103B5000040BE0B2F4E700BF50280040114B30B531 +:103B6000D3F89040240409D4D3F89040C3F890408F +:103B7000D3F8904044F40044C3F890400A4C2368C2 +:103B800043F4807323600244084BD2B2904200D1C8 +:103B900030BD441C00B251F8045B43F82050E0B241 +:103BA000F4E700BF001002400070004050280040C1 +:103BB00007B5012201A90020FFF7BEFF019803B05D +:103BC0005DF804FB13B50446FFF7F2FFA04205D0F1 +:103BD000012201A900200194FFF7C0FF02B010BD2F +:103BE000704700007047000070470000074B45F227 +:103BF00055521A6002225A6040F6FF729A604CF6E3 +:103C0000CC421A60024B01221A707047003000400B +:103C1000703A0020034B1B781BB1034B4AF6AA22D3 +:103C20001A607047703A002000300040054B1A6857 +:103C300032B902F1804202F50432D2F894201A60BF +:103C4000704700BF6C3A0020024B4FF40002C3F8EB +:103C5000942070470010024008B5FFF7E7FF024BC1 +:103C60001868C0F3407008BD6C3A0020704700002F +:103C7000FEE700000A4B0B480B4A90420BD30B4B5C +:103C8000DA1C121AC11E22F003028B4238BF002236 +:103C90000021FDF7C1B953F8041B40F8041BECE701 +:103CA0002C450008FC3A0020FC3A0020FC3A002099 +:103CB00000F0BEB84FF08043586A70474FF0804321 +:103CC000002258631A610222DA6070474FF0804385 +:103CD0000022DA60704700004FF08043586370475D +:103CE000FEE7000070B51B4B01630025044686B05B +:103CF000586085620E46FFF7FDFA04F11003C4E92F +:103D000004334FF0FF33C4E90635C4E90044A5602D +:103D1000E562FFF7CFFF2B460246C4E9082304F112 +:103D200034010D4A256580232046FFF70BFC012353 +:103D3000E0600A4A0375009272680192B268CDE9A8 +:103D40000223074B6846CDE90435FFF723FC06B094 +:103D500070BD00BF503A0020A4440008A9440008E8 +:103D6000E13C0008024AD36A1843D062704700BFA2 +:103D700028380020244B2548DA6A42F0070210B4A4 +:103D8000DA62DA6A224C22F00702DA62DA6ADA6C64 +:103D900042F00702DA64DA6E42F00702DA664FF0A8 +:103DA0009042DB6E4FF0AA31002353609160D060E7 +:103DB0004FF6FF7050611362536214601024C2F812 +:103DC0000434C2F80814C2F80C444FF6F774C2F871 +:103DD00014449924C2F82034C2F824440D4CC2F88B +:103DE0000044C2F80438C2F80818C2F80C38C2F807 +:103DF0001408C2F82038C2F82438C2F800385DF838 +:103E0000044B00F055B800BF001002400001002430 +:103E10000001002850000A0008B500F005FAFFF77D +:103E200069FBBDE80840FFF701BF000070470000D4 +:103E30000F4B9A6D42F001029A659A6F42F00102AF +:103E40009A670C4A9B6F936843F0010393604FF0AD +:103E500080434F229A624FF0FF32DA6200229A6169 +:103E60005A63DA605A6001225A611A60704700BFD3 +:103E700000100240002004E04FF0804208B51169B4 +:103E8000D3680B40D9B2C9439B07116107D53023D2 +:103E900083F31188FFF754FB002383F3118808BDD7 +:103EA00008B5FFF775FABDE8084000F099B90000C1 +:103EB0005A4B4FF0FF319A6A99629A6A00229A62CD +:103EC000986AD86A60F00700D862D86A00F00700E4 +:103ED000D862D86A186B1963186B1A63186B986BE1 +:103EE0009963986B9A63986BD86BD963D86BDA63D4 +:103EF000D86B186C1964196C1A641A6C484A4FF420 +:103F0000E06111601A6E474942F001021A66D3F867 +:103F1000802022F00102C3F88020D3F880209A6D1F +:103F200042F080529A659A6F22F080529A679A6F97 +:103F30004FF440720A604A6912F48062FBD14A6011 +:103F40001A6822F0F00242F060021A601A6842F029 +:103F500001021A601A689107FCD500229A609A68DB +:103F600012F00C02FBD1D3F8901011F4407F1EBF69 +:103F70004FF48031C3F89010C3F8902061221A608A +:103F80001A689207FCD500229A609A6812F00C0F0A +:103F9000FBD169221A60D3F8942022F4706242F4B3 +:103FA000C062C3F894201A6842F480321A601A681A +:103FB0009003FCD5D3F8902022F00322C3F8902080 +:103FC000194ADA601A6842F080721A601A68910120 +:103FD000FCD5164A1A611A6842F080621A601A68A3 +:103FE0001201FCD500229A600D49114AC3F88820BD +:103FF0000A6822F0070242F004020A600A6802F02E +:104000000702042AFAD19A6842F003029A609A6879 +:1040100002F00C020C2AFAD1704700BF00100240D7 +:10402000002002400070004003140001000C10004A +:1040300055550134074A08B5536903F0010353612C +:1040400023B1054A13680BB150689847BDE8084092 +:10405000FFF774B900040140743A0020074A08B51C +:10406000536903F00203536123B1054A93680BB10E +:10407000D0689847BDE80840FFF760B900040140E8 +:10408000743A0020074A08B5536903F004035361EA +:1040900023B1054A13690BB150699847BDE8084040 +:1040A000FFF74CB900040140743A0020074A08B5F4 +:1040B000536903F00803536123B1054A93690BB1B7 +:1040C000D0699847BDE80840FFF738B900040140BF +:1040D000743A0020074A08B5536903F0100353618E +:1040E00023B1054A136A0BB1506A9847BDE80840EE +:1040F000FFF724B900040140743A0020164B10B5B4 +:104100005C6904F478725A61A30604D5134A936A71 +:104110000BB1D06A9847600604D5104A136B0BB1F7 +:10412000506B9847210604D50C4A936B0BB1D06BAA +:104130009847E20504D5094A136C0BB1506C9847B7 +:10414000A30504D5054A936C0BB1D06C9847BDE824 +:104150001040FFF7F3B800BF00040140743A00209C +:10416000194B10B55C6904F47C425A61620504D5B0 +:10417000164A136D0BB1506D9847230504D5134AA9 +:10418000936D0BB1D06D9847E00404D50F4A136EC0 +:104190000BB1506E9847A10404D50C4A936E0BB135 +:1041A000D06E9847620404D5084A136F0BB1506F64 +:1041B0009847230404D5054A936F0BB1D06F9847F5 +:1041C000BDE81040FFF7BAB800040140743A00207F +:1041D00008B5FFF751FEBDE80840FFF7AFB8000093 +:1041E000062108B50846FFF7E7F806210720FFF784 +:1041F000E3F806210820FFF7DFF806210920FFF782 +:10420000DBF806210A20FFF7D7F806211720FFF771 +:10421000D3F806212820FFF7CFF8BDE80840072192 +:104220001C20FFF7C9B8000008B5FFF739FE00F001 +:1042300007F8FFF7FBFDBDE80840FFF739BD0000B8 +:104240000023054A19460133102BC2E9001102F17F +:104250000802F8D1704700BF743A00200B460146AF +:10426000184600F02DB8000000F040B8012838BF13 +:10427000012010B50446204600F030F830B900F0B7 +:1042800007F808B900F00CF88047F4E710BD00000B +:10429000024B1868BFF35B8F704700BFF43A0020F1 +:1042A00008B5062000F084F80120FFF7D1FA0000DD +:1042B000024B0A4601461868FFF7ECBB18110020B4 +:1042C00010B5054C13462CB10A4601460220AFF347 +:1042D000008010BD2046FCE700000000024B0146B4 +:1042E0001868FFF7DBBB00BF18110020024B014626 +:1042F0001868FFF7D7BB00BF1811002010B50139AF +:104300000244904201D1002005E0037811F8014FEA +:10431000A34201D0181B10BD0130F2E72DE9F04196 +:10432000A3B1C91A17780144044603F1FF3C8C423B +:10433000204601D9002009E00578BD4204F10104BE +:10434000F5D10CEB0405D618A54201D1BDE8F081EA +:1043500015F8018D16F801EDF045F5D0E7E70000FE +:104360001F2938B504460D4604D9162303604FF0C3 +:10437000FF3038BD426C12B152F821304BB92046A3 +:1043800000F030F82A4601462046BDE8384000F0EB +:1043900017B8012B0AD0591C03D116230360012042 +:1043A000E7E7002442F82540284698470020E0E748 +:1043B000024B01461868FFF7D3BF00BF1811002059 +:1043C00038B5074D00230446084611462B60FFF719 +:1043D00043FA431C02D12B6803B1236038BD00BFF0 +:1043E000F83A0020FFF732BA034611F8012B03F820 +:1043F000012B002AF9D170476F72672E61726475C4 +:1044000070696C6F742E4D6174656B4C3433312D53 +:10441000506572697068000040A2E4F1646891061A +:104420000041A3E5F2656992070000004261642043 +:1044300043414E496661636520696E6465782E006C +:1044400080000000008000000000800000000000EC +:10445000000000000918000829200008851F000836 +:104460004918000855180008551A000819180008BE +:10447000291800081D180008251800082118000830 +:10448000791900082D180008F92200083D180008C5 +:104490004D19000863300000944400088038002063 +:1044A000503A00206D61696E0069646C650000001F +:1044B000260400000000000000600300000000006F +:1044C000FE2A0100D20400001C11002000000000A0 +:1044D00000000000000000000000000000000000DC +:1044E00000000000000000000000000000000000CC +:1044F00000000000000000000000000000000000BC +:1045000000000000000000000000000000000000AB +:10451000000000000000000000000000000000009B +:0C4520000000000000000000000000008F :00000001FF diff --git a/Tools/bootloaders/MatekL431-Proximity_bl.bin b/Tools/bootloaders/MatekL431-Proximity_bl.bin index ce388fb8439813..c5b65e7ac25e36 100755 Binary files a/Tools/bootloaders/MatekL431-Proximity_bl.bin and b/Tools/bootloaders/MatekL431-Proximity_bl.bin differ diff --git a/Tools/bootloaders/MatekL431-RC_bl.bin b/Tools/bootloaders/MatekL431-RC_bl.bin index 49bf5329c25df3..6e63c57fb8ea44 100755 Binary files a/Tools/bootloaders/MatekL431-RC_bl.bin and b/Tools/bootloaders/MatekL431-RC_bl.bin differ diff --git a/Tools/bootloaders/MatekL431-Rangefinder_bl.bin b/Tools/bootloaders/MatekL431-Rangefinder_bl.bin index bab890793634ce..3dc296d2fe3363 100755 Binary files a/Tools/bootloaders/MatekL431-Rangefinder_bl.bin and b/Tools/bootloaders/MatekL431-Rangefinder_bl.bin differ diff --git a/Tools/bootloaders/MatekL431-Serial_bl.bin b/Tools/bootloaders/MatekL431-Serial_bl.bin index 80b78370907fa8..657d8e11630bf9 100755 Binary files a/Tools/bootloaders/MatekL431-Serial_bl.bin and b/Tools/bootloaders/MatekL431-Serial_bl.bin differ diff --git a/Tools/bootloaders/MatekL431-bdshot_bl.bin b/Tools/bootloaders/MatekL431-bdshot_bl.bin index 5c422467a3ca09..7ae5e09ea5f11c 100755 Binary files a/Tools/bootloaders/MatekL431-bdshot_bl.bin and b/Tools/bootloaders/MatekL431-bdshot_bl.bin differ diff --git a/Tools/bootloaders/Nucleo-G491_bl.bin b/Tools/bootloaders/Nucleo-G491_bl.bin index f7939575c7a403..495bcdfae2d248 100755 Binary files a/Tools/bootloaders/Nucleo-G491_bl.bin and b/Tools/bootloaders/Nucleo-G491_bl.bin differ diff --git a/Tools/bootloaders/Nucleo-G491_bl.elf b/Tools/bootloaders/Nucleo-G491_bl.elf index 8b3b6d6c5a9112..6f47c8397ac5e1 100755 Binary files a/Tools/bootloaders/Nucleo-G491_bl.elf and b/Tools/bootloaders/Nucleo-G491_bl.elf differ diff --git a/Tools/bootloaders/Nucleo-G491_bl.hex b/Tools/bootloaders/Nucleo-G491_bl.hex index 048444290b5b45..8234019cd1b8a9 100644 --- a/Tools/bootloaders/Nucleo-G491_bl.hex +++ b/Tools/bootloaders/Nucleo-G491_bl.hex @@ -1,1194 +1,1170 @@ :020000040800F2 -:1000000000070020F5040008552800080D28000806 -:10001000352800080D2800082D280008F7040008DE -:10002000F7040008F7040008F70400083538000852 -:10003000F7040008F7040008F7040008F7040008B4 -:10004000F7040008F7040008F7040008F7040008A4 -:10005000F7040008F7040008A9450008D145000886 -:10006000F94500082146000849460008F704000841 -:10007000F7040008F7040008F7040008F704000874 -:10008000F7040008F7040008F7040008F704000864 -:10009000F7040008ED270008FD2700087146000856 -:1000A000F7040008F7040008F7040008F704000844 -:1000B00045470008F7040008F7040008F7040008A3 -:1000C000F7040008F7040008F7040008F704000824 -:1000D000F7040008F7040008F7040008F704000814 -:1000E000D5460008F7040008F7040008F7040008E4 -:1000F000F7040008F7040008F7040008F7040008F4 -:10010000F7040008F7040008F7040008F7040008E3 -:10011000F7040008F7040008F7040008F7040008D3 -:10012000F7040008F7040008F7040008F7040008C3 -:10013000F7040008F7040008F7040008F7040008B3 -:10014000F7040008F7040008F7040008F7040008A3 -:10015000F7040008F7040008F7040008F704000893 -:10016000F7040008F7040008F7040008F704000883 -:10017000F7040008F7040008F7040008F704000873 -:10018000F7040008F7040008F7040008F704000863 -:10019000F7040008F7040008F7040008F704000853 -:1001A000F7040008F7040008F7040008F704000843 -:1001B000F7040008F7040008F7040008F704000833 -:1001C000F7040008F7040008F7040008F704000823 -:1001D000F7040008F7040008F7040008F704000813 -:1001E0006512000800000000000000000000000090 -:1001F00053B94AB9002908BF00281CBF4FF0FF318E -:100200004FF0FF3000F074B9ADF1080C6DE904CE89 -:1002100000F006F8DDF804E0DDE9022304B07047E1 -:100220002DE9F047089D04468E46002B4DD18A42A9 -:10023000944669D9B2FA82F252B101FA02F3C2F1DC -:10024000200120FA01F10CFA02FC41EA030E94406D -:100250004FEA1C48210CBEFBF8F61FFA8CF708FB8E -:1002600016E341EA034306FB07F199420AD91CEB66 -:10027000030306F1FF3080F01F81994240F21C8198 -:10028000023E63445B1AA4B2B3FBF8F008FB1033E0 -:1002900044EA034400FB07F7A7420AD91CEB040415 -:1002A00000F1FF3380F00A81A74240F207816444E5 -:1002B000023840EA0640E41B00261DB1D44000236A -:1002C000C5E900433146BDE8F0878B4209D9002DCE -:1002D00000F0EF800026C5E9000130463146BDE858 -:1002E000F087B3FA83F6002E4AD18B4202D38242C2 -:1002F00000F2F980841A61EB030301209E46002D71 -:10030000E0D0C5E9004EDDE702B9FFDEB2FA82F2C5 -:10031000002A40F09280A1EB0C014FEA1C471FFA23 -:100320008CFE0126200CB1FBF7F307FB131140EA0A -:1003300001410EFB03F0884208D91CEB010103F1D7 -:10034000FF3802D2884200F2CB804346091AA4B299 -:10035000B1FBF7F007FB101144EA01440EFB00FE6D -:10036000A64508D91CEB040400F1FF3102D2A645D2 -:1003700000F2BB800846A4EB0E0440EA03409CE771 -:10038000C6F12007B34022FA07FC4CEA030C20FA1E -:1003900007F401FA06F31C43F9404FEA1C4900FA3E -:1003A00006F3B1FBF9F8200C1FFA8CFE09FB1811BB -:1003B00040EA014108FB0EF0884202FA06F20BD92E -:1003C0001CEB010108F1FF3A80F08880884240F27E -:1003D0008580A8F102086144091AA4B2B1FBF9F0C2 -:1003E00009FB101144EA014100FB0EFE8E4508D9BD -:1003F0001CEB010100F1FF346CD28E456AD9023842 -:10040000614440EA0840A0FB0294A1EB0E01A14226 -:10041000C846A64656D353D05DB1B3EB080261EB94 -:100420000E0101FA07F722FA06F3F1401F43C5E96E -:10043000007100263146BDE8F087C2F12003D840A4 -:100440000CFA02FC21FA03F3914001434FEA1C47E6 -:100450001FFA8CFEB3FBF7F007FB10360B0C43EAD8 -:10046000064300FB0EF69E4204FA02F408D91CEB88 -:10047000030300F1FF382FD29E422DD90238634486 -:100480009B1B89B2B3FBF7F607FB163341EA034126 -:1004900006FB0EF38B4208D91CEB010106F1FF3875 -:1004A00016D28B4214D9023E6144C91A46EA00466C -:1004B00038E72E46284605E70646E3E61846F8E6FE -:1004C0004B45A9D2B9EB020864EB0C0E0138A3E747 -:1004D0004646EAE7204694E74046D1E7D0467BE728 -:1004E000023B614432E7304609E76444023842E7A0 -:1004F000704700BF02E000F000F8FEE772B6374830 -:1005000080F30888364880F3098836483649086001 -:1005100040F20000CCF200004EF63471CEF2000141 -:100520000860BFF34F8FBFF36F8F40F20000C0F23F -:10053000F0004EF68851CEF200010860BFF34F8FF5 -:10054000BFF36F8F4FF00000E1EE100A4EF63C71E2 -:10055000CEF200010860062080F31488BFF36F8F8D -:1005600003F052FE03F0E4FE4FF055301F491B4AE2 -:1005700091423CBF41F8040BFAE71D49184A9142E9 -:100580003CBF41F8040BFAE71A491B4A1B4B9A423D -:100590003EBF51F8040B42F8040BF8E7002018495D -:1005A000184A91423CBF41F8040BFAE703F030FED1 -:1005B00003F004FF144C154DAC4203DA54F8041B4D -:1005C0008847F9E700F042F8114C124DAC4203DACB -:1005D00054F8041B8847F9E703F018BE0007002011 -:1005E000002300200000000808ED00E000010020CA -:1005F00000070020F8490008002300207C23002089 -:1006000080230020D8500020E0010008E401000809 -:10061000E4010008E40100082DE9F04F2DED108AF7 -:10062000C1F80CD0C3689D46BDEC108ABDE8F08FC0 -:10063000002383F311882846A047002003F090FA96 -:10064000FEE703F0F3F900DFFEE70000F8B500F085 -:100650001BFE03F07BFD074603F0CCFD0546D0BB37 -:10066000294B9F4237D001339F4237D0274B27F089 -:10067000FF029A4235D1F8B200F03EFC2E4642F21B -:10068000107400F03FFC08B10024264601F0B4F8D5 -:1006900058B3032000F03EF80024264635B11C4B29 -:1006A0009F4203D003F09EFD00242646002003F065 -:1006B00057FD0EB100F044F800F056FC00F0E6FDE6 -:1006C00002F0D0F80546B4B900F096FC4FF47A7009 -:1006D00003F04CFAF7E72E460024D2E70446012641 -:1006E000CFE706464FF47A74CBE7002CD6D04FF410 -:1006F0007A740126D2E702F0B5F8431BA342E3D98E -:1007000000F01EF8DCE700BF010007B0000008B0F1 -:10071000263A09B0084B187003280CD8DFE800F01F -:1007200008050208022000F00DBE022000F002BE03 -:10073000024B00225A60704780230020842300204F -:1007400010B501F059F830B1234B03221A70234B36 -:1007500000225A6010BD224B224A1C461968013102 -:10076000F8D004339342F9D16268A242F2D31E4B0F -:100770009B6803F1006303F520439A42EAD203F039 -:1007800003FD03F015FD002000F09AFD0220FFF7A5 -:10079000C1FF164B9A6D00229A65996F9A67996FFF -:1007A000D96DDA65D96FDA67D96F196E1A66D3F821 -:1007B0008010C3F88020D3F8803072B64FF0E02369 -:1007C0003021C3F8084DD4E9003281F311889D46E9 -:1007D00083F308881047BDE780230020842300208E -:1007E00000A0000820A00008002300200010024004 -:1007F000094A136849F2690099B21B0C00FB0133E6 -:100800001360064B186844F2506182B2000C01FB81 -:100810000200186080B270471423002010230020CB -:1008200010B500211022044600F0A6FD034B03CBB7 -:10083000206061601868A06010BD00BF9075FF1F48 -:100840002DE9F041ADF54E7D0DF134086CAC40F270 -:10085000751207460D460EA80021C8F8001000F0DA -:100860008BFD4FF4C4720021204600F085FD01F09D -:10087000F9FF254B4FF47A72B0FBF2F0186093E861 -:100880000700022384E807000DF5E9702382FFF7D3 -:10089000C7FF41F204031D49238406A803F0E8FFC3 -:1008A000192384F832310DF2E32206AB0DF1300C3E -:1008B0001E4603CE664510605160334602F10802C1 -:1008C000F6D13378137041460122204600F0A0FD96 -:1008D00000230393AB7E029305F11903019380B2C9 -:1008E0000123CDE904800093E97E05A3D3E9002329 -:1008F000384602F075FB0DF54E7DBDE8F08100BF76 -:100900009E6AC421818A46EE8C230020804800081C -:100910002DE9F0412C4C237ADAB080460D465BBBC2 -:1009200027A9284600F084FE0746002842D19DF8FA -:100930009D60C82E3ED801464FF4A662204600F0C6 -:100940001BFD4FF48073C4F8F8314FF40073C4F802 -:100950000C334FF44073C4F8203432460DF19E013D -:1009600004F1090000F0F6FC26449DF89C307772F3 -:1009700023720BB9EB7E23728122002106AC27A8DB -:1009800000F0FAFC0122214627A800F08DFE00238A -:100990000393AB7E029305F1190380B201932823E0 -:1009A000CDE904400093E97E05A3D3E90023404646 -:1009B00002F016FB5AB0BDE8F08100BFAFF3008033 -:1009C00026417272DF25D7B788480020F0B5254E42 -:1009D0004FF48A7505FB0065F1B096F8D83085F8BC -:1009E000DC300024D822214685F8E8403AA800F0FF -:1009F000C3FC06F1090000F0B7FCD5F8E4308DF82F -:100A0000F000C2B206AF06F109010DF1F100CDE927 -:100A10003A3400F09FFC394601223AA800F070FEFB -:100A200080B2CDE9047008230127CDE9023706F131 -:100A3000D803019330230093317A0B4807A3D3E9FD -:100A4000002302F0CDFAA04206DD01F00BFFC5F84D -:100A5000E000384671B0F0BD2046FBE778F6339FE2 -:100A600093CACD8D88480020A43300202DE9F041A1 -:100A70001D4D1E4E1E4F86B0284602F0DDFA03467D -:100A800058B30024CDE90344ADF81440027B8DF83F -:100A9000142099684068029403AA03C21B68DFF817 -:100AA000548043F00043029301F0DEFE821941F1CD -:100AB0000003009402A9384601F0B6F8A04205DD13 -:100AC000284602F0BDFA88F80040D5E798F80030D3 -:100AD000072B05D8013388F8003006B0BDE8F08157 -:100AE000014802F0ADFAF8E7A433002040420F00BD -:100AF000D8330020BD4D002070B50D4614461E466B -:100B000002F0CAF950B9022E10D1012C0ED112A355 -:100B1000D3E90023C5E90023012007E0282C10D0E9 -:100B200005D8012C09D0052C0FD0002070BD302C29 -:100B3000FBD10BA3D3E90023ECE70BA3D3E90023FC -:100B4000E8E70BA3D3E90023E4E70BA3D3E90023F1 -:100B5000E0E700BFAFF30080401DA12026812A0BF3 -:100B600078F6339F93CACD8D9E6AC421818A46EE62 -:100B700026417272DF25D7B7F017304A39059E56E5 -:100B800038B505460E4C0021013500F0BBFBA4F83A -:100B90002C55B4F82C0500F09DFB78B1B4F82C0569 -:100BA00000F0A8FB014648B9B4F82C0500F0AAFBF8 -:100BB000B4F82C350133A4F82C35EAE738BD00BF72 -:100BC0008848002010B50A4B0A4A1A6003F5805382 -:100BD00093F848203AB95C6C2CB1204600F086FEB0 -:100BE000204603F0FBFDBDE81040034800F07EBE48 -:100BF000D8330020CC480008084400202DE9F04FED -:100C00008FB000AF05460C4602F046F9002849D1E6 -:100C1000237E022B1BD1E38A012B18D101F022FE87 -:100C20000646FFF7E5FD03464FF4C870DFF8C482BF -:100C3000B3FBF0F206F5167602FB103316FA83F3D7 -:100C4000C8F80030E37E33B9A34B00221A703C375A -:100C5000BD46BDE8F08F07F12401204600F0A6FC58 -:100C60000028F4D107F11400FFF7DAFD97F82640C9 -:100C700007F11401224607F1270003F0C7FD002801 -:100C8000E2D10F2C08D8944B1C70D8F80030A3F593 -:100C90001673C8F80030DAE797F82410284602F0F7 -:100CA000F3F8D4E7E38A282B2BD010D8012B23D0DC -:100CB000052BCCD1BFF34F8F8849894BCA6802F40A -:100CC000E0621343CB60BFF34F8F00BFFDE7302BD3 -:100CD000BDD1844EE17E327A9142B8D1607E3146F8 -:100CE000002291F8DC50854200F0A5800132042AF0 -:100CF00001F58A71F5D1AAE721462846FFF7A0FD44 -:100D0000A5E721462846FFF703FEA0E7B2F8EC501E -:100D10007B6005F103094FEA99094FEA8902D11D69 -:100D2000C908A8EBC1039D46EB460021584600F0D8 -:100D300023FB04F1EE012A463144584600F00AFB39 -:100D40007B6813B9012000F0BBFA96F8D20000F0DE -:100D5000C1FA044630B9307200F0DCFA204600F0E7 -:100D6000AFFAB1E0D6F8D4203AB996F8D200B6F886 -:100D70002C25824201D8FFF703FFD6F8D4202A445D -:100D8000944208D296F8D200B6F82C25013082425F -:100D900001D8FFF7F5FE70685FFA89F2594600F056 -:100DA000F3FA08B9C54679E0726896F8D2002A4489 -:100DB0007260D6F8D42005EB0209C6F8D49000F092 -:100DC00089FA814509D396F8D220D6F8D4000132A9 -:100DD000001B86F8D220C6F8D400FF2D0FD80024BF -:100DE000347200F097FA204600F06AFA00F004FD31 -:100DF0003D4B188108B9FFF7A3FCC54627E7BB6840 -:100E000096F8D9000AFB0362FB68D2F8E41082F876 -:100E1000E83001F58061C2F8E030C2F8E410FFF775 -:100E2000D5FDFFF723FE96F8D920013202F0030228 -:100E300086F8D920B6E74FF48A7A0AFB02F505F165 -:100E4000EA013144204600F087FCF86000287FF476 -:100E5000FEAE3544012285F8E82001F003FDD5F807 -:100E6000E020D6ED007ADFED216A801A192838BF1C -:100E7000192040F6B832904228BF1046B8EE677A83 -:100E800007EE900AF8EEE77A67EEA67ADFED186AC9 -:100E9000E7EE267AFCEEE77AC6ED007A96F8D930CE -:100EA000BB60BA6873680AFB02F4321992F8E81062 -:100EB00059B1D2F8E4108B42E8463FF427AF002145 -:100EC00082F8E810C2F8E010C5467368064A9B0A2B -:100ED00001331381BBE600BF9D33002000ED00E02D -:100EE0000400FA05884800208C230020CDCCCC3D9E -:100EF0006666663FA0330020014B1870704700BF44 -:100F00009823002038B54FF00054134B22689A42C2 -:100F100020D1124B627D12481A70237D03724FF468 -:100F20008073C0F8F8314FF40073C0F80C3300251B -:100F30004FF44073C0F820340A49C0F8E450C92285 -:100F4000093000F007FAE0222946204600F014FAA2 -:100F5000012038BD0020FCE79AAD44C5982300204D -:100F6000884800201600002037B500F045FC194DD8 -:100F70001949288102236B7100220123174801F0CF -:100F80007BF800230193164B164900931648174B24 -:100F90004FF4805201F050FF154B197811B11248EF -:100FA00001F072FF01F05EFC0446FFF721FC4FF4F4 -:100FB000C873B0FBF3F202FB130304F5167010FACA -:100FC00083F00C4B186003F015F908B10F232B8147 -:100FD00003B030BD8C23002040420F00D8330020E6 -:100FE000F90A00089C230020A4330020FD0B000810 -:100FF00098230020A03300202DE9F04F2DED028B27 -:1010000090A7D7E900670FF24429D9E90089884CF5 -:1010100095B00DAD9FED848BFFF728FDDFF834B25E -:1010200000230C93ADF83C300D936B6000230DF161 -:1010300025028DED008B4FF0010A09A958468DF865 -:1010400025308DF824A001F075FB9DF824200023A5 -:10105000002A40F0AF80204601F01EFF0546002820 -:1010600047D1DFF8F4B101F0FDFBDBF80030984226 -:101070003FD301F0F7FB0790FFF7BAFB079A4FF455 -:10108000C873B0FBF3F101FB130302F5167010FAFD -:1010900083F0CBF80000DFF8C4B19BF80010079193 -:1010A000002914BF2B46534610A88DF83030FFF7A7 -:1010B000B7FB0799C1F11002D2B2062A10AB28BFC4 -:1010C000062219440DF13100079200F043F9079A06 -:1010D0000CAB0393182302930132564BD2B2CDE9E5 -:1010E00000A304923B463246204601F01BFF8BF8DA -:1010F000005001F0B7FB504A504D1368C31AB3F5C6 -:101100007A7F32D3106001F0AFFB02460B462046D7 -:1011100001F0A0FF204601F0BFFE30B32B7ADFF8CC -:1011200040A1002B14BF032302238AF8053001F0ED -:1011300099FB0DF1400B4FF47A730122B0FBF3F0F1 -:101140005946CAF80000504600F008FA18230293E6 -:101150003B4B019380B240F25513CDE903B00093AD -:1011600042464B46204601F0DDFE2B7AB3B101F03A -:1011700079FB4FF0000A83464FF48A7295F8D90044 -:10118000504400F0030002FB005393F8E8100029DC -:1011900034D00AF1010ABAF1040FEFD1C82002F0ED -:1011A000E5FC2B7A002B7FF434AF15B0BDEC028B3D -:1011B000BDE8F08F4FF0904110A84A6982F02002FC -:1011C0004A611946102200F0D7F80DF126030AAA49 -:1011D0000CA9584600F01AFE95E8030011AB83E80D -:1011E00003009DF83C308DF84C300C9B109310A9F7 -:1011F000DDE90A23204602F001F917E7D3F8E010F1 -:1012000049B12B68FA2B38BFFA23ABEB0101053348 -:10121000B1EB430FBDD3FFF7D9FB4FF48A7200281F -:10122000B7D1BBE7AFF30080000000000000000072 -:10123000A43300209C330020B84D002088480020B3 -:10124000BC4D0020401DA12026812A0BF1C6A7C15C -:10125000D068080FD8330020A03300209D33002031 -:101260008C23002008B5054800F074FEBDE8084056 -:10127000034A0449002003F0ABBA00BFD833002072 -:10128000F84D0020C50B00087047000070B502F053 -:10129000F9FD094E094D30800024286833888342C7 -:1012A00008D902F0EBFD2B6804440133B4F5204F5C -:1012B0002B60F2D370BD00BFEC4D0020C04D00206C -:1012C00002F092BE00F10060920000F5204002F0B2 -:1012D00015BE0000054B1A68054B1B889B1A8342FC -:1012E00002D9104402F0CABD00207047C04D002052 -:1012F000EC4D0020024B1B68184402F0C5BD00BF36 -:10130000C04D0020024B1B68184402F0CFBD00BF47 -:10131000C04D0020064991F8243033B10023086AFB -:1013200081F824300822FFF7CDBF0120704700BFAD -:10133000C44D0020022802BF4FF0904320229A6142 -:1013400070470000022802BF4FF090434FF4001294 -:101350009A61704710B50023934203D0CC5CC4540B -:101360000133F9E710BD000003460246D01A12F916 -:10137000011B0029FAD1704702440346934202D070 -:1013800003F8011BFAE770472DE9F8431F4D144697 -:1013900095F824200746884652BBDFF870909CB32E -:1013A00095F824302BB92022FF2148462F62FFF701 -:1013B000E3FF95F82400C0F10802A24228BF2246AC -:1013C000D6B24146920005EB8000FFF7C3FF95F8C7 -:1013D0002430A41B1E44F6B2082E17449044E4B2F5 -:1013E00085F82460DBD1FFF795FF0028D7D108E00E -:1013F0002B6A03EB82038342CFD0FFF78BFF0028D9 -:10140000CBD10020BDE8F8830120FBE7C44D0020CC -:101410002DE9F0470D46044600219046284640F24B -:101420007912FFF7A9FF234620220021284601F068 -:1014300087FF231D02222021284601F081FF631D22 -:1014400003222221284601F07BFFA31D0322252130 -:10145000284601F075FF04F10803102228212846D0 -:1014600001F06EFF04F1100308223821284601F034 -:1014700067FF04F1110308224021284601F060FFB4 -:1014800004F1120308224821284601F059FF04F113 -:10149000140320225021284601F052FF04F11803C2 -:1014A00040227021284601F04BFF04F1200308225E -:1014B000B021284601F044FF04F121030822B8219D -:1014C000284601F03DFF04F12207C0263B46314685 -:1014D00008222846083601F033FFB6F5A07F07F151 -:1014E0000107F3D104F1320308223146284601F006 -:1014F00027FF002704F1330A94F832304FEAC70976 -:101500009F4209F5A47615D3B8F1000F08D13146F2 -:1015100004F599730722284601F012FF09F24F16CD -:10152000274694F832213B1B93420CD3F01DC00890 -:10153000BDE8F0870AEB070308223146284601F090 -:10154000FFFE0137D8E707F2331331460822284659 -:1015500001F0F6FE08360137E3E7000013B5044654 -:101560000846002101602346C0F8031020220190A4 -:1015700001F0E6FE0198231D0222202101F0E0FE89 -:101580000198631D0322222101F0DAFE0198A31DB8 -:101590000322252101F0D4FE019804F10803102252 -:1015A000282101F0CDFE072002B010BDF7B50023C1 -:1015B000047F00910E4607221946054601F084FD7E -:1015C000731C0093012200230721284601F07CFDB3 -:1015D000C4B9B31C0093052223460821284601F014 -:1015E00073FD0D243746B278BB1B934211D32B7F7A -:1015F000A88A0734E408BBB9844294BF00200120C4 -:1016000003B0F0BDAB8ADB00083BDB08B3700824F5 -:10161000E8E7FB1C0093214600230822284601F03E -:1016200053FD08340137DEE7201A18BF0120E7E731 -:10163000F7B50023047F00910E460822194605469F -:1016400001F042FD731CC4B90822009311462346E1 -:10165000284601F039FD1024012372785F1C013BFC -:10166000934211D32B7FA88A0734E408BBB9844284 -:1016700094BF0020012003B0F0BDAB8ADB00083B23 -:10168000DB0873700824E7E7F31900932146002371 -:101690000822284601F018FD08343B46DDE7201AF1 -:1016A00018BF0120E7E70000F8B50E4605461446CE -:1016B000002181223046FFF75FFE2B4608220021E1 -:1016C000304601F03DFE7CB96B1C072208213046F4 -:1016D00001F036FE0F2401236A785F1C013B934220 -:1016E00004D3E01DC008F8BD0824F4E7EB19214637 -:1016F0000822304601F024FE08343B46ECE70000A7 -:10170000F8B50E46054614460021CE223046FFF7B6 -:1017100033FE2B4628220021304601F011FE7CB911 -:1017200005F1080308222821304601F009FE302483 -:101730002F462A7A7B1B934204D3E01DC008F8BDD4 -:101740002824F5E707F1090321460822304601F075 -:10175000F7FD08340137ECE7F7B5047F00910E463A -:10176000012310220021054601F0AEFCC4B9B31CD0 -:101770000093092223461021284601F0A5FC1924D4 -:1017800037467288BB1B9A4211D82B7FA88A073430 -:10179000E408BBB9844294BF0020012003B0F0BD2F -:1017A000AB8ADB00103BDB0873801024E8E73B1DAD -:1017B0000093214600230822284601F085FC0834C6 -:1017C0000137DEE7201A18BF0120E7E730B5094DE1 -:1017D0000A4491420DD011F8013B5840082340F3D0 -:1017E0000004013B2C4013F0FF0384EA5000F6D1C3 -:1017F000EFE730BD2083B8EDF7B5364A1068516881 -:101800006B4603C36A4634493448082303F00EF894 -:10181000044690BB0A25324A106851686B4603C3E0 -:101820006A4630492D48082303F000F80446002892 -:1018300047D00369B3F5583F43D8B0F86620B2F5F6 -:10184000826F3ED1284A024402F15C018B4238D3B8 -:101850005C3B224900209E1AFFF7B8FF324607463C -:1018600004F164010020FFF7B1FFA3689F4228D173 -:10187000E368984208BF002523E00369B3F5583FA9 -:1018800026D8428BB2F5826F20D1174A024402F16A -:1018900010018B4218D3103B104900209D1AFFF70E -:1018A00095FF2A46064604F118010020FFF78EFF37 -:1018B000A3689E4202D1E368984201D00D25AAE7B1 -:1018C0000025284603B0F0BD1025A4E70C25A2E7AB -:1018D0000B25A0E79C480008DC5F030000A000087F -:1018E000A5480008905F03000860FFF710B5037C6F -:1018F000044613B9006802F081FF204610BD0000C5 -:101900000023BFF35B8FC360BFF35B8FBFF35B8FBD -:101910008360BFF35B8F7047BFF35B8F0068BFF3DB -:101920005B8F704770B505460C30FFF7F5FF05F18A -:10193000080604463046FFF7EFFFA04206D93046BE -:101940006D68FFF7E9FF2544281A70BD3046FFF7A0 -:10195000E3FF201AF9E7000070B50546406898B12A -:1019600005F10800FFF7D8FF05F10C0604463046E4 -:10197000FFF7D2FF8442304694BF6D680025FFF721 -:10198000CBFF013C2C44201A70BD000038B50C463A -:101990000546FFF7C7FFA04210D305F10800FFF787 -:1019A000BBFF04446868B4FBF0F100FB1144BFF3D3 -:1019B0005B8F0120AC60BFF35B8F38BD0020FCE77C -:1019C0002DE9F041144607460D46FFF7C5FF844256 -:1019D00028BF0446D4B1B84658F80C6B4046FFF710 -:1019E0009BFF3044286040467E68FFF795FF331A1E -:1019F0009C4203D86C600120BDE8F0816B60A41BA1 -:101A00003B68AB602044E8600220F5E72046F3E73E -:101A100038B50C460546FFF79FFFA04210D305F1ED -:101A20000C00FFF779FF04446868B4FBF0F100FB99 -:101A30001144BFF35B8F0120EC60BFF35B8F38BDB7 -:101A40000020FCE72DE9FF41884669460746FFF77D -:101A5000B7FF6C4606B204EBC6060025B44209D0B7 -:101A60006268206808EB0501FFF774FC63680834BE -:101A70001D44F3E729463846FFF7CAFF284604B05D -:101A8000BDE8F081F8B505460C300F46FFF744FF7E -:101A900005F1080604463046FFF73EFFA0423046F7 -:101AA00088BF6C68FFF738FF201A386020B13046D5 -:101AB0002C68FFF731FF2044F8BD000073B51446D1 -:101AC00006460D46FFF72EFF844228BF04460190CC -:101AD000DCB101A93046FFF7D5FF019B33B932686D -:101AE000C5E90233C5E9002401200CE09C4238BF5F -:101AF00001942860019868608442F5D93368AB602E -:101B0000241AEC60022002B070BD2046FBE7000002 -:101B10002DE9FF410F466946FFF7D0FF6C4600B242 -:101B200004EBC0050026AC4209D0D4F8048054F878 -:101B3000081BB8194246FFF70DFC4644F3E7304650 -:101B400004B0BDE8F081000038B50546FFF7E0FFBE -:101B5000044601462846FFF719FF204638BD00001D -:101B6000302383F3118862B670470000002383F3AB -:101B7000118862B67047000001207047704700006E -:101B800010B41346026814680022A4465DF8044BA2 -:101B90006047000000F5805090F85904704700003D -:101BA00000F5805090F852047047000000F5805016 -:101BB00090F95804704700005020704700F580529B -:101BC00008B5FFF7CDFFD2F89834D2F89404184442 -:101BD000D2F890341844D2F878341844D2F88834C3 -:101BE0001844D2F884341844FFF7C0FF08BD000041 -:101BF00038B5C26A936923F001039361044600F08B -:101C000031FE0546E36A9B69DB0706D500F02AFE34 -:101C1000431BFA2BF6D9002004E004F58054012080 -:101C200084F8520438BD00002DE9F04F0C4600F551 -:101C3000805185B01F4691F85234BDF83890054662 -:101C400090469BB1D1F874340133C1F874342368E1 -:101C50009A0006D4237B082B0BD9627B0AB10F2B89 -:101C600007D9D1F878340133C1F878344FF0FF3018 -:101C70000FE0FFF775FFEB6AD3F8C42012F4001AE7 -:101C80000AD0D1F87C340133C1F87C34FFF76EFF01 -:101C9000002005B0BDE8F08FD3F8C46022686B6AFD -:101CA000C6F301464FF0480B002A1BFB063BB4BFAE -:101CB00042F080429204CBF8002023685B0044BFCE -:101CC00042F00052CBF80020227B330643EA024365 -:101CD000CBF80430607B720118B343F44013CBF8A7 -:101CE0000430D1F8A4340133C1F8A434AB1803F59F -:101CF0008353197B41F020011973207B039200F07C -:101D00000DFE039A033080105FFA8AF383420AF1D2 -:101D1000010A0DDA04EB83010BEB83034968996038 -:101D2000F2E7AB1803F58353197B60F34511E3E742 -:101D3000EB6A0121B140C3F8CC10AB1803F5825314 -:101D4000C3E9048705EB461303F582532146183394 -:101D500004F10C0051F804CB43F804CB8142F9D1D3 -:101D6000098819802A4441F268032846D65002F5B2 -:101D7000805209F0030392F86C1043F0100321F035 -:101D80001F010B4382F86C30FFF7F0FE4246CDF89E -:101D900000903B46214600F087FD012079E70000D6 -:101DA00013B500F580540191606CFFF7D5FD1F2835 -:101DB0000AD90199606C2022FFF744FEA0F12003AC -:101DC0005842584102B010BD0020FBE708B500F5AD -:101DD0008050FFF7C5FE406CFFF792FDBDE808405C -:101DE000FFF7C4BE002202608281426082607047B9 -:101DF00010B500220023C0E900230023044603811C -:101E00000C30FFF7EFFF204610BD00002DE9F04732 -:101E1000074688B007F5805468469A468846FFF71B -:101E20009FFE9146FFF7E4FF606CFFF77BFD1F28E4 -:101E30002CD9606C20226946FFF786FE202825D128 -:101E400094F8523413B303AD444605AB2E4603CE8B -:101E50009E4220606160354604F10804F6D1306886 -:101E60002060B388A380DDE90023C9E90023BDF821 -:101E70000830AAF80030FFF779FE4A46534641463B -:101E8000384608B0BDE8F04700F0FCBCFFF76EFE36 -:101E9000002008B0BDE8F0872DE9F84F0023064682 -:101EA000C0E90133284B46F8303B00F58154054624 -:101EB00088463746103438462037FFF799FFA74247 -:101EC000F9D105F580544FF4805326630026C4E908 -:101ED0000D366764012305F5835705F5A359E663BD -:101EE00084F8403084F84830103709F110094FF079 -:101EF000000A4FF0000B47E908ABA7F11800FFF705 -:101F000071FF203747F8286C4F45F4D184F8588486 -:101F1000A4F85A64A4F85C64A4F85E6484F860646D -:101F2000A4F86264A4F86464A4F8666484F868643D -:101F3000B8F1000F02D0054800F08EFC044BEB62B4 -:101F40002846BDE8F88F00BFCC480008B04800081C -:101F50000064004010B5044B197804464A1C1A70FE -:101F6000FFF79AFF204610BDF54D00202DE9F04304 -:101F700000295FD03048314BB3FBF1F381428CBF75 -:101F80000A201120451EB3FBF0F700FB1730ECB21E -:101F900020B1022D2846F5D8002037E07D1EB5F58A -:101FA000806F33D2C4EBC40808F103034FEAE30E99 -:101FB000C3F3C703A4EB030C0EF101094FF47A70CD -:101FC0005FFA8CF60EFB000E59FA8CFCBEFBFCFC93 -:101FD000BCF5617F1CDC1FFA8CF4581C56FA80F0AB -:101FE00047431648B0FBF7F7B942D5D1013BDBB206 -:101FF0000F2BD1D8711EC9B207294FF0000005D8A8 -:10200000107114805580537191710120BDE8F083E7 -:1020100008F1FF334FEAE30CC3F3C703E41A0CF1F2 -:10202000010EE6B20CFB00005EFA84F4B0FBF4F49F -:10203000A4B2D2E70846E9E73F420F0000366E013E -:102040000B4B10B54FF45472044600211846FFF7AD -:1020500093F9084BA3614033E361D8332362F03333 -:102060006362E36A60610022C3F8C02010BD00BF54 -:1020700000A4004070A400402DE9F04F00F5805509 -:10208000994695F85834012B89B004468A46904603 -:1020900004D90027384609B0BDE8F08F8D4A52F8C0 -:1020A000231009B942F823008B49C4F80CA00B781F -:1020B00084F8109093B9FFF753FD884B9A6D42F066 -:1020C00000729A659A6B42F000729A639A6B22F0E2 -:1020D00000729A6301230B70FFF748FD95F85134A5 -:1020E00073B903211520FFF73BFD01F015FC032117 -:1020F000162001F011FC012385F85134FFF736FD5D -:10210000FFF72EFDE26A936923F01003936100F05C -:10211000A9FB0746E36A9E6916F0080607D000F09F -:10212000A1FBC31BFA2BF5D9FFF720FDB1E79A6994 -:1021300042F001029A6100F095FB0746E36A9A6952 -:10214000D00705D400F08EFBC31BFA2BF6D9EBE7C2 -:102150009A6942F002029A61E36A00275F65FFF71D -:1021600005FD686CFFF7CCFB04F5825B0BF1100BEF -:10217000202200216846FFF7FFF802A8FFF732FE91 -:1021800006976A460BEB06030DF1180E9446BCE861 -:102190000300F44518605960624603F10803F5D165 -:1021A000DCF80000186020369CF804201A71B6F59F -:1021B000806FDDD1002304F5A25285F8503485F8F4 -:1021C00053341A3251462046FFF7D0FE074690B9E5 -:1021D000E26A936923F00103936100F043FB054633 -:1021E000E36A9B69D9077FF554AF00F03BFB431BC3 -:1021F000FA2BF5D94DE795F85F6495F85E24C5F89C -:102200006CA4360246EA426695F86024E36A1643F7 -:10221000B5F85C2446EA0246DE61B8F1000F29D029 -:1022200004F5A352023241462046FFF79FFE90B9C3 -:10223000E26A936923F00103936100F013FB054602 -:10224000E36A9B69DA077FF524AF00F00BFB431BC1 -:10225000FA2BF5D91DE795F8683495F86714C5F899 -:1022600070841B0143EA0123B5F86414E26A43EA6F -:102270000143D3602046FFF7E3FE002385F859347D -:10228000E36A6FF040421A65E36A154A5A65E36AE9 -:1022900044229A65E36A0722C3F8DC20E36A03223A -:1022A0009145DA653FF4F6AEE26A936923F00103E3 -:1022B000936100F0D7FA0646E36A9B69DB0705D510 -:1022C00000F0D0FA831BFA2BF6D9E2E6012385F859 -:1022D0005234DFE6F04D0020F44D002000100240A3 -:1022E0009B0008002DE9F04F054689B090469946BD -:1022F000002741F2680A00F58056EB6AD3F8D43023 -:10230000FB40D8074AD505EB471252444FEA471B1A -:102310001379190742D4D6F880340133C6F88034D3 -:1023200013799A0648BFD6F8A83405EB0B0248BFCC -:102330000133524448BFC6F8A834137943F0080368 -:102340001371DB0722D596F85334FBB105F582549F -:10235000183468465C44FFF74BFD03AB04F1080CEE -:10236000206861681A4603C2083464451346F7D1F1 -:1023700020681060A2889A800123ADF808302B688D -:10238000CDE90089DB6B694628469847D6F8543476 -:1023900023B1D6F89C340133C6F89C340137202F82 -:1023A000ABD109B0BDE8F08F2DE9F04F8DB00446F8 -:1023B0000F4600F059FA82468946002F56D1E36A4B -:1023C000D3F89020920141BF04F58051D1F89424B4 -:1023D0000132C1F89424D3F89020160703D10020CD -:1023E0000DB0BDE8F08FD3F89050E669C5F3012534 -:1023F000482303FB0566E8464046FFF7F3FC3268D6 -:1024000051004ABF22F06043C2F38A4343F00043C5 -:10241000920048BF43F080430093736813F40013A5 -:102420001FBF04F5805201238DF80D30D2F8AC3473 -:102430000EBF8DF80D300133C2F8AC34F38803F0D1 -:102440000F038DF80C304FF0000B9DF80C0000F0DE -:1024500065FA5FFA8BF3984220D9F2180CA90B4465 -:10246000127A03F82C2C0BF1010BEEE7012FB6D1F9 -:10247000E36AD3F89820950141BF04F58051D1F863 -:1024800094240132C1F89424D3F898201007A6D0E0 -:10249000D3F89850266AC5F30125A9E7EFB9E36A96 -:1024A000C3F8945004A8FFF7A3FC98E80F0007AD09 -:1024B00007C52B800023ADF8183023682046CDE9EE -:1024C00004A9DB6B04A9984704F5805458B1D4F8EB -:1024D0008C340133C4F88C3482E7012F04BFE36AE3 -:1024E000C3F89C50DEE7D4F890340133C4F890343C -:1024F000012075E7F8B505460F4600F58054012622 -:1025000039462846FFF750FF10B184F85364F7E7C7 -:10251000D4F8543423B1D4F89C340133C4F89C3437 -:10252000F8BD0000F0B5C36A1A6C12F47F0F2BD00F -:1025300000F580541B6CC4F8A03441F268050023F8 -:1025400047194FF0010C00EB43122A445E01117948 -:1025500011F0020F15D0490713D4B959C66AD6F83D -:10256000C8E00CFA01F111EA0E0F0AD0C6F8D0103B -:10257000117941F004011171D4F888240132C4F8B2 -:1025800088240133202BDED1F0BD000010B5254C8E -:10259000254B226802B338B31A6D12060ED580227D -:1025A0001A6500F061F950EA01020B4602D00138C9 -:1025B00061F1000302462068FFF794FE1A4A136D8A -:1025C0001B032AD523684FF4002103F580531165BE -:1025D000012283F8592420E001221A6508221A6595 -:1025E0004FF480621A6510BD196DC80702D4196DC9 -:1025F000890705D50321196510460021FFF77AFFE9 -:10260000094B1A6D100702D41A6DD10605D5182290 -:102610001A6520680121FFF76DFF2068BDE81040B2 -:10262000FFF780BFF04D00200064004008B5FFF7C1 -:1026300097FAFFF777FFBDE80840FFF797BA000069 -:10264000C36AD3F8C40080F40010C0F34050704750 -:1026500000F5805008B5FFF783FA406CFFF762F988 -:10266000FFF784FA43090CBF0120002008BD0000D9 -:1026700000F5805393F8592462B1C16A8A6922F047 -:1026800001028A61D3F898240132C3F89824002209 -:1026900083F85924704700002DE9F74300F5825173 -:1026A00098461031FFF75CFA002541F2680E4FF0B2 -:1026B000010900F5805C00EB4514744423795E0742 -:1026C0001CD4DB061AD5C36A8E69D3F8C87009FA20 -:1026D00006F63E4212D04F6801970F689742019F5D -:1026E00077EB08070AD2C3F8D060237943F00403DC -:1026F0002371DCF884340133CCF884340135202D87 -:1027000001F12001D7D103B0BDE8F043FFF72EBAA5 -:10271000F8B51E46002313700F4605461446FFF712 -:1027200097FF80F0010038701EB12846FFF788FF40 -:102730002070F8BD2DE9F04F85B09946DDE90EA374 -:102740000D4602931378019391F800B08046164627 -:1027500000F08AF82B7804460F4613B93378002B23 -:1027600042D022463B464046FFF796FFFFF75EFF0A -:10277000FFF77EFF4B4632462946FFF7C9FF2B780D -:1027800033B1BBF1000F03D0012005B0BDE8F08FDD -:10279000337813B1019B002BF6D108F580530393D6 -:1027A000029B544577EB03031ED2039BD3F85404DA -:1027B000D0B10368AAEB0401DB6889B298474B46A5 -:1027C000324629464046FFF7A3FF2B7813B1BBF1F1 -:1027D000000FD9D1337813B1019B002BD4D100F075 -:1027E00043F804460F46DBE70020CEE708B500209B -:1027F000FFF7CCFEBDE8084001F050B808B5012055 -:10280000FFF7C4FEBDE8084001F048B800B59BB032 -:10281000EFF3098168226846FEF79CFDEFF305831C -:10282000014B9B6BFEE700BF00ED00E008B5FFF732 -:10283000EDFF000000B59BB0EFF309816822684608 -:10284000FEF788FDEFF30583014B5B6BFEE700BFEE -:1028500000ED00E0FEE700000FB408B5029801F0BB -:102860001BF9FEE701F00EBC01F0E6BB13B56C46A8 -:1028700084E80600031D94E8030083E805000120B6 -:1028800002B010BD73B58568019155B11B885B0717 -:1028900007D4D0E900369B6B9847019AC1B2304605 -:1028A000A847012002B070BDF0B5866889B0054622 -:1028B0000C465EB1BDF838305B070AD4D0E900376A -:1028C0009B6B98472246C1B23846B047012009B0F9 -:1028D000F0BD00220023CDE900230023ADF808302D -:1028E0000A4603AB01F10806106851681C4603C490 -:1028F0000832B2422346F7D1106820609288A28045 -:10290000FFF7B2FF0423ADF808302B68CDE90001D2 -:10291000DB6B694628469847D8E70000082817D996 -:1029200009280CD00A280CD00B280CD00C280CD06D -:102930000D280CD00E2814BF4020302070470C20EA -:1029400070471020704714207047182070472020CF -:10295000704700002DE9F041456A15B94162BDE8B4 -:10296000F0814B6823F06047C3F38A464FEAD37E79 -:10297000C3F3807816EA230638BF3E46AC462B46A2 -:102980005A68BEEBD27F22F060440AD0002A18DADF -:10299000A40CB44217D19D420FD10D60DEE713465F -:1029A000EEE7A74207D102F08044C2F380724245AD -:1029B0000BD054B1EFE708D2EDE7CCF800100B6074 -:1029C000CDE7B44201D0B442E5D81A689C46002A4B -:1029D000E5D11960C3E700002DE9F047089D01F03B -:1029E00007044FEAD508224405F0070500EBD100A3 -:1029F0004FF47F49944201D1BDE8F08704F0070706 -:102A000005F0070A57453E4638BF5646C6F1080648 -:102A1000111B8E4228BF0E46E10808EBD50E415C23 -:102A200013F80EC0B94029FA06F721FA0AF1FFB2ED -:102A30008CEA010147FA0AF739408CEA010C03F8E5 -:102A40000EC034443544D5E780EA0120082341F222 -:102A5000210201B24000002980B203F1FF33B8BF68 -:102A6000504013F0FF03F4D17047000038B50C4616 -:102A70008D18A54200D138BD14F8011BFFF7E4FF03 -:102A8000F7E7000042684AB11368436043898189CF -:102A900001339BB29942438138BF8381104670470E -:102AA00070B588B0202204460D4668460021FEF726 -:102AB00063FC20460495FFF7E5FF024658B16B46DC -:102AC000054608AE1C4603CCB44228606960234624 -:102AD00005F10805F6D1104608B070BD082817D9D1 -:102AE00009280CD00A280CD00B280CD00C280CD0AC -:102AF0000D280CD00E2814BF4020302070470C2029 -:102B0000704710207047142070471820704720200D -:102B100070470000082817D90C280CD910280CD9A8 -:102B200014280CD918280CD920280CD930288CBF8F -:102B30000F200E207047092070470A2070470B2095 -:102B400070470C2070470D20704700002DE9F843B6 -:102B5000078C072F04461ED9D0E9029800254FF6AE -:102B6000FF73C5F12006A5F1200029FA05F108FA46 -:102B700006F628FA00F031430143C9B21846FFF7C0 -:102B800063FF0835402D0346EBD1E1693A46BDE8C5 -:102B9000F843FFF76BBF4FF6FF70BDE8F883000006 -:102BA00010B54B6823B9CA8A63F30902CA8210BD03 -:102BB00004691A681C600361C38A013BC3824A60CE -:102BC000EFE700002DE9F84F1D46CB8A0F46C3F30F -:102BD00009010529814692460B4630D00020AAB251 -:102BE00007F11A049EB2042E1FFA80F80FD8904500 -:102BF00003F1010306D3FB8A0A4462F30903FB8253 -:102C000001201AE01AF80060E6540130EAE7904526 -:102C1000F1D2A1F1050B1C237C68BBFBF3F203FB93 -:102C200012BB1FFA8BF6002C45D14846FFF72AFF4E -:102C3000044638B978606FF00200BDE8F88F4FF0B5 -:102C40000008E6E7002606607860ADB24FF0000BA2 -:102C5000454510D90AEB0803221D13F8011B9155B5 -:102C6000B1B208F101081B291FFA88F82BD045459D -:102C700006F10106F1D8FB8AC3F30902154465F396 -:102C80000903BCE7013292B21C462368002BF9D13C -:102C90006B1F0B441C21B3FBF1F301339BB29A422F -:102CA000D3D2BBF1000FD0D14846FFF7EBFE20B9DD -:102CB000C4F800B0BFE70122E7E7C0F800B05E4605 -:102CC00020600446C1E74545D5D94846FFF7DAFEFE -:102CD00008B92060AFE7C0F800B0002620600446C5 -:102CE000B6E700002DE9F04F2DED028B1C4683B0B6 -:102CF0005B69019207468846002B00F09A80238C7E -:102D00002BB1E269002A00F09480072B35D807F137 -:102D10000C00FFF7B7FE054638B96FF002052846EC -:102D200003B0BDEC028BBDE8F08F14220021FEF74A -:102D300023FB228CE16905F10800FEF70BFB208CD8 -:102D4000013080B2FFF7E6FEFFF7C8FE013880B21F -:102D50002084013028746369228C1B782A4403F094 -:102D60001F0363F03F0348F0004113723846696067 -:102D70002946FFF7EFFD0125D1E700F10C034FF0E5 -:102D8000000908EE103A4FF0800A4E464D4618EE04 -:102D9000100AFFF777FE83460028BED014220021D8 -:102DA000FEF7EAFA002E3AD1019BABF80830022276 -:102DB0000BF1080E1FFA82FC0CF10100BCF1060FAA -:102DC000218C80B201D88E422BD3FFF7A3FEFFF7F0 -:102DD00085FE62691278013802F01F028E4208BF38 -:102DE0004FF0400A42EA49121BFA80F14AEA020A0D -:102DF000013048F0004281F808A08BF81000CBF8B1 -:102E0000042059463846FFF7A5FD238C0135B3420F -:102E10002DB289F001094FF0000AB8D17FE70022F6 -:102E2000C6E7E169895D0EF802100136B6B20132DB -:102E3000C0E76FF0010572E7F8B515460E4630227F -:102E4000002104461F46FEF797FA069B6360B5F51E -:102E5000001F079BA76034BF6A094FF6FF72A36289 -:102E600097B2E66104F1100000239A4206D80023CD -:102E70000360A782E3822383E360F8BD0660013329 -:102E800030462036F1E7000003781BB94BB2002B27 -:102E9000C8BF01707047000000787047F8B50C4655 -:102EA000C969074611B9238C002B37D1257E1F2D08 -:102EB00034D8387828BB228C072A2CD8268A36F0BA -:102EC00003032BD14FF6FF70FFF7D0FD20F0010078 -:102ED0003102400441EA0561400C41EA40254FF6C9 -:102EE000FF72234629463846FFF7FCFE002807DD1F -:102EF000626913780133DBB21F2B88BF0023137084 -:102F0000F8BD218A2D0645EA012505432046FFF735 -:102F10001DFE0246E5E76FF00300F1E76FF00100E8 -:102F2000EEE7000070B58AB004461646002128225C -:102F300068461D46FEF720FABDF83830ADF810306F -:102F40000F9B05939DF840308DF81830119B079327 -:102F50006946BDF84830ADF820302046CDE902651D -:102F6000FFF79CFF0AB070BD2DE9F041D36905461B -:102F70000C4616460BB9138C5BBB377E1F2F28D827 -:102F800095F80080B8F1000F26D03046FFF7DEFD3F -:102F90003378210241EAC33141EA0801338A41EA28 -:102FA000076141EA03410246334641F08001284669 -:102FB000FFF798FE00280ADD3378012B07D17269EC -:102FC00013780133DBB21F2B88BF00231370BDE8D9 -:102FD000F0816FF00100FAE76FF00300F7E70000FF -:102FE000F0B58BB004460D461746002128226846EE -:102FF0001E46FEF7C1F99DF84C305A1E534253410C -:103000008DF800309DF84030ADF81030119B0593DD -:103010009DF848308DF81830149B07936A46BDF828 -:103020005430ADF8203029462046CDE90276FFF72E -:103030009BFF0BB0F0BD0000406A00B10430704748 -:10304000436A1A68426202691A600361C38A013BDB -:10305000C38270472DE9F041D0F82080194E144604 -:103060001D464146002709B9BDE8F081D1E9022398 -:10307000A21A65EB0303964277EB03031ED2036AA1 -:103080008B420DD1FFF78CFD036A1B680362036955 -:103090000B60C38A0161016A013BC3828846E2E793 -:1030A000FFF77EFD0B68C8F8003003690B60C38A28 -:1030B0000161013BC382D8F80010D4E78846096853 -:1030C000D1E700BF80841E002DE9F04F8BB00D4684 -:1030D000DDF8509014469B468046002800F0198188 -:1030E000B9F1000F00F01581531E3F2B00F2118142 -:1030F000012A03D1BBF1000F40F00B810023CDE981 -:103100000833B8F81430B5EBC30F4FEAC30703D345 -:1031100000200BB0BDE8F08F2B199F42D8F80C307F -:103120003ABF7F1BFFB227461BB9D8F81030002BDF -:103130007AD0272D4ED8C5F12806B7424FF00003AC -:103140002CBFF6B23E4600932946D8F8080008ABDB -:103150003246FFF741FCA7EB060A35445FFA8AFACC -:10316000B8F8143003F10053053BDB000493D8F8A2 -:103170000C3003932821039B13B1BAF1000F2CD11B -:10318000D8F8100040B1BAF1000F05D0009608AB96 -:103190005246691AFFF720FC38B2002FB8D06607F4 -:1031A0000AD00AAB03EBD401624211F8083C02F0EA -:1031B0000702134101F8083C082C3CD9102C40F2BE -:1031C000B580202C40F2B780BBF1000F00F09C804E -:1031D000082334E0BA460026C2E7049BE02B28BF50 -:1031E000E02306930B44AB42059314D95A1B039872 -:1031F0000096924534BF5246D2B2691A08AB0430E9 -:103200000792FFF7E9FB079A1644AAEB020A154456 -:10321000F6B25FFA8AFA049B069A05999B1A049300 -:10322000039B1B680393A6E70093D8F8080008AB3C -:103230003A462946AEE7BBF1000F13D00123B4EBA9 -:10324000C30F6CD0082C12D89DF82030621E23FAD0 -:1032500002F2D50706D54FF0FF3202FA04F42343F9 -:103260008DF820309DF8203089F8003051E7102C7F -:1032700012D8BDF82030621E23FA02F2D10706D51B -:103280004FF0FF3202FA04F42343ADF82030BDF8CA -:103290002030A9F800303CE7202C0FD80899631E95 -:1032A00021FA03F3DA0705D54FF0FF3202FA04F4EE -:1032B0000C430894089BC9F800302AE7402C2BD017 -:1032C000DDE90865611EC4F12102A4F1210326FA9B -:1032D00001F105FA02F225FA03F311431943CB0772 -:1032E00012D50122A4F12003C4F1200102FA03F354 -:1032F00022FA01F1A240524243EA010363EB430385 -:1033000032432B43CDE90823DDE90823C9E9002333 -:10331000FFE66FF00100FCE66FF00800F9E6082C0C -:10332000A0D9102CB3D9202CEED8C3E7BBF1000FE5 -:10333000ADD0022383E7BBF1000FBBD004237EE7AF -:1033400030B5012A144638BF0124402C85B028BF6F -:1033500040240025012ACDE9025518D81B788DF8A4 -:10336000083063070AD004AB03EBD405624215F8BA -:10337000083C02F00702934005F8083C0091034620 -:103380002246002102A8FFF727FB05B030BD082A1E -:10339000E4D9102A03D81B88ADF80830E1E7202AC9 -:1033A0008DBFD3E900231B680293CDE90223D8E740 -:1033B00010B5CB681BB98B600B618B8210BD0469A3 -:1033C0001A681C600361C38A013BC382CA60F0E7CC -:1033D00003064CBFC0F3C0300220704708B5024658 -:1033E000FFF7F6FF022806D15306C2F30F2001D1E2 -:1033F00000F0030008BDC2F30740FBE72DE9F04FE2 -:1034000093B0CDE903230A6804461046FFF7E0FFB6 -:10341000022814BFC2F306260026002A0D46824663 -:1034200080F2F28112F0C04940F0EE81097B002960 -:1034300000F0EA81022803D02378B34240F0E7810C -:10344000C2F304630693104602F07F030593FFF76F -:10345000C5FF059B29444FEA834848EA0A4848EAE1 -:103460004668CE7800230022CDE90823F30983467D -:1034700048EA0008029367D0059B009302466768FC -:10348000534608A92046B847002800F0C381276AA0 -:103490004FB9414604F10C00FFF702FB074690B913 -:1034A0006FF0020054E03B6998450DD03F68002F53 -:1034B000F9D1414604F10C00FFF7F2FA0746002863 -:1034C000EED0236A3B60276297F817C006F01F080A -:1034D000CCF3840CACEB08001FFA80FE0028B8BFC8 -:1034E0000EF12000A8EB0C031FFA83FED7E902219E -:1034F000B8BF00B2002B0793BEBF0EF120031BB272 -:10350000079352EA010338D0039BDFF824E39A1AA9 -:10351000049B4FF0000C63EB010196457CEB01032B -:103520002BD36B7B97F81AE0734519D1029B002BC4 -:1035300078D0012821DC7868F8B9DFF8F0C294452A -:1035400070EB010316D337E0276A27B96FF00C0040 -:1035500013B0BDE8F08F3B699845B5D03F68F4E7FC -:10356000B24890427CEB010301D30020F0E7029BBC -:10357000002BFAD0079B0F2B17DCFA7DB30002F06B -:10358000030203F07C031343FB7539462046FFF723 -:1035900007FB6B7BBB76029B3BB9FB7DC3F38402CD -:1035A000013262F38603FB75D0E76A7BBB7E9A42E9 -:1035B000DBD1029B002B35D0B309022B32D0039B09 -:1035C000BB60049BFB60142200210DA8FDF7D4FE14 -:1035D000039B0A93049B0B932B1D0C932B7BADF841 -:1035E0003EB0013BDBB2ADF83C30069B8DF842307B -:1035F000059B8DF8433094F82C308DF840A083F073 -:1036000001038DF844308DF84180A3680AA9204653 -:103610009847FB7DC3F38403013303F01F039B0230 -:10362000FB82A2E7FB7DC6F34012B2EBD31F40F052 -:10363000F480C3F38403434540F0F280029A2B7B6D -:10364000B609002A4DD0F2075DD4032B40F2EB807F -:10365000039BBB60049BFB602B7BAE1D033BDBB27B -:103660003246394604F10C00FFF7ACFA00280CDAB8 -:1036700039462046FFF794FAFB7DC3F384030133F8 -:1036800003F01F039B02FB820AE7DDE90884AB8895 -:103690003B834FF6FF73C9F12000A9F1200228FAFD -:1036A00009F104FA00F0014324FA02F2114318462A -:1036B000C9B2FFF7C9F909F10809B9F1400F03468A -:1036C000E9D1B8822A7B033AD2B23146FFF7CEF96C -:1036D000FB7DB882DA43C2F3C01262F3C713FB75F5 -:1036E00043E786B92E1D013BDBB23246394604F171 -:1036F0000C00FFF767FA0028BADB2A7BB88A013A88 -:10370000D2B23146E2E7F98AC1F30901013B04294B -:10371000DAB25BD8281D002307F11B069A4208D9AC -:1037200010F801CB06F801C0013101330529DBB2E5 -:10373000F4D103990A9104990B91934207F11B016B -:103740000C9138BF043379680D9134BF55FA83F377 -:1037500000230E93FB8AADF83EB0C3F309031A446D -:10376000069B8DF84230059B8DF8433094F82C3041 -:10377000ADF83C2083F001038DF8443000238DF830 -:1037800040A08DF841807B602A7BB88A013A291DD0 -:10379000FFF76CF93B8BB882834203D1A3680AA977 -:1037A0002046984720460AA9FFF702FEFB7DBA8A09 -:1037B000C3F38403013303F01F039B02FB823B8BA3 -:1037C0009A420CBF00206FF01000C1E67B68002B0E -:1037D000AFD0052001E01C3033461E68002EFAD120 -:1037E000091A081D2E1D184401EB090CBCF11B0F12 -:1037F0005FFA89F39DD89A429BD916F8013B00F8ED -:10380000013B09F10109EFE76FF00900A0E66FF055 -:103810000A009DE66FF00B009AE66FF00D0097E648 -:103820006FF00E0094E66FF00F0091E640420F003B -:1038300080841E00EFF3098305494A6B22F00102E0 -:103840004A63683383F30988002383F31188704740 -:1038500000EF00E0302080F3118862B60C4B0D4A77 -:10386000D96821F4E0610904090C0A43DA60D3F84D -:10387000FC20094942F08072C3F8FC200A6842F03B -:1038800001020A602022DA7783F82200704700BF25 -:1038900000ED00E00003FA05001000E010B5302351 -:1038A00083F311880E4B5B6813F4006314D0F1EEC0 -:1038B000103AEFF30984683C4FF08073E361094BE1 -:1038C000DB6B236684F3098800F0A4F810B1064B83 -:1038D000A36110BD054BFBE783F31188F9E700BF37 -:1038E00000ED00E000EF00E0430600084606000897 -:1038F0004FF0E023002258684FF0FF31930003F1AE -:10390000604303F5614301329042C3F88010C3F86D -:103910008011F3D27047000000F1604303F561436A -:103920000901C9B283F80013012200F01F039A4075 -:1039300043099B0003F1604303F56143C3F8802111 -:103940001A60704700230375826803691B689968D1 -:103950009142FBD25A680360426010605860704721 -:1039600000230375826803691B6899689142FBD83C -:103970005A680360426010605860704708B5084696 -:10398000302383F311880B7D032B05D0042B0DD03E -:103990002BB983F3118808BD8B6900221A604FF0A0 -:1039A000FF338361FFF7CEFF0023F2E7D1E9003256 -:1039B00013605A60F3E70000FFF7C4BF054BD968F6 -:1039C0000875186802681A60536001220275D86091 -:1039D000FCF722BE004E002030B50C4BDD684B1CBE -:1039E00087B004460FD02B46094A684600F050F9CC -:1039F0002046FFF7E3FF009B13B1684600F052F941 -:103A0000A86907B030BDFFF7D9FFF9E7004E0020E5 -:103A10007D390008044B1A68DB6890689B689842FF -:103A200094BF002001207047004E0020084B10B5C5 -:103A30001C68D86822681A60536001222275DC6015 -:103A4000FFF78EFF01462046BDE81040FCF7E4BDBD -:103A5000004E0020044B1A68DB6892689B689A420B -:103A600001D9FFF7E3BF7047004E002038B5074C7F -:103A700007490848012300252370656000F000FC19 -:103A80000223237085F3118838BD00BF2850002021 -:103A900010490008004E002008B572B6044B1865A6 -:103AA00000F0B6FA00F06EFB024B03221A70FEE73C -:103AB000004E00202850002000F02AB9EFF31180BA -:103AC00020B9EFF30583302282F31188704700009C -:103AD00010B530B9EFF30584C4F3080414B180F3D2 -:103AE000118810BDFFF7B6FF84F31188F9E70000D5 -:103AF0008B60022308618B82084670478368A3F1BC -:103B0000840243F8142C026943F8442C426943F8B8 -:103B1000402C094A43F8242CC26843F8182C02228E -:103B200003F80C2C002203F80B2C044A43F8102C49 -:103B3000A3F12000704700BF31060008004E0020AE -:103B400008B5FFF7DBFFBDE80840FFF735BF000011 -:103B5000024BDB6898610F20FFF730BF004E00205A -:103B6000302383F31188FFF7F3BF000008B5014647 -:103B7000302383F311880820FFF72EFF002383F3FF -:103B8000118808BD10B503689C68A2420CD85C6817 -:103B90008A600B604C602160596099688A1A9A604B -:103BA0004FF0FF33836010BD1B68121BECE7000071 -:103BB0000A2938BF0A2170B504460D460A26601945 -:103BC00000F058FB00F044FB041BA54203D8751C11 -:103BD0002E460446F3E70A2E04D9BDE870400120C2 -:103BE00000F08EBB70BD0000F8B5144B0D46D961D6 -:103BF00003F1100141600A2A1969826038BF0A2264 -:103C0000016048601861A818144600F025FB0A27D7 -:103C100000F01EFB431BA342064606D37C1C28195A -:103C200000F028FB27463546F2E70A2F04D9BDE805 -:103C3000F840012000F064BBF8BD00BF004E00203A -:103C4000F8B506460D4600F003FB0F4A134653F83D -:103C5000107F9F4206D12A4601463046BDE8F84013 -:103C6000FFF7C2BFD169BB68441A2C1928BF2C4684 -:103C7000A34202D92946FFF79BFF2246314603485B -:103C8000BDE8F840FFF77EBF004E0020104E002038 -:103C900010B4C0E9032300235DF8044B4361FFF730 -:103CA000CFBF000010B5194C236998420DD0D0E960 -:103CB0000032816813605A609A680A449A6000234F -:103CC00003604FF0FF33A36110BD2346026843F841 -:103CD000102F53600022026022699A4203D1BDE88E -:103CE000104000F0C1BA936881680B44936000F003 -:103CF000AFFA2269E1699268441AA242E4D91144F8 -:103D0000BDE81040091AFFF753BF00BF004E002066 -:103D10002DE9F047DFF8BC8008F110072C4ED8F8E9 -:103D2000105000F095FAD8F81C40AA68031B9A427C -:103D30003ED81444D5E900324FF00009C8F81C40C1 -:103D400013605A60C5F80090D8F81030B34201D122 -:103D500000F08AFA89F31188D5E90331284698479B -:103D6000302383F311886B69002BD8D000F070FAF0 -:103D70006A69A0EB04094A4582460DD2022000F090 -:103D8000BFFA0022D8F81030B34208D15146284675 -:103D9000BDE8F047FFF728BF121A2244F2E712EB02 -:103DA000090938BF4A4629463846FFF7EBFEB5E712 -:103DB000D8F81030B34208D01444211AC8F81C00B7 -:103DC000A960BDE8F047FFF7F3BEBDE8F08700BF8C -:103DD000104E0020004E002000207047FEE700003B -:103DE000704700004FF0FF3070470000BFF34F8F67 -:103DF000024A1369DB03FCD4704700BF0020024075 -:103E000008B5094B1B7873B9FFF7F0FF074B5A69E8 -:103E1000002ABFBF064A9A6002F188329A601A6887 -:103E200022F480621A6008BD405000200020024049 -:103E30002301674508B50B4B1B7893B9FFF7D6FFF5 -:103E4000094B5A6942F000425A611A6842F48052A2 -:103E50001A601A6822F480521A601A6842F480626A -:103E60001A6008BD40500020002002407F289ABF01 -:103E700000F58030C0020020704700004FF4006061 -:103E800070470000802070477F2808B50BD8FFF7E7 -:103E9000EDFF00F500630268013204D10430834273 -:103EA000F9D1012008BD0020FCE700007F2810B5F3 -:103EB00004461FD8FFF79AFFFFF7A2FF0E4BF3222D -:103EC0001A6102225A615A6942EAC0025A615A6969 -:103ED00042F480325A61FFF789FF4FF40061FFF727 -:103EE000C5FF00F04BF9FFF7A5FF2046BDE81040E5 -:103EF000FFF7CABF002010BD002002402DE9F843A3 -:103F000040EA020313F00703144606D0304B40F298 -:103F100031321A600020BDE8F88385182D4A954299 -:103F20000CD92B4A40F236311160F3E7031D1B68B0 -:103F30004A68934208D1083C08300831072C14D94C -:103F400002680B689A42F1D0FFF75AFFFFF74EFF65 -:103F5000214E08314FF001084FF00009012CA1F16A -:103F6000080706D8FFF766FF01E0002CECD101201E -:103F7000D1E7C6F81480054651F8083C45F8043BE3 -:103F800051F8043C4360FFF731FF336943F001030C -:103F90003361C6F81490026851F8083C9A420CD07C -:103FA0000B4B40F25E321A600C4B18600C4B1C60DD -:103FB0000C4B1F60FFF73EFFACE72D6851F8043C47 -:103FC0009D4201F10801EBD1083C0830C6E700BF73 -:103FD0003C50002000000408002002403050002027 -:103FE0003850002034500020084908B50B7828B11B -:103FF0001BB9FFF705FF01230B7008BD002BFCD098 -:10400000BDE808400870FFF715BF00BF4050002012 -:1040100008B54FF4C0314FF0005000F0B1F8BDE8E2 -:1040200008404FF480414FF0805000F0A9B80000E4 -:10403000084600F0E3BB000070B582B0FFF73EFD1C -:104040000E4E054600F004F93268904237BF0C4A24 -:104050000B49516814682EBFD1E90041013151600C -:104060000419034641F10001284601913360FFF72E -:104070002FFD0199204602B070BD00BF44500020C2 -:104080004850002070B582B0FFF718FD104E05466D -:1040900000F0DEF83268904237BF0E4A0D49516891 -:1040A00014682EBFD1E9004101315160041941F17A -:1040B00000010346284601913360FFF709FD01998D -:1040C0004FF47A7200232046FCF792F802B070BDDC -:1040D00044500020485000200244D2B2904200D107 -:1040E0007047431C800000F1804000F514500068C8 -:1040F00041F8040BD8B2F1E7124B10B5D3F8904059 -:10410000240409D4D3F89040C3F89040D3F89040E9 -:1041100044F40044C3F890400B4C2368024443F439 -:1041200080732360D2B2904200D110BD431C800046 -:1041300000F1804000F5145051F8044B0460D8B2EF -:10414000F1E700BF001002400070004007B50122F7 -:1041500001A90020FFF7C0FF019803B05DF804FB40 -:1041600013B50446FFF7F2FFA04205D0012201A9D2 -:1041700000200194FFF7C0FF02B010BD704700009F -:104180007047000070470000074B45F255521A6017 -:1041900002225A6040F6FF729A604CF6CC421A60D6 -:1041A000024B01221A70704700300040545000202A -:1041B000034B1B781BB1034B4AF6AA221A607047C7 -:1041C0005450002000300040054B1A6832B902F10B -:1041D000804202F50432D2F894201A60704700BF82 -:1041E00050500020024B4FF40002C3F89420704757 -:1041F0000010024008B5FFF7E7FF024B1868C0F354 -:10420000407008BD5050002070470000FEE70000DD -:104210000A4B0B480B4A90420BD30B4BDA1C121A79 -:10422000C11E22F003028B4238BF00220021FDF79D -:10423000A3B853F8041B40F8041BECE7744A0008C9 -:10424000D8500020D8500020D850002000F0C2B82C -:104250004FF08043586A70474FF080430022586304 -:104260001A610222DA6070474FF080430022DA6060 -:10427000704700004FF0804358637047FEE700002E -:1042800070B51B4B01630025044686B058608562FB -:104290000E46FFF7DFFA04F11003C4E904334FF0D0 -:1042A000FF33C4E90635C4E90044A560E562FFF7C1 -:1042B000CFFF2B460246C4E9082304F134010D4A1E -:1042C000256580232046FFF713FC0123E0600A4A9E -:1042D0000375009272680192B268CDE90223074B20 -:1042E0006846CDE90435FFF72BFC06B070BD00BF72 -:1042F000285000201C490008214900087D42000880 -:10430000024AD36A1843D062704700BF004E0020B3 -:104310004B6843608B688360CB68C3600B69436103 -:104320004B6903628B6943620B680360704700004E -:1043300008B5204BDA6A42F07F02DA62DA6A22F0CC -:104340007F02DA62DA6ADA6C42F07F02DA64DA6EED -:1043500042F07F02DA66184ADB6E11464FF0904059 -:10436000FFF7D6FF02F11C0100F58060FFF7D0FFD8 -:1043700002F1380100F58060FFF7CAFF02F1540135 -:1043800000F58060FFF7C4FF02F1700100F5806066 -:10439000FFF7BEFF02F18C0100F58060FFF7B8FF68 -:1043A00002F1A80100F58060FFF7B2FFBDE8084008 -:1043B00000F050B8001002402849000808B500F08D -:1043C000EDF9FFF753FBBDE80840FFF7FDBE000025 -:1043D000704700000F4B9A6D42F001029A659A6F88 -:1043E00042F001029A670C4A9B6F936843F0010305 -:1043F00093604FF08043A7229A624FF0FF32DA6257 -:1044000000229A615A63DA605A6001225A611A6086 -:10441000704700BF00100240002004E04FF08042CF -:1044200008B51169D3680B40D9B2C9439B07116124 -:1044300007D5302383F31188FFF73EFB002383F376 -:10444000118808BD08B5FFF753FABDE8084000F031 -:1044500081B900004E4B4FF0FF319A6A99629A6A17 -:1044600000229A62986AD86A60F07F00D862D86A9F -:1044700000F07F00D862D86A186B1963186B1A6352 -:10448000186B986B9963986B9A63986BD86BD96328 -:10449000D86BDA63D86B186C1964196C1A64196CD0 -:1044A000196E41F001011966D3F8801021F0010165 -:1044B000C3F88010D3F88010996D41F08051996550 -:1044C000996F21F080519967996F32494FF40040FC -:1044D0008860CA600A624A628A62CA620A634A6380 -:1044E0008A63CA630A644A648A64CA640A654A655C -:1044F0004A604FF48072C1F880204FF440720A6025 -:104500004A6912F48062FBD1D3F8901011F4407F15 -:104510001EBF4FF48031C3F89010C3F89020D3F839 -:10452000982042F00102C3F89820D3F8982092070F -:10453000FBD51A6842F480321A601A689003FCD5E1 -:10454000D3F8902022F00322C3F89020124ADA60B8 -:104550001A6842F080721A601A689101FCD50F49FE -:104560000F4800229A60C3F888100E49C3F89C20B7 -:10457000016002684A401207FBD19A6842F00302C8 -:104580009A609A6802F00C020C2AFAD1704700BFB8 -:104590000010024000700040232A610155010050C4 -:1045A0000020024004070400074A08B5536903F0DD -:1045B0000103536123B1054A13680BB15068984752 -:1045C000BDE80840FFF76AB90004014058500020D8 -:1045D000074A08B5536903F00203536123B1054A42 -:1045E00093680BB1D0689847BDE80840FFF756B90B -:1045F0000004014058500020074A08B5536903F0F1 -:104600000403536123B1054A13690BB150699847FC -:10461000BDE80840FFF742B90004014058500020AF -:10462000074A08B5536903F00803536123B1054AEB -:1046300093690BB1D0699847BDE80840FFF72EB9E0 -:104640000004014058500020074A08B5536903F0A0 -:104650001003536123B1054A136A0BB1506A98479E -:10466000BDE80840FFF71AB9000401405850002087 -:10467000164B10B55C6904F478725A61A30604D530 -:10468000134A936A0BB1D06A9847600604D5104A62 -:10469000136B0BB1506B9847210604D50C4A936BF2 -:1046A0000BB1D06B9847E20504D5094A136C0BB1E6 -:1046B000506C9847A30504D5054A936C0BB1D06C98 -:1046C0009847BDE81040FFF7E9B800BF000401407B -:1046D00058500020194B10B55C6904F47C425A61B3 -:1046E000620504D5164A136D0BB1506D984723052A -:1046F00004D5134A936D0BB1D06D9847E00404D5EF -:104700000F4A136E0BB1506E9847A10404D50C4AA2 -:10471000936E0BB1D06E9847620404D5084A136FAC -:104720000BB1506F9847230404D5054A936F0BB122 -:10473000D06F9847BDE81040FFF7B0B800040140C3 -:104740005850002008B5FFF769FEBDE80840FFF7A4 -:10475000A5B80000062108B50846FFF7DDF80621D8 -:104760000720FFF7D9F806210820FFF7D5F8062122 -:104770000920FFF7D1F806210A20FFF7CDF806211E -:104780001720FFF7C9F806212820FFF7C5F8BDE874 -:10479000084007211C20FFF7BFB8000008B5FFF74D -:1047A00051FE00F007F8FFF713FEBDE80840FFF7E1 -:1047B0004DBD00000023054A19460133102BC2E904 -:1047C000001102F10802F8D1704700BF58500020D4 -:1047D0000B460146184600F003B8000000F00EB882 -:1047E00010B5054C13462CB10A4601460220AFF322 -:1047F000008010BD2046FCE700000000024B01468F -:104800001868FFF715BC00BF1823002010B5013948 -:104810000244904201D1002005E0037811F8014FD5 -:10482000A34201D0181B10BD0130F2E72DE9F04181 -:10483000A3B1C91A17780144044603F1FF3C8C4226 -:10484000204601D9002009E00578BD4204F10104A9 -:10485000F5D10CEB0405D618A54201D1BDE8F081D5 -:1048600015F8018D16F801EDF045F5D0E7E70000E9 -:10487000034611F8012B03F8012B002AF9D17047E8 -:104880006F72672E6172647570696C6F742E4E75ED -:10489000636C656F2D4734393100000040A2E4F1AC -:1048A000646891060041A3E5F26569920700000083 -:1048B0004261642043414E496661636520696E64CC -:1048C00065782E000000000000000000792000083C -:1048D000811B000835270008791B0008291C0008E7 -:1048E0000D1E0008F11B0008B91B0008BD1B0008C5 -:1048F000951B00087D1B0008CD1D0008A11B0008AA -:104900006D280008AD1B0008A11D000863300000E1 -:104910000C490008584E0020285000206D61696E37 -:104920000069646C650000000004002800000000BD -:10493000AAAAAAAA00000024DFFF000000000000CD -:104940000000000000000A0000000000AAAAAAAAB5 -:1049500000000000FFFF00000000000099000000C0 -:104960000000000000000000AAAAAAAA000000009F -:10497000FFFF000000000000000000000000000039 -:1049800000000000AAAAAAAA00000000FFFF000081 -:104990000000000000000000000000000000000017 -:1049A000AAAAAAAA00000000FFFF00000000000061 -:1049B000000000000000000000000000AAAAAAAA4F -:1049C00000000000FFFF00000000000000000000E9 -:1049D0000000000000000000AAAAAAAA000000002F -:1049E000FFFF0000000000000000000034B8FF7F5F -:1049F00001000000000000001004000000000000A2 -:104A00000060030000000000FE2A0100D204000044 -:104A10001C23002000000000000000000000000037 -:104A20000000000000000000000000000000000086 -:104A30000000000000000000000000000000000076 -:104A40000000000000000000000000000000000066 -:104A50000000000000000000000000000000000056 -:104A60000000000000000000000000000000000046 -:044A70000000000042 +:1000000000070020F1010008D1250008892500081B +:10001000B125000889250008A9250008F30100087A +:10002000F3010008F3010008F3010008B1350008EE +:10003000F3010008F3010008F3010008F3010008D0 +:10004000F3010008F3010008F3010008F3010008C0 +:10005000F3010008F3010008A5380008CD380008B6 +:10006000F53800081D39000845390008F30100087B +:10007000F3010008F3010008F3010008F301000890 +:10008000F3010008F3010008F3010008F301000880 +:10009000F301000869250008792500086D3900087A +:1000A000F3010008F3010008F3010008F301000860 +:1000B000413A0008F3010008F3010008F3010008C9 +:1000C000F3010008F3010008F3010008F301000840 +:1000D000F3010008F3010008F3010008F301000830 +:1000E000D1390008F3010008F3010008F30100080A +:1000F000F3010008F3010008F3010008F301000810 +:10010000F3010008F3010008F3010008F3010008FF +:10011000F3010008F3010008F3010008F3010008EF +:10012000F3010008F3010008F3010008F3010008DF +:10013000F3010008F3010008F3010008F3010008CF +:10014000F3010008F3010008F3010008F3010008BF +:10015000F3010008F3010008F3010008F3010008AF +:10016000F3010008F3010008F3010008F30100089F +:10017000F3010008F3010008F3010008F30100088F +:10018000F3010008F3010008F3010008F30100087F +:10019000F3010008F3010008F3010008F30100086F +:1001A000F3010008F3010008F3010008F30100085F +:1001B000F3010008F3010008F3010008F30100084F +:1001C000F3010008F3010008F3010008F30100083F +:1001D000F3010008F3010008F3010008F30100082F +:1001E000590F00080000000000000000000000009F +:1001F00002E000F000F8FEE772B6374880F30888A6 +:10020000364880F3098836483649086040F20000D5 +:10021000CCF200004EF63471CEF200010860BFF35C +:100220004F8FBFF36F8F40F20000C0F2F0004EF628 +:100230008851CEF200010860BFF34F8FBFF36F8F7C +:100240004FF00000E1EE100A4EF63C71CEF20001D4 +:100250000860062080F31488BFF36F8F04F08AF8DB +:1002600004F06AF94FF055301F491B4A91423CBFD8 +:1002700041F8040BFAE71D49184A91423CBF41F886 +:10028000040BFAE71A491B4A1B4B9A423EBF51F82E +:10029000040B42F8040BF8E700201849184A914271 +:1002A0003CBF41F8040BFAE704F068F804F08AF95F +:1002B000144C154DAC4203DA54F8041B8847F9E797 +:1002C00000F042F8114C124DAC4203DA54F8041B12 +:1002D0008847F9E704F050B8000700200023002009 +:1002E0000000000808ED00E00001002000070020E9 +:1002F0005848000800230020A4230020A823002041 +:1003000004510020E0010008E4010008E4010008B5 +:10031000E40100082DE9F04F2DED108AC1F80CD052 +:10032000C3689D46BDEC108ABDE8F08F002383F3BF +:1003300011882846A047002003F0C0FCFEE703F028 +:1003400049FC00DFFEE70000F8B500F017FE03F0FF +:10035000B3FF074604F004F80646C0BB274B9F4294 +:1003600035D001339F4235D0254B27F0FF029A420A +:1003700033D1F8B200F03AFC354642F2107400F086 +:100380003BFC08B10024254601F0AEF848B3032039 +:1003900000F03AF80024254636B11A4B9F4203D0AC +:1003A00003F0D6FF00242546002003F08FFF0DB197 +:1003B00000F040F800F052FC02F012F90546ACB92A +:1003C00000F094FC4FF47A7003F07EFCF7E73546BA +:1003D0000024D4E704460125D1E705464FF47A749A +:1003E000CDE7B4F57A7F08BF0125D5E702F0F8F82C +:1003F000431BA342E4D900F01DF8DDE7010007B07C +:10040000000008B0263A09B0084B187003280CD831 +:10041000DFE800F008050208022000F00BBE022011 +:1004200000F000BE024B00225A607047A823002053 +:10043000AC23002010B501F057F830B1234B032254 +:100440001A70234B00225A6010BD224B224A1C46D0 +:1004500019680131F8D004339342F9D16268A2429D +:10046000F2D31E4B9B6803F1006303F520439A42CD +:10047000EAD203F03FFF03F051FF002000F098FDA7 +:100480000220FFF7C1FF164B9A6D00229A65996F03 +:100490009A67996FD96DDA65D96FDA67D96F196E76 +:1004A0001A66D3F88010C3F88020D3F8803072B673 +:1004B0004FF0E0233021C3F8084DD4E9003281F336 +:1004C00011889D4683F308881047BDE7A8230020C4 +:1004D000AC23002000A0000820A00008002300207A +:1004E00000100240094A136849F2690099B21B0CD6 +:1004F00000FB01331360064B186844F2506182B26E +:10050000000C01FB0200186080B270471423002029 +:100510001023002010B500211022044600F0A4FD95 +:10052000034B03CB206061601868A06010BD00BF62 +:100530009075FF1F2DE9F041ADF54E7D0DF13408AA +:100540006CAC40F2751207460D460EA80021C8F8A3 +:10055000001000F089FD4FF4C4720021204600F025 +:1005600083FD02F03DF8254B4FF47A72B0FBF2F0B8 +:10057000186093E80700022384E807000DF5E9708E +:100580002382FFF7C7FF41F204031D49238406A815 +:1005900004F080F8192384F832310DF2E32206AB1F +:1005A0000DF1300C1E4603CE664510605160334697 +:1005B00002F10802F6D13378137041460122204639 +:1005C00000F09EFD00230393AB7E029305F1190317 +:1005D000019380B20123CDE904800093E97E05A355 +:1005E000D3E90023384602F0B9FB0DF54E7DBDE896 +:1005F000F08100BF9E6AC421818A46EEB4230020A8 +:10060000A44600082DE9F0412C4C237ADAB080464C +:100610000D465BBB27A9284600F082FE074600284E +:1006200042D19DF89D60C82E3ED801464FF4A66287 +:10063000204600F019FD4FF48073C4F8F8314FF4F0 +:100640000073C4F80C334FF44073C4F820343246BE +:100650000DF19E0104F1090000F0F4FC26449DF820 +:100660009C30777223720BB9EB7E237281220021BA +:1006700006AC27A800F0F8FC0122214627A800F0CC +:100680008BFE00230393AB7E029305F1190380B226 +:1006900001932823CDE904400093E97E05A3D3E923 +:1006A0000023404602F05AFB5AB0BDE8F08100BF7B +:1006B000AFF3008026417272DF25D7B7C048002013 +:1006C000F0B5254E4FF48A7505FB0065F1B096F83C +:1006D000D83085F8DC300024D822214685F8E8405F +:1006E0003AA800F0C1FC06F1090000F0B5FCD5F80D +:1006F000E4308DF8F000C2B206AF06F109010DF149 +:10070000F100CDE93A3400F09DFC394601223AA8C7 +:1007100000F06EFE80B2CDE9047008230127CDE918 +:10072000023706F1D803019330230093317A0B4846 +:1007300007A3D3E9002302F011FBA04206DD01F07C +:100740004FFFC5F8E000384671B0F0BD2046FBE72A +:1007500078F6339F93CACD8DC0480020CC3300205B +:100760002DE9F0411D4D1E4E1E4F86B0284602F069 +:1007700021FB034658B30024CDE90344ADF81440EF +:10078000027B8DF8142099684068029403AA03C282 +:100790001B68DFF8548043F00043029301F022FF0E +:1007A000821941F10003009402A9384601F0ACF827 +:1007B000A04205DD284602F001FB88F80040D5E79D +:1007C00098F80030072B05D8013388F8003006B0C0 +:1007D000BDE8F081014802F0F1FAF8E7CC330020DF +:1007E00040420F0000340020F54D002070B50D464A +:1007F00014461E4602F00EFA50B9022E10D1012CFA +:100800000ED112A3D3E90023C5E90023012007E09C +:10081000282C10D005D8012C09D0052C0FD0002091 +:1008200070BD302CFBD10BA3D3E90023ECE70BA365 +:10083000D3E90023E8E70BA3D3E90023E4E70BA304 +:10084000D3E90023E0E700BFAFF30080401DA12003 +:1008500026812A0B78F6339F93CACD8D9E6AC421D8 +:10086000818A46EE26417272DF25D7B7F017304AEB +:1008700039059E5638B505460E4C0021013500F06D +:10088000B9FBA4F82C55B4F82C0500F09BFB78B10B +:10089000B4F82C0500F0A6FB014648B9B4F82C05C5 +:1008A00000F0A8FBB4F82C350133A4F82C35EAE7A6 +:1008B00038BD00BFC048002010B50A4B0A4A1A6074 +:1008C00003F5805393F848203AB95C6C2CB120466C +:1008D00000F084FE204603F093FEBDE8104003487C +:1008E00000F07CBE00340020F046000830440020B8 +:1008F0002DE9F04F8FB000AF05460C4602F08AF9A3 +:10090000002849D1237E022B1BD1E38A012B18D169 +:1009100001F066FE0646FFF7E5FD03464FF4C8709A +:10092000DFF8C482B3FBF0F206F5167602FB103353 +:1009300016FA83F3C8F80030E37E33B9A34B0022E4 +:100940001A703C37BD46BDE8F08F07F12401204600 +:1009500000F0A4FC0028F4D107F11400FFF7DAFD41 +:1009600097F8264007F11401224607F1270003F00B +:100970005FFE0028E2D10F2C08D8944B1C70D8F8E9 +:100980000030A3F51673C8F80030DAE797F82410A2 +:10099000284602F037F9D4E7E38A282B2BD010D869 +:1009A000012B23D0052BCCD1BFF34F8F8849894B26 +:1009B000CA6802F4E0621343CB60BFF34F8F00BFFD +:1009C000FDE7302BBDD1844EE17E327A9142B8D121 +:1009D000607E3146002291F8DC50854200F0A5800F +:1009E0000132042A01F58A71F5D1AAE72146284689 +:1009F000FFF7A0FDA5E721462846FFF703FEA0E785 +:100A0000B2F8EC507B6005F103094FEA99094FEA0F +:100A10008902D11DC908A8EBC1039D46EB46002100 +:100A2000584600F021FB04F1EE012A4631445846B5 +:100A300000F008FB7B6813B9012000F0B9FA96F8C2 +:100A4000D20000F0BFFA044630B9307200F0DAFA92 +:100A5000204600F0ADFAB1E0D6F8D4203AB996F8C5 +:100A6000D200B6F82C25824201D8FFF703FFD6F852 +:100A7000D4202A44944208D296F8D200B6F82C2505 +:100A80000130824201D8FFF7F5FE70685FFA89F203 +:100A9000594600F0F1FA08B9C54679E0726896F84F +:100AA000D2002A447260D6F8D42005EB0209C6F8B9 +:100AB000D49000F087FA814509D396F8D220D6F871 +:100AC000D4000132001B86F8D220C6F8D400FF2DD6 +:100AD0000FD80024347200F095FA204600F068FA2E +:100AE00000F002FD3D4B188108B9FFF7A3FCC54695 +:100AF00027E7BB6896F8D9000AFB0362FB68D2F8C7 +:100B0000E41082F8E83001F58061C2F8E030C2F804 +:100B1000E410FFF7D5FDFFF723FE96F8D920013248 +:100B200002F0030286F8D920B6E74FF48A7A0AFB6E +:100B300002F505F1EA013144204600F085FCF86039 +:100B400000287FF4FEAE3544012285F8E82001F04C +:100B500047FDD5F8E020D6ED007ADFED216A801A56 +:100B6000192838BF192040F6B832904228BF1046E5 +:100B7000B8EE677A07EE900AF8EEE77A67EEA67AA3 +:100B8000DFED186AE7EE267AFCEEE77AC6ED007A2A +:100B900096F8D930BB60BA6873680AFB02F4321960 +:100BA00092F8E81059B1D2F8E4108B42E8463FF4CD +:100BB00027AF002182F8E810C2F8E010C54673683C +:100BC000064A9B0A01331381BBE600BFC5330020F0 +:100BD00000ED00E00400FA05C0480020B423002026 +:100BE000CDCCCC3D6666663FC8330020014B187003 +:100BF000704700BFC023002038B54FF00054134B9E +:100C000022689A4220D1124B627D12481A70237DCD +:100C100003724FF48073C0F8F8314FF40073C0F8DA +:100C20000C3300254FF44073C0F820340A49C0F853 +:100C3000E450C922093000F005FAE0222946204696 +:100C400000F012FA012038BD0020FCE79AAD44C53F +:100C5000C0230020C04800201600002037B500F057 +:100C600043FC194D1949288102236B71002201238D +:100C7000174801F093F800230193164B164900938F +:100C80001648174B4FF4805201F094FF154B19781A +:100C900011B1124801F0B6FF01F0A2FC0446FFF7C3 +:100CA00021FC4FF4C873B0FBF3F202FB130304F50D +:100CB000167010FA83F00C4B186003F051FB08B16A +:100CC0000F232B8103B030BDB423002040420F001E +:100CD00000340020ED070008C4230020CC3300209E +:100CE000F1080008C0230020C83300202DE9F04F90 +:100CF0002DED028B90A7D7E900670FF24429D9E9BF +:100D00000089884C95B00DAD9FED848BFFF728FDD1 +:100D1000DFF834B200230C93ADF83C300D936B60D8 +:100D200000230DF125028DED008B4FF0010A09A97A +:100D300058468DF825308DF824A001F0B9FB9DF8B8 +:100D400024200023002A40F0AF80204601F062FFFB +:100D50000546002847D1DFF8F4B101F041FCDBF88B +:100D6000003098423FD301F03BFC0790FFF7BAFBFD +:100D7000079A4FF4C873B0FBF3F101FB130302F5BC +:100D8000167010FA83F0CBF80000DFF8C4B19BF8BE +:100D900000100791002914BF2B46534610A88DF868 +:100DA0003030FFF7B7FB0799C1F11002D2B2062A23 +:100DB00010AB28BF062219440DF13100079200F054 +:100DC00041F9079A0CAB0393182302930132564B57 +:100DD000D2B2CDE900A304923B463246204601F050 +:100DE0005FFF8BF8005001F0FBFB504A504D136839 +:100DF000C31AB3F57A7F32D3106001F0F3FB0246D9 +:100E00000B46204601F0E4FF204601F003FF30B31B +:100E10002B7ADFF840A1002B14BF032302238AF8AA +:100E2000053001F0DDFB0DF1400B4FF47A73012228 +:100E3000B0FBF3F05946CAF80000504600F006FA3D +:100E4000182302933B4B019380B240F25513CDE936 +:100E500003B0009342464B46204601F021FF2B7A17 +:100E6000B3B101F0BDFB4FF0000A83464FF48A7224 +:100E700095F8D900504400F0030002FB005393F8AA +:100E8000E810002934D00AF1010ABAF1040FEFD1B9 +:100E9000C82002F019FF2B7A002B7FF434AF15B075 +:100EA000BDEC028BBDE8F08F4FF0904110A84A696D +:100EB00082F020024A611946102200F0D5F80DF1A7 +:100EC00026030AAA0CA9584600F012FE95E8030072 +:100ED00011AB83E803009DF83C308DF84C300C9B3F +:100EE000109310A9DDE90A23204602F045F917E71F +:100EF000D3F8E01049B12B68FA2B38BFFA23ABEBDB +:100F000001010533B1EB430FBDD3FFF7D9FB4FF41C +:100F10008A720028B7D1BBE7AFF300800000000061 +:100F200000000000CC330020C4330020F04D00202E +:100F3000C0480020F44D0020401DA12026812A0B2E +:100F4000F1C6A7C1D068080F00340020C8330020C4 +:100F5000C5330020B423002008B5054800F06EFE1C +:100F6000BDE80840034A0449002003F043BB00BF2A +:100F700000340020304E0020B908000870B503F09E +:100F80003FF8094E094D3080002428683388834299 +:100F900008D903F031F82B6804440133B4F5204F2D +:100FA0002B60F2D370BD00BF244E0020F84D00200E +:100FB00003F0D8B800F10060920000F5204003F083 +:100FC0005BB80000054B1A68054B1B889B1A8342CF +:100FD00002D9104403F010B800207047F84D0020EB +:100FE000244E0020024B1B68184403F00BB800BFCE +:100FF000F84D0020024B1B68184403F015B800BFE1 +:10100000F84D0020064991F8243033B10023086AD6 +:1010100081F824300822FFF7CDBF0120704700BFC0 +:10102000FC4D0020022802BF4FF0904320229A611D +:1010300070470000022802BF4FF090434FF40012A7 +:101040009A61704710B50023934203D0CC5CC4541E +:101050000133F9E710BD000003460246D01A12F929 +:10106000011B0029FAD1704702440346934202D083 +:1010700003F8011BFAE770472DE9F8431F4D1446AA +:1010800095F824200746884652BBDFF870909CB341 +:1010900095F824302BB92022FF2148462F62FFF714 +:1010A000E3FF95F82400C0F10802A24228BF2246BF +:1010B000D6B24146920005EB8000FFF7C3FF95F8DA +:1010C0002430A41B1E44F6B2082E17449044E4B208 +:1010D00085F82460DBD1FFF795FF0028D7D108E021 +:1010E0002B6A03EB82038342CFD0FFF78BFF0028EC +:1010F000CBD10020BDE8F8830120FBE7FC4D0020A8 +:101100002DE9F0470D46044600219046284640F25E +:101110007912FFF7A9FF234620220021284601F07B +:10112000CDFF231D02222021284601F0C7FF631DA9 +:1011300003222221284601F0C1FFA31D03222521FD +:10114000284601F0BBFF04F108031022282128469D +:1011500001F0B4FF04F1100308223821284601F001 +:10116000ADFF04F1110308224021284601F0A6FF3B +:1011700004F1120308224821284601F09FFF04F1E0 +:10118000140320225021284601F098FF04F118038F +:1011900040227021284601F091FF04F1200308222B +:1011A000B021284601F08AFF04F121030822B8216A +:1011B000284601F083FF04F12207C0263B46314652 +:1011C00008222846083601F079FFB6F5A07F07F11E +:1011D0000107F3D104F1320308223146284601F019 +:1011E0006DFF002704F1330A94F832304FEAC70943 +:1011F0009F4209F5A47615D3B8F1000F08D1314606 +:1012000004F599730722284601F058FF09F24F169A +:10121000274694F832213B1B93420CD3F01DC008A3 +:10122000BDE8F0870AEB070308223146284601F0A3 +:1012300045FF0137D8E707F2331331460822284625 +:1012400001F03CFF08360137E3E7000013B5044620 +:101250000846002101602346C0F8031020220190B7 +:1012600001F02CFF0198231D0222202101F026FF0E +:101270000198631D0322222101F020FF0198A31D84 +:101280000322252101F01AFF019804F1080310221E +:10129000282101F013FF072002B010BDF7B500238D +:1012A000047F00910E4607221946054601F0CAFD4B +:1012B000731C0093012200230721284601F0C2FD80 +:1012C000C4B9B31C0093052223460821284601F027 +:1012D000B9FD0D243746B278BB1B934211D32B7F47 +:1012E000A88A0734E408BBB9844294BF00200120D7 +:1012F00003B0F0BDAB8ADB00083BDB08B370082409 +:10130000E8E7FB1C0093214600230822284601F051 +:1013100099FD08340137DEE7201A18BF0120E7E7FE +:10132000F7B50023047F00910E46082219460546B2 +:1013300001F088FD731CC4B90822009311462346AE +:10134000284601F07FFD1024012372785F1C013BC9 +:10135000934211D32B7FA88A0734E408BBB9844297 +:1013600094BF0020012003B0F0BDAB8ADB00083B36 +:10137000DB0873700824E7E7F31900932146002384 +:101380000822284601F05EFD08343B46DDE7201ABE +:1013900018BF0120E7E70000F8B50E4605461446E1 +:1013A000002181223046FFF75FFE2B4608220021F4 +:1013B000304601F083FE7CB96B1C072208213046C1 +:1013C00001F07CFE0F2401236A785F1C013B9342ED +:1013D00004D3E01DC008F8BD0824F4E7EB1921464A +:1013E0000822304601F06AFE08343B46ECE7000074 +:1013F000F8B50E46054614460021CE223046FFF7CA +:1014000033FE2B4628220021304601F057FE7CB9DE +:1014100005F1080308222821304601F04FFE302450 +:101420002F462A7A7B1B934204D3E01DC008F8BDE7 +:101430002824F5E707F1090321460822304601F088 +:101440003DFE08340137ECE7F7B5047F00910E4606 +:10145000012310220021054601F0F4FCC4B9B31C9D +:101460000093092223461021284601F0EBFC1924A1 +:1014700037467288BB1B9A4211D82B7FA88A073443 +:10148000E408BBB9844294BF0020012003B0F0BD42 +:10149000AB8ADB00103BDB0873801024E8E73B1DC0 +:1014A0000093214600230822284601F0CBFC083493 +:1014B0000137DEE7201A18BF0120E7E730B5094DF4 +:1014C0000A4491420DD011F8013B5840082340F3E3 +:1014D0000004013B2C4013F0FF0384EA5000F6D1D6 +:1014E000EFE730BD2083B8EDF7B5364A1068516894 +:1014F0006B4603C36A4634493448082303F0A8F80E +:10150000044690BB0A25324A106851686B4603C3F3 +:101510006A4630492D48082303F09AF8044600280B +:1015200047D00369B3F5583F43D8B0F86620B2F509 +:10153000826F3ED1284A024402F15C018B4238D3CB +:101540005C3B224900209E1AFFF7B8FF324607464F +:1015500004F164010020FFF7B1FFA3689F4228D186 +:10156000E368984208BF002523E00369B3F5583FBC +:1015700026D8428BB2F5826F20D1174A024402F17D +:1015800010018B4218D3103B104900209D1AFFF721 +:1015900095FF2A46064604F118010020FFF78EFF4A +:1015A000A3689E4202D1E368984201D00D25AAE7C4 +:1015B0000025284603B0F0BD1025A4E70C25A2E7BE +:1015C0000B25A0E7C0460008DC5F030000A0000870 +:1015D000C9460008905F03000860FFF710B5037C60 +:1015E000044613B9006803F01BF8204610BD000044 +:1015F0000023BFF35B8FC360BFF35B8FBFF35B8FD1 +:101600008360BFF35B8F7047BFF35B8F0068BFF3EE +:101610005B8F704770B505460C30FFF7F5FF05F19D +:10162000080604463046FFF7EFFFA04206D93046D1 +:101630006D68FFF7E9FF2544281A70BD3046FFF7B3 +:10164000E3FF201AF9E7000070B50546406898B13D +:1016500005F10800FFF7D8FF05F10C0604463046F7 +:10166000FFF7D2FF8442304694BF6D680025FFF734 +:10167000CBFF013C2C44201A70BD000038B50C464D +:101680000546FFF7C7FFA04210D305F10800FFF79A +:10169000BBFF04446868B4FBF0F100FB1144BFF3E6 +:1016A0005B8F0120AC60BFF35B8F38BD0020FCE78F +:1016B0002DE9F041144607460D46FFF7C5FF844269 +:1016C00028BF0446D4B1B84658F80C6B4046FFF723 +:1016D0009BFF3044286040467E68FFF795FF331A31 +:1016E0009C4203D86C600120BDE8F0816B60A41BB4 +:1016F0003B68AB602044E8600220F5E72046F3E752 +:1017000038B50C460546FFF79FFFA04210D305F100 +:101710000C00FFF779FF04446868B4FBF0F100FBAC +:101720001144BFF35B8F0120EC60BFF35B8F38BDCA +:101730000020FCE72DE9FF41884669460746FFF790 +:10174000B7FF6C4606B204EBC6060025B44209D0CA +:101750006268206808EB0501FFF774FC63680834D1 +:101760001D44F3E729463846FFF7CAFF284604B070 +:10177000BDE8F081F8B505460C300F46FFF744FF91 +:1017800005F1080604463046FFF73EFFA04230460A +:1017900088BF6C68FFF738FF201A386020B13046E8 +:1017A0002C68FFF731FF2044F8BD000073B51446E4 +:1017B00006460D46FFF72EFF844228BF04460190DF +:1017C000DCB101A93046FFF7D5FF019B33B9326880 +:1017D000C5E90233C5E9002401200CE09C4238BF72 +:1017E00001942860019868608442F5D93368AB6041 +:1017F000241AEC60022002B070BD2046FBE7000016 +:101800002DE9FF410F466946FFF7D0FF6C4600B255 +:1018100004EBC0050026AC4209D0D4F8048054F88B +:10182000081BB8194246FFF70DFC4644F3E7304663 +:1018300004B0BDE8F081000038B50546FFF7E0FFD1 +:10184000044601462846FFF719FF204638BD000030 +:101850007047000010B41346026814680022A446C2 +:101860005DF8044B6047000000F5805090F8590483 +:101870007047000000F5805090F852047047000057 +:1018800000F5805090F958047047000050207047D0 +:10189000302383F3118800F58052D2F89C34D2F8BB +:1018A00098041844D2F894341844D2F87C3418447C +:1018B000D2F88C341844D2F888341844002383F3C7 +:1018C0001188704700F58050C0F85414012070470B +:1018D00038B5C26A936923F001039361044600F0AE +:1018E0007FFE0546E36A9B69DB0706D500F078FEBC +:1018F000431BFA2BF6D9002004E004F580540120A4 +:1019000084F8520438BD00002DE9F04F0C4600F574 +:10191000805185B01F4691F85234BDF83890054685 +:1019200090469BB1D1F878340133C1F878342368FC +:10193000980006D4237B082B0BD9627B0AB10F2BAE +:1019400007D9D1F87C340133C1F87C344FF0FF3033 +:1019500010E0302383F31188EB6AD3F8C42012F42B +:10196000001B0AD0D1F880340133C1F88034002044 +:1019700080F3118805B0BDE8F08FD3F8C43020683B +:10198000C3F3014A6B6A4822002812FB0A33B4BF32 +:1019900040F08040800418602268520044BF40F04C +:1019A00000501860207B4FEA0A6242EA00425A6007 +:1019B000607B4FEA4A1610B342F440125A60D1F8E5 +:1019C000B0240132C1F8B024AA1902F58352117B68 +:1019D00041F020011173207B039300F05DFE039B17 +:1019E000033080105FFA8BF282420BF1010B0DDAAB +:1019F00004EB820103EB820249689160F2E7AA19C5 +:101A000002F58352117B60F34511E3E7EB6A012293 +:101A100002FA0AF2C3F8CC2005EB4A11AB1903F520 +:101A2000825301F58251C3E904871831234604F13A +:101A30000C0253F8040B41F8040B9342F9D11B88B4 +:101A40000B802E4441F2680346F803A006F5805649 +:101A500009F0030396F86C2043F0100322F01F02F4 +:101A6000134386F86C30002383F31188CDF800907F +:101A700042463B462146284600F0D4FD012079E746 +:101A800013B500F580540191606CFFF7DDFD1F2850 +:101A90000AD90199606C2022FFF74CFEA0F12003C7 +:101AA0005842584102B010BD0020FBE708B5302372 +:101AB00083F3118800F58050406CFFF799FD0023F7 +:101AC00083F3118808BD0000002202608281426019 +:101AD0008260704710B500220023C0E90023002374 +:101AE000044603810C30FFF7EFFF204610BD0000D5 +:101AF0002DE9F0479A4688B007468846914630233C +:101B000083F3118807F580546846FFF7E3FF606CA4 +:101B1000FFF780FD1F282DD9606C20226946FFF752 +:101B20008BFE202826D194F852341BB303AD4446D3 +:101B300005AB2E4603CE9E4220606160354604F11F +:101B40000804F6D130682060B388A380DDE9002363 +:101B5000C9E90023BDF80830AAF80030002383F358 +:101B6000118853464A464146384608B0BDE8F0471A +:101B700000F046BD002080F3118808B0BDE8F08772 +:101B80002DE9F84F00230646C0E90133284B46F8FB +:101B9000303B00F5815405468846374610343846B8 +:101BA0002037FFF797FFA742F9D105F580544FF48E +:101BB000805326630026C4E90D366764012305F5CA +:101BC000835705F5A359E66384F8403084F848301C +:101BD000103709F110094FF0000A4FF0000B47E9E8 +:101BE00008ABA7F11800FFF76FFF203747F8286C04 +:101BF0004F45F4D184F85884A4F85A64A4F85C647E +:101C0000A4F85E6484F86064A4F86264A4F8646470 +:101C1000A4F8666484F86864B8F1000F02D005483F +:101C200000F0D8FC044BEB622846BDE8F88F00BFFB +:101C3000F0460008D44600080064004010B5044B8C +:101C4000197804464A1C1A70FFF79AFF204610BD07 +:101C50002D4E00202DE9F84315460C4600295CD096 +:101C6000022001F019FE2E49B0FBF4F78C428CBF24 +:101C70000A2111214B1EB7FBF1F601FB1671DAB2F6 +:101C800021B1022B1946F5D8002032E0731EB3F5BE +:101C9000806FF9D2C2EBC20808F103014FEAE10EEE +:101CA000C1F3C701A2EB010C0EF101094FF47A73E5 +:101CB0005FFA8CF70EFB033E59FA8CFCBEFBFCFC72 +:101CC000BCF5617F17DC1FFA8CF34A1C57FA82F2CD +:101CD0007243B0FBF2F08442D6D14A1E0F2AD3D809 +:101CE0007A1E072AD0D801202B806E802871697156 +:101CF000AF71BDE8F88308F1FF314FEAE10CC1F3A1 +:101D0000C701521A0CF1010ED7B20CFB03335EFA75 +:101D100082F2B3FBF2F39BB2D7E70846E9E700BFD4 +:101D20003F420F0030B50D4B0D4D05201C786C4324 +:101D30008C420ED15978518099785171D97891712E +:101D4000197911715B7903EB83035B001380012028 +:101D500030BD013803F10603E8D1F9E73047000848 +:101D600040420F000B4B10B54FF454720446002153 +:101D70001846FFF779F9084BA3614033E361D83384 +:101D80002362F0336362E36A60610022C3F8C0201B +:101D900010BD00BF00A4004070A400402DE9F04F2A +:101DA00000F580551F4695F85834012B89B004463C +:101DB0008946904604D90026304609B0BDE8F08F28 +:101DC0009A4A52F8231009B942F823009848C4F8F7 +:101DD0000C900178277499B9302383F31188954BBF +:101DE0009A6D42F000729A659A6B42F000729A63A3 +:101DF0009A6B22F000729A630123037081F31188B9 +:101E000095F851647EB9302383F31188032115209E +:101E100001F056FE0321162001F052FE012385F841 +:101E2000513486F31188302383F31188E26A936971 +:101E300023F01003936100F0D3FB8246E36A9E69AE +:101E400016F0080609D000F0CBFBA0EB0A03FA2B32 +:101E5000F4D9002686F31188AEE79A6942F00102B0 +:101E60009A6100F0BDFB8246E36A9A69D00706D406 +:101E700000F0B6FBA0EB0A03FA2BF5D9E9E79A6963 +:101E800042F002029A61E36A4FF0000AC3F854A0DC +:101E90008AF31188686CFFF7ABFB04F5825B0BF1EA +:101EA000100B202200216846FFF7DEF802A8FFF79A +:101EB0000BFECDF818A06A460BEB06030DF1180EC9 +:101EC0009446BCE80300F44518605960624603F18B +:101ED0000803F5D1DCF80000186020369CF80420D7 +:101EE0001A71B6F5806FDCD1002304F5A25285F893 +:101EF000503485F853341A3249462046FFF7AAFE7B +:101F0000064690B9E26A936923F00103936100F0F9 +:101F100067FB0546E36A9B69D9077FF54CAF00F084 +:101F20005FFB431BFA2BF5D945E795F85E34C5F8FE +:101F30006C94591E95F85F34E26A013B1B0243EA38 +:101F4000416395F8601401390B43B5F85C1401390D +:101F500043EA0143D361B8F1000F36D004F5A35230 +:101F6000023241462046FFF7DDFE90B9E26A9369EE +:101F700023F00103936100F033FB0546E36A9B699C +:101F8000DA077FF518AF00F02BFB431BFA2BF5D9CE +:101F900011E795F86724C5F87084511E95F86824F8 +:101FA000E36A013A120142EA012295F86614013906 +:101FB0000A43B5F86414013942EA014242F40002CE +:101FC000DA60E36A4FF420629A642046FFF7CAFEA3 +:101FD000002385F85934E36A6FF040421A65E36ADA +:101FE000154A5A65E36A44229A65E36A0722C3F8F0 +:101FF000DC20E36A03229742DA653FF4DDAEE26A51 +:10200000936923F00103936100F0EAFA0746E36A5B +:102010009B69DB0705D500F0E3FAC31BFA2BF6D961 +:10202000C9E6012385F85234C6E600BF284E0020D9 +:102030002C4E0020001002409B0008002DE9F04FBC +:10204000054689B090469946002741F2680A00F596 +:102050008056EB6AD3F8D430FB40D80751D505EB56 +:10206000471252444FEA471B1379190749D4D6F84F +:1020700084340133C6F8843405F5A553C3E90089D7 +:1020800013799A0648BFD6F8B43405EB0B0248BF63 +:102090000133524448BFC6F8B434137943F00803FF +:1020A0001371DB0722D596F85334FBB105F5825442 +:1020B000183468465C44FFF70DFD03AB04F1080CCF +:1020C000206861681A4603C2083464451346F7D194 +:1020D00020681060A2889A800123ADF808302B6830 +:1020E000CDE90089DB6B694628469847D6F8A834C5 +:1020F000D6F854040133C6F8A83410B103681B693C +:1021000098470137202FA4D109B0BDE8F08F000017 +:102110002DE9F04F8DB004460F4600F063FA824679 +:102120008946002F56D1E36AD3F89020920141BF2F +:1021300004F58051D1F898240132C1F89824D3F8DD +:102140009020160703D100200DB0BDE8F08FD3F822 +:102150009050E669C5F30125482303FB0566E84670 +:102160004046FFF7B1FC326851004ABF22F060439D +:10217000C2F38A4343F00043920048BF43F08043D8 +:102180000093736813F400131FBF04F580520123FA +:102190008DF80D30D2F8B8340EBF8DF80D30013304 +:1021A000C2F8B834F38803F00F038DF80C304FF009 +:1021B000000B9DF80C0000F06FFA5FFA8BF3984269 +:1021C00020D9F2180CA90B44127A03F82C2C0BF12D +:1021D000010BEEE7012FB6D1E36AD3F89820950101 +:1021E00041BF04F58051D1F898240132C1F89824F8 +:1021F000D3F898201007A6D0D3F89850266AC5F3D4 +:102200000125A9E7EFB9E36AC3F8945004A8FFF7E2 +:1022100061FC98E80F0007AD07C52B800023ADF8DF +:10222000183023682046CDE904A9DB6B04A9984740 +:1022300004F5805458B1D4F890340133C4F8903484 +:1022400082E7012F04BFE36AC3F89C50DEE7D4F8AD +:1022500094340133C4F89434012075E72DE9F0413A +:1022600005460F4600F58054012639462846FFF7FB +:102270004FFF10B184F85364F7E7D4F8A834D4F8CA +:1022800054040133C4F8A83420B10368BDE8F04118 +:102290001B691847BDE8F081F0B5C36A1A6C12F4E7 +:1022A0007F0F2BD000F580541B6CC4F8AC3441F286 +:1022B0006805002347194FF0010C00EB43122A4434 +:1022C0005E01117911F0020F15D0490713D4B959E5 +:1022D000C66AD6F8C8E00CFA01F111EA0E0F0AD06E +:1022E000C6F8D010117941F004011171D4F88C2492 +:1022F0000132C4F88C240133202BDED1F0BD000064 +:1023000010B5254C254B226802B338B31A6D12065E +:102310000ED580221A6500F065F950EA01020B46DD +:1023200002D0013861F1000302462068FFF786FE03 +:102330001A4A136D1B032AD523684FF4002103F5B5 +:1023400080531165012283F8592420E001221A6587 +:1023500008221A654FF480621A6510BD196DC8070E +:1023600002D4196D890705D503211965104600218E +:10237000FFF774FF094B1A6D100702D41A6DD106CE +:1023800005D518221A6520680121FFF767FF20682C +:10239000BDE81040FFF780BF284E002000640040D9 +:1023A00008B5302383F31188FFF776FF002383F30A +:1023B000118808BDC36AD3F8C40080F40010C0F3CC +:1023C0004050704708B5302383F3118800F58050E2 +:1023D000406CFFF71FF9002383F3118843090CBFFA +:1023E0000120002008BD000000F5805393F8592417 +:1023F00062B1C16A8A6922F001028A61D3F89C2421 +:102400000132C3F89C24002283F85924704700004D +:102410002DE9F743302181F3118800F58251103105 +:10242000002541F2680E4FF0010800F5805C00EBDA +:1024300045147444267977071CD4F6061AD5D0F8CB +:102440002C908E69D9F8C87008FA06F63E4211D071 +:102450004F6801970F689742019F9F410AD2C9F8C0 +:10246000D060267946F004062671DCF888440134F1 +:10247000CCF888440135202D01F12001D7D100236B +:1024800083F3118803B0BDE8F0830000F8B51E4661 +:10249000002313700F4605461446FFF793FF80F0A4 +:1024A000010038701EB12846FFF784FF2070F8BD88 +:1024B0002DE9F04F85B09946DDE90EA30D46029354 +:1024C0001378019391F800B08046164600F08AF820 +:1024D0002B7804460F4613B93378002B41D022469F +:1024E0003B464046FFF794FFFFF75AFFFFF77CFF9C +:1024F0004B4632462946FFF7C9FF2B7833B1BBF173 +:10250000000F03D0012005B0BDE8F08F337813B180 +:10251000019B002BF6D108F580530393029B544591 +:1025200077EB03031DD2039BD3F85404C8B10368AF +:10253000AAEB04011B6898474B46324629464046A1 +:10254000FFF7A4FF2B7813B1BBF1000FDAD133787A +:1025500013B1019B002BD5D100F044F804460F467F +:10256000DCE70020CFE7000008B50020FFF7C8FE39 +:10257000BDE8084001F050B808B50120FFF7C0FEE3 +:10258000BDE8084001F048B800B59BB0EFF3098101 +:1025900068226846FEF756FDEFF30583014B9B6BFF +:1025A000FEE700BF00ED00E008B5FFF7EDFF00001B +:1025B00000B59BB0EFF3098168226846FEF742FD43 +:1025C000EFF30583014B5B6BFEE700BF00ED00E01E +:1025D000FEE700000FB408B5029801F025FBFEE706 +:1025E00001F006BE01F0E8BD13B56C4684E80600B4 +:1025F000031D94E8030083E80500012002B010BD2C +:1026000073B58568019155B11B885B0707D4D0E984 +:1026100000369B6B9847019AC1B23046A84701200B +:1026200002B070BDF0B5866889B005460C465EB153 +:10263000BDF838305B070AD4D0E900379B6B984768 +:102640002246C1B23846B047012009B0F0BD002291 +:102650000023CDE900230023ADF808300A4603AB80 +:1026600001F10806106851681C4603C40832B242E2 +:102670002346F7D1106820609288A280FFF7B2FF4E +:102680000423ADF808302B68CDE90001DB6B694607 +:1026900028469847D8E70000082817D909280CD001 +:1026A0000A280CD00B280CD00C280CD00D280CD0EC +:1026B0000E2814BF4020302070470C207047102097 +:1026C0007047142070471820704720207047000082 +:1026D0002DE9F041456A15B94162BDE8F0814B68CA +:1026E00023F06047C3F38A464FEAD37EC3F3807872 +:1026F00016EA230638BF3E46AC462B465A68BEEB68 +:10270000D27F22F060440AD0002A18DAA40CB44226 +:1027100017D19D420FD10D60DEE71346EEE7A742C9 +:1027200007D102F08044C2F3807242450BD054B10D +:10273000EFE708D2EDE7CCF800100B60CDE7B4422C +:1027400001D0B442E5D81A689C46002AE5D1196048 +:10275000C3E700002DE9F047089D01F007044FEAA8 +:10276000D508224405F0070500EBD1004FF47F495E +:10277000944201D1BDE8F08704F0070705F0070A8D +:1027800057453E4638BF5646C6F10806111B8E42D5 +:1027900028BF0E46E10808EBD50E415C13F80EC0C9 +:1027A000B94029FA06F721FA0AF1FFB28CEA0101D1 +:1027B00047FA0AF739408CEA010C03F80EC034449A +:1027C0003544D5E780EA0120082341F2210201B215 +:1027D0004000002980B203F1FF33B8BF504013F02E +:1027E000FF03F4D17047000038B50C468D18A542A0 +:1027F00000D138BD14F8011BFFF7E4FFF7E7000034 +:1028000042684AB1136843604389818901339BB2AE +:102810009942438138BF83811046704770B588B0B4 +:10282000202204460D4668460021FEF71DFC204686 +:102830000495FFF7E5FF024658B16B46054608AE22 +:102840001C4603CCB44228606960234605F10805A4 +:10285000F6D1104608B070BD082817D909280CD049 +:102860000A280CD00B280CD00C280CD00D280CD02A +:102870000E2814BF4020302070470C2070471020D5 +:1028800070471420704718207047202070470000C0 +:10289000082817D90C280CD910280CD914280CD9C1 +:1028A00018280CD920280CD930288CBF0F200E20D6 +:1028B0007047092070470A2070470B2070470C2092 +:1028C00070470D20704700002DE9F843078C072F53 +:1028D00004461ED9D0E9029800254FF6FF73C5F1D2 +:1028E0002006A5F1200029FA05F108FA06F628FAD3 +:1028F00000F031430143C9B21846FFF763FF0835C2 +:10290000402D0346EBD1E1693A46BDE8F843FFF7B5 +:102910006BBF4FF6FF70BDE8F883000010B54B6841 +:1029200023B9CA8A63F30902CA8210BD04691A680E +:102930001C600361C38A013BC3824A60EFE7000069 +:102940002DE9F84F1D46CB8A0F46C3F3090105292F +:10295000814692460B4630D00020AAB207F11A04F5 +:102960009EB2042E1FFA80F80FD8904503F10103A0 +:1029700006D3FB8A0A4462F30903FB8201201AE0B2 +:102980001AF80060E6540130EAE79045F1D2A1F16F +:10299000050B1C237C68BBFBF3F203FB12BB1FFA85 +:1029A0008BF6002C45D14846FFF72AFF044638B97C +:1029B00078606FF00200BDE8F88F4FF00008E6E79E +:1029C000002606607860ADB24FF0000B454510D987 +:1029D0000AEB0803221D13F8011B9155B1B208F14F +:1029E00001081B291FFA88F82BD0454506F101067E +:1029F000F1D8FB8AC3F30902154465F30903BCE768 +:102A0000013292B21C462368002BF9D16B1F0B4494 +:102A10001C21B3FBF1F301339BB29A42D3D2BBF139 +:102A2000000FD0D14846FFF7EBFE20B9C4F800B044 +:102A3000BFE70122E7E7C0F800B05E462060044629 +:102A4000C1E74545D5D94846FFF7DAFE08B9206009 +:102A5000AFE7C0F800B0002620600446B6E70000EB +:102A60002DE9F04F2DED028B1C4683B05B6901927E +:102A700007468846002B00F09A80238C2BB1E26930 +:102A8000002A00F09480072B35D807F10C00FFF7DF +:102A9000B7FE054638B96FF00205284603B0BDEC15 +:102AA000028BBDE8F08F14220021FEF7DDFA228CA4 +:102AB000E16905F10800FEF7C5FA208C013080B20B +:102AC000FFF7E6FEFFF7C8FE013880B22084013030 +:102AD00028746369228C1B782A4403F01F0363F077 +:102AE0003F0348F000411372384669602946FFF7FA +:102AF000EFFD0125D1E700F10C034FF0000908EECE +:102B0000103A4FF0800A4E464D4618EE100AFFF775 +:102B100077FE83460028BED014220021FEF7A4FAD7 +:102B2000002E3AD1019BABF8083002220BF1080EBF +:102B30001FFA82FC0CF10100BCF1060F218C80B25F +:102B400001D88E422BD3FFF7A3FEFFF785FE626903 +:102B50001278013802F01F028E4208BF4FF0400A7F +:102B600042EA49121BFA80F14AEA020A013048F0AF +:102B7000004281F808A08BF81000CBF804205946D9 +:102B80003846FFF7A5FD238C0135B3422DB289F0FD +:102B900001094FF0000AB8D17FE70022C6E7E169DA +:102BA000895D0EF802100136B6B20132C0E76FF04F +:102BB000010572E7F8B515460E463022002104469D +:102BC0001F46FEF751FA069B6360B5F5001F079B91 +:102BD000A76034BF6A094FF6FF72A36297B2E6613D +:102BE00004F1100000239A4206D800230360A78254 +:102BF000E3822383E360F8BD06600133304620366C +:102C0000F1E7000003781BB94BB2002BC8BF01707D +:102C10007047000000787047F8B50C46C969074650 +:102C200011B9238C002B37D1257E1F2D34D838784D +:102C300028BB228C072A2CD8268A36F003032BD1F6 +:102C40004FF6FF70FFF7D0FD20F001003102400485 +:102C500041EA0561400C41EA40254FF6FF722346E8 +:102C600029463846FFF7FCFE002807DD6269137825 +:102C70000133DBB21F2B88BF00231370F8BD218AFC +:102C80002D0645EA012505432046FFF71DFE0246B5 +:102C9000E5E76FF00300F1E76FF00100EEE70000F9 +:102CA00070B58AB0044616460021282268461D46A3 +:102CB000FEF7DAF9BDF83830ADF810300F9B059308 +:102CC0009DF840308DF81830119B07936946BDF888 +:102CD0004830ADF820302046CDE90265FFF79CFF73 +:102CE0000AB070BD2DE9F041D36905460C46164681 +:102CF0000BB9138C5BBB377E1F2F28D895F800804B +:102D0000B8F1000F26D03046FFF7DEFD3378210200 +:102D100041EAC33141EA0801338A41EA076141EAE5 +:102D200003410246334641F080012846FFF798FEF2 +:102D300000280ADD3378012B07D17269137801333B +:102D4000DBB21F2B88BF00231370BDE8F0816FF04A +:102D50000100FAE76FF00300F7E70000F0B58BB071 +:102D600004460D4617460021282268461E46FEF7F7 +:102D70007BF99DF84C305A1E534253418DF8003078 +:102D80009DF84030ADF81030119B05939DF8483008 +:102D90008DF81830149B07936A46BDF85430ADF88F +:102DA000203029462046CDE90276FFF79BFF0BB085 +:102DB000F0BD0000406A00B104307047436A1A68F1 +:102DC000426202691A600361C38A013BC382704791 +:102DD0002DE9F041D0F82080194E14461D46414699 +:102DE000002709B9BDE8F081D1E90223A21A65EBF9 +:102DF0000303964277EB03031ED2036A8B420DD185 +:102E0000FFF78CFD036A1B68036203690B60C38ACA +:102E10000161016A013BC3828846E2E7FFF77EFD5C +:102E20000B68C8F8003003690B60C38A0161013B7D +:102E3000C382D8F80010D4E788460968D1E700BFFC +:102E400080841E002DE9F04F8BB00D46DDF85090C8 +:102E500014469B468046002800F01981B9F1000F06 +:102E600000F01581531E3F2B00F21181012A03D17E +:102E7000BBF1000F40F00B810023CDE90833B8F817 +:102E80001430B5EBC30F4FEAC30703D300200BB0D8 +:102E9000BDE8F08F2B199F42D8F80C303ABF7F1B4A +:102EA000FFB227461BB9D8F81030002B7AD0272D57 +:102EB0004ED8C5F12806B7424FF000032CBFF6B23A +:102EC0003E4600932946D8F8080008AB3246FFF783 +:102ED00041FCA7EB060A35445FFA8AFAB8F81430C9 +:102EE00003F10053053BDB000493D8F80C30039347 +:102EF0002821039B13B1BAF1000F2CD1D8F8100090 +:102F000040B1BAF1000F05D0009608AB5246691ADD +:102F1000FFF720FC38B2002FB8D066070AD00AAB02 +:102F200003EBD401624211F8083C02F0070213419E +:102F300001F8083C082C3CD9102C40F2B580202C1C +:102F400040F2B780BBF1000F00F09C80082334E012 +:102F5000BA460026C2E7049BE02B28BFE023069375 +:102F60000B44AB42059314D95A1B03980096924523 +:102F700034BF5246D2B2691A08AB04300792FFF749 +:102F8000E9FB079A1644AAEB020A1544F6B25FFA67 +:102F90008AFA049B069A05999B1A0493039B1B6863 +:102FA0000393A6E70093D8F8080008AB3A462946F1 +:102FB000AEE7BBF1000F13D00123B4EBC30F6CD00D +:102FC000082C12D89DF82030621E23FA02F2D50791 +:102FD00006D54FF0FF3202FA04F423438DF8203077 +:102FE0009DF8203089F8003051E7102C12D8BDF838 +:102FF0002030621E23FA02F2D10706D54FF0FF32CD +:1030000002FA04F42343ADF82030BDF82030A9F8CB +:1030100000303CE7202C0FD80899631E21FA03F3F7 +:10302000DA0705D54FF0FF3202FA04F40C43089496 +:10303000089BC9F800302AE7402C2BD0DDE9086551 +:10304000611EC4F12102A4F1210326FA01F105FA5F +:1030500002F225FA03F311431943CB0712D50122DB +:10306000A4F12003C4F1200102FA03F322FA01F1D2 +:10307000A240524243EA010363EB430332432B4332 +:10308000CDE90823DDE90823C9E90023FFE66FF055 +:103090000100FCE66FF00800F9E6082CA0D9102C1E +:1030A000B3D9202CEED8C3E7BBF1000FADD002237B +:1030B00083E7BBF1000FBBD004237EE730B5012AC4 +:1030C000144638BF0124402C85B028BF4024002579 +:1030D000012ACDE9025518D81B788DF8083063070E +:1030E0000AD004AB03EBD405624215F8083C02F0A9 +:1030F0000702934005F8083C009103462246002150 +:1031000002A8FFF727FB05B030BD082AE4D9102A32 +:1031100003D81B88ADF80830E1E7202A8DBFD3E93A +:1031200000231B680293CDE90223D8E710B5CB68D2 +:103130001BB98B600B618B8210BD04691A681C601F +:103140000361C38A013BC382CA60F0E703064CBF38 +:10315000C0F3C0300220704708B50246FFF7F6FF03 +:10316000022806D15306C2F30F2001D100F003005C +:1031700008BDC2F30740FBE72DE9F04F93B0CDE95E +:1031800003230A6804461046FFF7E0FF022814BF35 +:10319000C2F306260026002A0D46824680F2F281FE +:1031A00012F0C04940F0EE81097B002900F0EA816D +:1031B000022803D02378B34240F0E781C2F30463CE +:1031C0000693104602F07F030593FFF7C5FF059BAA +:1031D00029444FEA834848EA0A4848EA4668CE78D4 +:1031E00000230022CDE90823F309834648EA0008BA +:1031F000029367D0059B009302466768534608A96F +:103200002046B847002800F0C381276A4FB94146DD +:1032100004F10C00FFF702FB074690B96FF00200C3 +:1032200054E03B6998450DD03F68002FF9D14146E5 +:1032300004F10C00FFF7F2FA07460028EED0236AEB +:103240003B60276297F817C006F01F08CCF3840C88 +:10325000ACEB08001FFA80FE0028B8BF0EF120007A +:10326000A8EB0C031FFA83FED7E90221B8BF00B216 +:10327000002B0793BEBF0EF120031BB2079352EA47 +:10328000010338D0039BDFF824E39A1A049B4FF024 +:10329000000C63EB010196457CEB01032BD36B7BA8 +:1032A00097F81AE0734519D1029B002B78D00128BA +:1032B00021DC7868F8B9DFF8F0C2944570EB0103BF +:1032C00016D337E0276A27B96FF00C0013B0BDE8BA +:1032D000F08F3B699845B5D03F68F4E7B24890421B +:1032E0007CEB010301D30020F0E7029B002BFAD016 +:1032F000079B0F2B17DCFA7DB30002F0030203F0EB +:103300007C031343FB7539462046FFF707FB6B7BB5 +:10331000BB76029B3BB9FB7DC3F38402013262F3AF +:103320008603FB75D0E76A7BBB7E9A42DBD1029BAA +:10333000002B35D0B309022B32D0039BBB60049B1A +:10334000FB60142200210DA8FDF78EFE039B0A935B +:10335000049B0B932B1D0C932B7BADF83EB0013BD4 +:10336000DBB2ADF83C30069B8DF84230059B8DF802 +:10337000433094F82C308DF840A083F001038DF891 +:1033800044308DF84180A3680AA920469847FB7D08 +:10339000C3F38403013303F01F039B02FB82A2E704 +:1033A000FB7DC6F34012B2EBD31F40F0F480C3F3B1 +:1033B0008403434540F0F280029A2B7BB609002A31 +:1033C0004DD0F2075DD4032B40F2EB80039BBB6032 +:1033D000049BFB602B7BAE1D033BDBB232463946C0 +:1033E00004F10C00FFF7ACFA00280CDA394620464D +:1033F000FFF794FAFB7DC3F38403013303F01F034B +:103400009B02FB820AE7DDE90884AB883B834FF629 +:10341000FF73C9F12000A9F1200228FA09F104FA8A +:1034200000F0014324FA02F211431846C9B2FFF733 +:10343000C9F909F10809B9F1400F0346E9D1B88289 +:103440002A7B033AD2B23146FFF7CEF9FB7DB88230 +:10345000DA43C2F3C01262F3C713FB7543E786B9C0 +:103460002E1D013BDBB23246394604F10C00FFF75A +:1034700067FA0028BADB2A7BB88A013AD2B2314611 +:10348000E2E7F98AC1F30901013B0429DAB25BD80A +:10349000281D002307F11B069A4208D910F801CB1A +:1034A00006F801C0013101330529DBB2F4D10399DB +:1034B0000A9104990B91934207F11B010C9138BFBB +:1034C000043379680D9134BF55FA83F300230E93CA +:1034D000FB8AADF83EB0C3F309031A44069B8DF88E +:1034E0004230059B8DF8433094F82C30ADF83C20E9 +:1034F00083F001038DF8443000238DF840A08DF84F +:1035000041807B602A7BB88A013A291DFFF76CF95C +:103510003B8BB882834203D1A3680AA9204698470F +:1035200020460AA9FFF702FEFB7DBA8AC3F3840393 +:10353000013303F01F039B02FB823B8B9A420CBFBB +:1035400000206FF01000C1E67B68002BAFD0052093 +:1035500001E01C3033461E68002EFAD1091A081DFE +:103560002E1D184401EB090CBCF11B0F5FFA89F307 +:103570009DD89A429BD916F8013B00F8013B09F10E +:103580000109EFE76FF00900A0E66FF00A009DE681 +:103590006FF00B009AE66FF00D0097E66FF00E00EB +:1035A00094E66FF00F0091E640420F0080841E0009 +:1035B000EFF3098305494A6B22F001024A6368333D +:1035C00083F30988002383F31188704700EF00E03C +:1035D000302080F3118862B60C4B0D4AD96821F473 +:1035E000E0610904090C0A43DA60D3F8FC200949B8 +:1035F00042F08072C3F8FC200A6842F001020A60BF +:103600002022DA7783F82200704700BF00ED00E047 +:103610000003FA05001000E010B5302383F3118891 +:103620000E4B5B6813F4006314D0F1EE103AEFF325 +:103630000984683C4FF08073E361094BDB6B2366C0 +:1036400084F3098800F0BAFA10B1064BA36110BDEB +:10365000054BFBE783F31188F9E700BF00ED00E0BD +:1036600000EF00E03F03000842030008434B4FF423 +:10367000007270B51A605A6912F4C06FFBD1404BEA +:103680009A6802F00C02042A20D01A6842F4807270 +:103690001A601A685205FCD501229A609A6802F0F5 +:1036A0000C02042AFAD13749374A0A600A6812F034 +:1036B0000F02FBD1C3F8982063221A601A689603A0 +:1036C000FCD42E4A4FF48071C2F88010C468E50320 +:1036D00006D51A6842F480321A601A689103FCD544 +:1036E000C269D20709D5D3F8982042F00102C3F885 +:1036F0009820D3F898209607FBD54269DA6044F405 +:1037000080721A6004F0807111B11A689501FBD5BE +:10371000996802691B4E22F0030501F00301294359 +:10372000996085693560316869400907FBD11349A3 +:1037300005680D6046684E608068C1F880006E04C0 +:1037400017D448698505FCD4996802F0030021F07C +:1037500003010143996092009968514011F00C0FE8 +:10376000FAD1E2055EBF1A6822F480721A60002066 +:1037700070BD48698005FCD5E6E700BF00700040D9 +:1037800000100240002002400006040008B500F0CE +:1037900083F9BDE8084000F05BB9000010B5394C72 +:1037A0003948A36A4FF0FF32A262A36A0023A362E2 +:1037B000A16AE16A61F07F01E162E16A01F07F01E3 +:1037C000E162E16A216B2263216B2363216BA16BB0 +:1037D000A263A16BA363A16BE16BE263E16BE363A3 +:1037E000E16B216C2264226C2364226C226E42F015 +:1037F00001022266D4F8802022F00102C4F8802061 +:10380000D4F88020A26D42F08052A265A26F22F00F +:103810008052A267A26F1D4A4FF400419160D360AD +:10382000136253629362D362136353639363D363EC +:10383000136453649364D36413655365116841F44E +:1038400080711160D4F8902012F4407F1EBF4FF4B5 +:103850008032C4F89020C4F890300D4A0023A36051 +:10386000C4F88820C4F89C30FFF700FF10B1094865 +:1038700000F0DAF9D4F8903023F00323C4F8903044 +:1038800010BD00BF00100240584700080070004003 +:103890005501005150470008014B53F82000704774 +:1038A00018230020074A08B5536903F00103536148 +:1038B00023B1054A13680BB150689847BDE808402A +:1038C000FFF7AABE0004014084500020074A08B553 +:1038D000536903F00203536123B1054A93680BB1A6 +:1038E000D0689847BDE80840FFF796BE0004014045 +:1038F00084500020074A08B5536903F0040353615C +:1039000023B1054A13690BB150699847BDE80840D7 +:10391000FFF782BE0004014084500020074A08B52A +:10392000536903F00803536123B1054A93690BB14E +:10393000D0699847BDE80840FFF76EBE000401401B +:1039400084500020074A08B5536903F010035361FF +:1039500023B1054A136A0BB1506A9847BDE8084085 +:10396000FFF75ABE0004014084500020164B10B5EA +:103970005C6904F478725A61A30604D5134A936A09 +:103980000BB1D06A9847600604D5104A136B0BB18F +:10399000506B9847210604D50C4A936B0BB1D06B42 +:1039A0009847E20504D5094A136C0BB1506C98474F +:1039B000A30504D5054A936C0BB1D06C9847BDE8BC +:1039C0001040FFF729BE00BF0004014084500020D2 +:1039D000194B10B55C6904F47C425A61620504D548 +:1039E000164A136D0BB1506D9847230504D5134A41 +:1039F000936D0BB1D06D9847E00404D50F4A136E58 +:103A00000BB1506E9847A10404D50C4A936E0BB1CC +:103A1000D06E9847620404D5084A136F0BB1506FFB +:103A20009847230404D5054A936F0BB1D06F98478C +:103A3000BDE81040FFF7F0BD0004014084500020B5 +:103A400008B500F0F3FCBDE80840FFF7E5BD000055 +:103A5000062108B5084600F033F80621072000F0DB +:103A60002FF80621082000F02BF80621092000F08D +:103A700027F806210A2000F023F80621172000F07D +:103A80001FF80621282000F01BF8BDE80840072198 +:103A90001C2000F015B800004FF0E0230022586809 +:103AA0004FF0FF31930003F1604303F561430132AE +:103AB0009042C3F88010C3F88011F3D27047000021 +:103AC00000F1604303F561430901C9B283F80013B3 +:103AD000012200F01F039A4043099B0003F1604359 +:103AE00003F56143C3F880211A6070470023037512 +:103AF000826803691B6899689142FBD25A68036027 +:103B00004260106058607047002303758268036943 +:103B10001B6899689142FBD85A6803604260106044 +:103B20005860704708B50846302383F311880B7D31 +:103B3000032B05D0042B0DD02BB983F3118808BDBE +:103B40008B6900221A604FF0FF338361FFF7CEFFCD +:103B50000023F2E7D1E9003213605A60F3E7000076 +:103B6000FFF7C4BF054BD9680875186802681A606A +:103B7000536001220275D860FCF7CCBB384E0020A0 +:103B800030B50C4BDD684B1C87B004460FD02B467C +:103B9000094A684600F02AF92046FFF7E3FF009B38 +:103BA00013B1684600F02CF9A86907B030BDFFF7E3 +:103BB000D9FFF9E7384E0020253B0008044B1A686E +:103BC000DB6890689B68984294BF00200120704792 +:103BD000384E0020084B10B51C68D86822681A605F +:103BE000536001222275DC60FFF78EFF01462046FC +:103BF000BDE81040FCF78EBB384E002038B5074CAE +:103C000007490848012300252370656000F03CFC4B +:103C10000223237085F3118838BD00BF6050002057 +:103C20007C470008384E002008B572B6044B186572 +:103C300000F0ACFA00F05CFB024B03221A70FEE7C6 +:103C4000384E00206050002000F010B98B60022335 +:103C500008618B82084670478368A3F1840243F8A9 +:103C6000142C026943F8442C426943F8402C094A59 +:103C700043F8242CC26843F8182C022203F80C2CB9 +:103C8000002203F80B2C044A43F8102CA3F1200067 +:103C9000704700BF2D030008384E002008B5FFF71D +:103CA000DBFFBDE80840FFF75BBF0000024BDB68AD +:103CB00098610F20FFF756BF384E0020302383F362 +:103CC0001188FFF7F3BF000008B50146302383F3E6 +:103CD00011880820FFF754FF002383F3118808BDE3 +:103CE00010B503689C68A2420CD85C688A600B60BF +:103CF0004C602160596099688A1A9A604FF0FF33CE +:103D0000836010BD1B68121BECE700000A2938BF56 +:103D10000A2170B504460D460A26601900F0AEFB74 +:103D200000F09AFB041BA54203D8751C2E460446DE +:103D3000F3E70A2E04D9BDE87040012000F0E4BB8F +:103D400070BD0000F8B5144B0D46D96103F11001A8 +:103D500041600A2A1969826038BF0A2201604860FE +:103D60001861A818144600F07BFB0A2700F074FBCA +:103D7000431BA342064606D37C1C281900F07EFB99 +:103D800027463546F2E70A2F04D9BDE8F84001205E +:103D900000F0BABBF8BD00BF384E0020F8B50646AB +:103DA0000D4600F059FB0F4A134653F8107F9F420F +:103DB00006D12A4601463046BDE8F840FFF7C2BFAB +:103DC000D169BB68441A2C1928BF2C46A34202D9DA +:103DD0002946FFF79BFF224631460348BDE8F840DD +:103DE000FFF77EBF384E0020484E002010B4C0E9D7 +:103DF000032300235DF8044B4361FFF7CFBF0000AE +:103E000010B5194C236998420DD0D0E90032816871 +:103E100013605A609A680A449A60002303604FF066 +:103E2000FF33A36110BD2346026843F8102F53608F +:103E30000022026022699A4203D1BDE8104000F0DE +:103E400017BB936881680B44936000F005FB2269FF +:103E5000E1699268441AA242E4D91144BDE81040D5 +:103E6000091AFFF753BF00BF384E00202DE9F04775 +:103E7000DFF8BC8008F110072C4ED8F8105000F085 +:103E8000EBFAD8F81C40AA68031B9A423ED81444A7 +:103E9000D5E900324FF00009C8F81C4013605A60A1 +:103EA000C5F80090D8F81030B34201D100F0E0FA24 +:103EB00089F31188D5E9033128469847302383F3E5 +:103EC00011886B69002BD8D000F0C6FA6A69A0EBA4 +:103ED00004094A4582460DD2022000F015FB00225B +:103EE000D8F81030B34208D151462846BDE8F04713 +:103EF000FFF728BF121A2244F2E712EB090938BF74 +:103F00004A4629463846FFF7EBFEB5E7D8F81030A9 +:103F1000B34208D01444211AC8F81C00A960BDE8B7 +:103F2000F047FFF7F3BEBDE8F08700BF484E002022 +:103F3000384E002038B500F08FFA054AD2E908451E +:103F4000031B181945F10001C2E9080138BD00BF83 +:103F5000384E002000207047FEE700007047000048 +:103F60004FF0FF3070470000BFF34F8F024A1369D4 +:103F7000DB03FCD4704700BF0020024008B5094BAA +:103F80001B7873B9FFF7F0FF074B5A69002ABFBFD0 +:103F9000064A9A6002F188329A601A6822F48062B6 +:103FA0001A6008BD785000200020024023016745B8 +:103FB00008B50B4B1B7893B9FFF7D6FF094B5A692D +:103FC00042F000425A611A6842F480521A601A683C +:103FD00022F480521A601A6842F480621A6008BDA6 +:103FE00078500020002002407F289ABF00F58030E2 +:103FF000C0020020704700004FF4006070470000CE +:10400000802070477F2808B50BD8FFF7EDFF00F53B +:1040100000630268013204D104308342F9D10120E7 +:1040200008BD0020FCE700007F2810B504461FD81B +:10403000FFF79AFFFFF7A2FF0E4BF3221A6102224D +:104040005A615A6942EAC0025A615A6942F480329E +:104050005A61FFF789FF4FF40061FFF7C5FF00F0D9 +:1040600043F9FFF7A5FF2046BDE81040FFF7CABFA0 +:10407000002010BD002002402DE9F84340EA020371 +:1040800013F00703144606D0304B40F241321A6059 +:104090000020BDE8F88385182D4A95420CD92B4A9B +:1040A00040F246311160F3E7031D1B684A689342F2 +:1040B00008D1083C08300831072C14D902680B6875 +:1040C0009A42F1D0FFF75AFFFFF74EFF214E083119 +:1040D0004FF001084FF00009012CA1F1080706D8A4 +:1040E000FFF766FF01E0002CECD10120D1E7C6F814 +:1040F0001480054651F8083C45F8043B51F8043C4F +:104100004360FFF731FF336943F001033361C6F8C1 +:104110001490026851F8083C9A420CD00B4B40F2C4 +:104120006E321A600C4B18600C4B1C600C4B1F60FD +:10413000FFF73EFFACE72D6851F8043C9D4201F1CA +:104140000801EBD1083C0830C6E700BF74500020DE +:104150000000040800200240685000207050002039 +:104160006C500020084908B50B7828B11BB9FFF73F +:1041700005FF01230B7008BD002BFCD0BDE80840F3 +:104180000870FFF715BF00BF7850002008B506493A +:10419000064800F0ABF8BDE808404FF480414FF00E +:1041A000805000F0A3B800BF007F01000001002094 +:1041B000084600F035BA000038B5EFF311859DB917 +:1041C000EFF30584C4F30804302334B183F311887A +:1041D000FFF7B0FE85F3118838BD83F31188FFF730 +:1041E000A9FE84F3118838BDBDE83840FFF7A2BEB0 +:1041F00038B5FFF7E1FF114C114AC00840EA4170A1 +:10420000A0FB025EC908A0FB040C1CEB050CA1FB83 +:1042100004404FF000035B41A1FB02121CEB040CB5 +:1042200043EB000011EB0E0142F10002411842F194 +:104230000000090941EA007038BD00BFCFF753E321 +:10424000A59BC4200244D2B2904200D17047431CC7 +:10425000800000F1804000F51450006841F8040B24 +:10426000D8B2F1E7124B10B5D3F89040240409D42A +:10427000D3F89040C3F89040D3F8904044F4004401 +:10428000C3F890400B4C2368024443F480732360CE +:10429000D2B2904200D110BD431C800000F180409A +:1042A00000F5145051F8044B0460D8B2F1E700BF98 +:1042B000001002400070004007B5012201A9002053 +:1042C000FFF7C0FF019803B05DF804FB13B5044687 +:1042D000FFF7F2FFA04205D0012201A900200194BE +:1042E000FFF7C0FF02B010BD70470000704700002C +:1042F00070470000074B45F255521A6002225A607F +:1043000040F6FF729A604CF6CC421A60024B0122D2 +:104310001A7070470030004080500020034B1B781B +:104320001BB1034B4AF6AA221A6070478050002046 +:1043300000300040054B1A6832B902F1804202F5A4 +:104340000432D2F894201A60704700BF7C500020DD +:10435000024B4FF40002C3F8942070470010024053 +:1043600008B5FFF7E7FF024B1868C0F3407008BDBF +:104370007C50002070470000FEE700000A4B0B480D +:104380000B4A90420BD30B4BDA1C121AC11E22F0BF +:1043900003028B4238BF00220021FCF765BE53F8B0 +:1043A000041B40F8041BECE7FC4800080451002003 +:1043B00004510020045100200023054A194601330E +:1043C000102BC2E9001102F10802F8D1704700BFBA +:1043D0008450002008B5124B9A6D42F001029A6594 +:1043E0009A6F42F001029A670E4A9B6F936843F0FE +:1043F000010393600620FFF74FFA0B4BB0FBF3F07D +:104400004FF080434FF0FF3201389862DA620022A9 +:104410009A615A63DA605A6001225A611A6008BDD3 +:1044200000100240002004E040420F004FF08042A4 +:1044300008B51169D3680B40D9B2C9439B07116114 +:1044400007D5302383F31188FFF7FEFB002383F3A6 +:10445000118808BDFFF7BEBF4FF08043586A704710 +:104460004FF08043002258631A610222DA607047DD +:104470004FF080430022DA60704700004FF0804325 +:1044800058637047FEE7000070B51B4B01630025C1 +:10449000044686B0586085620E46FFF799F804F12D +:1044A0001003C4E904334FF0FF33C4E90635C4E90F +:1044B0000044A560E562FFF7CFFF2B460246C4E942 +:1044C000082304F134010D4A256580232046FFF7B7 +:1044D000BDFB0123E0600A4A0375009272680192F5 +:1044E000B268CDE90223074B6846CDE90435FFF7F2 +:1044F000D5FB06B070BD00BF6050002088470008A3 +:104500008D47000885440008024AD36A1843D062E8 +:10451000704700BF384E00204B6843608B68836053 +:10452000CB68C3600B6943614B6903628B6943626B +:104530000B6803607047000008B5204BDA6A42F050 +:104540007F02DA62DA6A22F07F02DA62DA6ADA6C11 +:1045500042F07F02DA64DA6E42F07F02DA66184ACD +:10456000DB6E11464FF09040FFF7D6FF02F11C01C1 +:1045700000F58060FFF7D0FF02F1380100F58060A0 +:10458000FFF7CAFF02F1540100F58060FFF7C4FF96 +:1045900002F1700100F58060FFF7BEFF02F18C01AF +:1045A00000F58060FFF7B8FF02F1A80100F5806018 +:1045B000FFF7B2FFBDE80840FFF7F0B80010024077 +:1045C0009447000808B500F009F8FFF717FBBDE8AD +:1045D0000840FFF7AFBE00007047000008B5FFF7C6 +:1045E000D5F8FFF7E9FEFFF7F7FFBDE80840FFF752 +:1045F00031BF00000B460146184600F003B800002A +:1046000000F00EB810B5054C13462CB10A46014611 +:104610000220AFF3008010BD2046FCE70000000040 +:10462000024B01461868FFF7C3BD00BF40230020BE +:1046300010B501390244904201D1002005E0037811 +:1046400011F8014FA34201D0181B10BD0130F2E751 +:104650002DE9F041A3B1C91A17780144044603F1CA +:10466000FF3C8C42204601D9002009E00578BD427C +:1046700004F10104F5D10CEB0405D618A54201D1D3 +:10468000BDE8F08115F8018D16F801EDF045F5D083 +:10469000E7E70000034611F8012B03F8012B002A7D +:1046A000F9D170476F72672E6172647570696C6FB3 +:1046B000742E4E75636C656F2D47343931000000E0 +:1046C00040A2E4F1646891060041A3E5F2656992B5 +:1046D000070000004261642043414E496661636502 +:1046E00020696E6465782E00000000000000000064 +:1046F0009D1D000855180008B1240008C5180008C1 +:1047000009190008F11A0008D11800088D180008CE +:10471000911800086918000851180008AD1A00081F +:1047200075180008E925000881180008811A00089A +:1047300001040E05054B02020E05054B04010E0592 +:10474000054B05010B04044B08010603034600005A +:10475000636C6B73776300000003000000000000CF +:1047600000010000000001010300000023283101C6 +:1047700004070400010000006330000078470008CF +:10478000904E0020605000206D61696E0069646C7D +:10479000650000000004002800000000AAAAAAAAE0 +:1047A00000000024DFFF0000000000000000000007 +:1047B00000000A0000000000AAAAAAAA0000000047 +:1047C000FFFF000000000000990000000000000052 +:1047D00000000000AAAAAAAA00000000FFFF000033 +:1047E00000000000000000000000000000000000C9 +:1047F000AAAAAAAA00000000FFFF00000000000013 +:10480000000000000000000000000000AAAAAAAA00 +:1048100000000000FFFF000000000000000000009A +:104820000000000000000000AAAAAAAA00000000E0 +:10483000FFFF00000000000000000000000000007A +:1048400000000000AAAAAAAA00000000FFFF0000C2 +:104850000000000000000000100400000000000044 +:104860000060030000000000FE2A0100D2040000E6 +:10487000006889096D8BB90200B4C4040068890915 +:104880000068890900688909006889090068890940 +:104890000068890900000000442300200000000097 +:1048A0000000000000000000000000000000000008 +:1048B00000000000000000000000000000000000F8 +:1048C00000000000000000000000000000000000E8 +:1048D00000000000000000000000000000000000D8 +:1048E00000000000000000000000000000000000C8 +:0C48F000000000000000000000000000BC :00000001FF diff --git a/Tools/bootloaders/Pixhawk6X-PPPGW_bl.bin b/Tools/bootloaders/Pixhawk6X-PPPGW_bl.bin index 53afb74ae6714d..1275617bf45113 100755 Binary files a/Tools/bootloaders/Pixhawk6X-PPPGW_bl.bin and b/Tools/bootloaders/Pixhawk6X-PPPGW_bl.bin differ diff --git a/Tools/bootloaders/Pixracer-periph_bl.bin b/Tools/bootloaders/Pixracer-periph_bl.bin index a1c5cc5e4a347a..ffa1ea7a60e9bf 100755 Binary files a/Tools/bootloaders/Pixracer-periph_bl.bin and b/Tools/bootloaders/Pixracer-periph_bl.bin differ diff --git a/Tools/bootloaders/Pixracer-periph_bl.hex b/Tools/bootloaders/Pixracer-periph_bl.hex index 33a8a8e4b61199..cfcfa42018b425 100644 --- a/Tools/bootloaders/Pixracer-periph_bl.hex +++ b/Tools/bootloaders/Pixracer-periph_bl.hex @@ -1,1859 +1,1809 @@ :020000040800F2 -:1000000000070020F5040008912F0008492F000880 -:10001000712F0008492F0008692F0008F704000815 -:10002000F7040008F7040008F7040008853F0008FB -:10003000F7040008F7040008F7040008F7040008B4 -:10004000F7040008F7040008F7040008F7040008A4 -:10005000F7040008F7040008396B0008616B00081A -:10006000896B0008B16B0008D96B0008F704000821 -:10007000F7040008F7040008F7040008F704000874 -:10008000F7040008F7040008F7040008FD2E000834 -:10009000292F0008392F0008F7040008016C000818 -:1000A000F7040008F7040008F7040008F704000844 -:1000B000E96C0008F7040008F7040008F7040008DA -:1000C000F7040008F7040008F7040008F704000824 -:1000D000F7040008F7040008D56C0008F7040008CE -:1000E000656C0008F7040008F7040008F70400082E -:1000F000F7040008F7040008F7040008F7040008F4 -:10010000F7040008F7040008F7040008F7040008E3 -:10011000F7040008F7040008F7040008F7040008D3 -:10012000F7040008F7040008F7040008F7040008C3 -:10013000F7040008F7040008F7040008F7040008B3 -:10014000F7040008F7040008F70400082961000814 -:10015000F7040008F7040008F7040008F704000893 -:10016000F7040008F7040008F7040008F704000883 -:10017000F7040008F7040008F7040008F704000873 -:10018000F7040008F7040008F7040008F704000863 -:10019000F7040008F7040008F7040008F704000853 -:1001A000F7040008F7040008F7040008F704000843 -:1001B000F7040008F7040008F7040008F704000833 -:1001C000F7040008F7040008F7040008F704000823 -:1001D000F7040008F7040008F7040008F704000813 -:1001E000911800080000000000000000000000005E -:1001F00053B94AB9002908BF00281CBF4FF0FF318E -:100200004FF0FF3000F074B9ADF1080C6DE904CE89 -:1002100000F006F8DDF804E0DDE9022304B07047E1 -:100220002DE9F047089D04468E46002B4DD18A42A9 -:10023000944669D9B2FA82F252B101FA02F3C2F1DC -:10024000200120FA01F10CFA02FC41EA030E94406D -:100250004FEA1C48210CBEFBF8F61FFA8CF708FB8E -:1002600016E341EA034306FB07F199420AD91CEB66 -:10027000030306F1FF3080F01F81994240F21C8198 -:10028000023E63445B1AA4B2B3FBF8F008FB1033E0 -:1002900044EA034400FB07F7A7420AD91CEB040415 -:1002A00000F1FF3380F00A81A74240F207816444E5 -:1002B000023840EA0640E41B00261DB1D44000236A -:1002C000C5E900433146BDE8F0878B4209D9002DCE -:1002D00000F0EF800026C5E9000130463146BDE858 -:1002E000F087B3FA83F6002E4AD18B4202D38242C2 -:1002F00000F2F980841A61EB030301209E46002D71 -:10030000E0D0C5E9004EDDE702B9FFDEB2FA82F2C5 -:10031000002A40F09280A1EB0C014FEA1C471FFA23 -:100320008CFE0126200CB1FBF7F307FB131140EA0A -:1003300001410EFB03F0884208D91CEB010103F1D7 -:10034000FF3802D2884200F2CB804346091AA4B299 -:10035000B1FBF7F007FB101144EA01440EFB00FE6D -:10036000A64508D91CEB040400F1FF3102D2A645D2 -:1003700000F2BB800846A4EB0E0440EA03409CE771 -:10038000C6F12007B34022FA07FC4CEA030C20FA1E -:1003900007F401FA06F31C43F9404FEA1C4900FA3E -:1003A00006F3B1FBF9F8200C1FFA8CFE09FB1811BB -:1003B00040EA014108FB0EF0884202FA06F20BD92E -:1003C0001CEB010108F1FF3A80F08880884240F27E -:1003D0008580A8F102086144091AA4B2B1FBF9F0C2 -:1003E00009FB101144EA014100FB0EFE8E4508D9BD -:1003F0001CEB010100F1FF346CD28E456AD9023842 -:10040000614440EA0840A0FB0294A1EB0E01A14226 -:10041000C846A64656D353D05DB1B3EB080261EB94 -:100420000E0101FA07F722FA06F3F1401F43C5E96E -:10043000007100263146BDE8F087C2F12003D840A4 -:100440000CFA02FC21FA03F3914001434FEA1C47E6 -:100450001FFA8CFEB3FBF7F007FB10360B0C43EAD8 -:10046000064300FB0EF69E4204FA02F408D91CEB88 -:10047000030300F1FF382FD29E422DD90238634486 -:100480009B1B89B2B3FBF7F607FB163341EA034126 -:1004900006FB0EF38B4208D91CEB010106F1FF3875 -:1004A00016D28B4214D9023E6144C91A46EA00466C -:1004B00038E72E46284605E70646E3E61846F8E6FE -:1004C0004B45A9D2B9EB020864EB0C0E0138A3E747 -:1004D0004646EAE7204694E74046D1E7D0467BE728 -:1004E000023B614432E7304609E76444023842E7A0 -:1004F000704700BF02E000F000F8FEE772B6374830 -:1005000080F30888364880F3098836483649086001 -:1005100040F20000CCF200004EF63471CEF2000141 -:100520000860BFF34F8FBFF36F8F40F20000C0F23F -:10053000F0004EF68851CEF200010860BFF34F8FF5 -:10054000BFF36F8F4FF00000E1EE100A4EF63C71E2 -:10055000CEF200010860062080F31488BFF36F8F8D -:1005600005F0AAFA06F08EF94FF055301F491B4AE4 -:1005700091423CBF41F8040BFAE71D49184A9142E9 -:100580003CBF41F8040BFAE71A491B4A1B4B9A423D -:100590003EBF51F8040B42F8040BF8E7002018495D -:1005A000184A91423CBF41F8040BFAE705F088FA7B -:1005B00006F0BCF9144C154DAC4203DA54F8041B98 -:1005C0008847F9E700F042F8114C124DAC4203DACB -:1005D00054F8041B8847F9E705F070BA00070020BB -:1005E000002300200000000808ED00E000010020CA -:1005F000000700204873000800230020BC230020CF -:10060000C023002008590020E0010008E401000890 -:10061000E4010008E40100082DE9F04F2DED108AF7 -:10062000C1F80CD0C3689D46BDEC108ABDE8F08FC0 -:10063000002383F311882846A047002004F02AFDF8 -:10064000FEE704F083FC00DFFEE70000F8B501F0F0 -:1006500031F905F0D3F930B12B4B00220F211A727A -:100660005A729972DA7205F0ABF9074605F010FA82 -:10067000054600283CD1254B9F4239D001339F428B -:1006800039D0234B27F0FF029A4237D1F8B200F05D -:100690001DFF2E4642F2107400F01EFF08B1002428 -:1006A000264601F063FD20B1032000F087F8002406 -:1006B000264635B1174B9F4203D005F0E1F90024DF -:1006C0002646002005F086F9134B1B6913F480734E -:1006D00018D00EB100F088F801F0C6FA00F068FFFB -:1006E00001F064F9204600F0DBF800F07DF8F9E74E -:1006F0002E460024D0E704460126CDE7064641F207 -:100700008834C9E71C46E7E700230020010007B052 -:10071000000008B0263A09B00004024008B501F014 -:1007200011F9A0F120035842584108BD07B541F224 -:100730001203022101A8ADF8043001F021F903B041 -:100740005DF804FB38B5302383F31188174803683C -:100750000BB104F06BFD164A144800234FF47A7174 -:1007600004F05AFD002383F31188124C236813B15F -:100770002368013B2360636813B16368013B6360D6 -:100780000D4D2B7833B963687BB9022001F0DEF997 -:10079000322363602B78032B07D163682BB90220C7 -:1007A00001F0D4F94FF47A73636038BDC0230020A0 -:1007B00045070008E0240020D8230020084B1870CB -:1007C00003280CD8DFE800F008050208022001F039 -:1007D000ADB9022001F09CB9024B00225A6070476B -:1007E000D8230020E024002010B501F0BFFC30B178 -:1007F000244B03221A70244B00225A6010BD234B55 -:10080000234A1C4619680131F8D004339342F9D1C8 -:100810006268204B9A42F1D91F4B9B6803F1006339 -:1008200003F580339A42E9D205F0FEF805F010F99D -:10083000002001F0D5F80220FFF7C0FF174B1A6C1B -:1008400000221A64196E1A66196E596C5A64596E30 -:100850005A665A6E1A6942F000521A611A6922F0F9 -:1008600000521A611B6972B64FF0E0233021C3F8C1 -:10087000084DD4E9003281F311889D4683F308883E -:100880001047BBE7D8230020E02400200000010827 -:1008900020000108FFFF000800230020003802406C -:1008A0002DE9F04F93B0AC4B00902022FF210AA815 -:1008B0009D6801F083F9A94A1378A3B9A8480121DA -:1008C00003601170302383F3118803680BB104F0C7 -:1008D000ADFCA44AA24800234FF47A7104F09CFCBA -:1008E000002383F31188009B13B19F4B009A1A6079 -:1008F0009E4A009C1378032B1EBF002313709A4A54 -:100900004FF0000A18BF5360D3465646D146012027 -:1009100001F00CF924B1944B1B68002B00F01582F8 -:10092000002001F00FF80390039B002B01DA00F088 -:1009300087FE039B002BEDDB012001F0E9F8039B10 -:10094000213B162BE3D801A252F823F0A909000895 -:10095000D1090008650A00080F0900080F090008FE -:100960000F090008EF0A0008BF0C0008D90B0008A7 -:100970003B0C0008630C0008890C00080F090008F4 -:100980009B0C00080F0900080D0D0008490A00081B -:100990000F090008510D0008B5090008490A0008B0 -:1009A0000F0900083B0C00080220FFF7B7FE0028E3 -:1009B00040F0F581009B0221BAF1000F08BF1C46F0 -:1009C00005A841F21233ADF8143000F0D9FF9EE7CC -:1009D0004FF47A7000F0B6FF071EEBDB0220FFF742 -:1009E0009DFE0028E6D0013F052F00F2DA81DFE806 -:1009F00007F0030A0D10133605230593042105A8FB -:100A000000F0BEFF17E054480421F9E758480421DC -:100A1000F6E758480421F3E74FF01C08404600F081 -:100A2000E1FF08F104080590042105A800F0A8FFE3 -:100A3000B8F12C0FF2D1012000FA07F747EA0B0BAF -:100A40005FFA8BFB4FF0000901F004F926B10BF0BF -:100A50000B030B2B08BF0024FFF768FE57E746483F -:100A60000421CDE7002EA5D00BF00B030B2BA1D159 -:100A70000220FFF753FE074600289BD0012000F01C -:100A8000AFFF0220FFF79AFE00261FFA86F84046C5 -:100A900000F0B6FF044690B10021404600F0C8FFC8 -:100AA00001360028F1D1BA46044641F21213022160 -:100AB00005A8ADF814303E4600F062FF27E701209C -:100AC000FFF77CFE2546244B9B68AB4207D928469E -:100AD00000F088FF013040F067810435F3E7234BD5 -:100AE00000251D70204BBA465D603E46ACE7002EE7 -:100AF0003FF460AF0BF00B030B2B7FF45BAF0220D6 -:100B0000FFF75CFE322000F01DFFB0F10008FFF699 -:100B100051AF18F003077FF44DAF0F4A926808EB0E -:100B2000050393423FF646AFB8F5807F3FF742AFEB -:100B3000124B0193B84523DD4FF47A7000F002FFA9 -:100B40000390039A002AFFF635AF019B039A03F83E -:100B5000012B0137EDE700BF00230020DC2400203B -:100B6000C023002045070008E0240020D8230020EF -:100B700004230020082300200C230020DC23002075 -:100B8000C820FFF7CBFD074600283FF413AF1F2D09 -:100B900011D8C5F1200242450AAB25F0030028BF59 -:100BA000424683490192184400F0E2FF019A8048CE -:100BB000FF2101F003F84FEAA8037D490193C8F330 -:100BC0008702284601F002F8064600283FF46DAF80 -:100BD000019B05EB830537E70220FFF79FFD002807 -:100BE0003FF4E8AE00F044FF00283FF4E3AE0027F6 -:100BF000B846704B9B68BB4218D91F2F11D80A9B6F -:100C000001330ED027F0030312AA134453F8203CFB -:100C100005934046042205A901F060FA0437804696 -:100C2000E7E7384600F0DEFE0590F2E7CDF81480E5 -:100C3000042105A800F0A4FE06E70023642104A80F -:100C4000049300F093FE00287FF4B4AE0220FFF777 -:100C500065FD00283FF4AEAE049800F0F1FE05906B -:100C6000E6E70023642104A8049300F07FFE002837 -:100C70007FF4A0AE0220FFF751FD00283FF49AAEAA -:100C8000049800F0EDFEEAE70220FFF747FD002898 -:100C90003FF490AE00F0FCFEE1E70220FFF73EFDDE -:100CA00000283FF487AE05A9142000F0F7FE0421C8 -:100CB0000746049004A800F063FE3946B9E73220E5 -:100CC00000F040FE071EFFF675AEBB077FF472AE64 -:100CD000384A926807EB090393423FF66BAE022055 -:100CE000FFF71CFD00283FF465AE27F003074F44D3 -:100CF000B9453FF4A9AE484600F074FE04210590C2 -:100D000005A800F03DFE09F10409F1E74FF47A70FF -:100D1000FFF704FD00283FF44DAE00F0A9FE0028C7 -:100D200044D00A9B01330BD008220AA9002000F00E -:100D30004DFF00283AD02022FF210AA800F03EFFF4 -:100D4000FFF7F4FC1C4804F0ABF913B0BDE8F08FDA -:100D5000002E3FF42FAE0BF00B030B2B7FF42AAECB -:100D60000023642105A8059300F000FE0746002833 -:100D70007FF420AE0220FFF7D1FC804600283FF42C -:100D800019AEFFF7D3FC41F2883004F089F90598D9 -:100D900000F0A4FF464600F05DFF3C46B7E506467E -:100DA00052E64FF0000905E6BA467EE637467CE695 -:100DB000DC23002000230020A0860100094A1368DC -:100DC00049F2690099B21B0C00FB01331360064B1A -:100DD000186844F2506182B2000C01FB02001860F6 -:100DE00080B27047182300201423002010B5002182 -:100DF0001022044600F0E2FE034B03CB206061604A -:100E00001868A06010BD00BF107AFF1F2DE9F041E7 -:100E1000ADF5507D0DF13C086EAC40F27512074601 -:100E20000D4610A80021C8F8001000F0C7FE4FF4CE -:100E3000C4720021204600F0C1FE02F0B1F8274B39 -:100E40004FF47A72B0FBF2F0186093E807000223C7 -:100E500084E807000DF5ED702382FFF7C7FF47F622 -:100E600005231F49238407A806F054F81D2384F89E -:100E700032310DF2EB2207AB0DF1340C1E4603CEDE -:100E8000664510605160334602F10802F6D13068C1 -:100E900010603379137141460122204600F040FF73 -:100EA00000230393AB7E029305F11903019380B2F3 -:100EB0000123CDE904800093E97E06A3D3E9002352 -:100EC000384602F035FC0DF5507DBDE8F08100BFDD -:100ED000AFF300809E6AC421818A46EEE824002098 -:100EE000246F00082DE9F0412C4C237ADAB08046BB -:100EF0000D465BBB27A9284601F022F807460028CB -:100F000042D19DF89D60C82E3ED801464FF4A6629E -:100F1000204600F053FE4FF48073C4F8F8314FF4CC -:100F20000073C4F80C334FF44073C4F820343246D5 -:100F30000DF19E0104F1090000F01AFE26449DF80F -:100F40009C30777223720BB9EB7E237281220021D1 -:100F500006AC27A800F032FE0122214627A801F0A6 -:100F60002BF800230393AB7E029305F1190380B2A3 -:100F700001932823CDE904400093E97E05A3D3E93A -:100F80000023404602F0D4FB5AB0BDE8F08100BF18 -:100F9000AFF3008026417272DF25D7B700460020EC -:100FA000F0B5254E4FF48A7505FB0065F1B096F853 -:100FB000D83085F8DC300024D822214685F8E84076 -:100FC0003AA800F0FBFD06F1090000F0EFFDD5F8AE -:100FD000E4308DF8F000C2B206AF06F109010DF160 -:100FE000F100CDE93A3400F0C3FD394601223AA8B8 -:100FF00001F00EF880B2CDE9047008230127CDE995 -:10100000023706F1D803019330230093317A0B485D -:1010100007A3D3E9002302F08BFBA04206DD01F019 -:10102000BFFFC5F8E000384671B0F0BD2046FBE7D1 -:1010300078F6339F93CACD8D0046002000350020FE -:101040002DE9F0411D4D1E4E1E4F86B0284602F080 -:101050009BFB034658B30024CDE90344ADF814408C -:10106000027B8DF8142099684068029403AA03C299 -:101070001B68DFF8548043F00043029301F092FFB5 -:10108000821941F10003009402A9384601F054FA94 -:10109000A04205DD284602F07BFB88F80040D5E73A -:1010A00098F80030072B05D8013388F8003006B0D7 -:1010B000BDE8F081014802F06BFBF8E70035002045 -:1010C00040420F0030350020354B002070B50D46F2 -:1010D00014461E4602F088FA50B9022E10D1012C97 -:1010E0000ED112A3D3E90023C5E90023012007E0B4 -:1010F000282C10D005D8012C09D0052C0FD00020A9 -:1011000070BD302CFBD10BA3D3E90023ECE70BA37C -:10111000D3E90023E8E70BA3D3E90023E4E70BA31B -:10112000D3E90023E0E700BFAFF30080401DA1201A -:1011300026812A0B78F6339F93CACD8D9E6AC421EF -:10114000818A46EE26417272DF25D7B7F017304A02 -:1011500039059E5638B505460E4C0021013500F084 -:1011600067FCA4F82C55B4F82C0500F049FC78B1C4 -:10117000B4F82C0500F054FC014648B9B4F82C052D -:1011800000F056FCB4F82C350133A4F82C35EAE70E -:1011900038BD00BF0046002010B50A4B0A4A1A604D -:1011A00003F5805393F860203AB9DC6D2CB12046EA -:1011B00001F05AF8204605F0EDFDBDE81040034867 -:1011C00001F052B830350020E06F0008784500206B -:1011D0002DE9F04F8FB000AF05460C4602F004FA3F -:1011E000002849D1237E022B1BD1E38A012B18D181 -:1011F00001F0D6FE0646FFF7E1FD03464FF4C87046 -:10120000DFF8C482B3FBF0F206F5167602FB10336A -:1012100016FA83F3C8F80030E37E33B9A34B0022FB -:101220001A703C37BD46BDE8F08F07F12401204617 -:1012300000F044FE0028F4D107F11400FFF7D6FDBA -:1012400097F8264007F11401224607F1270005F020 -:10125000EBFD0028E2D10F2C08D8944B1C70D8F875 -:101260000030A3F51673C8F80030DAE797F82410B9 -:10127000284602F0B1F9D4E7E38A282B2BD010D806 -:10128000012B23D0052BCCD1BFF34F8F8849894B3D -:10129000CA6802F4E0621343CB60BFF34F8F00BF14 -:1012A000FDE7302BBDD1844EE17E327A9142B8D138 -:1012B000607E3146002291F8DC50854200F0A58026 -:1012C0000132042A01F58A71F5D1AAE721462846A0 -:1012D000FFF79CFDA5E721462846FFF703FEA0E7A0 -:1012E000B2F8EC507B6005F103094FEA99094FEA27 -:1012F0008902D11DC908A8EBC1039D46EB46002118 -:10130000584600F05BFC04F1EE012A463144584691 -:1013100000F02EFC7B6813B9012000F061FB96F809 -:10132000D20000F06DFB044630B9307200F0A0FB33 -:10133000204600F055FBB1E0D6F8D4203AB996F833 -:10134000D200B6F82C25824201D8FFF703FFD6F869 -:10135000D4202A44944208D296F8D200B6F82C251C -:101360000130824201D8FFF7F5FE70685FFA89F21A -:10137000594600F02BFC08B9C54679E0726896F82A -:10138000D2002A447260D6F8D42005EB0209C6F8D0 -:10139000D49000F035FB814509D396F8D220D6F8D9 -:1013A000D4000132001B86F8D220C6F8D400FF2DED -:1013B0000FD80024347200F05BFB204600F010FBD5 -:1013C00000F0D4FE3D4B188108B9FFF70DFAC54671 -:1013D00027E7BB6896F8D9000AFB0362FB68D2F8DE -:1013E000E41082F8E83001F58061C2F8E030C2F81C -:1013F000E410FFF7D5FDFFF723FE96F8D920013260 -:1014000002F0030286F8D920B6E74FF48A7A0AFB85 -:1014100002F505F1EA013144204600F025FEF860AE -:1014200000287FF4FEAE3544012285F8E82001F063 -:10143000B7FDD5F8E020D6ED007ADFED216A801AFD -:10144000192838BF192040F6B832904228BF1046FC -:10145000B8EE677A07EE900AF8EEE77A67EEA67ABA -:10146000DFED186AE7EE267AFCEEE77AC6ED007A41 -:1014700096F8D930BB60BA6873680AFB02F4321977 -:1014800092F8E81059B1D2F8E4108B42E8463FF4E4 -:1014900027AF002182F8E810C2F8E010C546736853 -:1014A000064A9B0A01331381BBE600BFF9340020D2 -:1014B00000ED00E00400FA0500460020E8240020CA -:1014C000CDCCCC3D6666663FFC340020014B1870E5 -:1014D000704700BFF424002030B54FF000542B4B70 -:1014E00022689A4285B007D004F0DCFA044620BB9B -:1014F0000024204605B030BD254B627D25481A707A -:10150000237D03724FF48073C0F8F8314FF40073F9 -:10151000C0F80C3300254FF44073C0F820341E4946 -:10152000C0F8E450C922093000F022FB2046E02236 -:10153000294600F043FB0124DBE7184A184D136CE1 -:1015400043F000731364AA6D164B9A42D0D12B6EF0 -:10155000013B7E2BCCD8144A07CA01AB83E80700B5 -:101560001846032100F0D0FD6B6D83424FF000035D -:10157000BED12A6D8A4201BFAB65054B2A6E1A7037 -:1015800003BF0A4BEA6D1A601C46B2E79AAD44C528 -:10159000F4240020004600201600002000380240FD -:1015A000006600405041A0B0586600401023002063 -:1015B00037B51A4D00F0DAFD02236B71184B288104 -:1015C00019681848012201F089FB00230193164B8A -:1015D000164900931648174B4FF4805201F0D4FF80 -:1015E000154B197811B1124801F0F6FF01F0D8FC43 -:1015F0000446FFF7E3FB4FF4C873B0FBF3F202FBC2 -:10160000130304F5167010FA83F00C4B186004F005 -:101610003FFA08B10F232B8103B030BDE82400202E -:101620001023002030350020CD100008F8240020C1 -:1016300000350020D1110008F4240020FC340020E3 -:101640002DE9F04F2DED028B0FF23829D9E90089F1 -:10165000834C93B00BAE9FED7E8BFFF7F1FC814F77 -:10166000DFF828A200230A93ADF834300B9373609F -:101670004FF0000B5B468DED008B01250DF11D0237 -:1016800007A938468DF81C508DF81DB001F0D6FA28 -:101690009DF81C30002B40F0A580204601F0A4FFEF -:1016A0000646002845D1704F01F07AFC3B6898420D -:1016B0003FD301F075FC8246FFF780FB4FF4C873FF -:1016C000B0FBF3F202FB13030AF5167010FA83F075 -:1016D0003860664F97F800B0CBF1100ABBF1000FED -:1016E00014BF33462B465FFA8AFA0EA88DF82830CD -:1016F000FFF77CFBBAF1060F28BF4FF0060A0EABCE -:1017000003EB0B0152460DF1290000F031FA0AAB50 -:101710000393182302930AF10102554BD2B2CDE98B -:101720000053049220464CA3D3E9002301F0A2FF0A -:101730003E7001F035FC4F4A4F4D1368C31AB3F5A4 -:101740007A7F2ED3106001F02DFC02460B46204616 -:1017500002F028F8204601F047FF10B32B7A474EDD -:10176000002B14BF03230223737101F019FC0EAF89 -:101770004FF47A730122B0FBF3F039463060304603 -:1017800000F074FB182302933D4B019380B240F2AA -:101790005513CDE90370009342464B46204601F0B5 -:1017A00069FF2B7A93B101F0FBFB002607464FF44B -:1017B0008A7A95F8D900304400F003000AFB005300 -:1017C00093F8E82092B30136042EF2D1C82003F03A -:1017D00067FC2B7A002B7FF43DAF13B0BDEC028B7E -:1017E000BDE8F08FDAF8143083F00203CAF8143041 -:1017F000594610220EA800F0E1F90DF11E0308AAC7 -:101800000AA9384600F096FF96E803000FAB83E87C -:1018100003009DF834308DF844300A9B0E930EA9D6 -:10182000DDE90823204602F091F921E7D3F8E02012 -:1018300042B12B68FA2B38BFFA23BA1A0533B2EB40 -:10184000430FC0D3FFF7ACFB0028BCD1BEE700BFFD -:101850000000000000000000401DA12026812A0B8E -:101860000035002030350020FC340020F934002001 -:10187000F8340020304B002000460020E8240020EF -:10188000344B0020F1C6A7C1D068080F0004024005 -:1018900008B5054800F0E8FFBDE80840034A0449E0 -:1018A000002005F071BA00BF30350020844B0020C5 -:1018B00099110008704700002DE9F84F4FF47A7332 -:1018C000DFF85880DFF8589006460D4602FB03F714 -:1018D000002498F900305A1C5FFA84FA01D0A34220 -:1018E00012D159F8240003682A46D3F820B03146B3 -:1018F0003B46D847854207D1074B012083F800A01B -:10190000BDE8F88F0124E4E7002CFBD04FF4FA7017 -:1019100003F0C6FB0020F3E7784B00201C230020D7 -:101920002023002070B504464FF47A76412C2546DA -:1019300028BF412506FB05F003F0B2FB641BF5D17F -:1019400070BD000007B50023024601210DF107001C -:101950008DF80730FFF7B0FF20B19DF8070003B006 -:101960005DF804FB4FF0FF30F9E700000A4608B5C8 -:101970000421FFF7A1FF80F00100C0B2404208BD82 -:1019800030B4074B0A461978064B53F821402368B8 -:10199000DD69054B0146AC46204630BC604700BFC0 -:1019A000784B002020230020A086010070B503F0B2 -:1019B00099FE094E094D30800024286833888342FF -:1019C00008D903F089FE2B6804440133B4F5803F45 -:1019D0002B60F2D370BD00BF7A4B0020384B002043 -:1019E00003F036BF00F1006000F5803000687047FA -:1019F00000F10060920000F5803003F0C1BE0000ED -:101A0000054B1A68054B1B889B1A834202D9104468 -:101A100003F062BE00207047384B00207A4B002054 -:101A2000024B1B68184403F05FBE00BF384B002018 -:101A3000024B1B68184403F06FBE00BF384B0020F8 -:101A400010F003030AD1B0F5047F05D200F1005075 -:101A5000A0F51040D0F80038184670470023FBE787 -:101A600000F10050A0F51040D0F8100A70470000B7 -:101A7000064991F8243033B10023086A81F82430F4 -:101A80000822FFF7B5BF0120704700BF3C4B002084 -:101A9000014B1868704700BF002004E070B5194B77 -:101AA0001D68194B0138C5F30B0408442D0C0422A2 -:101AB0001E88A6420BD15C680A46013C824213464E -:101AC0000FD214F9016F4EB102F8016BF6E7013A3B -:101AD00003F10803ECD181420B4602D22C2203F819 -:101AE000012B0A4A05241688AE4204D1984284BFCD -:101AF000967803F8016B013C02F10402F3D1581A05 -:101B000070BD00BF002004E0846F0008706F000803 -:101B1000022802D1044B98617047012802BF024B92 -:101B200008229A61704700BF00040240022804D1D5 -:101B3000054B4FF400329A6170470128FCD1024BEB -:101B40004FF40022F7E700BF00040240022805D14D -:101B5000064A536983F00203536170470128FCD1A0 -:101B6000024A536983F00803F6E700BF000402400D -:101B700010B50023934203D0CC5CC4540133F9E781 -:101B800010BD000010B5013810F9013F3BB191F9CB -:101B900000409C4203D11AB10131013AF4E71AB175 -:101BA00091F90020981A10BD1046FCE70346024642 -:101BB000D01A12F9011B0029FAD1704702440346DA -:101BC000934202D003F8011BFAE770472DE9F8436E -:101BD0001F4D144695F824200746884652BBDFF86F -:101BE00070909CB395F824302BB92022FF214846F1 -:101BF0002F62FFF7E3FF95F82400C0F10802A2422C -:101C000028BF2246D6B24146920005EB8000FFF77E -:101C1000AFFF95F82430A41B1E44F6B2082E1744DB -:101C20009044E4B285F82460DBD1FFF721FF00285F -:101C3000D7D108E02B6A03EB82038342CFD0FFF7B2 -:101C400017FF0028CBD10020BDE8F8830120FBE777 -:101C50003C4B0020024B1A78024B1A70704700BFB1 -:101C6000784B00201C23002038B5174C174D204618 -:101C700002F046FD2946204602F06EFD2D686A6D91 -:101C8000936B23F4002393634FF47A70FFF74AFEBB -:101C90000F49284602F066FE6A6D0E4D936B286868 -:101CA0000D4943F400239363A0424FF4E1330B60EA -:101CB00001D002F085FC6868A04204D0BDE838403D -:101CC000054902F07DBC38BD68500020087100084D -:101CD0001071000820230020644B002070B50C4BCD -:101CE0000C4D1E780C4B55F826209A4204460DD018 -:101CF0000A4B002114221846FFF760FF04600146DA -:101D000055F82600BDE8704002F05ABC70BD00BF17 -:101D1000784B00202023002068500020644B0020D6 -:101D20002DE9F0470D46044600219046284640F232 -:101D30007912FFF743FF234620220021284601F0B5 -:101D4000A7FE231D02222021284601F0A1FE631DCB -:101D500003222221284601F09BFEA31D03222521F8 -:101D6000284601F095FE04F1080310222821284698 -:101D700001F08EFE04F1100308223821284601F0FC -:101D800087FE04F1110308224021284601F080FE5D -:101D900004F1120308224821284601F079FE04F1DB -:101DA000140320225021284601F072FE04F118038A -:101DB00040227021284601F06BFE04F12003082226 -:101DC000B021284601F064FE04F121030822B82165 -:101DD000284601F05DFE04F12207C0263B4631464D -:101DE00008222846083601F053FEB6F5A07F07F119 -:101DF0000107F3D104F1320308223146284601F0ED -:101E000047FE002704F1330A94F832304FEAC7093D -:101E10009F4209F5A47615D3B8F1000F08D13146D9 -:101E200004F599730722284601F032FE09F24F1695 -:101E3000274694F832213B1B93420CD3F01DC00877 -:101E4000BDE8F0870AEB070308223146284601F077 -:101E50001FFE0137D8E707F2331331460822284620 -:101E600001F016FE08360137E3E7000013B504461B -:101E70000846002101602346C0F80310202201908B -:101E800001F006FE0198231D0222202101F000FE30 -:101E90000198631D0322222101F0FAFD0198A31D80 -:101EA0000322252101F0F4FD019804F1080310221A -:101EB000282101F0EDFD072002B010BDF7B5002389 -:101EC000047F00910E4607221946054601F0A4FC46 -:101ED000731C0093012200230721284601F09CFC7B -:101EE000C4B9B31C0093052223460821284601F0FB -:101EF00093FC0D243746B278BB1B934211D32B7F42 -:101F0000A88A0734E408BBB9844294BF00200120AA -:101F100003B0F0BDAB8ADB00083BDB08B3700824DC -:101F2000E8E7FB1C0093214600230822284601F025 -:101F300073FC08340137DEE7201A18BF0120E7E7F9 -:101F4000F7B50023047F00910E4608221946054686 -:101F500001F062FC731CC4B90822009311462346A9 -:101F6000284601F059FC1024012372785F1C013BC4 -:101F7000934211D32B7FA88A0734E408BBB984426B -:101F800094BF0020012003B0F0BDAB8ADB00083B0A -:101F9000DB0873700824E7E7F31900932146002358 -:101FA0000822284601F038FC08343B46DDE7201AB9 -:101FB00018BF0120E7E70000F8B50E4605461446B5 -:101FC000002181223046FFF7F9FD2B46082200212F -:101FD000304601F05DFD7CB96B1C072208213046BC -:101FE00001F056FD0F2401236A785F1C013B9342E8 -:101FF00004D3E01DC008F8BD0824F4E7EB1921461E -:102000000822304601F044FD08343B46ECE700006E -:10201000F8B50E46054614460021CE223046FFF79D -:10202000CDFD2B4628220021304601F031FD7CB940 -:1020300005F1080308222821304601F029FD30244B -:102040002F462A7A7B1B934204D3E01DC008F8BDBB -:102050002824F5E707F1090321460822304601F05C -:1020600017FD08340137ECE7F7B5047F00910E4601 -:10207000012310220021054601F0CEFBC4B9B31C98 -:102080000093092223461021284601F0C5FB19249C -:1020900037467288BB1B9A4211D82B7FA88A073417 -:1020A000E408BBB9844294BF0020012003B0F0BD16 -:1020B000AB8ADB00103BDB0873801024E8E73B1D94 -:1020C0000093214600230822284601F0A5FB08348E -:1020D0000137DEE7201A18BF0120E7E730B5094DC8 -:1020E0000A4491420DD011F8013B5840082340F3B7 -:1020F0000004013B2C4013F0FF0384EA5000F6D1AA -:10210000EFE730BD2083B8EDF7B54FF0FF33DFF8D0 -:1021100054C0DFF854E000EB81011A4688421CD01D -:1021200050F8044B019401AF042417F8015B82EAD4 -:1021300005620825DB18164605F1FF355241002ED1 -:10214000BCBF83EA0C0382EA0E0215F0FF05F1D151 -:10215000013C14F0FF04E8D1E0E7D843D14303B0D9 -:10216000F0BD00BF9336EAA9EBE1F042F7B5384A7B -:10217000106851686B4603C36A46364936480823DF -:1021800004F062FE0446002833D10A25334A106861 -:1021900051686B4603C36A4631492F48082304F04F -:1021A00053FE0446002849D00369B3F5F81F45D80B -:1021B000B0F8661040F27A5291423FD1294A024467 -:1021C00002F15C018B4239D35C3B234900209E1A0B -:1021D000FFF784FF3246074604F164010020FFF751 -:1021E0007DFFA3689F4229D1E368984208BF00257C -:1021F00024E00369B3F5F81F27D8418B40F27A52E7 -:10220000914220D1174A024402F110018B4218D3A7 -:10221000103B114900209D1AFFF760FF2A46064631 -:1022200004F118010020FFF759FFA3689E4202D174 -:10223000E368984201D00D25A8E70025284603B0A1 -:10224000F0BD1025A2E70C25A0E70B259EE700BFF7 -:10225000A46F0008DCFF1E0000000108AD6F00083D -:1022600090FF1E000800FFF710B5037C044613B969 -:10227000006804F0D1FD204610BD00000023BFF32C -:102280005B8FC360BFF35B8FBFF35B8F8360BFF374 -:102290005B8F7047BFF35B8F0068BFF35B8F704746 -:1022A00070B505460C30FFF7F5FF05F1080604464A -:1022B0003046FFF7EFFFA04206D930466D68FFF7C2 -:1022C000E9FF2544281A70BD3046FFF7E3FF201AC6 -:1022D000F9E7000070B50546406898B105F10800BF -:1022E000FFF7D8FF05F10C0604463046FFF7D2FF92 -:1022F0008442304694BF6D680025FFF7CBFF013C58 -:102300002C44201A70BD000038B50C460546FFF776 -:10231000C7FFA04210D305F10800FFF7BBFF04443C -:102320006868B4FBF0F100FB1144BFF35B8F012040 -:10233000AC60BFF35B8F38BD0020FCE72DE9F041B6 -:10234000144607460D46FFF7C5FF844228BF0446E2 -:10235000D4B1B84658F80C6B4046FFF79BFF3044A9 -:10236000286040467E68FFF795FF331A9C4203D8E9 -:102370006C600120BDE8F0816B60A41B3B68AB6022 -:102380002044E8600220F5E72046F3E738B50C4624 -:102390000546FFF79FFFA04210D305F10C00FFF7A1 -:1023A00079FF04446868B4FBF0F100FB1144BFF30B -:1023B0005B8F0120EC60BFF35B8F38BD0020FCE732 -:1023C0002DE9FF41884669460746FFF7B7FF6C468F -:1023D00006B204EBC6060025B44209D06268206844 -:1023E00008EB0501FFF7C4FB636808341D44F3E7FD -:1023F00029463846FFF7CAFF284604B0BDE8F081F9 -:10240000F8B505460C300F46FFF744FF05F1080606 -:1024100004463046FFF73EFFA042304688BF6C6856 -:10242000FFF738FF201A386020B130462C68FFF7DC -:1024300031FF2044F8BD000073B5144606460D4632 -:10244000FFF72EFF844228BF04460190DCB101A9AA -:102450003046FFF7D5FF019B33B93268C5E9023337 -:10246000C5E9002401200CE09C4238BF019428609B -:10247000019868608442F5D93368AB60241AEC6037 -:10248000022002B070BD2046FBE700002DE9FF41AD -:102490000F466946FFF7D0FF6C4600B204EBC0055B -:1024A0000026AC4209D0D4F8048054F8081BB819AF -:1024B0004246FFF75DFB4644F3E7304604B0BDE813 -:1024C000F081000038B50546FFF7E0FF04460146FD -:1024D0002846FFF719FF204638BD0000302383F35C -:1024E000118862B670470000002383F3118862B63A -:1024F0007047000010B4026854681A4623465DF81D -:10250000044B184701207047002070470020704797 -:1025100070470000002070470E20704700F5805083 -:1025200090F8C800C0F340007047000000F58050EC -:1025300090F9C90070470000F7B50C68BDF820702D -:1025400014F000541E466FD10B7B082B6CD8FFF79C -:10255000C5FF4569AB685B010CD4AB681B0108D4AF -:10256000AC6814F080545DD1FFF7BEFF204603B085 -:10257000F0BD01240B6804F1180C002BB8BFDB0080 -:102580004FEA0C1CB4BF43F004035B0545F80C3064 -:102590000B680FFA84FC13F0804F18BF05EB0C1E7C -:1025A00005EB0C1C1EBFDEF8803143F00203CEF8B1 -:1025B00080310B7BCCF8843105EB04158B68C5F8B2 -:1025C0008C314B68C5F88831DCF8803143F0010369 -:1025D000CCF8803100EB441541F268031D4403EB55 -:1025E00044130344C5E9002608330D4601F10C0CE1 -:1025F00055F804EB43F804EB6545F9D184342D8894 -:102600001D8000EB441407F00303257925F00B052A -:102610002B432371FFF768FF0097334600F0E2FC7D -:102620000120A4E70224A5E74FF0FF309FE7000058 -:1026300013B500F580540191E06DFFF74BFE1F28A4 -:102640000AD90199E06D2022FFF7BAFEA0F120031C -:102650005842584102B010BD0020FBE708B500F514 -:102660008050FFF73BFFC06DFFF708FEBDE8084054 -:10267000FFF73ABF002202608281426082607047A9 -:1026800010B500220023C0E9002300230446038183 -:102690000C30FFF7EFFF204610BD0000F0B50546F7 -:1026A00000F580500C4690F8C83013F0040FC3F3C7 -:1026B000800108BF114661F3820304F1840680F8AB -:1026C000C83005EB461389B01B79D8072ED57AB3ED -:1026D00019072DD46846FFF7D3FF05EB441303F524 -:1026E000835303F1180703AA103318685968144676 -:1026F00003C40833BB422246F7D1186820609B8888 -:10270000A380DDE90E23CDE900230123ADF80830D5 -:102710002B686946DB6B2846984705EB46152B79F5 -:102720001A075CBF43F008032B7101E0002AF4D1C3 -:1027300009B0F0BD2DE9F047074688B007F5805491 -:1027400068469A468846FFF7C9FE9146FFF798FF0C -:10275000E06DFFF7A5FD1F2829D9E06D202269460D -:10276000FFF7B0FE202822D103AD444605AB2E462C -:1027700003CE9E4220606160354604F10804F6D124 -:1027800030682060B388A380DDE90023C9E9002315 -:10279000BDF80830AAF80030FFF7A6FE4A465346B7 -:1027A0004146384608B0BDE8F04700F009BCFFF7E5 -:1027B0009BFE002008B0BDE8F08700002DE9F84F2F -:1027C0000023C0E90133254B044640F8183B0F466F -:1027D000FFF750FF04F12800FFF752FF04F148080B -:1027E00004F582554646083530462036FFF748FF47 -:1027F000AE42F9D104F580554FF480534FF00009F3 -:10280000C5E91339C5F848800123EE6504F58758FA -:1028100004F58456C5F8549085F8583085F8603032 -:10282000083608F108084FF0000A4FF0000B46E99F -:1028300008ABA6F11800FFF71DFF203646F8289CCC -:102840004645F4D185F8C97017B1054800F0A2FBE0 -:10285000044B63612046BDE8F88F00BFE06F0008BD -:10286000B86F00080064004010B5044B19780446A6 -:102870004A1C1A70FFF7A2FF204610BD804B0020B3 -:102880002DE9F047002950D0294B2A4FB7FBF1F52D -:1028900099428CBF0A231123581EB5FBF3FC03FB9E -:1028A0001C53C4B22BB102280346F5D80020BDE862 -:1028B000F0870CF1FF36B6F5806FF7D2C4EBC40E8B -:1028C0000EF103034FEAE309C3F3C703A4EB0308C4 -:1028D00009F1010A4FF47A755FFA88F009FB055592 -:1028E0005AFA88F8B5FBF8F5B5F5617FC1BF0EF16E -:1028F000FF33C3F3C703E01AC0B25C1C50FA84F480 -:102900000CFB04F4B7FBF4F4A142CFD1013BDBB2E2 -:102910000F2BCBD80138C0B20728C7D800211071BF -:1029200016809170D3700120C1E70846BFE700BF51 -:102930003F420F0080DE800270B505460E464FF420 -:102940007A746B695B6803F00103B34207D04FF4FC -:102950007A7002F0A5FB013CF3D1204670BD012046 -:10296000FCE7000030B54269936913F0700F16D090 -:1029700000230B4C936103F1840200EB42121179A6 -:102980004D0709D5890707D5416954F823508D6053 -:10299000117941F0040111710133032BEBD130BDEA -:1029A000CC6F000873B51D46436916469A68D20776 -:1029B000044609D59A6801219960C2F34002CDE925 -:1029C00000650021FFF76AFE63699A68D1050BD59F -:1029D0009A684FF480719960C2F34022CDE9006596 -:1029E00001212046FFF75AFE63699A68D2030BD58E -:1029F0009A684FF480319960C2F34042CDE9006596 -:102A000002212046FFF74AFE204602B0BDE8704092 -:102A1000FFF7A8BFF8B50446466900296CD106F156 -:102A20000C07386880076AD006EB01153868D5F8BE -:102A3000B00110F0040FD5F8B0011ABFC00840F083 -:102A40000040400DA061D5F8B0C11CF0020F1CBFC2 -:102A500040F08040A061D5F8B40106EB011100F010 -:102A60000F0084F82400D1F8B8012077D1F8B8011C -:102A7000000A6077D1F8B801000CA077D1F8B8014E -:102A8000000EE077D1F8BC0184F82000D1F8BC0139 -:102A9000000A84F82100D1F8BC01000C84F822005F -:102AA000D1F8BC11090E84F823103821396004F1E3 -:102AB000340004F1180104F1240551F8046B40F8C6 -:102AC000046BA942F9D109880180C4E90A2321468F -:102AD0000023238651F8283B2046DB6B984704F5FA -:102AE0008052204692F8C83043F0040382F8C83080 -:102AF000BDE8F840FFF736BF06F1100791E7F8BDD3 -:102B000010B5044600F04EFA02460B4652EA0301A5 -:102B100002D0013A63F100030449086820B121465C -:102B2000BDE81040FFF776BF10BD00BF7C4B002012 -:102B3000F8B500F583511E46FFF7D0FCDFF844C01E -:102B40000831002404F1840500EB45152B795F075B -:102B50000ED4DB060CD5D1E900739742B34107D2FE -:102B600043695CF824709F602B7943F004032B7158 -:102B70000134032C01F12001E4D1BDE8F840FFF756 -:102B8000B3BC00BFCC6F000808B5FFF7A7FCFFF788 -:102B9000E9FEBDE80840FFF7A7BC0000F8B54369AF -:102BA0000546986800F0E050B0F1E05F0F461FD096 -:102BB000E8B1FFF793FC05F583541034002606F1C5 -:102BC000840305EB43131B791A0706D50136032E40 -:102BD00004F12004F3D1012007E05B07F6D421467D -:102BE000384600F039FA0028F0D1FFF77DFCF8BD37 -:102BF0000120FCE700F5805008B5FFF76FFCC06DC1 -:102C0000FFF74EFBFFF770FC43090CBF01200020CB -:102C100008BD0000F8B51D46002313700F46064698 -:102C20001446FFF7E7FF80F00100387025B1294610 -:102C30003046FFF7B3FF2070F8BD00002DE9B84122 -:102C40000C4615461F46804600F0ACF90B4621782D -:102C5000024609B9287850B14046FFF769FFFFF7EF -:102C600093FF3B462A462146FFF7D4FF0120BDE8EB -:102C7000B881000010B5FFF731FC174B1A6C42F019 -:102C800000721A641A6A42F000721A621A6A00F537 -:102C9000805422F000721A62FFF726FC94F8C830C4 -:102CA000DB0718D4B9B103211320FFF717FC01F09B -:102CB000BBFA0321142001F0B7FA0321152001F01B -:102CC000B3FA94F8C83043F0010384F8C830BDE883 -:102CD0001040FFF709BC10BD003802402DE9F04755 -:102CE00000F5805588B095F8C930012B0446884618 -:102CF00016467FD8804F57F823200AB947F823009B -:102D0000D7F800A0C4F80C802674BAF1000F63D085 -:102D100095F8C930012B6FD001212046FFF7AAFF9B -:102D2000FFF7DCFB6269136823F00203136062693A -:102D3000136843F001031360636900275F61012199 -:102D40002046FFF7D1FBFFF7F7FD002800F0958044 -:102D5000E86DFFF793FA04F58359BA4609F10809BB -:102D6000202200216846FEF729FF02A8FFF782FC17 -:102D7000CDF818A06A4609EB07030DF1180E94462A -:102D8000BCE80300F44518605960624603F108038B -:102D9000F5D1DCF80000186020379CF804201A7187 -:102DA000602FDDD195F8C8306FF38203002785F8D6 -:102DB000C8306A4641462046ADF80070ADF8027052 -:102DC0008DF80470FFF75CFD636948BB4FF4004267 -:102DD0001A6008B0BDE8F08741F2D00003F0DCFFD4 -:102DE000814610B15146FFF7E9FCC7F80090B9F1F0 -:102DF000000F8DD10020ECE7386803681B6B984703 -:102E00000146002888D13868FFF734FF3868036826 -:102E100032465B684146984700287FF47DAFE9E77A -:102E200061221A609DF802309DF803201B061204EF -:102E300002F4702203F040731343BDF80020C2F384 -:102E4000090213439DF804201205022E02F4E00249 -:102E50000CBF4FF000410021134362690B43D36163 -:102E6000636913225A616269136823F001031360D6 -:102E700039462046FFF760FD08B96369A6E795F873 -:102E8000C93093BB6169D1F8002242F00102C1F858 -:102E900000226169D1F8002222F47C5222F00E0255 -:102EA000C1F800226169D1F8002242F46062C1F8E1 -:102EB00000226269C2F814326269C2F8043262699F -:102EC00041F6FF71C2F80C126269C2F840326269C1 -:102ED000C2F8443263690122C3F81C226269D2F845 -:102EE000003223F00103C2F8003295F8C83043F0F5 -:102EF000020385F8C8306CE77C4B002008B500F071 -:102F000051F850EA0103024602D0421E61F100016D -:102F1000044B186810B10B46FFF744FDBDE80840AC -:102F200001F064B87C4B002008B50020FFF7E8FDF5 -:102F3000BDE8084001F05AB808B50120FFF7E0FDF0 -:102F4000BDE8084001F052B800B59BB0EFF309812D -:102F500068226846FEF70CFEEFF30583014B9B6B7E -:102F6000FEE700BF00ED00E008B5FFF7EDFF000051 -:102F700000B59BB0EFF3098168226846FEF7F8FDC3 -:102F8000EFF30583014B5B6BFEE700BF00ED00E054 -:102F9000FEE700000FB408B5029802F00DF8FEE756 -:102FA00002F0ACBC02F084BC13B56C4684E80600A9 -:102FB000031D94E8030083E80500012002B010BD62 -:102FC00073B58568019155B11B885B0707D4D0E9BB -:102FD00000369B6B9847019AC1B23046A847012042 -:102FE00002B070BDF0B5866889B005460C465EB18A -:102FF000BDF838305B070AD4D0E900379B6B98479F -:103000002246C1B23846B047012009B0F0BD0022C7 -:103010000023CDE900230023ADF808300A4603ABB6 -:1030200001F10806106851681C4603C40832B24218 -:103030002346F7D1106820609288A280FFF7B2FF84 -:103040000423ADF808302B68CDE90001DB6B69463D -:1030500028469847D8E7000030B503680968DD0FB7 -:10306000B5EBD17F23F0604421F060424FEAD1708C -:103070000BD0002BB8BFA40C0029B8BF920C94420F -:1030800002D034BF0120002030BD944205D1C1F3ED -:103090008070C3F380738342F6D194422CBF00202A -:1030A0000120F1E72DE9F041456A15B94162BDE81B -:1030B000F0814B6823F06047C3F38A464FEAD37E22 -:1030C000C3F3807816EA230638BF3E46AC462B464B -:1030D0005A68BEEBD27F22F060440AD0002A18DA88 -:1030E000A40CB44217D19D420FD10D60DEE7134608 -:1030F000EEE7A74207D102F08044C2F38072424556 -:103100000BD054B1EFE708D2EDE7CCF800100B601C -:10311000CDE7B44201D0B442E5D81A689C46002AF3 -:10312000E5D11960C3E700002DE9F047089D01F0E3 -:1031300007044FEAD508224405F0070500EBD1004B -:103140004FF47F49944201D1BDE8F08704F00707AE -:1031500005F0070A57453E4638BF5646C6F10806F1 -:10316000111B8E4228BF0E46E10808EBD50E415CCC -:1031700013F80EC0B94029FA06F721FA0AF1FFB296 -:103180008CEA010147FA0AF739408CEA010C03F88E -:103190000EC034443544D5E780EA0120082341F2CB -:1031A000210201B24000002980B203F1FF33B8BF11 -:1031B000504013F0FF03F4D17047000038B50C46BF -:1031C0008D18A54200D138BD14F8011BFFF7E4FFAC -:1031D000F7E7000042684AB1136843604389818978 -:1031E00001339BB29942438138BF838110467047B7 -:1031F00070B588B0202204460D4668460021FEF7CF -:10320000DDFC20460495FFF7E5FF024658B16B460A -:10321000054608AE1C4603CCB442286069602346CC -:1032200005F10805F6D1104608B070BD082817D979 -:1032300009280CD00A280CD00B280CD00C280CD054 -:103240000D280CD00E2814BF4020302070470C20D1 -:1032500070471020704714207047182070472020B6 -:1032600070470000082817D90C280CD910280CD951 -:1032700014280CD918280CD920280CD930288CBF38 -:103280000F200E207047092070470A2070470B203E -:1032900070470C2070470D20704700002DE9F8435F -:1032A000078C072F04461ED9D0E9029800254FF657 -:1032B000FF73C5F12006A5F1200029FA05F108FAEF -:1032C00006F628FA00F031430143C9B21846FFF769 -:1032D00063FF0835402D0346EBD1E1693A46BDE86E -:1032E000F843FFF76BBF4FF6FF70BDE8F8830000AF -:1032F00010B54B6823B9CA8A63F30902CA8210BDAC -:1033000004691A681C600361C38A013BC3824A6076 -:10331000EFE700002DE9F84F1D46CB8A0F46C3F3B7 -:1033200009010529814692460B4630D00020AAB2F9 -:1033300007F11A049EB2042E1FFA80F80FD89045A8 -:1033400003F1010306D3FB8A0A4462F30903FB82FB -:1033500001201AE01AF80060E6540130EAE79045CF -:10336000F1D2A1F1050B1C237C68BBFBF3F203FB3C -:1033700012BB1FFA8BF6002C45D14846FFF72AFFF7 -:10338000044638B978606FF00200BDE8F88F4FF05E -:103390000008E6E7002606607860ADB24FF0000B4B -:1033A000454510D90AEB0803221D13F8011B91555E -:1033B000B1B208F101081B291FFA88F82BD0454546 -:1033C00006F10106F1D8FB8AC3F30902154465F33F -:1033D0000903BCE7013292B21C462368002BF9D1E5 -:1033E0006B1F0B441C21B3FBF1F301339BB29A42D8 -:1033F000D3D2BBF1000FD0D14846FFF7EBFE20B986 -:10340000C4F800B0BFE70122E7E7C0F800B05E46AD -:1034100020600446C1E74545D5D94846FFF7DAFEA6 -:1034200008B92060AFE7C0F800B00026206004466D -:10343000B6E700002DE9F04F2DED028B1C4683B05E -:103440005B69019207468846002B00F09A80238C26 -:103450002BB1E269002A00F09480072B35D807F1E0 -:103460000C00FFF7B7FE054638B96FF00205284695 -:1034700003B0BDEC028BBDE8F08F14220021FEF7F3 -:103480009DFB228CE16905F10800FEF771FB208CA1 -:10349000013080B2FFF7E6FEFFF7C8FE013880B2C8 -:1034A0002084013028746369228C1B782A4403F03D -:1034B0001F0363F03F0348F0004113723846696010 -:1034C0002946FFF7EFFD0125D1E700F10C034FF08E -:1034D000000908EE103A4FF0800A4E464D4618EEAD -:1034E000100AFFF777FE83460028BED01422002181 -:1034F000FEF764FB002E3AD1019BABF808300222A4 -:103500000BF1080E1FFA82FC0CF10100BCF1060F52 -:10351000218C80B201D88E422BD3FFF7A3FEFFF798 -:1035200085FE62691278013802F01F028E4208BFE0 -:103530004FF0400A42EA49121BFA80F14AEA020AB5 -:10354000013048F0004281F808A08BF81000CBF859 -:10355000042059463846FFF7A5FD238C0135B342B8 -:103560002DB289F001094FF0000AB8D17FE700229F -:10357000C6E7E169895D0EF802100136B6B2013284 -:10358000C0E76FF0010572E7F8B515460E46302228 -:10359000002104461F46FEF711FB069B6360B5F54C -:1035A000001F079BA76034BF6A094FF6FF72A36232 -:1035B00097B2E66104F1100000239A4206D8002376 -:1035C0000360A782E3822383E360F8BD06600133D2 -:1035D00030462036F1E7000003781BB94BB2002BD0 -:1035E000C8BF01707047000000787047F8B50C46FE -:1035F000C969074611B9238C002B37D1257E1F2DB1 -:1036000034D8387828BB228C072A2CD8268A36F062 -:1036100003032BD14FF6FF70FFF7D0FD20F0010020 -:103620003102400441EA0561400C41EA40254FF671 -:10363000FF72234629463846FFF7FCFE002807DDC7 -:10364000626913780133DBB21F2B88BF002313702C -:10365000F8BD218A2D0645EA012505432046FFF7DE -:103660001DFE0246E5E76FF00300F1E76FF0010091 -:10367000EEE7000070B58AB0044616460021282205 -:1036800068461D46FEF79AFABDF83830ADF810309E -:103690000F9B05939DF840308DF81830119B0793D0 -:1036A0006946BDF84830ADF820302046CDE90265C6 -:1036B000FFF79CFF0AB070BD2DE9F041D3690546C4 -:1036C0000C4616460BB9138C5BBB377E1F2F28D8D0 -:1036D00095F80080B8F1000F26D03046FFF7DEFDE8 -:1036E0003378210241EAC33141EA0801338A41EAD1 -:1036F000076141EA03410246334641F08001284612 -:10370000FFF798FE00280ADD3378012B07D1726994 -:1037100013780133DBB21F2B88BF00231370BDE881 -:10372000F0816FF00100FAE76FF00300F7E70000A7 -:10373000F0B58BB004460D46174600212822684696 -:103740001E46FEF73BFA9DF84C305A1E5342534139 -:103750008DF800309DF84030ADF81030119B059386 -:103760009DF848308DF81830149B07936A46BDF8D1 -:103770005430ADF8203029462046CDE90276FFF7D7 -:103780009BFF0BB0F0BD0000406A00B104307047F1 -:10379000436A1A68426202691A600361C38A013B84 -:1037A000C38270472DE9F041D0F82080194E1446AD -:1037B0001D464146002709B9BDE8F081D1E9022341 -:1037C000A21A65EB0303964277EB03031ED2036A4A -:1037D0008B420DD1FFF78CFD036A1B6803620369FE -:1037E0000B60C38A0161016A013BC3828846E2E73C -:1037F000FFF77EFD0B68C8F8003003690B60C38AD1 -:103800000161013BC382D8F80010D4E788460968FB -:10381000D1E700BF80841E002DE9F04F8BB00D462C -:10382000DDF8509014469B468046002800F0198130 -:10383000B9F1000F00F01581531E3F2B00F21181EA -:10384000012A03D1BBF1000F40F00B810023CDE929 -:103850000833B8F81430B5EBC30F4FEAC30703D3EE -:1038600000200BB0BDE8F08F2B199F42D8F80C3028 -:103870003ABF7F1BFFB227461BB9D8F81030002B88 -:103880007AD0272D4ED8C5F12806B7424FF0000355 -:103890002CBFF6B23E4600932946D8F8080008AB84 -:1038A0003246FFF741FCA7EB060A35445FFA8AFA75 -:1038B000B8F8143003F10053053BDB000493D8F84B -:1038C0000C3003932821039B13B1BAF1000F2CD1C4 -:1038D000D8F8100040B1BAF1000F05D0009608AB3F -:1038E0005246691AFFF720FC38B2002FB8D066079D -:1038F0000AD00AAB03EBD401624211F8083C02F093 -:103900000702134101F8083C082C3CD9102C40F266 -:10391000B580202C40F2B780BBF1000F00F09C80F6 -:10392000082334E0BA460026C2E7049BE02B28BFF8 -:10393000E02306930B44AB42059314D95A1B03981A -:103940000096924534BF5246D2B2691A08AB043091 -:103950000792FFF7E9FB079A1644AAEB020A1544FF -:10396000F6B25FFA8AFA049B069A05999B1A0493A9 -:10397000039B1B680393A6E70093D8F8080008ABE5 -:103980003A462946AEE7BBF1000F13D00123B4EB52 -:10399000C30F6CD0082C12D89DF82030621E23FA79 -:1039A00002F2D50706D54FF0FF3202FA04F42343A2 -:1039B0008DF820309DF8203089F8003051E7102C28 -:1039C00012D8BDF82030621E23FA02F2D10706D5C4 -:1039D0004FF0FF3202FA04F42343ADF82030BDF873 -:1039E0002030A9F800303CE7202C0FD80899631E3E -:1039F00021FA03F3DA0705D54FF0FF3202FA04F497 -:103A00000C430894089BC9F800302AE7402C2BD0BF -:103A1000DDE90865611EC4F12102A4F1210326FA43 -:103A200001F105FA02F225FA03F311431943CB071A -:103A300012D50122A4F12003C4F1200102FA03F3FC -:103A400022FA01F1A240524243EA010363EB43032D -:103A500032432B43CDE90823DDE90823C9E90023DC -:103A6000FFE66FF00100FCE66FF00800F9E6082CB5 -:103A7000A0D9102CB3D9202CEED8C3E7BBF1000F8E -:103A8000ADD0022383E7BBF1000FBBD004237EE758 -:103A900030B5012A144638BF0124402C85B028BF18 -:103AA00040240025012ACDE9025518D81B788DF84D -:103AB000083063070AD004AB03EBD405624215F863 -:103AC000083C02F00702934005F8083C00910346C9 -:103AD0002246002102A8FFF727FB05B030BD082AC7 -:103AE000E4D9102A03D81B88ADF80830E1E7202A72 -:103AF0008DBFD3E900231B680293CDE90223D8E7E9 -:103B000010B5CB681BB98B600B618B8210BD04694B -:103B10001A681C600361C38A013BC382CA60F0E774 -:103B200003064CBFC0F3C0300220704708B5024600 -:103B3000FFF7F6FF022806D15306C2F30F2001D18A -:103B400000F0030008BDC2F30740FBE72DE9F04F8A -:103B500093B0CDE903230A6804461046FFF7E0FF5F -:103B6000022814BFC2F306260026002A0D4682460C -:103B700080F2F28112F0C04940F0EE81097B002909 -:103B800000F0EA81022803D02378B34240F0E781B5 -:103B9000C2F304630693104602F07F030593FFF718 -:103BA000C5FF059B29444FEA834848EA0A4848EA8A -:103BB0004668CE7800230022CDE90823F309834626 -:103BC00048EA0008029367D0059B009302466768A5 -:103BD000534608A92046B847002800F0C381276A49 -:103BE0004FB9414604F10C00FFF702FB074690B9BC -:103BF0006FF0020054E03B6998450DD03F68002FFC -:103C0000F9D1414604F10C00FFF7F2FA074600280B -:103C1000EED0236A3B60276297F817C006F01F08B2 -:103C2000CCF3840CACEB08001FFA80FE0028B8BF70 -:103C30000EF12000A8EB0C031FFA83FED7E9022146 -:103C4000B8BF00B2002B0793BEBF0EF120031BB21A -:103C5000079352EA010338D0039BDFF824E39A1A52 -:103C6000049B4FF0000C63EB010196457CEB0103D4 -:103C70002BD36B7B97F81AE0734519D1029B002B6D -:103C800078D0012821DC7868F8B9DFF8F0C29445D3 -:103C900070EB010316D337E0276A27B96FF00C00E9 -:103CA00013B0BDE8F08F3B699845B5D03F68F4E7A5 -:103CB000B24890427CEB010301D30020F0E7029B65 -:103CC000002BFAD0079B0F2B17DCFA7DB30002F014 -:103CD000030203F07C031343FB7539462046FFF7CC -:103CE00007FB6B7BBB76029B3BB9FB7DC3F3840276 -:103CF000013262F38603FB75D0E76A7BBB7E9A4292 -:103D0000DBD1029B002B35D0B309022B32D0039BB1 -:103D1000BB60049BFB60142200210DA8FDF74EFF41 -:103D2000039B0A93049B0B932B1D0C932B7BADF8E9 -:103D30003EB0013BDBB2ADF83C30069B8DF8423023 -:103D4000059B8DF8433094F82C308DF840A083F01B -:103D500001038DF844308DF84180A3680AA92046FC -:103D60009847FB7DC3F38403013303F01F039B02D9 -:103D7000FB82A2E7FB7DC6F34012B2EBD31F40F0FB -:103D8000F480C3F38403434540F0F280029A2B7B16 -:103D9000B609002A4DD0F2075DD4032B40F2EB8028 -:103DA000039BBB60049BFB602B7BAE1D033BDBB224 -:103DB0003246394604F10C00FFF7ACFA00280CDA61 -:103DC00039462046FFF794FAFB7DC3F384030133A1 -:103DD00003F01F039B02FB820AE7DDE90884AB883E -:103DE0003B834FF6FF73C9F12000A9F1200228FAA6 -:103DF00009F104FA00F0014324FA02F211431846D3 -:103E0000C9B2FFF7C9F909F10809B9F1400F034632 -:103E1000E9D1B8822A7B033AD2B23146FFF7CEF914 -:103E2000FB7DB882DA43C2F3C01262F3C713FB759D -:103E300043E786B92E1D013BDBB23246394604F119 -:103E40000C00FFF767FA0028BADB2A7BB88A013A30 -:103E5000D2B23146E2E7F98AC1F30901013B0429F4 -:103E6000DAB25BD8281D002307F11B069A4208D955 -:103E700010F801CB06F801C0013101330529DBB28E -:103E8000F4D103990A9104990B91934207F11B0114 -:103E90000C9138BF043379680D9134BF55FA83F320 -:103EA00000230E93FB8AADF83EB0C3F309031A4416 -:103EB000069B8DF84230059B8DF8433094F82C30EA -:103EC000ADF83C2083F001038DF8443000238DF8D9 -:103ED00040A08DF841807B602A7BB88A013A291D79 -:103EE000FFF76CF93B8BB882834203D1A3680AA920 -:103EF0002046984720460AA9FFF702FEFB7DBA8AB2 -:103F0000C3F38403013303F01F039B02FB823B8B4B -:103F10009A420CBF00206FF01000C1E67B68002BB6 -:103F2000AFD0052001E01C3033461E68002EFAD1C8 -:103F3000091A081D2E1D184401EB090CBCF11B0FBA -:103F40005FFA89F39DD89A429BD916F8013B00F895 -:103F5000013B09F10109EFE76FF00900A0E66FF0FE -:103F60000A009DE66FF00B009AE66FF00D0097E6F1 -:103F70006FF00E0094E66FF00F0091E640420F00E4 -:103F800080841E00EFF3098305494A6B22F0010289 -:103F90004A63683383F30988002383F311887047E9 -:103FA00000EF00E0302080F3118862B60C4B0D4A20 -:103FB000D96821F4E0610904090C0A43DA60D3F8F6 -:103FC000FC20094942F08072C3F8FC200A6842F0E4 -:103FD00001020A602022DA7783F82200704700BFCE -:103FE00000ED00E00003FA05001000E010B53023FA -:103FF00083F311880E4B5B6813F4006314D0F1EE69 -:10400000103AEFF30984683C4FF08073E361094B89 -:10401000DB6B236684F3098800F08CFF10B1064B3C -:10402000A36110BD054BFBE783F31188F9E700BFDF -:1040300000ED00E000EF00E043060008460600083F -:10404000026843681143016003B1184770470000DC -:10405000024AD36843F0C003D36070470044004075 -:1040600010B5054C054A0021204600F087FA044AA5 -:10407000044BC4E9972310BD884B00205140000831 -:104080000044004080DE8002234A037C002918BFE0 -:104090000A46012B30B5C0F868220CD11F4B98425C -:1040A00009D11F4B196C41F400311964196E41F4A8 -:1040B000003119661B6EB2F904501468D0F86032F2 -:1040C000D0F85C12002D03EB5403B3FBF4F3BEBF36 -:1040D00023F0070503F0070343EA450394888B6048 -:1040E000D38843F040030B61138943F001034B6114 -:1040F00044F4045343F02C03CB6004F4A054002395 -:104100000B60B4F5806F0B684B680CBF7F23FF23F7 -:1041100080F8643230BD00BF20700008884B00205A -:10412000003802402DE9F041D0F85C62F76833684E -:10413000DA0504469DB20DD5302383F311884FF480 -:1041400080610430FFF77CFF6FF4807333600023DD -:1041500083F31188302383F3118804F1040815F0E8 -:104160002F033AD183F31188380615D5290613D5C4 -:10417000302383F3118804F1380000F07BF9002824 -:104180004EDA0821201DFFF75BFF4FF67F733B409F -:10419000F360002383F311887A0616D56B0614D5D5 -:1041A000302383F31188D4E913239A420AD1236C74 -:1041B00043B127F040073F041021201D3F0CFFF7BB -:1041C0003FFFF760002383F31188D4F86822D36897 -:1041D00043B3BDE8F041106918472B0714D015F020 -:1041E000080F0CBF00214FF48071E80748BF41F071 -:1041F0002001AA0748BF41F040016B0748BF41F0CA -:1042000080014046FFF71CFFAD06736805D594F8A2 -:1042100064122046194000F0E1F93568ADB29EE71E -:104220007060B6E7BDE8F08100F1604303F56143DB -:104230000901C9B283F80013012200F01F039A405C -:1042400043099B0003F1604303F56143C3F88021F8 -:104250001A607047F8B5154682680669AA420B468F -:10426000816938BF8568761AB54204460BD2184674 -:104270002A46FDF77DFCA3692B44A361A3685B1B61 -:10428000A3602846F8BD0CD918463246FDF770FCED -:10429000AF1BE1683A463044FDF76AFCE3683B44F3 -:1042A000EBE718462A46FDF763FCE368E5E7000004 -:1042B00083689342F7B51546044638BF8568D0E950 -:1042C0000460361AB5420BD22A46FDF751FC6369E9 -:1042D0002B446361A36828465B1BA36003B0F0BD59 -:1042E0000DD932460191FDF743FC0199E068AF1BFF -:1042F0003A463144FDF73CFCE3683B44E9E72A4693 -:10430000FDF736FCE368E4E710B50A440024C36116 -:10431000029B8460C0E90000C0E90511C160026130 -:10432000036210BD08B5D0E90532934201D182681D -:1043300082B98268013282605A1C42611970D0E9E8 -:1043400004329A4224BFC3684361002100F0C4FED6 -:10435000002008BD4FF0FF30FBE7000070B53023B0 -:1043600004460E4683F31188A568A5B1A368A26927 -:10437000013BA360531CA36115782269934224BFBB -:10438000E368A361E3690BB120469847002383F3F8 -:104390001188284607E03146204600F08DFE0028AF -:1043A000E2DA85F3118870BD2DE9F74F04460E4619 -:1043B00017469846D0F81C904FF0300A8AF31188BF -:1043C0004FF0000B154665B12A4631462046FFF7EF -:1043D00041FF034660B94146204600F06DFE0028CB -:1043E000F1D0002383F31188781B03B0BDE8F08F70 -:1043F000B9F1000F03D001902046C847019B8BF311 -:104400001188ED1A1E448AF31188DCE7C0E9051112 -:10441000C160C3611144009B8260C0E9000001617A -:1044200003627047F8B504460D461646302383F301 -:104430001188A768A7B1A368013BA36063695A1CF0 -:1044400062611D70D4E904329A4224BFE36863615B -:10445000E3690BB120469847002080F3118807E0FC -:104460003146204600F028FE0028E2DA87F3118862 -:10447000F8BD0000D0E905239A4210B501D1826849 -:104480007AB98268013282605A1C82611C780369A1 -:104490009A4224BFC3688361002100F01DFE2046BC -:1044A00010BD4FF0FF30FBE72DE9F74F04460E46F5 -:1044B00017469846D0F81C904FF0300A8AF31188BE -:1044C0004FF0000B154665B12A4631462046FFF7EE -:1044D000EFFE034660B94146204600F0EDFD00289E -:1044E000F1D0002383F31188781B03B0BDE8F08F6F -:1044F000B9F1000F03D001902046C847019B8BF310 -:104500001188ED1A1E448AF31188DCE702684368BB -:104510001143016003B11847704700001430FFF7E2 -:1045200043BF00004FF0FF331430FFF73DBF0000E2 -:104530003830FFF7B9BF00004FF0FF333830FFF7D6 -:10454000B3BF00001430FFF709BF00004FF0FF3188 -:104550001430FFF703BF00003830FFF763BF0000DF -:104560004FF0FF323830FFF75DBF0000012914BF64 -:104570006FF0130000207047FFF772BD37B5154686 -:104580000E4A026000224260C0E902220122044673 -:1045900002740B46009000F15C014FF480721430FD -:1045A000FFF7B2FE00942B464FF4807204F5AE7113 -:1045B00004F13800FFF72AFF03B030BD3470000863 -:1045C00010B53023044683F31188FFF75DFD022305 -:1045D0002374002080F3118810BD000038B5C36932 -:1045E00004460D461BB904210844FFF78FFF2946F6 -:1045F00004F11400FFF796FE002806DA201D4FF4A0 -:104600000061BDE83840FFF781BF38BD02684368EC -:104610001143016003B118477047000013B5446BA4 -:10462000D4F894341A681178042915D1217C022910 -:1046300012D11979128901238B4013420CD101A99F -:1046400004F14C0001F0DAFFD4F89444019B217985 -:104650000246206800F0D0F902B010BD143001F01D -:104660005DBF00004FF0FF33143001F057BF000072 -:104670004C3002F02FB800004FF0FF334C3002F006 -:1046800029B80000143001F02BBF00004FF0FF31BB -:10469000143001F025BF00004C3001F0FBBF0000DA -:1046A0004FF0FF324C3001F0F5BF000000207047A2 -:1046B00010B5D0F894341A6811780429044617D13B -:1046C000017C022914D15979528901238B4013426C -:1046D0000ED1143001F0BEFE024648B1D4F8944425 -:1046E0004FF4807361792068BDE8104000F072B922 -:1046F00010BD0000406BFFF7DBBF000070470000FB -:104700007FB5124B036000234360C0E902330125EB -:1047100002260F4B057404460290019300F18402B7 -:10472000294600964FF48073143001F06FFE094B58 -:104730000294CDE9006304F523724FF48073294697 -:1047400004F14C0001F036FF04B070BD5C7000084D -:10475000F54600081D4600080B68302282F31188D8 -:104760000A7903EB820290614A79093243F8220008 -:104770008A7912B103EB820398610223C0F8941482 -:104780000374002080F311887047000038B5037F60 -:10479000044613B190F85430ABB9201D0125022115 -:1047A000FFF734FF04F1140025776FF0010100F0EA -:1047B0009FFC84F8545004F14C006FF00101BDE8F7 -:1047C000384000F095BC38BD10B5012104460430D6 -:1047D000FFF71CFF0023237784F8543010BD00003E -:1047E00038B504460025143001F028FE04F14C00D1 -:1047F000257701F0F7FE201D84F854500121FFF7C2 -:1048000005FF2046BDE83840FFF752BF90F844301E -:1048100003F06003202B07D190F84520212A4FF0A8 -:10482000000303D81F2A06D800207047222AFBD194 -:10483000C0E90E3303E0034A82630722C2630364C4 -:10484000012070472823002037B5D0F894341A6827 -:104850001178042904461AD1017C022917D119794B -:10486000128901238B40134211D100F14C052846D7 -:1048700001F078FF58B101A9284601F0BFFED4F835 -:104880009444019B21790246206800F0B5F803B0FA -:1048900030BD0000F0B500EB810385B09E69044691 -:1048A0000D46FEB1302383F3118804EB8507301DDC -:1048B0000821FFF7ABFEFB685B691B6806F14C0043 -:1048C0001BB1019001F0A8FE019803A901F096FE2A -:1048D000024648B1039B2946204600F08DF800238C -:1048E00083F3118805B0F0BDFB685A691268002A8D -:1048F000F5D01B8A013B1340F1D104F14402EAE7F1 -:10490000093138B550F82140DCB1302383F31188E8 -:10491000D4F894241368527903EB8203DB689B6913 -:104920005D6845B104216018FFF770FE294604F167 -:10493000140001F099FD2046FFF7BAFE002383F32F -:10494000118838BD7047000001F00EB901230370D3 -:104950000023C0E90133C36183620362C36243621F -:104960000363704738B50446302383F3118800256C -:10497000C0E90355C0E90555416001F005F902237E -:10498000237085F31188284638BD000070B500EB10 -:10499000810305465069DA600E46144618B11022AC -:1049A0000021FDF70BF9A06918B110220021FDF7D5 -:1049B00005F931462846BDE8704001F0AFB9000066 -:1049C000826802F0011282600022C0E90422826142 -:1049D00001F030BAF0B400EB81044789E4680125A6 -:1049E000A4698D403D43458123600023A26063603C -:1049F000F0BC01F04BBA0000F0B400EB8104078971 -:104A0000E468012564698D403D43058123600023EE -:104A1000A2606360F0BC01F0C5BA000070B502236B -:104A2000002504460370C0E90255C0E90455C56479 -:104A3000856180F8345001F00DF963681B6823B17B -:104A400029462046BDE87040184770BD0378052B05 -:104A500010B504460AD080F850300523037043682F -:104A60001B680BB1042198470023A36010BD000010 -:104A70000178052906D190F85020436802701B6820 -:104A800003B118477047000070B590F83430044601 -:104A900013B1002380F8343004F14402204601F0C1 -:104AA000EBF963689B68B3B994F8443013F0600580 -:104AB00035D00021204601F08BFC0021204601F07A -:104AC0007DFC63681B6813B10621204698470623C6 -:104AD00084F8343070BD204698470028E4D0B4F8FC -:104AE0004A30E26B9A4288BFE36394F94430E56B45 -:104AF000002B4FF0300380F20381002D00F0F28094 -:104B0000092284F8342083F311880021D4E90E238C -:104B10002046FFF771FF002383F31188DAE794F84A -:104B2000452003F07F0343EA022340F2023293421E -:104B300000F0C58021D8B3F5807F48D00DD8012B77 -:104B40003FD0022B00F09380002BB2D104F14C0235 -:104B5000A2630222E2632364C1E7B3F5817F00F020 -:104B60009B80B3F5407FA4D194F84630012BA0D1AF -:104B7000B4F84C3043F0020332E0B3F5006F4DD08F -:104B800017D8B3F5A06F31D0A3F5C063012B90D82F -:104B9000636894F846205E6894F84710B4F848308B -:104BA0002046B047002884D04368A3630368E363CA -:104BB0001AE0B3F5106F36D040F6024293427FF40C -:104BC00078AF5C4BA3630223E3630023C3E794F84D -:104BD0004630012B7FF46DAFB4F84C3023F0020364 -:104BE000C4E90E55A4F84C30256478E7B4F8443095 -:104BF000B3F5A06F0ED194F8463084F84E302046BD -:104C000001F080F863681B6813B1012120469847C2 -:104C1000032323700023C4E90E339CE704F14F0300 -:104C2000A3630123C3E72378042B10D1302383F33C -:104C300011882046FFF7C4FE85F3118803216368BD -:104C400084F84F5021701B680BB12046984794F8A8 -:104C50004630002BDED084F84F3004232370636885 -:104C60001B68002BD6D0022120469847D2E794F843 -:104C700048301D0603F00F0120460AD501F0EEF87A -:104C8000012804D002287FF414AF2B4B9AE72B4B5A -:104C900098E701F0D5F8F3E794F84630002B7FF45D -:104CA00008AF94F8483013F00F01B3D01A0620462D -:104CB00002D501F0A1FBADE701F094FBAAE794F85F -:104CC0004630002B7FF4F5AE94F8483013F00F0116 -:104CD000A0D01B06204602D501F07AFB9AE701F02E -:104CE0006DFB97E7142284F8342083F311882B4658 -:104CF0002A4629462046FFF76DFE85F31188E9E62E -:104D00005DB1152284F8342083F311880021D4E9A1 -:104D10000E232046FFF75EFEFDE60B2284F83420CA -:104D200083F311882B462A4629462046FFF764FE66 -:104D3000E3E700BF8C7000088470000888700008EA -:104D400038B590F834300446002B3ED0063BDAB23A -:104D50000F2A34D80F2B32D8DFE803F0373131086F -:104D6000223231313131313131313737C56BB0F821 -:104D70004A309D4214D2C3681B8AB5FBF3F203FB91 -:104D800012556DB9302383F311882B462A462946E4 -:104D9000FFF732FE85F311880A2384F834300EE0E1 -:104DA000142384F83430302383F3118800231A4607 -:104DB00019462046FFF70EFE002383F3118838BD05 -:104DC000036C03B198470023E7E70021204601F078 -:104DD000FFFA0021204601F0F1FA63681B6813B165 -:104DE0000621204698470623D7E7000010B590F823 -:104DF0003430142B044629D017D8062B05D001D8FF -:104E00001BB110BD093B022BFBD80021204601F04D -:104E1000DFFA0021204601F0D1FA63681B6813B164 -:104E2000062120469847062319E0152BE9D10B23CC -:104E300080F83430302383F3118800231A46194652 -:104E4000FFF7DAFD002383F31188DAE7C3689B6973 -:104E50005B68002BD5D1036C03B19847002384F81D -:104E60003430CEE700230375826803691B689968B4 -:104E70009142FBD25A6803604260106058607047EC -:104E800000230375826803691B6899689142FBD807 -:104E90005A680360426010605860704708B5084661 -:104EA000302383F311880B7D032B05D0042B0DD009 -:104EB0002BB983F3118808BD8B6900221A604FF06B -:104EC000FF338361FFF7CEFF0023F2E7D1E9003221 -:104ED00013605A60F3E70000FFF7C4BF054BD968C1 -:104EE0000875186802681A60536001220275D8605C -:104EF000FBF792BBF84D002030B50C4BDD684B1C26 -:104F000087B004460FD02B46094A684600F084F962 -:104F10002046FFF7E3FF009B13B1684600F086F9D7 -:104F2000A86907B030BDFFF7D9FFF9E7F84D0020B9 -:104F30009D4E0008044B1A68DB6890689B68984295 -:104F400094BF002001207047F84D0020084B10B599 -:104F50001C68D86822681A60536001222275DC60E0 -:104F6000FFF78EFF01462046BDE81040FBF754BB1B -:104F7000F84D0020044B1A68DB6892689B689A42DF -:104F800001D9FFF7E3BF7047F84D002038B5074C53 -:104F900007490848012300252370656001F01AFCC9 -:104FA0000223237085F3118838BD00BF60500020B4 -:104FB00094700008F84D002008B572B6044B1865CF -:104FC00000F05AFC00F018FD024B03221A70FEE7B5 -:104FD000F84D00206050002000F05EB9EFF3118022 -:104FE00020B9EFF30583302282F311887047000067 -:104FF00010B530B9EFF30584C4F3080414B180F39D -:10500000118810BDFFF7B6FF84F31188F9E700009F -:10501000034A516853685B1A9842FBD8704700BF37 -:10502000001000E08B60022308618B820846704705 -:105030008368A3F1840243F8142C026943F8442CDA -:10504000426943F8402C094A43F8242CC26843F8CB -:10505000182C022203F80C2C002203F80B2C044A13 -:1050600043F8102CA3F12000704700BF3106000860 -:10507000F84D002008B5FFF7DBFFBDE80840FFF75B -:105080002BBF0000024BDB6898610F20FFF726BFA3 -:10509000F84D0020302383F31188FFF7F3BF0000A1 -:1050A00008B50146302383F311880820FFF724FF59 -:1050B000002383F3118808BD064BDB6839B14268D1 -:1050C00018605A60136043600420FFF715BF4FF06B -:1050D000FF307047F84D00200368984206D01A68E8 -:1050E0000260506099611846FFF7F6BE70470000F5 -:1050F00038B504460D462068844200D138BD0368A7 -:1051000023605C608561FFF7E7FEF4E710B5036894 -:105110009C68A2420CD85C688A600B604C6021607D -:10512000596099688A1A9A604FF0FF33836010BD06 -:105130001B68121BECE700000A2938BF0A2170B572 -:1051400004460D460A26601901F03EFB01F02AFBD9 -:10515000041BA54203D8751C2E460446F3E70A2E0D -:1051600004D9BDE87040012001F074BB70BD00009F -:10517000F8B5144B0D46D96103F1100141600A2ABC -:105180001969826038BF0A22016048601861A81856 -:10519000144601F00BFB0A2701F004FB431BA3425A -:1051A000064606D37C1C281901F00EFB274635461F -:1051B000F2E70A2F04D9BDE8F840012001F04ABB0C -:1051C000F8BD00BFF84D0020F8B506460D4601F0C9 -:1051D000E9FA0F4A134653F8107F9F4206D12A4638 -:1051E00001463046BDE8F840FFF7C2BFD169BB6851 -:1051F000441A2C1928BF2C46A34202D92946FFF78E -:105200009BFF224631460348BDE8F840FFF77EBFCA -:10521000F84D0020084E002010B4C0E903230023FD -:105220005DF8044B4361FFF7CFBF000010B5194C88 -:10523000236998420DD0D0E90032816813605A602A -:105240009A680A449A60002303604FF0FF33A36119 -:1052500010BD2346026843F8102F536000220260FD -:1052600022699A4203D1BDE8104001F0A7BA9368C1 -:1052700081680B44936001F095FA2269E1699268B4 -:10528000441AA242E4D91144BDE81040091AFFF7BC -:1052900053BF00BFF84D00202DE9F047DFF8BC8078 -:1052A00008F110072C4ED8F8105001F07BFAD8F80E -:1052B0001C40AA68031B9A423ED81444D5E9003228 -:1052C0004FF00009C8F81C4013605A60C5F8009000 -:1052D000D8F81030B34201D101F070FA89F3118887 -:1052E000D5E9033128469847302383F311886B6949 -:1052F000002BD8D001F056FA6A69A0EB04094A45A0 -:1053000082460DD2022001F0A5FA0022D8F8103012 -:10531000B34208D151462846BDE8F047FFF728BF01 -:10532000121A2244F2E712EB090938BF4A4629460D -:105330003846FFF7EBFEB5E7D8F81030B34208D097 -:105340001444211AC8F81C00A960BDE8F047FFF713 -:10535000F3BEBDE8F08700BF084E0020F84D0020E6 -:1053600000207047FEE70000704700004FF0FF305C -:105370007047000002290CD0032904D001290748F6 -:1053800018BF00207047032A05D8054800EBC2006B -:105390007047044870470020704700BF6C710008D8 -:1053A000382300202071000870B59AB005460846E1 -:1053B00001A9144600F0C2F801A8FCF7F7FB431C52 -:1053C0005B00C5E900340022237003236370C6B27A -:1053D00001AB02341046D1B28E4204F1020401D86E -:1053E0001AB070BD13F8011B04F8021C04F8010C7C -:1053F0000132F0E708B5302383F311880348FFF743 -:1054000023FA002383F3118808BD00BF68500020F1 -:1054100090F8443003F01F02012A07D190F845208C -:105420000B2A03D10023C0E90E3315E003F060031B -:10543000202B08D1B0F848302BB990F84520212A0C -:1054400003D81F2A04D8FFF7E1B9222AEBD0FAE7E4 -:10545000034A82630722C26303640120704700BFCE -:105460002F23002007B5052917D8DFE801F019160A -:1054700003191920302383F31188104A0190012168 -:10548000FFF784FA01980E4A0221FFF77FFA0D48D0 -:10549000FFF7A6F9002383F3118803B05DF804FB3E -:1054A000302383F311880748FFF770F9F2E73023C0 -:1054B00083F311880348FFF787F9EBE7C070000812 -:1054C000E47000086850002038B50C4D0C4C0D49B4 -:1054D0002A4604F10800FFF767FF05F1CA0204F14C -:1054E00010000949FFF760FF05F5CA7204F11800C2 -:1054F0000649BDE83840FFF757BF00BF30550020D0 -:1055000038230020A0700008AA700008B5700008B9 -:1055100070B5044608460D46FCF748FBC6B2204667 -:10552000013403780BB9184670BD32462946FCF7A2 -:1055300029FB0028F3D10120F6E700002DE9F04710 -:1055400005460C46FCF732FB2C49C6B22846FFF74D -:10555000DFFF08B10836F6B229492846FFF7D8FF21 -:1055600008B11036F6B2632E0BD8DFF89080DFF862 -:105570009090244FDFF898A02E7846B92670BDE8A9 -:10558000F08729462046BDE8F04701F0C3BC252E30 -:1055900030D1072241462846FCF7F4FA80B91A4B6D -:1055A000224603F10C0153F8040B42F8040B8B4222 -:1055B000F9D119889B781180937007350F34DBE798 -:1055C000082249462846FCF7DDFA98B90F4BA21C81 -:1055D000197809090232C95D02F8041C13F8011B8D -:1055E00001F00F015345C95D02F8031CF0D11834D6 -:1055F0000835C1E704F8016B0135BDE78C7100087F -:10560000B570000894710008326F0008107AFF1F0F -:105610001C7AFF1FBFF34F8F024AD368DB03FCD411 -:10562000704700BF003C024008B5094B1B7873B9B6 -:10563000FFF7F0FF074B1A69002ABFBF064A5A60FE -:1056400002F188325A601A6822F480621A6008BD3A -:105650008E570020003C02402301674508B50B4BE4 -:105660001B7893B9FFF7D6FF094B1A6942F0004245 -:105670001A611A6842F480521A601A6822F4805241 -:105680001A601A6842F480621A6008BD8E570020C2 -:10569000003C02401728F0B516D80C4C0C49237872 -:1056A0007BB90C4D0E4618234FF0006255F8047B71 -:1056B00046F8042B013B13F0FF033A44F6D10123D3 -:1056C000237051F82000F0BD0020FCE7F0570020C7 -:1056D00090570020A8710008014B53F82000704734 -:1056E000A871000818207047172810B5044601D982 -:1056F000002010BDFFF7CEFF064B53F824301844AE -:10570000C21A0BB90120F4E712680132F0D1043B50 -:10571000F6E700BFA8710008172838B5044628D856 -:105720001549FFF777FFFFF77FFFF323CB600C23CB -:10573000B0FBF3F203FB1205D30143EAC503DBB26E -:1057400043F4007343F002030B610B6943F48033AD -:105750000B61FFF75FFFFFF79DFF084B53F8241025 -:1057600000F046F9FFF77AFF2046BDE83840FFF722 -:10577000BBBF002038BD00BF003C0240A87100083C -:10578000F8B512F00103144642D18218B2F1026F4B -:1057900057D82D4B1B6813F0010352D02B4DFFF748 -:1057A00043FFF323EB60FFF735FF40F20127032CA3 -:1057B00015D824F001046618244C401A40F2011751 -:1057C000B142236900EB010524D123F001032361D9 -:1057D000FFF744FF0120F8BD043C0430E7E78307EE -:1057E000E7D12B6923F440732B612B693B432B6179 -:1057F00051F8046B0660BFF34F8FFFF70BFF036890 -:105800009E42E9D02B6923F001032B61FFF726FFAD -:105810000020E0E723F44073236123693B432361C5 -:105820000B882B80BFF34F8FFFF7F4FE2D8831F8E4 -:10583000023BADB2AB42C3D0236923F00103236125 -:10584000E4E71846C7E700BF00380240003C0240CA -:10585000084908B50B7828B11BB9FFF7E5FE01230D -:105860000B7008BD002BFCD0BDE808400870FFF7A6 -:10587000F5BE00BF8E57002008B54FF440314FF001 -:10588000005000F0B7F8BDE808404FF480314FF009 -:10589000805000F0AFB800000846114601F09EBAF3 -:1058A000012001F09BBA0000084601F0B5BA0000E3 -:1058B00070B582B0FFF792FB0E4E054600F072FF06 -:1058C0003268904237BF0C4A0B49516814682EBFAA -:1058D000D1E90041013151600419034641F1000151 -:1058E000284601913360FFF783FB0199204602B0FF -:1058F00070BD00BFF4570020F857002070B582B08B -:10590000FFF76CFB104E054600F04CFF32689042EA -:1059100037BF0E4A0D49516814682EBFD1E90041C6 -:1059200001315160041941F10001034628460191FB -:105930003360FFF75DFB01994FF47A720023204634 -:10594000FAF756FC02B070BDF4570020F85700205B -:1059500010B50244064BD2B2904200D110BD441C97 -:1059600000B253F8200041F8040BE0B2F4E700BFA6 -:10597000502800400F4B30B51C6F240407D41C6F17 -:1059800044F400741C671C6F44F400441C670A4C08 -:10599000236843F4807323600244084BD2B29042E0 -:1059A00000D130BD441C00B251F8045B43F82050D4 -:1059B000E0B2F4E700380240007000405028004098 -:1059C00007B5012201A90020FFF7C2FF019803B02B -:1059D0005DF804FB13B50446FFF7F2FFA04205D0C3 -:1059E000012201A900200194FFF7C4FF02B010BDFD -:1059F000704700007047000070470000094B5A884C -:105A0000B2F5805F10460BD022F0020341F2010292 -:105A1000934205D041F20703C31A584258417047D8 -:105A200001207047002004E0074B45F255521A60F0 -:105A300002225A6040F6FF729A604CF6CC421A601D -:105A4000024B01221A7070470030004004580020B9 -:105A5000034B1B781BB1034B4AF6AA221A6070470E -:105A60000458002000300040034B1A681AB9034A5A -:105A7000D2F874281A6070470058002000300240A5 -:105A8000024B4FF08072C3F8742870470030024018 -:105A900008B5FFF7E9FF024B1868C0F3407008BD76 -:105AA0000058002008B5FFF7DFFF024B1868C0F36D -:105AB000007008BD0058002070470000FEE700009D -:105AC0000A4B0B480B4A90420BD30B4BDA1C121AB1 -:105AD000C11E22F003028B4238BF00220021FCF7D6 -:105AE0006DB853F8041B40F8041BECE7047400087D -:105AF00008590020085900200859002070B5D0E945 -:105B000015439E6800224FF0FF3504EB421351010C -:105B1000D3F800090028BEBFD3F8000940F0804048 -:105B2000C3F80009D3F8000B0028BEBFD3F8000B60 -:105B300040F08040C3F8000B013263189642C3F86E -:105B40000859C3F8085BE0D24FF00113C4F81C38C1 -:105B500070BD0000890141F02001016103699B06CD -:105B6000FCD41220FFF754BA10B5054C2046FEF7BE -:105B7000EDFE4FF0A0436365024BA36510BD00BF6F -:105B8000085800202C72000870B50378012B0546D8 -:105B900050D12A4B446D98421BD1294B5A6B42F08D -:105BA00080025A635A6D42F080025A655A6D5A69F2 -:105BB00042F080025A615A6922F080025A610E2135 -:105BC00043205B69FEF730FB1E4BE3601E4BC4F8BD -:105BD00000380023C4F8003EC02323606E6D4FF4EC -:105BE0005023A3633369002BFCDA012333610C20BB -:105BF000FFF70EFA3369DB07FCD41220FFF708FA2F -:105C00003369002BFCDA0026A6602846FFF776FFF2 -:105C10006B68C4F81068DB68C4F81468C4F81C68C2 -:105C20004BB90A4BA3614FF0FF336361A36843F0A4 -:105C30000103A36070BD064BF4E700BF08580020C5 -:105C4000003802404014004003002002003C30C0F5 -:105C5000083C30C0F8B5446D054600212046FFF7EA -:105C600079FFA96D00234FF001128F68C4F8343812 -:105C70004FF00066C4F81C284FF0FF3004EB4312CD -:105C800001339F42C2F80069C2F8006BC2F80809EC -:105C9000C2F8080BF2D20B686A6DEB6563621023E1 -:105CA0001361166916F01006FBD11220FFF7B0F948 -:105CB000D4F8003823F4FE63C4F80038A36943F431 -:105CC000402343F01003A3610923C4F81038C4F83B -:105CD00014380A4BEB604FF0C043C4F8103B084B3C -:105CE000C4F8003BC4F81069C4F80039EB6D03F147 -:105CF000100243F48013EA65A362F8BD087200083D -:105D000040800010426D90F84E10D2F8003823F415 -:105D1000FE6343EA0113C2F8003870472DE9F843E7 -:105D200000EB8103456DDA68166806F00306731E02 -:105D3000022B05EB41130C4680460FFA81F94FEA1E -:105D400041104FF00001C3F8101B4FF0010104F1A6 -:105D5000100398BFB60401FA03F391698EBF334E66 -:105D600006F1805606F5004600293AD0578A04F11C -:105D70005801490137436F50D5F81C180B43C5F83B -:105D80001C382B180021C3F8101953690127611E14 -:105D9000A7409BB3138A928B9B08012A88BF534369 -:105DA000D8F85C20981842EA034301F1400205EB61 -:105DB0008202C8F85C00214653602846FFF7CAFEFD -:105DC00008EB8900C3681B8A43EA845348346401A2 -:105DD0001E432E51D5F81C381F43C5F81C78BDE86A -:105DE000F88305EB4917D7F8001B21F40041C7F8E9 -:105DF000001BD5F81C1821EA0303C0E704F13F0398 -:105E000005EB83030A4A5A6028462146FFF7A2FEA3 -:105E100005EB4910D0F8003923F40043C0F80039ED -:105E2000D5F81C3823EA0707D7E700BF0080001029 -:105E300000040002826D1268C265FFF75FBE0000B9 -:105E40005831436D49015B5813F4004004D013F4FA -:105E5000001F0CBF02200120704700004831436D35 -:105E600049015B5813F4004004D013F4001F0CBF29 -:105E7000022001207047000000EB8101CB68196A05 -:105E80000B6813604B6853607047000000EB8103A0 -:105E900030B5DD68AA691368D36019B9402B84BF97 -:105EA000402313606B8A1468426D1C44013CB4FBB0 -:105EB000F3F46343033323F0030302EB411043EA9B -:105EC000C44343F0C043C0F8103B2B6803F0030306 -:105ED000012B09B20ED1D2F8083802EB411013F4AD -:105EE000807FD0F8003B14BF43F0805343F0005351 -:105EF000C0F8003B02EB4112D2F8003B43F00443F0 -:105F0000C2F8003B30BD00002DE9F041244D6E6D1C -:105F100006EB40130446D3F8087BC3F8087B380728 -:105F20000AD5D6F81438190706D505EB840321469F -:105F3000DB6828465B689847FA071FD5D6F81438FF -:105F4000DB071BD505EB8403D968CCB98B69488A7C -:105F50005A68B2FBF0F600FB16228AB91868DA68B4 -:105F600090420DD2121AC3E90024302383F3118822 -:105F70000B482146FFF78AFF84F31188BDE8F081C2 -:105F8000012303FA04F26B8923EA02036B81CB68D5 -:105F9000002BF3D021460248BDE8F041184700BF6E -:105FA0000858002000EB810370B5DD68436D6C6913 -:105FB0002668E6604A0156BB1A444FF40020C2F836 -:105FC00010092A6802F00302012A0AB20ED1D3F89E -:105FD000080803EB421410F4807FD4F8000914BFC2 -:105FE00040F0805040F00050C4F8000903EB42122A -:105FF000D2F8000940F00440C2F80009D3F8340890 -:10600000012202FA01F10143C3F8341870BD19B935 -:10601000402E84BF4020206020682E8A8419013CD5 -:10602000B4FBF6F440EAC44040F000501A44C6E71E -:106030002DE9F8433B4D6E6D06EB40130446D3F853 -:106040000889C3F8088918F0010F4FEA40171AD0E1 -:10605000D6F81038DB0716D505EB8003D9684B69F5 -:106060001868DA68904230D2121A4FF000091A60AC -:10607000C3F80490302383F3118821462846FFF7A4 -:1060800091FF89F3118818F0800F1CD0D6F83438AE -:106090000126A640334216D005EB84036D6DD3F87C -:1060A0000CC0DCF814200134E4B2D2F800E005EBB7 -:1060B00004342F445168714515D3D5F8343823EA98 -:1060C0000606C5F83468BDE8F883012303FA04F234 -:1060D0002B8923EA02032B818B68002BD3D0214626 -:1060E00028469847CFE7BCF81000AEEB0103834287 -:1060F00028BF0346D7F8180980B2B3EB800FE2D867 -:106100009068A0F1040959F8048FC4F80080A0EB4E -:1061100009089844B8F1040FF5D818440B4490606E -:106120005360C7E7085800202DE9F74FA24C656D72 -:106130006E69AB691E4016F480586E6107D0204628 -:10614000FEF76CFC03B0BDE8F04FFDF74FBF002E2B -:1061500012DAD5F8003E98489B071EBFD5F8003EDE -:1061600023F00303C5F8003ED5F8043823F00103FB -:10617000C5F80438FEF77CFC370505D58E48FFF7D7 -:10618000BDFC8D48FEF762FCB0040CD5D5F808388C -:1061900013F0060FEB6823F470530CBF43F4105355 -:1061A00043F4A053EB6031071BD56368DB681BB970 -:1061B000AB6923F00803AB612378052B0CD1D5F82C -:1061C000003E7D489A071EBFD5F8003E23F003032A -:1061D000C5F8003EFEF74CFC6368DB680BB17648FF -:1061E0009847F30274D4B70227D5D4F85490DFF857 -:1061F000C8B100274FF0010A09EB4712D2F8003B63 -:1062000003F44023B3F5802F11D1D2F8003B002BCB -:106210000DDA62890AFA07F322EA0303638104EBC9 -:106220008703DB68DB6813B1394658469847A36D8E -:1062300001379B68FFB29F42DED9F00617D5676D24 -:106240003A6AC2F30A1002F00F0302F4F012B2F538 -:10625000802F00F08580B2F5402F08D104EB830336 -:106260000022DB681B6A07F5805790426AD1300331 -:10627000D5F8184813D5E10302D50020FFF744FEF6 -:10628000A20302D50120FFF73FFE630302D50220DF -:10629000FFF73AFE270302D50320FFF735FE75030B -:1062A0007FF550AFE00702D50020FFF7C1FEA10740 -:1062B00002D50120FFF7BCFE620702D50220FFF7DE -:1062C000B7FE23077FF53EAF0320FFF7B1FE39E7A6 -:1062D000636DDFF8E4A0019300274FF00109A36D7F -:1062E0009B685FFA87FB9B453FF67DAF019B03EB05 -:1062F0004B13D3F8001901F44021B1F5802F1FD1C1 -:10630000D3F8001900291BDAD3F8001941F09041A5 -:10631000C3F80019D3F800190029FBDB5946606D5A -:10632000FFF718FC218909FA0BF321EA0303238103 -:1063300004EB8B03DB689B6813B1594650469847C2 -:106340000137CCE7910708BFD7F80080072A98BF2C -:1063500003F8018B02F1010298BF4FEA182884E785 -:10636000023304EB830207F580575268D2F818C055 -:10637000DCF80820DCE9001CA1EB0C0C00218842B1 -:106380000AD104EB830463689B699A6802449A60AB -:106390005A6802445A606AE711F0030F08BFD7F841 -:1063A00000808C4588BF02F8018B01F1010188BF94 -:1063B0004FEA1828E3E700BF08580020436D03EBBD -:1063C0004111D1F8003B43F40013C1F8003B704782 -:1063D000436D03EB4111D1F8003943F40013C1F8C8 -:1063E00000397047436D03EB4111D1F8003B23F4B2 -:1063F0000013C1F8003B7047436D03EB4111D1F826 -:10640000003923F40013C1F80039704730B5039CFC -:106410000172043304FB0325C0E90653049B0363A4 -:106420000021059BC160C0E90000C0E90422C0E969 -:106430000842C0E90A11436330BD0000416A0022EE -:10644000C0E90411C0E90A22C2606FF00101FEF741 -:106450004FBE0000D0E90432934201D1C2680AB9AC -:10646000181D70470020704703691960C268013227 -:10647000C260C269134482690361934224BF436AC4 -:1064800003610021FEF728BE38B504460D46E368D7 -:106490003BB16269131D1268A3621344E3620020DA -:1064A00007E0237A33B929462046FEF705FE002887 -:1064B000EDDA38BD6FF00100FBE70000C368C26988 -:1064C000013BC3604369134482694361934224BF23 -:1064D000436A436100238362036B03B1184770472B -:1064E00070B53023044683F31188866A3EB9FFF7FE -:1064F000CBFF054618B186F31188284670BDA36A04 -:10650000E26A13F8015BA362934202D32046FFF7CD -:10651000D5FF002383F31188EFE700002DE9F84F42 -:1065200004460E46174698464FF0300989F3118805 -:106530000025AA46D4F828B0BBF1000F09D1414686 -:106540002046FFF7A1FF20B18BF311882846BDE854 -:10655000F88FD4E90A12A7EB050B521A934528BF0E -:106560009346BBF1400F1BD9334601F1400251F86D -:10657000040B43F8040B9142F9D1A36A403340362F -:10658000A3624035D4E90A239A4202D32046FFF79A -:1065900095FF8AF31188BD42D8D289F31188C9E7E3 -:1065A00030465A46FBF7E4FAA36A5B445E44A362B2 -:1065B0005D44E7E710B5029C0172043303FB04213C -:1065C000C0E906130023C0E90A33039B0363049B5D -:1065D000C460C0E90000C0E90422C0E90842436386 -:1065E00010BD0000026AC260426AC0E904220022B3 -:1065F000C0E90A226FF00101FEF77ABDD0E9042359 -:106600009A4201D1C26822B9184650F8043B0B6087 -:10661000704700231846FAE7C368C2690133C360B4 -:106620004369134482694361934224BF436A4361CF -:106630000021FEF751BD000038B504460D46E36861 -:106640003BB123691A1DA262E2691344E362002090 -:1066500007E0237A33B929462046FEF72DFD0028AE -:10666000EDDA38BD6FF00100FBE700000369196047 -:10667000C268013AC260C2691344826903619342ED -:1066800024BF436A036100238362036B03B118478D -:106690007047000070B530230D460446114683F361 -:1066A0001188866A2EB9FFF7C7FF10B186F31188EB -:1066B00070BDA36A1D70A36AE26A01339342A362AC -:1066C00004D3E16920460439FFF7D0FF002080F3AE -:1066D0001188EDE72DE9F84F04460D46904699469E -:1066E0004FF0300A8AF311880026B346A76A4FB9E3 -:1066F00049462046FFF7A0FF20B187F311883046B6 -:10670000BDE8F88FD4E90A073A1AA8EB06079742C2 -:1067100028BF1746402F1BD905F1400355F8042B1D -:1067200040F8042B9D42F9D1A36A4033A36240365E -:10673000D4E90A239A4204D3E16920460439FFF7D9 -:1067400095FF8BF311884645D9D28AF31188CDE79E -:1067500029463A46FBF70CFAA36A3B443D44A36240 -:106760003E44E5E7D0E904239A4217D1C3689BB1C0 -:10677000836A8BB1043B9B1A0ED01360C368013B44 -:10678000C360C3691A44836902619A4224BF436AA1 -:106790000361002383620123184670470023FBE74F -:1067A00000F0D2B84FF08043586A70474FF08043F2 -:1067B000002258631A610222DA6070474FF080436A -:1067C0000022DA60704700004FF080435863704742 -:1067D000FEE7000070B51B4B01630025044686B040 -:1067E000586085620E46FDF7DDFB04F11003C4E935 -:1067F00004334FF0FF33C4E90635C4E90044A56013 -:10680000E562FFF7CFFF2B460246C4E9082304F1F7 -:1068100034010D4A256580232046FEF703FC012341 -:10682000E0600A4A0375009272680192B268CDE98D -:106830000223074B6846CDE90435FEF71BFC06B082 -:1068400070BD00BF60500020387200083D72000823 -:10685000D1670008024AD36A1843D062704700BF6C -:10686000F84D00204B6843608B688360CB68C36041 -:106870000B6943614B6903628B6943620B68036078 -:106880007047000008B5264B26481A6940F2FF11F0 -:106890000A431A611A6922F4FF7222F001021A6196 -:1068A0001A691A6B0A431A631A6D0A431A651E4A5B -:1068B0001B6D1146FFF7D6FF02F11C0100F5806049 -:1068C000FFF7D0FF02F1380100F58060FFF7CAFF43 -:1068D00002F1540100F58060FFF7C4FF02F170017E -:1068E00000F58060FFF7BEFF02F18C0100F58060CB -:1068F000FFF7B8FF02F1A80100F58060FFF7B2FFD3 -:1069000002F1C40100F58060FFF7ACFF02F1E00185 -:1069100000F58060FFF7A6FFBDE8084000F090B8E2 -:1069200000380240000002404472000808B500F040 -:106930000BFAFEF72BFBFFF797F8BDE80840FEF7D0 -:10694000C3BD0000704700000F4B1A6C42F00102FB -:106950001A641A6E42F001021A660C4A1B6E9368A2 -:1069600043F0010393604FF0804353229A624FF04B -:10697000FF32DA6200229A615A63DA605A600122B9 -:106980005A611A60704700BF00380240002004E0DE -:106990004FF0804208B51169D3680B40D9B2C943A2 -:1069A0009B07116107D5302383F31188FEF714FB91 -:1069B000002383F3118808BD1F4B1A696FEAC25286 -:1069C0006FEAD2521A611A69C2F308021A614FF0D3 -:1069D000FF301A695A69586100215A6959615A6928 -:1069E0001A6A62F080521A621A6A02F080521A62BF -:1069F0001A6A5A6A58625A6A59625A6A1A6C42F09A -:106A000080521A641A6E42F080521A661A6E0B4A4D -:106A1000106840F480701060186F00F44070B0F59A -:106A2000007F1EBF4FF4803018671967536823F446 -:106A30000073536000F060B90038024000700040FD -:106A4000344B4FF080521A64334A4FF44041116086 -:106A50001A6842F001021A601A689107FCD59A6818 -:106A600022F003029A602B4B9A6812F00C02FBD1C1 -:106A7000196801F0F90119609A601A6842F48032CD -:106A80001A601A689203FCD55A6F42F001025A67E5 -:106A9000204B5A6F9007FCD5204A5A601A6842F082 -:106AA00080721A601C4A53685904FCD5194B1A6845 -:106AB0009201FCD51A4A9A600322C3F88C20194B24 -:106AC0001A68194B9A42194B21D1194A1168194A6F -:106AD00091421CD140F205121A60144A136803F067 -:106AE0000F03052BFAD10B4B9A6842F002029A6011 -:106AF0009A6802F00C02082AFAD15A6C42F48042D9 -:106B00005A645A6E42F480425A665B6E704740F295 -:106B10000572E1E700380240007000401854400759 -:106B200000948838002004E011640020003C0240FA -:106B300000ED00E041C20F41074A08B5536903F078 -:106B40000103536123B1054A13680BB1506898479C -:106B5000BDE80840FDF74ABA003C014080580020DB -:106B6000074A08B5536903F00203536123B1054A8C -:106B700093680BB1D0689847BDE80840FDF736BA76 -:106B8000003C014080580020074A08B5536903F0D3 -:106B90000403536123B1054A13690BB15069984747 -:106BA000BDE80840FDF722BA003C014080580020B3 -:106BB000074A08B5536903F00803536123B1054A36 -:106BC00093690BB1D0699847BDE80840FDF70EBA4C -:106BD000003C014080580020074A08B5536903F083 -:106BE0001003536123B1054A136A0BB1506A9847E9 -:106BF000BDE80840FDF7FAB9003C0140805800208C -:106C0000164B10B55C6904F478725A61A30604D57A -:106C1000134A936A0BB1D06A9847600604D5104AAC -:106C2000136B0BB1506B9847210604D50C4A936B3C -:106C30000BB1D06B9847E20504D5094A136C0BB130 -:106C4000506C9847A30504D5054A936C0BB1D06CE2 -:106C50009847BDE81040FDF7C9B900BF003C0140AE -:106C600080580020194B10B55C6904F47C425A61CD -:106C7000620504D5164A136D0BB1506D9847230574 -:106C800004D5134A936D0BB1D06D9847E00404D539 -:106C90000F4A136E0BB1506E9847A10404D50C4AED -:106CA000936E0BB1D06E9847620404D5084A136FF7 -:106CB0000BB1506F9847230404D5054A936F0BB16D -:106CC000D06F9847BDE81040FDF790B9003C0140F7 -:106CD0008058002008B50348FDF724FABDE80840B5 -:106CE000FDF784B9884B002008B5FFF751FEBDE8D9 -:106CF0000840FDF77BB90000062108B50846FDF7FE -:106D000093FA06210720FDF78FFA06210820FDF7E8 -:106D10008BFA06210920FDF787FA06210A20FDF7E4 -:106D200083FA06211720FDF77FFA06212820FDF7B8 -:106D30007BFA07211C20FDF777FABDE808400C21FB -:106D40002620FDF771BA000008B5FFF735FE00F008 -:106D50000DF8FDF711FCFDF7F7FDFDF7CFFCFFF790 -:106D6000F1FDBDE80840FFF71BBD00000023054A08 -:106D700019460133102BC2E9001102F10802F8D1C3 -:106D8000704700BF805800200B460146184600F0AF -:106D90002DB8000000F040B8012838BF012010B520 -:106DA0000446204600F030F830B900F007F808B982 -:106DB00000F00CF88047F4E710BD0000024B1868A3 -:106DC000BFF35B8F704700BF0059002008B5062055 -:106DD00000F084F80120FEF7C5FA0000024B0A46D5 -:106DE00001461868FEF758BD5823002010B5054C21 -:106DF00013462CB10A4601460220AFF3008010BDB5 -:106E00002046FCE700000000024B01461868FEF730 -:106E100047BD00BF58230020024B01461868FEF70B -:106E200043BD00BF5823002010B5013902449042F1 -:106E300001D1002005E0037811F8014FA34201D0F1 -:106E4000181B10BD0130F2E72DE9F041A3B1C91ABA -:106E500017780144044603F1FF3C8C42204601D9D7 -:106E6000002009E00578BD4204F10104F5D10CEBE6 -:106E70000405D618A54201D1BDE8F08115F8018DB1 -:106E800016F801EDF045F5D0E7E700001F2938B509 -:106E900004460D4604D9162303604FF0FF3038BD79 -:106EA000426C12B152F821304BB9204600F030F854 -:106EB0002A4601462046BDE8384000F017B8012BAD -:106EC0000AD0591C03D1162303600120E7E70024F0 -:106ED00042F82540284698470020E0E7024B01464B -:106EE0001868FFF7D3BF00BF5823002038B5074DFF -:106EF00000230446084611462B60FEF737FA431C70 -:106F000002D12B6803B1236038BD00BF04590020B3 -:106F1000FEF726BA034611F8012B03F8012B002ACD -:106F2000F9D170476F72672E6172647570696C6F0A -:106F3000742E50697872616365722D706572697024 -:106F40006800000053544D3332463F3F3F005354D6 -:106F50004D3332463430780053544D333246343258 -:106F6000780053544D3332463434365858000000BC -:106F7000012033000010410001105A000310590095 -:106F80000710310000000000446F000813040000E7 -:106F90004E6F000819040000586F0008210400001B -:106FA000626F000840A2E4F1646891060041A3E525 -:106FB000F2656992070000004261642043414E4936 -:106FC0006661636520696E6465782E00800000004C -:106FD00000800000000080000000000000000000B1 -:106FE000F5240008DD2C00083D2C000805250008CC -:106FF000392500083527000809250008192500084B -:107000000D25000815250008112500085D2600083B -:107010001D250008A92F00082D250008312600088D -:1070200000960000000000000000000000000000CA -:107030000000000000000000394500082545000858 -:10704000614500084D4500085945000845450008C0 -:10705000314500081D4500086D450008000000008E -:107060007946000865460008A14600088D460008DC -:107070009946000885460008714600085D460008EC -:10708000AD46000800000000010000000000000004 -:107090006330000090700008504E002060500020C7 -:1070A0004172647550696C6F740025424F415244BF -:1070B000252D424C002553455249414C25000000E6 -:1070C0000200000000000000954800080149000887 -:1070D0004000400000550020105500200200000034 -:1070E0000000000003000000000000004549000807 -:1070F00000000000100000002055002000000000EB -:1071000001000000000000000858002001010200FA -:10711000655400087553000811540008F553000821 -:10712000430000002871000809024300020100C06A -:1071300032090400000102020100052400100105CB -:10714000240100010424020205240600010705822F -:10715000030800FF09040100020A000000070501FE -:1071600002400000070581024000000012000000FC -:107170007471000812011001020000400912415709 -:1071800000020102030100000403090425424F41EB -:1071900052442500303132333435363738394142A4 -:1071A000434445460000000000400000004000004D -:1071B000004000000040000000000100000002004C -:1071C00000000200000002000000020000000200B7 -:1071D000000002000000020000400000004000002B -:1071E000004000000040000000000100000002001C -:1071F0000000020000000200000002000000020087 -:10720000000002000000020000000000894A00089F -:10721000414D0008ED4D0008400040006858002036 -:10722000685800200100000078580020800000000D -:1072300040010000030000006D61696E0069646C2C -:10724000650000000000802A00000000AAAAAAAA87 -:1072500000000024FFFF00000000000000A00A0062 -:107260004400000000000000AAAAAAAA0000000032 -:10727000FFFF0000000000000000000010000040C0 -:1072800000000000AAAAAAAA10000040FFFF000008 -:1072900000000000000000000A681000000000006C -:1072A000AAAAAAAA00541000FFFF000099007007C4 -:1072B000000000000000004000000000AAAAAAAAE6 -:1072C00000000040FFFF0000000000000000000080 -:1072D0000000000000000000AAAAAAAA0000000006 -:1072E000FFFF0000000000000000000000000000A0 -:1072F00000000000AAAAAAAA00000000FFFF0000E8 -:10730000000000000000000000000000000000007D -:107310000A00000000000000030000000000000060 -:10732000000000000000000000000000000000005D -:10733000000000000000000000000000000000004D -:10734000E08EFF7F010000007A05000000000000D1 -:1073500000001F000000000040420F00FE2A010054 -:10736000D2040000FF00000068500020884B00207D -:1073700000960000000008009600000000080000D1 -:1073800004000000887100080000000000000000F8 -:1073900000000000000000000000000000000000ED -:1073A0005C2300200000000000000000000000003E -:1073B00000000000000000000000000000000000CD -:1073C00000000000000000000000000000000000BD -:1073D00000000000000000000000000000000000AD -:1073E000000000000000000000000000000000009D -:1073F000000000000000000000000000000000008D -:047400000000000088 +:1000000000070020F1010008BD2C0008752C000835 +:100010009D2C0008752C0008952C0008F3010008A1 +:10002000F3010008F3010008F3010008B13C0008E7 +:10003000F3010008F3010008F3010008F3010008D0 +:10004000F3010008F3010008F3010008F3010008C0 +:10005000F3010008F301000829680008516800084E +:1000600079680008A1680008C9680008F301000861 +:10007000F3010008F3010008F3010008F301000890 +:10008000F3010008F3010008F3010008292C00081F +:10009000552C0008652C0008F3010008F1680008E1 +:1000A000F3010008F3010008F3010008F301000860 +:1000B000D9690008F3010008F3010008F301000802 +:1000C000F3010008F3010008F3010008F301000840 +:1000D000F3010008F3010008C5690008F3010008F6 +:1000E00055690008F3010008F3010008F301000856 +:1000F000F3010008F3010008F3010008F301000810 +:10010000F3010008F3010008F3010008F3010008FF +:10011000F3010008F3010008F3010008F3010008EF +:10012000F3010008F3010008F3010008F3010008DF +:10013000F3010008F3010008F3010008F3010008CF +:10014000F3010008F3010008F3010008195E00083C +:10015000F3010008F3010008F3010008F3010008AF +:10016000F3010008F3010008F3010008F30100089F +:10017000F3010008F3010008F3010008F30100088F +:10018000F3010008F3010008F3010008F30100087F +:10019000F3010008F3010008F3010008F30100086F +:1001A000F3010008F3010008F3010008F30100085F +:1001B000F3010008F3010008F3010008F30100084F +:1001C000F3010008F3010008F3010008F30100083F +:1001D000F3010008F3010008F3010008F30100082F +:1001E0009D15000800000000000000000000000055 +:1001F00002E000F000F8FEE772B6374880F30888A6 +:10020000364880F3098836483649086040F20000D5 +:10021000CCF200004EF63471CEF200010860BFF35C +:100220004F8FBFF36F8F40F20000C0F2F0004EF628 +:100230008851CEF200010860BFF34F8FBFF36F8F7C +:100240004FF00000E1EE100A4EF63C71CEF20001D4 +:100250000860062080F31488BFF36F8F05F0A4FABE +:1002600006F088F94FF055301F491B4A91423CBFB8 +:1002700041F8040BFAE71D49184A91423CBF41F886 +:10028000040BFAE71A491B4A1B4B9A423EBF51F82E +:10029000040B42F8040BF8E700201849184A914271 +:1002A0003CBF41F8040BFAE705F082FA06F0B6F914 +:1002B000144C154DAC4203DA54F8041B8847F9E797 +:1002C00000F042F8114C124DAC4203DA54F8041B12 +:1002D0008847F9E705F06ABA0007002000230020EC +:1002E0000000000808ED00E00001002000070020E9 +:1002F0003070000800230020BC230020C023002011 +:1003000004590020E0010008E4010008E4010008AD +:10031000E40100082DE9F04F2DED108AC1F80CD052 +:10032000C3689D46BDEC108ABDE8F08F002383F3BF +:1003300011882846A047002004F01CFDFEE704F0C9 +:100340009BFC00DFFEE70000F8B501F0A3F905F023 +:10035000CDF930B12A4B00220F211A725A729972CC +:10036000DA7205F0A5F9074605F00AFA05460028F5 +:100370003AD1244B9F4237D001339F4237D0224B92 +:1003800027F0FF029A4235D1F8B200F025FF2E4641 +:1003900042F2107400F026FF08B10024264601F056 +:1003A00069FD20B1032000F085F80024264635B110 +:1003B000164B9F4203D005F0DBF9002426460020AF +:1003C00005F080F9124B1B6913F4807316D00EB13F +:1003D00000F086F801F0CCFA00F070FF204600F043 +:1003E000E5F800F07DF8F9E72E460024D2E7044650 +:1003F0000126CFE7064641F28834CBE71C46E9E701 +:1004000000230020010007B0000008B0263A09B020 +:100410000004024008B501F009F9A0F12003584298 +:10042000584108BD07B541F21203022101A8ADF8F9 +:10043000043001F019F903B05DF804FB38B530233E +:1004400083F31188174803680BB104F05FFD164A67 +:10045000144800234FF47A7104F04EFD002383F317 +:100460001188124C236813B12368013B2360636831 +:1004700013B16368013B63600D4D2B7833B963683A +:100480007BB9022001F0D6F9322363602B78032B6D +:1004900007D163682BB9022001F0CCF94FF47A73CD +:1004A000636038BDC02300203D040008E024002024 +:1004B000D8230020084B187003280CD8DFE800F080 +:1004C00008050208022001F0A5B9022001F094B944 +:1004D000024B00225A607047D8230020E0240020FD +:1004E00010B501F0C7FC30B1294B03221A70294B1B +:1004F00000225A6010BD284B284A1C461968013159 +:10050000F8D004339342F9D16268254B9A42F1D96D +:10051000244B9B6803F1006303F580339A42E9D2D0 +:1005200005F0FAF805F00CF9002001F0CDF80220F2 +:10053000FFF7C0FF1C4B1A6C00221A64196E1A6672 +:10054000196E596C5A64596E5A665A6E5A6942F05D +:1005500080025A615A6922F080025A615A691A6906 +:1005600042F000521A611A6922F000521A611B69A6 +:1005700072B64FF0E0233021C3F8084DD4E90032C1 +:1005800081F311889D4683F308881047B2E700BFC6 +:10059000D8230020E02400200000010820000108EA +:1005A000FFFF000800230020003802402DE9F04F33 +:1005B00093B0AC4B00902022FF210AA89D6801F067 +:1005C00081F9A94A1378A3B9A848012103601170E1 +:1005D000302383F3118803680BB104F097FCA44A1D +:1005E000A24800234FF47A7104F086FC002383F3C1 +:1005F0001188009B13B19F4B009A1A609E4A009C81 +:100600001378032B1EBF002313709A4A4FF0000A81 +:1006100018BF5360D3465646D146012001F0FAF880 +:1006200024B1944B1B68002B00F01582002000F0D1 +:10063000FDFF0390039B002B01DA00F087FE039B74 +:10064000002BEDDB012001F0D7F8039B213B162B9B +:10065000E3D801A252F823F0B5060008DD06000831 +:10066000710700081B0600081B0600081B0600088F +:10067000FB070008CB090008E50800084709000847 +:100680006F090008950900081B060008A709000863 +:100690001B060008190A0008550700081B06000879 +:1006A0005D0A0008C1060008550700081B0600087F +:1006B000470900080220FFF7ADFE002840F0F58151 +:1006C000009B0221BAF1000F08BF1C4605A841F2A9 +:1006D0001233ADF8143000F0C7FF9EE74FF47A7084 +:1006E00000F0A4FF071EEBDB0220FFF793FE0028BB +:1006F000E6D0013F052F00F2DA81DFE807F0030AB8 +:100700000D10133605230593042105A800F0ACFF56 +:1007100017E054480421F9E758480421F6E75848FF +:100720000421F3E74FF01C08404600F0CFFF08F12A +:1007300004080590042105A800F096FFB8F12C0FDD +:10074000F2D1012000FA07F747EA0B0B5FFA8BFBA7 +:100750004FF0000901F002F926B10BF00B030B2B4F +:1007600008BF0024FFF75EFE57E746480421CDE7A7 +:10077000002EA5D00BF00B030B2BA1D10220FFF70D +:1007800049FE074600289BD0012000F09DFF022073 +:10079000FFF790FE00261FFA86F8404600F0A4FFFF +:1007A000044690B10021404600F0B6FF0136002813 +:1007B000F1D1BA46044641F21213022105A8ADF860 +:1007C00014303E4600F050FF27E70120FFF772FE8D +:1007D0002546244B9B68AB4207D9284600F076FF9C +:1007E000013040F067810435F3E7234B00251D708D +:1007F000204BBA465D603E46ACE7002E3FF460AF4A +:100800000BF00B030B2B7FF45BAF0220FFF752FEC4 +:10081000322000F00BFFB0F10008FFF651AF18F0E6 +:1008200003077FF44DAF0F4A926808EB050393422C +:100830003FF646AFB8F5807F3FF742AF124B0193CA +:10084000B84523DD4FF47A7000F0F0FE0390039A70 +:10085000002AFFF635AF019B039A03F8012B0137FD +:10086000EDE700BF00230020DC240020C02300208F +:100870003D040008E0240020D823002004230020A9 +:10088000082300200C230020DC230020C820FFF7D1 +:10089000C1FD074600283FF413AF1F2D11D8C5F145 +:1008A000200242450AAB25F0030028BF4246834997 +:1008B0000192184400F0E0FF019A8048FF2101F006 +:1008C00001F84FEAA8037D490193C8F3870228463F +:1008D00001F000F8064600283FF46DAF019B05EBE0 +:1008E000830537E70220FFF795FD00283FF4E8AEC7 +:1008F00000F032FF00283FF4E3AE0027B846704B0B +:100900009B68BB4218D91F2F11D80A9B01330ED008 +:1009100027F0030312AA134453F8203C05934046E2 +:10092000042205A901F05EFA04378046E7E738465D +:1009300000F0CCFE0590F2E7CDF81480042105A864 +:1009400000F092FE06E70023642104A8049300F05F +:1009500081FE00287FF4B4AE0220FFF75BFD002883 +:100960003FF4AEAE049800F0DFFE0590E6E700230A +:10097000642104A8049300F06DFE00287FF4A0AE6B +:100980000220FFF747FD00283FF49AAE049800F0DC +:10099000DBFEEAE70220FFF73DFD00283FF490AEC2 +:1009A00000F0EAFEE1E70220FFF734FD00283FF403 +:1009B00087AE05A9142000F0E5FE04210746049047 +:1009C00004A800F051FE3946B9E7322000F02EFEAF +:1009D000071EFFF675AEBB077FF472AE384A926809 +:1009E00007EB090393423FF66BAE0220FFF712FDBF +:1009F00000283FF465AE27F003074F44B9453FF4A4 +:100A0000A9AE484600F062FE0421059005A800F05A +:100A10002BFE09F10409F1E74FF47A70FFF7FAFCB5 +:100A200000283FF44DAE00F097FE002844D00A9B0A +:100A300001330BD008220AA9002000F04BFF002848 +:100A40003AD02022FF210AA800F03CFFFFF7EAFC81 +:100A50001C4804F095F913B0BDE8F08F002E3FF468 +:100A60002FAE0BF00B030B2B7FF42AAE0023642177 +:100A700005A8059300F0EEFD074600287FF420AEA0 +:100A80000220FFF7C7FC804600283FF419AEFFF7AD +:100A9000C9FC41F2883004F073F9059800F0A2FF18 +:100AA000464600F05BFF3C46B7E5064652E64FF08F +:100AB000000905E6BA467EE637467CE6DC230020E0 +:100AC00000230020A0860100094A136849F269004A +:100AD00099B21B0C00FB01331360064B186844F2FB +:100AE000506182B2000C01FB0200186080B27047B6 +:100AF000182300201423002010B5002110220446E2 +:100B000000F0E0FE034B03CB206061601868A0603A +:100B100010BD00BF107AFF1F2DE9F041ADF5507DEB +:100B20000DF13C086EAC40F2751207460D4610A858 +:100B30000021C8F8001000F0C5FE4FF4C472002177 +:100B4000204600F0BFFE02F0C1F8274B4FF47A7246 +:100B5000B0FBF2F0186093E80700022384E8070076 +:100B60000DF5ED702382FFF7C7FF47F605231F49F8 +:100B7000238407A806F046F81D2384F832310DF2CD +:100B8000EB2207AB0DF1340C1E4603CE6645106018 +:100B90005160334602F10802F6D1306810603379B3 +:100BA000137141460122204600F03EFF00230393CB +:100BB000AB7E029305F11903019380B20123CDE9C5 +:100BC00004800093E97E06A3D3E90023384602F0AF +:100BD00045FC0DF5507DBDE8F08100BFAFF300800E +:100BE0009E6AC421818A46EEE8240020146C000825 +:100BF0002DE9F0412C4C237ADAB080460D465BBBE0 +:100C000027A9284601F020F80746002842D19DF880 +:100C10009D60C82E3ED801464FF4A662204600F0E3 +:100C200051FE4FF48073C4F8F8314FF40073C4F8E8 +:100C30000C334FF44073C4F8203432460DF19E015A +:100C400004F1090000F018FE26449DF89C307772EC +:100C500023720BB9EB7E23728122002106AC27A8F8 +:100C600000F030FE0122214627A801F029F80023D8 +:100C70000393AB7E029305F1190380B201932823FD +:100C8000CDE904400093E97E05A3D3E90023404663 +:100C900002F0E4FB5AB0BDE8F08100BFAFF3008082 +:100CA00026417272DF25D7B708460020F0B5254EE1 +:100CB0004FF48A7505FB0065F1B096F8D83085F8D9 +:100CC000DC300024D822214685F8E8403AA800F01C +:100CD000F9FD06F1090000F0EDFDD5F8E4308DF8DE +:100CE000F000C2B206AF06F109010DF1F100CDE945 +:100CF0003A3400F0C1FD394601223AA801F00CF85F +:100D000080B2CDE9047008230127CDE9023706F14E +:100D1000D803019330230093317A0B4807A3D3E91A +:100D2000002302F09BFBA04206DD01F0CFFFC5F8D7 +:100D3000E000384671B0F0BD2046FBE778F6339FFF +:100D400093CACD8D08460020003500202DE9F041E2 +:100D50001D4D1E4E1E4F86B0284602F0ABFB0346CB +:100D600058B30024CDE90344ADF81440027B8DF85C +:100D7000142099684068029403AA03C21B68DFF834 +:100D8000548043F00043029301F0A2FF821941F125 +:100D90000003009402A9384601F04AFAA04205DD9A +:100DA000284602F08BFB88F80040D5E798F8003021 +:100DB000072B05D8013388F8003006B0BDE8F08174 +:100DC000014802F07BFBF8E70035002040420F00AD +:100DD000303500203D4B002070B50D4614461E46B0 +:100DE00002F098FA50B9022E10D1012C0ED112A3A4 +:100DF000D3E90023C5E90023012007E0282C10D007 +:100E000005D8012C09D0052C0FD0002070BD302C46 +:100E1000FBD10BA3D3E90023ECE70BA3D3E9002319 +:100E2000E8E70BA3D3E90023E4E70BA3D3E900230E +:100E3000E0E700BFAFF30080401DA12026812A0B10 +:100E400078F6339F93CACD8D9E6AC421818A46EE7F +:100E500026417272DF25D7B7F017304A39059E5602 +:100E600038B505460E4C0021013500F055FCA4F8BC +:100E70002C55B4F82C0500F037FC78B1B4F82C05EB +:100E800000F042FC014648B9B4F82C0500F044FCDF +:100E9000B4F82C350133A4F82C35EAE738BD00BF8F +:100EA0000846002010B50A4B0A4A1A6003F5805321 +:100EB00093F860203AB9DC6D2CB1204601F058F867 +:100EC000204605F0DFFDBDE81040034801F050B8B2 +:100ED00030350020D06C0008784500202DE9F04F17 +:100EE0008FB000AF05460C4602F014FA002849D135 +:100EF000237E022B1BD1E38A012B18D101F0E6FEE1 +:100F00000646FFF7E1FD03464FF4C870DFF8C482E0 +:100F1000B3FBF0F206F5167602FB103316FA83F3F4 +:100F2000C8F80030E37E33B9A34B00221A703C3777 +:100F3000BD46BDE8F08F07F12401204600F042FED7 +:100F40000028F4D107F11400FFF7D6FD97F82640EA +:100F500007F11401224607F1270005F0DDFD002806 +:100F6000E2D10F2C08D8944B1C70D8F80030A3F5B0 +:100F70001673C8F80030DAE797F82410284602F014 +:100F8000C1F9D4E7E38A282B2BD010D8012B23D02A +:100F9000052BCCD1BFF34F8F8849894BCA6802F427 +:100FA000E0621343CB60BFF34F8F00BFFDE7302BF0 +:100FB000BDD1844EE17E327A9142B8D1607E314615 +:100FC000002291F8DC50854200F0A5800132042A0D +:100FD00001F58A71F5D1AAE721462846FFF79CFD65 +:100FE000A5E721462846FFF703FEA0E7B2F8EC503C +:100FF0007B6005F103094FEA99094FEA8902D11D87 +:10100000C908A8EBC1039D46EB460021584600F0F5 +:1010100059FC04F1EE012A463144584600F02CFCFC +:101020007B6813B9012000F04FFB96F8D20000F066 +:101030005BFB044630B9307200F08EFB204600F0B6 +:1010400043FBB1E0D6F8D4203AB996F8D200B6F80E +:101050002C25824201D8FFF703FFD6F8D4202A447A +:10106000944208D296F8D200B6F82C25013082427C +:1010700001D8FFF7F5FE70685FFA89F2594600F073 +:1010800029FC08B9C54679E0726896F8D2002A446E +:101090007260D6F8D42005EB0209C6F8D49000F0AF +:1010A00023FB814509D396F8D220D6F8D40001322B +:1010B000001B86F8D220C6F8D400FF2D0FD80024DC +:1010C000347200F049FB204600F0FEFA00F0D2FE38 +:1010D0003D4B188108B9FFF703FAC54627E7BB68FF +:1010E00096F8D9000AFB0362FB68D2F8E41082F894 +:1010F000E83001F58061C2F8E030C2F8E410FFF793 +:10110000D5FDFFF723FE96F8D920013202F0030245 +:1011100086F8D920B6E74FF48A7A0AFB02F505F182 +:10112000EA013144204600F023FEF86000287FF4F5 +:10113000FEAE3544012285F8E82001F0C7FDD5F860 +:10114000E020D6ED007ADFED216A801A192838BF39 +:10115000192040F6B832904228BF1046B8EE677AA0 +:1011600007EE900AF8EEE77A67EEA67ADFED186AE6 +:10117000E7EE267AFCEEE77AC6ED007A96F8D930EB +:10118000BB60BA6873680AFB02F4321992F8E8107F +:1011900059B1D2F8E4108B42E8463FF427AF002162 +:1011A00082F8E810C2F8E010C5467368064A9B0A48 +:1011B00001331381BBE600BFF934002000ED00E0ED +:1011C0000400FA0508460020E8240020CDCCCC3DE0 +:1011D0006666663FFC340020014B1870704700BF04 +:1011E000F424002030B54FF000542B4B22689A4273 +:1011F00085B007D004F0CEFA044620BB0024204678 +:1012000005B030BD254B627D25481A70237D0372E1 +:101210004FF48073C0F8F8314FF40073C0F80C330A +:1012200000254FF44073C0F820341E49C0F8E45044 +:10123000C922093000F020FB2046E022294600F0B8 +:1012400041FB0124DBE7184A184D136C43F000738F +:101250001364AA6D164B9A42D0D12B6E013B7E2BA4 +:10126000CCD8144A07CA01AB83E80700184603210B +:1012700000F0CEFD6B6D83424FF00003BED12A6DAE +:101280008A4201BFAB65054B2A6E1A7003BF0A4B39 +:10129000EA6D1A601C46B2E79AAD44C5F4240020FA +:1012A000084600201600002000380240006600407A +:1012B0005041A0B0586600401023002037B51A4DA9 +:1012C00000F0D8FD02236B71184B2881196818486B +:1012D000012201F097FB00230193164B164900935E +:1012E0001648174B4FF4805201F0E4FF154B197864 +:1012F00011B1124802F006F801F0E8FC0446FFF7CD +:10130000E3FB4FF4C873B0FBF3F202FB130304F5E5 +:10131000167010FA83F00C4B186004F031FA08B123 +:101320000F232B8103B030BDE824002010230020C0 +:1013300030350020D90D0008F824002000350020A9 +:10134000DD0E0008F4240020FC3400202DE9F04FCD +:101350002DED028B0FF23829D9E90089834C93B027 +:101360000BAE9FED7E8BFFF7F1FC814FDFF828A2DB +:1013700000230A93ADF834300B9373604FF0000BE9 +:101380005B468DED008B01250DF11D0207A9384646 +:101390008DF81C508DF81DB001F0E2FA9DF81C305C +:1013A000002B40F0A580204601F0B4FF064600283F +:1013B00045D1704F01F08AFC3B6898423FD301F061 +:1013C00085FC8246FFF780FB4FF4C873B0FBF3F255 +:1013D00002FB13030AF5167010FA83F03860664FAB +:1013E00097F800B0CBF1100ABBF1000F14BF3346E1 +:1013F0002B465FFA8AFA0EA88DF82830FFF77CFB9F +:10140000BAF1060F28BF4FF0060A0EAB03EB0B0133 +:1014100052460DF1290000F02FFA0AAB039318236E +:1014200002930AF10102554BD2B2CDE90053049266 +:1014300020464CA3D3E9002301F0B2FF3E7001F037 +:1014400045FC4F4A4F4D1368C31AB3F57A7F2ED32C +:10145000106001F03DFC02460B46204602F038F8D1 +:10146000204601F057FF10B32B7A474E002B14BFD4 +:1014700003230223737101F029FC0EAF4FF47A733A +:101480000122B0FBF3F039463060304600F072FBC9 +:10149000182302933D4B019380B240F25513CDE9DE +:1014A0000370009342464B46204601F079FF2B7AA9 +:1014B00093B101F00BFC002607464FF48A7A95F8A9 +:1014C000D900304400F003000AFB005393F8E820F1 +:1014D00092B30136042EF2D1C82003F051FC2B7ACE +:1014E000002B7FF43DAF13B0BDEC028BBDE8F08F55 +:1014F000DAF8143083F00203CAF814305946102287 +:101500000EA800F0DFF90DF11E0308AA0AA938465B +:1015100000F08EFF96E803000FAB83E803009DF810 +:1015200034308DF844300A9B0E930EA9DDE9082370 +:10153000204602F0A1F921E7D3F8E02042B12B6860 +:10154000FA2B38BFFA23BA1A0533B2EB430FC0D3D4 +:10155000FFF7ACFB0028BCD1BEE700BF00000000D5 +:1015600000000000401DA12026812A0B003500202C +:1015700030350020FC340020F9340020F8340020FD +:10158000384B002008460020E82400203C4B002077 +:10159000F1C6A7C1D068080F0004024008B505488D +:1015A00000F0E2FFBDE80840034A0449002005F0CE +:1015B00063BA00BF303500208C4B0020A50E000818 +:1015C0002DE9F84F4FF47A73DFF85880DFF8589020 +:1015D00006460D4602FB03F7002498F900305A1C1A +:1015E0005FFA84FA01D0A34212D159F824000368AB +:1015F0002A46D3F820B031463B46D847854207D12A +:10160000074B012083F800A0BDE8F88F0124E4E730 +:10161000002CFBD04FF4FA7003F0B2FB0020F3E78C +:10162000804B00201C2300202023002007B500232E +:10163000024601210DF107008DF80730FFF7C0FFCA +:1016400020B19DF8070003B05DF804FB4FF0FF30B8 +:10165000F9E700000A4608B50421FFF7B1FF80F062 +:101660000100C0B2404208BD30B4074B0A461978A9 +:10167000064B53F821402368DD69054B0146AC4613 +:10168000204630BC604700BF804B00202023002054 +:10169000A086010070B503F0A5FE094E094D30800B +:1016A000002428683388834208D903F095FE2B680C +:1016B00004440133B4F5803F2B60F2D370BD00BF0A +:1016C000824B0020404B002003F042BF00F100603D +:1016D00000F580300068704700F10060920000F56E +:1016E000803003F0CDBE0000054B1A68054B1B8807 +:1016F0009B1A834202D9104403F06EBE002070474B +:10170000404B0020824B0020024B1B68184403F022 +:101710006BBE00BF404B0020024B1B68184403F017 +:101720007BBE00BF404B002010F003030AD1B0F590 +:10173000047F05D200F10050A0F51040D0F8003829 +:10174000184670470023FBE700F10050A0F5104059 +:10175000D0F8100A70470000064991F8243033B1E0 +:101760000023086A81F824300822FFF7B5BF012062 +:10177000704700BF444B0020014B1868704700BF02 +:10178000002004E070B5194B1D68194B0138C5F3F2 +:101790000B0408442D0C04221E88A6420BD15C6861 +:1017A0000A46013C824213460FD214F9016F4EB132 +:1017B00002F8016BF6E7013A03F10803ECD181422C +:1017C0000B4602D22C2203F8012B0A4A0524168864 +:1017D000AE4204D1984284BF967803F8016B013C75 +:1017E00002F10402F3D1581A70BD00BF002004E0DA +:1017F000746C0008606C0008022802D1044B9861E8 +:101800007047012802BF024B08229A61704700BF4F +:1018100000040240022804D1054B4FF400329A61C3 +:1018200070470128FCD1024B4FF40022F7E700BFBC +:1018300000040240022805D1064A536983F00203DE +:10184000536170470128FCD1024A536983F00803B1 +:10185000F6E700BF0004024070B504464FF47A7604 +:101860004CB1412C254628BF412506FB05F003F06D +:1018700087FA641BF4E770BD10B50023934203D0D0 +:10188000CC5CC4540133F9E710BD000010B5013839 +:1018900010F9013F3BB191F900409C4203D11AB1CC +:1018A0000131013AF4E71AB191F90020981A10BDFC +:1018B0001046FCE703460246D01A12F9011B002924 +:1018C000FAD1704702440346934202D003F8011B49 +:1018D000FAE770472DE9F8431F4D144695F8242088 +:1018E0000746884652BBDFF870909CB395F82430C9 +:1018F0002BB92022FF2148462F62FFF7E3FF95F81E +:101900002400C0F10802A24228BF2246D6B24146B6 +:10191000920005EB8000FFF7AFFF95F82430A41B81 +:101920001E44F6B2082E17449044E4B285F82460B1 +:10193000DBD1FFF711FF0028D7D108E02B6A03EBBA +:1019400082038342CFD0FFF707FF0028CBD10020CE +:10195000BDE8F8830120FBE7444B0020024B1A78D6 +:10196000024B1A70704700BF804B00201C230020E0 +:1019700038B5174C174D204602F058FD2946204631 +:1019800002F080FD2D686A6D936B23F4002393634E +:101990004FF47A70FFF760FF0F49284602F078FE97 +:1019A0006A6D0E4D936B28680D4943F400239363D1 +:1019B000A0424FF4E1330B6001D002F097FC68685D +:1019C000A04204D0BDE83840054902F08FBC38BDC4 +:1019D00070500020F86D0008006E000820230020E1 +:1019E0006C4B002070B50C4B0C4D1E780C4B55F811 +:1019F00026209A4204460DD00A4B00211422184694 +:101A0000FFF760FF0460014655F82600BDE870400E +:101A100002F06CBC70BD00BF804B00202023002072 +:101A2000705000206C4B00202DE9F0470D46044615 +:101A300000219046284640F27912FFF743FF2346E3 +:101A400020220021284601F0B9FE231D0222202178 +:101A5000284601F0B3FE631D03222221284601F02F +:101A6000ADFEA31D03222521284601F0A7FE04F1A7 +:101A7000080310222821284601F0A0FE04F11003DB +:101A800008223821284601F099FE04F111030822AA +:101A90004021284601F092FE04F112030822482159 +:101AA000284601F08BFE04F1140320225021284621 +:101AB00001F084FE04F1180340227021284601F051 +:101AC0007DFE04F120030822B021284601F076FEB5 +:101AD00004F121030822B821284601F06FFE04F129 +:101AE0002207C0263B46314608222846083601F028 +:101AF00065FEB6F5A07F07F10107F3D104F13203CB +:101B000008223146284601F059FE002704F1330A25 +:101B100094F832304FEAC7099F4209F5A47615D3ED +:101B2000B8F1000F08D1314604F599730722284611 +:101B300001F044FE09F24F16274694F832213B1B70 +:101B400093420CD3F01DC008BDE8F0870AEB0703F1 +:101B500008223146284601F031FE0137D8E707F266 +:101B6000331331460822284601F028FE0836013793 +:101B7000E3E7000013B50446084600210160234650 +:101B8000C0F803102022019001F018FE0198231DD7 +:101B90000222202101F012FE0198631D032222215E +:101BA00001F00CFE0198A31D0322252101F006FE81 +:101BB000019804F108031022282101F0FFFD0720FD +:101BC00002B010BDF7B50023047F00910E46072236 +:101BD0001946054601F0B6FC731C00930122002350 +:101BE0000721284601F0AEFCC4B9B31C00930522BE +:101BF00023460821284601F0A5FC0D243746B2787B +:101C0000BB1B934211D32B7FA88A0734E408BBB9CE +:101C1000844294BF0020012003B0F0BDAB8ADB00FA +:101C2000083BDB08B3700824E8E7FB1C009321465F +:101C300000230822284601F085FC08340137DEE73E +:101C4000201A18BF0120E7E7F7B50023047F0091B1 +:101C50000E4608221946054601F074FC731CC4B9EF +:101C60000822009311462346284601F06BFC1024FD +:101C7000012372785F1C013B934211D32B7FA88A0A +:101C80000734E408BBB9844294BF0020012003B0AC +:101C9000F0BDAB8ADB00083BDB0873700824E7E784 +:101CA000F3190093214600230822284601F04AFC3C +:101CB00008343B46DDE7201A18BF0120E7E70000A3 +:101CC000F8B50E4605461446002181223046FFF73E +:101CD000F9FD2B4608220021304601F06FFD7CB94A +:101CE0006B1C07220821304601F068FD0F240123F8 +:101CF0006A785F1C013B934204D3E01DC008F8BD25 +:101D00000824F4E7EB1921460822304601F056FD7D +:101D100008343B46ECE70000F8B50E46054614468D +:101D20000021CE223046FFF7CDFD2B462822002190 +:101D3000304601F043FD7CB905F108030822282153 +:101D4000304601F03BFD30242F462A7A7B1B93421C +:101D500004D3E01DC008F8BD2824F5E707F1090306 +:101D600021460822304601F029FD08340137ECE70E +:101D7000F7B5047F00910E4601231022002105468D +:101D800001F0E0FBC4B9B31C0093092223461021E3 +:101D9000284601F0D7FB192437467288BB1B9A42AC +:101DA00011D82B7FA88A0734E408BBB9844294BFBA +:101DB0000020012003B0F0BDAB8ADB00103BDB0844 +:101DC00073801024E8E73B1D00932146002308227E +:101DD000284601F0B7FB08340137DEE7201A18BFA8 +:101DE0000120E7E730B5094D0A4491420DD011F8C2 +:101DF000013B5840082340F30004013B2C4013F002 +:101E0000FF0384EA5000F6D1EFE730BD2083B8ED40 +:101E1000F7B54FF0FF33DFF854C0DFF854E000EBC4 +:101E200081011A4688421CD050F8044B019401AF3E +:101E3000042417F8015B82EA05620825DB181646C0 +:101E400005F1FF355241002EBCBF83EA0C0382EA44 +:101E50000E0215F0FF05F1D1013C14F0FF04E8D1AA +:101E6000E0E7D843D14303B0F0BD00BF9336EAA901 +:101E7000EBE1F042F7B5384A106851686B4603C38E +:101E80006A4636493648082304F056FE04460028C0 +:101E900033D10A25334A106851686B4603C36A463A +:101EA00031492F48082304F047FE0446002849D052 +:101EB0000369B3F5F81F45D8B0F8661040F27A52BE +:101EC00091423FD1294A024402F15C018B4239D34D +:101ED0005C3B234900209E1AFFF784FF32460746E9 +:101EE00004F164010020FFF77DFFA3689F4229D120 +:101EF000E368984208BF002524E00369B3F5F81FA2 +:101F000027D8418B40F27A52914220D1174A02449D +:101F100002F110018B4218D3103B114900209D1A89 +:101F2000FFF760FF2A46064604F118010020FFF77C +:101F300059FFA3689E4202D1E368984201D00D2563 +:101F4000A8E70025284603B0F0BD1025A2E70C2520 +:101F5000A0E70B259EE700BF946C0008DCFF1E0085 +:101F6000000001089D6C000890FF1E000800FFF7AC +:101F700010B5037C044613B9006804F0C5FD204683 +:101F800010BD00000023BFF35B8FC360BFF35B8F06 +:101F9000BFF35B8F8360BFF35B8F7047BFF35B8FD3 +:101FA0000068BFF35B8F704770B505460C30FFF7D4 +:101FB000F5FF05F1080604463046FFF7EFFFA042A3 +:101FC00006D930466D68FFF7E9FF2544281A70BD31 +:101FD0003046FFF7E3FF201AF9E7000070B5054629 +:101FE000406898B105F10800FFF7D8FF05F10C062D +:101FF00004463046FFF7D2FF8442304694BF6D68F6 +:102000000025FFF7CBFF013C2C44201A70BD0000D7 +:1020100038B50C460546FFF7C7FFA04210D305F1BF +:102020000800FFF7BBFF04446868B4FBF0F100FB55 +:102030001144BFF35B8F0120AC60BFF35B8F38BDF1 +:102040000020FCE72DE9F041144607460D46FFF756 +:10205000C5FF844228BF0446D4B1B84658F80C6B7B +:102060004046FFF79BFF3044286040467E68FFF7FC +:1020700095FF331A9C4203D86C600120BDE8F081C3 +:102080006B60A41B3B68AB602044E8600220F5E76E +:102090002046F3E738B50C460546FFF79FFFA04200 +:1020A00010D305F10C00FFF779FF04446868B4FB16 +:1020B000F0F100FB1144BFF35B8F0120EC60BFF334 +:1020C0005B8F38BD0020FCE72DE9FF41884669465B +:1020D0000746FFF7B7FF6C4606B204EBC6060025BD +:1020E000B44209D06268206808EB0501FFF7C4FB21 +:1020F000636808341D44F3E729463846FFF7CAFFF2 +:10210000284604B0BDE8F081F8B505460C300F460E +:10211000FFF744FF05F1080604463046FFF73EFF8F +:10212000A042304688BF6C68FFF738FF201A38603D +:1021300020B130462C68FFF731FF2044F8BD000085 +:1021400073B5144606460D46FFF72EFF844228BF9E +:1021500004460190DCB101A93046FFF7D5FF019B91 +:1021600033B93268C5E90233C5E9002401200CE027 +:102170009C4238BF01942860019868608442F5D978 +:102180003368AB60241AEC60022002B070BD2046B8 +:10219000FBE700002DE9FF410F466946FFF7D0FF3E +:1021A0006C4600B204EBC0050026AC4209D0D4F85E +:1021B000048054F8081BB8194246FFF75DFB4644FB +:1021C000F3E7304604B0BDE8F081000038B50546BD +:1021D000FFF7E0FF044601462846FFF719FF2046B7 +:1021E00038BD000010B4026854681A4623465DF8F2 +:1021F000044B1847002070470020704770470000CC +:10220000002070470E20704700F5805090F8C800FD +:10221000C0F340007047000000F5805090F9D000F6 +:102220007047000000F58050C0F8CC1001207047C6 +:10223000F7B50C68BDF8207014F0005470D10D7B18 +:10224000082D6DD8302585F311884569AE68760173 +:102250000CD4AC68240108D4AC6814F080545DD16F +:1022600084F31188204603B0F0BD01240E6804F108 +:10227000180C002EB8BFF6004FEA0C1CB4BF46F095 +:102280000406760545F80C600E680FFA84FC16F01B +:10229000804F18BF05EB0C1E05EB0C1C1EBFDEF8B3 +:1022A000806146F00206CEF880610E7BCCF8846136 +:1022B00005EB04158E68C5F88C614E68C5F8886119 +:1022C000DCF8805145F00105CCF8805100EB441654 +:1022D00041F268052E4405EB44150544C6E9002388 +:1022E00008350E4601F10C0C56F804EB45F804EBEA +:1022F0006645F9D1843436882E8000EB441407F00B +:102300000305267926F00B0635432571002484F356 +:102310001188009700F0FCFC0120A4E70224A5E747 +:102320004FF0FF309FE7000013B500F58054019196 +:10233000E06DFFF753FE1F280AD90199E06D2022B6 +:10234000FFF7C2FEA0F120035842584102B010BD71 +:102350000020FBE708B5302383F3118800F5805097 +:10236000C06DFFF70FFE002383F3118808BD000046 +:1023700000220260828142608260704710B50022B4 +:102380000023C0E900230023044603810C30FFF73B +:10239000EFFF204610BD0000F0B5054600F5805067 +:1023A0000C4690F8C83013F0040FC3F3800108BF47 +:1023B000114661F3820304F1840680F8C83005EB0E +:1023C000461389B01B79D8072ED57AB319072DD4B7 +:1023D0006846FFF7D3FF05EB441303F5835303F17E +:1023E000180703AA103318685968144603C4083341 +:1023F000BB422246F7D1186820609B88A380DDE9A4 +:102400000E23CDE900230123ADF808302B6869467F +:10241000DB6B2846984705EB46152B791A075CBFFE +:1024200043F008032B7101E0002AF4D109B0F0BD9C +:102430002DE9F0479A4688B00746884691463023F2 +:1024400083F3118807F580546846FFF797FFE06D26 +:10245000FFF7AAFD1F282AD9E06D20226946FFF761 +:10246000B5FE202823D103AD444605AB2E4603CE4E +:102470009E4220606160354604F10804F6D1306860 +:102480002060B388A380DDE90023C9E90023BDF8FB +:102490000830AAF80030002383F3118853464A46D7 +:1024A0004146384608B0BDE8F04700F01FBC0020A8 +:1024B00080F3118808B0BDE8F08700002DE9F84FDF +:1024C0000023C0E90133254B044640F8183B0F4672 +:1024D000FFF74EFF04F12800FFF750FF04F1480812 +:1024E00004F582554646083530462036FFF746FF4C +:1024F000AE42F9D104F580554FF480534FF00009F6 +:10250000C5E91339C5F848800123EE6504F58758FD +:1025100004F58456C5F8549085F8583085F8603035 +:10252000083608F108084FF0000A4FF0000B46E9A2 +:1025300008ABA6F11800FFF71BFF203646F8289CD1 +:102540004645F4D185F8D07017B1054800F0B8FBC6 +:10255000044B63612046BDE8F88F00BFD06C0008D3 +:10256000A86C00080064004010B5044B19780446BC +:102570004A1C1A70FFF7A2FF204610BD884B0020AE +:102580002DE9F047002950D0294B2A4FB7FBF1F530 +:1025900099428CBF0A231123581EB5FBF3FC03FBA1 +:1025A0001C53C4B22BB102280346F5D80020BDE865 +:1025B000F0870CF1FF36B6F5806FF7D2C4EBC40E8E +:1025C0000EF103034FEAE309C3F3C703A4EB0308C7 +:1025D00009F1010A4FF47A755FFA88F009FB055595 +:1025E0005AFA88F8B5FBF8F5B5F5617FC1BF0EF171 +:1025F000FF33C3F3C703E01AC0B25C1C50FA84F483 +:102600000CFB04F4B7FBF4F4A142CFD1013BDBB2E5 +:102610000F2BCBD80138C0B20728C7D800211071C2 +:1026200016809170D3700120C1E70846BFE700BF54 +:102630003F420F0080DE800270B505460E464FF423 +:102640007A746B695B6803F00103B34207D04FF4FF +:102650007A7002F095FB013CF3D1204670BD012059 +:10266000FCE7000030B54269936913F0700F16D093 +:1026700000230B4C936103F1840200EB42121179A9 +:102680004D0709D5890707D5416954F823508D6056 +:10269000117941F0040111710133032BEBD130BDED +:1026A000BC6C000873B51D46436916469A68D2078C +:1026B000044609D59A6801219960C2F34002CDE928 +:1026C00000650021FFF768FE63699A68D1050BD5A4 +:1026D0009A684FF480719960C2F34022CDE9006599 +:1026E00001212046FFF758FE63699A68D2030BD593 +:1026F0009A684FF480319960C2F34042CDE9006599 +:1027000002212046FFF748FE04F58053D3F8CC00A1 +:1027100010B103681B699847204602B0BDE87040BD +:10272000FFF7A0BFF8B504464669002972D106F14B +:102730000C073868800770D006EB01153868D5F8AB +:10274000B00110F0040FD5F8B0011ABFC00840F076 +:102750000040400DA061D5F8B0C11CF0020F1CBFB5 +:1027600040F08040A061D5F8B40106EB011100F003 +:102770000F0084F82400D1F8B8012077D1F8B8010F +:10278000000A6077D1F8B801000CA077D1F8B80141 +:10279000000EE077D1F8BC0184F82000D1F8BC012C +:1027A000000A84F82100D1F8BC01000C84F8220052 +:1027B000D1F8BC11090E84F823103821396004F1D6 +:1027C000340004F1180104F1240551F8046B40F8B9 +:1027D000046BA942F9D109880180C4E90A23214682 +:1027E0000023238651F8283B2046DB6B984704F5ED +:1027F000805393F8C820D3F8CC0042F0040283F849 +:10280000C82010B103681B6998472046BDE8F8400E +:10281000FFF728BF06F110078BE7F8BD10B5044697 +:1028200000F056FA02460B4652EA030102D0013A82 +:1028300063F100030449086820B12146BDE8104057 +:10284000FFF770BF10BD00BF844B0020F0B53021F2 +:1028500081F31188DFF848C000F583510831002466 +:1028600004F1840500EB45152E7977070ED4F606A2 +:102870000CD5D1E9007697429E4107D246695CF8B3 +:102880002470B7602E7946F004062E710134032CB3 +:1028900001F12001E4D1002383F31188F0BD00BFD2 +:1028A000BC6C000808B5302383F31188FFF7DAFE0B +:1028B000002383F3118808BDF8B54369054698687D +:1028C00000F0E050B0F1E05F0F4621D0F8B13023C6 +:1028D00083F3118805F583541034002606F1840330 +:1028E00005EB43131B791A0706D50136032E04F1B5 +:1028F0002004F3D1012007E05B07F6D421463846D7 +:1029000000F040FA0028F0D1002383F31188F8BDCD +:102910000120FCE708B5302383F3118800F58050CF +:10292000C06DFFF741FB002383F3118843090CBFFF +:102930000120002008BD0000F8B51D4600231370DB +:102940000F4606461446FFF7E5FF80F00100387099 +:1029500025B129463046FFF7AFFF2070F8BD0000D3 +:102960002DE9B8410C4615461F46804600F0B0F9E7 +:102970000B462178024609B9287850B14046FFF746 +:1029800065FFFFF78FFF3B462A462146FFF7D4FF3E +:102990000120BDE8B881000070B5302686F31188AB +:1029A000174B1A6C42F000721A641A6A42F00072F5 +:1029B0001A621A6A22F000721A62002383F31188E5 +:1029C00000F5805494F8C83013F0010516D1A9B170 +:1029D00086F311880321132001F0BCFA032114208F +:1029E00001F0B8FA0321152001F0B4FA94F8C830C8 +:1029F00043F0010384F8C83085F3118870BD00BF2F +:102A0000003802402DE9F04700F5805588B095F870 +:102A1000D030012B04468846164600F28180814F53 +:102A200057F823200AB947F82300D7F800A0C4F8C4 +:102A30000C802674BAF1000F64D095F8D030012BC9 +:102A400070D001212046FFF7A7FF302383F31188C0 +:102A50006269136823F0020313606269136843F02C +:102A600001031360636900275F6187F31188012107 +:102A70002046FFF7E1FD002800F09580E86DFFF7A4 +:102A800081FA04F58359BA4609F108092022002188 +:102A90006846FEF717FF02A8FFF76AFCCDF818A0FA +:102AA0006A4609EB07030DF1180E9446BCE80300D3 +:102AB000F44518605960624603F10803F5D1DCF86B +:102AC0000000186020379CF804201A71602FDDD1B7 +:102AD00095F8C8306FF38203002785F8C8306A463E +:102AE00041462046ADF80070ADF802708DF80470D4 +:102AF000FFF746FD636948BB4FF400421A6008B017 +:102B0000BDE8F08741F2D80003F0BEFF814610B166 +:102B10005146FFF7D3FCC7F80090B9F1000F8CD1F4 +:102B20000020ECE7386803681B6B984701460028D3 +:102B300087D13868FFF730FF3868036832465B6832 +:102B40004146984700287FF47CAFE9E761221A608C +:102B50009DF802309DF803201B06120402F4702237 +:102B600003F040731343BDF80020C2F3090213437E +:102B70009DF804201205022E02F4E0020CBF4FF073 +:102B800000410021134362690B43D361636913223F +:102B90005A616269136823F00103136039462046C5 +:102BA000FFF74AFD08B96369A6E795F8D03093BBF3 +:102BB0006169D1F8002242F00102C1F80022616986 +:102BC000D1F8002222F47C5222F00E02C1F8002239 +:102BD0006169D1F8002242F46062C1F800226269A2 +:102BE000C2F814326269C2F80432626941F6FF71B8 +:102BF000C2F80C126269C2F840326269C2F844320B +:102C000063690122C3F81C226269D2F8003223F002 +:102C10000103C2F8003295F8C83043F0020385F88A +:102C2000C8306CE7844B002008B500F051F850EA3A +:102C30000103024602D0421E61F10001044B1868F4 +:102C400010B10B46FFF72EFDBDE8084001F064B857 +:102C5000844B002008B50020FFF7E0FDBDE80840E8 +:102C600001F05AB808B50120FFF7D8FDBDE80840CB +:102C700001F052B800B59BB0EFF3098168226846B5 +:102C8000FEF7FAFDEFF30583014B9B6BFEE700BFF8 +:102C900000ED00E008B5FFF7EDFF000000B59BB0C8 +:102CA000EFF3098168226846FEF7E6FDEFF305833E +:102CB000014B5B6BFEE700BF00ED00E0FEE70000AC +:102CC0000FB408B5029802F001F8FEE702F08EBCDE +:102CD00002F070BC13B56C4684E80600031D94E84E +:102CE000030083E80500012002B010BD73B58568BC +:102CF000019155B11B885B0707D4D0E900369B6B67 +:102D00009847019AC1B23046A847012002B070BD71 +:102D1000F0B5866889B005460C465EB1BDF838301E +:102D20005B070AD4D0E900379B6B98472246C1B2B3 +:102D30003846B047012009B0F0BD00220023CDE99C +:102D400000230023ADF808300A4603AB01F1080662 +:102D5000106851681C4603C40832B2422346F7D1BA +:102D6000106820609288A280FFF7B2FF0423ADF8BC +:102D700008302B68CDE90001DB6B6946284698478F +:102D8000D8E7000030B503680968DD0FB5EBD17FE7 +:102D900023F0604421F060424FEAD1700BD0002B49 +:102DA000B8BFA40C0029B8BF920C944202D034BF23 +:102DB0000120002030BD944205D1C1F38070C3F3DF +:102DC00080738342F6D194422CBF00200120F1E7AA +:102DD0002DE9F041456A15B94162BDE8F0814B68C3 +:102DE00023F06047C3F38A464FEAD37EC3F380786B +:102DF00016EA230638BF3E46AC462B465A68BEEB61 +:102E0000D27F22F060440AD0002A18DAA40CB4421F +:102E100017D19D420FD10D60DEE71346EEE7A742C2 +:102E200007D102F08044C2F3807242450BD054B106 +:102E3000EFE708D2EDE7CCF800100B60CDE7B44225 +:102E400001D0B442E5D81A689C46002AE5D1196041 +:102E5000C3E700002DE9F047089D01F007044FEAA1 +:102E6000D508224405F0070500EBD1004FF47F4957 +:102E7000944201D1BDE8F08704F0070705F0070A86 +:102E800057453E4638BF5646C6F10806111B8E42CE +:102E900028BF0E46E10808EBD50E415C13F80EC0C2 +:102EA000B94029FA06F721FA0AF1FFB28CEA0101CA +:102EB00047FA0AF739408CEA010C03F80EC0344493 +:102EC0003544D5E780EA0120082341F2210201B20E +:102ED0004000002980B203F1FF33B8BF504013F027 +:102EE000FF03F4D17047000038B50C468D18A54299 +:102EF00000D138BD14F8011BFFF7E4FFF7E700002D +:102F000042684AB1136843604389818901339BB2A7 +:102F10009942438138BF83811046704770B588B0AD +:102F2000202204460D4668460021FEF7CBFC2046D1 +:102F30000495FFF7E5FF024658B16B46054608AE1B +:102F40001C4603CCB44228606960234605F108059D +:102F5000F6D1104608B070BD082817D909280CD042 +:102F60000A280CD00B280CD00C280CD00D280CD023 +:102F70000E2814BF4020302070470C2070471020CE +:102F800070471420704718207047202070470000B9 +:102F9000082817D90C280CD910280CD914280CD9BA +:102FA00018280CD920280CD930288CBF0F200E20CF +:102FB0007047092070470A2070470B2070470C208B +:102FC00070470D20704700002DE9F843078C072F4C +:102FD00004461ED9D0E9029800254FF6FF73C5F1CB +:102FE0002006A5F1200029FA05F108FA06F628FACC +:102FF00000F031430143C9B21846FFF763FF0835BB +:10300000402D0346EBD1E1693A46BDE8F843FFF7AE +:103010006BBF4FF6FF70BDE8F883000010B54B683A +:1030200023B9CA8A63F30902CA8210BD04691A6807 +:103030001C600361C38A013BC3824A60EFE7000062 +:103040002DE9F84F1D46CB8A0F46C3F30901052928 +:10305000814692460B4630D00020AAB207F11A04EE +:103060009EB2042E1FFA80F80FD8904503F1010399 +:1030700006D3FB8A0A4462F30903FB8201201AE0AB +:103080001AF80060E6540130EAE79045F1D2A1F168 +:10309000050B1C237C68BBFBF3F203FB12BB1FFA7E +:1030A0008BF6002C45D14846FFF72AFF044638B975 +:1030B00078606FF00200BDE8F88F4FF00008E6E797 +:1030C000002606607860ADB24FF0000B454510D980 +:1030D0000AEB0803221D13F8011B9155B1B208F148 +:1030E00001081B291FFA88F82BD0454506F1010677 +:1030F000F1D8FB8AC3F30902154465F30903BCE761 +:10310000013292B21C462368002BF9D16B1F0B448D +:103110001C21B3FBF1F301339BB29A42D3D2BBF132 +:10312000000FD0D14846FFF7EBFE20B9C4F800B03D +:10313000BFE70122E7E7C0F800B05E462060044622 +:10314000C1E74545D5D94846FFF7DAFE08B9206002 +:10315000AFE7C0F800B0002620600446B6E70000E4 +:103160002DE9F04F2DED028B1C4683B05B69019277 +:1031700007468846002B00F09A80238C2BB1E26929 +:10318000002A00F09480072B35D807F10C00FFF7D8 +:10319000B7FE054638B96FF00205284603B0BDEC0E +:1031A000028BBDE8F08F14220021FEF78BFB228CEE +:1031B000E16905F10800FEF75FFB208C013080B269 +:1031C000FFF7E6FEFFF7C8FE013880B22084013029 +:1031D00028746369228C1B782A4403F01F0363F070 +:1031E0003F0348F000411372384669602946FFF7F3 +:1031F000EFFD0125D1E700F10C034FF0000908EEC7 +:10320000103A4FF0800A4E464D4618EE100AFFF76E +:1032100077FE83460028BED014220021FEF752FB21 +:10322000002E3AD1019BABF8083002220BF1080EB8 +:103230001FFA82FC0CF10100BCF1060F218C80B258 +:1032400001D88E422BD3FFF7A3FEFFF785FE6269FC +:103250001278013802F01F028E4208BF4FF0400A78 +:1032600042EA49121BFA80F14AEA020A013048F0A8 +:10327000004281F808A08BF81000CBF804205946D2 +:103280003846FFF7A5FD238C0135B3422DB289F0F6 +:1032900001094FF0000AB8D17FE70022C6E7E169D3 +:1032A000895D0EF802100136B6B20132C0E76FF048 +:1032B000010572E7F8B515460E4630220021044696 +:1032C0001F46FEF7FFFA069B6360B5F5001F079BDC +:1032D000A76034BF6A094FF6FF72A36297B2E66136 +:1032E00004F1100000239A4206D800230360A7824D +:1032F000E3822383E360F8BD066001333046203665 +:10330000F1E7000003781BB94BB2002BC8BF017076 +:103310007047000000787047F8B50C46C969074649 +:1033200011B9238C002B37D1257E1F2D34D8387846 +:1033300028BB228C072A2CD8268A36F003032BD1EF +:103340004FF6FF70FFF7D0FD20F00100310240047E +:1033500041EA0561400C41EA40254FF6FF722346E1 +:1033600029463846FFF7FCFE002807DD626913781E +:103370000133DBB21F2B88BF00231370F8BD218AF5 +:103380002D0645EA012505432046FFF71DFE0246AE +:10339000E5E76FF00300F1E76FF00100EEE70000F2 +:1033A00070B58AB0044616460021282268461D469C +:1033B000FEF788FABDF83830ADF810300F9B059352 +:1033C0009DF840308DF81830119B07936946BDF881 +:1033D0004830ADF820302046CDE90265FFF79CFF6C +:1033E0000AB070BD2DE9F041D36905460C4616467A +:1033F0000BB9138C5BBB377E1F2F28D895F8008044 +:10340000B8F1000F26D03046FFF7DEFD33782102F9 +:1034100041EAC33141EA0801338A41EA076141EADE +:1034200003410246334641F080012846FFF798FEEB +:1034300000280ADD3378012B07D172691378013334 +:10344000DBB21F2B88BF00231370BDE8F0816FF043 +:103450000100FAE76FF00300F7E70000F0B58BB06A +:1034600004460D4617460021282268461E46FEF7F0 +:1034700029FA9DF84C305A1E534253418DF80030C2 +:103480009DF84030ADF81030119B05939DF8483001 +:103490008DF81830149B07936A46BDF85430ADF888 +:1034A000203029462046CDE90276FFF79BFF0BB07E +:1034B000F0BD0000406A00B104307047436A1A68EA +:1034C000426202691A600361C38A013BC38270478A +:1034D0002DE9F041D0F82080194E14461D46414692 +:1034E000002709B9BDE8F081D1E90223A21A65EBF2 +:1034F0000303964277EB03031ED2036A8B420DD17E +:10350000FFF78CFD036A1B68036203690B60C38AC3 +:103510000161016A013BC3828846E2E7FFF77EFD55 +:103520000B68C8F8003003690B60C38A0161013B76 +:10353000C382D8F80010D4E788460968D1E700BFF5 +:1035400080841E002DE9F04F8BB00D46DDF85090C1 +:1035500014469B468046002800F01981B9F1000FFF +:1035600000F01581531E3F2B00F21181012A03D177 +:10357000BBF1000F40F00B810023CDE90833B8F810 +:103580001430B5EBC30F4FEAC30703D300200BB0D1 +:10359000BDE8F08F2B199F42D8F80C303ABF7F1B43 +:1035A000FFB227461BB9D8F81030002B7AD0272D50 +:1035B0004ED8C5F12806B7424FF000032CBFF6B233 +:1035C0003E4600932946D8F8080008AB3246FFF77C +:1035D00041FCA7EB060A35445FFA8AFAB8F81430C2 +:1035E00003F10053053BDB000493D8F80C30039340 +:1035F0002821039B13B1BAF1000F2CD1D8F8100089 +:1036000040B1BAF1000F05D0009608AB5246691AD6 +:10361000FFF720FC38B2002FB8D066070AD00AABFB +:1036200003EBD401624211F8083C02F00702134197 +:1036300001F8083C082C3CD9102C40F2B580202C15 +:1036400040F2B780BBF1000F00F09C80082334E00B +:10365000BA460026C2E7049BE02B28BFE02306936E +:103660000B44AB42059314D95A1B0398009692451C +:1036700034BF5246D2B2691A08AB04300792FFF742 +:10368000E9FB079A1644AAEB020A1544F6B25FFA60 +:103690008AFA049B069A05999B1A0493039B1B685C +:1036A0000393A6E70093D8F8080008AB3A462946EA +:1036B000AEE7BBF1000F13D00123B4EBC30F6CD006 +:1036C000082C12D89DF82030621E23FA02F2D5078A +:1036D00006D54FF0FF3202FA04F423438DF8203070 +:1036E0009DF8203089F8003051E7102C12D8BDF831 +:1036F0002030621E23FA02F2D10706D54FF0FF32C6 +:1037000002FA04F42343ADF82030BDF82030A9F8C4 +:1037100000303CE7202C0FD80899631E21FA03F3F0 +:10372000DA0705D54FF0FF3202FA04F40C4308948F +:10373000089BC9F800302AE7402C2BD0DDE908654A +:10374000611EC4F12102A4F1210326FA01F105FA58 +:1037500002F225FA03F311431943CB0712D50122D4 +:10376000A4F12003C4F1200102FA03F322FA01F1CB +:10377000A240524243EA010363EB430332432B432B +:10378000CDE90823DDE90823C9E90023FFE66FF04E +:103790000100FCE66FF00800F9E6082CA0D9102C17 +:1037A000B3D9202CEED8C3E7BBF1000FADD0022374 +:1037B00083E7BBF1000FBBD004237EE730B5012ABD +:1037C000144638BF0124402C85B028BF4024002572 +:1037D000012ACDE9025518D81B788DF80830630707 +:1037E0000AD004AB03EBD405624215F8083C02F0A2 +:1037F0000702934005F8083C009103462246002149 +:1038000002A8FFF727FB05B030BD082AE4D9102A2B +:1038100003D81B88ADF80830E1E7202A8DBFD3E933 +:1038200000231B680293CDE90223D8E710B5CB68CB +:103830001BB98B600B618B8210BD04691A681C6018 +:103840000361C38A013BC382CA60F0E703064CBF31 +:10385000C0F3C0300220704708B50246FFF7F6FFFC +:10386000022806D15306C2F30F2001D100F0030055 +:1038700008BDC2F30740FBE72DE9F04F93B0CDE957 +:1038800003230A6804461046FFF7E0FF022814BF2E +:10389000C2F306260026002A0D46824680F2F281F7 +:1038A00012F0C04940F0EE81097B002900F0EA8166 +:1038B000022803D02378B34240F0E781C2F30463C7 +:1038C0000693104602F07F030593FFF7C5FF059BA3 +:1038D00029444FEA834848EA0A4848EA4668CE78CD +:1038E00000230022CDE90823F309834648EA0008B3 +:1038F000029367D0059B009302466768534608A968 +:103900002046B847002800F0C381276A4FB94146D6 +:1039100004F10C00FFF702FB074690B96FF00200BC +:1039200054E03B6998450DD03F68002FF9D14146DE +:1039300004F10C00FFF7F2FA07460028EED0236AE4 +:103940003B60276297F817C006F01F08CCF3840C81 +:10395000ACEB08001FFA80FE0028B8BF0EF1200073 +:10396000A8EB0C031FFA83FED7E90221B8BF00B20F +:10397000002B0793BEBF0EF120031BB2079352EA40 +:10398000010338D0039BDFF824E39A1A049B4FF01D +:10399000000C63EB010196457CEB01032BD36B7BA1 +:1039A00097F81AE0734519D1029B002B78D00128B3 +:1039B00021DC7868F8B9DFF8F0C2944570EB0103B8 +:1039C00016D337E0276A27B96FF00C0013B0BDE8B3 +:1039D000F08F3B699845B5D03F68F4E7B248904214 +:1039E0007CEB010301D30020F0E7029B002BFAD00F +:1039F000079B0F2B17DCFA7DB30002F0030203F0E4 +:103A00007C031343FB7539462046FFF707FB6B7BAE +:103A1000BB76029B3BB9FB7DC3F38402013262F3A8 +:103A20008603FB75D0E76A7BBB7E9A42DBD1029BA3 +:103A3000002B35D0B309022B32D0039BBB60049B13 +:103A4000FB60142200210DA8FDF73CFF039B0A93A5 +:103A5000049B0B932B1D0C932B7BADF83EB0013BCD +:103A6000DBB2ADF83C30069B8DF84230059B8DF8FB +:103A7000433094F82C308DF840A083F001038DF88A +:103A800044308DF84180A3680AA920469847FB7D01 +:103A9000C3F38403013303F01F039B02FB82A2E7FD +:103AA000FB7DC6F34012B2EBD31F40F0F480C3F3AA +:103AB0008403434540F0F280029A2B7BB609002A2A +:103AC0004DD0F2075DD4032B40F2EB80039BBB602B +:103AD000049BFB602B7BAE1D033BDBB232463946B9 +:103AE00004F10C00FFF7ACFA00280CDA3946204646 +:103AF000FFF794FAFB7DC3F38403013303F01F0344 +:103B00009B02FB820AE7DDE90884AB883B834FF622 +:103B1000FF73C9F12000A9F1200228FA09F104FA83 +:103B200000F0014324FA02F211431846C9B2FFF72C +:103B3000C9F909F10809B9F1400F0346E9D1B88282 +:103B40002A7B033AD2B23146FFF7CEF9FB7DB88229 +:103B5000DA43C2F3C01262F3C713FB7543E786B9B9 +:103B60002E1D013BDBB23246394604F10C00FFF753 +:103B700067FA0028BADB2A7BB88A013AD2B231460A +:103B8000E2E7F98AC1F30901013B0429DAB25BD803 +:103B9000281D002307F11B069A4208D910F801CB13 +:103BA00006F801C0013101330529DBB2F4D10399D4 +:103BB0000A9104990B91934207F11B010C9138BFB4 +:103BC000043379680D9134BF55FA83F300230E93C3 +:103BD000FB8AADF83EB0C3F309031A44069B8DF887 +:103BE0004230059B8DF8433094F82C30ADF83C20E2 +:103BF00083F001038DF8443000238DF840A08DF848 +:103C000041807B602A7BB88A013A291DFFF76CF955 +:103C10003B8BB882834203D1A3680AA92046984708 +:103C200020460AA9FFF702FEFB7DBA8AC3F384038C +:103C3000013303F01F039B02FB823B8B9A420CBFB4 +:103C400000206FF01000C1E67B68002BAFD005208C +:103C500001E01C3033461E68002EFAD1091A081DF7 +:103C60002E1D184401EB090CBCF11B0F5FFA89F300 +:103C70009DD89A429BD916F8013B00F8013B09F107 +:103C80000109EFE76FF00900A0E66FF00A009DE67A +:103C90006FF00B009AE66FF00D0097E66FF00E00E4 +:103CA00094E66FF00F0091E640420F0080841E0002 +:103CB000EFF3098305494A6B22F001024A63683336 +:103CC00083F30988002383F31188704700EF00E035 +:103CD000302080F3118862B60C4B0D4AD96821F46C +:103CE000E0610904090C0A43DA60D3F8FC200949B1 +:103CF00042F08072C3F8FC200A6842F001020A60B8 +:103D00002022DA7783F82200704700BF00ED00E040 +:103D10000003FA05001000E010B5302383F311888A +:103D20000E4B5B6813F4006314D0F1EE103AEFF31E +:103D30000984683C4FF08073E361094BDB6B2366B9 +:103D400084F3098800F08CFF10B1064BA36110BD0D +:103D5000054BFBE783F31188F9E700BF00ED00E0B6 +:103D600000EF00E03F0300084203000802684368D8 +:103D70001143016003B1184770470000024AD3683D +:103D800043F0C003D36070470044004010B5054CB9 +:103D9000054A0021204600F087FA044A044BC4E992 +:103DA000972310BD904B00207D3D0008004400404B +:103DB00080DE8002234A037C002918BF0A46012BBB +:103DC00030B5C0F868220CD11F4B984209D11F4B67 +:103DD000196C41F400311964196E41F4003119660F +:103DE0001B6EB2F904501468D0F86032D0F85C123F +:103DF000002D03EB5403B3FBF4F3BEBF23F0070520 +:103E000003F0070343EA450394888B60D38843F0AB +:103E100040030B61138943F001034B6144F40453E5 +:103E200043F02C03CB6004F4A05400230B60B4F5E2 +:103E3000806F0B684B680CBF7F23FF2380F86432D0 +:103E400030BD00BF106D0008904B002000380240CC +:103E50002DE9F041D0F85C62F7683368DA05044672 +:103E60009DB20DD5302383F311884FF48061043067 +:103E7000FFF77CFF6FF480733360002383F31188B6 +:103E8000302383F3118804F1040815F02F033AD18D +:103E900083F31188380615D5290613D5302383F30B +:103EA000118804F1380000F07BF900284EDA08216F +:103EB000201DFFF75BFF4FF67F733B40F36000234D +:103EC00083F311887A0616D56B0614D5302383F355 +:103ED0001188D4E913239A420AD1236C43B127F005 +:103EE00040073F041021201D3F0CFFF73FFFF76004 +:103EF000002383F31188D4F86822D36843B3BDE864 +:103F0000F041106918472B0714D015F0080F0CBFAB +:103F100000214FF48071E80748BF41F02001AA0753 +:103F200048BF41F040016B0748BF41F08001404667 +:103F3000FFF71CFFAD06736805D594F864122046A0 +:103F4000194000F0E1F93568ADB29EE77060B6E760 +:103F5000BDE8F08100F1604303F561430901C9B296 +:103F600083F80013012200F01F039A4043099B00CD +:103F700003F1604303F56143C3F880211A60704781 +:103F8000F8B5154682680669AA420B46816938BFB2 +:103F90008568761AB54204460BD218462A46FDF7C4 +:103FA0006BFCA3692B44A361A3685B1BA360284639 +:103FB000F8BD0CD918463246FDF75EFCAF1BE16830 +:103FC0003A463044FDF758FCE3683B44EBE71846BB +:103FD0002A46FDF751FCE368E5E700008368934259 +:103FE000F7B51546044638BF8568D0E90460361A2F +:103FF000B5420BD22A46FDF73FFC63692B4463614F +:10400000A36828465B1BA36003B0F0BD0DD9324600 +:104010000191FDF731FC0199E068AF1B3A4631444C +:10402000FDF72AFCE3683B44E9E72A46FDF724FC58 +:10403000E368E4E710B50A440024C361029B84608E +:10404000C0E90000C0E90511C1600261036210BD52 +:1040500008B5D0E90532934201D1826882B98268FD +:10406000013282605A1C42611970D0E904329A42CE +:1040700024BFC3684361002100F09EFE002008BDFC +:104080004FF0FF30FBE7000070B5302304460E46CA +:1040900083F31188A568A5B1A368A269013BA36059 +:1040A000531CA36115782269934224BFE368A3617E +:1040B000E3690BB120469847002383F31188284613 +:1040C00007E03146204600F067FE0028E2DA85F37B +:1040D000118870BD2DE9F74F04460E4617469846E5 +:1040E000D0F81C904FF0300A8AF311884FF0000B83 +:1040F000154665B12A4631462046FFF741FF034683 +:1041000060B94146204600F047FE0028F1D0002368 +:1041100083F31188781B03B0BDE8F08FB9F1000F6D +:1041200003D001902046C847019B8BF31188ED1AFC +:104130001E448AF31188DCE7C0E90511C160C36140 +:104140001144009B8260C0E9000001610362704776 +:10415000F8B504460D461646302383F31188A76848 +:10416000A7B1A368013BA36063695A1C62611D701B +:10417000D4E904329A4224BFE3686361E3690BB176 +:1041800020469847002080F3118807E031462046FA +:1041900000F002FE0028E2DA87F31188F8BD000083 +:1041A000D0E905239A4210B501D182687AB98268B4 +:1041B000013282605A1C82611C7803699A4224BFD2 +:1041C000C3688361002100F0F7FD204610BD4FF069 +:1041D000FF30FBE72DE9F74F04460E461746984699 +:1041E000D0F81C904FF0300A8AF311884FF0000B82 +:1041F000154665B12A4631462046FFF7EFFE0346D5 +:1042000060B94146204600F0C7FD0028F1D00023E8 +:1042100083F31188781B03B0BDE8F08FB9F1000F6C +:1042200003D001902046C847019B8BF31188ED1AFB +:104230001E448AF31188DCE7026843681143016079 +:1042400003B11847704700001430FFF743BF000068 +:104250004FF0FF331430FFF73DBF00003830FFF759 +:10426000B9BF00004FF0FF333830FFF7B3BF000095 +:104270001430FFF709BF00004FF0FF311430FFF793 +:1042800003BF00003830FFF763BF00004FF0FF327C +:104290003830FFF75DBF0000012914BF6FF0130035 +:1042A00000207047FFF772BD37B515460E4A026011 +:1042B00000224260C0E902220122044602740B4639 +:1042C000009000F15C014FF480721430FFF7B2FEF1 +:1042D00000942B464FF4807204F5AE7104F138005F +:1042E000FFF72AFF03B030BD246D000810B530235E +:1042F000044683F31188FFF75DFD02232374002039 +:1043000080F3118810BD000038B5C36904460D461E +:104310001BB904210844FFF78FFF294604F114005C +:10432000FFF796FE002806DA201D4FF40061BDE875 +:104330003840FFF781BF38BD026843681143016010 +:1043400003B118477047000013B5446BD4F8943498 +:104350001A681178042915D1217C022912D1197902 +:10436000128901238B4013420CD101A904F14C00A6 +:1043700001F0BCFFD4F89444019B217902462068E7 +:1043800000F0D0F902B010BD143001F03FBF0000C2 +:104390004FF0FF33143001F039BF00004C3002F011 +:1043A00011B800004FF0FF334C3002F00BB80000A2 +:1043B000143001F00DBF00004FF0FF31143001F058 +:1043C00007BF00004C3001F0DDBF00004FF0FF32AE +:1043D0004C3001F0D7BF00000020704710B5D0F876 +:1043E00094341A6811780429044617D1017C0229F3 +:1043F00014D15979528901238B4013420ED11430C4 +:1044000001F0A0FE024648B1D4F894444FF4807302 +:1044100061792068BDE8104000F072B910BD00005D +:10442000406BFFF7DBBF0000704700007FB5124B09 +:10443000036000234360C0E90233012502260F4BCD +:10444000057404460290019300F184022946009607 +:104450004FF48073143001F051FE094B0294CDE902 +:10446000006304F523724FF48073294604F14C0075 +:1044700001F018FF04B070BD4C6D00082144000825 +:10448000494300080B68302282F311880A7903EB54 +:10449000820290614A79093243F822008A7912B186 +:1044A00003EB820398610223C0F894140374002084 +:1044B00080F311887047000038B5037F044613B1BC +:1044C00090F85430ABB9201D01250221FFF734FFCD +:1044D00004F1140025776FF0010100F079FC84F8F5 +:1044E000545004F14C006FF00101BDE8384000F079 +:1044F0006FBC38BD10B5012104460430FFF71CFF26 +:104500000023237784F8543010BD000038B50446EA +:104510000025143001F00AFE04F14C00257701F06B +:10452000D9FE201D84F854500121FFF705FF2046D5 +:10453000BDE83840FFF752BF90F8443003F0600305 +:10454000202B07D190F84520212A4FF0000303D8F3 +:104550001F2A06D800207047222AFBD1C0E90E335B +:1045600003E0034A82630722C263036401207047A9 +:104570002823002037B5D0F894341A68117804291C +:1045800004461AD1017C022917D119791289012315 +:104590008B40134211D100F14C05284601F05AFF1F +:1045A00058B101A9284601F0A1FED4F89444019B1A +:1045B00021790246206800F0B5F803B030BD000054 +:1045C000F0B500EB810385B09E6904460D46FEB14F +:1045D000302383F3118804EB8507301D0821FFF792 +:1045E000ABFEFB685B691B6806F14C001BB10190D8 +:1045F00001F08AFE019803A901F078FE024648B155 +:10460000039B2946204600F08DF8002383F3118890 +:1046100005B0F0BDFB685A691268002AF5D01B8A04 +:10462000013B1340F1D104F14402EAE7093138B506 +:1046300050F82140DCB1302383F31188D4F894245E +:104640001368527903EB8203DB689B695D6845B1AF +:1046500004216018FFF770FE294604F1140001F0F0 +:104660007BFD2046FFF7BAFE002383F3118838BD97 +:104670007047000001F0F0B8012303700023C0E987 +:104680000133C36183620362C362436203637047A1 +:1046900038B50446302383F311880025C0E903555B +:1046A000C0E90555416001F0E7F80223237085F366 +:1046B0001188284638BD000070B500EB810305461F +:1046C0005069DA600E46144618B110220021FDF739 +:1046D000F9F8A06918B110220021FDF7F3F831466E +:1046E0002846BDE8704001F091B90000826802F0F0 +:1046F000011282600022C0E90422826101F012BA34 +:10470000F0B400EB81044789E4680125A4698D4079 +:104710003D43458123600023A2606360F0BC01F04B +:104720002DBA0000F0B400EB81040789E46801258C +:1047300064698D403D43058123600023A26063606E +:10474000F0BC01F0A7BA000070B5022300250446B2 +:104750000370C0E90255C0E90455C564856180F85D +:10476000345001F0EFF863681B6823B129462046F6 +:10477000BDE87040184770BD0378052B10B504469E +:104780000AD080F850300523037043681B680BB1D2 +:10479000042198470023A36010BD0000017805297B +:1047A00006D190F85020436802701B6803B1184787 +:1047B0007047000070B590F83430044613B1002300 +:1047C00080F8343004F14402204601F0CDF96368EA +:1047D0009B68B3B994F8443013F0600535D00021DC +:1047E000204601F06DFC0021204601F05FFC63686B +:1047F0001B6813B1062120469847062384F83430FD +:1048000070BD204698470028E4D0B4F84A30E26BE7 +:104810009A4288BFE36394F94430E56B002B4FF074 +:10482000300380F20381002D00F0F280092284F829 +:10483000342083F311880021D4E90E232046FFF7AA +:1048400071FF002383F31188DAE794F8452003F021 +:104850007F0343EA022340F20232934200F0C58014 +:1048600021D8B3F5807F48D00DD8012B3FD0022B43 +:1048700000F09380002BB2D104F14C02A26302221B +:10488000E2632364C1E7B3F5817F00F09B80B3F559 +:10489000407FA4D194F84630012BA0D1B4F84C301D +:1048A00043F0020332E0B3F5006F4DD017D8B3F5F3 +:1048B000A06F31D0A3F5C063012B90D8636894F842 +:1048C00046205E6894F84710B4F848302046B04758 +:1048D000002884D04368A3630368E3631AE0B3F558 +:1048E000106F36D040F6024293427FF478AF5C4BB3 +:1048F000A3630223E3630023C3E794F84630012B4C +:104900007FF46DAFB4F84C3023F00203C4E90E55C8 +:10491000A4F84C30256478E7B4F84430B3F5A06FC0 +:104920000ED194F8463084F84E30204601F062F8FB +:1049300063681B6813B10121204698470323237045 +:104940000023C4E90E339CE704F14F03A363012362 +:10495000C3E72378042B10D1302383F3118820463A +:10496000FFF7C4FE85F311880321636884F84F5074 +:1049700021701B680BB12046984794F84630002BF5 +:10498000DED084F84F300423237063681B68002B4B +:10499000D6D0022120469847D2E794F848301D0629 +:1049A00003F00F0120460AD501F0D0F8012804D009 +:1049B00002287FF414AF2B4B9AE72B4B98E701F0BA +:1049C000B7F8F3E794F84630002B7FF408AF94F87B +:1049D000483013F00F01B3D01A06204602D501F07B +:1049E00083FBADE701F076FBAAE794F84630002B95 +:1049F0007FF4F5AE94F8483013F00F01A0D01B06F9 +:104A0000204602D501F05CFB9AE701F04FFB97E7E7 +:104A1000142284F8342083F311882B462A46294631 +:104A20002046FFF76DFE85F31188E9E65DB115229A +:104A300084F8342083F311880021D4E90E23204622 +:104A4000FFF75EFEFDE60B2284F8342083F3118825 +:104A50002B462A4629462046FFF764FEE3E700BFBF +:104A60007C6D0008746D0008786D000838B590F80A +:104A700034300446002B3ED0063BDAB20F2A34D83D +:104A80000F2B32D8DFE803F03731310822323131D1 +:104A90003131313131313737C56BB0F84A309D4251 +:104AA00014D2C3681B8AB5FBF3F203FB12556DB930 +:104AB000302383F311882B462A462946FFF732FE1E +:104AC00085F311880A2384F834300EE0142384F827 +:104AD0003430302383F3118800231A4619462046C8 +:104AE000FFF70EFE002383F3118838BD036C03B17A +:104AF00098470023E7E70021204601F0E1FA002172 +:104B0000204601F0D3FA63681B6813B106212046E2 +:104B100098470623D7E7000010B590F83430142BDF +:104B2000044629D017D8062B05D001D81BB110BDDB +:104B3000093B022BFBD80021204601F0C1FA0021DD +:104B4000204601F0B3FA63681B6813B106212046C2 +:104B50009847062319E0152BE9D10B2380F8343050 +:104B6000302383F3118800231A461946FFF7DAFD34 +:104B7000002383F31188DAE7C3689B695B68002B25 +:104B8000D5D1036C03B19847002384F83430CEE7C5 +:104B900000230375826803691B6899689142FBD200 +:104BA0005A680360426010605860704700230375C4 +:104BB000826803691B6899689142FBD85A68036050 +:104BC000426010605860704708B50846302383F390 +:104BD00011880B7D032B05D0042B0DD02BB983F34B +:104BE000118808BD8B6900221A604FF0FF33836182 +:104BF000FFF7CEFF0023F2E7D1E9003213605A60DD +:104C0000F3E70000FFF7C4BF054BD96808751868C3 +:104C100002681A60536001220275D860FBF77ABB04 +:104C2000004E002030B50C4BDD684B1C87B00446AD +:104C30000FD02B46094A684600F05EF92046FFF780 +:104C4000E3FF009B13B1684600F060F9A86907B064 +:104C500030BDFFF7D9FFF9E7004E0020C94B00082F +:104C6000044B1A68DB6890689B68984294BF0020E8 +:104C700001207047004E0020084B10B51C68D86812 +:104C800022681A60536001222275DC60FFF78EFFF4 +:104C900001462046BDE81040FBF73CBB004E00201B +:104CA00038B5074C07490848012300252370656083 +:104CB00001F008FC0223237085F3118838BD00BF82 +:104CC00068500020846D0008004E002008B572B6C0 +:104CD000044B186500F050FC00F006FD024B032267 +:104CE0001A70FEE7004E00206850002000F044B922 +:104CF000034A516853685B1A9842FBD8704700BF5B +:104D0000001000E08B60022308618B820846704728 +:104D10008368A3F1840243F8142C026943F8442CFD +:104D2000426943F8402C094A43F8242CC26843F8EE +:104D3000182C022203F80C2C002203F80B2C044A36 +:104D400043F8102CA3F12000704700BF2D0300088A +:104D5000004E002008B5FFF7DBFFBDE80840FFF775 +:104D600051BF0000024BDB6898610F20FFF74CBF7A +:104D7000004E0020302383F31188FFF7F3BF0000BB +:104D800008B50146302383F311880820FFF74AFF56 +:104D9000002383F3118808BD064BDB6839B14268F4 +:104DA00018605A60136043600420FFF73BBF4FF068 +:104DB000FF307047004E00200368984206D01A6802 +:104DC0000260506099611846FFF71CBF70470000F1 +:104DD00038B504460D462068844200D138BD0368CA +:104DE00023605C608561FFF70DFFF4E710B5036891 +:104DF0009C68A2420CD85C688A600B604C602160A1 +:104E0000596099688A1A9A604FF0FF33836010BD29 +:104E10001B68121BECE700000A2938BF0A2170B595 +:104E200004460D460A26601901F046FB01F032FBEC +:104E3000041BA54203D8751C2E460446F3E70A2E30 +:104E400004D9BDE87040012001F07CBB70BD0000BA +:104E5000F8B5144B0D46D96103F1100141600A2ADF +:104E60001969826038BF0A22016048601861A81879 +:104E7000144601F013FB0A2701F00CFB431BA3426D +:104E8000064606D37C1C281901F016FB274635463A +:104E9000F2E70A2F04D9BDE8F840012001F052BB27 +:104EA000F8BD00BF004E0020F8B506460D4601F0E3 +:104EB000F1FA0F4A134653F8107F9F4206D12A4653 +:104EC00001463046BDE8F840FFF7C2BFD169BB6874 +:104ED000441A2C1928BF2C46A34202D92946FFF7B1 +:104EE0009BFF224631460348BDE8F840FFF77EBFEE +:104EF000004E0020104E002010B4C0E90323002310 +:104F00005DF8044B4361FFF7CFBF000010B5194CAB +:104F1000236998420DD0D0E90032816813605A604D +:104F20009A680A449A60002303604FF0FF33A3613C +:104F300010BD2346026843F8102F53600022026020 +:104F400022699A4203D1BDE8104001F0AFBA9368DC +:104F500081680B44936001F09DFA2269E1699268CF +:104F6000441AA242E4D91144BDE81040091AFFF7DF +:104F700053BF00BF004E00202DE9F047DFF8BC8092 +:104F800008F110072C4ED8F8105001F083FAD8F829 +:104F90001C40AA68031B9A423ED81444D5E900324B +:104FA0004FF00009C8F81C4013605A60C5F8009023 +:104FB000D8F81030B34201D101F078FA89F31188A2 +:104FC000D5E9033128469847302383F311886B696C +:104FD000002BD8D001F05EFA6A69A0EB04094A45BB +:104FE00082460DD2022001F0ADFA0022D8F810302E +:104FF000B34208D151462846BDE8F047FFF728BF25 +:10500000121A2244F2E712EB090938BF4A46294630 +:105010003846FFF7EBFEB5E7D8F81030B34208D0BA +:105020001444211AC8F81C00A960BDE8F047FFF736 +:10503000F3BEBDE8F08700BF104E0020004E0020F8 +:1050400038B501F027FA054AD2E90845031B1819BB +:1050500045F10001C2E9080138BD00BF004E002043 +:1050600000207047FEE70000704700004FF0FF305F +:105070007047000002290CD0032904D001290748F9 +:1050800018BF00207047032A05D8054800EBC2006E +:105090007047044870470020704700BF5C6E0008EE +:1050A00038230020106E000870B59AB005460846F7 +:1050B00001A9144600F0C2F801A8FCF7FBFB431C51 +:1050C0005B00C5E900340022237003236370C6B27D +:1050D00001AB02341046D1B28E4204F1020401D871 +:1050E0001AB070BD13F8011B04F8021C04F8010C7F +:1050F0000132F0E708B5302383F311880348FFF746 +:1051000039FA002383F3118808BD00BF70500020D6 +:1051100090F8443003F01F02012A07D190F845208F +:105120000B2A03D10023C0E90E3315E003F060031E +:10513000202B08D1B0F848302BB990F84520212A0F +:1051400003D81F2A04D8FFF7F7B9222AEBD0FAE7D1 +:10515000034A82630722C26303640120704700BFD1 +:105160002F23002007B5052917D8DFE801F019160D +:1051700003191920302383F31188104A019001216B +:10518000FFF79AFA01980E4A0221FFF795FA0D48A7 +:10519000FFF7BCF9002383F3118803B05DF804FB2B +:1051A000302383F311880748FFF786F9F2E73023AD +:1051B00083F311880348FFF79DF9EBE7B06D000812 +:1051C000D46D00087050002038B50C4D0C4C0D49C2 +:1051D0002A4604F10800FFF767FF05F1CA0204F14F +:1051E00010000949FFF760FF05F5CA7204F11800C5 +:1051F0000649BDE83840FFF757BF00BF38550020CB +:1052000038230020906D00089A6D0008A56D0008F5 +:1052100070B5044608460D46FCF74CFBC6B2204666 +:10522000013403780BB9184670BD32462946FCF7A5 +:105230002DFB0028F3D10120F6E700002DE9F0470F +:1052400005460C46FCF736FB2C49C6B22846FFF74C +:10525000DFFF08B10836F6B229492846FFF7D8FF24 +:1052600008B11036F6B2632E0BD8DFF89080DFF865 +:105270009090244FDFF898A02E7846B92670BDE8AC +:10528000F08729462046BDE8F04701F0BBBC252E3B +:1052900030D1072241462846FCF7F8FA80B91A4B6C +:1052A000224603F10C0153F8040B42F8040B8B4225 +:1052B000F9D119889B781180937007350F34DBE79B +:1052C000082249462846FCF7E1FA98B90F4BA21C80 +:1052D000197809090232C95D02F8041C13F8011B90 +:1052E00001F00F015345C95D02F8031CF0D11834D9 +:1052F0000835C1E704F8016B0135BDE77C6E000895 +:10530000A56D0008846E0008226C0008107AFF1F4B +:105310001C7AFF1FBFF34F8F024AD368DB03FCD414 +:10532000704700BF003C024008B5094B1B7873B9B9 +:10533000FFF7F0FF074B1A69002ABFBF064A5A6001 +:1053400002F188325A601A6822F480621A6008BD3D +:1053500096570020003C02402301674508B50B4BDF +:105360001B7893B9FFF7D6FF094B1A6942F0004248 +:105370001A611A6842F480521A601A6822F4805244 +:105380001A601A6842F480621A6008BD96570020BD +:10539000003C02401728F0B516D80C4C0C49237875 +:1053A0007BB90C4D0E4618234FF0006255F8047B74 +:1053B00046F8042B013B13F0FF033A44F6D10123D6 +:1053C000237051F82000F0BD0020FCE7F8570020C2 +:1053D00098570020986E0008014B53F82000704742 +:1053E000986E000818207047172810B5044601D998 +:1053F000002010BDFFF7CEFF064B53F824301844B1 +:10540000C21A0BB90120F4E712680132F0D1043B53 +:10541000F6E700BF986E0008172838B5044628D86C +:105420001549FFF777FFFFF77FFFF323CB600C23CE +:10543000B0FBF3F203FB1205D30143EAC503DBB271 +:1054400043F4007343F002030B610B6943F48033B0 +:105450000B61FFF75FFFFFF79DFF084B53F8241028 +:1054600000F03EF9FFF77AFF2046BDE83840FFF72D +:10547000BBBF002038BD00BF003C0240986E000852 +:10548000F8B512F00103144642D18218B2F1026F4E +:1054900057D82D4B1B6813F0010352D02B4DFFF74B +:1054A00043FFF323EB60FFF735FF40F20127032CA6 +:1054B00015D824F001046618244C401A40F2011754 +:1054C000B142236900EB010524D123F001032361DC +:1054D000FFF744FF0120F8BD043C0430E7E78307F1 +:1054E000E7D12B6923F440732B612B693B432B617C +:1054F00051F8046B0660BFF34F8FFFF70BFF036893 +:105500009E42E9D02B6923F001032B61FFF726FFB0 +:105510000020E0E723F44073236123693B432361C8 +:105520000B882B80BFF34F8FFFF7F4FE2D8831F8E7 +:10553000023BADB2AB42C3D0236923F00103236128 +:10554000E4E71846C7E700BF00380240003C0240CD +:10555000084908B50B7828B11BB9FFF7E5FE012310 +:105560000B7008BD002BFCD0BDE808400870FFF7A9 +:10557000F5BE00BF9657002008B50649064800F062 +:10558000B1F8BDE808404FF480314FF0805000F092 +:10559000A9B800BF00FF0200000100200846114624 +:1055A00001F094BA012001F091BA0000084601F020 +:1055B000ABBA000038B5EFF311859DB9EFF3058460 +:1055C000C4F30804302334B183F31188FFF738FDA6 +:1055D00085F3118838BD83F31188FFF731FD84F31B +:1055E000118838BDBDE83840FFF72ABD38B5FFF750 +:1055F000E1FF114C114AC00840EA4170A0FB025E75 +:10560000C908A0FB040C1CEB050CA1FB04404FF0E7 +:1056100000035B41A1FB02121CEB040C43EB0000F6 +:1056200011EB0E0142F10002411842F1000009099C +:1056300041EA007038BD00BFCFF753E3A59BC420FB +:1056400010B50244064BD2B2904200D110BD441CAA +:1056500000B253F8200041F8040BE0B2F4E700BFB9 +:10566000502800400F4B30B51C6F240407D41C6F2A +:1056700044F400741C671C6F44F400441C670A4C1B +:10568000236843F4807323600244084BD2B29042F3 +:1056900000D130BD441C00B251F8045B43F82050E7 +:1056A000E0B2F4E7003802400070004050280040AB +:1056B00007B5012201A90020FFF7C2FF019803B03E +:1056C0005DF804FB13B50446FFF7F2FFA04205D0D6 +:1056D000012201A900200194FFF7C4FF02B010BD10 +:1056E000704700007047000070470000094B5A885F +:1056F000B2F5805F10460BD022F0020341F20102A6 +:10570000934205D041F20703C31A584258417047EB +:1057100001207047002004E0074B45F255521A6003 +:1057200002225A6040F6FF729A604CF6CC421A6030 +:10573000024B01221A7070470030004000580020D0 +:10574000034B1B781BB1034B4AF6AA221A60704721 +:105750000058002000300040034B1A681AB9034A71 +:10576000D2F874281A607047FC57002000300240BD +:10577000024B4FF08072C3F874287047003002402B +:1057800008B5FFF7E9FF024B1868C0F3407008BD89 +:10579000FC57002008B5FFF7DFFF024B1868C0F385 +:1057A000007008BDFC57002070470000FEE70000B5 +:1057B0000A4B0B480B4A90420BD30B4BDA1C121AC4 +:1057C000C11E22F003028B4238BF00220021FCF7E9 +:1057D00079B853F8041B40F8041BECE7EC700008A0 +:1057E00004590020045900200459002070B5D0E964 +:1057F00015439E6800224FF0FF3504EB4213510120 +:10580000D3F800090028BEBFD3F8000940F080405B +:10581000C3F80009D3F8000B0028BEBFD3F8000B73 +:1058200040F08040C3F8000B013263189642C3F881 +:105830000859C3F8085BE0D24FF00113C4F81C38D4 +:1058400070BD0000890141F02001016103699B06E0 +:10585000FCD41220FFF74CBA10B5054C2046FEF7D9 +:105860000BFF4FF0A0436365024BA36510BD00BF63 +:10587000045800201C6F000870B50378012B054602 +:1058800050D12A4B446D98421BD1294B5A6B42F0A0 +:1058900080025A635A6D42F080025A655A6D5A6905 +:1058A00042F080025A615A6922F080025A610E2148 +:1058B00043205B69FEF74EFB1E4BE3601E4BC4F8B2 +:1058C00000380023C4F8003EC02323606E6D4FF4FF +:1058D0005023A3633369002BFCDA012333610C20CE +:1058E000FFF706FA3369DB07FCD41220FFF700FA52 +:1058F0003369002BFCDA0026A6602846FFF776FF06 +:105900006B68C4F81068DB68C4F81468C4F81C68D5 +:105910004BB90A4BA3614FF0FF336361A36843F0B7 +:105920000103A36070BD064BF4E700BF04580020DC +:10593000003802404014004003002002003C30C008 +:10594000083C30C0F8B5446D054600212046FFF7FD +:1059500079FFA96D00234FF001128F68C4F8343825 +:105960004FF00066C4F81C284FF0FF3004EB4312E0 +:1059700001339F42C2F80069C2F8006BC2F80809FF +:10598000C2F8080BF2D20B686A6DEB6563621023F4 +:105990001361166916F01006FBD11220FFF7A8F963 +:1059A000D4F8003823F4FE63C4F80038A36943F444 +:1059B000402343F01003A3610923C4F81038C4F84E +:1059C00014380A4BEB604FF0C043C4F8103B084B4F +:1059D000C4F8003BC4F81069C4F80039EB6D03F15A +:1059E000100243F48013EA65A362F8BDF86E000864 +:1059F00040800010426D90F84E10D2F8003823F429 +:105A0000FE6343EA0113C2F8003870472DE9F843FA +:105A100000EB8103456DDA68166806F00306731E15 +:105A2000022B05EB41130C4680460FFA81F94FEA31 +:105A300041104FF00001C3F8101B4FF0010104F1B9 +:105A4000100398BFB60401FA03F391698EBF334E79 +:105A500006F1805606F5004600293AD0578A04F12F +:105A60005801490137436F50D5F81C180B43C5F84E +:105A70001C382B180021C3F8101953690127611E27 +:105A8000A7409BB3138A928B9B08012A88BF53437C +:105A9000D8F85C20981842EA034301F1400205EB74 +:105AA0008202C8F85C00214653602846FFF7CAFE10 +:105AB00008EB8900C3681B8A43EA845348346401B5 +:105AC0001E432E51D5F81C381F43C5F81C78BDE87D +:105AD000F88305EB4917D7F8001B21F40041C7F8FC +:105AE000001BD5F81C1821EA0303C0E704F13F03AB +:105AF00005EB83030A4A5A6028462146FFF7A2FEB7 +:105B000005EB4910D0F8003923F40043C0F8003900 +:105B1000D5F81C3823EA0707D7E700BF008000103C +:105B200000040002826D1268C265FFF75FBE0000CC +:105B30005831436D49015B5813F4004004D013F40D +:105B4000001F0CBF02200120704700004831436D48 +:105B500049015B5813F4004004D013F4001F0CBF3C +:105B6000022001207047000000EB8101CB68196A18 +:105B70000B6813604B6853607047000000EB8103B3 +:105B800030B5DD68AA691368D36019B9402B84BFAA +:105B9000402313606B8A1468426D1C44013CB4FBC3 +:105BA000F3F46343033323F0030302EB411043EAAE +:105BB000C44343F0C043C0F8103B2B6803F0030319 +:105BC000012B09B20ED1D2F8083802EB411013F4C0 +:105BD000807FD0F8003B14BF43F0805343F0005364 +:105BE000C0F8003B02EB4112D2F8003B43F0044303 +:105BF000C2F8003B30BD00002DE9F041244D6E6D30 +:105C000006EB40130446D3F8087BC3F8087B38073B +:105C10000AD5D6F81438190706D505EB84032146B2 +:105C2000DB6828465B689847FA071FD5D6F8143812 +:105C3000DB071BD505EB8403D968CCB98B69488A8F +:105C40005A68B2FBF0F600FB16228AB91868DA68C7 +:105C500090420DD2121AC3E90024302383F3118835 +:105C60000B482146FFF78AFF84F31188BDE8F081D5 +:105C7000012303FA04F26B8923EA02036B81CB68E8 +:105C8000002BF3D021460248BDE8F041184700BF81 +:105C90000458002000EB810370B5DD68436D6C692A +:105CA0002668E6604A0156BB1A444FF40020C2F849 +:105CB00010092A6802F00302012A0AB20ED1D3F8B1 +:105CC000080803EB421410F4807FD4F8000914BFD5 +:105CD00040F0805040F00050C4F8000903EB42123D +:105CE000D2F8000940F00440C2F80009D3F83408A3 +:105CF000012202FA01F10143C3F8341870BD19B949 +:105D0000402E84BF4020206020682E8A8419013CE8 +:105D1000B4FBF6F440EAC44040F000501A44C6E731 +:105D20002DE9F8433B4D6E6D06EB40130446D3F866 +:105D30000889C3F8088918F0010F4FEA40171AD0F4 +:105D4000D6F81038DB0716D505EB8003D9684B6908 +:105D50001868DA68904230D2121A4FF000091A60BF +:105D6000C3F80490302383F3118821462846FFF7B7 +:105D700091FF89F3118818F0800F1CD0D6F83438C1 +:105D80000126A640334216D005EB84036D6DD3F88F +:105D90000CC0DCF814200134E4B2D2F800E005EBCA +:105DA00004342F445168714515D3D5F8343823EAAB +:105DB0000606C5F83468BDE8F883012303FA04F247 +:105DC0002B8923EA02032B818B68002BD3D0214639 +:105DD00028469847CFE7BCF81000AEEB010383429A +:105DE00028BF0346D7F8180980B2B3EB800FE2D87A +:105DF0009068A0F1040959F8048FC4F80080A0EB62 +:105E000009089844B8F1040FF5D818440B44906081 +:105E10005360C7E7045800202DE9F74FA24C656D89 +:105E20006E69AB691E4016F480586E6107D020463B +:105E3000FEF78AFC03B0BDE8F04FFDF76DBF002E02 +:105E400012DAD5F8003E98489B071EBFD5F8003EF1 +:105E500023F00303C5F8003ED5F8043823F001030E +:105E6000C5F80438FEF79AFC370505D58E48FFF7CC +:105E7000BDFC8D48FEF780FCB0040CD5D5F8083881 +:105E800013F0060FEB6823F470530CBF43F4105368 +:105E900043F4A053EB6031071BD56368DB681BB983 +:105EA000AB6923F00803AB612378052B0CD1D5F83F +:105EB000003E7D489A071EBFD5F8003E23F003033D +:105EC000C5F8003EFEF76AFC6368DB680BB17648F4 +:105ED0009847F30274D4B70227D5D4F85490DFF86A +:105EE000C8B100274FF0010A09EB4712D2F8003B76 +:105EF00003F44023B3F5802F11D1D2F8003B002BDF +:105F00000DDA62890AFA07F322EA0303638104EBDC +:105F10008703DB68DB6813B1394658469847A36DA1 +:105F200001379B68FFB29F42DED9F00617D5676D37 +:105F30003A6AC2F30A1002F00F0302F4F012B2F54B +:105F4000802F00F08580B2F5402F08D104EB830349 +:105F50000022DB681B6A07F5805790426AD1300344 +:105F6000D5F8184813D5E10302D50020FFF744FE09 +:105F7000A20302D50120FFF73FFE630302D50220F2 +:105F8000FFF73AFE270302D50320FFF735FE75031E +:105F90007FF550AFE00702D50020FFF7C1FEA10753 +:105FA00002D50120FFF7BCFE620702D50220FFF7F1 +:105FB000B7FE23077FF53EAF0320FFF7B1FE39E7B9 +:105FC000636DDFF8E4A0019300274FF00109A36D92 +:105FD0009B685FFA87FB9B453FF67DAF019B03EB18 +:105FE0004B13D3F8001901F44021B1F5802F1FD1D4 +:105FF000D3F8001900291BDAD3F8001941F09041B9 +:10600000C3F80019D3F800190029FBDB5946606D6D +:10601000FFF718FC218909FA0BF321EA0303238116 +:1060200004EB8B03DB689B6813B1594650469847D5 +:106030000137CCE7910708BFD7F80080072A98BF3F +:1060400003F8018B02F1010298BF4FEA182884E798 +:10605000023304EB830207F580575268D2F818C068 +:10606000DCF80820DCE9001CA1EB0C0C00218842C4 +:106070000AD104EB830463689B699A6802449A60BE +:106080005A6802445A606AE711F0030F08BFD7F854 +:1060900000808C4588BF02F8018B01F1010188BFA7 +:1060A0004FEA1828E3E700BF04580020436D03EBD4 +:1060B0004111D1F8003B43F40013C1F8003B704795 +:1060C000436D03EB4111D1F8003943F40013C1F8DB +:1060D00000397047436D03EB4111D1F8003B23F4C5 +:1060E0000013C1F8003B7047436D03EB4111D1F839 +:1060F000003923F40013C1F80039704730B5039C10 +:106100000172043304FB0325C0E90653049B0363B7 +:106110000021059BC160C0E90000C0E90422C0E97C +:106120000842C0E90A11436330BD0000416A002201 +:10613000C0E90411C0E90A22C2606FF00101FEF754 +:1061400047BE0000D0E90432934201D1C2680AB9C7 +:10615000181D70470020704703691960C26801323A +:10616000C260C269134482690361934224BF436AD7 +:1061700003610021FEF720BE38B504460D46E368F2 +:106180003BB16269131D1268A3621344E3620020ED +:1061900007E0237A33B929462046FEF7FDFD0028A3 +:1061A000EDDA38BD6FF00100FBE70000C368C2699B +:1061B000013BC3604369134482694361934224BF36 +:1061C000436A436100238362036B03B1184770473E +:1061D00070B53023044683F31188866A3EB9FFF711 +:1061E000CBFF054618B186F31188284670BDA36A17 +:1061F000E26A13F8015BA362934202D32046FFF7E1 +:10620000D5FF002383F31188EFE700002DE9F84F55 +:1062100004460E46174698464FF0300989F3118818 +:106220000025AA46D4F828B0BBF1000F09D1414699 +:106230002046FFF7A1FF20B18BF311882846BDE867 +:10624000F88FD4E90A12A7EB050B521A934528BF21 +:106250009346BBF1400F1BD9334601F1400251F880 +:10626000040B43F8040B9142F9D1A36A4033403642 +:10627000A3624035D4E90A239A4202D32046FFF7AD +:1062800095FF8AF31188BD42D8D289F31188C9E7F6 +:1062900030465A46FBF7F0FAA36A5B445E44A362B9 +:1062A0005D44E7E710B5029C0172043303FB04214F +:1062B000C0E906130023C0E90A33039B0363049B70 +:1062C000C460C0E90000C0E90422C0E90842436399 +:1062D00010BD0000026AC260426AC0E904220022C6 +:1062E000C0E90A226FF00101FEF772BDD0E9042374 +:1062F0009A4201D1C26822B9184650F8043B0B609B +:10630000704700231846FAE7C368C2690133C360C7 +:106310004369134482694361934224BF436A4361E2 +:106320000021FEF749BD000038B504460D46E3687C +:106330003BB123691A1DA262E2691344E3620020A3 +:1063400007E0237A33B929462046FEF725FD0028C9 +:10635000EDDA38BD6FF00100FBE70000036919605A +:10636000C268013AC260C269134482690361934200 +:1063700024BF436A036100238362036B03B11847A0 +:106380007047000070B530230D460446114683F374 +:106390001188866A2EB9FFF7C7FF10B186F31188FE +:1063A00070BDA36A1D70A36AE26A01339342A362BF +:1063B00004D3E16920460439FFF7D0FF002080F3C1 +:1063C0001188EDE72DE9F84F04460D4690469946B1 +:1063D0004FF0300A8AF311880026B346A76A4FB9F6 +:1063E00049462046FFF7A0FF20B187F311883046C9 +:1063F000BDE8F88FD4E90A073A1AA8EB06079742D6 +:1064000028BF1746402F1BD905F1400355F8042B30 +:1064100040F8042B9D42F9D1A36A4033A362403671 +:10642000D4E90A239A4204D3E16920460439FFF7EC +:1064300095FF8BF311884645D9D28AF31188CDE7B1 +:1064400029463A46FBF718FAA36A3B443D44A36247 +:106450003E44E5E7D0E904239A4217D1C3689BB1D3 +:10646000836A8BB1043B9B1A0ED01360C368013B57 +:10647000C360C3691A44836902619A4224BF436AB4 +:106480000361002383620123184670470023FBE762 +:1064900000F0D2B84FF08043586A70474FF0804305 +:1064A000002258631A610222DA6070474FF080437D +:1064B0000022DA60704700004FF080435863704755 +:1064C000FEE7000070B51B4B01630025044686B053 +:1064D000586085620E46FDF7FBFB04F11003C4E92A +:1064E00004334FF0FF33C4E90635C4E90044A56026 +:1064F000E562FFF7CFFF2B460246C4E9082304F10B +:1065000034010D4A256580232046FEF7FBFB01235D +:10651000E0600A4A0375009272680192B268CDE9A0 +:106520000223074B6846CDE90435FEF713FC06B09D +:1065300070BD00BF68500020286F00082D6F000854 +:10654000C1640008024AD36A1843D062704700BF92 +:10655000004E00204B6843608B688360CB68C3604B +:106560000B6943614B6903628B6943620B6803608B +:106570007047000008B5264B26481A6940F2FF1103 +:106580000A431A611A6922F4FF7222F001021A61A9 +:106590001A691A6B0A431A631A6D0A431A651E4A6E +:1065A0001B6D1146FFF7D6FF02F11C0100F580605C +:1065B000FFF7D0FF02F1380100F58060FFF7CAFF56 +:1065C00002F1540100F58060FFF7C4FF02F1700191 +:1065D00000F58060FFF7BEFF02F18C0100F58060DE +:1065E000FFF7B8FF02F1A80100F58060FFF7B2FFE6 +:1065F00002F1C40100F58060FFF7ACFF02F1E00199 +:1066000000F58060FFF7A6FFBDE8084000F090B8F5 +:106610000038024000000240346F000808B500F066 +:106620000BFAFEF73DFBFFF797F8BDE80840FEF7D1 +:10663000CBBD0000704700000F4B1A6C42F0010206 +:106640001A641A6E42F001021A660C4A1B6E9368B5 +:1066500043F0010393604FF0804353229A624FF05E +:10666000FF32DA6200229A615A63DA605A600122CC +:106670005A611A60704700BF00380240002004E0F1 +:106680004FF0804208B51169D3680B40D9B2C943B5 +:106690009B07116107D5302383F31188FEF726FB92 +:1066A000002383F3118808BD1F4B1A696FEAC25299 +:1066B0006FEAD2521A611A69C2F308021A614FF0E6 +:1066C000FF301A695A69586100215A6959615A693B +:1066D0001A6A62F080521A621A6A02F080521A62D2 +:1066E0001A6A5A6A58625A6A59625A6A1A6C42F0AD +:1066F00080521A641A6E42F080521A661A6E0B4A61 +:10670000106840F480701060186F00F44070B0F5AD +:10671000007F1EBF4FF4803018671967536823F459 +:106720000073536000F060B9003802400070004010 +:10673000344B4FF080521A64334A4FF44041116099 +:106740001A6842F001021A601A689107FCD59A682B +:1067500022F003029A602B4B9A6812F00C02FBD1D4 +:10676000196801F0F90119609A601A6842F48032E0 +:106770001A601A689203FCD55A6F42F001025A67F8 +:10678000204B5A6F9007FCD5204A5A601A6842F095 +:1067900080721A601C4A53685904FCD5194B1A6858 +:1067A0009201FCD51A4A9A600322C3F88C20194B37 +:1067B0001A68194B9A42194B21D1194A1168194A82 +:1067C00091421CD140F205121A60144A136803F07A +:1067D0000F03052BFAD10B4B9A6842F002029A6024 +:1067E0009A6802F00C02082AFAD15A6C42F48042EC +:1067F0005A645A6E42F480425A665B6E704740F2A9 +:106800000572E1E70038024000700040185440076C +:1068100000948838002004E011640020003C02400D +:1068200000ED00E041C20F41074A08B5536903F08B +:106830000103536123B1054A13680BB150689847AF +:10684000BDE80840FDF768BA003C01407C580020D4 +:10685000074A08B5536903F00203536123B1054A9F +:1068600093680BB1D0689847BDE80840FDF754BA6B +:10687000003C01407C580020074A08B5536903F0EA +:106880000403536123B1054A13690BB1506998475A +:10689000BDE80840FDF740BA003C01407C580020AC +:1068A000074A08B5536903F00803536123B1054A49 +:1068B00093690BB1D0699847BDE80840FDF72CBA41 +:1068C000003C01407C580020074A08B5536903F09A +:1068D0001003536123B1054A136A0BB1506A9847FC +:1068E000BDE80840FDF718BA003C01407C58002084 +:1068F000164B10B55C6904F478725A61A30604D58E +:10690000134A936A0BB1D06A9847600604D5104ABF +:10691000136B0BB1506B9847210604D50C4A936B4F +:106920000BB1D06B9847E20504D5094A136C0BB143 +:10693000506C9847A30504D5054A936C0BB1D06CF5 +:106940009847BDE81040FDF7E7B900BF003C0140A3 +:106950007C580020194B10B55C6904F47C425A61E4 +:10696000620504D5164A136D0BB1506D9847230587 +:1069700004D5134A936D0BB1D06D9847E00404D54C +:106980000F4A136E0BB1506E9847A10404D50C4A00 +:10699000936E0BB1D06E9847620404D5084A136F0A +:1069A0000BB1506F9847230404D5054A936F0BB180 +:1069B000D06F9847BDE81040FDF7AEB9003C0140EC +:1069C0007C58002008B50348FDF742FABDE80840AE +:1069D000FDF7A2B9904B002008B5FFF751FEBDE8C6 +:1069E0000840FDF799B90000062108B50846FDF7F3 +:1069F000B1FA06210720FDF7ADFA06210820FDF7C0 +:106A0000A9FA06210920FDF7A5FA06210A20FDF7BB +:106A1000A1FA06211720FDF79DFA06212820FDF78F +:106A200099FA07211C20FDF795FABDE808400C21D2 +:106A30002620FDF78FBA000008B5FFF735FE00F0FD +:106A40000DF8FDF72FFCFDF715FEFDF7EDFCFFF748 +:106A5000F1FDBDE80840FFF71BBD00000023054A1B +:106A600019460133102BC2E9001102F10802F8D1D6 +:106A7000704700BF7C5800200B460146184600F0C6 +:106A80002DB8000000F040B8012838BF012010B533 +:106A90000446204600F030F830B900F007F808B995 +:106AA00000F00CF88047F4E710BD0000024B1868B6 +:106AB000BFF35B8F704700BFFC58002008B506206D +:106AC00000F084F80120FEF7CDFA0000024B0A46E0 +:106AD00001461868FEF762BD5823002010B5054C2A +:106AE00013462CB10A4601460220AFF3008010BDC8 +:106AF0002046FCE700000000024B01461868FEF744 +:106B000051BD00BF58230020024B01461868FEF714 +:106B10004DBD00BF5823002010B5013902449042FA +:106B200001D1002005E0037811F8014FA34201D004 +:106B3000181B10BD0130F2E72DE9F041A3B1C91ACD +:106B400017780144044603F1FF3C8C42204601D9EA +:106B5000002009E00578BD4204F10104F5D10CEBF9 +:106B60000405D618A54201D1BDE8F08115F8018DC4 +:106B700016F801EDF045F5D0E7E700001F2938B51C +:106B800004460D4604D9162303604FF0FF3038BD8C +:106B9000426C12B152F821304BB9204600F030F867 +:106BA0002A4601462046BDE8384000F017B8012BC0 +:106BB0000AD0591C03D1162303600120E7E7002403 +:106BC00042F82540284698470020E0E7024B01465E +:106BD0001868FFF7D3BF00BF5823002038B5074D12 +:106BE00000230446084611462B60FEF73FFA431C7B +:106BF00002D12B6803B1236038BD00BF00590020CB +:106C0000FEF72EBA034611F8012B03F8012B002AD8 +:106C1000F9D170476F72672E6172647570696C6F1D +:106C2000742E50697872616365722D706572697037 +:106C30006800000053544D3332463F3F3F005354E9 +:106C40004D3332463430780053544D33324634326B +:106C5000780053544D3332463434365858000000CF +:106C6000012033000010410001105A0003105900A8 +:106C70000710310000000000346C0008130400000D +:106C80003E6C000819040000486C00082104000054 +:106C9000526C000840A2E4F1646891060041A3E54B +:106CA000F2656992070000004261642043414E4949 +:106CB0006661636520696E6465782E00800000005F +:106CC00000800000000080000000000000000000C4 +:106CD000E5210008052A000861290008252200088E +:106CE0003122000831240008F5210008052200089F +:106CF000F921000801220008FD21000855230008A1 +:106D000009220008D52C00081922000829230008B0 +:106D100000960000000000000000000000000000DD +:106D20000000000000000000654200085142000819 +:106D30008D4200087942000885420008714200082F +:106D40005D42000849420008994200080000000026 +:106D5000A543000891430008CD430008B94300084B +:106D6000C5430008B14300089D430008894300085B +:106D7000D9430008000000000100000000000000EE +:106D800063300000806D0008584E002068500020DD +:106D90004172647550696C6F740025424F415244D2 +:106DA000252D424C002553455249414C25000000F9 +:106DB0000200000000000000C14500082D46000848 +:106DC0004000400008550020185500200200000037 +:106DD00000000000030000000000000071460008F1 +:106DE00000000000100000002855002000000000F6 +:106DF0000100000000000000045800200101020012 +:106E0000655100087550000811510008F550000840 +:106E100043000000186E000809024300020100C090 +:106E200032090400000102020100052400100105DE +:106E30002401000104240202052406000107058242 +:106E4000030800FF09040100020A00000007050111 +:106E5000024000000705810240000000120000000F +:106E6000646E00081201100102000040091241572F +:106E700000020102030100000403090425424F41FE +:106E800052442500303132333435363738394142B7 +:106E90004344454600000000004000000040000060 +:106EA000004000000040000000000100000002005F +:106EB00000000200000002000000020000000200CA +:106EC000000002000000020000400000004000003E +:106ED000004000000040000000000100000002002F +:106EE000000002000000020000000200000002009A +:106EF000000002000000020000000000B54700088A +:106F00006D4A0008194B00084000400064580020FA +:106F10006458002001000000745800208000000028 +:106F200040010000030000006D61696E0069646C3F +:106F3000650000000000802A00000000AAAAAAAA9A +:106F400000000024FFFF00000000000000A00A0075 +:106F50004400000000000000AAAAAAAA0000000045 +:106F6000FFFF0000000000000000000010000040D3 +:106F700000000000AAAAAAAA10000040FFFF00001B +:106F800000000000000000000A681000000000007F +:106F9000AAAAAAAA00541000FFFF000099007007D7 +:106FA000000000000000004000000000AAAAAAAAF9 +:106FB00000000040FFFF0000000000000000000093 +:106FC0000000000000000000AAAAAAAA0000000019 +:106FD000FFFF0000000000000000000000000000B3 +:106FE00000000000AAAAAAAA00000000FFFF0000FB +:106FF0000000000000000000000000000000000091 +:107000000A00000000000000030000000000000073 +:107010000000000000000000000000000000000070 +:107020000000000000000000000000000000000060 +:107030007A0500000000000000001F0000000000B2 +:1070400040420F00FE2A0100D2040000FF000000B1 +:1070500070500020904B00200096000000000800B7 +:10706000960000000008000004000000786E000890 +:107070000000000000000000000000000000000010 +:1070800000000000000000005C2300200000000061 +:1070900000000000000000000000000000000000F0 +:1070A00000000000000000000000000000000000E0 +:1070B00000000000000000000000000000000000D0 +:1070C00000000000000000000000000000000000C0 +:1070D00000000000000000000000000000000000B0 +:0C70E000000000000000000000000000A4 :00000001FF diff --git a/Tools/bootloaders/Sierra-L431_bl.bin b/Tools/bootloaders/Sierra-L431_bl.bin index 64dfe430f880fb..46646b7e038f70 100755 Binary files a/Tools/bootloaders/Sierra-L431_bl.bin and b/Tools/bootloaders/Sierra-L431_bl.bin differ diff --git a/Tools/bootloaders/Sierra-PrecisionPoint_bl.bin b/Tools/bootloaders/Sierra-PrecisionPoint_bl.bin old mode 100644 new mode 100755 index fe14c80e861bcb..bdefa4b06a1be6 Binary files a/Tools/bootloaders/Sierra-PrecisionPoint_bl.bin and b/Tools/bootloaders/Sierra-PrecisionPoint_bl.bin differ diff --git a/Tools/bootloaders/Sierra-PrecisionPoint_bl.hex b/Tools/bootloaders/Sierra-PrecisionPoint_bl.hex index 11826b369e91be..c91ff23b4ba604 100644 --- a/Tools/bootloaders/Sierra-PrecisionPoint_bl.hex +++ b/Tools/bootloaders/Sierra-PrecisionPoint_bl.hex @@ -1,1851 +1,1801 @@ :020000040800F2 -:1000000000070020F5040008412F0008F92E000821 -:10001000212F0008F92E0008192F0008F704000806 -:10002000F7040008F7040008F7040008353F00084B -:10003000F7040008F7040008F7040008F7040008B4 -:10004000F7040008F7040008F7040008F7040008A4 -:10005000F7040008F7040008E56A00080D6B0008C3 -:10006000356B00085D6B0008856B0008F70400081D -:10007000F7040008F7040008F7040008F704000874 -:10008000F7040008F7040008F7040008AD2E000884 -:10009000D92E0008E92E0008F7040008AD6B00080F -:1000A000F7040008F7040008F7040008F704000844 -:1000B000956C0008F7040008F7040008F70400082E -:1000C000F7040008F7040008F7040008F704000824 -:1000D000F7040008816C0008F7040008F704000822 -:1000E000116C0008F7040008F7040008F704000882 -:1000F000F7040008F7040008F7040008F7040008F4 -:10010000F7040008F7040008F7040008F7040008E3 -:10011000F7040008F7040008F7040008F7040008D3 -:10012000F7040008F7040008F7040008F7040008C3 -:10013000F7040008F7040008F7040008F7040008B3 -:10014000F7040008F7040008F704000899600008A5 -:10015000F7040008F7040008F7040008F704000893 -:10016000F7040008F7040008F7040008F704000883 -:10017000F7040008F7040008F7040008F704000873 -:10018000F7040008F7040008F7040008F704000863 -:10019000F7040008F7040008F7040008F704000853 -:1001A000F7040008F7040008F7040008F704000843 -:1001B000F7040008F7040008F7040008F704000833 -:1001C000F7040008F7040008F7040008F704000823 -:1001D000F7040008F7040008F7040008F704000813 -:1001E0005D18000800000000000000000000000092 -:1001F00053B94AB9002908BF00281CBF4FF0FF318E -:100200004FF0FF3000F074B9ADF1080C6DE904CE89 -:1002100000F006F8DDF804E0DDE9022304B07047E1 -:100220002DE9F047089D04468E46002B4DD18A42A9 -:10023000944669D9B2FA82F252B101FA02F3C2F1DC -:10024000200120FA01F10CFA02FC41EA030E94406D -:100250004FEA1C48210CBEFBF8F61FFA8CF708FB8E -:1002600016E341EA034306FB07F199420AD91CEB66 -:10027000030306F1FF3080F01F81994240F21C8198 -:10028000023E63445B1AA4B2B3FBF8F008FB1033E0 -:1002900044EA034400FB07F7A7420AD91CEB040415 -:1002A00000F1FF3380F00A81A74240F207816444E5 -:1002B000023840EA0640E41B00261DB1D44000236A -:1002C000C5E900433146BDE8F0878B4209D9002DCE -:1002D00000F0EF800026C5E9000130463146BDE858 -:1002E000F087B3FA83F6002E4AD18B4202D38242C2 -:1002F00000F2F980841A61EB030301209E46002D71 -:10030000E0D0C5E9004EDDE702B9FFDEB2FA82F2C5 -:10031000002A40F09280A1EB0C014FEA1C471FFA23 -:100320008CFE0126200CB1FBF7F307FB131140EA0A -:1003300001410EFB03F0884208D91CEB010103F1D7 -:10034000FF3802D2884200F2CB804346091AA4B299 -:10035000B1FBF7F007FB101144EA01440EFB00FE6D -:10036000A64508D91CEB040400F1FF3102D2A645D2 -:1003700000F2BB800846A4EB0E0440EA03409CE771 -:10038000C6F12007B34022FA07FC4CEA030C20FA1E -:1003900007F401FA06F31C43F9404FEA1C4900FA3E -:1003A00006F3B1FBF9F8200C1FFA8CFE09FB1811BB -:1003B00040EA014108FB0EF0884202FA06F20BD92E -:1003C0001CEB010108F1FF3A80F08880884240F27E -:1003D0008580A8F102086144091AA4B2B1FBF9F0C2 -:1003E00009FB101144EA014100FB0EFE8E4508D9BD -:1003F0001CEB010100F1FF346CD28E456AD9023842 -:10040000614440EA0840A0FB0294A1EB0E01A14226 -:10041000C846A64656D353D05DB1B3EB080261EB94 -:100420000E0101FA07F722FA06F3F1401F43C5E96E -:10043000007100263146BDE8F087C2F12003D840A4 -:100440000CFA02FC21FA03F3914001434FEA1C47E6 -:100450001FFA8CFEB3FBF7F007FB10360B0C43EAD8 -:10046000064300FB0EF69E4204FA02F408D91CEB88 -:10047000030300F1FF382FD29E422DD90238634486 -:100480009B1B89B2B3FBF7F607FB163341EA034126 -:1004900006FB0EF38B4208D91CEB010106F1FF3875 -:1004A00016D28B4214D9023E6144C91A46EA00466C -:1004B00038E72E46284605E70646E3E61846F8E6FE -:1004C0004B45A9D2B9EB020864EB0C0E0138A3E747 -:1004D0004646EAE7204694E74046D1E7D0467BE728 -:1004E000023B614432E7304609E76444023842E7A0 -:1004F000704700BF02E000F000F8FEE772B6374830 -:1005000080F30888364880F3098836483649086001 -:1005100040F20000CCF200004EF63471CEF2000141 -:100520000860BFF34F8FBFF36F8F40F20000C0F23F -:10053000F0004EF68851CEF200010860BFF34F8FF5 -:10054000BFF36F8F4FF00000E1EE100A4EF63C71E2 -:10055000CEF200010860062080F31488BFF36F8F8D -:1005600005F062FA06F05AF94FF055301F491B4A60 -:1005700091423CBF41F8040BFAE71D49184A9142E9 -:100580003CBF41F8040BFAE71A491B4A1B4B9A423D -:100590003EBF51F8040B42F8040BF8E7002018495D -:1005A000184A91423CBF41F8040BFAE705F040FAC3 -:1005B00006F082F9144C154DAC4203DA54F8041BD2 -:1005C0008847F9E700F042F8114C124DAC4203DACB -:1005D00054F8041B8847F9E705F028BA0007002003 -:1005E000002300200000000808ED00E000010020CA -:1005F00000070020C872000800230020BC23002050 -:10060000C0230020E0580020E0010008E4010008B9 -:10061000E4010008E40100082DE9F04F2DED108AF7 -:10062000C1F80CD0C3689D46BDEC108ABDE8F08FC0 -:10063000002383F311882846A047002004F00AFD18 -:10064000FEE704F063FC00DFFEE70000F8B501F010 -:1006500017F905F083F9074605F0D2F90546B8BB4E -:10066000204B9F4234D001339F4234D01E4B27F0A1 -:10067000FF029A4232D1F8B200F00EFF2E4642F24B -:10068000107400F00FFF08B10024264601F046FD6B -:1006900020B1032000F07CF80024264635B1134B2E -:1006A0009F4203D005F0A4F900242646002005F05F -:1006B0005FF90EB100F082F801F0AAFA00F05EFFD7 -:1006C00001F05AF9204600F0D5F800F077F8F9E784 -:1006D0002E460024D5E704460126D2E706464FF40D -:1006E0007A74CEE7010007B0000008B0263A09B0DE -:1006F00008B501F00DF9A0F120035842584108BD9A -:1007000007B541F21203022101A8ADF8043001F04F -:100710001DF903B05DF804FB38B5302383F311886D -:10072000174803680BB104F061FD164A1448002312 -:100730004FF47A7104F050FD002383F31188124CBA -:10074000236813B12368013B2360636813B16368B6 -:10075000013B63600D4D2B7833B963687BB9022090 -:1007600001F0D0F9322363602B78032B07D1636843 -:100770002BB9022001F0C6F94FF47A73636038BDDB -:10078000C023002019070008E0240020D8230020FF -:10079000084B187003280CD8DFE800F008050208A1 -:1007A000022001F0A5B9022001F098B9024B002205 -:1007B0005A607047D8230020E024002010B501F0D3 -:1007C000ADFC30B1244B03221A70244B00225A6036 -:1007D00010BD234B234A1C4619680131F8D004335D -:1007E0009342F9D16268204B9A42F1D91F4B9B6822 -:1007F00003F1006303F580339A42E9D205F0CCF8A7 -:1008000005F0DEF8002001F0D1F80220FFF7C0FF6C -:10081000174B1A6C00221A64196E1A66196E596CFD -:100820005A64596E5A665A6E1A6942F000521A6139 -:100830001A6922F000521A611B6972B64FF0E02368 -:100840003021C3F8084DD4E9003281F311889D4668 -:1008500083F308881047BBE7D8230020E02400205A -:100860000000010820000108FFFF0008002300200D -:10087000003802402DE9F04F93B0AC4B009020229D -:10088000FF210AA89D6801F06DF9A94A1378A3B960 -:10089000A848012103601170302383F31188036895 -:1008A0000BB104F0A3FCA44AA24800234FF47A71D0 -:1008B00004F092FC002383F31188009B13B19F4B3B -:1008C000009A1A609E4A009C1378032B1EBF0023D7 -:1008D00013709A4A4FF0000A18BF5360D346564629 -:1008E000D146012001F004F924B1944B1B68002B80 -:1008F00000F01582002001F00BF80390039B002B01 -:1009000001DA00F083FE039B002BEDDB012001F0F8 -:10091000E5F8039B213B162BE3D801A252F823F004 -:100920007D090008A5090008390A0008E308000845 -:10093000E3080008E3080008C30A0008930C000855 -:10094000AD0B00080F0C0008370C00085D0C000808 -:10095000E30800086F0C0008E3080008E10C000839 -:100960001D0A0008E3080008250D00088909000891 -:100970001D0A0008E30800080F0C00080220FFF71A -:10098000B7FE002840F0F581009B0221BAF1000F6C -:1009900008BF1C4605A841F21233ADF8143000F030 -:1009A000D5FF9EE74FF47A7000F0B2FF071EEBDB35 -:1009B0000220FFF79DFE0028E6D0013F052F00F240 -:1009C000DA81DFE807F0030A0D10133605230593DB -:1009D000042105A800F0BAFF17E054480421F9E704 -:1009E00058480421F6E758480421F3E74FF01C0863 -:1009F000404600F0DDFF08F104080590042105A839 -:100A000000F0A4FFB8F12C0FF2D1012000FA07F793 -:100A100047EA0B0B5FFA8BFB4FF0000901F0EEF891 -:100A200026B10BF00B030B2B08BF0024FFF768FE69 -:100A300057E746480421CDE7002EA5D00BF00B0365 -:100A40000B2BA1D10220FFF753FE074600289BD0B5 -:100A5000012000F0ABFF0220FFF79AFE00261FFAEC -:100A600086F8404600F0B2FF044690B100214046AF -:100A700000F0C4FF01360028F1D1BA46044641F225 -:100A80001213022105A8ADF814303E4600F05EFFB7 -:100A900027E70120FFF77CFE2546244B9B68AB42ED -:100AA00007D9284600F084FF013040F06781043503 -:100AB000F3E7234B00251D70204BBA465D603E4690 -:100AC000ACE7002E3FF460AF0BF00B030B2B7FF471 -:100AD0005BAF0220FFF75CFE322000F019FFB0F19F -:100AE0000008FFF651AF18F003077FF44DAF0F4A2F -:100AF000926808EB050393423FF646AFB8F5807F56 -:100B00003FF742AF124B0193B84523DD4FF47A70A3 -:100B100000F0FEFE0390039A002AFFF635AF019B1A -:100B2000039A03F8012B0137EDE700BF00230020F3 -:100B3000DC240020C023002019070008E024002046 -:100B4000D823002004230020082300200C230020A9 -:100B5000DC230020C820FFF7CBFD074600283FF428 -:100B600013AF1F2D11D8C5F1200242450AAB25F065 -:100B7000030028BF424683490192184400F0CCFF8D -:100B8000019A8048FF2100F0EDFF4FEAA8037D495C -:100B90000193C8F38702284600F0ECFF06460028C0 -:100BA0003FF46DAF019B05EB830537E70220FFF7AC -:100BB0009FFD00283FF4E8AE00F040FF00283FF41E -:100BC000E3AE0027B846704B9B68BB4218D91F2F75 -:100BD00011D80A9B01330ED027F0030312AA134445 -:100BE00053F8203C05934046042205A901F04EFA33 -:100BF00004378046E7E7384600F0DAFE0590F2E772 -:100C0000CDF81480042105A800F0A0FE06E700231B -:100C1000642104A8049300F08FFE00287FF4B4AE92 -:100C20000220FFF765FD00283FF4AEAE049800F007 -:100C3000EDFE0590E6E70023642104A8049300F08C -:100C40007BFE00287FF4A0AE0220FFF751FD0028B4 -:100C50003FF49AAE049800F0E9FEEAE70220FFF7BD -:100C600047FD00283FF490AE00F0F8FEE1E70220D7 -:100C7000FFF73EFD00283FF487AE05A9142000F0E1 -:100C8000F3FE04210746049004A800F05FFE3946F5 -:100C9000B9E7322000F03CFE071EFFF675AEBB0739 -:100CA0007FF472AE384A926807EB090393423FF62D -:100CB0006BAE0220FFF71CFD00283FF465AE27F065 -:100CC00003074F44B9453FF4A9AE484600F070FE13 -:100CD0000421059005A800F039FE09F10409F1E7A7 -:100CE0004FF47A70FFF704FD00283FF44DAE00F09A -:100CF000A5FE002844D00A9B01330BD008220AA984 -:100D0000002000F037FF00283AD02022FF210AA857 -:100D100000F028FFFFF7F4FC1C4804F0A1F913B021 -:100D2000BDE8F08F002E3FF42FAE0BF00B030B2B22 -:100D30007FF42AAE0023642105A8059300F0FCFD92 -:100D4000074600287FF420AE0220FFF7D1FC804642 -:100D500000283FF419AEFFF7D3FC41F2883004F0CD -:100D60007FF9059800F092FF464600F047FF3C46A9 -:100D7000B7E5064652E64FF0000905E6BA467EE6BC -:100D800037467CE6DC23002000230020A0860100FB -:100D9000094A136849F2690099B21B0C00FB013340 -:100DA0001360064B186844F2506182B2000C01FBDC -:100DB0000200186080B2704718230020142300201E -:100DC00010B500211022044600F0CCFE034B03CBEB -:100DD000206061601868A06010BD00BF107AFF1F1E -:100DE0002DE9F041ADF5507D0DF13C086EAC40F2BF -:100DF000751207460D4610A80021C8F8001000F033 -:100E0000B1FE4FF4C4720021204600F0ABFE02F0A8 -:100E10009FF8254B4FF47A72B0FBF2F0186093E81C -:100E20000700022384E807000DF5ED702382FFF729 -:100E3000C7FF44F204731D49238406A806F040F856 -:100E4000212384F832310DF2EB2206AB0DF1380C80 -:100E50001E4603CE664510605160334602F108021B -:100E6000F6D13378137041460122204600F030FF5E -:100E700000230393AB7E029305F11903019380B223 -:100E80000123CDE904800093E97E05A3D3E9002383 -:100E9000384602F025FC0DF5507DBDE8F08100BF1D -:100EA0009E6AC421818A46EEE8240020D06E0008A4 -:100EB0002DE9F0412C4C237ADAB080460D465BBB1D -:100EC00027A9284601F014F80746002842D19DF8CA -:100ED0009D60C82E3ED801464FF4A662204600F021 -:100EE00041FE4FF48073C4F8F8314FF40073C4F836 -:100EF0000C334FF44073C4F8203432460DF19E0198 -:100F000004F1090000F008FE26449DF89C30777239 -:100F100023720BB9EB7E23728122002106AC27A835 -:100F200000F020FE0122214627A801F01DF8002331 -:100F30000393AB7E029305F1190380B2019328233A -:100F4000CDE904400093E97E05A3D3E900234046A0 -:100F500002F0C6FB5AB0BDE8F08100BFAFF30080DD -:100F600026417272DF25D7B700460020F0B5254E26 -:100F70004FF48A7505FB0065F1B096F8D83085F816 -:100F8000DC300024D822214685F8E8403AA800F059 -:100F9000E9FD06F1090000F0DDFDD5F8E4308DF83B -:100FA000F000C2B206AF06F109010DF1F100CDE982 -:100FB0003A3400F0B1FD394601223AA801F000F8B8 -:100FC00080B2CDE9047008230127CDE9023706F18C -:100FD000D803019330230093317A0B4807A3D3E958 -:100FE000002302F07DFBA04206DD01F0B1FFC5F851 -:100FF000E000384671B0F0BD2046FBE778F6339F3D -:1010000093CACD8D00460020003500202DE9F04127 -:101010001D4D1E4E1E4F86B0284602F08DFB034626 -:1010200058B30024CDE90344ADF81440027B8DF899 -:10103000142099684068029403AA03C21B68DFF871 -:10104000548043F00043029301F084FF821941F180 -:101050000003009402A9384601F046FAA04205DDDB -:10106000284602F06DFB88F80040D5E798F800307C -:10107000072B05D8013388F8003006B0BDE8F081B1 -:10108000014802F05DFBF8E70035002040420F0008 -:1010900030350020354B002070B50D4614461E46F5 -:1010A00002F07AFA50B9022E10D1012C0ED112A3FF -:1010B000D3E90023C5E90023012007E0282C10D044 -:1010C00005D8012C09D0052C0FD0002070BD302C84 -:1010D000FBD10BA3D3E90023ECE70BA3D3E9002357 -:1010E000E8E70BA3D3E90023E4E70BA3D3E900234C -:1010F000E0E700BFAFF30080401DA12026812A0B4E -:1011000078F6339F93CACD8D9E6AC421818A46EEBC -:1011100026417272DF25D7B7F017304A39059E563F -:1011200038B505460E4C0021013500F067FCA4F8E7 -:101130002C55B4F82C0500F049FC78B1B4F82C0516 -:1011400000F054FC014648B9B4F82C0500F056FCF8 -:10115000B4F82C350133A4F82C35EAE738BD00BFCC -:101160000046002010B50A4B0A4A1A6003F5805366 -:1011700093F860203AB9DC6D2CB1204601F04CF8B0 -:10118000204605F0DDFDBDE81040034801F044B8FD -:1011900030350020906F0008784500202DE9F04F91 -:1011A0008FB000AF05460C4602F0F6F9002849D191 -:1011B000237E022B1BD1E38A012B18D101F0C8FE3C -:1011C0000646FFF7E5FD03464FF4C870DFF8C4821A -:1011D000B3FBF0F206F5167602FB103316FA83F332 -:1011E000C8F80030E37E33B9A34B00221A703C37B5 -:1011F000BD46BDE8F08F07F12401204600F036FE21 -:101200000028F4D107F11400FFF7DAFD97F8264023 -:1012100007F11401224607F1270005F0DBFD002845 -:10122000E2D10F2C08D8944B1C70D8F80030A3F5ED -:101230001673C8F80030DAE797F82410284602F051 -:10124000A3F9D4E7E38A282B2BD010D8012B23D085 -:10125000052BCCD1BFF34F8F8849894BCA6802F464 -:10126000E0621343CB60BFF34F8F00BFFDE7302B2D -:10127000BDD1844EE17E327A9142B8D1607E314652 -:10128000002291F8DC50854200F0A5800132042A4A -:1012900001F58A71F5D1AAE721462846FFF7A0FD9E -:1012A000A5E721462846FFF703FEA0E7B2F8EC5079 -:1012B0007B6005F103094FEA99094FEA8902D11DC4 -:1012C000C908A8EBC1039D46EB460021584600F033 -:1012D00049FC04F1EE012A463144584600F01CFC5A -:1012E0007B6813B9012000F061FB96F8D20000F092 -:1012F0006DFB044630B9307200F0A0FB204600F0D0 -:1013000055FBB1E0D6F8D4203AB996F8D200B6F839 -:101310002C25824201D8FFF703FFD6F8D4202A44B7 -:10132000944208D296F8D200B6F82C2501308242B9 -:1013300001D8FFF7F5FE70685FFA89F2594600F0B0 -:1013400019FC08B9C54679E0726896F8D2002A44BB -:101350007260D6F8D42005EB0209C6F8D49000F0EC -:1013600035FB814509D396F8D220D6F8D400013256 -:10137000001B86F8D220C6F8D400FF2D0FD8002419 -:10138000347200F05BFB204600F010FB00F0C6FE5C -:101390003D4B188108B9FFF711FAC54627E7BB682E -:1013A00096F8D9000AFB0362FB68D2F8E41082F8D1 -:1013B000E83001F58061C2F8E030C2F8E410FFF7D0 -:1013C000D5FDFFF723FE96F8D920013202F0030283 -:1013D00086F8D920B6E74FF48A7A0AFB02F505F1C0 -:1013E000EA013144204600F017FEF86000287FF43F -:1013F000FEAE3544012285F8E82001F0A9FDD5F8BC -:10140000E020D6ED007ADFED216A801A192838BF76 -:10141000192040F6B832904228BF1046B8EE677ADD -:1014200007EE900AF8EEE77A67EEA67ADFED186A23 -:10143000E7EE267AFCEEE77AC6ED007A96F8D93028 -:10144000BB60BA6873680AFB02F4321992F8E810BC -:1014500059B1D2F8E4108B42E8463FF427AF00219F -:1014600082F8E810C2F8E010C5467368064A9B0A85 -:1014700001331381BBE600BFF934002000ED00E02A -:101480000400FA0500460020E8240020CDCCCC3D25 -:101490006666663FFC340020014B1870704700BF41 -:1014A000F424002030B54FF000542B4B22689A42B0 -:1014B00085B007D004F0AEFA044620BB00242046D5 -:1014C00005B030BD254B627D25481A70237D03721F -:1014D0004FF48073C0F8F8314FF40073C0F80C3348 -:1014E00000254FF44073C0F820341E49C0F8E45082 -:1014F000C922093000F010FB2046E022294600F006 -:1015000031FB0124DBE7184A184D136C43F00073DC -:101510001364AA6D164B9A42D0D12B6E013B7E2BE1 -:10152000CCD8144A07CA01AB83E807001846032148 -:1015300000F0C2FD6B6D83424FF00003BED12A6DF7 -:101540008A4201BFAB65054B2A6E1A7003BF0A4B76 -:10155000EA6D1A601C46B2E79AAD44C5F424002037 -:1015600000460020160000200038024000660040BF -:101570005041A0B0586600401023002037B51A4DE6 -:1015800000F0CCFD02236B71184B288119681848B4 -:10159000012201F07BFB00230193164B16490093B7 -:1015A0001648174B4FF4805201F0C6FF154B1978BF -:1015B00011B1124801F0E8FF01F0CAFC0446FFF740 -:1015C000E7FB4FF4C873B0FBF3F202FB130304F51F -:1015D000167010FA83F00C4B186004F011FA08B181 -:1015E0000F232B8103B030BDE824002010230020FE -:1015F0003035002099100008F82400200035002024 -:101600009D110008F4240020FC3400202DE9F04F47 -:101610002DED028B0FF23829D9E90089834C93B064 -:101620000BAE9FED7E8BFFF7F1FC814FDFF828A218 -:1016300000230A93ADF834300B9373604FF0000B26 -:101640005B468DED008B01250DF11D0207A9384683 -:101650008DF81C508DF81DB001F0C8FA9DF81C30B3 -:10166000002B40F0A580204601F096FF064600289A -:1016700045D1704F01F06CFC3B6898423FD301F0BC -:1016800067FC8246FFF784FB4FF4C873B0FBF3F2AC -:1016900002FB13030AF5167010FA83F03860664FE8 -:1016A00097F800B0CBF1100ABBF1000F14BF33461E -:1016B0002B465FFA8AFA0EA88DF82830FFF780FBD8 -:1016C000BAF1060F28BF4FF0060A0EAB03EB0B0171 -:1016D00052460DF1290000F01FFA0AAB03931823BC -:1016E00002930AF10102554BD2B2CDE900530492A4 -:1016F00020464CA3D3E9002301F094FF3E7001F093 -:1017000027FC4F4A4F4D1368C31AB3F57A7F2ED387 -:10171000106001F01FFC02460B46204602F01AF84A -:10172000204601F039FF10B32B7A474E002B14BF2F -:1017300003230223737101F00BFC0EAF4FF47A7395 -:101740000122B0FBF3F039463060304600F066FB12 -:10175000182302933D4B019380B240F25513CDE91B -:101760000370009342464B46204601F05BFF2B7A04 -:1017700093B101F0EDFB002607464FF48A7A95F805 -:10178000D900304400F003000AFB005393F8E8202E -:1017900092B30136042EF2D1C82003F061FC2B7AFB -:1017A000002B7FF43DAF13B0BDEC028BBDE8F08F92 -:1017B000DAF8143083F48053CAF8143059461022F2 -:1017C0000EA800F0CFF90DF11E0308AA0AA93846A9 -:1017D00000F088FF96E803000FAB83E803009DF854 -:1017E00034308DF844300A9B0E930EA9DDE90823AE -:1017F000204602F083F921E7D3F8E02042B12B68BC -:10180000FA2B38BFFA23BA1A0533B2EB430FC0D311 -:10181000FFF7ACFB0028BCD1BEE700BF0000000012 -:1018200000000000401DA12026812A0B0035002069 -:1018300030350020FC340020F9340020F83400203A -:10184000304B002000460020E8240020344B0020CC -:10185000F1C6A7C1D068080F0004024008B50548CA -:1018600000F0DAFFBDE80840034A0449002005F013 -:1018700061BA00BF30350020844B0020651100089C -:10188000704700002DE9F84F4FF47A73DFF8588065 -:10189000DFF8589006460D4602FB03F7002498F93E -:1018A00000305A1C5FFA84FA01D0A34212D159F8D1 -:1018B000240003682A46D3F820B031463B46D84777 -:1018C000854207D1074B012083F800A0BDE8F88FBF -:1018D0000124E4E7002CFBD04FF4FA7003F0C0FBC6 -:1018E0000020F3E7784B00201C2300202023002059 -:1018F00070B504464FF47A76412C254628BF412521 -:1019000006FB05F003F0ACFB641BF5D170BD0000D5 -:1019100007B50023024601210DF107008DF80730BD -:10192000FFF7B0FF20B19DF8070003B05DF804FB9E -:101930004FF0FF30F9E700000A4608B50421FFF731 -:10194000A1FF80F00100C0B2404208BD30B4074B97 -:101950000A461978064B53F821402368DD69054B88 -:101960000146AC46204630BC604700BF784B0020A3 -:1019700020230020A086010070B503F091FE094EDF -:10198000094D3080002428683388834208D903F049 -:1019900081FE2B6804440133B4F5803F2B60F2D301 -:1019A00070BD00BF7A4B0020384B002003F028BFE9 -:1019B00000F1006000F580300068704700F10060C1 -:1019C000920000F5803003F0B1BE0000054B1A68AC -:1019D000054B1B889B1A834202D9104403F05ABE60 -:1019E00000207047384B00207A4B0020024B1B68C8 -:1019F000184403F057BE00BF384B0020024B1B6851 -:101A0000184403F067BE00BF384B002010F00303FA -:101A10000AD1B0F5047F05D200F10050A0F51040C6 -:101A2000D0F80038184670470023FBE700F100505B -:101A3000A0F51040D0F8100A70470000064991F850 -:101A4000243033B10023086A81F824300822FFF7DC -:101A5000B5BF0120704700BF3C4B0020014B186808 -:101A6000704700BF002004E070B5194B1D68194B8A -:101A70000138C5F30B0408442D0C04221E88A6422D -:101A80000BD15C680A46013C824213460FD214F91E -:101A9000016F4EB102F8016BF6E7013A03F108035A -:101AA000ECD181420B4602D22C2203F8012B0A4AC8 -:101AB00005241688AE4204D1984284BF967803F874 -:101AC000016B013C02F10402F3D1581A70BD00BF52 -:101AD000002004E0346F0008206F0008022802BFD5 -:101AE000024B4FF080529A61704700BF00040240E1 -:101AF000022802BF024B4FF480529A61704700BF28 -:101B000000040240022801BF024A536983F4805353 -:101B1000536170470004024010B50023934203D084 -:101B2000CC5CC4540133F9E710BD000010B5013896 -:101B300010F9013F3BB191F900409C4203D11AB129 -:101B40000131013AF4E71AB191F90020981A10BD59 -:101B50001046FCE703460246D01A12F9011B002981 -:101B6000FAD1704702440346934202D003F8011BA6 -:101B7000FAE770472DE9F8431F4D144695F82420E5 -:101B80000746884652BBDFF870909CB395F8243026 -:101B90002BB92022FF2148462F62FFF7E3FF95F87B -:101BA0002400C0F10802A24228BF2246D6B2414614 -:101BB000920005EB8000FFF7AFFF95F82430A41BDF -:101BC0001E44F6B2082E17449044E4B285F824600F -:101BD000DBD1FFF733FF0028D7D108E02B6A03EBF6 -:101BE00082038342CFD0FFF729FF0028CBD100200A -:101BF000BDE8F8830120FBE73C4B0020024B1A783C -:101C0000024B1A70704700BF784B00201C23002045 -:101C100038B5194C194D204602F04AFD2946204698 -:101C200002F072FD2D68EA6ED2F8043843F0020328 -:101C3000C2F804384FF47A70FFF75AFE104928466C -:101C400002F06AFEEA6E0F4DD2F8043828680E4999 -:101C500023F00203C2F80438A0424FF461430B6042 -:101C600001D002F085FC6868A04204D0BDE838408D -:101C7000054902F07DBC38BD68500020CC700008DA -:101C8000D470000820230020644B002070B50C4B5A -:101C90000C4D1E780C4B55F826209A4204460DD068 -:101CA0000A4B002114221846FFF75CFF046001462E -:101CB00055F82600BDE8704002F05ABC70BD00BF68 -:101CC000784B00202023002068500020644B002027 -:101CD0002DE9F0470D46044600219046284640F283 -:101CE0007912FFF73FFF234620220021284601F00A -:101CF000A7FE231D02222021284601F0A1FE631D1C -:101D000003222221284601F09BFEA31D0322252148 -:101D1000284601F095FE04F10803102228212846E8 -:101D200001F08EFE04F1100308223821284601F04C -:101D300087FE04F1110308224021284601F080FEAD -:101D400004F1120308224821284601F079FE04F12B -:101D5000140320225021284601F072FE04F11803DA -:101D600040227021284601F06BFE04F12003082276 -:101D7000B021284601F064FE04F121030822B821B5 -:101D8000284601F05DFE04F12207C0263B4631469D -:101D900008222846083601F053FEB6F5A07F07F169 -:101DA0000107F3D104F1320308223146284601F03D -:101DB00047FE002704F1330A94F832304FEAC7098E -:101DC0009F4209F5A47615D3B8F1000F08D131462A -:101DD00004F599730722284601F032FE09F24F16E6 -:101DE000274694F832213B1B93420CD3F01DC008C8 -:101DF000BDE8F0870AEB070308223146284601F0C8 -:101E00001FFE0137D8E707F2331331460822284670 -:101E100001F016FE08360137E3E7000013B504466B -:101E20000846002101602346C0F8031020220190DB -:101E300001F006FE0198231D0222202101F000FE80 -:101E40000198631D0322222101F0FAFD0198A31DD0 -:101E50000322252101F0F4FD019804F1080310226A -:101E6000282101F0EDFD072002B010BDF7B50023D9 -:101E7000047F00910E4607221946054601F0A4FC96 -:101E8000731C0093012200230721284601F09CFCCB -:101E9000C4B9B31C0093052223460821284601F04B -:101EA00093FC0D243746B278BB1B934211D32B7F92 -:101EB000A88A0734E408BBB9844294BF00200120FB -:101EC00003B0F0BDAB8ADB00083BDB08B37008242D -:101ED000E8E7FB1C0093214600230822284601F076 -:101EE00073FC08340137DEE7201A18BF0120E7E74A -:101EF000F7B50023047F00910E46082219460546D7 -:101F000001F062FC731CC4B90822009311462346F9 -:101F1000284601F059FC1024012372785F1C013B14 -:101F2000934211D32B7FA88A0734E408BBB98442BB -:101F300094BF0020012003B0F0BDAB8ADB00083B5A -:101F4000DB0873700824E7E7F319009321460023A8 -:101F50000822284601F038FC08343B46DDE7201A09 -:101F600018BF0120E7E70000F8B50E460546144605 -:101F7000002181223046FFF7F5FD2B460822002183 -:101F8000304601F05DFD7CB96B1C0722082130460C -:101F900001F056FD0F2401236A785F1C013B934238 -:101FA00004D3E01DC008F8BD0824F4E7EB1921466E -:101FB0000822304601F044FD08343B46ECE70000BF -:101FC000F8B50E46054614460021CE223046FFF7EE -:101FD000C9FD2B4628220021304601F031FD7CB995 -:101FE00005F1080308222821304601F029FD30249C -:101FF0002F462A7A7B1B934204D3E01DC008F8BD0C -:102000002824F5E707F1090321460822304601F0AC -:1020100017FD08340137ECE7F7B5047F00910E4651 -:10202000012310220021054601F0CEFBC4B9B31CE8 -:102030000093092223461021284601F0C5FB1924EC -:1020400037467288BB1B9A4211D82B7FA88A073467 -:10205000E408BBB9844294BF0020012003B0F0BD66 -:10206000AB8ADB00103BDB0873801024E8E73B1DE4 -:102070000093214600230822284601F0A5FB0834DE -:102080000137DEE7201A18BF0120E7E730B5094D18 -:102090000A4491420DD011F8013B5840082340F307 -:1020A0000004013B2C4013F0FF0384EA5000F6D1FA -:1020B000EFE730BD2083B8EDF7B54FF0FF33DFF821 -:1020C00054C0DFF854E000EB81011A4688421CD06E -:1020D00050F8044B019401AF042417F8015B82EA25 -:1020E00005620825DB18164605F1FF355241002E22 -:1020F000BCBF83EA0C0382EA0E0215F0FF05F1D1A2 -:10210000013C14F0FF04E8D1E0E7D843D14303B029 -:10211000F0BD00BF9336EAA9EBE1F042F7B5384ACB -:10212000106851686B4603C36A463649364808232F -:1021300004F060FE0446002833D10A25334A1068B3 -:1021400051686B4603C36A4631492F48082304F09F -:1021500051FE0446002849D00369B3F5E02F45D865 -:10216000B0F8661040F2474291423FD1294A0244FA -:1021700002F15C018B4239D35C3B234900209E1A5B -:10218000FFF784FF3246074604F164010020FFF7A1 -:102190007DFFA3689F4229D1E368984208BF0025CC -:1021A00024E00369B3F5E02F27D8418B40F2474282 -:1021B000914220D1174A024402F110018B4218D3F8 -:1021C000103B114900209D1AFFF760FF2A46064682 -:1021D00004F118010020FFF759FFA3689E4202D1C5 -:1021E000E368984201D00D25A8E70025284603B0F2 -:1021F000F0BD1025A2E70C25A0E70B259EE700BF48 -:10220000546F0008DCFF0600000001085D6F000845 -:1022100090FF06000800FFF710B5037C044613B9D1 -:10222000006804F0CFFD204610BD00000023BFF37E -:102230005B8FC360BFF35B8FBFF35B8F8360BFF3C4 -:102240005B8F7047BFF35B8F0068BFF35B8F704796 -:1022500070B505460C30FFF7F5FF05F1080604469A -:102260003046FFF7EFFFA04206D930466D68FFF712 -:10227000E9FF2544281A70BD3046FFF7E3FF201A16 -:10228000F9E7000070B50546406898B105F108000F -:10229000FFF7D8FF05F10C0604463046FFF7D2FFE2 -:1022A0008442304694BF6D680025FFF7CBFF013CA8 -:1022B0002C44201A70BD000038B50C460546FFF7C7 -:1022C000C7FFA04210D305F10800FFF7BBFF04448D -:1022D0006868B4FBF0F100FB1144BFF35B8F012091 -:1022E000AC60BFF35B8F38BD0020FCE72DE9F04107 -:1022F000144607460D46FFF7C5FF844228BF044633 -:10230000D4B1B84658F80C6B4046FFF79BFF3044F9 -:10231000286040467E68FFF795FF331A9C4203D839 -:102320006C600120BDE8F0816B60A41B3B68AB6072 -:102330002044E8600220F5E72046F3E738B50C4674 -:102340000546FFF79FFFA04210D305F10C00FFF7F1 -:1023500079FF04446868B4FBF0F100FB1144BFF35B -:102360005B8F0120EC60BFF35B8F38BD0020FCE782 -:102370002DE9FF41884669460746FFF7B7FF6C46DF -:1023800006B204EBC6060025B44209D06268206894 -:1023900008EB0501FFF7C0FB636808341D44F3E751 -:1023A00029463846FFF7CAFF284604B0BDE8F08149 -:1023B000F8B505460C300F46FFF744FF05F1080657 -:1023C00004463046FFF73EFFA042304688BF6C68A7 -:1023D000FFF738FF201A386020B130462C68FFF72D -:1023E00031FF2044F8BD000073B5144606460D4683 -:1023F000FFF72EFF844228BF04460190DCB101A9FB -:102400003046FFF7D5FF019B33B93268C5E9023387 -:10241000C5E9002401200CE09C4238BF01942860EB -:10242000019868608442F5D93368AB60241AEC6087 -:10243000022002B070BD2046FBE700002DE9FF41FD -:102440000F466946FFF7D0FF6C4600B204EBC005AB -:102450000026AC4209D0D4F8048054F8081BB819FF -:102460004246FFF759FB4644F3E7304604B0BDE867 -:10247000F081000038B50546FFF7E0FF044601464D -:102480002846FFF719FF204638BD0000302383F3AC -:10249000118862B670470000002383F3118862B68A -:1024A0007047000010B4026854681A4623465DF86D -:1024B000044B1847012070470020704700207047E8 -:1024C00070470000002070470E20704700F58050D4 -:1024D00090F8C800C0F340007047000000F580503D -:1024E00090F9C90070470000F7B50C68BDF820707E -:1024F00014F000541E466FD10B7B082B6CD8FFF7ED -:10250000C5FF4569AB685B010CD4AB681B0108D4FF -:10251000AC6814F080545DD1FFF7BEFF204603B0D5 -:10252000F0BD01240B6804F1180C002BB8BFDB00D0 -:102530004FEA0C1CB4BF43F004035B0545F80C30B4 -:102540000B680FFA84FC13F0804F18BF05EB0C1ECC -:1025500005EB0C1C1EBFDEF8803143F00203CEF801 -:1025600080310B7BCCF8843105EB04158B68C5F802 -:102570008C314B68C5F88831DCF8803143F00103B9 -:10258000CCF8803100EB441541F268031D4403EBA5 -:1025900044130344C5E9002608330D4601F10C0C31 -:1025A00055F804EB43F804EB6545F9D184342D88E4 -:1025B0001D8000EB441407F00303257925F00B057B -:1025C0002B432371FFF768FF0097334600F0E2FCCE -:1025D0000120A4E70224A5E74FF0FF309FE70000A9 -:1025E00013B500F580540191E06DFFF74BFE1F28F5 -:1025F0000AD90199E06D2022FFF7BAFEA0F120036D -:102600005842584102B010BD0020FBE708B500F564 -:102610008050FFF73BFFC06DFFF708FEBDE80840A4 -:10262000FFF73ABF002202608281426082607047F9 -:1026300010B500220023C0E90023002304460381D3 -:102640000C30FFF7EFFF204610BD0000F0B5054647 -:1026500000F580500C4690F8C83013F0040FC3F317 -:10266000800108BF114661F3820304F1840680F8FB -:10267000C83005EB461389B01B79D8072ED57AB33D -:1026800019072DD46846FFF7D3FF05EB441303F574 -:10269000835303F1180703AA1033186859681446C6 -:1026A00003C40833BB422246F7D1186820609B88D8 -:1026B000A380DDE90E23CDE900230123ADF8083026 -:1026C0002B686946DB6B2846984705EB46152B7946 -:1026D0001A075CBF43F008032B7101E0002AF4D114 -:1026E00009B0F0BD2DE9F047074688B007F58054E2 -:1026F00068469A468846FFF7C9FE9146FFF798FF5D -:10270000E06DFFF7A5FD1F2829D9E06D202269465D -:10271000FFF7B0FE202822D103AD444605AB2E467C -:1027200003CE9E4220606160354604F10804F6D174 -:1027300030682060B388A380DDE90023C9E9002365 -:10274000BDF80830AAF80030FFF7A6FE4A46534607 -:102750004146384608B0BDE8F04700F009BCFFF735 -:102760009BFE002008B0BDE8F08700002DE9F84F7F -:102770000023C0E90133254B044640F8183B0F46BF -:10278000FFF750FF04F12800FFF752FF04F148085B -:1027900004F582554646083530462036FFF748FF97 -:1027A000AE42F9D104F580554FF480534FF0000943 -:1027B000C5E91339C5F848800123EE6504F587584B -:1027C00004F58456C5F8549085F8583085F8603083 -:1027D000083608F108084FF0000A4FF0000B46E9F0 -:1027E00008ABA6F11800FFF71DFF203646F8289C1D -:1027F0004645F4D185F8C97017B1054800F0A2FB31 -:10280000044B63612046BDE8F88F00BF906F00085D -:10281000686F00080064004010B5044B1978044646 -:102820004A1C1A70FFF7A2FF204610BD804B002003 -:102830002DE9F047002950D0294B2A4FB7FBF1F57D -:1028400099428CBF0A231123581EB5FBF3FC03FBEE -:102850001C53C4B22BB102280346F5D80020BDE8B2 -:10286000F0870CF1FF36B6F5806FF7D2C4EBC40EDB -:102870000EF103034FEAE309C3F3C703A4EB030814 -:1028800009F1010A4FF47A755FFA88F009FB0555E2 -:102890005AFA88F8B5FBF8F5B5F5617FC1BF0EF1BE -:1028A000FF33C3F3C703E01AC0B25C1C50FA84F4D0 -:1028B0000CFB04F4B7FBF4F4A142CFD1013BDBB233 -:1028C0000F2BCBD80138C0B20728C7D80021107110 -:1028D00016809170D3700120C1E70846BFE700BFA2 -:1028E0003F420F0040787D0170B505460E464FF41B -:1028F0007A746B695B6803F00103B34207D04FF44D -:102900007A7002F0ADFB013CF3D1204670BD01208E -:10291000FCE7000030B54269936913F0700F16D0E0 -:1029200000230B4C936103F1840200EB42121179F6 -:102930004D0709D5890707D5416954F823508D60A3 -:10294000117941F0040111710133032BEBD130BD3A -:102950007C6F000873B51D46436916469A68D20716 -:10296000044609D59A6801219960C2F34002CDE975 -:1029700000650021FFF76AFE63699A68D1050BD5EF -:102980009A684FF480719960C2F34022CDE90065E6 -:1029900001212046FFF75AFE63699A68D2030BD5DE -:1029A0009A684FF480319960C2F34042CDE90065E6 -:1029B00002212046FFF74AFE204602B0BDE87040E3 -:1029C000FFF7A8BFF8B50446466900296CD106F1A7 -:1029D0000C07386880076AD006EB01153868D5F80F -:1029E000B00110F0040FD5F8B0011ABFC00840F0D4 -:1029F0000040400DA061D5F8B0C11CF0020F1CBF13 -:102A000040F08040A061D5F8B40106EB011100F060 -:102A10000F0084F82400D1F8B8012077D1F8B8016C -:102A2000000A6077D1F8B801000CA077D1F8B8019E -:102A3000000EE077D1F8BC0184F82000D1F8BC0189 -:102A4000000A84F82100D1F8BC01000C84F82200AF -:102A5000D1F8BC11090E84F823103821396004F133 -:102A6000340004F1180104F1240551F8046B40F816 -:102A7000046BA942F9D109880180C4E90A232146DF -:102A80000023238651F8283B2046DB6B984704F54A -:102A90008052204692F8C83043F0040382F8C830D0 -:102AA000BDE8F840FFF736BF06F1100791E7F8BD23 -:102AB00010B5044600F04EFA02460B4652EA0301F6 -:102AC00002D0013A63F100030449086820B12146AD -:102AD000BDE81040FFF776BF10BD00BF7C4B002063 -:102AE000F8B500F583511E46FFF7D0FCDFF844C06F -:102AF0000831002404F1840500EB45152B795F07AC -:102B00000ED4DB060CD5D1E900739742B34107D24E -:102B100043695CF824709F602B7943F004032B71A8 -:102B20000134032C01F12001E4D1BDE8F840FFF7A6 -:102B3000B3BC00BF7C6F000808B5FFF7A7FCFFF728 -:102B4000E9FEBDE80840FFF7A7BC0000F8B54369FF -:102B50000546986800F0E050B0F1E05F0F461FD0E6 -:102B6000E8B1FFF793FC05F583541034002606F115 -:102B7000840305EB43131B791A0706D50136032E90 -:102B800004F12004F3D1012007E05B07F6D42146CD -:102B9000384600F039FA0028F0D1FFF77DFCF8BD87 -:102BA0000120FCE700F5805008B5FFF76FFCC06D11 -:102BB000FFF74EFBFFF770FC43090CBF012000201C -:102BC00008BD0000F8B51D46002313700F460646E9 -:102BD0001446FFF7E7FF80F00100387025B1294661 -:102BE0003046FFF7B3FF2070F8BD00002DE9B84173 -:102BF0000C4615461F46804600F0ACF90B4621787E -:102C0000024609B9287850B14046FFF769FFFFF73F -:102C100093FF3B462A462146FFF7D4FF0120BDE83B -:102C2000B881000010B5FFF731FC174B1A6C42F069 -:102C300000721A641A6A42F000721A621A6A00F587 -:102C4000805422F000721A62FFF726FC94F8C83014 -:102C5000DB0718D4B9B103211320FFF717FC01F0EB -:102C6000BBFA0321142001F0B7FA0321152001F06B -:102C7000B3FA94F8C83043F0010384F8C830BDE8D3 -:102C80001040FFF709BC10BD003802402DE9F047A5 -:102C900000F5805588B095F8C930012B0446884668 -:102CA00016467FD8804F57F823200AB947F82300EB -:102CB000D7F800A0C4F80C802674BAF1000F63D0D6 -:102CC00095F8C930012B6FD001212046FFF7AAFFEC -:102CD000FFF7DCFB6269136823F00203136062698B -:102CE000136843F001031360636900275F610121EA -:102CF0002046FFF7D1FBFFF7F7FD002800F0958095 -:102D0000E86DFFF793FA04F58359BA4609F108090B -:102D1000202200216846FEF725FF02A8FFF782FC6B -:102D2000CDF818A06A4609EB07030DF1180E94467A -:102D3000BCE80300F44518605960624603F10803DB -:102D4000F5D1DCF80000186020379CF804201A71D7 -:102D5000602FDDD195F8C8306FF38203002785F826 -:102D6000C8306A4641462046ADF80070ADF80270A2 -:102D70008DF80470FFF75CFD636948BB4FF40042B7 -:102D80001A6008B0BDE8F08741F2D00003F0DAFF26 -:102D9000814610B15146FFF7E9FCC7F80090B9F140 -:102DA000000F8DD10020ECE7386803681B6B984753 -:102DB0000146002888D13868FFF734FF3868036877 -:102DC00032465B684146984700287FF47DAFE9E7CB -:102DD00061221A609DF802309DF803201B06120440 -:102DE00002F4702203F040731343BDF80020C2F3D5 -:102DF000090213439DF804201205022E02F4E0029A -:102E00000CBF4FF000410021134362690B43D361B3 -:102E1000636913225A616269136823F00103136026 -:102E200039462046FFF760FD08B96369A6E795F8C3 -:102E3000C93093BB6169D1F8002242F00102C1F8A8 -:102E400000226169D1F8002222F47C5222F00E02A5 -:102E5000C1F800226169D1F8002242F46062C1F831 -:102E600000226269C2F814326269C2F804326269EF -:102E700041F6FF71C2F80C126269C2F84032626911 -:102E8000C2F8443263690122C3F81C226269D2F895 -:102E9000003223F00103C2F8003295F8C83043F045 -:102EA000020385F8C8306CE77C4B002008B500F0C1 -:102EB00051F850EA0103024602D0421E61F10001BE -:102EC000044B186810B10B46FFF744FDBDE80840FD -:102ED00001F064B87C4B002008B50020FFF7E8FD46 -:102EE000BDE8084001F05AB808B50120FFF7E0FD41 -:102EF000BDE8084001F052B800B59BB0EFF309817E -:102F000068226846FEF708FEEFF30583014B9B6BD2 -:102F1000FEE700BF00ED00E008B5FFF7EDFF0000A1 -:102F200000B59BB0EFF3098168226846FEF7F4FD17 -:102F3000EFF30583014B5B6BFEE700BF00ED00E0A4 -:102F4000FEE700000FB408B5029802F015F8FEE79E -:102F500002F0A2BC02F07ABC13B56C4684E806000D -:102F6000031D94E8030083E80500012002B010BDB2 -:102F700073B58568019155B11B885B0707D4D0E90B -:102F800000369B6B9847019AC1B23046A847012092 -:102F900002B070BDF0B5866889B005460C465EB1DA -:102FA000BDF838305B070AD4D0E900379B6B9847EF -:102FB0002246C1B23846B047012009B0F0BD002218 -:102FC0000023CDE900230023ADF808300A4603AB07 -:102FD00001F10806106851681C4603C40832B24269 -:102FE0002346F7D1106820609288A280FFF7B2FFD5 -:102FF0000423ADF808302B68CDE90001DB6B69468E -:1030000028469847D8E7000030B503680968DD0F07 -:10301000B5EBD17F23F0604421F060424FEAD170DC -:103020000BD0002BB8BFA40C0029B8BF920C94425F -:1030300002D034BF0120002030BD944205D1C1F33D -:103040008070C3F380738342F6D194422CBF00207A -:103050000120F1E72DE9F041456A15B94162BDE86B -:10306000F0814B6823F06047C3F38A464FEAD37E72 -:10307000C3F3807816EA230638BF3E46AC462B469B -:103080005A68BEEBD27F22F060440AD0002A18DAD8 -:10309000A40CB44217D19D420FD10D60DEE7134658 -:1030A000EEE7A74207D102F08044C2F380724245A6 -:1030B0000BD054B1EFE708D2EDE7CCF800100B606D -:1030C000CDE7B44201D0B442E5D81A689C46002A44 -:1030D000E5D11960C3E700002DE9F047089D01F034 -:1030E00007044FEAD508224405F0070500EBD1009C -:1030F0004FF47F49944201D1BDE8F08704F00707FF -:1031000005F0070A57453E4638BF5646C6F1080641 -:10311000111B8E4228BF0E46E10808EBD50E415C1C -:1031200013F80EC0B94029FA06F721FA0AF1FFB2E6 -:103130008CEA010147FA0AF739408CEA010C03F8DE -:103140000EC034443544D5E780EA0120082341F21B -:10315000210201B24000002980B203F1FF33B8BF61 -:10316000504013F0FF03F4D17047000038B50C460F -:103170008D18A54200D138BD14F8011BFFF7E4FFFC -:10318000F7E7000042684AB11368436043898189C8 -:1031900001339BB29942438138BF83811046704707 -:1031A00070B588B0202204460D4668460021FEF71F -:1031B000D9FC20460495FFF7E5FF024658B16B465F -:1031C000054608AE1C4603CCB4422860696023461D -:1031D00005F10805F6D1104608B070BD082817D9CA -:1031E00009280CD00A280CD00B280CD00C280CD0A5 -:1031F0000D280CD00E2814BF4020302070470C2022 -:103200007047102070471420704718207047202006 -:1032100070470000082817D90C280CD910280CD9A1 -:1032200014280CD918280CD920280CD930288CBF88 -:103230000F200E207047092070470A2070470B208E -:1032400070470C2070470D20704700002DE9F843AF -:10325000078C072F04461ED9D0E9029800254FF6A7 -:10326000FF73C5F12006A5F1200029FA05F108FA3F -:1032700006F628FA00F031430143C9B21846FFF7B9 -:1032800063FF0835402D0346EBD1E1693A46BDE8BE -:10329000F843FFF76BBF4FF6FF70BDE8F8830000FF -:1032A00010B54B6823B9CA8A63F30902CA8210BDFC -:1032B00004691A681C600361C38A013BC3824A60C7 -:1032C000EFE700002DE9F84F1D46CB8A0F46C3F308 -:1032D00009010529814692460B4630D00020AAB24A -:1032E00007F11A049EB2042E1FFA80F80FD89045F9 -:1032F00003F1010306D3FB8A0A4462F30903FB824C -:1033000001201AE01AF80060E6540130EAE790451F -:10331000F1D2A1F1050B1C237C68BBFBF3F203FB8C -:1033200012BB1FFA8BF6002C45D14846FFF72AFF47 -:10333000044638B978606FF00200BDE8F88F4FF0AE -:103340000008E6E7002606607860ADB24FF0000B9B -:10335000454510D90AEB0803221D13F8011B9155AE -:10336000B1B208F101081B291FFA88F82BD0454596 -:1033700006F10106F1D8FB8AC3F30902154465F38F -:103380000903BCE7013292B21C462368002BF9D135 -:103390006B1F0B441C21B3FBF1F301339BB29A4228 -:1033A000D3D2BBF1000FD0D14846FFF7EBFE20B9D6 -:1033B000C4F800B0BFE70122E7E7C0F800B05E46FE -:1033C00020600446C1E74545D5D94846FFF7DAFEF7 -:1033D00008B92060AFE7C0F800B0002620600446BE -:1033E000B6E700002DE9F04F2DED028B1C4683B0AF -:1033F0005B69019207468846002B00F09A80238C77 -:103400002BB1E269002A00F09480072B35D807F130 -:103410000C00FFF7B7FE054638B96FF002052846E5 -:1034200003B0BDEC028BBDE8F08F14220021FEF743 -:1034300099FB228CE16905F10800FEF76DFB208CF9 -:10344000013080B2FFF7E6FEFFF7C8FE013880B218 -:103450002084013028746369228C1B782A4403F08D -:103460001F0363F03F0348F0004113723846696060 -:103470002946FFF7EFFD0125D1E700F10C034FF0DE -:10348000000908EE103A4FF0800A4E464D4618EEFD -:10349000100AFFF777FE83460028BED014220021D1 -:1034A000FEF760FB002E3AD1019BABF808300222F8 -:1034B0000BF1080E1FFA82FC0CF10100BCF1060FA3 -:1034C000218C80B201D88E422BD3FFF7A3FEFFF7E9 -:1034D00085FE62691278013802F01F028E4208BF31 -:1034E0004FF0400A42EA49121BFA80F14AEA020A06 -:1034F000013048F0004281F808A08BF81000CBF8AA -:10350000042059463846FFF7A5FD238C0135B34208 -:103510002DB289F001094FF0000AB8D17FE70022EF -:10352000C6E7E169895D0EF802100136B6B20132D4 -:10353000C0E76FF0010572E7F8B515460E46302278 -:10354000002104461F46FEF70DFB069B6360B5F5A0 -:10355000001F079BA76034BF6A094FF6FF72A36282 -:1035600097B2E66104F1100000239A4206D80023C6 -:103570000360A782E3822383E360F8BD0660013322 -:1035800030462036F1E7000003781BB94BB2002B20 -:10359000C8BF01707047000000787047F8B50C464E -:1035A000C969074611B9238C002B37D1257E1F2D01 -:1035B00034D8387828BB228C072A2CD8268A36F0B3 -:1035C00003032BD14FF6FF70FFF7D0FD20F0010071 -:1035D0003102400441EA0561400C41EA40254FF6C2 -:1035E000FF72234629463846FFF7FCFE002807DD18 -:1035F000626913780133DBB21F2B88BF002313707D -:10360000F8BD218A2D0645EA012505432046FFF72E -:103610001DFE0246E5E76FF00300F1E76FF00100E1 -:10362000EEE7000070B58AB0044616460021282255 -:1036300068461D46FEF796FABDF83830ADF81030F2 -:103640000F9B05939DF840308DF81830119B079320 -:103650006946BDF84830ADF820302046CDE9026516 -:10366000FFF79CFF0AB070BD2DE9F041D369054614 -:103670000C4616460BB9138C5BBB377E1F2F28D820 -:1036800095F80080B8F1000F26D03046FFF7DEFD38 -:103690003378210241EAC33141EA0801338A41EA21 -:1036A000076141EA03410246334641F08001284662 -:1036B000FFF798FE00280ADD3378012B07D17269E5 -:1036C00013780133DBB21F2B88BF00231370BDE8D2 -:1036D000F0816FF00100FAE76FF00300F7E70000F8 -:1036E000F0B58BB004460D461746002128226846E7 -:1036F0001E46FEF737FA9DF84C305A1E534253418E -:103700008DF800309DF84030ADF81030119B0593D6 -:103710009DF848308DF81830149B07936A46BDF821 -:103720005430ADF8203029462046CDE90276FFF727 -:103730009BFF0BB0F0BD0000406A00B10430704741 -:10374000436A1A68426202691A600361C38A013BD4 -:10375000C38270472DE9F041D0F82080194E1446FD -:103760001D464146002709B9BDE8F081D1E9022391 -:10377000A21A65EB0303964277EB03031ED2036A9A -:103780008B420DD1FFF78CFD036A1B68036203694E -:103790000B60C38A0161016A013BC3828846E2E78C -:1037A000FFF77EFD0B68C8F8003003690B60C38A21 -:1037B0000161013BC382D8F80010D4E7884609684C -:1037C000D1E700BF80841E002DE9F04F8BB00D467D -:1037D000DDF8509014469B468046002800F0198181 -:1037E000B9F1000F00F01581531E3F2B00F211813B -:1037F000012A03D1BBF1000F40F00B810023CDE97A -:103800000833B8F81430B5EBC30F4FEAC30703D33E -:1038100000200BB0BDE8F08F2B199F42D8F80C3078 -:103820003ABF7F1BFFB227461BB9D8F81030002BD8 -:103830007AD0272D4ED8C5F12806B7424FF00003A5 -:103840002CBFF6B23E4600932946D8F8080008ABD4 -:103850003246FFF741FCA7EB060A35445FFA8AFAC5 -:10386000B8F8143003F10053053BDB000493D8F89B -:103870000C3003932821039B13B1BAF1000F2CD114 -:10388000D8F8100040B1BAF1000F05D0009608AB8F -:103890005246691AFFF720FC38B2002FB8D06607ED -:1038A0000AD00AAB03EBD401624211F8083C02F0E3 -:1038B0000702134101F8083C082C3CD9102C40F2B7 -:1038C000B580202C40F2B780BBF1000F00F09C8047 -:1038D000082334E0BA460026C2E7049BE02B28BF49 -:1038E000E02306930B44AB42059314D95A1B03986B -:1038F0000096924534BF5246D2B2691A08AB0430E2 -:103900000792FFF7E9FB079A1644AAEB020A15444F -:10391000F6B25FFA8AFA049B069A05999B1A0493F9 -:10392000039B1B680393A6E70093D8F8080008AB35 -:103930003A462946AEE7BBF1000F13D00123B4EBA2 -:10394000C30F6CD0082C12D89DF82030621E23FAC9 -:1039500002F2D50706D54FF0FF3202FA04F42343F2 -:103960008DF820309DF8203089F8003051E7102C78 -:1039700012D8BDF82030621E23FA02F2D10706D514 -:103980004FF0FF3202FA04F42343ADF82030BDF8C3 -:103990002030A9F800303CE7202C0FD80899631E8E -:1039A00021FA03F3DA0705D54FF0FF3202FA04F4E7 -:1039B0000C430894089BC9F800302AE7402C2BD010 -:1039C000DDE90865611EC4F12102A4F1210326FA94 -:1039D00001F105FA02F225FA03F311431943CB076B -:1039E00012D50122A4F12003C4F1200102FA03F34D -:1039F00022FA01F1A240524243EA010363EB43037E -:103A000032432B43CDE90823DDE90823C9E900232C -:103A1000FFE66FF00100FCE66FF00800F9E6082C05 -:103A2000A0D9102CB3D9202CEED8C3E7BBF1000FDE -:103A3000ADD0022383E7BBF1000FBBD004237EE7A8 -:103A400030B5012A144638BF0124402C85B028BF68 -:103A500040240025012ACDE9025518D81B788DF89D -:103A6000083063070AD004AB03EBD405624215F8B3 -:103A7000083C02F00702934005F8083C0091034619 -:103A80002246002102A8FFF727FB05B030BD082A17 -:103A9000E4D9102A03D81B88ADF80830E1E7202AC2 -:103AA0008DBFD3E900231B680293CDE90223D8E739 -:103AB00010B5CB681BB98B600B618B8210BD04699C -:103AC0001A681C600361C38A013BC382CA60F0E7C5 -:103AD00003064CBFC0F3C0300220704708B5024651 -:103AE000FFF7F6FF022806D15306C2F30F2001D1DB -:103AF00000F0030008BDC2F30740FBE72DE9F04FDB -:103B000093B0CDE903230A6804461046FFF7E0FFAF -:103B1000022814BFC2F306260026002A0D4682465C -:103B200080F2F28112F0C04940F0EE81097B002959 -:103B300000F0EA81022803D02378B34240F0E78105 -:103B4000C2F304630693104602F07F030593FFF768 -:103B5000C5FF059B29444FEA834848EA0A4848EADA -:103B60004668CE7800230022CDE90823F309834676 -:103B700048EA0008029367D0059B009302466768F5 -:103B8000534608A92046B847002800F0C381276A99 -:103B90004FB9414604F10C00FFF702FB074690B90C -:103BA0006FF0020054E03B6998450DD03F68002F4C -:103BB000F9D1414604F10C00FFF7F2FA074600285C -:103BC000EED0236A3B60276297F817C006F01F0803 -:103BD000CCF3840CACEB08001FFA80FE0028B8BFC1 -:103BE0000EF12000A8EB0C031FFA83FED7E9022197 -:103BF000B8BF00B2002B0793BEBF0EF120031BB26B -:103C0000079352EA010338D0039BDFF824E39A1AA2 -:103C1000049B4FF0000C63EB010196457CEB010324 -:103C20002BD36B7B97F81AE0734519D1029B002BBD -:103C300078D0012821DC7868F8B9DFF8F0C2944523 -:103C400070EB010316D337E0276A27B96FF00C0039 -:103C500013B0BDE8F08F3B699845B5D03F68F4E7F5 -:103C6000B24890427CEB010301D30020F0E7029BB5 -:103C7000002BFAD0079B0F2B17DCFA7DB30002F064 -:103C8000030203F07C031343FB7539462046FFF71C -:103C900007FB6B7BBB76029B3BB9FB7DC3F38402C6 -:103CA000013262F38603FB75D0E76A7BBB7E9A42E2 -:103CB000DBD1029B002B35D0B309022B32D0039B02 -:103CC000BB60049BFB60142200210DA8FDF74AFF96 -:103CD000039B0A93049B0B932B1D0C932B7BADF83A -:103CE0003EB0013BDBB2ADF83C30069B8DF8423074 -:103CF000059B8DF8433094F82C308DF840A083F06C -:103D000001038DF844308DF84180A3680AA920464C -:103D10009847FB7DC3F38403013303F01F039B0229 -:103D2000FB82A2E7FB7DC6F34012B2EBD31F40F04B -:103D3000F480C3F38403434540F0F280029A2B7B66 -:103D4000B609002A4DD0F2075DD4032B40F2EB8078 -:103D5000039BBB60049BFB602B7BAE1D033BDBB274 -:103D60003246394604F10C00FFF7ACFA00280CDAB1 -:103D700039462046FFF794FAFB7DC3F384030133F1 -:103D800003F01F039B02FB820AE7DDE90884AB888E -:103D90003B834FF6FF73C9F12000A9F1200228FAF6 -:103DA00009F104FA00F0014324FA02F21143184623 -:103DB000C9B2FFF7C9F909F10809B9F1400F034683 -:103DC000E9D1B8822A7B033AD2B23146FFF7CEF965 -:103DD000FB7DB882DA43C2F3C01262F3C713FB75EE -:103DE00043E786B92E1D013BDBB23246394604F16A -:103DF0000C00FFF767FA0028BADB2A7BB88A013A81 -:103E0000D2B23146E2E7F98AC1F30901013B042944 -:103E1000DAB25BD8281D002307F11B069A4208D9A5 -:103E200010F801CB06F801C0013101330529DBB2DE -:103E3000F4D103990A9104990B91934207F11B0164 -:103E40000C9138BF043379680D9134BF55FA83F370 -:103E500000230E93FB8AADF83EB0C3F309031A4466 -:103E6000069B8DF84230059B8DF8433094F82C303A -:103E7000ADF83C2083F001038DF8443000238DF829 -:103E800040A08DF841807B602A7BB88A013A291DC9 -:103E9000FFF76CF93B8BB882834203D1A3680AA970 -:103EA0002046984720460AA9FFF702FEFB7DBA8A02 -:103EB000C3F38403013303F01F039B02FB823B8B9C -:103EC0009A420CBF00206FF01000C1E67B68002B07 -:103ED000AFD0052001E01C3033461E68002EFAD119 -:103EE000091A081D2E1D184401EB090CBCF11B0F0B -:103EF0005FFA89F39DD89A429BD916F8013B00F8E6 -:103F0000013B09F10109EFE76FF00900A0E66FF04E -:103F10000A009DE66FF00B009AE66FF00D0097E641 -:103F20006FF00E0094E66FF00F0091E640420F0034 -:103F300080841E00EFF3098305494A6B22F00102D9 -:103F40004A63683383F30988002383F31188704739 -:103F500000EF00E0302080F3118862B60C4B0D4A70 -:103F6000D96821F4E0610904090C0A43DA60D3F846 -:103F7000FC20094942F08072C3F8FC200A6842F034 -:103F800001020A602022DA7783F82200704700BF1E -:103F900000ED00E00003FA05001000E010B530234A -:103FA00083F311880E4B5B6813F4006314D0F1EEB9 -:103FB000103AEFF30984683C4FF08073E361094BDA -:103FC000DB6B236684F3098800F094FF10B1064B85 -:103FD000A36110BD054BFBE783F31188F9E700BF30 -:103FE00000ED00E000EF00E0430600084606000890 -:103FF000026843681143016003B11847704700002D -:10400000024AD36843F0C003D360704700100140F8 -:1040100010B5054C054A0021204600F087FA044AF5 -:10402000044BC4E9972310BD884B002001400008D1 -:104030000010014080F0FA02234A037C002918BFD7 -:104040000A46012B30B5C0F868220CD11F4B9842AC -:1040500009D11F4B596C41F010015964596E41F060 -:10406000100159665B6EB2F904501468D0F86032E2 -:10407000D0F85C12002D03EB5403B3FBF4F3BEBF86 -:1040800023F0070503F0070343EA450394888B6098 -:10409000D38843F040030B61138943F001034B6164 -:1040A00044F4045343F02C03CB6004F4A0540023E5 -:1040B0000B60B4F5806F0B684B680CBF7F23FF2348 -:1040C00080F8643230BD00BFD06F0008884B0020FC -:1040D000003802402DE9F041D0F85C62F76833689F -:1040E000DA0504469DB20DD5302383F311884FF4D1 -:1040F00080610430FFF77CFF6FF48073336000232E -:1041000083F31188302383F3118804F1040815F038 -:104110002F033AD183F31188380615D5290613D514 -:10412000302383F3118804F1380000F07BF9002874 -:104130004EDA0821201DFFF75BFF4FF67F733B40EF -:10414000F360002383F311887A0616D56B0614D525 -:10415000302383F31188D4E913239A420AD1236CC4 -:1041600043B127F040073F041021201D3F0CFFF70B -:104170003FFFF760002383F31188D4F86822D368E7 -:1041800043B3BDE8F041106918472B0714D015F070 -:10419000080F0CBF00214FF48071E80748BF41F0C1 -:1041A0002001AA0748BF41F040016B0748BF41F01A -:1041B00080014046FFF71CFFAD06736805D594F8F3 -:1041C00064122046194000F0E1F93568ADB29EE76F -:1041D0007060B6E7BDE8F08100F1604303F561432C -:1041E0000901C9B283F80013012200F01F039A40AD -:1041F00043099B0003F1604303F56143C3F8802149 -:104200001A607047F8B5154682680669AA420B46DF -:10421000816938BF8568761AB54204460BD21846C4 -:104220002A46FDF779FCA3692B44A361A3685B1BB5 -:10423000A3602846F8BD0CD918463246FDF76CFC41 -:10424000AF1BE1683A463044FDF766FCE3683B4447 -:10425000EBE718462A46FDF75FFCE368E5E7000058 -:1042600083689342F7B51546044638BF8568D0E9A0 -:104270000460361AB5420BD22A46FDF74DFC63693D -:104280002B446361A36828465B1BA36003B0F0BDA9 -:104290000DD932460191FDF73FFC0199E068AF1B53 -:1042A0003A463144FDF738FCE3683B44E9E72A46E7 -:1042B000FDF732FCE368E4E710B50A440024C3616B -:1042C000029B8460C0E90000C0E90511C160026181 -:1042D000036210BD08B5D0E90532934201D182686E -:1042E00082B98268013282605A1C42611970D0E939 -:1042F00004329A4224BFC3684361002100F0CCFE1F -:10430000002008BD4FF0FF30FBE7000070B5302300 -:1043100004460E4683F31188A568A5B1A368A26977 -:10432000013BA360531CA36115782269934224BF0B -:10433000E368A361E3690BB120469847002383F348 -:104340001188284607E03146204600F095FE0028F7 -:10435000E2DA85F3118870BD2DE9F74F04460E4669 -:1043600017469846D0F81C904FF0300A8AF311880F -:104370004FF0000B154665B12A4631462046FFF73F -:1043800041FF034660B94146204600F075FE002813 -:10439000F1D0002383F31188781B03B0BDE8F08FC0 -:1043A000B9F1000F03D001902046C847019B8BF361 -:1043B0001188ED1A1E448AF31188DCE7C0E9051163 -:1043C000C160C3611144009B8260C0E900000161CB -:1043D00003627047F8B504460D461646302383F352 -:1043E0001188A768A7B1A368013BA36063695A1C41 -:1043F00062611D70D4E904329A4224BFE3686361AC -:10440000E3690BB120469847002080F3118807E04C -:104410003146204600F030FE0028E2DA87F31188AA -:10442000F8BD0000D0E905239A4210B501D1826899 -:104430007AB98268013282605A1C82611C780369F1 -:104440009A4224BFC3688361002100F025FE204604 -:1044500010BD4FF0FF30FBE72DE9F74F04460E4645 -:1044600017469846D0F81C904FF0300A8AF311880E -:104470004FF0000B154665B12A4631462046FFF73E -:10448000EFFE034660B94146204600F0F5FD0028E6 -:10449000F1D0002383F31188781B03B0BDE8F08FBF -:1044A000B9F1000F03D001902046C847019B8BF360 -:1044B0001188ED1A1E448AF31188DCE7026843680C -:1044C0001143016003B11847704700001430FFF733 -:1044D00043BF00004FF0FF331430FFF73DBF000033 -:1044E0003830FFF7B9BF00004FF0FF333830FFF727 -:1044F000B3BF00001430FFF709BF00004FF0FF31D9 -:104500001430FFF703BF00003830FFF763BF00002F -:104510004FF0FF323830FFF75DBF0000012914BFB4 -:104520006FF0130000207047FFF772BD37B51546D6 -:104530000E4A026000224260C0E9022201220446C3 -:1045400002740B46009000F15C014FF4807214304D -:10455000FFF7B2FE00942B464FF4807204F5AE7163 -:1045600004F13800FFF72AFF03B030BDE46F000804 -:1045700010B53023044683F31188FFF75DFD022355 -:104580002374002080F3118810BD000038B5C36982 -:1045900004460D461BB904210844FFF78FFF294646 -:1045A00004F11400FFF796FE002806DA201D4FF4F0 -:1045B0000061BDE83840FFF781BF38BD026843683D -:1045C0001143016003B118477047000013B5446BF5 -:1045D000D4F894341A681178042915D1217C022961 -:1045E00012D11979128901238B4013420CD101A9F0 -:1045F00004F14C0001F0CEFFD4F89444019B2179E2 -:104600000246206800F0D6F902B010BD143001F067 -:1046100051BF00004FF0FF33143001F04BBF0000DA -:104620004C3002F023B800004FF0FF334C3002F062 -:104630001DB80000143001F01FBF00004FF0FF3123 -:10464000143001F019BF00004C3001F0EFBF000042 -:104650004FF0FF324C3001F0E9BF000000207047FE -:1046600010B5D0F894341A6811780429044617D18B -:10467000017C022914D15979528901238B401342BC -:104680000ED1143001F0B2FE024648B1D4F8944481 -:104690004FF4807361792068BDE8104000F078B96C -:1046A00010BD0000406BFFF7DBBF0000704700004B -:1046B0007FB5124B036000234360C0E9023301253C -:1046C00002260F4B057404460290019300F1840208 -:1046D000294600964FF48073143001F063FE094BB5 -:1046E0000294CDE9006304F523724FF480732946E8 -:1046F00004F14C0001F02AFF04B070BD0C700008FA -:10470000A5460008CD4500080B68302282F31188C9 -:104710000A7903EB820210624A790D3243F82200D3 -:104720008A7912B103EB820318620223C0F8941451 -:104730000374002080F311887047000038B5037FB0 -:10474000044613B190F85430ABB9201D0125022165 -:10475000FFF734FF04F1140025776FF0010100F03A -:10476000A7FC84F8545004F14C006FF00101BDE83F -:10477000384000F09DBC38BD10B50121044604301E -:10478000FFF71CFF0023237784F8543010BD00008E -:1047900038B504460025143001F01CFE04F14C002D -:1047A000257701F0EBFE201D84F854500121FFF71E -:1047B00005FF2046BDE83840FFF752BF90F85C3057 -:1047C00003F06003202B07D190F85D20212A4FF0E1 -:1047D000000303D81F2A06D800207047222AFBD1E5 -:1047E000C0E9143303E0034A02650722426583658A -:1047F000012070472823002037B5D0F894341A6878 -:104800001178042904461AD1017C022917D119799B -:10481000128901238B40134211D100F14C05284627 -:1048200001F06CFF58B101A9284601F0B3FED4F89D -:104830009444019B21790246206800F0BBF803B044 -:1048400030BD0000F0B500EB810385B01E6A044660 -:104850000D46FEB1302383F3118804EB8507301D2C -:104860000821FFF7ABFEFB685B691B6806F14C0093 -:104870001BB1019001F09CFE019803A901F08AFE92 -:10488000024648B1039B2946204600F093F80023D6 -:1048900083F3118805B0F0BDFB685A691268002ADD -:1048A000F5D01B8A013B1340F1D104F15C02EAE729 -:1048B0000D3138B550F82140DCB1302383F3118835 -:1048C000D4F894241368527903EB8203DB689B6964 -:1048D0005D6845B104216018FFF770FE294604F1B8 -:1048E000140001F08DFD2046FFF7BAFE002383F38C -:1048F000118838BD7047000001F0EEB810B50123F3 -:104900000446282200F8243B0021FDF72BF9002360 -:10491000C4E9013310BD000038B50446302383F3E9 -:1049200011880025C0E90355C0E90555C0E90755C0 -:10493000416001F0E1F80223237085F311882846D5 -:1049400038BD000070B500EB810305465069DA60A0 -:104950000E46144618B110220021FDF703F9A06994 -:1049600018B110220021FDF7FDF831462846BDE8B8 -:10497000704001F08BB90000826802F00112826081 -:104980000022C0E90422C0E90622026201F00ABA4C -:10499000F0B400EB81044789E4680125A4698D40E7 -:1049A0003D43458123600023A2606360F0BC01F0B9 -:1049B00025BA0000F0B400EB81040789E468012502 -:1049C00064698D403D43058123600023A2606360DC -:1049D000F0BC01F09FBA000070B502230025044628 -:1049E0000370C0E90255C0E90455C0E906554566A3 -:1049F000056280F84C5001F0E5F863681B6823B14C -:104A000029462046BDE87040184770BD0378052B45 -:104A100010B504460AD080F8683005230370436857 -:104A20001B680BB1042198470023A36010BD000050 -:104A30000178052906D190F86820436802701B6848 -:104A400003B118477047000070B590F84C30044629 -:104A500013B1002380F84C3004F15C02204601F0D1 -:104A6000C3F963689B68B3B994F85C3013F06005D0 -:104A700035D00021204601F077FC0021204601F0CE -:104A800069FC63681B6813B106212046984706231A -:104A900084F84C3070BD204698470028E4D0B4F824 -:104AA0006230626D9A4288BF636594F95C30656DCF -:104AB000002B4FF0300380F20381002D00F0F280D4 -:104AC000092284F84C2083F311880021D4E91423AF -:104AD0002046FFF76FFF002383F31188DAE794F88D -:104AE0005D2003F07F0343EA022340F20232934247 -:104AF00000F0C58021D8B3F5807F48D00DD8012BB8 -:104B00003FD0022B00F09380002BB2D104F164025D -:104B1000226502226265A365C1E7B3F5817F00F0DB -:104B20009B80B3F5407FA4D194F85E30012BA0D1D7 -:104B3000B4F8643043F0020332E0B3F5006F4DD0B7 -:104B400017D8B3F5A06F31D0A3F5C063012B90D86F -:104B5000636894F85E205E6894F85F10B4F8603083 -:104B60002046B047002884D0436823650368636506 -:104B70001AE0B3F5106F36D040F6024293427FF44C -:104B800078AF5C4B2365022363650023C3E794F889 -:104B90005E30012B7FF46DAFB4F8643023F0020374 -:104BA000C4E91455A4F86430A56578E7B4F85C301E -:104BB000B3F5A06F0ED194F85E3084F866302046CD -:104BC00001F058F863681B6813B10121204698472B -:104BD000032323700023C4E914339CE704F1670323 -:104BE00023650123C3E72378042B10D1302383F3FB -:104BF00011882046FFF7C0FE85F311880321636802 -:104C000084F8675021701B680BB12046984794F8D0 -:104C10005E30002BDED084F8673004232370636895 -:104C20001B68002BD6D0022120469847D2E794F883 -:104C300060301D0603F00F0120460AD501F0C6F8CA -:104C4000012804D002287FF414AF2B4B9AE72B4B9A -:104C500098E701F0ADF8F3E794F85E30002B7FF4AD -:104C600008AF94F8603013F00F01B3D01A06204655 -:104C700002D501F08DFBADE701F080FBAAE794F8C7 -:104C80005E30002B7FF4F5AE94F8603013F00F0126 -:104C9000A0D01B06204602D501F066FB9AE701F082 -:104CA00059FB97E7142284F84C2083F311882B4694 -:104CB0002A4629462046FFF76BFE85F31188E9E670 -:104CC0005DB1152284F84C2083F311880021D4E9CA -:104CD00014232046FFF75CFEFDE60B2284F84C20EF -:104CE00083F311882B462A4629462046FFF762FEA9 -:104CF000E3E700BF3C70000834700008387000081B -:104D000038B590F84C300446002B3ED0063BDAB262 -:104D10000F2A34D80F2B32D8DFE803F037313108AF -:104D2000223231313131313131313737456DB0F8DF -:104D300062309D4214D2C3681B8AB5FBF3F203FBB9 -:104D400012556DB9302383F311882B462A46294624 -:104D5000FFF730FE85F311880A2384F84C300EE00B -:104D6000142384F84C30302383F3118800231A462F -:104D700019462046FFF70CFE002383F3118838BD47 -:104D8000836D03B198470023E7E70021204601F037 -:104D9000EBFA0021204601F0DDFA63681B6813B1CD -:104DA0000621204698470623D7E7000010B590F863 -:104DB0004C30142B044629D017D8062B05D001D827 -:104DC0001BB110BD093B022BFBD80021204601F08E -:104DD000CBFA0021204601F0BDFA63681B6813B1CD -:104DE000062120469847062319E0152BE9D10B230D -:104DF00080F84C30302383F3118800231A4619467B -:104E0000FFF7D8FD002383F31188DAE7C3689B69B5 -:104E10005B68002BD5D1836D03B19847002384F8DC -:104E20004C30CEE700230375826803691B689968DC -:104E30009142FBD25A68036042601060586070472C -:104E400000230375826803691B6899689142FBD847 -:104E50005A680360426010605860704708B50846A1 -:104E6000302383F311880B7D032B05D0042B0DD049 -:104E70002BB983F3118808BD8B6900221A604FF0AB -:104E8000FF338361FFF7CEFF0023F2E7D1E9003261 -:104E900013605A60F3E70000FFF7C4BF054BD96801 -:104EA0000875186802681A60536001220275D8609C -:104EB000FBF7B2BBF84D002030B50C4BDD684B1C46 -:104EC00087B004460FD02B46094A684600F084F9A3 -:104ED0002046FFF7E3FF009B13B1684600F086F918 -:104EE000A86907B030BDFFF7D9FFF9E7F84D0020FA -:104EF0005D4E0008044B1A68DB6890689B68984216 -:104F000094BF002001207047F84D0020084B10B5D9 -:104F10001C68D86822681A60536001222275DC6020 -:104F2000FFF78EFF01462046BDE81040FBF774BB3B -:104F3000F84D0020044B1A68DB6892689B689A421F -:104F400001D9FFF7E3BF7047F84D002038B5074C93 -:104F500007490848012300252370656001F006FC1D -:104F60000223237085F3118838BD00BF60500020F4 -:104F700044700008F84D002008B572B6044B18655F -:104F800000F052FC00F006FD024B03221A70FEE70F -:104F9000F84D00206050002000F05EB9EFF3118062 -:104FA00020B9EFF30583302282F3118870470000A7 -:104FB00010B530B9EFF30584C4F3080414B180F3DD -:104FC000118810BDFFF7B6FF84F31188F9E70000E0 -:104FD000034A516853685B1A9842FBD8704700BF78 -:104FE000001000E08B60022308618B820846704746 -:104FF0008368A3F1840243F8142C026943F8442C1B -:10500000426943F8402C094A43F8242CC26843F80B -:10501000182C022203F80C2C002203F80B2C044A53 -:1050200043F8102CA3F12000704700BF31060008A0 -:10503000F84D002008B5FFF7DBFFBDE80840FFF79B -:105040002BBF0000024BDB6898610F20FFF726BFE3 -:10505000F84D0020302383F31188FFF7F3BF0000E1 -:1050600008B50146302383F311880820FFF724FF99 -:10507000002383F3118808BD064BDB6839B1426811 -:1050800018605A60136043600420FFF715BF4FF0AB -:10509000FF307047F84D00200368984206D01A6828 -:1050A0000260506099611846FFF7F6BE7047000035 -:1050B00038B504460D462068844200D138BD0368E7 -:1050C00023605C608561FFF7E7FEF4E710B50368D5 -:1050D0009C68A2420CD85C688A600B604C602160BE -:1050E000596099688A1A9A604FF0FF33836010BD47 -:1050F0001B68121BECE700000A2938BF0A2170B5B3 -:1051000004460D460A26601901F02AFB01F016FB41 -:10511000041BA54203D8751C2E460446F3E70A2E4D -:1051200004D9BDE87040012001F060BB70BD0000F3 -:10513000F8B5144B0D46D96103F1100141600A2AFC -:105140001969826038BF0A22016048601861A81896 -:10515000144601F0F7FA0A2701F0F0FA431BA342C4 -:10516000064606D37C1C281901F0FAFA2746354674 -:10517000F2E70A2F04D9BDE8F840012001F036BB60 -:10518000F8BD00BFF84D0020F8B506460D4601F009 -:10519000D5FA0F4A134653F8107F9F4206D12A468C -:1051A00001463046BDE8F840FFF7C2BFD169BB6891 -:1051B000441A2C1928BF2C46A34202D92946FFF7CE -:1051C0009BFF224631460348BDE8F840FFF77EBF0B -:1051D000F84D0020084E002010B4C0E9032300233E -:1051E0005DF8044B4361FFF7CFBF000010B5194CC9 -:1051F000236998420DD0D0E90032816813605A606B -:105200009A680A449A60002303604FF0FF33A36159 -:1052100010BD2346026843F8102F5360002202603D -:1052200022699A4203D1BDE8104001F093BA936815 -:1052300081680B44936001F081FA2269E169926808 -:10524000441AA242E4D91144BDE81040091AFFF7FC -:1052500053BF00BFF84D00202DE9F047DFF8BC80B8 -:1052600008F110072C4ED8F8105001F067FAD8F862 -:105270001C40AA68031B9A423ED81444D5E9003268 -:105280004FF00009C8F81C4013605A60C5F8009040 -:10529000D8F81030B34201D101F05CFA89F31188DB -:1052A000D5E9033128469847302383F311886B6989 -:1052B000002BD8D001F042FA6A69A0EB04094A45F4 -:1052C00082460DD2022001F091FA0022D8F8103067 -:1052D000B34208D151462846BDE8F047FFF728BF42 -:1052E000121A2244F2E712EB090938BF4A4629464E -:1052F0003846FFF7EBFEB5E7D8F81030B34208D0D8 -:105300001444211AC8F81C00A960BDE8F047FFF753 -:10531000F3BEBDE8F08700BF084E0020F84D002026 -:1053200000207047FEE70000704700004FF0FF309C -:105330007047000002290CD0032904D00129074836 -:1053400018BF00207047032A05D8054800EBC200AB -:105350007047044870470020704700BF3071000854 -:1053600038230020E470000870B59AB0054608465E -:1053700001A9144600F0C2F801A8FCF7EBFB431C9E -:105380005B00C5E900340022237003236370C6B2BA -:1053900001AB02341046D1B28E4204F1020401D8AE -:1053A0001AB070BD13F8011B04F8021C04F8010CBC -:1053B0000132F0E708B5302383F311880348FFF783 -:1053C0001BFA002383F3118808BD00BF685000203A -:1053D00090F85C3003F01F02012A07D190F85D209D -:1053E0000B2A03D10023C0E9143315E003F0600356 -:1053F000202B08D1B0F860302BB990F85D20212A1D -:1054000003D81F2A04D8FFF7D9B9222AEBD0FAE72C -:10541000034A02650722426583650120704700BF89 -:105420002F23002007B5052917D8DFE801F019164A -:1054300003191920302383F31188104A01900121A8 -:10544000FFF780FA01980E4A0221FFF77BFA0D4818 -:10545000FFF79EF9002383F3118803B05DF804FB86 -:10546000302383F311880748FFF768F9F2E7302308 -:1054700083F311880348FFF77FF9EBE78470000896 -:10548000A87000086850002038B50C4D0C4C0D4930 -:105490002A4604F10800FFF767FF05F1CA0204F18C -:1054A00010000949FFF760FF05F5CA7204F1180002 -:1054B0000649BDE83840FFF757BF00BF3055002010 -:1054C0003823002050700008617000087A700008CE -:1054D00070B5044608460D46FCF73CFBC6B22046B4 -:1054E000013403780BB9184670BD32462946FCF7E3 -:1054F0001DFB0028F3D10120F6E700002DE9F0475D -:1055000005460C46FCF726FB2B49C6B22846FFF79A -:10551000DFFF08B10E36F6B228492846FFF7D8FF5C -:1055200008B11036F6B2632E0BD8DFF88C80DFF8A6 -:105530008C90234FDFF894A02E7846B92670BDE8F2 -:10554000F08729462046BDE8F04701F0B9BC252E7A -:105550002ED1072241462846FCF7E8FA70B9194BCC -:10556000224603F1140153F8040B42F8040B8B425A -:10557000F9D11B78137007351534DDE70822494649 -:105580002846FCF7D3FA98B90F4BA21C19780909E1 -:105590000232C95D02F8041C13F8011B01F00F016F -:1055A0005345C95D02F8031CF0D118340835C3E730 -:1055B00004F8016B0135BFE7507100087A700008EC -:1055C0006E71000858710008107AFF1F1C7AFF1FC7 -:1055D000BFF34F8F024AD368DB03FCD4704700BF90 -:1055E000003C024008B5094B1B7873B9FFF7F0FF88 -:1055F000074B1A69002ABFBF064A5A6002F1883277 -:105600005A601A6822F480621A6008BD8E57002022 -:10561000003C02402301674508B50B4B1B7893B94A -:10562000FFF7D6FF094B1A6942F000421A611A6867 -:1056300042F480521A601A6822F480521A601A6882 -:1056400042F480621A6008BD8E570020003C024080 -:105650000728F0B516D80C4C0C4923787BB90C4DB3 -:105660000E4608234FF0006255F8047B46F8042BE1 -:10567000013B13F0FF033A44F6D10123237051F8A4 -:105680002000F0BD0020FCE7B0570020905700201C -:1056900080710008014B53F82000704780710008AA -:1056A00008207047072810B5044601D9002010BD16 -:1056B000FFF7CEFF064B53F824301844C21A0BB93B -:1056C0000120F4E712680132F0D1043BF6E700BF95 -:1056D00080710008072810B5044621D8FFF778FF2D -:1056E000FFF780FF0F4AF323D360C300DBB243F41C -:1056F000007343F002031361136943F480331361B1 -:10570000FFF766FFFFF7A4FF074B53F8241000F0E4 -:105710003DF9FFF781FF2046BDE81040FFF7C2BF0B -:10572000002010BD003C024080710008F8B512F066 -:105730000103144642D185182E4A954257D82E4B64 -:105740001B6813F0010352D02C4DFFF74BFFF323DE -:10575000EB60FFF73DFF40F20127032C15D824F042 -:1057600001046618254C401A40F20117B142236922 -:1057700000EB010524D123F001032361FFF74CFF67 -:105780000120F8BD043C0430E7E78307E7D12B692B -:1057900023F440732B612B693B432B6151F8046B5D -:1057A0000660BFF34F8FFFF713FF03689E42E9D0F7 -:1057B0002B6923F001032B61FFF72EFF0020E0E7A8 -:1057C00023F44073236123693B4323610B882B80BF -:1057D000BFF34F8FFFF7FCFE2D8831F8023BADB2CF -:1057E000AB42C3D0236923F001032361E4E71846E9 -:1057F000C7E700BF0000080800380240003C024034 -:10580000084908B50B7828B11BB9FFF7EBFE012357 -:105810000B7008BD002BFCD0BDE808400870FFF7F6 -:10582000FBBE00BF8E5700204FF480214FF0005088 -:1058300000F0AEB80846114601F0A6BA012001F00A -:10584000A3BA0000084601F0BDBA000070B582B0EE -:10585000FFF7A4FB0E4E054600F070FF3268904241 -:1058600037BF0C4A0B49516814682EBFD1E900417B -:10587000013151600419034641F1000128460191AC -:105880003360FFF795FB0199204602B070BD00BF61 -:10589000B4570020B857002070B582B0FFF77EFBE8 -:1058A000104E054600F04AFF3268904237BF0E4A5C -:1058B0000D49516814682EBFD1E900410131516092 -:1058C000041941F100010346284601913360FFF7B6 -:1058D0006FFB01994FF47A7200232046FAF788FC97 -:1058E00002B070BDB4570020B857002010B5024474 -:1058F000064BD2B2904200D110BD441C00B253F806 -:10590000200041F8040BE0B2F4E700BF502800404B -:105910000F4B30B51C6F240407D41C6F44F4007483 -:105920001C671C6F44F400441C670A4C236843F452 -:10593000807323600244084BD2B2904200D130BD44 -:10594000441C00B251F8045B43F82050E0B2F4E785 -:1059500000380240007000405028004007B5012286 -:1059600001A90020FFF7C2FF019803B05DF804FB16 -:1059700013B50446FFF7F2FFA04205D0012201A9AA -:1059800000200194FFF7C4FF02B010BD7047000073 -:105990007047000070470000074B45F255521A60EF -:1059A00002225A6040F6FF729A604CF6CC421A60AE -:1059B000024B01221A70704700300040C45700208B -:1059C000034B1B781BB1034B4AF6AA221A6070479F -:1059D000C457002000300040034B1A681AB9034A2C -:1059E000D2F874281A607047C05700200030024077 -:1059F000024B4FF08072C3F87428704700300240A9 -:105A000008B5FFF7E9FF024B1868C0F3407008BD06 -:105A1000C057002008B5FFF7DFFF024B1868C0F33E -:105A2000007008BDC057002070470000FEE700006E -:105A30000A4B0B480B4A90420BD30B4BDA1C121A41 -:105A4000C11E22F003028B4238BF00220021FCF766 -:105A500089B853F8041B40F8041BECE78473000872 -:105A6000E0580020E0580020E058002070B5D0E950 -:105A70001B439E6800224FF0FF3504EB4213510197 -:105A8000D3F800090028BEBFD3F8000940F08040D9 -:105A9000C3F80009D3F8000B0028BEBFD3F8000BF1 -:105AA00040F08040C3F8000B013263189642C3F8FF -:105AB0000859C3F8085BE0D24FF00113C4F81C3852 -:105AC00070BD0000890141F02001016103699B065E -:105AD000FCD41220FFF77CBA10B5054C2046FEF727 -:105AE0000DFF4FF0A043E366024B236710BD00BFDC -:105AF000C8570020C471000870B50378012B054613 -:105B000050D12A4BC46E98421BD1294B5A6B42F09C -:105B100080025A635A6D42F080025A655A6D5A6982 -:105B200042F080025A615A6922F080025A610E21C5 -:105B300043205B69FEF750FB1E4BE3601E4BC4F82D -:105B400000380023C4F8003EC0232360EE6E4FF4FB -:105B50000413A3633369002BFCDA012333610C20A7 -:105B6000FFF736FA3369DB07FCD41220FFF730FA6F -:105B70003369002BFCDA0026A6602846FFF776FF83 -:105B80006B68C4F81068DB68C4F81468C4F81C6853 -:105B90004BB90A4BA3614FF0FF336361A36843F035 -:105BA0000103A36070BD064BF4E700BFC857002097 -:105BB000003802404014004003002002003C30C086 -:105BC000083C30C0F8B5C46E054600212046FFF7FA -:105BD00079FF296F00234FF001128F68C4F8343821 -:105BE0004FF00066C4F81C284FF0FF3004EB43125E -:105BF00001339F42C2F80069C2F8006BC2F808097D -:105C0000C2F8080BF2D20B68EA6E6B67636210236E -:105C10001361166916F01006FBD11220FFF7D8F9B0 -:105C2000D4F8003823F4FE63C4F80038A36943F4C1 -:105C3000402343F01003A3610923C4F81038C4F8CB -:105C400014380A4BEB604FF0C043C4F8103B084BCC -:105C5000C4F8003BC4F81069C4F800396B6F03F155 -:105C6000100243F480136A67A362F8BDA0710008B4 -:105C700040800010C26E90F86610D2F8003823F40D -:105C8000FE6343EA0113C2F8003870472DE9F84378 -:105C900000EB8103C56EDA68166806F00306731E12 -:105CA000022B05EB41130C4680460FFA81F94FEAAF -:105CB00041104FF00001C3F8101B4FF0010104F137 -:105CC000100398BFB60401FA03F391698EBF334EF7 -:105CD00006F1805606F5004600293AD0578A04F1AD -:105CE0005801490137436F50D5F81C180B43C5F8CC -:105CF0001C382B180021C3F8101953690127611EA5 -:105D0000A7409BB3138A928B9B08012A88BF5343F9 -:105D1000D8F87420981842EA034301F1400205EBD9 -:105D20008202C8F87400214653602846FFF7CAFE75 -:105D300008EB8900C3681B8A43EA84534834640132 -:105D40001E432E51D5F81C381F43C5F81C78BDE8FA -:105D5000F88305EB4917D7F8001B21F40041C7F879 -:105D6000001BD5F81C1821EA0303C0E704F13F0328 -:105D700005EB83030A4A5A6028462146FFF7A2FE34 -:105D800005EB4910D0F8003923F40043C0F800397E -:105D9000D5F81C3823EA0707D7E700BF00800010BA -:105DA00000040002026F12684267FFF75FBE000046 -:105DB0005831C36E49015B5813F4004004D013F40A -:105DC000001F0CBF02200120704700004831C36E45 -:105DD00049015B5813F4004004D013F4001F0CBFBA -:105DE000022001207047000000EB8101CB68196A96 -:105DF0000B6813604B6853607047000000EB810331 -:105E000030B5DD68AA691368D36019B9402B84BF27 -:105E1000402313606B8A1468C26E1C44013CB4FBBF -:105E2000F3F46343033323F0030302EB411043EA2B -:105E3000C44343F0C043C0F8103B2B6803F0030396 -:105E4000012B09B20ED1D2F8083802EB411013F43D -:105E5000807FD0F8003B14BF43F0805343F00053E1 -:105E6000C0F8003B02EB4112D2F8003B43F0044380 -:105E7000C2F8003B30BD00002DE9F041244DEE6E2C -:105E800006EB40130446D3F8087BC3F8087B3807B9 -:105E90000AD5D6F81438190706D505EB8403214630 -:105EA000DB6828465B689847FA071FD5D6F8143890 -:105EB000DB071BD505EB8403D968CCB98B69488A0D -:105EC0005A68B2FBF0F600FB16228AB91868DA6845 -:105ED00090420DD2121AC3E90024302383F31188B3 -:105EE0000B482146FFF78AFF84F31188BDE8F08153 -:105EF000012303FA04F26B8923EA02036B81CB6866 -:105F0000002BF3D021460248BDE8F041184700BFFE -:105F1000C857002000EB810370B5DD68C36E6C6963 -:105F20002668E6604A0156BB1A444FF40020C2F8C6 -:105F300010092A6802F00302012A0AB20ED1D3F82E -:105F4000080803EB421410F4807FD4F8000914BF52 -:105F500040F0805040F00050C4F8000903EB4212BA -:105F6000D2F8000940F00440C2F80009D3F8340820 -:105F7000012202FA01F10143C3F8341870BD19B9C6 -:105F8000402E84BF4020206020682E8A8419013C66 -:105F9000B4FBF6F440EAC44040F000501A44C6E7AF -:105FA0002DE9F8433B4DEE6E06EB40130446D3F863 -:105FB0000889C3F8088918F0010F4FEA40171AD072 -:105FC000D6F81038DB0716D505EB8003D9684B6986 -:105FD0001868DA68904230D2121A4FF000091A603D -:105FE000C3F80490302383F3118821462846FFF735 -:105FF00091FF89F3118818F0800F1CD0D6F834383F -:106000000126A640334216D005EB8403ED6ED3F88B -:106010000CC0DCF814200134E4B2D2F800E005EB47 -:1060200004342F445168714515D3D5F8343823EA28 -:106030000606C5F83468BDE8F883012303FA04F2C4 -:106040002B8923EA02032B818B68002BD3D02146B6 -:1060500028469847CFE7BCF81000AEEB0103834217 -:1060600028BF0346D7F8180980B2B3EB800FE2D8F7 -:106070009068A0F1040959F8048FC4F80080A0EBDF -:1060800009089844B8F1040FF5D818440B449060FF -:106090005360C7E7C85700202DE9F74FAC4CE56EB9 -:1060A0006E69AB691E4016F480586E6107D02046B9 -:1060B000FEF792FC03B0BDE8F04FFDF76FBF002E76 -:1060C00012DAD5F8003EA2489B071EBFD5F8003E65 -:1060D00023F00303C5F8003ED5F8043823F001038C -:1060E000C5F80438FEF7A4FC370505D59848FFF736 -:1060F000BDFC9748FEF78AFCB0040CD5D5F80838EB -:1061000013F0060FEB6823F470530CBF43F41053E5 -:1061100043F4A053EB6031071BD56368DB681BB900 -:10612000AB6923F00803AB612378052B0CD1D5F8BC -:10613000003E87489A071EBFD5F8003E23F00303B0 -:10614000C5F8003EFEF774FC6368DB680BB180485D -:106150009847F30200F18980B70227D5D4F86C90F4 -:10616000DFF8ECB100274FF0010A09EB4712D2F833 -:10617000003B03F44023B3F5802F11D1D2F8003B4C -:10618000002B0DDA62890AFA07F322EA030363811E -:1061900004EB8703DB68DB6813B139465846984740 -:1061A000236F01379B68FFB29F42DED9F00617D5F7 -:1061B000E76E3A6AC2F30A1002F00F0302F4F0121B -:1061C000B2F5802F00F09980B2F5402F08D104EB92 -:1061D00083030022DB681B6A07F5805790427ED15B -:1061E0003303D5F818481DD5E70302D50020FFF783 -:1061F00043FEA50302D50120FFF73EFE600302D552 -:106200000220FFF739FE210302D50320FFF734FEF9 -:10621000E20202D50420FFF72FFEA30202D50520DB -:10622000FFF72AFE77037FF545AFE60702D500208A -:10623000FFF7B6FEA50702D50120FFF7B1FE600704 -:1062400002D50220FFF7ACFE210702D50320FFF79D -:10625000A7FEE20602D50420FFF7A2FEA3067FF503 -:1062600029AF0520FFF79CFE24E7E36EDFF8E0A0EE -:10627000019300274FF00109236F9B685FFA87FBAA -:106280009B453FF669AF019B03EB4B13D3F8001915 -:1062900001F44021B1F5802F1FD1D3F80019002956 -:1062A0001BDAD3F8001941F09041C3F80019D3F874 -:1062B00000190029FBDB5946E06EFFF703FC21893A -:1062C00009FA0BF321EA0303238104EB8B03DB6858 -:1062D0009B6813B15946504698470137CCE7910760 -:1062E00008BFD7F80080072A98BF03F8018B02F196 -:1062F000010298BF4FEA182870E7023304EB8302CB -:1063000007F580575268D2F818C0DCF80820DCE99D -:10631000001CA1EB0C0C002188420AD104EB830481 -:1063200063689B699A6802449A605A6802445A609A -:1063300056E711F0030F08BFD7F800808C4588BFDF -:1063400002F8018B01F1010188BF4FEA1828E3E749 -:10635000C8570020C36E03EB4111D1F8003B43F452 -:106360000013C1F8003B7047C36E03EB4111D1F835 -:10637000003943F40013C1F800397047C36E03EBD2 -:106380004111D1F8003B23F40013C1F8003B7047E2 -:10639000C36E03EB4111D1F8003923F40013C1F8A7 -:1063A0000039704730B5039C0172043304FB0325A8 -:1063B000C0E90653049B03630021059BC160C0E94B -:1063C0000000C0E90422C0E90842C0E90A114363A1 -:1063D00030BD0000416A0022C0E90411C0E90A2270 -:1063E000C2606FF00101FEF763BE0000D0E9043225 -:1063F000934201D1C2680AB9181D70470020704746 -:1064000003691960C2680132C260C26913448269BB -:106410000361934224BF436A03610021FEF73CBE3F -:1064200038B504460D46E3683BB16269131D126836 -:10643000A3621344E362002007E0237A33B92946BC -:106440002046FEF719FE0028EDDA38BD6FF0010096 -:10645000FBE70000C368C269013BC36043691344A2 -:1064600082694361934224BF436A4361002383628C -:10647000036B03B11847704770B53023044683F3AC -:106480001188866A3EB9FFF7CBFF054618B186F33F -:106490001188284670BDA36AE26A13F8015BA36203 -:1064A000934202D32046FFF7D5FF002383F31188E0 -:1064B000EFE700002DE9F84F04460E4617469846D0 -:1064C0004FF0300989F311880025AA46D4F828B086 -:1064D000BBF1000F09D141462046FFF7A1FF20B1D3 -:1064E0008BF311882846BDE8F88FD4E90A12A7EB90 -:1064F000050B521A934528BF9346BBF1400F1BD999 -:10650000334601F1400251F8040B43F8040B914269 -:10651000F9D1A36A40334036A3624035D4E90A2357 -:106520009A4202D32046FFF795FF8AF31188BD42B5 -:10653000D8D289F31188C9E730465A46FBF7ECFAFE -:10654000A36A5B445E44A3625D44E7E710B5029C26 -:106550000172043303FB0421C0E906130023C0E9E0 -:106560000A33039B0363049BC460C0E90000C0E9D5 -:106570000422C0E90842436310BD0000026AC26001 -:10658000426AC0E904220022C0E90A226FF0010138 -:10659000FEF78EBDD0E904239A4201D1C26822B928 -:1065A000184650F8043B0B60704700231846FAE782 -:1065B000C368C2690133C36043691344826943619C -:1065C000934224BF436A43610021FEF765BD00008A -:1065D00038B504460D46E3683BB123691A1DA26233 -:1065E000E2691344E362002007E0237A33B92946C5 -:1065F0002046FEF741FD0028EDDA38BD6FF00100BE -:10660000FBE7000003691960C268013AC260C26911 -:10661000134482690361934224BF436A03610023E8 -:106620008362036B03B118477047000070B53023D5 -:106630000D460446114683F31188866A2EB9FFF78A -:10664000C7FF10B186F3118870BDA36A1D70A36ADD -:10665000E26A01339342A36204D3E169204604391C -:10666000FFF7D0FF002080F31188EDE72DE9F84F08 -:1066700004460D46904699464FF0300A8AF3118839 -:106680000026B346A76A4FB949462046FFF7A0FF48 -:1066900020B187F311883046BDE8F88FD4E90A07A6 -:1066A0003A1AA8EB0607974228BF1746402F1BD976 -:1066B00005F1400355F8042B40F8042B9D42F9D115 -:1066C000A36A4033A3624036D4E90A239A4204D332 -:1066D000E16920460439FFF795FF8BF311884645A1 -:1066E000D9D28AF31188CDE729463A46FBF714FA46 -:1066F000A36A3B443D44A3623E44E5E7D0E904235A -:106700009A4217D1C3689BB1836A8BB1043B9B1A31 -:106710000ED01360C368013BC360C3691A44836928 -:1067200002619A4224BF436A03610023836201230A -:10673000184670470023FBE700F0CCB84FF08043C9 -:10674000586A70474FF08043002258631A61022252 -:10675000DA6070474FF080430022DA607047000033 -:106760004FF0804358637047FEE7000070B51B4B45 -:1067700001630025044686B0586085620E46FDF729 -:10678000E9FB04F11003C4E904334FF0FF33C4E91B -:106790000635C4E90044A560E562FFF7CFFF2B464C -:1067A0000246C4E9082304F134010D4A256580231B -:1067B0002046FEF717FC0123E0600A4A03750092A9 -:1067C00072680192B268CDE90223074B6846CDE9B1 -:1067D0000435FEF72FFC06B070BD00BF60500020EE -:1067E000D0710008D571000869670008024AD36AB1 -:1067F0001843D062704700BFF84D00204B684360DB -:106800008B688360CB68C3600B6943614B6903622B -:106810008B6943620B6803607047000008B5234B27 -:1068200023481A6942F0FF021A611A6922F0FF0236 -:106830001A611A691A6B42F0FF021A631A6D42F06C -:10684000FF021A651B4A1B6D1146FFF7D7FF02F1C5 -:106850001C0100F58060FFF7D1FF02F1380100F55F -:106860008060FFF7CBFF02F1540100F58060FFF775 -:10687000C5FF02F1700100F58060FFF7BFFF02F174 -:106880008C0100F58060FFF7B9FF02F1A80100F567 -:106890008060FFF7B3FF02F1C40100F58060FFF7ED -:1068A000ADFFBDE8084000F08FB800BF00380240DF -:1068B00000000240DC71000808B500F01BFAFEF78A -:1068C00045FBFFF789F8BDE80840FEF7DDBD000095 -:1068D000704700000F4B1A6C42F001021A641A6EE6 -:1068E00042F001021A660C4A1B6E936843F00103E2 -:1068F00093604FF0804331229A624FF0FF32DA62A8 -:1069000000229A615A63DA605A6001225A611A6061 -:10691000704700BF00380240002004E04FF0804282 -:1069200008B51169D3680B40D9B2C9439B071161FF -:1069300007D5302383F31188FEF72EFB002383F362 -:10694000118808BD1E4B1A6962F0FF021A611A69AC -:10695000D2B21A614FF0FF301A695A6958610021AA -:106960005A6959615A691A6A62F080521A621A6A3F -:1069700002F080521A621A6A5A6A58625A6A596256 -:106980005A6A1A6C42F080521A641A6E42F08052AF -:106990001A661A6E0B4A106840F480701060186F07 -:1069A00000F44070B0F5007F1EBF4FF480301867D0 -:1069B0001967536823F40073536000F073B900BF84 -:1069C00000380240007000403B4B3C4A1A643C4A8D -:1069D0004FF4404111601A6842F001021A601A68CF -:1069E0009007FCD59A6822F003029A60324B9A68AD -:1069F00012F00C02FBD1196801F0F90119609A60DC -:106A00001A6842F480321A601A689103FCD55A6FF2 -:106A100042F001025A67284B5A6F9207FCD5294A67 -:106A20005A601A6842F080721A60254A5368580406 -:106A3000FCD5214B1A689101FCD5234AC3F8842068 -:106A40001A6842F080621A601A681201FCD51F4A67 -:106A50009A600322C3F88C204FF00062C3F89420A0 -:106A60001B4B1A681B4B9A421B4B21D11B4A1168C6 -:106A70001B4A91421CD140F203121A60164A136855 -:106A800003F00F03032BFAD10B4B9A6842F002027A -:106A90009A609A6802F00C02082AFAD15A6C42F401 -:106AA00080425A645A6E42F480425A665B6E704766 -:106AB00040F20372E1E700BF00380240000400101A -:106AC00000700040081940021030002400948838FB -:106AD000002004E011640020003C024000ED00E0D2 -:106AE00041C20F41074A08B5536903F001035361DE -:106AF00023B1054A13680BB150689847BDE80840B8 -:106B0000FDF74CBA003C014058580020074A08B530 -:106B1000536903F00203536123B1054A93680BB133 -:106B2000D0689847BDE80840FDF738BA003C0140FE -:106B300058580020074A08B5536903F0040353610D -:106B400023B1054A13690BB150699847BDE8084065 -:106B5000FDF724BA003C014058580020074A08B508 -:106B6000536903F00803536123B1054A93690BB1DC -:106B7000D0699847BDE80840FDF710BA003C0140D5 -:106B800058580020074A08B5536903F010035361B1 -:106B900023B1054A136A0BB1506A9847BDE8084013 -:106BA000FDF7FCB9003C014058580020164B10B5C9 -:106BB0005C6904F478725A61A30604D5134A936A97 -:106BC0000BB1D06A9847600604D5104A136B0BB11D -:106BD000506B9847210604D50C4A936B0BB1D06BD0 -:106BE0009847E20504D5094A136C0BB1506C9847DD -:106BF000A30504D5054A936C0BB1D06C9847BDE84A -:106C00001040FDF7CBB900BF003C014058580020B0 -:106C1000194B10B55C6904F47C425A61620504D5D5 -:106C2000164A136D0BB1506D9847230504D5134ACE -:106C3000936D0BB1D06D9847E00404D50F4A136EE5 -:106C40000BB1506E9847A10404D50C4A936E0BB15A -:106C5000D06E9847620404D5084A136F0BB1506F89 -:106C60009847230404D5054A936F0BB1D06F98471A -:106C7000BDE81040FDF792B9003C01405858002093 -:106C800008B50348FDF726FABDE80840FDF786B9C8 -:106C9000884B002008B5FFF741FEBDE80840FDF72E -:106CA0007DB90000062108B50846FDF795FA0621D2 -:106CB0000720FDF791FA06210820FDF78DFA06213D -:106CC0000920FDF789FA06210A20FDF785FA062139 -:106CD0001720FDF781FA06212820FDF77DFA07210C -:106CE0001C20FDF779FABDE808400C212520FDF7AE -:106CF00073BA000008B5FFF725FE00F00DF8FDF7A8 -:106D000013FCFDF7F9FDFDF7D1FCFFF7E1FDBDE850 -:106D10000840FFF711BD00000023054A1946013362 -:106D2000102BC2E9001102F10802F8D1704700BF30 -:106D3000585800200B460146184600F02DB80000B8 -:106D400000F040B8012838BF012010B504462046A5 -:106D500000F030F830B900F007F808B900F00CF88E -:106D60008047F4E710BD0000024B1868BFF35B8F4B -:106D7000704700BFD858002008B5062000F084F8FE -:106D80000120FEF7CFFA0000024B0A4601461868C0 -:106D9000FEF750BD5823002010B5054C13462CB10A -:106DA0000A4601460220AFF3008010BD2046FCE7F2 -:106DB00000000000024B01461868FEF73FBD00BF0F -:106DC00058230020024B01461868FEF73BBD00BF68 -:106DD0005823002010B501390244904201D100200F -:106DE00005E0037811F8014FA34201D0181B10BD34 -:106DF0000130F2E72DE9F041A3B1C91A1778014437 -:106E0000044603F1FF3C8C42204601D9002009E0F2 -:106E10000578BD4204F10104F5D10CEB0405D61848 -:106E2000A54201D1BDE8F08115F8018D16F801EDFC -:106E3000F045F5D0E7E700001F2938B504460D46B8 -:106E400004D9162303604FF0FF3038BD426C12B1F5 -:106E500052F821304BB9204600F030F82A4601465E -:106E60002046BDE8384000F017B8012B0AD0591C65 -:106E700003D1162303600120E7E7002442F82540F0 -:106E8000284698470020E0E7024B01461868FFF7C4 -:106E9000D3BF00BF5823002038B5074D0023044658 -:106EA000084611462B60FEF741FA431C02D12B68BD -:106EB00003B1236038BD00BFDC580020FEF730BAB4 -:106EC000034611F8012B03F8012B002AF9D1704772 -:106ED000696E2E7369657272616165726F7370613C -:106EE00063652E507265636973696F6E506F696E6A -:106EF0007400000053544D3332463F3F3F0053541B -:106F00004D3332463430780053544D3332463432A8 -:106F1000780053544D33324634343658580000000C -:106F2000012033000010410001105A0003105900E5 -:106F30000710310000000000F46E00081304000088 -:106F4000FE6E000819040000086F0008210400000C -:106F5000126F000840A2E4F1646891060041A3E5C5 -:106F6000F2656992070000004261642043414E4986 -:106F70006661636520696E6465782E00800000009C -:106F80000080000000008000000000000000000001 -:106F9000A52400088D2C0008ED2B0008B52400085E -:106FA000E9240008E5260008B9240008C9240008DF -:106FB000BD240008C5240008C12400080D260008CF -:106FC000CD240008592F0008DD240008E125000821 -:106FD000009600000000000000000000000000001B -:106FE0000000000000000000E9440008D54400084B -:106FF00011450008FD44000809450008F544000853 -:10700000E1440008CD4400081D45000800000000D0 -:107010002946000815460008514600083D4600086C -:107020004946000835460008214600080D4600087C -:107030005D460008000000000100000000000000A4 -:107040006330000040700008504E00206050002067 -:10705000536965727261204165726F737061636517 -:10706000005369657272612D507265636973696F4F -:107070006E506F696E742D424C0025534552494144 -:107080004C250000020000000000000045480008F8 -:10709000B148000840004000005500201055002075 -:1070A00002000000000000000300000000000000DB -:1070B000F5480008000000001000000020550020E6 -:1070C000000000000100000000000000C857002080 -:1070D000010102002554000835530008D15300086F -:1070E000B553000843000000EC700008090243009B -:1070F000020100C03209040000010202010005245F -:1071000000100105240100010424020205240600E8 -:1071100001070582030800FF09040100020A0000BC -:107120000007050102400000070581024000000041 -:107130001200000038710008120110010200004026 -:10714000091241570002010203010000040309046F -:1071500025424F41524425005369657272612D509A -:107160007265636973696F6E506F696E7400303158 -:1071700032333435363738394142434445460000CE -:1071800000400000004000000040000000400000FF -:1071900000000100000002000000020000000200E8 -:1071A00000000000494A0008014D0008AD4D0008EC -:1071B00040004000405800204058002001000000DE -:1071C0005058002080000000400100000500000031 -:1071D0006D61696E0069646C650000000000002844 -:1071E00000020000AAAAAAAA00000024FFFF0000D3 -:1071F000000000000000000000A00A1500000000D0 -:10720000AAAAAA9600500000FF8F00000000007795 -:10721000880000000510000000000000AA9AAAAA39 -:1072200005000000FFFF000000000000000000005B -:107230000000000000000000AAAAAAAA00000000A6 -:10724000FFFF000000000000000000000000000040 -:1072500000000000AAAAAAAA00000000FFFF000088 -:10726000000000000000000000000000000000001E -:10727000AAAAAAAA00000000FFFF00000000000068 -:10728000000000000000000000000000AAAAAAAA56 -:1072900000000000FFFF00000000000000000000F0 -:1072A00000000000000000000A00000000000000D4 -:1072B000030000000000000000000000648FFF7F5A -:1072C0000100000000000000470400000000000072 -:1072D000000007000000000040420F00FE2A0100ED -:1072E000D2040000FF00000068500020884B0020FE -:1072F0000096000000000800960000000008000052 -:10730000040000004C7100080000000000000000B4 -:10731000000000000000000000000000000000006D -:107320005C230020000000000000000000000000BE -:10733000000000000000000000000000000000004D -:10734000000000000000000000000000000000003D -:10735000000000000000000000000000000000002D -:10736000000000000000000000000000000000001D -:10737000000000000000000000000000000000000D -:047380000000000009 +:1000000000070020F10100086D2C0008252C0008D5 +:100010004D2C0008252C0008452C0008F301000891 +:10002000F3010008F3010008F3010008613C000837 +:10003000F3010008F3010008F3010008F3010008D0 +:10004000F3010008F3010008F3010008F3010008C0 +:10005000F3010008F3010008D5670008FD670008F8 +:10006000256800084D68000875680008F30100085D +:10007000F3010008F3010008F3010008F301000890 +:10008000F3010008F3010008F3010008D92B000870 +:10009000052C0008152C0008F30100089D680008D5 +:1000A000F3010008F3010008F3010008F301000860 +:1000B00085690008F3010008F3010008F301000856 +:1000C000F3010008F3010008F3010008F301000840 +:1000D000F301000871690008F3010008F30100084A +:1000E00001690008F3010008F3010008F3010008AA +:1000F000F3010008F3010008F3010008F301000810 +:10010000F3010008F3010008F3010008F3010008FF +:10011000F3010008F3010008F3010008F3010008EF +:10012000F3010008F3010008F3010008F3010008DF +:10013000F3010008F3010008F3010008F3010008CF +:10014000F3010008F3010008F3010008895D0008CD +:10015000F3010008F3010008F3010008F3010008AF +:10016000F3010008F3010008F3010008F30100089F +:10017000F3010008F3010008F3010008F30100088F +:10018000F3010008F3010008F3010008F30100087F +:10019000F3010008F3010008F3010008F30100086F +:1001A000F3010008F3010008F3010008F30100085F +:1001B000F3010008F3010008F3010008F30100084F +:1001C000F3010008F3010008F3010008F30100083F +:1001D000F3010008F3010008F3010008F30100082F +:1001E0006915000800000000000000000000000089 +:1001F00002E000F000F8FEE772B6374880F30888A6 +:10020000364880F3098836483649086040F20000D5 +:10021000CCF200004EF63471CEF200010860BFF35C +:100220004F8FBFF36F8F40F20000C0F2F0004EF628 +:100230008851CEF200010860BFF34F8FBFF36F8F7C +:100240004FF00000E1EE100A4EF63C71CEF20001D4 +:100250000860062080F31488BFF36F8F05F05CFA06 +:1002600006F054F94FF055301F491B4A91423CBFEC +:1002700041F8040BFAE71D49184A91423CBF41F886 +:10028000040BFAE71A491B4A1B4B9A423EBF51F82E +:10029000040B42F8040BF8E700201849184A914271 +:1002A0003CBF41F8040BFAE705F03AFA06F07CF996 +:1002B000144C154DAC4203DA54F8041B8847F9E797 +:1002C00000F042F8114C124DAC4203DA54F8041B12 +:1002D0008847F9E705F022BA000700200023002034 +:1002E0000000000808ED00E00001002000070020E9 +:1002F000B06F000800230020BC230020C023002092 +:10030000DC580020E0010008E4010008E4010008D6 +:10031000E40100082DE9F04F2DED108AC1F80CD052 +:10032000C3689D46BDEC108ABDE8F08F002383F3BF +:1003300011882846A047002004F0FCFCFEE704F0EA +:100340007BFC00DFFEE70000F8B501F089F905F05D +:100350007DF9074605F0CCF90546A8BB1F4B9F4227 +:1003600032D001339F4232D01D4B27F0FF029A4218 +:1003700030D1F8B200F016FF2E4642F2107400F0B1 +:1003800017FF08B10024264601F04CFD20B10320E0 +:1003900000F07AF80024264635B1124B9F4203D074 +:1003A00005F09EF900242646002005F059F90EB10B +:1003B00000F080F801F0B0FA00F066FF204600F08F +:1003C000DFF800F077F8F9E72E460024D7E7044677 +:1003D0000126D4E706464FF47A74D0E7010007B04F +:1003E000000008B0263A09B008B501F005F9A0F1FF +:1003F00020035842584108BD07B541F212030221BB +:1004000001A8ADF8043001F015F903B05DF804FB64 +:1004100038B5302383F31188174803680BB104F013 +:1004200055FD164A144800234FF47A7104F044FD38 +:10043000002383F31188124C236813B12368013B16 +:100440002360636813B16368013B63600D4D2B78D3 +:1004500033B963687BB9022001F0C8F932236360C5 +:100460002B78032B07D163682BB9022001F0BEF96A +:100470004FF47A73636038BDC02300201104000874 +:10048000E0240020D8230020084B187003280CD843 +:10049000DFE800F008050208022001F09DB9022003 +:1004A00001F090B9024B00225A607047D823002017 +:1004B000E024002010B501F0B5FC30B1294B032237 +:1004C0001A70294B00225A6010BD284B284A1C463E +:1004D00019680131F8D004339342F9D16268254B91 +:1004E0009A42F1D9244B9B6803F1006303F58033F2 +:1004F0009A42E9D205F0C8F805F0DAF8002001F0D8 +:10050000C9F80220FFF7C0FF1C4B1A6C00221A64C6 +:10051000196E1A66196E596C5A64596E5A665A6E7B +:100520005A6942F080025A615A6922F080025A6187 +:100530005A691A6942F000521A611A6922F000528F +:100540001A611B6972B64FF0E0233021C3F8084DE1 +:10055000D4E9003281F311889D4683F3088810475F +:10056000B2E700BFD8230020E024002000000108EB +:1005700020000108FFFF000800230020003802408F +:100580002DE9F04F93B0AC4B00902022FF210AA838 +:100590009D6801F06BF9A94A1378A3B9A848012115 +:1005A00003601170302383F3118803680BB104F0EA +:1005B0008DFCA44AA24800234FF47A7104F07CFC1D +:1005C000002383F31188009B13B19F4B009A1A609C +:1005D0009E4A009C1378032B1EBF002313709A4A77 +:1005E0004FF0000A18BF5360D3465646D14601204B +:1005F00001F0F2F824B1944B1B68002B00F0158237 +:10060000002000F0F9FF0390039B002B01DA00F0BB +:1006100083FE039B002BEDDB012001F0D3F8039B4D +:10062000213B162BE3D801A252F823F089060008DB +:10063000B106000845070008EF050008EF050008AF +:10064000EF050008CF0700089F090008B908000857 +:100650001B0900084309000869090008EF050008A4 +:100660007B090008EF050008ED09000829070008CC +:10067000EF050008310A0008950600082907000860 +:10068000EF0500081B0900080220FFF7ADFE002857 +:1006900040F0F581009B0221BAF1000F08BF1C4613 +:1006A00005A841F21233ADF8143000F0C3FF9EE705 +:1006B0004FF47A7000F0A0FF071EEBDB0220FFF77B +:1006C00093FE0028E6D0013F052F00F2DA81DFE833 +:1006D00007F0030A0D10133605230593042105A81E +:1006E00000F0A8FF17E054480421F9E75848042116 +:1006F000F6E758480421F3E74FF01C08404600F0A5 +:10070000CBFF08F104080590042105A800F092FF32 +:10071000B8F12C0FF2D1012000FA07F747EA0B0BD2 +:100720005FFA8BFB4FF0000901F0ECF826B10BF0FB +:100730000B030B2B08BF0024FFF75EFE57E746486C +:100740000421CDE7002EA5D00BF00B030B2BA1D17C +:100750000220FFF749FE074600289BD0012000F049 +:1007600099FF0220FFF790FE00261FFA86F8404608 +:1007700000F0A0FF044690B10021404600F0B2FF17 +:1007800001360028F1D1BA46044641F21213022183 +:1007900005A8ADF814303E4600F04CFF27E70120D5 +:1007A000FFF772FE2546244B9B68AB4207D92846CB +:1007B00000F072FF013040F067810435F3E7234B0E +:1007C00000251D70204BBA465D603E46ACE7002E0A +:1007D0003FF460AF0BF00B030B2B7FF45BAF0220F9 +:1007E000FFF752FE322000F007FFB0F10008FFF6DD +:1007F00051AF18F003077FF44DAF0F4A926808EB32 +:10080000050393423FF646AFB8F5807F3FF742AF0E +:10081000124B0193B84523DD4FF47A7000F0ECFEE3 +:100820000390039A002AFFF635AF019B039A03F861 +:10083000012B0137EDE700BF00230020DC2400205E +:10084000C023002011040008E0240020D823002049 +:1008500004230020082300200C230020DC23002098 +:10086000C820FFF7C1FD074600283FF413AF1F2D36 +:1008700011D8C5F1200242450AAB25F0030028BF7C +:10088000424683490192184400F0CAFF019A804809 +:10089000FF2100F0EBFF4FEAA8037D490193C8F365 +:1008A0008702284600F0EAFF064600283FF46DAFB5 +:1008B000019B05EB830537E70220FFF795FD002834 +:1008C0003FF4E8AE00F02EFF00283FF4E3AE00272F +:1008D000B846704B9B68BB4218D91F2F11D80A9B92 +:1008E00001330ED027F0030312AA134453F8203C1F +:1008F00005934046042205A901F04CFA04378046CE +:10090000E7E7384600F0C8FE0590F2E7CDF814801E +:10091000042105A800F08EFE06E70023642104A848 +:10092000049300F07DFE00287FF4B4AE0220FFF7B0 +:100930005BFD00283FF4AEAE049800F0DBFE0590AE +:10094000E6E70023642104A8049300F069FE002870 +:100950007FF4A0AE0220FFF747FD00283FF49AAED7 +:10096000049800F0D7FEEAE70220FFF73DFD0028DB +:100970003FF490AE00F0E6FEE1E70220FFF734FD21 +:1009800000283FF487AE05A9142000F0E1FE042101 +:100990000746049004A800F04DFE3946B9E732201E +:1009A00000F02AFE071EFFF675AEBB077FF472AE9D +:1009B000384A926807EB090393423FF66BAE022078 +:1009C000FFF712FD00283FF465AE27F003074F4400 +:1009D000B9453FF4A9AE484600F05EFE04210590FB +:1009E00005A800F027FE09F10409F1E74FF47A7039 +:1009F000FFF7FAFC00283FF44DAE00F093FE00280C +:100A000044D00A9B01330BD008220AA9002000F031 +:100A100035FF00283AD02022FF210AA800F026FF47 +:100A2000FFF7EAFC1C4804F08BF913B0BDE8F08F27 +:100A3000002E3FF42FAE0BF00B030B2B7FF42AAEEE +:100A40000023642105A8059300F0EAFD074600286D +:100A50007FF420AE0220FFF7C7FC804600283FF459 +:100A600019AEFFF7C9FC41F2883004F069F9059826 +:100A700000F090FF464600F045FF3C46B7E50646CD +:100A800052E64FF0000905E6BA467EE637467CE6B8 +:100A9000DC23002000230020A0860100094A1368FF +:100AA00049F2690099B21B0C00FB01331360064B3D +:100AB000186844F2506182B2000C01FB0200186019 +:100AC00080B27047182300201423002010B50021A5 +:100AD0001022044600F0CAFE034B03CB2060616085 +:100AE0001868A06010BD00BF107AFF1F2DE9F0410B +:100AF000ADF5507D0DF13C086EAC40F27512074625 +:100B00000D4610A80021C8F8001000F0AFFE4FF409 +:100B1000C4720021204600F0A9FE02F0AFF8254B78 +:100B20004FF47A72B0FBF2F0186093E807000223EA +:100B300084E807000DF5ED702382FFF7C7FF44F24C +:100B400004731D49238406A806F032F8212384F893 +:100B500032310DF2EB2206AB0DF1380C1E4603CEFE +:100B6000664510605160334602F10802F6D13378D1 +:100B7000137041460122204600F02EFF002303930C +:100B8000AB7E029305F11903019380B20123CDE9F5 +:100B900004800093E97E05A3D3E90023384602F0E0 +:100BA00035FC0DF5507DBDE8F08100BF9E6AC42183 +:100BB000818A46EEE8240020C06B00082DE9F04150 +:100BC0002C4C237ADAB080460D465BBB27A9284619 +:100BD00001F012F80746002842D19DF89D60C82E0A +:100BE0003ED801464FF4A662204600F03FFE4FF487 +:100BF0008073C4F8F8314FF40073C4F80C334FF429 +:100C00004073C4F8203432460DF19E0104F109000E +:100C100000F006FE26449DF89C30777223720BB9D3 +:100C2000EB7E23728122002106AC27A800F01EFE75 +:100C30000122214627A801F01BF800230393AB7E75 +:100C4000029305F1190380B201932823CDE90440F2 +:100C50000093E97E05A3D3E90023404602F0D6FBCA +:100C60005AB0BDE8F08100BFAFF300802641727238 +:100C7000DF25D7B708460020F0B5254E4FF48A751A +:100C800005FB0065F1B096F8D83085F8DC3000241B +:100C9000D822214685F8E8403AA800F0E7FD06F1A1 +:100CA000090000F0DBFDD5F8E4308DF8F000C2B2A9 +:100CB00006AF06F109010DF1F100CDE93A3400F07B +:100CC000AFFD394601223AA800F0FEFF80B2CDE91F +:100CD000047008230127CDE9023706F1D8030193F8 +:100CE00030230093317A0B4807A3D3E9002302F0A5 +:100CF0008DFBA04206DD01F0C1FFC5F8E0003846DB +:100D000071B0F0BD2046FBE778F6339F93CACD8DD6 +:100D100008460020003500202DE9F0411D4D1E4EF3 +:100D20001E4F86B0284602F09DFB034658B30024B0 +:100D3000CDE90344ADF81440027B8DF81420996886 +:100D40004068029403AA03C21B68DFF8548043F092 +:100D50000043029301F094FF821941F100030094D3 +:100D600002A9384601F03CFAA04205DD284602F00F +:100D70007DFB88F80040D5E798F80030072B05D8B0 +:100D8000013388F8003006B0BDE8F081014802F078 +:100D90006DFBF8E70035002040420F0030350020A1 +:100DA0003D4B002070B50D4614461E4602F08AFAEF +:100DB00050B9022E10D1012C0ED112A3D3E9002379 +:100DC000C5E90023012007E0282C10D005D8012C0C +:100DD00009D0052C0FD0002070BD302CFBD10BA307 +:100DE000D3E90023ECE70BA3D3E90023E8E70BA347 +:100DF000D3E90023E4E70BA3D3E90023E0E700BF36 +:100E0000AFF30080401DA12026812A0B78F6339F86 +:100E100093CACD8D9E6AC421818A46EE26417272A4 +:100E2000DF25D7B7F017304A39059E5638B5054645 +:100E30000E4C0021013500F055FCA4F82C55B4F8F7 +:100E40002C0500F037FC78B1B4F82C0500F042FC1A +:100E5000014648B9B4F82C0500F044FCB4F82C3530 +:100E60000133A4F82C35EAE738BD00BF084600205E +:100E700010B50A4B0A4A1A6003F5805393F86020B4 +:100E80003AB9DC6D2CB1204601F04AF8204605F055 +:100E9000CFFDBDE81040034801F042B830350020D6 +:100EA000806C0008784500202DE9F04F8FB000AF2E +:100EB00005460C4602F006FA002849D1237E022B93 +:100EC0001BD1E38A012B18D101F0D8FE0646FFF7AB +:100ED000E5FD03464FF4C870DFF8C482B3FBF0F2BF +:100EE00006F5167602FB103316FA83F3C8F80030C5 +:100EF000E37E33B9A34B00221A703C37BD46BDE8F0 +:100F0000F08F07F12401204600F034FE0028F4D1D0 +:100F100007F11400FFF7DAFD97F8264007F11401F6 +:100F2000224607F1270005F0CDFD0028E2D10F2C65 +:100F300008D8944B1C70D8F80030A3F51673C8F885 +:100F40000030DAE797F82410284602F0B3F9D4E726 +:100F5000E38A282B2BD010D8012B23D0052BCCD102 +:100F6000BFF34F8F8849894BCA6802F4E06213438C +:100F7000CB60BFF34F8F00BFFDE7302BBDD1844E58 +:100F8000E17E327A9142B8D1607E3146002291F8FA +:100F9000DC50854200F0A5800132042A01F58A71F7 +:100FA000F5D1AAE721462846FFF7A0FDA5E721468F +:100FB0002846FFF703FEA0E7B2F8EC507B6005F18E +:100FC00003094FEA99094FEA8902D11DC908A8EB24 +:100FD000C1039D46EB460021584600F047FC04F152 +:100FE000EE012A463144584600F01AFC7B6813B9DA +:100FF000012000F04FFB96F8D20000F05BFB0446A6 +:1010000030B9307200F08EFB204600F043FBB1E0B7 +:10101000D6F8D4203AB996F8D200B6F82C258242F8 +:1010200001D8FFF703FFD6F8D4202A44944208D20F +:1010300096F8D200B6F82C250130824201D8FFF78D +:10104000F5FE70685FFA89F2594600F017FC08B99E +:10105000C54679E0726896F8D2002A447260D6F8E4 +:10106000D42005EB0209C6F8D49000F023FB81459B +:1010700009D396F8D220D6F8D4000132001B86F8A6 +:10108000D220C6F8D400FF2D0FD80024347200F00F +:1010900049FB204600F0FEFA00F0C4FE3D4B1881EB +:1010A00008B9FFF707FAC54627E7BB6896F8D900E5 +:1010B0000AFB0362FB68D2F8E41082F8E83001F51D +:1010C0008061C2F8E030C2F8E410FFF7D5FDFFF709 +:1010D00023FE96F8D920013202F0030286F8D920C7 +:1010E000B6E74FF48A7A0AFB02F505F1EA013144CA +:1010F000204600F015FEF86000287FF4FEAE35446F +:10110000012285F8E82001F0B9FDD5F8E020D6ED00 +:10111000007ADFED216A801A192838BF192040F6BD +:10112000B832904228BF1046B8EE677A07EE900AB0 +:10113000F8EEE77A67EEA67ADFED186AE7EE267A30 +:10114000FCEEE77AC6ED007A96F8D930BB60BA6853 +:1011500073680AFB02F4321992F8E81059B1D2F818 +:10116000E4108B42E8463FF427AF002182F8E810F4 +:10117000C2F8E010C5467368064A9B0A0133138122 +:10118000BBE600BFF934002000ED00E00400FA05E2 +:1011900008460020E8240020CDCCCC3D6666663FA2 +:1011A000FC340020014B1870704700BFF42400206D +:1011B00030B54FF000542B4B22689A4285B007D0CF +:1011C00004F0A0FA044620BB0024204605B030BD40 +:1011D000254B627D25481A70237D03724FF480737E +:1011E000C0F8F8314FF40073C0F80C3300254FF409 +:1011F0004073C0F820341E49C0F8E450C9220930B9 +:1012000000F00EFB2046E022294600F02FFB0124CF +:10121000DBE7184A184D136C43F000731364AA6D92 +:10122000164B9A42D0D12B6E013B7E2BCCD8144A60 +:1012300007CA01AB83E807001846032100F0C0FD90 +:101240006B6D83424FF00003BED12A6D8A4201BF0D +:10125000AB65054B2A6E1A7003BF0A4BEA6D1A6024 +:101260001C46B2E79AAD44C5F4240020084600208D +:101270001600002000380240006600405041A0B037 +:10128000586600401023002037B51A4D00F0CAFD03 +:1012900002236B71184B288119681848012201F04C +:1012A00089FB00230193164B164900931648174BF0 +:1012B0004FF4805201F0D6FF154B197811B1124846 +:1012C00001F0F8FF01F0DAFC0446FFF7E7FB4FF40A +:1012D000C873B0FBF3F202FB130304F5167010FAA7 +:1012E00083F00C4B186004F003FA08B10F232B8134 +:1012F00003B030BDE824002010230020303500204A +:10130000A50D0008F824002000350020A90E0008D3 +:10131000F4240020FC3400202DE9F04F2DED028B49 +:101320000FF23829D9E90089834C93B00BAE9FEDB9 +:101330007E8BFFF7F1FC814FDFF828A200230A9390 +:10134000ADF834300B9373604FF0000B5B468DEDBE +:10135000008B01250DF11D0207A938468DF81C50A0 +:101360008DF81DB001F0D4FA9DF81C30002B40F030 +:10137000A580204601F0A6FF0646002845D1704F03 +:1013800001F07CFC3B6898423FD301F077FC824639 +:10139000FFF784FB4FF4C873B0FBF3F202FB1303B7 +:1013A0000AF5167010FA83F03860664F97F800B0AF +:1013B000CBF1100ABBF1000F14BF33462B465FFA86 +:1013C0008AFA0EA88DF82830FFF780FBBAF1060FD5 +:1013D00028BF4FF0060A0EAB03EB0B0152460DF18E +:1013E000290000F01DFA0AAB0393182302930AF1B7 +:1013F0000102554BD2B2CDE90053049220464CA3D2 +:10140000D3E9002301F0A4FF3E7001F037FC4F4AFE +:101410004F4D1368C31AB3F57A7F2ED3106001F0D5 +:101420002FFC02460B46204602F02AF8204601F027 +:1014300049FF10B32B7A474E002B14BF032302231E +:10144000737101F01BFC0EAF4FF47A730122B0FBF5 +:10145000F3F039463060304600F064FB1823029305 +:101460003D4B019380B240F25513CDE903700093D8 +:1014700042464B46204601F06BFF2B7A93B101F0B8 +:10148000FDFB002607464FF48A7A95F8D9003044D0 +:1014900000F003000AFB005393F8E82092B30136F2 +:1014A000042EF2D1C82003F04BFC2B7A002B7FF4E2 +:1014B0003DAF13B0BDEC028BBDE8F08FDAF814300D +:1014C00083F48053CAF81430594610220EA800F055 +:1014D000CDF90DF11E0308AA0AA9384600F080FFD5 +:1014E00096E803000FAB83E803009DF834308DF8D5 +:1014F00044300A9B0E930EA9DDE90823204602F032 +:1015000093F921E7D3F8E02042B12B68FA2B38BFDA +:10151000FA23BA1A0533B2EB430FC0D3FFF7ACFB83 +:101520000028BCD1BEE700BF0000000000000000A2 +:10153000401DA12026812A0B0035002030350020D7 +:10154000FC340020F9340020F8340020384B00200F +:1015500008460020E82400203C4B0020F1C6A7C12B +:10156000D068080F0004024008B5054800F0D4FF19 +:10157000BDE80840034A0449002005F053BA00BF03 +:10158000303500208C4B0020710E00082DE9F84FFB +:101590004FF47A73DFF85880DFF8589006460D460E +:1015A00002FB03F7002498F900305A1C5FFA84FA12 +:1015B00001D0A34212D159F8240003682A46D3F877 +:1015C00020B031463B46D847854207D1074B012022 +:1015D00083F800A0BDE8F88F0124E4E7002CFBD0DD +:1015E0004FF4FA7003F0ACFB0020F3E7804B0020CF +:1015F0001C2300202023002007B5002302460121E0 +:101600000DF107008DF80730FFF7C0FF20B19DF8FE +:10161000070003B05DF804FB4FF0FF30F9E700006E +:101620000A4608B50421FFF7B1FF80F00100C0B2FF +:10163000404208BD30B4074B0A461978064B53F8B0 +:1016400021402368DD69054B0146AC46204630BC8D +:10165000604700BF804B002020230020A0860100AF +:1016600070B503F09DFE094E094D308000242868B6 +:101670003388834208D903F08DFE2B68044401337C +:10168000B4F5803F2B60F2D370BD00BF824B0020C9 +:10169000404B002003F034BF00F1006000F58030C3 +:1016A0000068704700F10060920000F5803003F0A0 +:1016B000BDBE0000054B1A68054B1B889B1A834270 +:1016C00002D9104403F066BE00207047404B002052 +:1016D000824B0020024B1B68184403F063BE00BF1E +:1016E000404B0020024B1B68184403F073BE00BF40 +:1016F000404B002010F003030AD1B0F5047F05D25F +:1017000000F10050A0F51040D0F80038184670479E +:101710000023FBE700F10050A0F51040D0F8100ABC +:1017200070470000064991F8243033B10023086A5D +:1017300081F824300822FFF7B5BF0120704700BFB1 +:10174000444B0020014B1868704700BF002004E0A4 +:1017500070B5194B1D68194B0138C5F30B040844CB +:101760002D0C04221E88A6420BD15C680A46013C5F +:10177000824213460FD214F9016F4EB102F8016B89 +:10178000F6E7013A03F10803ECD181420B4602D29D +:101790002C2203F8012B0A4A05241688AE4204D1F4 +:1017A000984284BF967803F8016B013C02F1040271 +:1017B000F3D1581A70BD00BF002004E0246C00086B +:1017C000106C0008022802BF024B4FF080529A6151 +:1017D000704700BF00040240022802BF024B4FF4D2 +:1017E00080529A61704700BF00040240022801BF86 +:1017F000024A536983F480535361704700040240E6 +:1018000070B504464FF47A764CB1412C254628BF7A +:10181000412506FB05F003F093FA641BF4E770BD65 +:1018200010B50023934203D0CC5CC4540133F9E7D4 +:1018300010BD000010B5013810F9013F3BB191F91E +:1018400000409C4203D11AB10131013AF4E71AB1C8 +:1018500091F90020981A10BD1046FCE70346024695 +:10186000D01A12F9011B0029FAD17047024403462D +:10187000934202D003F8011BFAE770472DE9F843C1 +:101880001F4D144695F824200746884652BBDFF8C2 +:1018900070909CB395F824302BB92022FF21484644 +:1018A0002F62FFF7E3FF95F82400C0F10802A2427F +:1018B00028BF2246D6B24146920005EB8000FFF7D2 +:1018C000AFFF95F82430A41B1E44F6B2082E17442F +:1018D0009044E4B285F82460DBD1FFF723FF0028B1 +:1018E000D7D108E02B6A03EB82038342CFD0FFF706 +:1018F00019FF0028CBD10020BDE8F8830120FBE7C9 +:10190000444B0020024B1A78024B1A70704700BFFC +:10191000804B00201C23002038B5194C194D20465F +:1019200002F05CFD2946204602F084FD2D68EA6E37 +:10193000D2F8043843F00203C2F804384FF47A7046 +:10194000FFF75EFF1049284602F07CFEEA6E0F4D5D +:10195000D2F8043828680E4923F00203C2F804388C +:10196000A0424FF461430B6001D002F097FC68681D +:10197000A04204D0BDE83840054902F08FBC38BD14 +:1019800070500020BC6D0008C46D000820230020AA +:101990006C4B002070B50C4B0C4D1E780C4B55F861 +:1019A00026209A4204460DD00A4B002114221846E4 +:1019B000FFF75CFF0460014655F82600BDE8704063 +:1019C00002F06CBC70BD00BF804B002020230020C3 +:1019D000705000206C4B00202DE9F0470D46044666 +:1019E00000219046284640F27912FFF73FFF234638 +:1019F00020220021284601F0B9FE231D02222021C9 +:101A0000284601F0B3FE631D03222221284601F07F +:101A1000ADFEA31D03222521284601F0A7FE04F1F7 +:101A2000080310222821284601F0A0FE04F110032B +:101A300008223821284601F099FE04F111030822FA +:101A40004021284601F092FE04F1120308224821A9 +:101A5000284601F08BFE04F1140320225021284671 +:101A600001F084FE04F1180340227021284601F0A1 +:101A70007DFE04F120030822B021284601F076FE05 +:101A800004F121030822B821284601F06FFE04F179 +:101A90002207C0263B46314608222846083601F078 +:101AA00065FEB6F5A07F07F10107F3D104F132031B +:101AB00008223146284601F059FE002704F1330A76 +:101AC00094F832304FEAC7099F4209F5A47615D33E +:101AD000B8F1000F08D1314604F599730722284662 +:101AE00001F044FE09F24F16274694F832213B1BC1 +:101AF00093420CD3F01DC008BDE8F0870AEB070342 +:101B000008223146284601F031FE0137D8E707F2B6 +:101B1000331331460822284601F028FE08360137E3 +:101B2000E3E7000013B504460846002101602346A0 +:101B3000C0F803102022019001F018FE0198231D27 +:101B40000222202101F012FE0198631D03222221AE +:101B500001F00CFE0198A31D0322252101F006FED1 +:101B6000019804F108031022282101F0FFFD07204D +:101B700002B010BDF7B50023047F00910E46072286 +:101B80001946054601F0B6FC731C009301220023A0 +:101B90000721284601F0AEFCC4B9B31C009305220E +:101BA00023460821284601F0A5FC0D243746B278CB +:101BB000BB1B934211D32B7FA88A0734E408BBB91F +:101BC000844294BF0020012003B0F0BDAB8ADB004B +:101BD000083BDB08B3700824E8E7FB1C00932146B0 +:101BE00000230822284601F085FC08340137DEE78F +:101BF000201A18BF0120E7E7F7B50023047F009102 +:101C00000E4608221946054601F074FC731CC4B93F +:101C10000822009311462346284601F06BFC10244D +:101C2000012372785F1C013B934211D32B7FA88A5A +:101C30000734E408BBB9844294BF0020012003B0FC +:101C4000F0BDAB8ADB00083BDB0873700824E7E7D4 +:101C5000F3190093214600230822284601F04AFC8C +:101C600008343B46DDE7201A18BF0120E7E70000F3 +:101C7000F8B50E4605461446002181223046FFF78E +:101C8000F5FD2B4608220021304601F06FFD7CB99E +:101C90006B1C07220821304601F068FD0F24012348 +:101CA0006A785F1C013B934204D3E01DC008F8BD75 +:101CB0000824F4E7EB1921460822304601F056FDCE +:101CC00008343B46ECE70000F8B50E4605461446DE +:101CD0000021CE223046FFF7C9FD2B4628220021E5 +:101CE000304601F043FD7CB905F1080308222821A4 +:101CF000304601F03BFD30242F462A7A7B1B93426D +:101D000004D3E01DC008F8BD2824F5E707F1090356 +:101D100021460822304601F029FD08340137ECE75E +:101D2000F7B5047F00910E460123102200210546DD +:101D300001F0E0FBC4B9B31C009309222346102133 +:101D4000284601F0D7FB192437467288BB1B9A42FC +:101D500011D82B7FA88A0734E408BBB9844294BF0A +:101D60000020012003B0F0BDAB8ADB00103BDB0894 +:101D700073801024E8E73B1D0093214600230822CE +:101D8000284601F0B7FB08340137DEE7201A18BFF8 +:101D90000120E7E730B5094D0A4491420DD011F812 +:101DA000013B5840082340F30004013B2C4013F052 +:101DB000FF0384EA5000F6D1EFE730BD2083B8ED91 +:101DC000F7B54FF0FF33DFF854C0DFF854E000EB15 +:101DD00081011A4688421CD050F8044B019401AF8F +:101DE000042417F8015B82EA05620825DB18164611 +:101DF00005F1FF355241002EBCBF83EA0C0382EA95 +:101E00000E0215F0FF05F1D1013C14F0FF04E8D1FA +:101E1000E0E7D843D14303B0F0BD00BF9336EAA951 +:101E2000EBE1F042F7B5384A106851686B4603C3DE +:101E30006A4636493648082304F054FE0446002812 +:101E400033D10A25334A106851686B4603C36A468A +:101E500031492F48082304F045FE0446002849D0A4 +:101E60000369B3F5E02F45D8B0F8661040F2474259 +:101E700091423FD1294A024402F15C018B4239D39D +:101E80005C3B234900209E1AFFF784FF3246074639 +:101E900004F164010020FFF77DFFA3689F4229D170 +:101EA000E368984208BF002524E00369B3F5E02FFA +:101EB00027D8418B40F24742914220D1174A024431 +:101EC00002F110018B4218D3103B114900209D1ADA +:101ED000FFF760FF2A46064604F118010020FFF7CD +:101EE00059FFA3689E4202D1E368984201D00D25B4 +:101EF000A8E70025284603B0F0BD1025A2E70C2571 +:101F0000A0E70B259EE700BF446C0008DCFF06003D +:101F1000000001084D6C000890FF06000800FFF764 +:101F200010B5037C044613B9006804F0C3FD2046D5 +:101F300010BD00000023BFF35B8FC360BFF35B8F56 +:101F4000BFF35B8F8360BFF35B8F7047BFF35B8F23 +:101F50000068BFF35B8F704770B505460C30FFF724 +:101F6000F5FF05F1080604463046FFF7EFFFA042F3 +:101F700006D930466D68FFF7E9FF2544281A70BD81 +:101F80003046FFF7E3FF201AF9E7000070B5054679 +:101F9000406898B105F10800FFF7D8FF05F10C067D +:101FA00004463046FFF7D2FF8442304694BF6D6846 +:101FB0000025FFF7CBFF013C2C44201A70BD000028 +:101FC00038B50C460546FFF7C7FFA04210D305F110 +:101FD0000800FFF7BBFF04446868B4FBF0F100FBA6 +:101FE0001144BFF35B8F0120AC60BFF35B8F38BD42 +:101FF0000020FCE72DE9F041144607460D46FFF7A7 +:10200000C5FF844228BF0446D4B1B84658F80C6BCB +:102010004046FFF79BFF3044286040467E68FFF74C +:1020200095FF331A9C4203D86C600120BDE8F08113 +:102030006B60A41B3B68AB602044E8600220F5E7BE +:102040002046F3E738B50C460546FFF79FFFA04250 +:1020500010D305F10C00FFF779FF04446868B4FB66 +:10206000F0F100FB1144BFF35B8F0120EC60BFF384 +:102070005B8F38BD0020FCE72DE9FF4188466946AB +:102080000746FFF7B7FF6C4606B204EBC60600250D +:10209000B44209D06268206808EB0501FFF7C0FB75 +:1020A000636808341D44F3E729463846FFF7CAFF42 +:1020B000284604B0BDE8F081F8B505460C300F465F +:1020C000FFF744FF05F1080604463046FFF73EFFE0 +:1020D000A042304688BF6C68FFF738FF201A38608E +:1020E00020B130462C68FFF731FF2044F8BD0000D6 +:1020F00073B5144606460D46FFF72EFF844228BFEF +:1021000004460190DCB101A93046FFF7D5FF019BE1 +:1021100033B93268C5E90233C5E9002401200CE077 +:102120009C4238BF01942860019868608442F5D9C8 +:102130003368AB60241AEC60022002B070BD204608 +:10214000FBE700002DE9FF410F466946FFF7D0FF8E +:102150006C4600B204EBC0050026AC4209D0D4F8AE +:10216000048054F8081BB8194246FFF759FB46444F +:10217000F3E7304604B0BDE8F081000038B505460D +:10218000FFF7E0FF044601462846FFF719FF204607 +:1021900038BD000010B4026854681A4623465DF842 +:1021A000044B18470020704700207047704700001C +:1021B000002070470E20704700F5805090F8C8004E +:1021C000C0F340007047000000F5805090F9D00047 +:1021D0007047000000F58050C0F8CC100120704717 +:1021E000F7B50C68BDF8207014F0005470D10D7B69 +:1021F000082D6DD8302585F311884569AE687601C4 +:102200000CD4AC68240108D4AC6814F080545DD1BF +:1022100084F31188204603B0F0BD01240E6804F158 +:10222000180C002EB8BFF6004FEA0C1CB4BF46F0E5 +:102230000406760545F80C600E680FFA84FC16F06B +:10224000804F18BF05EB0C1E05EB0C1C1EBFDEF803 +:10225000806146F00206CEF880610E7BCCF8846186 +:1022600005EB04158E68C5F88C614E68C5F8886169 +:10227000DCF8805145F00105CCF8805100EB4416A4 +:1022800041F268052E4405EB44150544C6E90023D8 +:1022900008350E4601F10C0C56F804EB45F804EB3A +:1022A0006645F9D1843436882E8000EB441407F05B +:1022B0000305267926F00B0635432571002484F3A7 +:1022C0001188009700F0FCFC0120A4E70224A5E798 +:1022D0004FF0FF309FE7000013B500F580540191E7 +:1022E000E06DFFF753FE1F280AD90199E06D202207 +:1022F000FFF7C2FEA0F120035842584102B010BDC2 +:102300000020FBE708B5302383F3118800F58050E7 +:10231000C06DFFF70FFE002383F3118808BD000096 +:1023200000220260828142608260704710B5002204 +:102330000023C0E900230023044603810C30FFF78B +:10234000EFFF204610BD0000F0B5054600F58050B7 +:102350000C4690F8C83013F0040FC3F3800108BF97 +:10236000114661F3820304F1840680F8C83005EB5E +:10237000461389B01B79D8072ED57AB319072DD407 +:102380006846FFF7D3FF05EB441303F5835303F1CE +:10239000180703AA103318685968144603C4083391 +:1023A000BB422246F7D1186820609B88A380DDE9F4 +:1023B0000E23CDE900230123ADF808302B686946D0 +:1023C000DB6B2846984705EB46152B791A075CBF4F +:1023D00043F008032B7101E0002AF4D109B0F0BDED +:1023E0002DE9F0479A4688B0074688469146302343 +:1023F00083F3118807F580546846FFF797FFE06D77 +:10240000FFF7AAFD1F282AD9E06D20226946FFF7B1 +:10241000B5FE202823D103AD444605AB2E4603CE9E +:102420009E4220606160354604F10804F6D13068B0 +:102430002060B388A380DDE90023C9E90023BDF84B +:102440000830AAF80030002383F3118853464A4627 +:102450004146384608B0BDE8F04700F01FBC0020F8 +:1024600080F3118808B0BDE8F08700002DE9F84F2F +:102470000023C0E90133254B044640F8183B0F46C2 +:10248000FFF74EFF04F12800FFF750FF04F1480862 +:1024900004F582554646083530462036FFF746FF9C +:1024A000AE42F9D104F580554FF480534FF0000946 +:1024B000C5E91339C5F848800123EE6504F587584E +:1024C00004F58456C5F8549085F8583085F8603086 +:1024D000083608F108084FF0000A4FF0000B46E9F3 +:1024E00008ABA6F11800FFF71BFF203646F8289C22 +:1024F0004645F4D185F8D07017B1054800F0B8FB17 +:10250000044B63612046BDE8F88F00BF806C000873 +:10251000586C00080064004010B5044B197804465C +:102520004A1C1A70FFF7A2FF204610BD884B0020FE +:102530002DE9F047002950D0294B2A4FB7FBF1F580 +:1025400099428CBF0A231123581EB5FBF3FC03FBF1 +:102550001C53C4B22BB102280346F5D80020BDE8B5 +:10256000F0870CF1FF36B6F5806FF7D2C4EBC40EDE +:102570000EF103034FEAE309C3F3C703A4EB030817 +:1025800009F1010A4FF47A755FFA88F009FB0555E5 +:102590005AFA88F8B5FBF8F5B5F5617FC1BF0EF1C1 +:1025A000FF33C3F3C703E01AC0B25C1C50FA84F4D3 +:1025B0000CFB04F4B7FBF4F4A142CFD1013BDBB236 +:1025C0000F2BCBD80138C0B20728C7D80021107113 +:1025D00016809170D3700120C1E70846BFE700BFA5 +:1025E0003F420F0040787D0170B505460E464FF41E +:1025F0007A746B695B6803F00103B34207D04FF450 +:102600007A7002F09DFB013CF3D1204670BD0120A1 +:10261000FCE7000030B54269936913F0700F16D0E3 +:1026200000230B4C936103F1840200EB42121179F9 +:102630004D0709D5890707D5416954F823508D60A6 +:10264000117941F0040111710133032BEBD130BD3D +:102650006C6C000873B51D46436916469A68D2072C +:10266000044609D59A6801219960C2F34002CDE978 +:1026700000650021FFF768FE63699A68D1050BD5F4 +:102680009A684FF480719960C2F34022CDE90065E9 +:1026900001212046FFF758FE63699A68D2030BD5E3 +:1026A0009A684FF480319960C2F34042CDE90065E9 +:1026B00002212046FFF748FE04F58053D3F8CC00F2 +:1026C00010B103681B699847204602B0BDE870400E +:1026D000FFF7A0BFF8B504464669002972D106F19C +:1026E0000C073868800770D006EB01153868D5F8FC +:1026F000B00110F0040FD5F8B0011ABFC00840F0C7 +:102700000040400DA061D5F8B0C11CF0020F1CBF05 +:1027100040F08040A061D5F8B40106EB011100F053 +:102720000F0084F82400D1F8B8012077D1F8B8015F +:10273000000A6077D1F8B801000CA077D1F8B80191 +:10274000000EE077D1F8BC0184F82000D1F8BC017C +:10275000000A84F82100D1F8BC01000C84F82200A2 +:10276000D1F8BC11090E84F823103821396004F126 +:10277000340004F1180104F1240551F8046B40F809 +:10278000046BA942F9D109880180C4E90A232146D2 +:102790000023238651F8283B2046DB6B984704F53D +:1027A000805393F8C820D3F8CC0042F0040283F899 +:1027B000C82010B103681B6998472046BDE8F8405F +:1027C000FFF728BF06F110078BE7F8BD10B50446E8 +:1027D00000F056FA02460B4652EA030102D0013AD3 +:1027E00063F100030449086820B12146BDE81040A8 +:1027F000FFF770BF10BD00BF844B0020F0B5302143 +:1028000081F31188DFF848C000F5835108310024B6 +:1028100004F1840500EB45152E7977070ED4F606F2 +:102820000CD5D1E9007697429E4107D246695CF803 +:102830002470B7602E7946F004062E710134032C03 +:1028400001F12001E4D1002383F31188F0BD00BF22 +:102850006C6C000808B5302383F31188FFF7DAFEAB +:10286000002383F3118808BDF8B5436905469868CD +:1028700000F0E050B0F1E05F0F4621D0F8B1302316 +:1028800083F3118805F583541034002606F1840380 +:1028900005EB43131B791A0706D50136032E04F105 +:1028A0002004F3D1012007E05B07F6D42146384627 +:1028B00000F040FA0028F0D1002383F31188F8BD1E +:1028C0000120FCE708B5302383F3118800F5805020 +:1028D000C06DFFF741FB002383F3118843090CBF50 +:1028E0000120002008BD0000F8B51D46002313702C +:1028F0000F4606461446FFF7E5FF80F001003870EA +:1029000025B129463046FFF7AFFF2070F8BD000023 +:102910002DE9B8410C4615461F46804600F0B0F937 +:102920000B462178024609B9287850B14046FFF796 +:1029300065FFFFF78FFF3B462A462146FFF7D4FF8E +:102940000120BDE8B881000070B5302686F31188FB +:10295000174B1A6C42F000721A641A6A42F0007245 +:102960001A621A6A22F000721A62002383F3118835 +:1029700000F5805494F8C83013F0010516D1A9B1C0 +:1029800086F311880321132001F0BCFA03211420DF +:1029900001F0B8FA0321152001F0B4FA94F8C83018 +:1029A00043F0010384F8C83085F3118870BD00BF7F +:1029B000003802402DE9F04700F5805588B095F8C1 +:1029C000D030012B04468846164600F28180814FA4 +:1029D00057F823200AB947F82300D7F800A0C4F815 +:1029E0000C802674BAF1000F64D095F8D030012B1A +:1029F00070D001212046FFF7A7FF302383F3118811 +:102A00006269136823F0020313606269136843F07C +:102A100001031360636900275F6187F31188012157 +:102A20002046FFF7E1FD002800F09580E86DFFF7F4 +:102A300081FA04F58359BA4609F1080920220021D8 +:102A40006846FEF713FF02A8FFF76AFCCDF818A04E +:102A50006A4609EB07030DF1180E9446BCE8030023 +:102A6000F44518605960624603F10803F5D1DCF8BB +:102A70000000186020379CF804201A71602FDDD107 +:102A800095F8C8306FF38203002785F8C8306A468E +:102A900041462046ADF80070ADF802708DF8047024 +:102AA000FFF746FD636948BB4FF400421A6008B067 +:102AB000BDE8F08741F2D80003F0BCFF814610B1B9 +:102AC0005146FFF7D3FCC7F80090B9F1000F8CD145 +:102AD0000020ECE7386803681B6B98470146002824 +:102AE00087D13868FFF730FF3868036832465B6883 +:102AF0004146984700287FF47CAFE9E761221A60DD +:102B00009DF802309DF803201B06120402F4702287 +:102B100003F040731343BDF80020C2F309021343CE +:102B20009DF804201205022E02F4E0020CBF4FF0C3 +:102B300000410021134362690B43D361636913228F +:102B40005A616269136823F0010313603946204615 +:102B5000FFF74AFD08B96369A6E795F8D03093BB43 +:102B60006169D1F8002242F00102C1F800226169D6 +:102B7000D1F8002222F47C5222F00E02C1F8002289 +:102B80006169D1F8002242F46062C1F800226269F2 +:102B9000C2F814326269C2F80432626941F6FF7108 +:102BA000C2F80C126269C2F840326269C2F844325B +:102BB00063690122C3F81C226269D2F8003223F053 +:102BC0000103C2F8003295F8C83043F0020385F8DB +:102BD000C8306CE7844B002008B500F051F850EA8B +:102BE0000103024602D0421E61F10001044B186845 +:102BF00010B10B46FFF72EFDBDE8084001F064B8A8 +:102C0000844B002008B50020FFF7E0FDBDE8084038 +:102C100001F05AB808B50120FFF7D8FDBDE808401B +:102C200001F052B800B59BB0EFF309816822684605 +:102C3000FEF7F6FDEFF30583014B9B6BFEE700BF4C +:102C400000ED00E008B5FFF7EDFF000000B59BB018 +:102C5000EFF3098168226846FEF7E2FDEFF3058392 +:102C6000014B5B6BFEE700BF00ED00E0FEE70000FC +:102C70000FB408B5029802F009F8FEE702F084BC30 +:102C800002F066BC13B56C4684E80600031D94E8A8 +:102C9000030083E80500012002B010BD73B585680C +:102CA000019155B11B885B0707D4D0E900369B6BB7 +:102CB0009847019AC1B23046A847012002B070BDC2 +:102CC000F0B5866889B005460C465EB1BDF838306F +:102CD0005B070AD4D0E900379B6B98472246C1B204 +:102CE0003846B047012009B0F0BD00220023CDE9ED +:102CF00000230023ADF808300A4603AB01F10806B3 +:102D0000106851681C4603C40832B2422346F7D10A +:102D1000106820609288A280FFF7B2FF0423ADF80C +:102D200008302B68CDE90001DB6B694628469847DF +:102D3000D8E7000030B503680968DD0FB5EBD17F37 +:102D400023F0604421F060424FEAD1700BD0002B99 +:102D5000B8BFA40C0029B8BF920C944202D034BF73 +:102D60000120002030BD944205D1C1F38070C3F32F +:102D700080738342F6D194422CBF00200120F1E7FA +:102D80002DE9F041456A15B94162BDE8F0814B6813 +:102D900023F06047C3F38A464FEAD37EC3F38078BB +:102DA00016EA230638BF3E46AC462B465A68BEEBB1 +:102DB000D27F22F060440AD0002A18DAA40CB44270 +:102DC00017D19D420FD10D60DEE71346EEE7A74213 +:102DD00007D102F08044C2F3807242450BD054B157 +:102DE000EFE708D2EDE7CCF800100B60CDE7B44276 +:102DF00001D0B442E5D81A689C46002AE5D1196092 +:102E0000C3E700002DE9F047089D01F007044FEAF1 +:102E1000D508224405F0070500EBD1004FF47F49A7 +:102E2000944201D1BDE8F08704F0070705F0070AD6 +:102E300057453E4638BF5646C6F10806111B8E421E +:102E400028BF0E46E10808EBD50E415C13F80EC012 +:102E5000B94029FA06F721FA0AF1FFB28CEA01011A +:102E600047FA0AF739408CEA010C03F80EC03444E3 +:102E70003544D5E780EA0120082341F2210201B25E +:102E80004000002980B203F1FF33B8BF504013F077 +:102E9000FF03F4D17047000038B50C468D18A542E9 +:102EA00000D138BD14F8011BFFF7E4FFF7E700007D +:102EB00042684AB1136843604389818901339BB2F8 +:102EC0009942438138BF83811046704770B588B0FE +:102ED000202204460D4668460021FEF7C7FC204626 +:102EE0000495FFF7E5FF024658B16B46054608AE6C +:102EF0001C4603CCB44228606960234605F10805EE +:102F0000F6D1104608B070BD082817D909280CD092 +:102F10000A280CD00B280CD00C280CD00D280CD073 +:102F20000E2814BF4020302070470C20704710201E +:102F30007047142070471820704720207047000009 +:102F4000082817D90C280CD910280CD914280CD90A +:102F500018280CD920280CD930288CBF0F200E201F +:102F60007047092070470A2070470B2070470C20DB +:102F700070470D20704700002DE9F843078C072F9C +:102F800004461ED9D0E9029800254FF6FF73C5F11B +:102F90002006A5F1200029FA05F108FA06F628FA1C +:102FA00000F031430143C9B21846FFF763FF08350B +:102FB000402D0346EBD1E1693A46BDE8F843FFF7FF +:102FC0006BBF4FF6FF70BDE8F883000010B54B688B +:102FD00023B9CA8A63F30902CA8210BD04691A6858 +:102FE0001C600361C38A013BC3824A60EFE70000B3 +:102FF0002DE9F84F1D46CB8A0F46C3F30901052979 +:10300000814692460B4630D00020AAB207F11A043E +:103010009EB2042E1FFA80F80FD8904503F10103E9 +:1030200006D3FB8A0A4462F30903FB8201201AE0FB +:103030001AF80060E6540130EAE79045F1D2A1F1B8 +:10304000050B1C237C68BBFBF3F203FB12BB1FFACE +:103050008BF6002C45D14846FFF72AFF044638B9C5 +:1030600078606FF00200BDE8F88F4FF00008E6E7E7 +:10307000002606607860ADB24FF0000B454510D9D0 +:103080000AEB0803221D13F8011B9155B1B208F198 +:1030900001081B291FFA88F82BD0454506F10106C7 +:1030A000F1D8FB8AC3F30902154465F30903BCE7B1 +:1030B000013292B21C462368002BF9D16B1F0B44DE +:1030C0001C21B3FBF1F301339BB29A42D3D2BBF183 +:1030D000000FD0D14846FFF7EBFE20B9C4F800B08E +:1030E000BFE70122E7E7C0F800B05E462060044673 +:1030F000C1E74545D5D94846FFF7DAFE08B9206053 +:10310000AFE7C0F800B0002620600446B6E7000034 +:103110002DE9F04F2DED028B1C4683B05B690192C7 +:1031200007468846002B00F09A80238C2BB1E26979 +:10313000002A00F09480072B35D807F10C00FFF728 +:10314000B7FE054638B96FF00205284603B0BDEC5E +:10315000028BBDE8F08F14220021FEF787FB228C42 +:10316000E16905F10800FEF75BFB208C013080B2BD +:10317000FFF7E6FEFFF7C8FE013880B22084013079 +:1031800028746369228C1B782A4403F01F0363F0C0 +:103190003F0348F000411372384669602946FFF743 +:1031A000EFFD0125D1E700F10C034FF0000908EE17 +:1031B000103A4FF0800A4E464D4618EE100AFFF7BF +:1031C00077FE83460028BED014220021FEF74EFB76 +:1031D000002E3AD1019BABF8083002220BF1080E09 +:1031E0001FFA82FC0CF10100BCF1060F218C80B2A9 +:1031F00001D88E422BD3FFF7A3FEFFF785FE62694D +:103200001278013802F01F028E4208BF4FF0400AC8 +:1032100042EA49121BFA80F14AEA020A013048F0F8 +:10322000004281F808A08BF81000CBF80420594622 +:103230003846FFF7A5FD238C0135B3422DB289F046 +:1032400001094FF0000AB8D17FE70022C6E7E16923 +:10325000895D0EF802100136B6B20132C0E76FF098 +:10326000010572E7F8B515460E46302200210446E6 +:103270001F46FEF7FBFA069B6360B5F5001F079B30 +:10328000A76034BF6A094FF6FF72A36297B2E66186 +:1032900004F1100000239A4206D800230360A7829D +:1032A000E3822383E360F8BD0660013330462036B5 +:1032B000F1E7000003781BB94BB2002BC8BF0170C7 +:1032C0007047000000787047F8B50C46C96907469A +:1032D00011B9238C002B37D1257E1F2D34D8387897 +:1032E00028BB228C072A2CD8268A36F003032BD140 +:1032F0004FF6FF70FFF7D0FD20F0010031024004CF +:1033000041EA0561400C41EA40254FF6FF72234631 +:1033100029463846FFF7FCFE002807DD626913786E +:103320000133DBB21F2B88BF00231370F8BD218A45 +:103330002D0645EA012505432046FFF71DFE0246FE +:10334000E5E76FF00300F1E76FF00100EEE7000042 +:1033500070B58AB0044616460021282268461D46EC +:10336000FEF784FABDF83830ADF810300F9B0593A6 +:103370009DF840308DF81830119B07936946BDF8D1 +:103380004830ADF820302046CDE90265FFF79CFFBC +:103390000AB070BD2DE9F041D36905460C461646CA +:1033A0000BB9138C5BBB377E1F2F28D895F8008094 +:1033B000B8F1000F26D03046FFF7DEFD337821024A +:1033C00041EAC33141EA0801338A41EA076141EA2F +:1033D00003410246334641F080012846FFF798FE3C +:1033E00000280ADD3378012B07D172691378013385 +:1033F000DBB21F2B88BF00231370BDE8F0816FF094 +:103400000100FAE76FF00300F7E70000F0B58BB0BA +:1034100004460D4617460021282268461E46FEF740 +:1034200025FA9DF84C305A1E534253418DF8003016 +:103430009DF84030ADF81030119B05939DF8483051 +:103440008DF81830149B07936A46BDF85430ADF8D8 +:10345000203029462046CDE90276FFF79BFF0BB0CE +:10346000F0BD0000406A00B104307047436A1A683A +:10347000426202691A600361C38A013BC3827047DA +:103480002DE9F041D0F82080194E14461D464146E2 +:10349000002709B9BDE8F081D1E90223A21A65EB42 +:1034A0000303964277EB03031ED2036A8B420DD1CE +:1034B000FFF78CFD036A1B68036203690B60C38A14 +:1034C0000161016A013BC3828846E2E7FFF77EFDA6 +:1034D0000B68C8F8003003690B60C38A0161013BC7 +:1034E000C382D8F80010D4E788460968D1E700BF46 +:1034F00080841E002DE9F04F8BB00D46DDF8509012 +:1035000014469B468046002800F01981B9F1000F4F +:1035100000F01581531E3F2B00F21181012A03D1C7 +:10352000BBF1000F40F00B810023CDE90833B8F860 +:103530001430B5EBC30F4FEAC30703D300200BB021 +:10354000BDE8F08F2B199F42D8F80C303ABF7F1B93 +:10355000FFB227461BB9D8F81030002B7AD0272DA0 +:103560004ED8C5F12806B7424FF000032CBFF6B283 +:103570003E4600932946D8F8080008AB3246FFF7CC +:1035800041FCA7EB060A35445FFA8AFAB8F8143012 +:1035900003F10053053BDB000493D8F80C30039390 +:1035A0002821039B13B1BAF1000F2CD1D8F81000D9 +:1035B00040B1BAF1000F05D0009608AB5246691A27 +:1035C000FFF720FC38B2002FB8D066070AD00AAB4C +:1035D00003EBD401624211F8083C02F007021341E8 +:1035E00001F8083C082C3CD9102C40F2B580202C66 +:1035F00040F2B780BBF1000F00F09C80082334E05C +:10360000BA460026C2E7049BE02B28BFE0230693BE +:103610000B44AB42059314D95A1B0398009692456C +:1036200034BF5246D2B2691A08AB04300792FFF792 +:10363000E9FB079A1644AAEB020A1544F6B25FFAB0 +:103640008AFA049B069A05999B1A0493039B1B68AC +:103650000393A6E70093D8F8080008AB3A4629463A +:10366000AEE7BBF1000F13D00123B4EBC30F6CD056 +:10367000082C12D89DF82030621E23FA02F2D507DA +:1036800006D54FF0FF3202FA04F423438DF82030C0 +:103690009DF8203089F8003051E7102C12D8BDF881 +:1036A0002030621E23FA02F2D10706D54FF0FF3216 +:1036B00002FA04F42343ADF82030BDF82030A9F815 +:1036C00000303CE7202C0FD80899631E21FA03F341 +:1036D000DA0705D54FF0FF3202FA04F40C430894E0 +:1036E000089BC9F800302AE7402C2BD0DDE908659B +:1036F000611EC4F12102A4F1210326FA01F105FAA9 +:1037000002F225FA03F311431943CB0712D5012224 +:10371000A4F12003C4F1200102FA03F322FA01F11B +:10372000A240524243EA010363EB430332432B437B +:10373000CDE90823DDE90823C9E90023FFE66FF09E +:103740000100FCE66FF00800F9E6082CA0D9102C67 +:10375000B3D9202CEED8C3E7BBF1000FADD00223C4 +:1037600083E7BBF1000FBBD004237EE730B5012A0D +:10377000144638BF0124402C85B028BF40240025C2 +:10378000012ACDE9025518D81B788DF80830630757 +:103790000AD004AB03EBD405624215F8083C02F0F2 +:1037A0000702934005F8083C009103462246002199 +:1037B00002A8FFF727FB05B030BD082AE4D9102A7C +:1037C00003D81B88ADF80830E1E7202A8DBFD3E984 +:1037D00000231B680293CDE90223D8E710B5CB681C +:1037E0001BB98B600B618B8210BD04691A681C6069 +:1037F0000361C38A013BC382CA60F0E703064CBF82 +:10380000C0F3C0300220704708B50246FFF7F6FF4C +:10381000022806D15306C2F30F2001D100F00300A5 +:1038200008BDC2F30740FBE72DE9F04F93B0CDE9A7 +:1038300003230A6804461046FFF7E0FF022814BF7E +:10384000C2F306260026002A0D46824680F2F28147 +:1038500012F0C04940F0EE81097B002900F0EA81B6 +:10386000022803D02378B34240F0E781C2F3046317 +:103870000693104602F07F030593FFF7C5FF059BF3 +:1038800029444FEA834848EA0A4848EA4668CE781D +:1038900000230022CDE90823F309834648EA000803 +:1038A000029367D0059B009302466768534608A9B8 +:1038B0002046B847002800F0C381276A4FB9414627 +:1038C00004F10C00FFF702FB074690B96FF002000D +:1038D00054E03B6998450DD03F68002FF9D141462F +:1038E00004F10C00FFF7F2FA07460028EED0236A35 +:1038F0003B60276297F817C006F01F08CCF3840CD2 +:10390000ACEB08001FFA80FE0028B8BF0EF12000C3 +:10391000A8EB0C031FFA83FED7E90221B8BF00B25F +:10392000002B0793BEBF0EF120031BB2079352EA90 +:10393000010338D0039BDFF824E39A1A049B4FF06D +:10394000000C63EB010196457CEB01032BD36B7BF1 +:1039500097F81AE0734519D1029B002B78D0012803 +:1039600021DC7868F8B9DFF8F0C2944570EB010308 +:1039700016D337E0276A27B96FF00C0013B0BDE803 +:10398000F08F3B699845B5D03F68F4E7B248904264 +:103990007CEB010301D30020F0E7029B002BFAD05F +:1039A000079B0F2B17DCFA7DB30002F0030203F034 +:1039B0007C031343FB7539462046FFF707FB6B7BFF +:1039C000BB76029B3BB9FB7DC3F38402013262F3F9 +:1039D0008603FB75D0E76A7BBB7E9A42DBD1029BF4 +:1039E000002B35D0B309022B32D0039BBB60049B64 +:1039F000FB60142200210DA8FDF738FF039B0A93FA +:103A0000049B0B932B1D0C932B7BADF83EB0013B1D +:103A1000DBB2ADF83C30069B8DF84230059B8DF84B +:103A2000433094F82C308DF840A083F001038DF8DA +:103A300044308DF84180A3680AA920469847FB7D51 +:103A4000C3F38403013303F01F039B02FB82A2E74D +:103A5000FB7DC6F34012B2EBD31F40F0F480C3F3FA +:103A60008403434540F0F280029A2B7BB609002A7A +:103A70004DD0F2075DD4032B40F2EB80039BBB607B +:103A8000049BFB602B7BAE1D033BDBB23246394609 +:103A900004F10C00FFF7ACFA00280CDA3946204696 +:103AA000FFF794FAFB7DC3F38403013303F01F0394 +:103AB0009B02FB820AE7DDE90884AB883B834FF673 +:103AC000FF73C9F12000A9F1200228FA09F104FAD4 +:103AD00000F0014324FA02F211431846C9B2FFF77D +:103AE000C9F909F10809B9F1400F0346E9D1B882D3 +:103AF0002A7B033AD2B23146FFF7CEF9FB7DB8827A +:103B0000DA43C2F3C01262F3C713FB7543E786B909 +:103B10002E1D013BDBB23246394604F10C00FFF7A3 +:103B200067FA0028BADB2A7BB88A013AD2B231465A +:103B3000E2E7F98AC1F30901013B0429DAB25BD853 +:103B4000281D002307F11B069A4208D910F801CB63 +:103B500006F801C0013101330529DBB2F4D1039924 +:103B60000A9104990B91934207F11B010C9138BF04 +:103B7000043379680D9134BF55FA83F300230E9313 +:103B8000FB8AADF83EB0C3F309031A44069B8DF8D7 +:103B90004230059B8DF8433094F82C30ADF83C2032 +:103BA00083F001038DF8443000238DF840A08DF898 +:103BB00041807B602A7BB88A013A291DFFF76CF9A6 +:103BC0003B8BB882834203D1A3680AA92046984759 +:103BD00020460AA9FFF702FEFB7DBA8AC3F38403DD +:103BE000013303F01F039B02FB823B8B9A420CBF05 +:103BF00000206FF01000C1E67B68002BAFD00520DD +:103C000001E01C3033461E68002EFAD1091A081D47 +:103C10002E1D184401EB090CBCF11B0F5FFA89F350 +:103C20009DD89A429BD916F8013B00F8013B09F157 +:103C30000109EFE76FF00900A0E66FF00A009DE6CA +:103C40006FF00B009AE66FF00D0097E66FF00E0034 +:103C500094E66FF00F0091E640420F0080841E0052 +:103C6000EFF3098305494A6B22F001024A63683386 +:103C700083F30988002383F31188704700EF00E085 +:103C8000302080F3118862B60C4B0D4AD96821F4BC +:103C9000E0610904090C0A43DA60D3F8FC20094901 +:103CA00042F08072C3F8FC200A6842F001020A6008 +:103CB0002022DA7783F82200704700BF00ED00E091 +:103CC0000003FA05001000E010B5302383F31188DB +:103CD0000E4B5B6813F4006314D0F1EE103AEFF36F +:103CE0000984683C4FF08073E361094BDB6B23660A +:103CF00084F3098800F094FF10B1064BA36110BD56 +:103D0000054BFBE783F31188F9E700BF00ED00E006 +:103D100000EF00E03F030008420300080268436828 +:103D20001143016003B1184770470000024AD3688D +:103D300043F0C003D36070470010014010B5054C3C +:103D4000054A0021204600F087FA044A044BC4E9E2 +:103D5000972310BD904B00202D3D0008001001401E +:103D600080F0FA02234A037C002918BF0A46012B7F +:103D700030B5C0F868220CD11F4B984209D11F4BB7 +:103D8000596C41F010015964596E41F010015966A7 +:103D90005B6EB2F904501468D0F86032D0F85C124F +:103DA000002D03EB5403B3FBF4F3BEBF23F0070570 +:103DB00003F0070343EA450394888B60D38843F0FC +:103DC00040030B61138943F001034B6144F4045336 +:103DD00043F02C03CB6004F4A05400230B60B4F533 +:103DE000806F0B684B680CBF7F23FF2380F8643221 +:103DF00030BD00BFC06C0008904B0020003802406E +:103E00002DE9F041D0F85C62F7683368DA050446C2 +:103E10009DB20DD5302383F311884FF480610430B7 +:103E2000FFF77CFF6FF480733360002383F3118806 +:103E3000302383F3118804F1040815F02F033AD1DD +:103E400083F31188380615D5290613D5302383F35B +:103E5000118804F1380000F07BF900284EDA0821BF +:103E6000201DFFF75BFF4FF67F733B40F36000239D +:103E700083F311887A0616D56B0614D5302383F3A5 +:103E80001188D4E913239A420AD1236C43B127F055 +:103E900040073F041021201D3F0CFFF73FFFF76054 +:103EA000002383F31188D4F86822D36843B3BDE8B4 +:103EB000F041106918472B0714D015F0080F0CBFFC +:103EC00000214FF48071E80748BF41F02001AA07A4 +:103ED00048BF41F040016B0748BF41F080014046B8 +:103EE000FFF71CFFAD06736805D594F864122046F1 +:103EF000194000F0E1F93568ADB29EE77060B6E7B1 +:103F0000BDE8F08100F1604303F561430901C9B2E6 +:103F100083F80013012200F01F039A4043099B001D +:103F200003F1604303F56143C3F880211A607047D1 +:103F3000F8B5154682680669AA420B46816938BF02 +:103F40008568761AB54204460BD218462A46FDF714 +:103F500067FCA3692B44A361A3685B1BA36028468D +:103F6000F8BD0CD918463246FDF75AFCAF1BE16884 +:103F70003A463044FDF754FCE3683B44EBE718460F +:103F80002A46FDF74DFCE368E5E7000083689342AD +:103F9000F7B51546044638BF8568D0E90460361A7F +:103FA000B5420BD22A46FDF73BFC63692B446361A3 +:103FB000A36828465B1BA36003B0F0BD0DD9324651 +:103FC0000191FDF72DFC0199E068AF1B3A463144A1 +:103FD000FDF726FCE3683B44E9E72A46FDF720FCB1 +:103FE000E368E4E710B50A440024C361029B8460DF +:103FF000C0E90000C0E90511C1600261036210BDA3 +:1040000008B5D0E90532934201D1826882B982684D +:10401000013282605A1C42611970D0E904329A421E +:1040200024BFC3684361002100F0A6FE002008BD44 +:104030004FF0FF30FBE7000070B5302304460E461A +:1040400083F31188A568A5B1A368A269013BA360A9 +:10405000531CA36115782269934224BFE368A361CE +:10406000E3690BB120469847002383F31188284663 +:1040700007E03146204600F06FFE0028E2DA85F3C3 +:10408000118870BD2DE9F74F04460E461746984635 +:10409000D0F81C904FF0300A8AF311884FF0000BD3 +:1040A000154665B12A4631462046FFF741FF0346D3 +:1040B00060B94146204600F04FFE0028F1D00023B1 +:1040C00083F31188781B03B0BDE8F08FB9F1000FBE +:1040D00003D001902046C847019B8BF31188ED1A4D +:1040E0001E448AF31188DCE7C0E90511C160C36191 +:1040F0001144009B8260C0E90000016103627047C7 +:10410000F8B504460D461646302383F31188A76898 +:10411000A7B1A368013BA36063695A1C62611D706B +:10412000D4E904329A4224BFE3686361E3690BB1C6 +:1041300020469847002080F3118807E0314620464A +:1041400000F00AFE0028E2DA87F31188F8BD0000CB +:10415000D0E905239A4210B501D182687AB9826804 +:10416000013282605A1C82611C7803699A4224BF22 +:10417000C3688361002100F0FFFD204610BD4FF0B1 +:10418000FF30FBE72DE9F74F04460E4617469846E9 +:10419000D0F81C904FF0300A8AF311884FF0000BD2 +:1041A000154665B12A4631462046FFF7EFFE034625 +:1041B00060B94146204600F0CFFD0028F1D0002331 +:1041C00083F31188781B03B0BDE8F08FB9F1000FBD +:1041D00003D001902046C847019B8BF31188ED1A4C +:1041E0001E448AF31188DCE70268436811430160CA +:1041F00003B11847704700001430FFF743BF0000B9 +:104200004FF0FF331430FFF73DBF00003830FFF7A9 +:10421000B9BF00004FF0FF333830FFF7B3BF0000E5 +:104220001430FFF709BF00004FF0FF311430FFF7E3 +:1042300003BF00003830FFF763BF00004FF0FF32CC +:104240003830FFF75DBF0000012914BF6FF0130085 +:1042500000207047FFF772BD37B515460E4A026061 +:1042600000224260C0E902220122044602740B4689 +:10427000009000F15C014FF480721430FFF7B2FE41 +:1042800000942B464FF4807204F5AE7104F13800AF +:10429000FFF72AFF03B030BDD46C000810B53023FF +:1042A000044683F31188FFF75DFD02232374002089 +:1042B00080F3118810BD000038B5C36904460D466F +:1042C0001BB904210844FFF78FFF294604F11400AD +:1042D000FFF796FE002806DA201D4FF40061BDE8C6 +:1042E0003840FFF781BF38BD026843681143016061 +:1042F00003B118477047000013B5446BD4F89434E9 +:104300001A681178042915D1217C022912D1197952 +:10431000128901238B4013420CD101A904F14C00F6 +:1043200001F0B0FFD4F89444019B21790246206843 +:1043300000F0D6F902B010BD143001F033BF000018 +:104340004FF0FF33143001F02DBF00004C3002F06D +:1043500005B800004FF0FF334C3001F0FFBF000004 +:10436000143001F001BF00004FF0FF31143001F0B4 +:10437000FBBE00004C3001F0D1BF00004FF0FF3217 +:104380004C3001F0CBBF00000020704710B5D0F8D2 +:1043900094341A6811780429044617D1017C022943 +:1043A00014D15979528901238B4013420ED1143014 +:1043B00001F094FE024648B1D4F894444FF480735F +:1043C00061792068BDE8104000F078B910BD0000A8 +:1043D000406BFFF7DBBF0000704700007FB5124B5A +:1043E000036000234360C0E90233012502260F4B1E +:1043F000057404460290019300F184022946009658 +:104400004FF48073143001F045FE094B0294CDE95E +:10441000006304F523724FF48073294604F14C00C5 +:1044200001F00CFF04B070BDFC6C0008D143000823 +:10443000F94200080B68302282F311880A7903EBF5 +:10444000820210624A790D3243F822008A7912B151 +:1044500003EB820318620223C0F894140374002053 +:1044600080F311887047000038B5037F044613B10C +:1044700090F85430ABB9201D01250221FFF734FF1D +:1044800004F1140025776FF0010100F081FC84F83D +:10449000545004F14C006FF00101BDE8384000F0C9 +:1044A00077BC38BD10B5012104460430FFF71CFF6E +:1044B0000023237784F8543010BD000038B504463B +:1044C0000025143001F0FEFD04F14C00257701F0C9 +:1044D000CDFE201D84F854500121FFF705FF204632 +:1044E000BDE83840FFF752BF90F85C3003F060033E +:1044F000202B07D190F85D20212A4FF0000303D82C +:104500001F2A06D800207047222AFBD1C0E91433A5 +:1045100003E0034A02650722426583650120704774 +:104520002823002037B5D0F894341A68117804296C +:1045300004461AD1017C022917D119791289012365 +:104540008B40134211D100F14C05284601F04EFF7B +:1045500058B101A9284601F095FED4F89444019B76 +:1045600021790246206800F0BBF803B030BD00009E +:10457000F0B500EB810385B01E6A04460D46FEB11E +:10458000302383F3118804EB8507301D0821FFF7E2 +:10459000ABFEFB685B691B6806F14C001BB1019028 +:1045A00001F07EFE019803A901F06CFE024648B1BD +:1045B000039B2946204600F093F8002383F31188DB +:1045C00005B0F0BDFB685A691268002AF5D01B8A55 +:1045D000013B1340F1D104F15C02EAE70D3138B53B +:1045E00050F82140DCB1302383F31188D4F89424AF +:1045F0001368527903EB8203DB689B695D6845B100 +:1046000004216018FFF770FE294604F1140001F040 +:104610006FFD2046FFF7BAFE002383F3118838BDF3 +:104620007047000001F0D0B810B5012304462822DD +:1046300000F8243B0021FDF719F90023C4E90133F8 +:1046400010BD000038B50446302383F311880025DF +:10465000C0E90355C0E90555C0E90755416001F0BF +:10466000C3F80223237085F31188284638BD000063 +:1046700070B500EB810305465069DA600E461446BA +:1046800018B110220021FDF7F1F8A06918B110222D +:104690000021FDF7EBF831462846BDE8704001F0F7 +:1046A0006DB90000826802F0011282600022C0E948 +:1046B0000422C0E90622026201F0ECB9F0B400EB7A +:1046C00081044789E4680125A4698D403D43458103 +:1046D00023600023A2606360F0BC01F007BA000011 +:1046E000F0B400EB81040789E468012564698D401A +:1046F0003D43058123600023A2606360F0BC01F0AC +:1047000081BA000070B50223002504460370C0E999 +:104710000255C0E90455C0E906554566056280F8B2 +:104720004C5001F0C7F863681B6823B12946204646 +:10473000BDE87040184770BD0378052B10B50446DE +:104740000AD080F868300523037043681B680BB1FA +:10475000042198470023A36010BD000001780529BB +:1047600006D190F86820436802701B6803B11847AF +:104770007047000070B590F84C30044613B1002328 +:1047800080F84C3004F15C02204601F0A5F9636822 +:104790009B68B3B994F85C3013F0600535D0002104 +:1047A000204601F059FC0021204601F04BFC6368D3 +:1047B0001B6813B1062120469847062384F84C3025 +:1047C00070BD204698470028E4D0B4F86230626D8E +:1047D0009A4288BF636594F95C30656D002B4FF099 +:1047E000300380F20381002D00F0F280092284F86A +:1047F0004C2083F311880021D4E914232046FFF7CD +:104800006FFF002383F31188DAE794F85D2003F04B +:104810007F0343EA022340F20232934200F0C58054 +:1048200021D8B3F5807F48D00DD8012B3FD0022B83 +:1048300000F09380002BB2D104F1640222650222C1 +:104840006265A365C1E7B3F5817F00F09B80B3F596 +:10485000407FA4D194F85E30012BA0D1B4F864302D +:1048600043F0020332E0B3F5006F4DD017D8B3F533 +:10487000A06F31D0A3F5C063012B90D8636894F882 +:104880005E205E6894F85F10B4F860302046B04750 +:10489000002884D043682365036863651AE0B3F594 +:1048A000106F36D040F6024293427FF478AF5C4BF3 +:1048B0002365022363650023C3E794F85E30012B70 +:1048C0007FF46DAFB4F8643023F00203C4E91455EB +:1048D000A4F86430A56578E7B4F85C30B3F5A06F50 +:1048E0000ED194F85E3084F86630204601F03AF834 +:1048F00063681B6813B10121204698470323237086 +:104900000023C4E914339CE704F167032365012302 +:10491000C3E72378042B10D1302383F3118820467A +:10492000FFF7C0FE85F311880321636884F86750A0 +:1049300021701B680BB12046984794F85E30002B1D +:10494000DED084F867300423237063681B68002B73 +:10495000D6D0022120469847D2E794F860301D0651 +:1049600003F00F0120460AD501F0A8F8012804D071 +:1049700002287FF414AF2B4B9AE72B4B98E701F0FA +:104980008FF8F3E794F85E30002B7FF408AF94F8CB +:10499000603013F00F01B3D01A06204602D501F0A3 +:1049A0006FFBADE701F062FBAAE794F85E30002BE5 +:1049B0007FF4F5AE94F8603013F00F01A0D01B0621 +:1049C000204602D501F048FB9AE701F03BFB97E750 +:1049D000142284F84C2083F311882B462A4629465A +:1049E0002046FFF76BFE85F31188E9E65DB11522DD +:1049F00084F84C2083F311880021D4E91423204645 +:104A0000FFF75CFEFDE60B2284F84C2083F311884F +:104A10002B462A4629462046FFF762FEE3E700BF01 +:104A20002C6D0008246D0008286D000838B590F83A +:104A30004C300446002B3ED0063BDAB20F2A34D865 +:104A40000F2B32D8DFE803F0373131082232313111 +:104A50003131313131313737456DB0F862309D42F7 +:104A600014D2C3681B8AB5FBF3F203FB12556DB970 +:104A7000302383F311882B462A462946FFF730FE60 +:104A800085F311880A2384F84C300EE0142384F84F +:104A90004C30302383F3118800231A4619462046F0 +:104AA000FFF70CFE002383F3118838BD836D03B13B +:104AB00098470023E7E70021204601F0CDFA0021C6 +:104AC000204601F0BFFA63681B6813B10621204637 +:104AD00098470623D7E7000010B590F84C30142B08 +:104AE000044629D017D8062B05D001D81BB110BD1C +:104AF000093B022BFBD80021204601F0ADFA002132 +:104B0000204601F09FFA63681B6813B10621204616 +:104B10009847062319E0152BE9D10B2380F84C3078 +:104B2000302383F3118800231A461946FFF7D8FD76 +:104B3000002383F31188DAE7C3689B695B68002B65 +:104B4000D5D1836D03B19847002384F84C30CEE76C +:104B500000230375826803691B6899689142FBD240 +:104B60005A68036042601060586070470023037504 +:104B7000826803691B6899689142FBD85A68036090 +:104B8000426010605860704708B50846302383F3D0 +:104B900011880B7D032B05D0042B0DD02BB983F38B +:104BA000118808BD8B6900221A604FF0FF338361C2 +:104BB000FFF7CEFF0023F2E7D1E9003213605A601D +:104BC000F3E70000FFF7C4BF054BD9680875186804 +:104BD00002681A60536001220275D860FBF79ABB25 +:104BE000004E002030B50C4BDD684B1C87B00446EE +:104BF0000FD02B46094A684600F05EF92046FFF7C1 +:104C0000E3FF009B13B1684600F060F9A86907B0A4 +:104C100030BDFFF7D9FFF9E7004E0020894B0008AF +:104C2000044B1A68DB6890689B68984294BF002028 +:104C300001207047004E0020084B10B51C68D86852 +:104C400022681A60536001222275DC60FFF78EFF34 +:104C500001462046BDE81040FBF75CBB004E00203B +:104C600038B5074C074908480123002523706560C3 +:104C700001F0F4FB0223237085F3118838BD00BFD7 +:104C800068500020346D0008004E002008B572B650 +:104C9000044B186500F048FC00F0F4FC024B0322C2 +:104CA0001A70FEE7004E00206850002000F044B962 +:104CB000034A516853685B1A9842FBD8704700BF9B +:104CC000001000E08B60022308618B820846704769 +:104CD0008368A3F1840243F8142C026943F8442C3E +:104CE000426943F8402C094A43F8242CC26843F82F +:104CF000182C022203F80C2C002203F80B2C044A77 +:104D000043F8102CA3F12000704700BF2D030008CA +:104D1000004E002008B5FFF7DBFFBDE80840FFF7B5 +:104D200051BF0000024BDB6898610F20FFF74CBFBA +:104D3000004E0020302383F31188FFF7F3BF0000FB +:104D400008B50146302383F311880820FFF74AFF96 +:104D5000002383F3118808BD064BDB6839B1426834 +:104D600018605A60136043600420FFF73BBF4FF0A8 +:104D7000FF307047004E00200368984206D01A6842 +:104D80000260506099611846FFF71CBF7047000031 +:104D900038B504460D462068844200D138BD03680A +:104DA00023605C608561FFF70DFFF4E710B50368D1 +:104DB0009C68A2420CD85C688A600B604C602160E1 +:104DC000596099688A1A9A604FF0FF33836010BD6A +:104DD0001B68121BECE700000A2938BF0A2170B5D6 +:104DE00004460D460A26601901F032FB01F01EFB55 +:104DF000041BA54203D8751C2E460446F3E70A2E71 +:104E000004D9BDE87040012001F068BB70BD00000E +:104E1000F8B5144B0D46D96103F1100141600A2A1F +:104E20001969826038BF0A22016048601861A818B9 +:104E3000144601F0FFFA0A2701F0F8FA431BA342D7 +:104E4000064606D37C1C281901F002FB274635468E +:104E5000F2E70A2F04D9BDE8F840012001F03EBB7B +:104E6000F8BD00BF004E0020F8B506460D4601F023 +:104E7000DDFA0F4A134653F8107F9F4206D12A46A7 +:104E800001463046BDE8F840FFF7C2BFD169BB68B4 +:104E9000441A2C1928BF2C46A34202D92946FFF7F1 +:104EA0009BFF224631460348BDE8F840FFF77EBF2E +:104EB000004E0020104E002010B4C0E90323002350 +:104EC0005DF8044B4361FFF7CFBF000010B5194CEC +:104ED000236998420DD0D0E90032816813605A608E +:104EE0009A680A449A60002303604FF0FF33A3617D +:104EF00010BD2346026843F8102F53600022026061 +:104F000022699A4203D1BDE8104001F09BBA936830 +:104F100081680B44936001F089FA2269E169926823 +:104F2000441AA242E4D91144BDE81040091AFFF71F +:104F300053BF00BF004E00202DE9F047DFF8BC80D2 +:104F400008F110072C4ED8F8105001F06FFAD8F87D +:104F50001C40AA68031B9A423ED81444D5E900328B +:104F60004FF00009C8F81C4013605A60C5F8009063 +:104F7000D8F81030B34201D101F064FA89F31188F6 +:104F8000D5E9033128469847302383F311886B69AC +:104F9000002BD8D001F04AFA6A69A0EB04094A450F +:104FA00082460DD2022001F099FA0022D8F8103082 +:104FB000B34208D151462846BDE8F047FFF728BF65 +:104FC000121A2244F2E712EB090938BF4A46294671 +:104FD0003846FFF7EBFEB5E7D8F81030B34208D0FB +:104FE0001444211AC8F81C00A960BDE8F047FFF777 +:104FF000F3BEBDE8F08700BF104E0020004E002039 +:1050000038B501F013FA054AD2E90845031B18190F +:1050100045F10001C2E9080138BD00BF004E002083 +:1050200000207047FEE70000704700004FF0FF309F +:105030007047000002290CD0032904D00129074839 +:1050400018BF00207047032A05D8054800EBC200AE +:105050007047044870470020704700BF206E00086A +:1050600038230020D46D000870B59AB00546084674 +:1050700001A9144600F0C2F801A8FCF7EFFB431C9D +:105080005B00C5E900340022237003236370C6B2BD +:1050900001AB02341046D1B28E4204F1020401D8B1 +:1050A0001AB070BD13F8011B04F8021C04F8010CBF +:1050B0000132F0E708B5302383F311880348FFF786 +:1050C00031FA002383F3118808BD00BF705000201F +:1050D00090F85C3003F01F02012A07D190F85D20A0 +:1050E0000B2A03D10023C0E9143315E003F0600359 +:1050F000202B08D1B0F860302BB990F85D20212A20 +:1051000003D81F2A04D8FFF7EFB9222AEBD0FAE719 +:10511000034A02650722426583650120704700BF8C +:105120002F23002007B5052917D8DFE801F019164D +:1051300003191920302383F31188104A01900121AB +:10514000FFF796FA01980E4A0221FFF791FA0D48EF +:10515000FFF7B4F9002383F3118803B05DF804FB73 +:10516000302383F311880748FFF77EF9F2E73023F5 +:1051700083F311880348FFF795F9EBE7746D000896 +:10518000986D00087050002038B50C4D0C4C0D493E +:105190002A4604F10800FFF767FF05F1CA0204F18F +:1051A00010000949FFF760FF05F5CA7204F1180005 +:1051B0000649BDE83840FFF757BF00BF385500200B +:1051C00038230020406D0008516D00086A6D00080A +:1051D00070B5044608460D46FCF740FBC6B22046B3 +:1051E000013403780BB9184670BD32462946FCF7E6 +:1051F00021FB0028F3D10120F6E700002DE9F0475C +:1052000005460C46FCF72AFB2B49C6B22846FFF799 +:10521000DFFF08B10E36F6B228492846FFF7D8FF5F +:1052200008B11036F6B2632E0BD8DFF88C80DFF8A9 +:105230008C90234FDFF894A02E7846B92670BDE8F5 +:10524000F08729462046BDE8F04701F0B1BC252E85 +:105250002ED1072241462846FCF7ECFA70B9194BCB +:10526000224603F1140153F8040B42F8040B8B425D +:10527000F9D11B78137007351534DDE7082249464C +:105280002846FCF7D7FA98B90F4BA21C19780909E0 +:105290000232C95D02F8041C13F8011B01F00F0172 +:1052A0005345C95D02F8031CF0D118340835C3E733 +:1052B00004F8016B0135BFE7406E00086A6D000815 +:1052C0005E6E0008486E0008107AFF1F1C7AFF1FF0 +:1052D000BFF34F8F024AD368DB03FCD4704700BF93 +:1052E000003C024008B5094B1B7873B9FFF7F0FF8B +:1052F000074B1A69002ABFBF064A5A6002F188327A +:105300005A601A6822F480621A6008BD965700201D +:10531000003C02402301674508B50B4B1B7893B94D +:10532000FFF7D6FF094B1A6942F000421A611A686A +:1053300042F480521A601A6822F480521A601A6885 +:1053400042F480621A6008BD96570020003C02407B +:105350000728F0B516D80C4C0C4923787BB90C4DB6 +:105360000E4608234FF0006255F8047B46F8042BE4 +:10537000013B13F0FF033A44F6D10123237051F8A7 +:105380002000F0BD0020FCE7B8570020985700200F +:10539000706E0008014B53F820007047706E0008D3 +:1053A00008207047072810B5044601D9002010BD19 +:1053B000FFF7CEFF064B53F824301844C21A0BB93E +:1053C0000120F4E712680132F0D1043BF6E700BF98 +:1053D000706E0008072810B5044621D8FFF778FF43 +:1053E000FFF780FF0F4AF323D360C300DBB243F41F +:1053F000007343F002031361136943F480331361B4 +:10540000FFF766FFFFF7A4FF074B53F8241000F0E7 +:1054100035F9FFF781FF2046BDE81040FFF7C2BF16 +:10542000002010BD003C0240706E0008F8B512F07C +:105430000103144642D185182E4A954257D82E4B67 +:105440001B6813F0010352D02C4DFFF74BFFF323E1 +:10545000EB60FFF73DFF40F20127032C15D824F045 +:1054600001046618254C401A40F20117B142236925 +:1054700000EB010524D123F001032361FFF74CFF6A +:105480000120F8BD043C0430E7E78307E7D12B692E +:1054900023F440732B612B693B432B6151F8046B60 +:1054A0000660BFF34F8FFFF713FF03689E42E9D0FA +:1054B0002B6923F001032B61FFF72EFF0020E0E7AB +:1054C00023F44073236123693B4323610B882B80C2 +:1054D000BFF34F8FFFF7FCFE2D8831F8023BADB2D2 +:1054E000AB42C3D0236923F001032361E4E71846EC +:1054F000C7E700BF0000080800380240003C024037 +:10550000084908B50B7828B11BB9FFF7EBFE01235A +:105510000B7008BD002BFCD0BDE808400870FFF7F9 +:10552000FBBE00BF965700200149024800F0A8B812 +:1055300000FF0300000100200846114601F09CBA5C +:10554000012001F099BA0000084601F0B3BA00004A +:1055500038B5EFF311859DB9EFF30584C4F3080462 +:10556000302334B183F31188FFF74AFD85F31188A6 +:1055700038BD83F31188FFF743FD84F3118838BDEC +:10558000BDE83840FFF73CBD38B5FFF7E1FF114CEF +:10559000114AC00840EA4170A0FB025EC908A0FBA6 +:1055A000040C1CEB050CA1FB04404FF000035B4115 +:1055B000A1FB02121CEB040C43EB000011EB0E01EB +:1055C00042F10002411842F10000090941EA00706D +:1055D00038BD00BFCFF753E3A59BC42010B50244EC +:1055E000064BD2B2904200D110BD441C00B253F819 +:1055F000200041F8040BE0B2F4E700BF502800405F +:105600000F4B30B51C6F240407D41C6F44F4007496 +:105610001C671C6F44F400441C670A4C236843F465 +:10562000807323600244084BD2B2904200D130BD57 +:10563000441C00B251F8045B43F82050E0B2F4E798 +:1056400000380240007000405028004007B5012299 +:1056500001A90020FFF7C2FF019803B05DF804FB29 +:1056600013B50446FFF7F2FFA04205D0012201A9BD +:1056700000200194FFF7C4FF02B010BD7047000086 +:105680007047000070470000074B45F255521A6002 +:1056900002225A6040F6FF729A604CF6CC421A60C1 +:1056A000024B01221A70704700300040C0570020A2 +:1056B000034B1B781BB1034B4AF6AA221A607047B2 +:1056C000C057002000300040034B1A681AB9034A43 +:1056D000D2F874281A607047BC570020003002408E +:1056E000024B4FF08072C3F87428704700300240BC +:1056F00008B5FFF7E9FF024B1868C0F3407008BD1A +:10570000BC57002008B5FFF7DFFF024B1868C0F355 +:10571000007008BDBC57002070470000FEE7000085 +:105720000A4B0B480B4A90420BD30B4BDA1C121A54 +:10573000C11E22F003028B4238BF00220021FCF779 +:1057400095B853F8041B40F8041BECE76C70000894 +:10575000DC580020DC580020DC58002070B5D0E96F +:105760001B439E6800224FF0FF3504EB42135101AA +:10577000D3F800090028BEBFD3F8000940F08040EC +:10578000C3F80009D3F8000B0028BEBFD3F8000B04 +:1057900040F08040C3F8000B013263189642C3F812 +:1057A0000859C3F8085BE0D24FF00113C4F81C3865 +:1057B00070BD0000890141F02001016103699B0671 +:1057C000FCD41220FFF774BA10B5054C2046FEF742 +:1057D0002BFF4FF0A043E366024B236710BD00BFD1 +:1057E000C4570020B46E000870B50378012B05463D +:1057F00050D12A4BC46E98421BD1294B5A6B42F0B0 +:1058000080025A635A6D42F080025A655A6D5A6995 +:1058100042F080025A615A6922F080025A610E21D8 +:1058200043205B69FEF76EFB1E4BE3601E4BC4F822 +:1058300000380023C4F8003EC0232360EE6E4FF40E +:105840000413A3633369002BFCDA012333610C20BA +:10585000FFF72EFA3369DB07FCD41220FFF728FA92 +:105860003369002BFCDA0026A6602846FFF776FF96 +:105870006B68C4F81068DB68C4F81468C4F81C6866 +:105880004BB90A4BA3614FF0FF336361A36843F048 +:105890000103A36070BD064BF4E700BFC4570020AE +:1058A000003802404014004003002002003C30C099 +:1058B000083C30C0F8B5C46E054600212046FFF70D +:1058C00079FF296F00234FF001128F68C4F8343834 +:1058D0004FF00066C4F81C284FF0FF3004EB431271 +:1058E00001339F42C2F80069C2F8006BC2F8080990 +:1058F000C2F8080BF2D20B68EA6E6B676362102382 +:105900001361166916F01006FBD11220FFF7D0F9CB +:10591000D4F8003823F4FE63C4F80038A36943F4D4 +:10592000402343F01003A3610923C4F81038C4F8DE +:1059300014380A4BEB604FF0C043C4F8103B084BDF +:10594000C4F8003BC4F81069C4F800396B6F03F168 +:10595000100243F480136A67A362F8BD906E0008DA +:1059600040800010C26E90F86610D2F8003823F420 +:10597000FE6343EA0113C2F8003870472DE9F8438B +:1059800000EB8103C56EDA68166806F00306731E25 +:10599000022B05EB41130C4680460FFA81F94FEAC2 +:1059A00041104FF00001C3F8101B4FF0010104F14A +:1059B000100398BFB60401FA03F391698EBF334E0A +:1059C00006F1805606F5004600293AD0578A04F1C0 +:1059D0005801490137436F50D5F81C180B43C5F8DF +:1059E0001C382B180021C3F8101953690127611EB8 +:1059F000A7409BB3138A928B9B08012A88BF53430D +:105A0000D8F87420981842EA034301F1400205EBEC +:105A10008202C8F87400214653602846FFF7CAFE88 +:105A200008EB8900C3681B8A43EA84534834640145 +:105A30001E432E51D5F81C381F43C5F81C78BDE80D +:105A4000F88305EB4917D7F8001B21F40041C7F88C +:105A5000001BD5F81C1821EA0303C0E704F13F033B +:105A600005EB83030A4A5A6028462146FFF7A2FE47 +:105A700005EB4910D0F8003923F40043C0F8003991 +:105A8000D5F81C3823EA0707D7E700BF00800010CD +:105A900000040002026F12684267FFF75FBE000059 +:105AA0005831C36E49015B5813F4004004D013F41D +:105AB000001F0CBF02200120704700004831C36E58 +:105AC00049015B5813F4004004D013F4001F0CBFCD +:105AD000022001207047000000EB8101CB68196AA9 +:105AE0000B6813604B6853607047000000EB810344 +:105AF00030B5DD68AA691368D36019B9402B84BF3B +:105B0000402313606B8A1468C26E1C44013CB4FBD2 +:105B1000F3F46343033323F0030302EB411043EA3E +:105B2000C44343F0C043C0F8103B2B6803F00303A9 +:105B3000012B09B20ED1D2F8083802EB411013F450 +:105B4000807FD0F8003B14BF43F0805343F00053F4 +:105B5000C0F8003B02EB4112D2F8003B43F0044393 +:105B6000C2F8003B30BD00002DE9F041244DEE6E3F +:105B700006EB40130446D3F8087BC3F8087B3807CC +:105B80000AD5D6F81438190706D505EB8403214643 +:105B9000DB6828465B689847FA071FD5D6F81438A3 +:105BA000DB071BD505EB8403D968CCB98B69488A20 +:105BB0005A68B2FBF0F600FB16228AB91868DA6858 +:105BC00090420DD2121AC3E90024302383F31188C6 +:105BD0000B482146FFF78AFF84F31188BDE8F08166 +:105BE000012303FA04F26B8923EA02036B81CB6879 +:105BF000002BF3D021460248BDE8F041184700BF12 +:105C0000C457002000EB810370B5DD68C36E6C697A +:105C10002668E6604A0156BB1A444FF40020C2F8D9 +:105C200010092A6802F00302012A0AB20ED1D3F841 +:105C3000080803EB421410F4807FD4F8000914BF65 +:105C400040F0805040F00050C4F8000903EB4212CD +:105C5000D2F8000940F00440C2F80009D3F8340833 +:105C6000012202FA01F10143C3F8341870BD19B9D9 +:105C7000402E84BF4020206020682E8A8419013C79 +:105C8000B4FBF6F440EAC44040F000501A44C6E7C2 +:105C90002DE9F8433B4DEE6E06EB40130446D3F876 +:105CA0000889C3F8088918F0010F4FEA40171AD085 +:105CB000D6F81038DB0716D505EB8003D9684B6999 +:105CC0001868DA68904230D2121A4FF000091A6050 +:105CD000C3F80490302383F3118821462846FFF748 +:105CE00091FF89F3118818F0800F1CD0D6F8343852 +:105CF0000126A640334216D005EB8403ED6ED3F89F +:105D00000CC0DCF814200134E4B2D2F800E005EB5A +:105D100004342F445168714515D3D5F8343823EA3B +:105D20000606C5F83468BDE8F883012303FA04F2D7 +:105D30002B8923EA02032B818B68002BD3D02146C9 +:105D400028469847CFE7BCF81000AEEB010383422A +:105D500028BF0346D7F8180980B2B3EB800FE2D80A +:105D60009068A0F1040959F8048FC4F80080A0EBF2 +:105D700009089844B8F1040FF5D818440B44906012 +:105D80005360C7E7C45700202DE9F74FAC4CE56ED0 +:105D90006E69AB691E4016F480586E6107D02046CC +:105DA000FEF7B0FC03B0BDE8F04FFDF78DBF002E4D +:105DB00012DAD5F8003EA2489B071EBFD5F8003E78 +:105DC00023F00303C5F8003ED5F8043823F001039F +:105DD000C5F80438FEF7C2FC370505D59848FFF72B +:105DE000BDFC9748FEF7A8FCB0040CD5D5F80838E0 +:105DF00013F0060FEB6823F470530CBF43F41053F9 +:105E000043F4A053EB6031071BD56368DB681BB913 +:105E1000AB6923F00803AB612378052B0CD1D5F8CF +:105E2000003E87489A071EBFD5F8003E23F00303C3 +:105E3000C5F8003EFEF792FC6368DB680BB1804852 +:105E40009847F30200F18980B70227D5D4F86C9007 +:105E5000DFF8ECB100274FF0010A09EB4712D2F846 +:105E6000003B03F44023B3F5802F11D1D2F8003B5F +:105E7000002B0DDA62890AFA07F322EA0303638131 +:105E800004EB8703DB68DB6813B139465846984753 +:105E9000236F01379B68FFB29F42DED9F00617D50A +:105EA000E76E3A6AC2F30A1002F00F0302F4F0122E +:105EB000B2F5802F00F09980B2F5402F08D104EBA5 +:105EC00083030022DB681B6A07F5805790427ED16E +:105ED0003303D5F818481DD5E70302D50020FFF796 +:105EE00043FEA50302D50120FFF73EFE600302D565 +:105EF0000220FFF739FE210302D50320FFF734FE0D +:105F0000E20202D50420FFF72FFEA30202D50520EE +:105F1000FFF72AFE77037FF545AFE60702D500209D +:105F2000FFF7B6FEA50702D50120FFF7B1FE600717 +:105F300002D50220FFF7ACFE210702D50320FFF7B0 +:105F4000A7FEE20602D50420FFF7A2FEA3067FF516 +:105F500029AF0520FFF79CFE24E7E36EDFF8E0A001 +:105F6000019300274FF00109236F9B685FFA87FBBD +:105F70009B453FF669AF019B03EB4B13D3F8001928 +:105F800001F44021B1F5802F1FD1D3F80019002969 +:105F90001BDAD3F8001941F09041C3F80019D3F887 +:105FA00000190029FBDB5946E06EFFF703FC21894D +:105FB00009FA0BF321EA0303238104EB8B03DB686B +:105FC0009B6813B15946504698470137CCE7910773 +:105FD00008BFD7F80080072A98BF03F8018B02F1A9 +:105FE000010298BF4FEA182870E7023304EB8302DE +:105FF00007F580575268D2F818C0DCF80820DCE9B1 +:10600000001CA1EB0C0C002188420AD104EB830494 +:1060100063689B699A6802449A605A6802445A60AD +:1060200056E711F0030F08BFD7F800808C4588BFF2 +:1060300002F8018B01F1010188BF4FEA1828E3E75C +:10604000C4570020C36E03EB4111D1F8003B43F469 +:106050000013C1F8003B7047C36E03EB4111D1F848 +:10606000003943F40013C1F800397047C36E03EBE5 +:106070004111D1F8003B23F40013C1F8003B7047F5 +:10608000C36E03EB4111D1F8003923F40013C1F8BA +:106090000039704730B5039C0172043304FB0325BB +:1060A000C0E90653049B03630021059BC160C0E95E +:1060B0000000C0E90422C0E90842C0E90A114363B4 +:1060C00030BD0000416A0022C0E90411C0E90A2283 +:1060D000C2606FF00101FEF75BBE0000D0E9043240 +:1060E000934201D1C2680AB9181D70470020704759 +:1060F00003691960C2680132C260C26913448269CF +:106100000361934224BF436A03610021FEF734BE5A +:1061100038B504460D46E3683BB16269131D126849 +:10612000A3621344E362002007E0237A33B92946CF +:106130002046FEF711FE0028EDDA38BD6FF00100B1 +:10614000FBE70000C368C269013BC36043691344B5 +:1061500082694361934224BF436A4361002383629F +:10616000036B03B11847704770B53023044683F3BF +:106170001188866A3EB9FFF7CBFF054618B186F352 +:106180001188284670BDA36AE26A13F8015BA36216 +:10619000934202D32046FFF7D5FF002383F31188F3 +:1061A000EFE700002DE9F84F04460E4617469846E3 +:1061B0004FF0300989F311880025AA46D4F828B099 +:1061C000BBF1000F09D141462046FFF7A1FF20B1E6 +:1061D0008BF311882846BDE8F88FD4E90A12A7EBA3 +:1061E000050B521A934528BF9346BBF1400F1BD9AC +:1061F000334601F1400251F8040B43F8040B91427D +:10620000F9D1A36A40334036A3624035D4E90A236A +:106210009A4202D32046FFF795FF8AF31188BD42C8 +:10622000D8D289F31188C9E730465A46FBF7F8FA05 +:10623000A36A5B445E44A3625D44E7E710B5029C39 +:106240000172043303FB0421C0E906130023C0E9F3 +:106250000A33039B0363049BC460C0E90000C0E9E8 +:106260000422C0E90842436310BD0000026AC26014 +:10627000426AC0E904220022C0E90A226FF001014B +:10628000FEF786BDD0E904239A4201D1C26822B943 +:10629000184650F8043B0B60704700231846FAE795 +:1062A000C368C2690133C3604369134482694361AF +:1062B000934224BF436A43610021FEF75DBD0000A5 +:1062C00038B504460D46E3683BB123691A1DA26246 +:1062D000E2691344E362002007E0237A33B92946D8 +:1062E0002046FEF739FD0028EDDA38BD6FF00100D9 +:1062F000FBE7000003691960C268013AC260C26925 +:10630000134482690361934224BF436A03610023FB +:106310008362036B03B118477047000070B53023E8 +:106320000D460446114683F31188866A2EB9FFF79D +:10633000C7FF10B186F3118870BDA36A1D70A36AF0 +:10634000E26A01339342A36204D3E169204604392F +:10635000FFF7D0FF002080F31188EDE72DE9F84F1B +:1063600004460D46904699464FF0300A8AF311884C +:106370000026B346A76A4FB949462046FFF7A0FF5B +:1063800020B187F311883046BDE8F88FD4E90A07B9 +:106390003A1AA8EB0607974228BF1746402F1BD989 +:1063A00005F1400355F8042B40F8042B9D42F9D128 +:1063B000A36A4033A3624036D4E90A239A4204D345 +:1063C000E16920460439FFF795FF8BF311884645B4 +:1063D000D9D28AF31188CDE729463A46FBF720FA4D +:1063E000A36A3B443D44A3623E44E5E7D0E904236D +:1063F0009A4217D1C3689BB1836A8BB1043B9B1A45 +:106400000ED01360C368013BC360C3691A4483693B +:1064100002619A4224BF436A03610023836201231D +:10642000184670470023FBE700F0CCB84FF08043DC +:10643000586A70474FF08043002258631A61022265 +:10644000DA6070474FF080430022DA607047000046 +:106450004FF0804358637047FEE7000070B51B4B58 +:1064600001630025044686B0586085620E46FDF73C +:1064700007FC04F11003C4E904334FF0FF33C4E90F +:106480000635C4E90044A560E562FFF7CFFF2B465F +:106490000246C4E9082304F134010D4A256580232E +:1064A0002046FEF70FFC0123E0600A4A03750092C4 +:1064B00072680192B268CDE90223074B6846CDE9C4 +:1064C0000435FEF727FC06B070BD00BF6850002001 +:1064D000C06E0008C56E000859640008024AD36AFD +:1064E0001843D062704700BF004E00204B684360E5 +:1064F0008B688360CB68C3600B6943614B6903623F +:106500008B6943620B6803607047000008B5234B3A +:1065100023481A6942F0FF021A611A6922F0FF0249 +:106520001A611A691A6B42F0FF021A631A6D42F07F +:10653000FF021A651B4A1B6D1146FFF7D7FF02F1D8 +:106540001C0100F58060FFF7D1FF02F1380100F572 +:106550008060FFF7CBFF02F1540100F58060FFF788 +:10656000C5FF02F1700100F58060FFF7BFFF02F187 +:106570008C0100F58060FFF7B9FF02F1A80100F57A +:106580008060FFF7B3FF02F1C40100F58060FFF700 +:10659000ADFFBDE8084000F08FB800BF00380240F2 +:1065A00000000240CC6E000808B500F01BFAFEF7B0 +:1065B00057FBFFF789F8BDE80840FEF7E5BD00008E +:1065C000704700000F4B1A6C42F001021A641A6EF9 +:1065D00042F001021A660C4A1B6E936843F00103F5 +:1065E00093604FF0804331229A624FF0FF32DA62BB +:1065F00000229A615A63DA605A6001225A611A6075 +:10660000704700BF00380240002004E04FF0804295 +:1066100008B51169D3680B40D9B2C9439B07116112 +:1066200007D5302383F31188FEF740FB002383F363 +:10663000118808BD1E4B1A6962F0FF021A611A69BF +:10664000D2B21A614FF0FF301A695A6958610021BD +:106650005A6959615A691A6A62F080521A621A6A52 +:1066600002F080521A621A6A5A6A58625A6A596269 +:106670005A6A1A6C42F080521A641A6E42F08052C2 +:106680001A661A6E0B4A106840F480701060186F1A +:1066900000F44070B0F5007F1EBF4FF480301867E3 +:1066A0001967536823F40073536000F073B900BF97 +:1066B00000380240007000403B4B3C4A1A643C4AA0 +:1066C0004FF4404111601A6842F001021A601A68E2 +:1066D0009007FCD59A6822F003029A60324B9A68C0 +:1066E00012F00C02FBD1196801F0F90119609A60EF +:1066F0001A6842F480321A601A689103FCD55A6F06 +:1067000042F001025A67284B5A6F9207FCD5294A7A +:106710005A601A6842F080721A60254A5368580419 +:10672000FCD5214B1A689101FCD5234AC3F884207B +:106730001A6842F080621A601A681201FCD51F4A7A +:106740009A600322C3F88C204FF00062C3F89420B3 +:106750001B4B1A681B4B9A421B4B21D11B4A1168D9 +:106760001B4A91421CD140F203121A60164A136868 +:1067700003F00F03032BFAD10B4B9A6842F002028D +:106780009A609A6802F00C02082AFAD15A6C42F414 +:1067900080425A645A6E42F480425A665B6E704779 +:1067A00040F20372E1E700BF00380240000400102D +:1067B000007000400819400210300024009488380E +:1067C000002004E011640020003C024000ED00E0E5 +:1067D00041C20F41074A08B5536903F001035361F1 +:1067E00023B1054A13680BB150689847BDE80840CB +:1067F000FDF76ABA003C014054580020074A08B52A +:10680000536903F00203536123B1054A93680BB146 +:10681000D0689847BDE80840FDF756BA003C0140F3 +:1068200054580020074A08B5536903F00403536124 +:1068300023B1054A13690BB150699847BDE8084078 +:10684000FDF742BA003C014054580020074A08B501 +:10685000536903F00803536123B1054A93690BB1EF +:10686000D0699847BDE80840FDF72EBA003C0140CA +:1068700054580020074A08B5536903F010035361C8 +:1068800023B1054A136A0BB1506A9847BDE8084026 +:10689000FDF71ABA003C014054580020164B10B5C1 +:1068A0005C6904F478725A61A30604D5134A936AAA +:1068B0000BB1D06A9847600604D5104A136B0BB130 +:1068C000506B9847210604D50C4A936B0BB1D06BE3 +:1068D0009847E20504D5094A136C0BB1506C9847F0 +:1068E000A30504D5054A936C0BB1D06C9847BDE85D +:1068F0001040FDF7E9B900BF003C014054580020AA +:10690000194B10B55C6904F47C425A61620504D5E8 +:10691000164A136D0BB1506D9847230504D5134AE1 +:10692000936D0BB1D06D9847E00404D50F4A136EF8 +:106930000BB1506E9847A10404D50C4A936E0BB16D +:10694000D06E9847620404D5084A136F0BB1506F9C +:106950009847230404D5054A936F0BB1D06F98472D +:10696000BDE81040FDF7B0B9003C0140545800208C +:1069700008B50348FDF744FABDE80840FDF7A4B99F +:10698000904B002008B5FFF741FEBDE80840FDF739 +:106990009BB90000062108B50846FDF7B3FA0621A9 +:1069A0000720FDF7AFFA06210820FDF7ABFA062114 +:1069B0000920FDF7A7FA06210A20FDF7A3FA062110 +:1069C0001720FDF79FFA06212820FDF79BFA0721E3 +:1069D0001C20FDF797FABDE808400C212520FDF7A3 +:1069E00091BA000008B5FFF725FE00F00DF8FDF79D +:1069F00031FCFDF717FEFDF7EFFCFFF7E1FDBDE809 +:106A00000840FFF711BD00000023054A1946013375 +:106A1000102BC2E9001102F10802F8D1704700BF43 +:106A2000545800200B460146184600F02DB80000CF +:106A300000F040B8012838BF012010B504462046B8 +:106A400000F030F830B900F007F808B900F00CF8A1 +:106A50008047F4E710BD0000024B1868BFF35B8F5E +:106A6000704700BFD458002008B5062000F084F815 +:106A70000120FEF7D7FA0000024B0A4601461868CB +:106A8000FEF75ABD5823002010B5054C13462CB113 +:106A90000A4601460220AFF3008010BD2046FCE705 +:106AA00000000000024B01461868FEF749BD00BF18 +:106AB00058230020024B01461868FEF745BD00BF71 +:106AC0005823002010B501390244904201D1002022 +:106AD00005E0037811F8014FA34201D0181B10BD47 +:106AE0000130F2E72DE9F041A3B1C91A177801444A +:106AF000044603F1FF3C8C42204601D9002009E006 +:106B00000578BD4204F10104F5D10CEB0405D6185B +:106B1000A54201D1BDE8F08115F8018D16F801ED0F +:106B2000F045F5D0E7E700001F2938B504460D46CB +:106B300004D9162303604FF0FF3038BD426C12B108 +:106B400052F821304BB9204600F030F82A46014671 +:106B50002046BDE8384000F017B8012B0AD0591C78 +:106B600003D1162303600120E7E7002442F8254003 +:106B7000284698470020E0E7024B01461868FFF7D7 +:106B8000D3BF00BF5823002038B5074D002304466B +:106B9000084611462B60FEF749FA431C02D12B68C8 +:106BA00003B1236038BD00BFD8580020FEF738BAC3 +:106BB000034611F8012B03F8012B002AF9D1704785 +:106BC000696E2E7369657272616165726F7370614F +:106BD00063652E507265636973696F6E506F696E7D +:106BE0007400000053544D3332463F3F3F0053542E +:106BF0004D3332463430780053544D3332463432BC +:106C0000780053544D33324634343658580000001F +:106C1000012033000010410001105A0003105900F8 +:106C20000710310000000000E46B000813040000AE +:106C3000EE6B000819040000F86B00082104000046 +:106C4000026C000840A2E4F1646891060041A3E5EB +:106C5000F2656992070000004261642043414E4999 +:106C60006661636520696E6465782E0080000000AF +:106C70000080000000008000000000000000000014 +:106C800095210008B529000811290008D521000820 +:106C9000E1210008E1230008A5210008B521000832 +:106CA000A9210008B1210008AD2100080523000832 +:106CB000B9210008852C0008C9210008D922000844 +:106CC000009600000000000000000000000000002E +:106CD000000000000000000015420008014200080A +:106CE0003D420008294200083542000821420008C0 +:106CF0000D420008F9410008494200080000000068 +:106D000055430008414300087D43000869430008DB +:106D100075430008614300084D43000839430008EB +:106D2000894300080000000001000000000000008E +:106D300063300000306D0008584E0020685000207D +:106D4000536965727261204165726F73706163652A +:106D5000005369657272612D507265636973696F62 +:106D60006E506F696E742D424C0025534552494157 +:106D70004C250000020000000000000071450008E2 +:106D8000DD4500084000400008550020185500204F +:106D900002000000000000000300000000000000EE +:106DA00021460008000000001000000028550020C7 +:106DB000000000000100000000000000C457002097 +:106DC000010102002551000835500008D15000088B +:106DD000B550000843000000DC6D000809024300C4 +:106DE000020100C032090400000102020100052472 +:106DF00000100105240100010424020205240600FC +:106E000001070582030800FF09040100020A0000CF +:106E10000007050102400000070581024000000054 +:106E200012000000286E000812011001020000404C +:106E30000912415700020102030100000403090482 +:106E400025424F41524425005369657272612D50AD +:106E50007265636973696F6E506F696E740030316B +:106E600032333435363738394142434445460000E1 +:106E70000040000000400000004000000040000012 +:106E800000000100000002000000020000000200FB +:106E900000000000754700082D4A0008D94A000884 +:106EA000400040003C5800203C58002001000000F9 +:106EB0004C58002080000000400100000500000048 +:106EC0006D61696E0069646C650000000000002857 +:106ED00000020000AAAAAAAA00000024FFFF0000E6 +:106EE000000000000000000000A00A1500000000E3 +:106EF000AAAAAA9600500000FF8F000000000077A9 +:106F0000880000000510000000000000AA9AAAAA4C +:106F100005000000FFFF000000000000000000006E +:106F20000000000000000000AAAAAAAA00000000B9 +:106F3000FFFF000000000000000000000000000053 +:106F400000000000AAAAAAAA00000000FFFF00009B +:106F50000000000000000000000000000000000031 +:106F6000AAAAAAAA00000000FFFF0000000000007B +:106F7000000000000000000000000000AAAAAAAA69 +:106F800000000000FFFF0000000000000000000003 +:106F900000000000000000000A00000000000000E7 +:106FA00003000000000000000000000000000000DE +:106FB000470400000000000000000700000000007F +:106FC00040420F00FE2A0100D2040000FF00000032 +:106FD00070500020904B0020009600000000080038 +:106FE0009600000000080000040000003C6E00084D +:106FF0000000000000000000000000000000000091 +:1070000000000000000000005C23002000000000E1 +:107010000000000000000000000000000000000070 +:107020000000000000000000000000000000000060 +:107030000000000000000000000000000000000050 +:107040000000000000000000000000000000000040 +:107050000000000000000000000000000000000030 +:0C70600000000000000000000000000024 :00000001FF diff --git a/Tools/bootloaders/Sierra-TrueNavIC_bl.bin b/Tools/bootloaders/Sierra-TrueNavIC_bl.bin index f4cbd81f201bb8..999c3fb439f7f2 100755 Binary files a/Tools/bootloaders/Sierra-TrueNavIC_bl.bin and b/Tools/bootloaders/Sierra-TrueNavIC_bl.bin differ diff --git a/Tools/bootloaders/Sierra-TrueNavIC_bl.hex b/Tools/bootloaders/Sierra-TrueNavIC_bl.hex index cc08da520c12ab..186fcc74c01b03 100644 --- a/Tools/bootloaders/Sierra-TrueNavIC_bl.hex +++ b/Tools/bootloaders/Sierra-TrueNavIC_bl.hex @@ -1,19 +1,19 @@ :020000040800F2 -:1000000000090020B1010008F9220008B12200080F -:10001000D9220008B1220008D1220008B30100084B -:10002000B3010008B3010008B3010008ED32000875 +:1000000000090020B1010008ED220008A522000827 +:10001000CD220008A5220008C5220008B30100086F +:10002000B3010008B3010008B3010008E132000881 :10003000B3010008B3010008B3010008B3010008D0 :10004000B3010008B3010008B3010008B3010008C0 -:10005000B3010008B30100084D40000875400008D6 -:100060009D400008C5400008ED400008B3010008AD +:10005000B3010008B3010008454000086D400008E6 +:1000600095400008BD400008E5400008B3010008C5 :10007000B3010008B3010008B3010008B301000890 -:10008000B3010008B3010008B301000865220008AD -:1000900091220008A1220008B301000815410008C0 +:10008000B3010008B3010008B301000859220008B9 +:100090008522000895220008B30100080D410008E0 :1000A000B3010008B3010008B3010008B301000860 -:1000B000E9410008B3010008B3010008B3010008DA +:1000B000E1410008B3010008B3010008B3010008E2 :1000C000B3010008B3010008B3010008B301000840 :1000D000B3010008B3010008B3010008B301000830 -:1000E00079410008B3010008B3010008B30100081A +:1000E00071410008B3010008B3010008B301000822 :1000F000B3010008B3010008B3010008B301000810 :10010000B3010008B3010008B3010008B3010008FF :10011000B3010008B3010008B3010008B3010008EF @@ -25,1087 +25,1086 @@ :10017000B3010008B3010008B3010008B30100088F :10018000B3010008B3010008B3010008B30100087F :10019000B3010008B3010008B3010008B30100086F -:1001A000210F000800000000000000000000000017 +:1001A000190F00080000000000000000000000001F :1001B00002E000F000F8FEE772B6374880F30888E6 :1001C000364880F3098836483649086040F2000016 :1001D000CCF200004EF63471CEF200010860BFF39D :1001E0004F8FBFF36F8F40F20000C0F2F0004EF669 :1001F0008851CEF200010860BFF34F8FBFF36F8FBD :100200004FF00000E1EE100A4EF63C71CEF2000114 -:100210000860062080F31488BFF36F8F03F030FD71 -:1002200003F0B2FD4FF055301F491B4A91423CBFCD +:100210000860062080F31488BFF36F8F03F02CFD75 +:1002200003F0AEFD4FF055301F491B4A91423CBFD1 :1002300041F8040BFAE71D49184A91423CBF41F8C6 :10024000040BFAE71A491B4A1B4B9A423EBF51F86E :10025000040B42F8040BF8E700201849184A9142B1 -:100260003CBF41F8040BFAE703F00EFD03F0E0FD9C +:100260003CBF41F8040BFAE703F00AFD03F0DCFDA4 :10027000144C154DAC4203DA54F8041B8847F9E7D7 :1002800000F042F8114C124DAC4203DA54F8041B52 -:100290008847F9E703F0F6BC0009002000110020B0 +:100290008847F9E703F0F2BC0009002000110020B4 :1002A0000000000808ED00E0000100200009002027 -:1002B000C8440008001100207C110020801100209B +:1002B000C0440008001100207C11002080110020A3 :1002C000FC3A0020A0010008A4010008A4010008D5 :1002D000A40100082DE9F04F2DED108AC1F80CD0D3 :1002E000C3689D46BDEC108ABDE8F08F002383F300 -:1002F00011882846A047002003F068F9FEE703F0C4 -:10030000F1F800DFFEE70000F8B500F01BFE03F097 -:1003100059FC074603F0AAFC0546D0BB294B9F4277 -:1003200037D001339F4237D0274B27F0FF029A4244 -:1003300035D1F8B200F03EFC2E4642F2107400F0C7 -:100340003FFC08B10024264601F0B2F858B3032060 -:1003500000F03EF80024264635B11C4B9F4203D0E6 -:1003600003F07CFC00242646002003F035FC0EB18F -:1003700000F044F800F056FC00F0E6FD01F0C4FF88 -:100380000546B4B900F096FC4FF47A7003F024F9F6 -:10039000F7E72E460024D2E704460126CFE70646BB -:1003A0004FF47A74CBE7002CD6D04FF47A74012640 -:1003B000D2E701F0A9FF431BA342E3D900F01EF8E6 -:1003C000DCE700BF010007B0000008B0263A09B022 -:1003D000084B187003280CD8DFE800F00805020865 -:1003E000022000F00BBE022000F002BE024B0022F1 -:1003F0005A607047801100208411002010B501F070 -:1004000057F830B1234B03221A70234B00225A6055 -:1004100010BD224B224A1C4619680131F8D0043322 -:100420009342F9D16268A242F2D31E4B9B6803F15A -:10043000006303F520439A42EAD203F0E1FB03F0A4 -:10044000F3FB002000F09AFD0220FFF7C1FF164BDE -:100450009A6D00229A65996F9A67996FD96DDA65DE -:10046000D96FDA67D96F196E1A66D3F88010C3F89E -:100470008020D3F8803072B64FF0E0233021C3F8EB -:10048000084DD4E9003281F311889D4683F3088832 -:100490001047BDE7801100208411002000A0000853 -:1004A00020A000080011002000100240094A136833 -:1004B00049F2690099B21B0C00FB01331360064B33 -:1004C000186844F2506182B2000C01FB020018600F -:1004D00080B27047141100201011002010B50021C7 -:1004E0001022044600F0A4FD034B03CB20606160A2 -:1004F0001868A06010BD00BF9075FF1F2DE9F04186 -:10050000ADF5507D0DF13C086EAC40F2751207461A -:100510000D4610A80021C8F8001000F089FD4FF426 -:10052000C4720021204600F083FD01F0EDFE254B52 -:100530004FF47A72B0FBF2F0186093E807000223E0 -:1005400084E807000DF5ED702382FFF7C7FF4BF23B -:1005500014631D49238407A803F052FF1C2384F869 -:1005600032310DF2EB226B440DF1340C1E4603CEFA -:10057000664510605160334602F10802F6D13068DA -:10058000106041460122204600F09EFD00230393A7 -:10059000AB7E029305F11903019380B20123CDE9EB -:1005A00004800093E97E05A3D3E90023384602F0D6 -:1005B00073FA0DF5507DBDE8F08100BF9E6AC4213D -:1005C000818A46EE8C110020104400082DE9F0418C -:1005D0002C4C237ADAB080460D465BBB27A928460F -:1005E00000F082FE0746002842D19DF89D60C82E8B -:1005F0003ED801464FF4A662204600F019FD4FF4A4 -:100600008073C4F8F8314FF40073C4F80C334FF41E -:100610004073C4F8203432460DF19E0104F1090004 -:1006200000F0F4FC26449DF89C30777223720BB9DD -:10063000EB7E23728122002106AC27A800F0F8FC93 -:100640000122214627A800F08BFE00230393AB7EF6 -:10065000029305F1190380B201932823CDE90440E8 -:100660000093E97E05A3D3E90023404602F014FA83 -:100670005AB0BDE8F08100BFAFF30080264172722E -:10068000DF25D7B7B0320020F0B5254E4FF48A757C -:1006900005FB0065F1B096F8D83085F8DC30002411 -:1006A000D822214685F8E8403AA800F0C1FC06F1BE -:1006B000090000F0B5FCD5F8E4308DF8F000C2B2C6 -:1006C00006AF06F109010DF1F100CDE93A3400F071 -:1006D0009DFC394601223AA800F06EFE80B2CDE9B9 -:1006E000047008230127CDE9023706F1D8030193EE -:1006F00030230093317A0B4807A3D3E9002302F09B -:10070000CBF9A04206DD01F0FFFDC5F8E000384658 -:1007100071B0F0BD2046FBE778F6339F93CACD8DCC -:10072000B0320020A42100202DE9F0411D4D1E4EC5 -:100730001E4F86B0284602F0DBF9034658B300246A -:10074000CDE90344ADF81440027B8DF8142099687C -:100750004068029403AA03C21B68DFF8548043F088 -:100760000043029301F0D2FD821941F1000300948D -:1007700002A9384601F07AF8A04205DD284602F0C9 -:10078000BBF988F80040D5E798F80030072B05D86A -:10079000013388F8003006B0BDE8F081014802F06E -:1007A000ABF9F8E7A421002040420F00D821002037 -:1007B000E537002070B50D4614461E4602F0C8F815 -:1007C00050B9022E10D1012C0ED112A3D3E900236F -:1007D000C5E90023012007E0282C10D005D8012C02 -:1007E00009D0052C0FD0002070BD302CFBD10BA3FD -:1007F000D3E90023ECE70BA3D3E90023E8E70BA33D -:10080000D3E90023E4E70BA3D3E90023E0E700BF2B -:10081000AFF30080401DA12026812A0B78F6339F7C -:1008200093CACD8D9E6AC421818A46EE264172729A -:10083000DF25D7B7F017304A39059E5638B505463B -:100840000E4C0021013500F0BBFBA4F82C55B4F888 -:100850002C0500F09DFB78B1B4F82C0500F0A8FB46 -:10086000014648B9B4F82C0500F0AAFBB4F82C35C1 -:100870000133A4F82C35EAE738BD00BFB0320020C0 -:1008800010B50A4B0A4A1A6003F5805393F86020AA -:100890003AB9DC6D2CB1204600F088FE204603F00A -:1008A000EFFCBDE81040034800F080BED8210020D6 -:1008B0006C440008203200202DE9F04F8FB000AFCB -:1008C00005460C4602F044F8002849D1237E022B4D -:1008D0001BD1E38A012B18D101F016FD0646FFF764 -:1008E000E5FD03464FF4C870DFF8C482B3FBF0F2B5 -:1008F00006F5167602FB103316FA83F3C8F80030BB -:10090000E37E33B9A34B00221A703C37BD46BDE8E5 -:10091000F08F07F12401204600F0A4FC0028F4D158 -:1009200007F11400FFF7DAFD97F8264007F11401EC -:10093000224607F1270003F0EDFC0028E2D10F2C3E -:1009400008D8944B1C70D8F80030A3F51673C8F87B -:100950000030DAE797F82410284601F0F1FFD4E7D9 -:10096000E38A282B2BD010D8012B23D0052BCCD1F8 -:10097000BFF34F8F8849894BCA6802F4E062134382 -:10098000CB60BFF34F8F00BFFDE7302BBDD1844E4E -:10099000E17E327A9142B8D1607E3146002291F8F0 -:1009A000DC50854200F0A5800132042A01F58A71ED -:1009B000F5D1AAE721462846FFF7A0FDA5E7214685 -:1009C0002846FFF703FEA0E7B2F8EC507B6005F184 -:1009D00003094FEA99094FEA8902D11DC908A8EB1A -:1009E000C1039D46EB460021584600F021FB04F16F -:1009F000EE012A463144584600F008FB7B6813B9E3 -:100A0000012000F0BBFA96F8D20000F0C1FA0446CB -:100A100030B9307200F0DCFA204600F0AFFAB1E0F5 -:100A2000D6F8D4203AB996F8D200B6F82C258242EE -:100A300001D8FFF703FFD6F8D4202A44944208D205 -:100A400096F8D200B6F82C250130824201D8FFF783 -:100A5000F5FE70685FFA89F2594600F0F1FA08B9BC -:100A6000C54679E0726896F8D2002A447260D6F8DA -:100A7000D42005EB0209C6F8D49000F089FA81452C -:100A800009D396F8D220D6F8D4000132001B86F89C -:100A9000D220C6F8D400FF2D0FD80024347200F005 -:100AA00097FA204600F06AFA00F002FD3D4B1881EB -:100AB00008B9FFF7A3FCC54627E7BB6896F8D9003D -:100AC0000AFB0362FB68D2F8E41082F8E83001F513 -:100AD0008061C2F8E030C2F8E410FFF7D5FDFFF7FF -:100AE00023FE96F8D920013202F0030286F8D920BD -:100AF000B6E74FF48A7A0AFB02F505F1EA013144C0 -:100B0000204600F085FCF86000287FF4FEAE3544F6 -:100B1000012285F8E82001F0F7FBD5F8E020D6EDBA -:100B2000007ADFED216A801A192838BF192040F6B3 -:100B3000B832904228BF1046B8EE677A07EE900AA6 -:100B4000F8EEE77A67EEA67ADFED186AE7EE267A26 -:100B5000FCEEE77AC6ED007A96F8D930BB60BA6849 -:100B600073680AFB02F4321992F8E81059B1D2F80E -:100B7000E4108B42E8463FF427AF002182F8E810EA -:100B8000C2F8E010C5467368064A9B0A0133138118 -:100B9000BBE600BF9D21002000ED00E00400FA0547 -:100BA000B03200208C110020CDCCCC3D6666663F73 -:100BB000A0210020014B1870704700BF9811002041 -:100BC00038B54FF00054134B22689A4220D1124B93 -:100BD000627D12481A70237D03724FF48073C0F84F -:100BE000F8314FF40073C0F80C3300254FF4407314 -:100BF000C0F820340A49C0F8E450C922093000F096 -:100C000005FAE0222946204600F012FA012038BDFC -:100C10000020FCE79AAD44C598110020B0320020B6 -:100C20001600002037B500F043FC194D1949288102 -:100C30000223012218486B7101F002FA002301938C -:100C4000164B174900931748174B4FF4805201F089 -:100C50004FFE164B197811B1124801F071FE01F0E8 -:100C600053FB0446FFF722FC4FF4C873B0FBF3F2CA -:100C700002FB130304F5167010FA83F00C4B186096 -:100C800002F0F4FF08B10F232B8103B030BD00BF89 -:100C90008C11002040420F00D8210020B507000829 -:100CA0009C110020A4210020B90800089811002000 -:100CB000A02100202DE9F04F2DED028B90A7D7E960 -:100CC00000670FF24429D9E90089884C95B00DAD31 -:100CD0009FED848BFFF728FDDFF834B200230C93DF -:100CE000ADF83C300D936B6000230DF125028DEDC6 -:100CF000008B4FF0010A09A958468DF825308DF870 -:100D000024A001F04BF99DF824200023002A40F094 -:100D1000AF80204601F01CFE0546002847D1DFF8D1 -:100D2000F4B101F0F1FADBF8003098423FD301F062 -:100D3000EBFA0790FFF7BAFB079A4FF4C873B0FBC2 -:100D4000F3F101FB130302F5167010FA83F0CBF8F0 -:100D50000000DFF8C4B19BF800100791002914BF10 -:100D60002B46534610A88DF83030FFF7B7FB079994 -:100D7000C1F11002D2B2062A10AB28BF06221944D4 -:100D80000DF13100079200F041F9079A0CAB039383 -:100D9000182302930132564BD2B2CDE900A304923C -:100DA0003B463246204601F019FE8BF8005001F018 -:100DB000ABFA504A504D1368C31AB3F57A7F32D359 -:100DC000106001F0A3FA02460B46204601F09EFE99 -:100DD000204601F0BDFD30B32B7ADFF840A1002B97 -:100DE00014BF032302238AF8053001F08DFA0DF1B8 -:100DF000400B4FF47A730122B0FBF3F05946CAF866 -:100E00000000504600F006FA182302933B4B019372 -:100E100080B240F25513CDE903B0009342464B46F1 -:100E2000204601F0DBFD2B7AB3B101F06DFA4FF0F3 -:100E3000000A83464FF48A7295F8D900504400F0B6 -:100E4000030002FB005393F8E810002934D00AF1A4 -:100E5000010ABAF1040FEFD1C82002F0BDFB2B7AD2 -:100E6000002B7FF434AF15B0BDEC028BBDE8F08FE2 -:100E70004FF0904110A84A6982F002024A61194677 -:100E8000102200F0D5F80DF126030AAA0CA9584645 -:100E900000F0ECFD95E8030011AB83E803009DF83A -:100EA0003C308DF84C300C9B109310A9DDE90A23DF -:100EB000204601F0FFFF17E7D3F8E01049B12B6897 -:100EC000FA2B38BFFA23ABEB01010533B1EB430F2B -:100ED000BDD3FFF7D9FB4FF48A720028B7D1BBE727 -:100EE000AFF300800000000000000000A4210020FB -:100EF0009C210020E0370020B0320020E4370020A1 -:100F0000401DA12026812A0BF1C6A7C1D068080F79 -:100F1000D8210020A02100209D2100208C1100203C -:100F200008B5054800F03EFEBDE80840034A044904 -:100F3000002003F09FB900BFD821002020380020F6 -:100F4000810800087047000070B502F0E1FC094E0E -:100F5000094D3080002428683388834208D902F084 -:100F6000D3FC2B6804440133B4F5204F2B60F2D33B -:100F700070BD00BF14380020E837002002F07ABDB1 -:100F800000F10060920000F5204002F0FDBC00007E -:100F9000054B1A68054B1B889B1A834202D91044E3 -:100FA00002F0B2BC00207047E8370020143800205F -:100FB000024B1B68184402F0ADBC00BFE8370020AC -:100FC000024B1B68184402F0B7BC00BFE837002092 -:100FD000064991F8243033B10023086A81F824309F -:100FE0000822FFF7CDBF0120704700BFEC3700207B -:100FF000022804BF4FF0904398617047022802BF57 -:101000004FF090434FF400329A61704710B50023BF -:10101000934203D0CC5CC4540133F9E710BD000007 -:1010200003460246D01A12F9011B0029FAD1704773 -:1010300002440346934202D003F8011BFAE77047CB -:101040002DE9F8431F4D144695F82420074688469D -:1010500052BBDFF870909CB395F824302BB9202256 -:10106000FF2148462F62FFF7E3FF95F82400C0F107 -:101070000802A24228BF2246D6B24146920005EBA2 -:101080008000FFF7C3FF95F82430A41B1E44F6B27E -:10109000082E17449044E4B285F82460DBD1FFF7B2 -:1010A00097FF0028D7D108E02B6A03EB8203834225 -:1010B000CFD0FFF78DFF0028CBD10020BDE8F8830B -:1010C0000120FBE7EC3700202DE9F0470D460446F0 -:1010D00000219046284640F27912FFF7A9FF2346E7 -:1010E00020220021284601F087FE231D0222202114 -:1010F000284601F081FE631D03222221284601F0CB -:101100007BFEA31D03222521284601F075FE04F174 -:10111000080310222821284601F06EFE04F1100376 -:1011200008223821284601F067FE04F11103082245 -:101130004021284601F060FE04F1120308224821F4 -:10114000284601F059FE04F11403202250212846BC -:1011500001F052FE04F1180340227021284601F0EC -:101160004BFE04F120030822B021284601F044FE82 -:1011700004F121030822B821284601F03DFE04F1C4 -:101180002207C0263B46314608222846083601F091 -:1011900033FEB6F5A07F07F10107F3D104F1320366 -:1011A00008223146284601F027FE002704F1330AC1 -:1011B00094F832304FEAC7099F4209F5A47615D357 -:1011C000B8F1000F08D1314604F59973072228467B -:1011D00001F012FE09F24F16274694F832213B1B0C -:1011E00093420CD3F01DC008BDE8F0870AEB07035B -:1011F00008223146284601F0FFFD0137D8E707F203 -:10120000331331460822284601F0F6FD083601372F -:10121000E3E7000013B504460846002101602346B9 -:10122000C0F803102022019001F0E6FD0198231D73 -:101230000222202101F0E0FD0198631D03222221FA -:1012400001F0DAFD0198A31D0322252101F0D4FD50 -:10125000019804F108031022282101F0CDFD072098 -:1012600002B010BDF7B50023047F00910E4607229F -:101270001946054601F084FC731C009301220023EB -:101280000721284601F07CFCC4B9B31C0093052259 -:1012900023460821284601F073FC0D243746B27816 -:1012A000BB1B934211D32B7FA88A0734E408BBB938 -:1012B000844294BF0020012003B0F0BDAB8ADB0064 -:1012C000083BDB08B3700824E8E7FB1C00932146C9 -:1012D00000230822284601F053FC08340137DEE7DA -:1012E000201A18BF0120E7E7F7B50023047F00911B -:1012F0000E4608221946054601F042FC731CC4B98B -:101300000822009311462346284601F039FC102498 -:10131000012372785F1C013B934211D32B7FA88A73 -:101320000734E408BBB9844294BF0020012003B015 -:10133000F0BDAB8ADB00083BDB0873700824E7E7ED -:10134000F3190093214600230822284601F018FCD7 -:1013500008343B46DDE7201A18BF0120E7E700000C -:10136000F8B50E4605461446002181223046FFF7A7 -:101370005FFE2B4608220021304601F03DFD7CB97E -:101380006B1C07220821304601F036FD0F24012393 -:101390006A785F1C013B934204D3E01DC008F8BD8E -:1013A0000824F4E7EB1921460822304601F024FD19 -:1013B00008343B46ECE70000F8B50E4605461446F7 -:1013C0000021CE223046FFF733FE2B462822002193 -:1013D000304601F011FD7CB905F1080308222821EF -:1013E000304601F009FD30242F462A7A7B1B9342B8 -:1013F00004D3E01DC008F8BD2824F5E707F1090370 -:1014000021460822304601F0F7FC08340137ECE7AA -:10141000F7B5047F00910E460123102200210546F6 -:1014200001F0AEFBC4B9B31C00930922234610217E -:10143000284601F0A5FB192437467288BB1B9A4247 -:1014400011D82B7FA88A0734E408BBB9844294BF23 -:101450000020012003B0F0BDAB8ADB00103BDB08AD -:1014600073801024E8E73B1D0093214600230822E7 -:10147000284601F085FB08340137DEE7201A18BF43 -:101480000120E7E730B5094D0A4491420DD011F82B -:10149000013B5840082340F30004013B2C4013F06B -:1014A000FF0384EA5000F6D1EFE730BD2083B8EDAA -:1014B000F7B5384A106851686B4603C36A46364927 -:1014C0003648082302F036FF0446002833D10A25A7 -:1014D000334A106851686B4603C36A4631492F4846 -:1014E000082302F027FF0446002849D00369B3F51A -:1014F000583F45D8B0F8661041F2B64291423FD10C -:10150000294A024402F15C018B4239D35C3B2349F6 -:1015100000209E1AFFF7B6FF3246074604F1640129 -:101520000020FFF7AFFFA3689F4229D1E3689842EC -:1015300008BF002524E00369B3F5583F27D8418B45 -:1015400041F2B642914220D1174A024402F1100101 -:101550008B4218D3103B114900209D1AFFF792FFD0 -:101560002A46064604F118010020FFF78BFFA36806 -:101570009E4202D1E368984201D00D25A8E70025DC -:10158000284603B0F0BD1025A2E70C25A0E70B25E7 -:101590009EE700BF30440008DC5F030000A00008A5 -:1015A00039440008905F03000860FFF710B5037C22 -:1015B000044613B9006802F0A5FE204610BD0000E5 -:1015C0000023BFF35B8FC360BFF35B8FBFF35B8F01 -:1015D0008360BFF35B8F7047BFF35B8F0068BFF31F -:1015E0005B8F704770B505460C30FFF7F5FF05F1CE -:1015F000080604463046FFF7EFFFA04206D9304602 -:101600006D68FFF7E9FF2544281A70BD3046FFF7E3 -:10161000E3FF201AF9E7000070B50546406898B16D -:1016200005F10800FFF7D8FF05F10C060446304627 -:10163000FFF7D2FF8442304694BF6D680025FFF764 -:10164000CBFF013C2C44201A70BD000038B50C467D -:101650000546FFF7C7FFA04210D305F10800FFF7CA -:10166000BBFF04446868B4FBF0F100FB1144BFF316 -:101670005B8F0120AC60BFF35B8F38BD0020FCE7BF -:101680002DE9F041144607460D46FFF7C5FF844299 -:1016900028BF0446D4B1B84658F80C6B4046FFF753 -:1016A0009BFF3044286040467E68FFF795FF331A61 -:1016B0009C4203D86C600120BDE8F0816B60A41BE4 -:1016C0003B68AB602044E8600220F5E72046F3E782 -:1016D00038B50C460546FFF79FFFA04210D305F131 -:1016E0000C00FFF779FF04446868B4FBF0F100FBDD -:1016F0001144BFF35B8F0120EC60BFF35B8F38BDFB -:101700000020FCE72DE9FF41884669460746FFF7C0 -:10171000B7FF6C4606B204EBC6060025B44209D0FA -:101720006268206808EB0501FFF770FC6368083405 -:101730001D44F3E729463846FFF7CAFF284604B0A0 -:10174000BDE8F081F8B505460C300F46FFF744FFC1 -:1017500005F1080604463046FFF73EFFA04230463A -:1017600088BF6C68FFF738FF201A386020B1304618 -:101770002C68FFF731FF2044F8BD000073B5144614 -:1017800006460D46FFF72EFF844228BF044601900F -:10179000DCB101A93046FFF7D5FF019B33B93268B0 -:1017A000C5E90233C5E9002401200CE09C4238BFA2 -:1017B00001942860019868608442F5D93368AB6071 -:1017C000241AEC60022002B070BD2046FBE7000046 -:1017D0002DE9FF410F466946FFF7D0FF6C4600B286 -:1017E00004EBC0050026AC4209D0D4F8048054F8BC -:1017F000081BB8194246FFF709FC4644F3E7304698 -:1018000004B0BDE8F081000038B50546FFF7E0FF01 -:10181000044601462846FFF719FF204638BD000060 -:1018200010B4026854681A4623465DF8044B184702 -:10183000002070470020704770470000002070476C -:101840000E20704700F5805090F8C800C0F34000AB -:101850007047000000F5805090F9D00070470000FC -:1018600000F58050C0F8CC1001207047F7B50C6827 -:10187000BDF8207014F0005470D10D7B082D6DD888 -:10188000302585F311884569AE6876010CD4AC68C3 -:10189000240108D4AC6814F080545DD184F311881D -:1018A000204603B0F0BD01240E6804F1180C002E90 -:1018B000B8BFF6004FEA0C1CB4BF46F0040676052C -:1018C00045F80C600E680FFA84FC16F0804F18BFC4 -:1018D00005EB0C1E05EB0C1C1EBFDEF8806146F00C -:1018E0000206CEF880610E7BCCF8846105EB04150E -:1018F0008E68C5F88C614E68C5F88861DCF8805147 -:1019000045F00105CCF8805100EB441641F2680522 -:101910002E4405EB44150544C6E9002308350E4660 -:1019200001F10C0C56F804EB45F804EB6645F9D1CF -:10193000843436882E8000EB441407F003052679A2 -:1019400026F00B0635432571002484F31188009797 -:1019500000F0FCFC0120A4E70224A5E74FF0FF30D3 -:101960009FE7000013B500F580540191E06DFFF78B -:1019700053FE1F280AD90199E06D2022FFF7C2FE0D -:10198000A0F120035842584102B010BD0020FBE7EF -:1019900008B5302383F3118800F58050C06DFFF740 -:1019A0000FFE002383F3118808BD000000220260AF -:1019B000828142608260704710B500220023C0E936 -:1019C00000230023044603810C30FFF7EFFF20467D -:1019D00010BD0000F0B5054600F580500C4690F8AB -:1019E000C83013F0040FC3F3800108BF114661F340 -:1019F000820304F1840680F8C83005EB461389B0F1 -:101A00001B79D8072ED57AB319072DD46846FFF76E -:101A1000D3FF05EB441303F5835303F1180703AA1F -:101A2000103318685968144603C40833BB42224671 -:101A3000F7D1186820609B88A380DDE90E23CDE9EB -:101A400000230123ADF808302B686946DB6B28467C -:101A5000984705EB46152B791A075CBF43F008033E -:101A60002B7101E0002AF4D109B0F0BD2DE9F04757 -:101A70009A4688B0074688469146302383F31188FA -:101A800007F580546846FFF797FFE06DFFF7AAFD62 -:101A90001F282AD9E06D20226946FFF7B5FE2028CD -:101AA00023D103AD444605AB2E4603CE9E422060B3 -:101AB0006160354604F10804F6D130682060B388CF -:101AC000A380DDE90023C9E90023BDF80830AAF8A6 -:101AD0000030002383F3118853464A464146384676 -:101AE00008B0BDE8F04700F01FBC002080F311886B -:101AF00008B0BDE8F08700002DE9F84F0023C0E9E9 -:101B00000133254B044640F8183B0F46FFF74EFFC4 -:101B100004F12800FFF750FF04F1480804F582554E -:101B20004646083530462036FFF746FFAE42F9D12B -:101B300004F580554FF480534FF00009C5E913397F -:101B4000C5F848800123EE6504F5875804F58456EE -:101B5000C5F8549085F8583085F86030083608F19B -:101B600008084FF0000A4FF0000B46E908ABA6F159 -:101B70001800FFF71BFF203646F8289C4645F4D195 -:101B800085F8D07017B1054800F0B8FB044B6361CD -:101B90002046BDE8F88F00BF6C44000844440008AC -:101BA0000064004010B5044B197804464A1C1A70B2 -:101BB000FFF7A2FF204610BD1C3800202DE9F0479A -:101BC000002950D0294B2A4FB7FBF1F599428CBF21 -:101BD0000A231123581EB5FBF3FC03FB1C53C4B2AC -:101BE0002BB102280346F5D80020BDE8F0870CF1A0 -:101BF000FF36B6F5806FF7D2C4EBC40E0EF10303C7 -:101C00004FEAE309C3F3C703A4EB030809F1010A90 -:101C10004FF47A755FFA88F009FB05555AFA88F88F -:101C2000B5FBF8F5B5F5617FC1BF0EF1FF33C3F326 -:101C3000C703E01AC0B25C1C50FA84F40CFB04F435 -:101C4000B7FBF4F4A142CFD1013BDBB20F2BCBD8D1 -:101C50000138C0B20728C7D80021107116809170D2 -:101C6000D3700120C1E70846BFE700BF3F420F0025 -:101C700000B4C40470B505460E464FF47A746B691F -:101C80005B6803F00103B34207D04FF47A7001F0B0 -:101C9000A3FC013CF3D1204670BD0120FCE700000D -:101CA00030B54269936913F0700F16D000230B4CC6 -:101CB000936103F1840200EB421211794D0709D5BB -:101CC000890707D5416954F823508D60117941F097 -:101CD000040111710133032BEBD130BD58440008CE -:101CE00073B51D46436916469A68D207044609D55E -:101CF0009A6801219960C2F34002CDE90065002194 -:101D0000FFF768FE63699A68D1050BD59A684FF4AE -:101D100080719960C2F34022CDE90065012120461F -:101D2000FFF758FE63699A68D2030BD59A684FF49F -:101D300080319960C2F34042CDE90065022120461E -:101D4000FFF748FE04F58053D3F8CC0010B10368C8 -:101D50001B699847204602B0BDE87040FFF7A0BF5E -:101D6000F8B504464669002972D106F10C073868B7 -:101D7000800770D006EB01153868D5F8B00110F077 -:101D8000040FD5F8B0011ABFC00840F00040400D64 -:101D9000A061D5F8B0C11CF0020F1CBF40F080401C -:101DA000A061D5F8B40106EB011100F00F0084F832 -:101DB0002400D1F8B8012077D1F8B801000A607783 -:101DC000D1F8B801000CA077D1F8B801000EE07787 -:101DD000D1F8BC0184F82000D1F8BC01000A84F8D5 -:101DE0002100D1F8BC01000C84F82200D1F8BC110C -:101DF000090E84F823103821396004F1340004F10D -:101E0000180104F1240551F8046B40F8046BA94251 -:101E1000F9D109880180C4E90A23214600232386D9 -:101E200051F8283B2046DB6B984704F5805393F824 -:101E3000C820D3F8CC0042F0040283F8C82010B1C7 -:101E400003681B6998472046BDE8F840FFF728BFA4 -:101E500006F110078BE7F8BD10B5044600F056FAFE -:101E600002460B4652EA030102D0013A63F1000335 -:101E70000449086820B12146BDE81040FFF770BF53 -:101E800010BD00BF18380020F0B5302181F3118853 -:101E9000DFF848C000F583510831002404F18405BF -:101EA00000EB45152E7977070ED4F6060CD5D1E94F -:101EB000007697429E4107D246695CF82470B7606D -:101EC0002E7946F004062E710134032C01F1200115 -:101ED000E4D1002383F31188F0BD00BF584400080B -:101EE00008B5302383F31188FFF7DAFE002383F36C -:101EF000118808BDF8B543690546986800F0E050C0 -:101F0000B0F1E05F0F4621D0F8B1302383F31188A0 -:101F100005F583541034002606F1840305EB4313C2 -:101F20001B791A0706D50136032E04F12004F3D1DC -:101F3000012007E05B07F6D42146384600F040FA5E -:101F40000028F0D1002383F31188F8BD0120FCE7BD -:101F500008B5302383F3118800F58050C06DFFF77A -:101F600041FB002383F3118843090CBF01200020AB -:101F700008BD0000F8B51D46002313700F46064645 -:101F80001446FFF7E5FF80F00100387025B12946BF -:101F90003046FFF7AFFF2070F8BD00002DE9B841D3 -:101FA0000C4615461F46804600F0B0F90B462178D6 -:101FB000024609B9287850B14046FFF765FFFFF7A0 -:101FC0008FFF3B462A462146FFF7D4FF0120BDE89C -:101FD000B881000070B5302686F31188174B9A6DD2 -:101FE00042F000729A659A6B42F000729A639A6BA3 -:101FF00022F000729A63002383F3118800F5805465 -:1020000094F8C83013F0010516D1A9B186F31188F0 -:102010000321132001F0DCF90321142001F0D8F989 -:102020000321152001F0D4F994F8C83043F00103DE -:1020300084F8C83085F3118870BD00BF00100240DD -:102040002DE9F04700F5805588B095F8D030012B88 -:1020500004468846164600F28180814F57F82320B7 -:102060000AB947F82300D7F800A0C4F80C802674FA -:10207000BAF1000F64D095F8D030012B70D0012157 -:102080002046FFF7A7FF302383F3118862691368A6 -:1020900023F0020313606269136843F001031360C5 -:1020A000636900275F6187F3118801212046FFF7EC -:1020B000E1FD002800F09580E86DFFF781FA04F556 -:1020C0008359BA4609F10809202200216846FEF723 -:1020D000AFFF02A8FFF76AFCCDF818A06A4609EB2B -:1020E00007030DF1180E9446BCE80300F445186090 -:1020F0005960624603F10803F5D1DCF8000018606E -:1021000020379CF804201A71602FDDD195F8C83073 -:102110006FF38203002785F8C8306A46414620469F -:10212000ADF80070ADF802708DF80470FFF746FD51 -:10213000636948BB4FF400421A6008B0BDE8F087FD -:1021400041F2D80002F09EF8814610B15146FFF7E7 -:10215000D3FCC7F80090B9F1000F8CD10020ECE758 -:10216000386803681B6B98470146002887D1386898 -:10217000FFF730FF3868036832465B68414698478E -:1021800000287FF47CAFE9E761221A609DF80230F5 -:102190009DF803201B06120402F4702203F0407322 -:1021A0001343BDF80020C2F3090213439DF8042035 -:1021B0001205022E02F4E0020CBF4FF00041002194 -:1021C000134362690B43D361636913225A616269E5 -:1021D000136823F00103136039462046FFF74AFDD8 -:1021E00008B96369A6E795F8D03093BB6169D1F867 -:1021F000002242F00102C1F800226169D1F80022F8 -:1022000022F47C5222F00E02C1F800226169D1F85A -:10221000002242F46062C1F800226269C2F81432FE -:102220006269C2F80432626941F6FF71C2F80C12A9 -:102230006269C2F840326269C2F8443263690122BD -:10224000C3F81C226269D2F8003223F00103C2F8FD -:10225000003295F8C83043F0020385F8C8306CE7C7 -:102260001838002008B500F051F850EA0103024682 -:1022700002D0421E61F10001044B186810B10B46F8 -:10228000FFF72EFDBDE8084001F064B818380020C3 -:1022900008B50020FFF7E0FDBDE8084001F05AB89E -:1022A00008B50120FFF7D8FDBDE8084001F052B89D -:1022B00000B59BB0EFF3098168226846FEF7A6FEE1 -:1022C000EFF30583014B9B6BFEE700BF00ED00E0E1 -:1022D00008B5FFF7EDFF000000B59BB0EFF30981F3 -:1022E00068226846FEF792FEEFF30583014B5B6BB5 -:1022F000FEE700BF00ED00E0FEE700000FB408B508 -:10230000029801F019F9FEE701F0F6BB01F0D8BB25 -:1023100013B56C4684E80600031D94E8030083E8C7 -:102320000500012002B010BD73B58568019155B15B -:102330001B885B0707D4D0E900369B6B9847019A4E -:10234000C1B23046A847012002B070BDF0B5866822 -:1023500089B005460C465EB1BDF838305B070AD43B -:10236000D0E900379B6B98472246C1B23846B04748 -:10237000012009B0F0BD00220023CDE90023002395 -:10238000ADF808300A4603AB01F108061068516841 -:102390001C4603C40832B2422346F7D110682060BD -:1023A0009288A280FFF7B2FF0423ADF808302B68B3 -:1023B000CDE90001DB6B694628469847D8E7000065 -:1023C00030B503680968DD0FB5EBD17F23F06044B9 -:1023D00021F060424FEAD1700BD0002BB8BFA40CA3 -:1023E0000029B8BF920C944202D034BF01200020D3 -:1023F00030BD944205D1C1F38070C3F38073834232 -:10240000F6D194422CBF00200120F1E72DE9F041E4 -:10241000456A15B94162BDE8F0814B6823F0604719 -:10242000C3F38A464FEAD37EC3F3807816EA2306C5 -:1024300038BF3E46AC462B465A68BEEBD27F22F0F0 -:1024400060440AD0002A18DAA40CB44217D19D4285 -:102450000FD10D60DEE71346EEE7A74207D102F089 -:102460008044C2F3807242450BD054B1EFE708D2EA -:10247000EDE7CCF800100B60CDE7B44201D0B442D8 -:10248000E5D81A689C46002AE5D11960C3E7000028 -:102490002DE9F047089D01F007044FEAD5082244D2 -:1024A00005F0070500EBD1004FF47F49944201D1BC -:1024B000BDE8F08704F0070705F0070A57453E46D8 -:1024C00038BF5646C6F10806111B8E4228BF0E467D -:1024D000E10808EBD50E415C13F80EC0B94029FAAB -:1024E00006F721FA0AF1FFB28CEA010147FA0AF76E -:1024F00039408CEA010C03F80EC034443544D5E76A -:1025000080EA0120082341F2210201B240000029A3 -:1025100080B203F1FF33B8BF504013F0FF03F4D192 -:102520007047000038B50C468D18A54200D138BD63 -:1025300014F8011BFFF7E4FFF7E7000042684AB117 -:10254000136843604389818901339BB29942438177 -:1025500038BF83811046704770B588B0202204468A -:102560000D4668460021FEF763FD20460495FFF7FF -:10257000E5FF024658B16B46054608AE1C4603CC43 -:10258000B44228606960234605F10805F6D110467B -:1025900008B070BD082817D909280CD00A280CD01B -:1025A0000B280CD00C280CD00D280CD00E2814BFF2 -:1025B0004020302070470C207047102070471420B6 -:1025C000704718207047202070470000082817D94E -:1025D0000C280CD910280CD914280CD918280CD97F -:1025E00020280CD930288CBF0F200E2070470920DE -:1025F00070470A2070470B2070470C2070470D2051 -:10260000704700002DE9F843078C072F04461ED9B8 -:10261000D0E9029800254FF6FF73C5F12006A5F119 -:10262000200029FA05F108FA06F628FA00F03143ED -:102630000143C9B21846FFF763FF0835402D034632 -:10264000EBD1E1693A46BDE8F843FFF76BBF4FF6BF -:10265000FF70BDE8F883000010B54B6823B9CA8A43 -:1026600063F30902CA8210BD04691A681C60036121 -:10267000C38A013BC3824A60EFE700002DE9F84FAF -:102680001D46CB8A0F46C3F30901052981469246B0 -:102690000B4630D00020AAB207F11A049EB2042ED5 -:1026A0001FFA80F80FD8904503F1010306D3FB8A87 -:1026B0000A4462F30903FB8201201AE01AF8006061 -:1026C000E6540130EAE79045F1D2A1F1050B1C2355 -:1026D0007C68BBFBF3F203FB12BB1FFA8BF6002CEA -:1026E00045D14846FFF72AFF044638B978606FF0B5 -:1026F0000200BDE8F88F4FF00008E6E7002606600C -:102700007860ADB24FF0000B454510D90AEB0803D5 -:10271000221D13F8011B9155B1B208F101081B29C4 -:102720001FFA88F82BD0454506F10106F1D8FB8A3F -:10273000C3F30902154465F30903BCE7013292B201 -:102740001C462368002BF9D16B1F0B441C21B3FBE3 -:10275000F1F301339BB29A42D3D2BBF1000FD0D137 -:102760004846FFF7EBFE20B9C4F800B0BFE70122EE -:10277000E7E7C0F800B05E4620600446C1E7454583 -:10278000D5D94846FFF7DAFE08B92060AFE7C0F8B0 -:1027900000B0002620600446B6E700002DE9F04FA7 -:1027A0002DED028B1C4683B05B690192074688467B -:1027B000002B00F09A80238C2BB1E269002A00F0F4 -:1027C0009480072B35D807F10C00FFF7B7FE0546BC -:1027D00038B96FF00205284603B0BDEC028BBDE8A6 -:1027E000F08F14220021FEF723FC228CE16905F111 -:1027F0000800FEF70BFC208C013080B2FFF7E6FEEC -:10280000FFF7C8FE013880B2208401302874636964 -:10281000228C1B782A4403F01F0363F03F0348F027 -:1028200000411372384669602946FFF7EFFD012524 -:10283000D1E700F10C034FF0000908EE103A4FF019 -:10284000800A4E464D4618EE100AFFF777FE834683 -:102850000028BED014220021FEF7EAFB002E3AD158 -:10286000019BABF8083002220BF1080E1FFA82FC24 -:102870000CF10100BCF1060F218C80B201D88E4210 -:102880002BD3FFF7A3FEFFF785FE626912780138AC -:1028900002F01F028E4208BF4FF0400A42EA49127E -:1028A0001BFA80F14AEA020A013048F0004281F83E -:1028B00008A08BF81000CBF8042059463846FFF7E3 -:1028C000A5FD238C0135B3422DB289F001094FF0EB -:1028D000000AB8D17FE70022C6E7E169895D0EF8FA -:1028E00002100136B6B20132C0E76FF0010572E79F -:1028F000F8B515460E463022002104461F46FEF765 -:1029000097FB069B6360B5F5001F079BA76034BF6C -:102910006A094FF6FF72A36297B2E66104F11000F4 -:1029200000239A4206D800230360A782E382238310 -:10293000E360F8BD0660013330462036F1E7000061 -:1029400003781BB94BB2002BC8BF01707047000061 -:1029500000787047F8B50C46C969074611B9238C51 -:10296000002B37D1257E1F2D34D8387828BB228CF8 -:10297000072A2CD8268A36F003032BD14FF6FF7096 -:10298000FFF7D0FD20F001003102400441EA05616B -:10299000400C41EA40254FF6FF722346294638464F -:1029A000FFF7FCFE002807DD626913780133DBB214 -:1029B0001F2B88BF00231370F8BD218A2D0645EA1E -:1029C000012505432046FFF71DFE0246E5E76FF0AF -:1029D0000300F1E76FF00100EEE7000070B58AB088 -:1029E000044616460021282268461D46FEF720FBB5 -:1029F000BDF83830ADF810300F9B05939DF840308E -:102A00008DF81830119B07936946BDF84830ADF832 -:102A100020302046CDE90265FFF79CFF0AB070BD6B -:102A20002DE9F041D36905460C4616460BB9138CC7 -:102A30005BBB377E1F2F28D895F80080B8F1000FB8 -:102A400026D03046FFF7DEFD3378210241EAC3315C -:102A500041EA0801338A41EA076141EA034102463B -:102A6000334641F080012846FFF798FE00280ADD32 -:102A70003378012B07D1726913780133DBB21F2B36 -:102A800088BF00231370BDE8F0816FF00100FAE702 -:102A90006FF00300F7E70000F0B58BB004460D4679 -:102AA00017460021282268461E46FEF7C1FA9DF807 -:102AB0004C305A1E534253418DF800309DF840303F -:102AC000ADF81030119B05939DF848308DF8183003 -:102AD000149B07936A46BDF85430ADF82030294660 -:102AE0002046CDE90276FFF79BFF0BB0F0BD00005A -:102AF000406A00B104307047436A1A684262026952 -:102B00001A600361C38A013BC38270472DE9F0411B -:102B1000D0F82080194E14461D464146002709B9B9 -:102B2000BDE8F081D1E90223A21A65EB03039642C6 -:102B300077EB03031ED2036A8B420DD1FFF78CFDA6 -:102B4000036A1B68036203690B60C38A0161016A3F -:102B5000013BC3828846E2E7FFF77EFD0B68C8F8B9 -:102B6000003003690B60C38A0161013BC382D8F85E -:102B70000010D4E788460968D1E700BF80841E00B2 -:102B80002DE9F04F8BB00D46DDF8509014469B4672 -:102B90008046002800F01981B9F1000F00F015817E -:102BA000531E3F2B00F21181012A03D1BBF1000F0C -:102BB00040F00B810023CDE90833B8F81430B5EBB1 -:102BC000C30F4FEAC30703D300200BB0BDE8F08F5B -:102BD0002B199F42D8F80C303ABF7F1BFFB2274613 -:102BE0001BB9D8F81030002B7AD0272D4ED8C5F15C -:102BF0002806B7424FF000032CBFF6B23E460093C2 -:102C00002946D8F8080008AB3246FFF741FCA7EB8D -:102C1000060A35445FFA8AFAB8F8143003F1005313 -:102C2000053BDB000493D8F80C3003932821039B69 -:102C300013B1BAF1000F2CD1D8F8100040B1BAF19D -:102C4000000F05D0009608AB5246691AFFF720FC2A -:102C500038B2002FB8D066070AD00AAB03EBD40114 -:102C6000624211F8083C02F00702134101F8083CE7 -:102C7000082C3CD9102C40F2B580202C40F2B780B3 -:102C8000BBF1000F00F09C80082334E0BA46002618 -:102C9000C2E7049BE02B28BFE02306930B44AB4222 -:102CA000059314D95A1B03980096924534BF524697 -:102CB000D2B2691A08AB04300792FFF7E9FB079A12 -:102CC0001644AAEB020A1544F6B25FFA8AFA049B8C -:102CD000069A05999B1A0493039B1B680393A6E726 -:102CE0000093D8F8080008AB3A462946AEE7BBF196 -:102CF000000F13D00123B4EBC30F6CD0082C12D8F3 -:102D00009DF82030621E23FA02F2D50706D54FF057 -:102D1000FF3202FA04F423438DF820309DF820306E -:102D200089F8003051E7102C12D8BDF82030621E0F -:102D300023FA02F2D10706D54FF0FF3202FA04F46B -:102D40002343ADF82030BDF82030A9F800303CE72F -:102D5000202C0FD80899631E21FA03F3DA0705D552 -:102D60004FF0FF3202FA04F40C430894089BC9F8B0 -:102D700000302AE7402C2BD0DDE90865611EC4F144 -:102D80002102A4F1210326FA01F105FA02F225FA43 -:102D900003F311431943CB0712D50122A4F12003F9 -:102DA000C4F1200102FA03F322FA01F1A2405242D7 -:102DB00043EA010363EB430332432B43CDE908238A -:102DC000DDE90823C9E90023FFE66FF00100FCE616 -:102DD0006FF00800F9E6082CA0D9102CB3D9202CEC -:102DE000EED8C3E7BBF1000FADD0022383E7BBF100 -:102DF000000FBBD004237EE730B5012A144638BF4C -:102E00000124402C85B028BF40240025012ACDE9AB -:102E1000025518D81B788DF8083063070AD004AB28 -:102E200003EBD405624215F8083C02F00702934018 -:102E300005F8083C009103462246002102A8FFF74E -:102E400027FB05B030BD082AE4D9102A03D81B8817 -:102E5000ADF80830E1E7202A8DBFD3E900231B68D5 -:102E60000293CDE90223D8E710B5CB681BB98B607C -:102E70000B618B8210BD04691A681C600361C38AF0 -:102E8000013BC382CA60F0E703064CBFC0F3C03009 -:102E90000220704708B50246FFF7F6FF022806D168 -:102EA0005306C2F30F2001D100F0030008BDC2F3A6 -:102EB0000740FBE72DE9F04F93B0CDE903230A6803 -:102EC00004461046FFF7E0FF022814BFC2F30626AF -:102ED0000026002A0D46824680F2F28112F0C04997 -:102EE00040F0EE81097B002900F0EA81022803D03E -:102EF0002378B34240F0E781C2F30463069310469F -:102F000002F07F030593FFF7C5FF059B29444FEAB5 -:102F1000834848EA0A4848EA4668CE7800230022F7 -:102F2000CDE90823F309834648EA0008029367D0F5 -:102F3000059B009302466768534608A92046B84798 -:102F4000002800F0C381276A4FB9414604F10C0004 -:102F5000FFF702FB074690B96FF0020054E03B69AF -:102F600098450DD03F68002FF9D1414604F10C007F -:102F7000FFF7F2FA07460028EED0236A3B6027628B -:102F800097F817C006F01F08CCF3840CACEB0800D0 -:102F90001FFA80FE0028B8BF0EF12000A8EB0C033A -:102FA0001FFA83FED7E90221B8BF00B2002B0793B6 -:102FB000BEBF0EF120031BB2079352EA010338D0C3 -:102FC000039BDFF824E39A1A049B4FF0000C63EB99 -:102FD000010196457CEB01032BD36B7B97F81AE03C -:102FE000734519D1029B002B78D0012821DC786829 -:102FF000F8B9DFF8F0C2944570EB010316D337E05F -:10300000276A27B96FF00C0013B0BDE8F08F3B6959 -:103010009845B5D03F68F4E7B24890427CEB010395 -:1030200001D30020F0E7029B002BFAD0079B0F2B67 -:1030300017DCFA7DB30002F0030203F07C031343B4 -:10304000FB7539462046FFF707FB6B7BBB76029B7F -:103050003BB9FB7DC3F38402013262F38603FB7547 -:10306000D0E76A7BBB7E9A42DBD1029B002B35D036 -:10307000B309022B32D0039BBB60049BFB6014227C -:1030800000210DA8FDF7D4FF039B0A93049B0B932B -:103090002B1D0C932B7BADF83EB0013BDBB2ADF8A2 -:1030A0003C30069B8DF84230059B8DF8433094F8F8 -:1030B0002C308DF840A083F001038DF844308DF85A -:1030C0004180A3680AA920469847FB7DC3F3840387 -:1030D000013303F01F039B02FB82A2E7FB7DC6F3D3 -:1030E0004012B2EBD31F40F0F480C3F38403434596 -:1030F00040F0F280029A2B7BB609002A4DD0F207ED -:103100005DD4032B40F2EB80039BBB60049BFB6010 -:103110002B7BAE1D033BDBB23246394604F10C007B -:10312000FFF7ACFA00280CDA39462046FFF794FA8C -:10313000FB7DC3F38403013303F01F039B02FB8277 -:103140000AE7DDE90884AB883B834FF6FF73C9F1DA -:103150002000A9F1200228FA09F104FA00F0014345 -:1031600024FA02F211431846C9B2FFF7C9F909F16E -:103170000809B9F1400F0346E9D1B8822A7B033A26 -:10318000D2B23146FFF7CEF9FB7DB882DA43C2F303 -:10319000C01262F3C713FB7543E786B92E1D013BCE -:1031A000DBB23246394604F10C00FFF767FA00281B -:1031B000BADB2A7BB88A013AD2B23146E2E7F98A11 -:1031C000C1F30901013B0429DAB25BD8281D0023B1 -:1031D00007F11B069A4208D910F801CB06F801C086 -:1031E000013101330529DBB2F4D103990A91049925 -:1031F0000B91934207F11B010C9138BF043379689E -:103200000D9134BF55FA83F300230E93FB8AADF87A -:103210003EB0C3F309031A44069B8DF84230059B68 -:103220008DF8433094F82C30ADF83C2083F0010346 -:103230008DF8443000238DF840A08DF841807B60EC -:103240002A7BB88A013A291DFFF76CF93B8BB882BB -:10325000834203D1A3680AA92046984720460AA9B9 -:10326000FFF702FEFB7DBA8AC3F38403013303F048 -:103270001F039B02FB823B8B9A420CBF00206FF026 -:103280001000C1E67B68002BAFD0052001E01C30A8 -:1032900033461E68002EFAD1091A081D2E1D184447 -:1032A00001EB090CBCF11B0F5FFA89F39DD89A4220 -:1032B0009BD916F8013B00F8013B09F10109EFE742 -:1032C0006FF00900A0E66FF00A009DE66FF00B00BA -:1032D0009AE66FF00D0097E66FF00E0094E66FF03F -:1032E0000F0091E640420F0080841E00EFF3098337 -:1032F00005494A6B22F001024A63683383F3098867 -:10330000002383F31188704700EF00E0302080F342 -:10331000118862B60C4B0D4AD96821F4E0610904AA -:10332000090C0A43DA60D3F8FC20094942F08072A4 -:10333000C3F8FC200A6842F001020A602022DA7712 -:1033400083F82200704700BF00ED00E00003FA059B -:10335000001000E010B5302383F311880E4B5B683A -:1033600013F4006314D0F1EE103AEFF30984683CD3 -:103370004FF08073E361094BDB6B236684F30988AC -:1033800000F0A4F810B1064BA36110BD054BFBE79C -:1033900083F31188F9E700BF00ED00E000EF00E0E3 -:1033A000FF020008020300084FF0E02300225868E3 -:1033B0004FF0FF31930003F1604303F561430132A5 -:1033C0009042C3F88010C3F88011F3D27047000018 -:1033D00000F1604303F561430901C9B283F80013AA -:1033E000012200F01F039A4043099B0003F1604350 -:1033F00003F56143C3F880211A6070470023037509 -:10340000826803691B6899689142FBD25A6803601D -:10341000426010605860704700230375826803693A -:103420001B6899689142FBD85A680360426010603B -:103430005860704708B50846302383F311880B7D28 -:10344000032B05D0042B0DD02BB983F3118808BDB5 -:103450008B6900221A604FF0FF338361FFF7CEFFC4 -:103460000023F2E7D1E9003213605A60F3E700006D -:10347000FFF7C4BF054BD9680875186802681A6061 -:10348000536001220275D860FCF724BF2838002061 -:1034900030B50C4BDD684B1C87B004460FD02B4673 -:1034A000094A684600F02AF92046FFF7E3FF009B2F -:1034B00013B1684600F02CF9A86907B030BDFFF7DA -:1034C000D9FFF9E72838002035340008044B1A6882 -:1034D000DB6890689B68984294BF00200120704789 -:1034E00028380020084B10B51C68D86822681A607C -:1034F000536001222275DC60FFF78EFF01462046F3 -:10350000BDE81040FCF7E6BE2838002038B5074C6F -:1035100007490848012300252370656000F0ECFB93 -:103520000223237085F3118838BD00BF503A002074 -:10353000B04400082838002008B572B6044B18655E -:1035400000F0ACFA00F05AFB024B03221A70FEE7BF -:1035500028380020503A002000F010B98B60022378 -:1035600008618B82084670478368A3F1840243F8A0 -:10357000142C026943F8442C426943F8402C094A50 -:1035800043F8242CC26843F8182C022203F80C2CB0 -:10359000002203F80B2C044A43F8102CA3F120005E -:1035A000704700BFED0200082838002008B5FFF77B -:1035B000DBFFBDE80840FFF75BBF0000024BDB68A4 -:1035C00098610F20FFF756BF28380020302383F37F -:1035D0001188FFF7F3BF000008B50146302383F3DD -:1035E00011880820FFF754FF002383F3118808BDDA -:1035F00010B503689C68A2420CD85C688A600B60B6 -:103600004C602160596099688A1A9A604FF0FF33C4 -:10361000836010BD1B68121BECE700000A2938BF4D -:103620000A2170B504460D460A26601900F05EFBBB -:1036300000F04AFB041BA54203D8751C2E46044625 -:10364000F3E70A2E04D9BDE87040012000F094BBD6 -:1036500070BD0000F8B5144B0D46D96103F110019F -:1036600041600A2A1969826038BF0A2201604860F5 -:103670001861A818144600F02BFB0A2700F024FB61 -:10368000431BA342064606D37C1C281900F02EFBE0 -:1036900027463546F2E70A2F04D9BDE8F840012055 -:1036A00000F06ABBF8BD00BF28380020F8B5064618 -:1036B0000D4600F009FB0F4A134653F8107F9F4256 -:1036C00006D12A4601463046BDE8F840FFF7C2BFA2 -:1036D000D169BB68441A2C1928BF2C46A34202D9D1 -:1036E0002946FFF79BFF224631460348BDE8F840D4 -:1036F000FFF77EBF283800203838002010B4C0E91A -:10370000032300235DF8044B4361FFF7CFBF0000A4 -:1037100010B5194C236998420DD0D0E90032816868 -:1037200013605A609A680A449A60002303604FF05D -:10373000FF33A36110BD2346026843F8102F536086 -:103740000022026022699A4203D1BDE8104000F0D5 -:10375000C7BA936881680B44936000F0B5FA226998 -:10376000E1699268441AA242E4D91144BDE81040CC -:10377000091AFFF753BF00BF283800202DE9F04792 -:10378000DFF8BC8008F110072C4ED8F8105000F07C -:103790009BFAD8F81C40AA68031B9A423ED81444EE -:1037A000D5E900324FF00009C8F81C4013605A6098 -:1037B000C5F80090D8F81030B34201D100F090FA6B -:1037C00089F31188D5E9033128469847302383F3DC -:1037D00011886B69002BD8D000F076FA6A69A0EBEB -:1037E00004094A4582460DD2022000F0C5FA0022A3 -:1037F000D8F81030B34208D151462846BDE8F0470A -:10380000FFF728BF121A2244F2E712EB090938BF6A -:103810004A4629463846FFF7EBFEB5E7D8F81030A0 -:10382000B34208D01444211AC8F81C00A960BDE8AE -:10383000F047FFF7F3BEBDE8F08700BF383800203F -:103840002838002038B500F03FFA054AD2E908458B -:10385000031B181945F10001C2E9080138BD00BF7A -:103860002838002000207047FEE700007047000065 -:103870004FF0FF3070470000BFF34F8F024A1369CB -:10388000DB03FCD4704700BF0020024008B5094BA1 -:103890001B7873B9FFF7F0FF074B5A69002ABFBFC7 -:1038A000064A9A6002F188329A601A6822F48062AD -:1038B0001A6008BD683A00200020024023016745D5 -:1038C00008B50B4B1B7893B9FFF7D6FF094B5A6924 -:1038D00042F000425A611A6842F480521A601A6833 -:1038E00022F480521A601A6842F480621A6008BD9D -:1038F000683A0020002002407F289ABF00F58030FF -:10390000C0020020704700004FF4006070470000C4 -:10391000802070477F2808B50BD8FFF7EDFF00F532 -:1039200000630268013204D104308342F9D10120DE -:1039300008BD0020FCE700007F2810B504461FD812 -:10394000FFF79AFFFFF7A2FF0E4BF3221A61022244 -:103950005A615A6942EAC0025A615A6942F4803295 -:103960005A61FFF789FF4FF40061FFF7C5FF00F0D0 -:1039700041F9FFF7A5FF2046BDE81040FFF7CABF99 -:10398000002010BD002002402DE9F84340EA020368 -:1039900013F00703144606D0304B40F233321A605E -:1039A0000020BDE8F88385182D4A95420CD92B4A92 -:1039B0004FF44E711160F3E7031D1B684A68934290 -:1039C00008D1083C08300831072C14D902680B686C -:1039D0009A42F1D0FFF75AFFFFF74EFF214E083110 -:1039E0004FF001084FF00009012CA1F1080706D89B -:1039F000FFF766FF01E0002CECD10120D1E7C6F80B -:103A00001480054651F8083C45F8043B51F8043C45 -:103A10004360FFF731FF336943F001033361C6F8B8 -:103A20001490026851F8083C9A420CD00B4B4FF4AA -:103A300058721A600C4B18600C4B1C600C4B1F60CA -:103A4000FFF73EFFACE72D6851F8043C9D4201F1C1 -:103A50000801EBD1083C0830C6E700BF643A0020FB -:103A60000000040800200240583A0020603A00207C -:103A70005C3A0020084908B50B7828B11BB9FFF75C -:103A800005FF01230B7008BD002BFCD0BDE80840EA -:103A90000870FFF715BF00BF683A00204FF480316F -:103AA0004FF0005000F0A8B80846114600F00CBCDA -:103AB000012000F009BC0000084600F023BC000013 -:103AC00038B5EFF311859DB9EFF30584C4F308040D -:103AD000302334B183F31188FFF7B4FE85F31188E6 -:103AE00038BD83F31188FFF7ADFE84F3118838BD2C -:103AF000BDE83840FFF7A6BE38B5FFF7E1FF114C2F -:103B0000114AC00840EA4170A0FB025EC908A0FB50 -:103B1000040C1CEB050CA1FB04404FF000035B41BF -:103B2000A1FB02121CEB040C43EB000011EB0E0195 -:103B300042F10002411842F10000090941EA007017 -:103B400038BD00BFCFF753E3A59BC42010B5024496 -:103B5000064BD2B2904200D110BD441C00B253F8C3 -:103B6000200041F8040BE0B2F4E700BF5028004009 -:103B7000114B30B5D3F89040240409D4D3F89040C9 -:103B8000C3F89040D3F8904044F40044C3F8904008 -:103B90000A4C236843F4807323600244084BD2B27A -:103BA000904200D130BD441C00B251F8045B43F890 -:103BB0002050E0B2F4E700BF001002400070004067 -:103BC0005028004007B5012201A90020FFF7BEFFE1 -:103BD000019803B05DF804FB13B50446FFF7F2FF4C -:103BE000A04205D0012201A900200194FFF7C0FFE7 -:103BF00002B010BD70470000704700007047000021 -:103C0000074B45F255521A6002225A6040F6FF7285 -:103C10009A604CF6CC421A60024B01221A7070472F -:103C200000300040703A0020034B1B781BB1034B5F -:103C30004AF6AA221A607047703A0020003000400D -:103C4000054B1A6832B902F1804202F50432D2F80B -:103C500094201A60704700BF6C3A0020024B4FF46A -:103C60000002C3F8942070470010024008B5FFF727 -:103C7000E7FF024B1868C0F3407008BD6C3A0020A3 -:103C800070470000FEE700000A4B0B480B4A9042C9 -:103C90000BD30B4BDA1C121AC11E22F003028B420B -:103CA00038BF00220021FDF7C3B953F8041B40F8C8 -:103CB000041BECE744450008FC3A0020FC3A0020D5 -:103CC000FC3A002000F0C0B84FF08043586A7047BB -:103CD0004FF08043002258631A610222DA60704775 -:103CE0004FF080430022DA60704700004FF08043BD -:103CF00058637047FEE7000070B51B4B0163002559 -:103D0000044686B0586085620E46FFF7FFFA04F15C -:103D10001003C4E904334FF0FF33C4E90635C4E9A6 -:103D20000044A560E562FFF7CFFF2B460246C4E9D9 -:103D3000082304F134010D4A256580232046FFF74E -:103D40000DFC0123E0600A4A03750092726801923B -:103D5000B268CDE90223074B6846CDE90435FFF789 -:103D600025FC06B070BD00BF503A0020BC440008DE -:103D7000C1440008F53C0008024AD36A1843D062E7 -:103D8000704700BF28380020254B2648DA6A42F0E9 -:103D9000070210B4DA62DA6A22F00702DA62DA6A3B -:103DA000DA6C42F00702DA64DA6E42F00702DA6691 -:103DB0004FF09042DB6E4FF0AA31002353604FF476 -:103DC00019249160D0604FF6FD7050611362546207 -:103DD000154C1460154CC2F80434C2F80844C2F8FB -:103DE0000C34C2F8140441F20400C2F82034C2F8C2 -:103DF0002434C2F80004C2F80438C2F808184FF698 -:103E0000FF71C2F80C38C2F81418C2F82038C2F892 -:103E10002438C2F800385DF8044B00F055B800BFF4 -:103E200000100240000001240400812AA69AAAAAD8 -:103E300008B500F005FAFFF769FBBDE80840FFF799 -:103E4000FFBE0000704700000F4B9A6D42F0010268 -:103E50009A659A6F42F001029A670C4A9B6F9368C9 -:103E600043F0010393604FF080434F229A624FF07A -:103E7000FF32DA6200229A615A63DA605A600122E4 -:103E80005A611A60704700BF00100240002004E031 -:103E90004FF0804208B51169D3680B40D9B2C943CD -:103EA0009B07116107D5302383F31188FFF754FB7B -:103EB000002383F3118808BD08B5FFF775FABDE844 -:103EC000084000F099B900005A4B4FF0FF319A6A50 -:103ED00099629A6A00229A62986AD86A60F007002A -:103EE000D862D86A00F00700D862D86A186B1963E4 -:103EF000186B1A63186B986B9963986B9A63986B3D -:103F0000D86BD963D86BDA63D86B186C1964196CE9 -:103F10001A641A6C484A4FF4E06111601A6E4749FE -:103F200042F001021A66D3F8802022F00102C3F8A1 -:103F30008020D3F880209A6D42F080529A659A6F63 -:103F400022F080529A679A6F4FF440720A604A6971 -:103F500012F48062FBD14A601A6822F0F00242F04B -:103F600060021A601A6842F001021A601A6891072A -:103F7000FCD500229A609A6812F00C02FBD1D3F8AB -:103F8000901011F4407F1EBF4FF48031C3F89010A1 -:103F9000C3F8902061221A601A689207FCD50022AB -:103FA0009A609A6812F00C0FFBD169221A60D3F85C -:103FB000942022F4706242F4C062C3F894201A681C -:103FC00042F480321A601A689003FCD5D3F890202E -:103FD00022F00322C3F89020194ADA601A6842F0EE -:103FE00080721A601A689101FCD5164A1A611A6823 -:103FF00042F080621A601A681201FCD500229A60B1 -:104000000D49114AC3F888200A6822F0070242F0DD -:1040100004020A600A6802F00702042AFAD19A68C8 -:1040200042F003029A609A6802F00C020C2AFAD15C -:10403000704700BF001002400020024000700040A6 -:1040400013140001100C100055550134074A08B52F -:10405000536903F00103536123B1054A13680BB19F -:1040600050689847BDE80840FFF774B90004014064 -:10407000743A0020074A08B5536903F002035361FC -:1040800023B1054A93680BB1D0689847BDE8084052 -:10409000FFF760B900040140743A0020074A08B5F0 -:1040A000536903F00403536123B1054A13690BB14B -:1040B00050699847BDE80840FFF74CB9000401403B -:1040C000743A0020074A08B5536903F008035361A6 -:1040D00023B1054A93690BB1D0699847BDE8084000 -:1040E000FFF738B900040140743A0020074A08B5C8 -:1040F000536903F01003536123B1054A136A0BB1EE -:10410000506A9847BDE80840FFF724B90004014011 -:10411000743A0020164B10B55C6904F478725A6149 -:10412000A30604D5134A936A0BB1D06A9847600678 -:1041300004D5104A136B0BB1506B9847210604D578 -:104140000C4A936B0BB1D06B9847E20504D5094A32 -:10415000136C0BB1506C9847A30504D5054A936CBA -:104160000BB1D06C9847BDE81040FFF7F3B800BF23 -:1041700000040140743A0020194B10B55C6904F446 -:104180007C425A61620504D5164A136D0BB1506D1D -:104190009847230504D5134A936D0BB1D06D98470A -:1041A000E00404D50F4A136E0BB1506E9847A1047A -:1041B00004D50C4A936E0BB1D06E9847620404D5B7 -:1041C000084A136F0BB1506F9847230404D5054A72 -:1041D000936F0BB1D06F9847BDE81040FFF7BAB8A6 -:1041E00000040140743A002008B5FFF751FEBDE815 -:1041F0000840FFF7AFB80000062108B50846FFF7F2 -:10420000E7F806210720FFF7E3F806210820FFF76B -:10421000DFF806210920FFF7DBF806210A20FFF767 -:10422000D7F806211720FFF7D3F806212820FFF73B -:10423000CFF8BDE8084007211C20FFF7C9B80000EF -:1042400008B5FFF739FE00F007F8FFF7FBFDBDE802 -:104250000840FFF737BD00000023054A1946013327 -:10426000102BC2E9001102F10802F8D1704700BF1B -:10427000743A00200B460146184600F02DB80000A5 -:1042800000F040B8012838BF012010B50446204690 -:1042900000F030F830B900F007F808B900F00CF879 -:1042A0008047F4E710BD0000024B1868BFF35B8F36 -:1042B000704700BFF43A002008B5062000F084F8EB -:1042C0000120FFF7D1FA0000024B0A4601461868A8 -:1042D000FFF7EABB1811002010B5054C13462CB1AE -:1042E0000A4601460220AFF3008010BD2046FCE7DD -:1042F00000000000024B01461868FFF7D9BB00BF61 -:1043000018110020024B01461868FFF7D5BB00BF0B -:104310001811002010B501390244904201D100204B -:1043200005E0037811F8014FA34201D0181B10BD1E -:104330000130F2E72DE9F041A3B1C91A1778014421 -:10434000044603F1FF3C8C42204601D9002009E0DD -:104350000578BD4204F10104F5D10CEB0405D61833 -:10436000A54201D1BDE8F08115F8018D16F801EDE7 -:10437000F045F5D0E7E700001F2938B504460D46A3 -:1043800004D9162303604FF0FF3038BD426C12B1E0 -:1043900052F821304BB9204600F030F82A46014649 -:1043A0002046BDE8384000F017B8012B0AD0591C50 -:1043B00003D1162303600120E7E7002442F82540DB -:1043C000284698470020E0E7024B01461868FFF7AF -:1043D000D3BF00BF1811002038B5074D0023044695 -:1043E000084611462B60FFF743FA431C02D12B68A5 -:1043F00003B1236038BD00BFF83A0020FFF732BA9E -:10440000034611F8012B03F8012B002AF9D170475C -:10441000696E2E7369657272616165726F73706126 -:1044200063652E547275654E617649430000000045 -:1044300040A2E4F1646891060041A3E5F265699247 -:10444000070000004261642043414E496661636594 -:1044500020696E6465782E008000000000800000F6 -:10446000000080000000000000000000211800088B -:10447000412000089D1F0008611800086D18000801 -:104480006D1A000831180008411800083518000896 -:104490003D1800083918000891190008451800084F -:1044A0001123000855180008651900086330000042 -:1044B000AC44000880380020503A00206D61696EDD -:1044C0000069646C65000000B61400000000000084 -:1044D0000060030000000000FE2A0100D20400007A -:1044E0001C1100200000000000000000000000007F +:1002F00011882846A047002003F062F9FEE703F0CA +:10030000EBF800DFFEE70000F8B500F017FE03F0A1 +:1003100055FC074603F0A6FC0646C0BB274B9F4290 +:1003200035D001339F4235D0254B27F0FF029A424A +:1003300033D1F8B200F03AFC354642F2107400F0C6 +:100340003BFC08B10024254601F0ACF848B303207B +:1003500000F03AF80024254636B11A4B9F4203D0EC +:1003600003F078FC00242546002003F031FC0DB199 +:1003700000F040F800F052FC01F0C0FF0546ACB9B7 +:1003800000F094FC4FF47A7003F020F9F7E735465B +:100390000024D4E704460125D1E705464FF47A74DA +:1003A000CDE7B4F57A7F08BF0125D5E701F0A6FFB8 +:1003B000431BA342E4D900F01DF8DDE7010007B0BC +:1003C000000008B0263A09B0084B187003280CD872 +:1003D000DFE800F008050208022000F009BE022054 +:1003E00000F000BE024B00225A60704780110020CE +:1003F0008411002010B501F055F830B1234B0322D1 +:100400001A70234B00225A6010BD224B224A1C4610 +:1004100019680131F8D004339342F9D16268A242DD +:10042000F2D31E4B9B6803F1006303F520439A420D +:10043000EAD203F0E1FB03F0F3FB002000F098FDAB +:100440000220FFF7C1FF164B9A6D00229A65996F43 +:100450009A67996FD96DDA65D96FDA67D96F196EB6 +:100460001A66D3F88010C3F88020D3F8803072B6B3 +:100470004FF0E0233021C3F8084DD4E9003281F376 +:1004800011889D4683F308881047BDE7801100203E +:100490008411002000A0000820A000080011002006 +:1004A00000100240094A136849F2690099B21B0C16 +:1004B00000FB01331360064B186844F2506182B2AE +:1004C000000C01FB0200186080B27047141100207C +:1004D0001011002010B500211022044600F0A2FDEA +:1004E000034B03CB206061601868A06010BD00BFA3 +:1004F0009075FF1F2DE9F041ADF5507D0DF13C08E1 +:100500006EAC40F2751207460D4610A80021C8F8DF +:10051000001000F087FD4FF4C4720021204600F067 +:1005200081FD01F0EBFE254B4FF47A72B0FBF2F047 +:10053000186093E80700022384E807000DF5ED70CA +:100540002382FFF7C7FF4BF214631D49238407A8DA +:1005500003F052FF1C2384F832310DF2EB226B447E +:100560000DF1340C1E4603CE6645106051603346D3 +:1005700002F10802F6D1306810604146012220469F +:1005800000F09CFD00230393AB7E029305F1190359 +:10059000019380B20123CDE904800093E97E05A395 +:1005A000D3E90023384602F071FA0DF5507DBDE81D +:1005B000F08100BF9E6AC421818A46EE8C11002022 +:1005C000084400082DE9F0412C4C237ADAB080462B +:1005D0000D465BBB27A9284600F080FE0746002891 +:1005E00042D19DF89D60C82E3ED801464FF4A662C8 +:1005F000204600F017FD4FF48073C4F8F8314FF433 +:100600000073C4F80C334FF44073C4F820343246FE +:100610000DF19E0104F1090000F0F2FC26449DF862 +:100620009C30777223720BB9EB7E237281220021FA +:1006300006AC27A800F0F6FC0122214627A800F00E +:1006400089FE00230393AB7E029305F1190380B268 +:1006500001932823CDE904400093E97E05A3D3E963 +:100660000023404602F012FA5AB0BDE8F08100BF04 +:10067000AFF3008026417272DF25D7B7B032002079 +:10068000F0B5254E4FF48A7505FB0065F1B096F87C +:10069000D83085F8DC300024D822214685F8E8409F +:1006A0003AA800F0BFFC06F1090000F0B3FCD5F851 +:1006B000E4308DF8F000C2B206AF06F109010DF189 +:1006C000F100CDE93A3400F09BFC394601223AA80A +:1006D00000F06CFE80B2CDE9047008230127CDE95B +:1006E000023706F1D803019330230093317A0B4887 +:1006F00007A3D3E9002302F0C9F9A04206DD01F007 +:10070000FDFDC5F8E000384671B0F0BD2046FBE7BE +:1007100078F6339F93CACD8DB0320020A4210020FB +:100720002DE9F0411D4D1E4E1E4F86B0284602F0A9 +:10073000D9F9034658B30024CDE90344ADF8144079 +:10074000027B8DF8142099684068029403AA03C2C2 +:100750001B68DFF8548043F00043029301F0D0FDA2 +:10076000821941F10003009402A9384601F078F89B +:10077000A04205DD284602F0B9F988F80040D5E727 +:1007800098F80030072B05D8013388F8003006B000 +:10079000BDE8F081014802F0A9F9F8E7A4210020A2 +:1007A00040420F00D8210020E537002070B50D46EB +:1007B00014461E4602F0C6F850B9022E10D1012C84 +:1007C0000ED112A3D3E90023C5E90023012007E0DD +:1007D000282C10D005D8012C09D0052C0FD00020D2 +:1007E00070BD302CFBD10BA3D3E90023ECE70BA3A6 +:1007F000D3E90023E8E70BA3D3E90023E4E70BA345 +:10080000D3E90023E0E700BFAFF30080401DA12043 +:1008100026812A0B78F6339F93CACD8D9E6AC42118 +:10082000818A46EE26417272DF25D7B7F017304A2B +:1008300039059E5638B505460E4C0021013500F0AD +:10084000B9FBA4F82C55B4F82C0500F09BFB78B14B +:10085000B4F82C0500F0A6FB014648B9B4F82C0505 +:1008600000F0A8FBB4F82C350133A4F82C35EAE7E6 +:1008700038BD00BFB032002010B50A4B0A4A1A60DA +:1008800003F5805393F860203AB9DC6D2CB1204613 +:1008900000F086FE204603F0EFFCBDE81040034860 +:1008A00000F07EBED82100206444000820320020E1 +:1008B0002DE9F04F8FB000AF05460C4602F042F82C +:1008C000002849D1237E022B1BD1E38A012B18D1AA +:1008D00001F014FD0646FFF7E5FD03464FF4C8702E +:1008E000DFF8C482B3FBF0F206F5167602FB103394 +:1008F00016FA83F3C8F80030E37E33B9A34B002225 +:100900001A703C37BD46BDE8F08F07F12401204640 +:1009100000F0A2FC0028F4D107F11400FFF7DAFD83 +:1009200097F8264007F11401224607F1270003F04B +:10093000EDFC0028E2D10F2C08D8944B1C70D8F89D +:100940000030A3F51673C8F80030DAE797F82410E2 +:10095000284601F0EFFFD4E7E38A282B2BD010D8EC +:10096000012B23D0052BCCD1BFF34F8F8849894B66 +:10097000CA6802F4E0621343CB60BFF34F8F00BF3D +:10098000FDE7302BBDD1844EE17E327A9142B8D161 +:10099000607E3146002291F8DC50854200F0A5804F +:1009A0000132042A01F58A71F5D1AAE721462846C9 +:1009B000FFF7A0FDA5E721462846FFF703FEA0E7C5 +:1009C000B2F8EC507B6005F103094FEA99094FEA50 +:1009D0008902D11DC908A8EBC1039D46EB46002141 +:1009E000584600F01FFB04F1EE012A4631445846F8 +:1009F00000F006FB7B6813B9012000F0B9FA96F805 +:100A0000D20000F0BFFA044630B9307200F0DAFAD2 +:100A1000204600F0ADFAB1E0D6F8D4203AB996F805 +:100A2000D200B6F82C25824201D8FFF703FFD6F892 +:100A3000D4202A44944208D296F8D200B6F82C2545 +:100A40000130824201D8FFF7F5FE70685FFA89F243 +:100A5000594600F0EFFA08B9C54679E0726896F891 +:100A6000D2002A447260D6F8D42005EB0209C6F8F9 +:100A7000D49000F087FA814509D396F8D220D6F8B1 +:100A8000D4000132001B86F8D220C6F8D400FF2D16 +:100A90000FD80024347200F095FA204600F068FA6E +:100AA00000F000FD3D4B188108B9FFF7A3FCC546D7 +:100AB00027E7BB6896F8D9000AFB0362FB68D2F807 +:100AC000E41082F8E83001F58061C2F8E030C2F845 +:100AD000E410FFF7D5FDFFF723FE96F8D920013289 +:100AE00002F0030286F8D920B6E74FF48A7A0AFBAF +:100AF00002F505F1EA013144204600F083FCF8607C +:100B000000287FF4FEAE3544012285F8E82001F08C +:100B1000F5FBD5F8E020D6ED007ADFED216A801AEA +:100B2000192838BF192040F6B832904228BF104625 +:100B3000B8EE677A07EE900AF8EEE77A67EEA67AE3 +:100B4000DFED186AE7EE267AFCEEE77AC6ED007A6A +:100B500096F8D930BB60BA6873680AFB02F43219A0 +:100B600092F8E81059B1D2F8E4108B42E8463FF40D +:100B700027AF002182F8E810C2F8E010C54673687C +:100B8000064A9B0A01331381BBE600BF9D2100206A +:100B900000ED00E00400FA05B03200208C110020C6 +:100BA000CDCCCC3D6666663FA0210020014B18707D +:100BB000704700BF9811002038B54FF00054134B18 +:100BC00022689A4220D1124B627D12481A70237D0E +:100BD00003724FF48073C0F8F8314FF40073C0F81B +:100BE0000C3300254FF44073C0F820340A49C0F894 +:100BF000E450C922093000F003FAE02229462046D9 +:100C000000F010FA012038BD0020FCE79AAD44C581 +:100C100098110020B03200201600002037B500F0F7 +:100C200041FC194D194928810223012218486B7192 +:100C300001F000FA00230193164B1749009317485F +:100C4000174B4FF4805201F04DFE164B197811B13D +:100C5000124801F06FFE01F051FB0446FFF722FC41 +:100C60004FF4C873B0FBF3F202FB130304F51670E4 +:100C700010FA83F00C4B186002F0F4FF08B10F2358 +:100C80002B8103B030BD00BF8C11002040420F000B +:100C9000D8210020AD0700089C110020A4210020CD +:100CA000B108000898110020A02100202DE9F04F84 +:100CB0002DED028B90A7D7E900670FF24429D9E9FF +:100CC0000089884C95B00DAD9FED848BFFF728FD12 +:100CD000DFF834B200230C93ADF83C300D936B6019 +:100CE00000230DF125028DED008B4FF0010A09A9BB +:100CF00058468DF825308DF824A001F049F99DF86B +:100D000024200023002A40F0AF80204601F01AFE84 +:100D10000546002847D1DFF8F4B101F0EFFADBF81F +:100D2000003098423FD301F0E9FA0790FFF7BAFB91 +:100D3000079A4FF4C873B0FBF3F101FB130302F5FC +:100D4000167010FA83F0CBF80000DFF8C4B19BF8FE +:100D500000100791002914BF2B46534610A88DF8A8 +:100D60003030FFF7B7FB0799C1F11002D2B2062A63 +:100D700010AB28BF062219440DF13100079200F094 +:100D80003FF9079A0CAB0393182302930132564B99 +:100D9000D2B2CDE900A304923B463246204601F090 +:100DA00017FE8BF8005001F0A9FA504A504D136815 +:100DB000C31AB3F57A7F32D3106001F0A1FA02466C +:100DC0000B46204601F09CFE204601F0BBFD30B3EF +:100DD0002B7ADFF840A1002B14BF032302238AF8EB +:100DE000053001F08BFA0DF1400B4FF47A730122BC +:100DF000B0FBF3F05946CAF80000504600F004FA80 +:100E0000182302933B4B019380B240F25513CDE976 +:100E100003B0009342464B46204601F0D9FD2B7AA1 +:100E2000B3B101F06BFA4FF0000A83464FF48A72B7 +:100E300095F8D900504400F0030002FB005393F8EA +:100E4000E810002934D00AF1010ABAF1040FEFD1F9 +:100E5000C82002F0BBFB2B7A002B7FF434AF15B017 +:100E6000BDEC028BBDE8F08F4FF0904110A84A69AD +:100E700082F002024A611946102200F0D3F80DF107 +:100E800026030AAA0CA9584600F0EAFD95E80300DB +:100E900011AB83E803009DF83C308DF84C300C9B7F +:100EA000109310A9DDE90A23204601F0FDFF17E7A2 +:100EB000D3F8E01049B12B68FA2B38BFFA23ABEB1B +:100EC00001010533B1EB430FBDD3FFF7D9FB4FF45D +:100ED0008A720028B7D1BBE7AFF3008000000000A2 +:100EE00000000000A42100209C210020E037002009 +:100EF000B0320020E4370020401DA12026812A0BBB +:100F0000F1C6A7C1D068080FD8210020A021002079 +:100F10009D2100208C11002008B5054800F03CFE02 +:100F2000BDE80840034A0449002003F09FB900BF10 +:100F3000D8210020203800207908000870B502F080 +:100F4000E1FC094E094D3080002428683388834233 +:100F500008D902F0D3FC2B6804440133B4F5204FC8 +:100F60002B60F2D370BD00BF14380020E83700209A +:100F700002F07ABD00F10060920000F5204002F01E +:100F8000FDBC0000054B1A68054B1B889B1A834269 +:100F900002D9104402F0B2BC00207047E8370020AC +:100FA00014380020024B1B68184402F0ADBC00BF8F +:100FB000E8370020024B1B68184402F0B7BC00BFA2 +:100FC000E8370020064991F8243033B10023086A3D +:100FD00081F824300822FFF7CDBF0120704700BF01 +:100FE000EC370020022804BF4FF09043986170470F +:100FF000022802BF4FF090434FF400329A617047CD +:1010000010B50023934203D0CC5CC4540133F9E7FC +:1010100010BD000003460246D01A12F9011B002938 +:10102000FAD1704702440346934202D003F8011BF1 +:10103000FAE770472DE9F8431F4D144695F8242030 +:101040000746884652BBDFF870909CB395F8243071 +:101050002BB92022FF2148462F62FFF7E3FF95F8C6 +:101060002400C0F10802A24228BF2246D6B241465F +:10107000920005EB8000FFF7C3FF95F82430A41B16 +:101080001E44F6B2082E17449044E4B285F824605A +:10109000DBD1FFF797FF0028D7D108E02B6A03EBDD +:1010A00082038342CFD0FFF78DFF0028CBD10020F1 +:1010B000BDE8F8830120FBE7EC3700202DE9F0477D +:1010C0000D46044600219046284640F27912FFF76B +:1010D000A9FF234620220021284601F087FE231D78 +:1010E00002222021284601F081FE631D03222221D5 +:1010F000284601F07BFEA31D03222521284601F08E +:1011000075FE04F1080310222821284601F06EFE26 +:1011100004F1100308223821284601F067FE04F18B +:10112000110308224021284601F060FE04F1120359 +:1011300008224821284601F059FE04F11403202218 +:101140005021284601F052FE04F11803402270217C +:10115000284601F04BFE04F120030822B021284666 +:1011600001F044FE04F121030822B821284601F0D1 +:101170003DFE04F12207C0263B46314608222846A0 +:10118000083601F033FEB6F5A07F07F10107F3D171 +:1011900004F1320308223146284601F027FE0027D9 +:1011A00004F1330A94F832304FEAC7099F4209F537 +:1011B000A47615D3B8F1000F08D1314604F5997320 +:1011C0000722284601F012FE09F24F16274694F82E +:1011D00032213B1B93420CD3F01DC008BDE8F087C1 +:1011E0000AEB070308223146284601F0FFFD0137CC +:1011F000D8E707F2331331460822284601F0F6FDFE +:1012000008360137E3E7000013B50446084600211D +:1012100001602346C0F803102022019001F0E6FD92 +:101220000198231D0222202101F0E0FD0198631D99 +:101230000322222101F0DAFD0198A31D03222521BA +:1012400001F0D4FD019804F108031022282101F0D7 +:10125000CDFD072002B010BDF7B50023047F00913B +:101260000E4607221946054601F084FC731C0093C4 +:10127000012200230721284601F07CFCC4B9B31CDD +:101280000093052223460821284601F073FC0D2413 +:101290003746B278BB1B934211D32B7FA88A073401 +:1012A000E408BBB9844294BF0020012003B0F0BD24 +:1012B000AB8ADB00083BDB08B3700824E8E7FB1CC3 +:1012C0000093214600230822284601F053FC0834ED +:1012D0000137DEE7201A18BF0120E7E7F7B5002342 +:1012E000047F00910E4608221946054601F042FC93 +:1012F000731CC4B90822009311462346284601F006 +:1013000039FC1024012372785F1C013B934211D3F6 +:101310002B7FA88A0734E408BBB9844294BF00201D +:10132000012003B0F0BDAB8ADB00083BDB08737023 +:101330000824E7E7F31900932146002308222846F2 +:1013400001F018FC08343B46DDE7201A18BF0120E5 +:10135000E7E70000F8B50E46054614460021812255 +:101360003046FFF75FFE2B4608220021304601F091 +:101370003DFD7CB96B1C07220821304601F036FD8B +:101380000F2401236A785F1C013B934204D3E01DC4 +:10139000C008F8BD0824F4E7EB19214608223046BE +:1013A00001F024FD08343B46ECE70000F8B50E469A +:1013B000054614460021CE223046FFF733FE2B4669 +:1013C00028220021304601F011FD7CB905F1080307 +:1013D00008222821304601F009FD30242F462A7AC0 +:1013E0007B1B934204D3E01DC008F8BD2824F5E719 +:1013F00007F1090321460822304601F0F7FC0834C2 +:101400000137ECE7F7B5047F00910E460123102267 +:101410000021054601F0AEFBC4B9B31C00930922BC +:1014200023461021284601F0A5FB1924374672886F +:10143000BB1B9A4211D82B7FA88A0734E408BBB99A +:10144000844294BF0020012003B0F0BDAB8ADB00D2 +:10145000103BDB0873801024E8E73B1D0093214616 +:1014600000230822284601F085FB08340137DEE717 +:10147000201A18BF0120E7E730B5094D0A44914210 +:101480000DD011F8013B5840082340F30004013B04 +:101490002C4013F0FF0384EA5000F6D1EFE730BD93 +:1014A0002083B8EDF7B5384A106851686B4603C31E +:1014B0006A4636493648082302F038FF04460028B9 +:1014C00033D10A25334A106851686B4603C36A4614 +:1014D00031492F48082302F029FF0446002849D04B +:1014E0000369B3F5583F45D8B0F8661041F2B642EB +:1014F00091423FD1294A024402F15C018B4239D327 +:101500005C3B234900209E1AFFF7B6FF3246074690 +:1015100004F164010020FFF7AFFFA3689F4229D1C7 +:10152000E368984208BF002524E00369B3F5583FFB +:1015300027D8418B41F2B642914220D1174A02444A +:1015400002F110018B4218D3103B114900209D1A63 +:10155000FFF792FF2A46064604F118010020FFF724 +:101560008BFFA3689E4202D1E368984201D00D250B +:10157000A8E70025284603B0F0BD1025A2E70C25FA +:10158000A0E70B259EE700BF28440008DC5F0300AE +:1015900000A0000831440008905F03000860FFF7D6 +:1015A00010B5037C044613B9006802F0A7FE20467C +:1015B00010BD00000023BFF35B8FC360BFF35B8FE0 +:1015C000BFF35B8F8360BFF35B8F7047BFF35B8FAD +:1015D0000068BFF35B8F704770B505460C30FFF7AE +:1015E000F5FF05F1080604463046FFF7EFFFA0427D +:1015F00006D930466D68FFF7E9FF2544281A70BD0B +:101600003046FFF7E3FF201AF9E7000070B5054602 +:10161000406898B105F10800FFF7D8FF05F10C0606 +:1016200004463046FFF7D2FF8442304694BF6D68CF +:101630000025FFF7CBFF013C2C44201A70BD0000B1 +:1016400038B50C460546FFF7C7FFA04210D305F199 +:101650000800FFF7BBFF04446868B4FBF0F100FB2F +:101660001144BFF35B8F0120AC60BFF35B8F38BDCB +:101670000020FCE72DE9F041144607460D46FFF730 +:10168000C5FF844228BF0446D4B1B84658F80C6B55 +:101690004046FFF79BFF3044286040467E68FFF7D6 +:1016A00095FF331A9C4203D86C600120BDE8F0819D +:1016B0006B60A41B3B68AB602044E8600220F5E748 +:1016C0002046F3E738B50C460546FFF79FFFA042DA +:1016D00010D305F10C00FFF779FF04446868B4FBF0 +:1016E000F0F100FB1144BFF35B8F0120EC60BFF30E +:1016F0005B8F38BD0020FCE72DE9FF418846694635 +:101700000746FFF7B7FF6C4606B204EBC606002596 +:10171000B44209D06268206808EB0501FFF770FC4D +:10172000636808341D44F3E729463846FFF7CAFFCB +:10173000284604B0BDE8F081F8B505460C300F46E8 +:10174000FFF744FF05F1080604463046FFF73EFF69 +:10175000A042304688BF6C68FFF738FF201A386017 +:1017600020B130462C68FFF731FF2044F8BD00005F +:1017700073B5144606460D46FFF72EFF844228BF78 +:1017800004460190DCB101A93046FFF7D5FF019B6B +:1017900033B93268C5E90233C5E9002401200CE001 +:1017A0009C4238BF01942860019868608442F5D952 +:1017B0003368AB60241AEC60022002B070BD204692 +:1017C000FBE700002DE9FF410F466946FFF7D0FF18 +:1017D0006C4600B204EBC0050026AC4209D0D4F838 +:1017E000048054F8081BB8194246FFF709FC464428 +:1017F000F3E7304604B0BDE8F081000038B5054697 +:10180000FFF7E0FF044601462846FFF719FF204690 +:1018100038BD000010B4026854681A4623465DF8CB +:10182000044B1847002070470020704770470000A5 +:10183000002070470E20704700F5805090F8C800D7 +:10184000C0F340007047000000F5805090F9D000D0 +:101850007047000000F58050C0F8CC1001207047A0 +:10186000F7B50C68BDF8207014F0005470D10D7BF2 +:10187000082D6DD8302585F311884569AE6876014D +:101880000CD4AC68240108D4AC6814F080545DD149 +:1018900084F31188204603B0F0BD01240E6804F1E2 +:1018A000180C002EB8BFF6004FEA0C1CB4BF46F06F +:1018B0000406760545F80C600E680FFA84FC16F0F5 +:1018C000804F18BF05EB0C1E05EB0C1C1EBFDEF88D +:1018D000806146F00206CEF880610E7BCCF8846110 +:1018E00005EB04158E68C5F88C614E68C5F88861F3 +:1018F000DCF8805145F00105CCF8805100EB44162E +:1019000041F268052E4405EB44150544C6E9002361 +:1019100008350E4601F10C0C56F804EB45F804EBC3 +:101920006645F9D1843436882E8000EB441407F0E4 +:101930000305267926F00B0635432571002484F330 +:101940001188009700F0FCFC0120A4E70224A5E721 +:101950004FF0FF309FE7000013B500F58054019170 +:10196000E06DFFF753FE1F280AD90199E06D202290 +:10197000FFF7C2FEA0F120035842584102B010BD4B +:101980000020FBE708B5302383F3118800F5805071 +:10199000C06DFFF70FFE002383F3118808BD000020 +:1019A00000220260828142608260704710B500228E +:1019B0000023C0E900230023044603810C30FFF715 +:1019C000EFFF204610BD0000F0B5054600F5805041 +:1019D0000C4690F8C83013F0040FC3F3800108BF21 +:1019E000114661F3820304F1840680F8C83005EBE8 +:1019F000461389B01B79D8072ED57AB319072DD491 +:101A00006846FFF7D3FF05EB441303F5835303F157 +:101A1000180703AA103318685968144603C408331A +:101A2000BB422246F7D1186820609B88A380DDE97D +:101A30000E23CDE900230123ADF808302B68694659 +:101A4000DB6B2846984705EB46152B791A075CBFD8 +:101A500043F008032B7101E0002AF4D109B0F0BD76 +:101A60002DE9F0479A4688B00746884691463023CC +:101A700083F3118807F580546846FFF797FFE06D00 +:101A8000FFF7AAFD1F282AD9E06D20226946FFF73B +:101A9000B5FE202823D103AD444605AB2E4603CE28 +:101AA0009E4220606160354604F10804F6D130683A +:101AB0002060B388A380DDE90023C9E90023BDF8D5 +:101AC0000830AAF80030002383F3118853464A46B1 +:101AD0004146384608B0BDE8F04700F01FBC002082 +:101AE00080F3118808B0BDE8F08700002DE9F84FB9 +:101AF0000023C0E90133254B044640F8183B0F464C +:101B0000FFF74EFF04F12800FFF750FF04F14808EB +:101B100004F582554646083530462036FFF746FF25 +:101B2000AE42F9D104F580554FF480534FF00009CF +:101B3000C5E91339C5F848800123EE6504F58758D7 +:101B400004F58456C5F8549085F8583085F860300F +:101B5000083608F108084FF0000A4FF0000B46E97C +:101B600008ABA6F11800FFF71BFF203646F8289CAB +:101B70004645F4D185F8D07017B1054800F0B8FBA0 +:101B8000044B63612046BDE8F88F00BF6444000841 +:101B90003C4400080064004010B5044B197804462A +:101BA0004A1C1A70FFF7A2FF204610BD1C38002007 +:101BB0002DE9F047002950D0294B2A4FB7FBF1F50A +:101BC00099428CBF0A231123581EB5FBF3FC03FB7B +:101BD0001C53C4B22BB102280346F5D80020BDE83F +:101BE000F0870CF1FF36B6F5806FF7D2C4EBC40E68 +:101BF0000EF103034FEAE309C3F3C703A4EB0308A1 +:101C000009F1010A4FF47A755FFA88F009FB05556E +:101C10005AFA88F8B5FBF8F5B5F5617FC1BF0EF14A +:101C2000FF33C3F3C703E01AC0B25C1C50FA84F45C +:101C30000CFB04F4B7FBF4F4A142CFD1013BDBB2BF +:101C40000F2BCBD80138C0B20728C7D8002110719C +:101C500016809170D3700120C1E70846BFE700BF2E +:101C60003F420F0000B4C40470B505460E464FF461 +:101C70007A746B695B6803F00103B34207D04FF4D9 +:101C80007A7001F0A3FC013CF3D1204670BD012025 +:101C9000FCE7000030B54269936913F0700F16D06D +:101CA00000230B4C936103F1840200EB4212117983 +:101CB0004D0709D5890707D5416954F823508D6030 +:101CC000117941F0040111710133032BEBD130BDC7 +:101CD0005044000873B51D46436916469A68D207FA +:101CE000044609D59A6801219960C2F34002CDE902 +:101CF00000650021FFF768FE63699A68D1050BD57E +:101D00009A684FF480719960C2F34022CDE9006572 +:101D100001212046FFF758FE63699A68D2030BD56C +:101D20009A684FF480319960C2F34042CDE9006572 +:101D300002212046FFF748FE04F58053D3F8CC007B +:101D400010B103681B699847204602B0BDE8704097 +:101D5000FFF7A0BFF8B504464669002972D106F125 +:101D60000C073868800770D006EB01153868D5F885 +:101D7000B00110F0040FD5F8B0011ABFC00840F050 +:101D80000040400DA061D5F8B0C11CF0020F1CBF8F +:101D900040F08040A061D5F8B40106EB011100F0DD +:101DA0000F0084F82400D1F8B8012077D1F8B801E9 +:101DB000000A6077D1F8B801000CA077D1F8B8011B +:101DC000000EE077D1F8BC0184F82000D1F8BC0106 +:101DD000000A84F82100D1F8BC01000C84F822002C +:101DE000D1F8BC11090E84F823103821396004F1B0 +:101DF000340004F1180104F1240551F8046B40F893 +:101E0000046BA942F9D109880180C4E90A2321465B +:101E10000023238651F8283B2046DB6B984704F5C6 +:101E2000805393F8C820D3F8CC0042F0040283F822 +:101E3000C82010B103681B6998472046BDE8F840E8 +:101E4000FFF728BF06F110078BE7F8BD10B5044671 +:101E500000F056FA02460B4652EA030102D0013A5C +:101E600063F100030449086820B12146BDE8104031 +:101E7000FFF770BF10BD00BF18380020F0B530214B +:101E800081F31188DFF848C000F583510831002440 +:101E900004F1840500EB45152E7977070ED4F6067C +:101EA0000CD5D1E9007697429E4107D246695CF88D +:101EB0002470B7602E7946F004062E710134032C8D +:101EC00001F12001E4D1002383F31188F0BD00BFAC +:101ED0005044000808B5302383F31188FFF7DAFE79 +:101EE000002383F3118808BDF8B543690546986857 +:101EF00000F0E050B0F1E05F0F4621D0F8B13023A0 +:101F000083F3118805F583541034002606F1840309 +:101F100005EB43131B791A0706D50136032E04F18E +:101F20002004F3D1012007E05B07F6D421463846B0 +:101F300000F040FA0028F0D1002383F31188F8BDA7 +:101F40000120FCE708B5302383F3118800F58050A9 +:101F5000C06DFFF741FB002383F3118843090CBFD9 +:101F60000120002008BD0000F8B51D4600231370B5 +:101F70000F4606461446FFF7E5FF80F00100387073 +:101F800025B129463046FFF7AFFF2070F8BD0000AD +:101F90002DE9B8410C4615461F46804600F0B0F9C1 +:101FA0000B462178024609B9287850B14046FFF720 +:101FB00065FFFFF78FFF3B462A462146FFF7D4FF18 +:101FC0000120BDE8B881000070B5302686F3118885 +:101FD000174B9A6D42F000729A659A6B42F000724C +:101FE0009A639A6B22F000729A63002383F311883C +:101FF00000F5805494F8C83013F0010516D1A9B14A +:1020000086F311880321132001F0DCF90321142049 +:1020100001F0D8F90321152001F0D4F994F8C83063 +:1020200043F0010384F8C83085F3118870BD00BF08 +:10203000001002402DE9F04700F5805588B095F872 +:10204000D030012B04468846164600F28180814F2D +:1020500057F823200AB947F82300D7F800A0C4F89E +:102060000C802674BAF1000F64D095F8D030012BA3 +:1020700070D001212046FFF7A7FF302383F311889A +:102080006269136823F0020313606269136843F006 +:1020900001031360636900275F6187F311880121E1 +:1020A0002046FFF7E1FD002800F09580E86DFFF77E +:1020B00081FA04F58359BA4609F108092022002162 +:1020C0006846FEF7AFFF02A8FFF76AFCCDF818A03C +:1020D0006A4609EB07030DF1180E9446BCE80300AD +:1020E000F44518605960624603F10803F5D1DCF845 +:1020F0000000186020379CF804201A71602FDDD191 +:1021000095F8C8306FF38203002785F8C8306A4617 +:1021100041462046ADF80070ADF802708DF80470AD +:10212000FFF746FD636948BB4FF400421A6008B0F0 +:10213000BDE8F08741F2D80002F0A0F8814610B166 +:102140005146FFF7D3FCC7F80090B9F1000F8CD1CE +:102150000020ECE7386803681B6B984701460028AD +:1021600087D13868FFF730FF3868036832465B680C +:102170004146984700287FF47CAFE9E761221A6066 +:102180009DF802309DF803201B06120402F4702211 +:1021900003F040731343BDF80020C2F30902134358 +:1021A0009DF804201205022E02F4E0020CBF4FF04D +:1021B00000410021134362690B43D3616369132219 +:1021C0005A616269136823F001031360394620469F +:1021D000FFF74AFD08B96369A6E795F8D03093BBCD +:1021E0006169D1F8002242F00102C1F80022616960 +:1021F000D1F8002222F47C5222F00E02C1F8002213 +:102200006169D1F8002242F46062C1F8002262697B +:10221000C2F814326269C2F80432626941F6FF7191 +:10222000C2F80C126269C2F840326269C2F84432E4 +:1022300063690122C3F81C226269D2F8003223F0DC +:102240000103C2F8003295F8C83043F0020385F864 +:10225000C8306CE71838002008B500F051F850EA93 +:102260000103024602D0421E61F10001044B1868CE +:1022700010B10B46FFF72EFDBDE8084001F064B831 +:102280001838002008B50020FFF7E0FDBDE8084041 +:1022900001F05AB808B50120FFF7D8FDBDE80840A5 +:1022A00001F052B800B59BB0EFF30981682268468F +:1022B000FEF7A6FEEFF30583014B9B6BFEE700BF25 +:1022C00000ED00E008B5FFF7EDFF000000B59BB0A2 +:1022D000EFF3098168226846FEF792FEEFF305836B +:1022E000014B5B6BFEE700BF00ED00E0FEE7000086 +:1022F0000FB408B5029801F019F9FEE701F0F8BB38 +:1023000001F0DABB13B56C4684E80600031D94E8BF +:10231000030083E80500012002B010BD73B5856895 +:10232000019155B11B885B0707D4D0E900369B6B40 +:102330009847019AC1B23046A847012002B070BD4B +:10234000F0B5866889B005460C465EB1BDF83830F8 +:102350005B070AD4D0E900379B6B98472246C1B28D +:102360003846B047012009B0F0BD00220023CDE976 +:1023700000230023ADF808300A4603AB01F108063C +:10238000106851681C4603C40832B2422346F7D194 +:10239000106820609288A280FFF7B2FF0423ADF896 +:1023A00008302B68CDE90001DB6B69462846984769 +:1023B000D8E7000030B503680968DD0FB5EBD17FC1 +:1023C00023F0604421F060424FEAD1700BD0002B23 +:1023D000B8BFA40C0029B8BF920C944202D034BFFD +:1023E0000120002030BD944205D1C1F38070C3F3B9 +:1023F00080738342F6D194422CBF00200120F1E784 +:102400002DE9F041456A15B94162BDE8F0814B689C +:1024100023F06047C3F38A464FEAD37EC3F3807844 +:1024200016EA230638BF3E46AC462B465A68BEEB3A +:10243000D27F22F060440AD0002A18DAA40CB442F9 +:1024400017D19D420FD10D60DEE71346EEE7A7429C +:1024500007D102F08044C2F3807242450BD054B1E0 +:10246000EFE708D2EDE7CCF800100B60CDE7B442FF +:1024700001D0B442E5D81A689C46002AE5D119601B +:10248000C3E700002DE9F047089D01F007044FEA7B +:10249000D508224405F0070500EBD1004FF47F4931 +:1024A000944201D1BDE8F08704F0070705F0070A60 +:1024B00057453E4638BF5646C6F10806111B8E42A8 +:1024C00028BF0E46E10808EBD50E415C13F80EC09C +:1024D000B94029FA06F721FA0AF1FFB28CEA0101A4 +:1024E00047FA0AF739408CEA010C03F80EC034446D +:1024F0003544D5E780EA0120082341F2210201B2E8 +:102500004000002980B203F1FF33B8BF504013F000 +:10251000FF03F4D17047000038B50C468D18A54272 +:1025200000D138BD14F8011BFFF7E4FFF7E7000006 +:1025300042684AB1136843604389818901339BB281 +:102540009942438138BF83811046704770B588B087 +:10255000202204460D4668460021FEF763FD204612 +:102560000495FFF7E5FF024658B16B46054608AEF5 +:102570001C4603CCB44228606960234605F1080577 +:10258000F6D1104608B070BD082817D909280CD01C +:102590000A280CD00B280CD00C280CD00D280CD0FD +:1025A0000E2814BF4020302070470C2070471020A8 +:1025B0007047142070471820704720207047000093 +:1025C000082817D90C280CD910280CD914280CD994 +:1025D00018280CD920280CD930288CBF0F200E20A9 +:1025E0007047092070470A2070470B2070470C2065 +:1025F00070470D20704700002DE9F843078C072F26 +:1026000004461ED9D0E9029800254FF6FF73C5F1A4 +:102610002006A5F1200029FA05F108FA06F628FAA5 +:1026200000F031430143C9B21846FFF763FF083594 +:10263000402D0346EBD1E1693A46BDE8F843FFF788 +:102640006BBF4FF6FF70BDE8F883000010B54B6814 +:1026500023B9CA8A63F30902CA8210BD04691A68E1 +:102660001C600361C38A013BC3824A60EFE700003C +:102670002DE9F84F1D46CB8A0F46C3F30901052902 +:10268000814692460B4630D00020AAB207F11A04C8 +:102690009EB2042E1FFA80F80FD8904503F1010373 +:1026A00006D3FB8A0A4462F30903FB8201201AE085 +:1026B0001AF80060E6540130EAE79045F1D2A1F142 +:1026C000050B1C237C68BBFBF3F203FB12BB1FFA58 +:1026D0008BF6002C45D14846FFF72AFF044638B94F +:1026E00078606FF00200BDE8F88F4FF00008E6E771 +:1026F000002606607860ADB24FF0000B454510D95A +:102700000AEB0803221D13F8011B9155B1B208F121 +:1027100001081B291FFA88F82BD0454506F1010650 +:10272000F1D8FB8AC3F30902154465F30903BCE73A +:10273000013292B21C462368002BF9D16B1F0B4467 +:102740001C21B3FBF1F301339BB29A42D3D2BBF10C +:10275000000FD0D14846FFF7EBFE20B9C4F800B017 +:10276000BFE70122E7E7C0F800B05E4620600446FC +:10277000C1E74545D5D94846FFF7DAFE08B92060DC +:10278000AFE7C0F800B0002620600446B6E70000BE +:102790002DE9F04F2DED028B1C4683B05B69019251 +:1027A00007468846002B00F09A80238C2BB1E26903 +:1027B000002A00F09480072B35D807F10C00FFF7B2 +:1027C000B7FE054638B96FF00205284603B0BDECE8 +:1027D000028BBDE8F08F14220021FEF723FC228C2F +:1027E000E16905F10800FEF70BFC208C013080B296 +:1027F000FFF7E6FEFFF7C8FE013880B22084013003 +:1028000028746369228C1B782A4403F01F0363F049 +:102810003F0348F000411372384669602946FFF7CC +:10282000EFFD0125D1E700F10C034FF0000908EEA0 +:10283000103A4FF0800A4E464D4618EE100AFFF748 +:1028400077FE83460028BED014220021FEF7EAFB63 +:10285000002E3AD1019BABF8083002220BF1080E92 +:102860001FFA82FC0CF10100BCF1060F218C80B232 +:1028700001D88E422BD3FFF7A3FEFFF785FE6269D6 +:102880001278013802F01F028E4208BF4FF0400A52 +:1028900042EA49121BFA80F14AEA020A013048F082 +:1028A000004281F808A08BF81000CBF804205946AC +:1028B0003846FFF7A5FD238C0135B3422DB289F0D0 +:1028C00001094FF0000AB8D17FE70022C6E7E169AD +:1028D000895D0EF802100136B6B20132C0E76FF022 +:1028E000010572E7F8B515460E4630220021044670 +:1028F0001F46FEF797FB069B6360B5F5001F079B1D +:10290000A76034BF6A094FF6FF72A36297B2E6610F +:1029100004F1100000239A4206D800230360A78226 +:10292000E3822383E360F8BD06600133304620363E +:10293000F1E7000003781BB94BB2002BC8BF017050 +:102940007047000000787047F8B50C46C969074623 +:1029500011B9238C002B37D1257E1F2D34D8387820 +:1029600028BB228C072A2CD8268A36F003032BD1C9 +:102970004FF6FF70FFF7D0FD20F001003102400458 +:1029800041EA0561400C41EA40254FF6FF722346BB +:1029900029463846FFF7FCFE002807DD62691378F8 +:1029A0000133DBB21F2B88BF00231370F8BD218ACF +:1029B0002D0645EA012505432046FFF71DFE024688 +:1029C000E5E76FF00300F1E76FF00100EEE70000CC +:1029D00070B58AB0044616460021282268461D4676 +:1029E000FEF720FBBDF83830ADF810300F9B059393 +:1029F0009DF840308DF81830119B07936946BDF85B +:102A00004830ADF820302046CDE90265FFF79CFF45 +:102A10000AB070BD2DE9F041D36905460C46164653 +:102A20000BB9138C5BBB377E1F2F28D895F800801D +:102A3000B8F1000F26D03046FFF7DEFD33782102D3 +:102A400041EAC33141EA0801338A41EA076141EAB8 +:102A500003410246334641F080012846FFF798FEC5 +:102A600000280ADD3378012B07D17269137801330E +:102A7000DBB21F2B88BF00231370BDE8F0816FF01D +:102A80000100FAE76FF00300F7E70000F0B58BB044 +:102A900004460D4617460021282268461E46FEF7CA +:102AA000C1FA9DF84C305A1E534253418DF8003004 +:102AB0009DF84030ADF81030119B05939DF84830DB +:102AC0008DF81830149B07936A46BDF85430ADF862 +:102AD000203029462046CDE90276FFF79BFF0BB058 +:102AE000F0BD0000406A00B104307047436A1A68C4 +:102AF000426202691A600361C38A013BC382704764 +:102B00002DE9F041D0F82080194E14461D4641466B +:102B1000002709B9BDE8F081D1E90223A21A65EBCB +:102B20000303964277EB03031ED2036A8B420DD157 +:102B3000FFF78CFD036A1B68036203690B60C38A9D +:102B40000161016A013BC3828846E2E7FFF77EFD2F +:102B50000B68C8F8003003690B60C38A0161013B50 +:102B6000C382D8F80010D4E788460968D1E700BFCF +:102B700080841E002DE9F04F8BB00D46DDF850909B +:102B800014469B468046002800F01981B9F1000FD9 +:102B900000F01581531E3F2B00F21181012A03D151 +:102BA000BBF1000F40F00B810023CDE90833B8F8EA +:102BB0001430B5EBC30F4FEAC30703D300200BB0AB +:102BC000BDE8F08F2B199F42D8F80C303ABF7F1B1D +:102BD000FFB227461BB9D8F81030002B7AD0272D2A +:102BE0004ED8C5F12806B7424FF000032CBFF6B20D +:102BF0003E4600932946D8F8080008AB3246FFF756 +:102C000041FCA7EB060A35445FFA8AFAB8F814309B +:102C100003F10053053BDB000493D8F80C30039319 +:102C20002821039B13B1BAF1000F2CD1D8F8100062 +:102C300040B1BAF1000F05D0009608AB5246691AB0 +:102C4000FFF720FC38B2002FB8D066070AD00AABD5 +:102C500003EBD401624211F8083C02F00702134171 +:102C600001F8083C082C3CD9102C40F2B580202CEF +:102C700040F2B780BBF1000F00F09C80082334E0E5 +:102C8000BA460026C2E7049BE02B28BFE023069348 +:102C90000B44AB42059314D95A1B039800969245F6 +:102CA00034BF5246D2B2691A08AB04300792FFF71C +:102CB000E9FB079A1644AAEB020A1544F6B25FFA3A +:102CC0008AFA049B069A05999B1A0493039B1B6836 +:102CD0000393A6E70093D8F8080008AB3A462946C4 +:102CE000AEE7BBF1000F13D00123B4EBC30F6CD0E0 +:102CF000082C12D89DF82030621E23FA02F2D50764 +:102D000006D54FF0FF3202FA04F423438DF8203049 +:102D10009DF8203089F8003051E7102C12D8BDF80A +:102D20002030621E23FA02F2D10706D54FF0FF329F +:102D300002FA04F42343ADF82030BDF82030A9F89E +:102D400000303CE7202C0FD80899631E21FA03F3CA +:102D5000DA0705D54FF0FF3202FA04F40C43089469 +:102D6000089BC9F800302AE7402C2BD0DDE9086524 +:102D7000611EC4F12102A4F1210326FA01F105FA32 +:102D800002F225FA03F311431943CB0712D50122AE +:102D9000A4F12003C4F1200102FA03F322FA01F1A5 +:102DA000A240524243EA010363EB430332432B4305 +:102DB000CDE90823DDE90823C9E90023FFE66FF028 +:102DC0000100FCE66FF00800F9E6082CA0D9102CF1 +:102DD000B3D9202CEED8C3E7BBF1000FADD002234E +:102DE00083E7BBF1000FBBD004237EE730B5012A97 +:102DF000144638BF0124402C85B028BF402400254C +:102E0000012ACDE9025518D81B788DF808306307E0 +:102E10000AD004AB03EBD405624215F8083C02F07B +:102E20000702934005F8083C009103462246002122 +:102E300002A8FFF727FB05B030BD082AE4D9102A05 +:102E400003D81B88ADF80830E1E7202A8DBFD3E90D +:102E500000231B680293CDE90223D8E710B5CB68A5 +:102E60001BB98B600B618B8210BD04691A681C60F2 +:102E70000361C38A013BC382CA60F0E703064CBF0B +:102E8000C0F3C0300220704708B50246FFF7F6FFD6 +:102E9000022806D15306C2F30F2001D100F003002F +:102EA00008BDC2F30740FBE72DE9F04F93B0CDE931 +:102EB00003230A6804461046FFF7E0FF022814BF08 +:102EC000C2F306260026002A0D46824680F2F281D1 +:102ED00012F0C04940F0EE81097B002900F0EA8140 +:102EE000022803D02378B34240F0E781C2F30463A1 +:102EF0000693104602F07F030593FFF7C5FF059B7D +:102F000029444FEA834848EA0A4848EA4668CE78A6 +:102F100000230022CDE90823F309834648EA00088C +:102F2000029367D0059B009302466768534608A941 +:102F30002046B847002800F0C381276A4FB94146B0 +:102F400004F10C00FFF702FB074690B96FF0020096 +:102F500054E03B6998450DD03F68002FF9D14146B8 +:102F600004F10C00FFF7F2FA07460028EED0236ABE +:102F70003B60276297F817C006F01F08CCF3840C5B +:102F8000ACEB08001FFA80FE0028B8BF0EF120004D +:102F9000A8EB0C031FFA83FED7E90221B8BF00B2E9 +:102FA000002B0793BEBF0EF120031BB2079352EA1A +:102FB000010338D0039BDFF824E39A1A049B4FF0F7 +:102FC000000C63EB010196457CEB01032BD36B7B7B +:102FD00097F81AE0734519D1029B002B78D001288D +:102FE00021DC7868F8B9DFF8F0C2944570EB010392 +:102FF00016D337E0276A27B96FF00C0013B0BDE88D +:10300000F08F3B699845B5D03F68F4E7B2489042ED +:103010007CEB010301D30020F0E7029B002BFAD0E8 +:10302000079B0F2B17DCFA7DB30002F0030203F0BD +:103030007C031343FB7539462046FFF707FB6B7B88 +:10304000BB76029B3BB9FB7DC3F38402013262F382 +:103050008603FB75D0E76A7BBB7E9A42DBD1029B7D +:10306000002B35D0B309022B32D0039BBB60049BED +:10307000FB60142200210DA8FDF7D4FF039B0A93E7 +:10308000049B0B932B1D0C932B7BADF83EB0013BA7 +:10309000DBB2ADF83C30069B8DF84230059B8DF8D5 +:1030A000433094F82C308DF840A083F001038DF864 +:1030B00044308DF84180A3680AA920469847FB7DDB +:1030C000C3F38403013303F01F039B02FB82A2E7D7 +:1030D000FB7DC6F34012B2EBD31F40F0F480C3F384 +:1030E0008403434540F0F280029A2B7BB609002A04 +:1030F0004DD0F2075DD4032B40F2EB80039BBB6005 +:10310000049BFB602B7BAE1D033BDBB23246394692 +:1031100004F10C00FFF7ACFA00280CDA394620461F +:10312000FFF794FAFB7DC3F38403013303F01F031D +:103130009B02FB820AE7DDE90884AB883B834FF6FC +:10314000FF73C9F12000A9F1200228FA09F104FA5D +:1031500000F0014324FA02F211431846C9B2FFF706 +:10316000C9F909F10809B9F1400F0346E9D1B8825C +:103170002A7B033AD2B23146FFF7CEF9FB7DB88203 +:10318000DA43C2F3C01262F3C713FB7543E786B993 +:103190002E1D013BDBB23246394604F10C00FFF72D +:1031A00067FA0028BADB2A7BB88A013AD2B23146E4 +:1031B000E2E7F98AC1F30901013B0429DAB25BD8DD +:1031C000281D002307F11B069A4208D910F801CBED +:1031D00006F801C0013101330529DBB2F4D10399AE +:1031E0000A9104990B91934207F11B010C9138BF8E +:1031F000043379680D9134BF55FA83F300230E939D +:10320000FB8AADF83EB0C3F309031A44069B8DF860 +:103210004230059B8DF8433094F82C30ADF83C20BB +:1032200083F001038DF8443000238DF840A08DF821 +:1032300041807B602A7BB88A013A291DFFF76CF92F +:103240003B8BB882834203D1A3680AA920469847E2 +:1032500020460AA9FFF702FEFB7DBA8AC3F3840366 +:10326000013303F01F039B02FB823B8B9A420CBF8E +:1032700000206FF01000C1E67B68002BAFD0052066 +:1032800001E01C3033461E68002EFAD1091A081DD1 +:103290002E1D184401EB090CBCF11B0F5FFA89F3DA +:1032A0009DD89A429BD916F8013B00F8013B09F1E1 +:1032B0000109EFE76FF00900A0E66FF00A009DE654 +:1032C0006FF00B009AE66FF00D0097E66FF00E00BE +:1032D00094E66FF00F0091E640420F0080841E00DC +:1032E000EFF3098305494A6B22F001024A63683310 +:1032F00083F30988002383F31188704700EF00E00F +:10330000302080F3118862B60C4B0D4AD96821F445 +:10331000E0610904090C0A43DA60D3F8FC2009498A +:1033200042F08072C3F8FC200A6842F001020A6091 +:103330002022DA7783F82200704700BF00ED00E01A +:103340000003FA05001000E010B5302383F3118864 +:103350000E4B5B6813F4006314D0F1EE103AEFF3F8 +:103360000984683C4FF08073E361094BDB6B236693 +:1033700084F3098800F0A4F810B1064BA36110BDD6 +:10338000054BFBE783F31188F9E700BF00ED00E090 +:1033900000EF00E0FF020008020300084FF0E02306 +:1033A000002258684FF0FF31930003F1604303F5AA +:1033B000614301329042C3F88010C3F88011F3D208 +:1033C0007047000000F1604303F561430901C9B291 +:1033D00083F80013012200F01F039A4043099B0069 +:1033E00003F1604303F56143C3F880211A6070471D +:1033F00000230375826803691B6899689142FBD2B8 +:103400005A6803604260106058607047002303757B +:10341000826803691B6899689142FBD85A68036007 +:10342000426010605860704708B50846302383F347 +:1034300011880B7D032B05D0042B0DD02BB983F302 +:10344000118808BD8B6900221A604FF0FF33836139 +:10345000FFF7CEFF0023F2E7D1E9003213605A6094 +:10346000F3E70000FFF7C4BF054BD968087518687B +:1034700002681A60536001220275D860FCF72ABF07 +:103480002838002030B50C4BDD684B1C87B0044653 +:103490000FD02B46094A684600F02AF92046FFF76C +:1034A000E3FF009B13B1684600F02CF9A86907B050 +:1034B00030BDFFF7D9FFF9E728380020293400088C +:1034C000044B1A68DB6890689B68984294BF0020A0 +:1034D0000120704728380020084B10B51C68D868B8 +:1034E00022681A60536001222275DC60FFF78EFFAC +:1034F00001462046BDE81040FCF7ECBE283800200D +:1035000038B5074C0749084801230025237065603A +:1035100000F0EEFB0223237085F3118838BD00BF55 +:10352000503A0020A84400082838002008B572B698 +:10353000044B186500F0ACFA00F05CFB024B032270 +:103540001A70FEE728380020503A002000F010B929 +:103550008B60022308618B82084670478368A3F161 +:10356000840243F8142C026943F8442C426943F85E +:10357000402C094A43F8242CC26843F8182C022234 +:1035800003F80C2C002203F80B2C044A43F8102CEF +:10359000A3F12000704700BFED020008283800208A +:1035A00008B5FFF7DBFFBDE80840FFF75BBF000091 +:1035B000024BDB6898610F20FFF756BF28380020C8 +:1035C000302383F31188FFF7F3BF000008B50146ED +:1035D000302383F311880820FFF754FF002383F37F +:1035E000118808BD10B503689C68A2420CD85C68BD +:1035F0008A600B604C602160596099688A1A9A60F1 +:103600004FF0FF33836010BD1B68121BECE7000016 +:103610000A2938BF0A2170B504460D460A266019EA +:1036200000F060FB00F04CFB041BA54203D8751CA6 +:103630002E460446F3E70A2E04D9BDE87040012067 +:1036400000F096BB70BD0000F8B5144B0D46D96173 +:1036500003F1100141600A2A1969826038BF0A2209 +:10366000016048601861A818144600F02DFB0A2775 +:1036700000F026FB431BA342064606D37C1C2819F8 +:1036800000F030FB27463546F2E70A2F04D9BDE8A3 +:10369000F840012000F06CBBF8BD00BF28380020C6 +:1036A000F8B506460D4600F00BFB0F4A134653F8DB +:1036B000107F9F4206D12A4601463046BDE8F840B9 +:1036C000FFF7C2BFD169BB68441A2C1928BF2C462A +:1036D000A34202D92946FFF79BFF22463146034801 +:1036E000BDE8F840FFF77EBF2838002038380020BA +:1036F00010B4C0E9032300235DF8044B4361FFF7D6 +:10370000CFBF000010B5194C236998420DD0D0E905 +:103710000032816813605A609A680A449A600023F4 +:1037200003604FF0FF33A36110BD2346026843F8E6 +:10373000102F53600022026022699A4203D1BDE833 +:10374000104000F0C9BA936881680B44936000F0A0 +:10375000B7FA2269E1699268441AA242E4D9114495 +:10376000BDE81040091AFFF753BF00BF28380020FA +:103770002DE9F047DFF8BC8008F110072C4ED8F88F +:10378000105000F09DFAD8F81C40AA68031B9A421A +:103790003ED81444D5E900324FF00009C8F81C4067 +:1037A00013605A60C5F80090D8F81030B34201D1C8 +:1037B00000F092FA89F31188D5E903312846984739 +:1037C000302383F311886B69002BD8D000F078FA8E +:1037D0006A69A0EB04094A4582460DD2022000F036 +:1037E000C7FA0022D8F81030B34208D15146284613 +:1037F000BDE8F047FFF728BF121A2244F2E712EBA8 +:10380000090938BF4A4629463846FFF7EBFEB5E7B7 +:10381000D8F81030B34208D01444211AC8F81C005C +:10382000A960BDE8F047FFF7F3BEBDE8F08700BF31 +:10383000383800202838002038B500F041FA054A11 +:10384000D2E90845031B181945F10001C2E9080136 +:1038500038BD00BF2838002000207047FEE7000078 +:10386000704700004FF0FF3070470000BFF34F8FEC +:10387000024A1369DB03FCD4704700BF00200240FA +:1038800008B5094B1B7873B9FFF7F0FF074B5A696E +:10389000002ABFBF064A9A6002F188329A601A680D +:1038A00022F480621A6008BD683A002000200240BD +:1038B0002301674508B50B4B1B7893B9FFF7D6FF7B +:1038C000094B5A6942F000425A611A6842F4805228 +:1038D0001A601A6822F480521A601A6842F48062F0 +:1038E0001A6008BD683A0020002002407F289ABF75 +:1038F00000F58030C0020020704700004FF40060E7 +:1039000070470000802070477F2808B50BD8FFF76C +:10391000EDFF00F500630268013204D104308342F8 +:10392000F9D1012008BD0020FCE700007F2810B578 +:1039300004461FD8FFF79AFFFFF7A2FF0E4BF322B2 +:103940001A6102225A615A6942EAC0025A615A69EE +:1039500042F480325A61FFF789FF4FF40061FFF7AC +:10396000C5FF00F043F9FFF7A5FF2046BDE8104072 +:10397000FFF7CABF002010BD002002402DE9F84328 +:1039800040EA020313F00703144606D0304B40F21E +:1039900041321A600020BDE8F88385182D4A95420F +:1039A0000CD92B4A40F246311160F3E7031D1B6826 +:1039B0004A68934208D1083C08300831072C14D9D2 +:1039C00002680B689A42F1D0FFF75AFFFFF74EFFEB +:1039D000214E08314FF001084FF00009012CA1F1F0 +:1039E000080706D8FFF766FF01E0002CECD10120A4 +:1039F000D1E7C6F81480054651F8083C45F8043B69 +:103A000051F8043C4360FFF731FF336943F0010391 +:103A10003361C6F81490026851F8083C9A420CD001 +:103A20000B4B40F26E321A600C4B18600C4B1C6052 +:103A30000C4B1F60FFF73EFFACE72D6851F8043CCC +:103A40009D4201F10801EBD1083C0830C6E700BFF8 +:103A5000643A00200000040800200240583A002088 +:103A6000603A00205C3A0020084908B50B7828B17C +:103A70001BB9FFF705FF01230B7008BD002BFCD01D +:103A8000BDE808400870FFF715BF00BF683A002086 +:103A900002484FF47F4100F0ABB800BF00010020A6 +:103AA0000846114600F00CBC012000F009BC0000E3 +:103AB000084600F023BC000038B5EFF311859DB92E +:103AC000EFF30584C4F30804302334B183F3118881 +:103AD000FFF7B2FE85F3118838BD83F31188FFF735 +:103AE000ABFE84F3118838BDBDE83840FFF7A4BEB3 +:103AF00038B5FFF7E1FF114C114AC00840EA4170A8 +:103B0000A0FB025EC908A0FB040C1CEB050CA1FB8A +:103B100004404FF000035B41A1FB02121CEB040CBC +:103B200043EB000011EB0E0142F10002411842F19B +:103B30000000090941EA007038BD00BFCFF753E328 +:103B4000A59BC42010B50244064BD2B2904200D1CE +:103B500010BD441C00B253F8200041F8040BE0B241 +:103B6000F4E700BF50280040114B30B5D3F8904027 +:103B7000240409D4D3F89040C3F89040D3F890407F +:103B800044F40044C3F890400A4C236843F4807323 +:103B900023600244084BD2B2904200D130BD441C95 +:103BA00000B251F8045B43F82050E0B2F4E700BFE4 +:103BB00000100240007000405028004007B501226C +:103BC00001A90020FFF7BEFF019803B05DF804FBD8 +:103BD00013B50446FFF7F2FFA04205D0012201A968 +:103BE00000200194FFF7C0FF02B010BD7047000035 +:103BF0007047000070470000074B45F255521A60AD +:103C000002225A6040F6FF729A604CF6CC421A606B +:103C1000024B01221A70704700300040703A0020B9 +:103C2000034B1B781BB1034B4AF6AA221A6070475C +:103C3000703A002000300040054B1A6832B902F19A +:103C4000804202F50432D2F894201A60704700BF17 +:103C50006C3A0020024B4FF40002C3F894207047E6 +:103C60000010024008B5FFF7E7FF024B1868C0F3E9 +:103C7000407008BD6C3A002070470000FEE700006D +:103C80000A4B0B480B4A90420BD30B4BDA1C121A0F +:103C9000C11E22F003028B4238BF00220021FDF733 +:103CA000C1B953F8041B40F8041BECE73C4500087D +:103CB000FC3A0020FC3A0020FC3A002000F0C0B89A +:103CC0004FF08043586A70474FF08043002258639A +:103CD0001A610222DA6070474FF080430022DA60F6 +:103CE000704700004FF0804358637047FEE70000C4 +:103CF00070B51B4B01630025044686B05860856291 +:103D00000E46FFF7FDFA04F11003C4E904334FF047 +:103D1000FF33C4E90635C4E90044A560E562FFF756 +:103D2000CFFF2B460246C4E9082304F134010D4AB3 +:103D3000256580232046FFF70BFC0123E0600A4A3B +:103D40000375009272680192B268CDE90223074BB5 +:103D50006846CDE90435FFF723FC06B070BD00BF0F +:103D6000503A0020B4440008B9440008ED3C000873 +:103D7000024AD36A1843D062704700BF2838002037 +:103D8000254B2648DA6A42F0070210B4DA62DA6A92 +:103D900022F00702DA62DA6ADA6C42F00702DA64C9 +:103DA000DA6E42F00702DA664FF09042DB6E4FF0B7 +:103DB000AA31002353604FF419249160D0604FF66C +:103DC000FD70506113625462154C1460154CC2F8BA +:103DD0000434C2F80844C2F80C34C2F8140441F2A6 +:103DE0000400C2F82034C2F82434C2F80004C2F837 +:103DF0000438C2F808184FF6FF71C2F80C38C2F840 +:103E00001418C2F82038C2F82438C2F800385DF817 +:103E1000044B00F055B800BF001002400000012420 +:103E20000400812AA69AAAAA08B500F005FAFFF7AD +:103E300067FBBDE80840FFF7FFBE000070470000C9 +:103E40000F4B9A6D42F001029A659A6F42F001029F +:103E50009A670C4A9B6F936843F0010393604FF09D +:103E600080434F229A624FF0FF32DA6200229A6159 +:103E70005A63DA605A6001225A611A60704700BFC3 +:103E800000100240002004E04FF0804208B51169A4 +:103E9000D3680B40D9B2C9439B07116107D53023C2 +:103EA00083F31188FFF752FB002383F3118808BDC9 +:103EB00008B5FFF773FABDE8084000F099B90000B3 +:103EC0005A4B4FF0FF319A6A99629A6A00229A62BD +:103ED000986AD86A60F00700D862D86A00F00700D4 +:103EE000D862D86A186B1963186B1A63186B986BD1 +:103EF0009963986B9A63986BD86BD963D86BDA63C4 +:103F0000D86B186C1964196C1A641A6C484A4FF40F +:103F1000E06111601A6E474942F001021A66D3F857 +:103F2000802022F00102C3F88020D3F880209A6D0F +:103F300042F080529A659A6F22F080529A679A6F87 +:103F40004FF440720A604A6912F48062FBD14A6001 +:103F50001A6822F0F00242F060021A601A6842F019 +:103F600001021A601A689107FCD500229A609A68CB +:103F700012F00C02FBD1D3F8901011F4407F1EBF59 +:103F80004FF48031C3F89010C3F8902061221A607A +:103F90001A689207FCD500229A609A6812F00C0FFA +:103FA000FBD169221A60D3F8942022F4706242F4A3 +:103FB000C062C3F894201A6842F480321A601A680A +:103FC0009003FCD5D3F8902022F00322C3F8902070 +:103FD000194ADA601A6842F080721A601A68910110 +:103FE000FCD5164A1A611A6842F080621A601A6893 +:103FF0001201FCD500229A600D49114AC3F88820AD +:104000000A6822F0070242F004020A600A6802F01D +:104010000702042AFAD19A6842F003029A609A6869 +:1040200002F00C020C2AFAD1704700BF00100240C7 +:10403000002002400070004013140001100C10001A +:1040400055550134074A08B5536903F0010353611C +:1040500023B1054A13680BB150689847BDE8084082 +:10406000FFF772B900040140743A0020074A08B50E +:10407000536903F00203536123B1054A93680BB1FE +:10408000D0689847BDE80840FFF75EB900040140DA +:10409000743A0020074A08B5536903F004035361DA +:1040A00023B1054A13690BB150699847BDE8084030 +:1040B000FFF74AB900040140743A0020074A08B5E6 +:1040C000536903F00803536123B1054A93690BB1A7 +:1040D000D0699847BDE80840FFF736B900040140B1 +:1040E000743A0020074A08B5536903F0100353617E +:1040F00023B1054A136A0BB1506A9847BDE80840DE +:10410000FFF722B900040140743A0020164B10B5A5 +:104110005C6904F478725A61A30604D5134A936A61 +:104120000BB1D06A9847600604D5104A136B0BB1E7 +:10413000506B9847210604D50C4A936B0BB1D06B9A +:104140009847E20504D5094A136C0BB1506C9847A7 +:10415000A30504D5054A936C0BB1D06C9847BDE814 +:104160001040FFF7F1B800BF00040140743A00208E +:10417000194B10B55C6904F47C425A61620504D5A0 +:10418000164A136D0BB1506D9847230504D5134A99 +:10419000936D0BB1D06D9847E00404D50F4A136EB0 +:1041A0000BB1506E9847A10404D50C4A936E0BB125 +:1041B000D06E9847620404D5084A136F0BB1506F54 +:1041C0009847230404D5054A936F0BB1D06F9847E5 +:1041D000BDE81040FFF7B8B800040140743A002071 +:1041E00008B5FFF751FEBDE80840FFF7ADB8000085 +:1041F000062108B50846FFF7E5F806210720FFF776 +:10420000E1F806210820FFF7DDF806210920FFF775 +:10421000D9F806210A20FFF7D5F806211720FFF765 +:10422000D1F806212820FFF7CDF8BDE80840072186 +:104230001C20FFF7C7B8000008B5FFF739FE00F0F3 +:1042400007F8FFF7FBFDBDE80840FFF737BD0000AA +:104250000023054A19460133102BC2E9001102F16F +:104260000802F8D1704700BF743A00200B4601469F +:10427000184600F02DB8000000F040B8012838BF03 +:10428000012010B50446204600F030F830B900F0A7 +:1042900007F808B900F00CF88047F4E710BD0000FB +:1042A000024B1868BFF35B8F704700BFF43A0020E1 +:1042B00008B5062000F084F80120FFF7CFFA0000CF +:1042C000024B0A4601461868FFF7EABB18110020A6 +:1042D00010B5054C13462CB10A4601460220AFF337 +:1042E000008010BD2046FCE700000000024B0146A4 +:1042F0001868FFF7D9BB00BF18110020024B014618 +:104300001868FFF7D5BB00BF1811002010B50139A0 +:104310000244904201D1002005E0037811F8014FDA +:10432000A34201D0181B10BD0130F2E72DE9F04186 +:10433000A3B1C91A17780144044603F1FF3C8C422B +:10434000204601D9002009E00578BD4204F10104AE +:10435000F5D10CEB0405D618A54201D1BDE8F081DA +:1043600015F8018D16F801EDF045F5D0E7E70000EE +:104370001F2938B504460D4604D9162303604FF0B3 +:10438000FF3038BD426C12B152F821304BB9204693 +:1043900000F030F82A4601462046BDE8384000F0DB +:1043A00017B8012B0AD0591C03D116230360012032 +:1043B000E7E7002442F82540284698470020E0E738 +:1043C000024B01461868FFF7D3BF00BF1811002049 +:1043D00038B5074D00230446084611462B60FFF709 +:1043E00041FA431C02D12B6803B1236038BD00BFE2 +:1043F000F83A0020FFF730BA034611F8012B03F812 +:10440000012B002AF9D17047696E2E7369657272AB +:10441000616165726F73706163652E547275654E6C +:10442000617649430000000040A2E4F1646891060F +:104430000041A3E5F2656992070000004261642033 +:1044400043414E496661636520696E6465782E005C +:1044500080000000008000000000800000000000DC +:10446000000000001518000835200008911F000802 +:104470005518000861180008611A0008251800087E +:104480003518000829180008311800082D180008F0 +:104490008519000839180008052300084918000884 +:1044A0005919000863300000A44400088038002037 +:1044B000503A00206D61696E0069646C650000000F +:1044C000B6140000000000000060030000000000BF +:1044D000FE2A0100D20400001C1100200000000090 +:1044E00000000000000000000000000000000000CC :1044F00000000000000000000000000000000000BC :1045000000000000000000000000000000000000AB :10451000000000000000000000000000000000009B :10452000000000000000000000000000000000008B -:10453000000000000000000000000000000000007B -:044540000000000077 +:0C4530000000000000000000000000007F :00000001FF diff --git a/Tools/bootloaders/Sierra-TrueNavPro-G4_bl.bin b/Tools/bootloaders/Sierra-TrueNavPro-G4_bl.bin index 628100d66be528..9efbd78c54b007 100755 Binary files a/Tools/bootloaders/Sierra-TrueNavPro-G4_bl.bin and b/Tools/bootloaders/Sierra-TrueNavPro-G4_bl.bin differ diff --git a/Tools/bootloaders/Sierra-TrueNavPro-G4_bl.hex b/Tools/bootloaders/Sierra-TrueNavPro-G4_bl.hex index a252f716cf17ca..1fc93056ac280e 100644 --- a/Tools/bootloaders/Sierra-TrueNavPro-G4_bl.hex +++ b/Tools/bootloaders/Sierra-TrueNavPro-G4_bl.hex @@ -1,19 +1,19 @@ :020000040800F2 -:1000000000070020F1010008852500083D250008B3 -:10001000652500083D2500085D250008F30100085E -:10002000F3010008F3010008F3010008653500083A +:1000000000070020F1010008E125000899250008FB +:10001000C125000899250008B9250008F30100084A +:10002000F3010008F3010008F3010008C1350008DE :10003000F3010008F3010008F3010008F3010008D0 :10004000F3010008F3010008F3010008F3010008C0 -:10005000F3010008F301000899420008C1420008BA -:10006000E94200081143000839430008F301000881 +:10005000F3010008F3010008B5380008DD38000896 +:10006000053900082D39000855390008F30100084A :10007000F3010008F3010008F3010008F301000890 :10008000F3010008F3010008F3010008F301000880 -:10009000F30100081D2500082D2500086143000814 +:10009000F301000879250008892500087D3900084A :1000A000F3010008F3010008F3010008F301000860 -:1000B00035440008F3010008F3010008F3010008CB +:1000B000513A0008F3010008F3010008F3010008B9 :1000C000F3010008F3010008F3010008F301000840 :1000D000F3010008F3010008F3010008F301000830 -:1000E000C5430008F3010008F3010008F30100080C +:1000E000E1390008F3010008F3010008F3010008FA :1000F000F3010008F3010008F3010008F301000810 :10010000F3010008F3010008F3010008F3010008FF :10011000F3010008F3010008F3010008F3010008EF @@ -36,97 +36,97 @@ :100220004F8FBFF36F8F40F20000C0F2F0004EF628 :100230008851CEF200010860BFF34F8FBFF36F8F7C :100240004FF00000E1EE100A4EF63C71CEF20001D4 -:100250000860062080F31488BFF36F8F03F04CFE14 -:1002600003F0DEFE4FF055301F491B4A91423CBF60 +:100250000860062080F31488BFF36F8F04F092F8D3 +:1002600004F072F94FF055301F491B4A91423CBFD0 :1002700041F8040BFAE71D49184A91423CBF41F886 :10028000040BFAE71A491B4A1B4B9A423EBF51F82E :10029000040B42F8040BF8E700201849184A914271 -:1002A0003CBF41F8040BFAE703F02AFE03F0FEFE20 +:1002A0003CBF41F8040BFAE704F070F804F092F94F :1002B000144C154DAC4203DA54F8041B8847F9E797 :1002C00000F042F8114C124DAC4203DA54F8041B12 -:1002D0008847F9E703F012BE000700200023002042 +:1002D0008847F9E704F058B8000700200023002001 :1002E0000000000808ED00E00001002000070020E9 -:1002F000E8460008002300207C2300208023002003 -:100300001C510020E0010008E4010008E40100089D +:1002F0007048000800230020A4230020A823002029 +:1003000044510020E0010008E4010008E401000875 :10031000E40100082DE9F04F2DED108AC1F80CD052 :10032000C3689D46BDEC108ABDE8F08F002383F3BF -:1003300011882846A047002003F084FAFEE703F066 -:100340000DFA00DFFEE70000F8B500F01BFE03F039 -:1003500075FD074603F0C6FD0546D0BB294B9F42FD -:1003600037D001339F4237D0274B27F0FF029A4204 -:1003700035D1F8B200F03EFC2E4642F2107400F087 -:100380003FFC08B10024264601F0B4F858B303201E +:1003300011882846A047002003F0C8FCFEE703F020 +:1003400051FC00DFFEE70000F8B500F01BFE03F0F3 +:10035000BBFF074604F00CF80546C0BB294B9F4283 +:1003600035D001339F4235D0274B27F0FF029A4208 +:1003700033D1F8B200F03EFC2E4642F2107400F089 +:100380003FFC08B10024264601F0B2F848B3032030 :1003900000F03EF80024264635B11C4B9F4203D0A6 -:1003A00003F098FD00242646002003F051FD0EB115 -:1003B00000F044F800F056FC00F0E6FD02F0EAF828 -:1003C0000546B4B900F096FC4FF47A7003F040FA99 -:1003D000F7E72E460024D2E704460126CFE706467B -:1003E00040F6C414CBE7002CD6D04FF47A74012623 -:1003F000D2E702F0CFF8431BA342E3D900F01EF886 -:10040000DCE700BF010007B0000008B0263A09B0E1 +:1003A00003F0DEFF00242646002003F097FF0EB185 +:1003B00000F044F800F056FC02F01AF90546C4B902 +:1003C00000F098FC4FF47A7003F086FCF7E72E46B5 +:1003D0000024D4E704460126D1E7064640F6C414BB +:1003E000CDE740F6C4139C4204BF4FF47A74012653 +:1003F000D2E702F0FDF8431BA342E1D900F01EF85A +:10040000DAE700BF010007B0000008B0263A09B0E3 :10041000084B187003280CD8DFE800F00805020824 -:10042000022000F00DBE022000F002BE024B0022AE -:100430005A607047802300208423002010B501F00B -:1004400059F830B1234B03221A70234B00225A6013 +:10042000022000F00BBE022000F000BE024B0022B2 +:100430005A607047A8230020AC23002010B501F0BB +:1004400057F830B1234B03221A70234B00225A6015 :1004500010BD224B224A1C4619680131F8D00433E2 :100460009342F9D16268A242F2D31E4B9B6803F11A -:10047000006303F510439A42EAD203F0FDFC03F057 -:100480000FFD002000F09AFD0220FFF7C1FF164B80 +:10047000006303F510439A42EAD203F043FF03F00E +:1004800055FF002000F098FD0220FFF7C1FF164B3A :100490009A6D00229A65996F9A67996FD96DDA659E :1004A000D96FDA67D96F196E1A66D3F88010C3F85E :1004B0008020D3F8803072B64FF0E0233021C3F8AB :1004C000084DD4E9003281F311889D4683F30888F2 -:1004D0001047BDE7802300208423002000900008FF +:1004D0001047BDE7A8230020AC23002000900008AF :1004E000209000080023002000100240094A1368F1 :1004F00049F2690099B21B0C00FB01331360064BF3 :10050000186844F2506182B2000C01FB02001860CE :1005100080B27047142300201023002010B5002162 -:100520001022044600F0A6FD034B03CB206061605F +:100520001022044600F0A4FD034B03CB2060616061 :100530001868A06010BD00BF9075FF1F2DE9F04145 :10054000ADF5507D0DF13C086EAC40F275120746DA -:100550000D4610A80021C8F8001000F08BFD4FF4E4 -:10056000C4720021204600F085FD02F013F8254BEF +:100550000D4610A80021C8F8001000F089FD4FF4E6 +:10056000C4720021204600F083FD02F041F8254BC3 :100570004FF47A72B0FBF2F0186093E807000223A0 :1005800084E807000DF5ED702382FFF7C7FF4BF2FB -:1005900014531D49238406A803F0E2FF202384F8A6 +:1005900014531D49238406A804F084F8202384F80A :1005A00032310DF2EB2606AB0DF1380C1A4603CAB8 :1005B000624530607160134606F10806F6D1414687 -:1005C0000122204600F0A2FD00230393AB7E02939C +:1005C0000122204600F0A0FD00230393AB7E02939E :1005D00005F11903019380B20123CDE90480009352 -:1005E000E97E06A3D3E90023384602F091FB0DF51E +:1005E000E97E06A3D3E90023384602F0BFFB0DF5F0 :1005F000507DBDE8F08100BFAFF300809E6AC4214A -:10060000818A46EE8C230020704500082DE9F041D8 +:10060000818A46EEB4230020B44600082DE9F0416B :100610002C4C237ADAB080460D465BBB27A92846CE -:1006200000F084FE0746002842D19DF89D60C82E48 -:100630003ED801464FF4A662204600F01BFD4FF461 +:1006200000F082FE0746002842D19DF89D60C82E4A +:100630003ED801464FF4A662204600F019FD4FF463 :100640008073C4F8F8314FF40073C4F80C334FF4DE :100650004073C4F8203432460DF19E0104F10900C4 -:1006600000F0F6FC26449DF89C30777223720BB99B -:10067000EB7E23728122002106AC27A800F0FAFC51 -:100680000122214627A800F08DFE00230393AB7EB4 +:1006600000F0F4FC26449DF89C30777223720BB99D +:10067000EB7E23728122002106AC27A800F0F8FC53 +:100680000122214627A800F08BFE00230393AB7EB6 :10069000029305F1190380B201932823CDE90440A8 -:1006A0000093E97E05A3D3E90023404602F030FB26 +:1006A0000093E97E05A3D3E90023404602F05EFBF8 :1006B0005AB0BDE8F08100BFAFF3008026417272EE -:1006C000DF25D7B798480020F0B5254E4FF48A753E +:1006C000DF25D7B7C0480020F0B5254E4FF48A7516 :1006D00005FB0065F1B096F8D83085F8DC300024D1 -:1006E000D822214685F8E8403AA800F0C3FC06F17C -:1006F000090000F0B7FCD5F8E4308DF8F000C2B284 +:1006E000D822214685F8E8403AA800F0C1FC06F17E +:1006F000090000F0B5FCD5F8E4308DF8F000C2B286 :1007000006AF06F109010DF1F100CDE93A3400F030 -:100710009FFC394601223AA800F070FE80B2CDE974 +:100710009DFC394601223AA800F06EFE80B2CDE978 :10072000047008230127CDE9023706F1D8030193AD :1007300030230093317A0B4807A3D3E9002302F05A -:10074000E7FAA04206DD01F025FFC5F8E0003846D3 +:1007400015FBA04206DD01F053FFC5F8E000384676 :1007500071B0F0BD2046FBE778F6339F93CACD8D8C -:1007600098480020A43300202DE9F0411D4D1E4E75 -:100770001E4F86B0284602F0F7FA034658B300240D +:10076000C0480020CC3300202DE9F0411D4D1E4E25 +:100770001E4F86B0284602F025FB034658B30024DE :10078000CDE90344ADF81440027B8DF8142099683C :100790004068029403AA03C21B68DFF8548043F048 -:1007A0000043029301F0F8FE821941F10003009426 -:1007B00002A9384601F0B2F8A04205DD284602F051 -:1007C000D7FA88F80040D5E798F80030072B05D80D +:1007A0000043029301F026FF821941F100030094F7 +:1007B00002A9384601F0B0F8A04205DD284602F053 +:1007C00005FB88F80040D5E798F80030072B05D8DE :1007D000013388F8003006B0BDE8F081014802F02E -:1007E000C7FAF8E7A433002040420F00D8330020B6 -:1007F000CD4D002070B50D4614461E4602F0E4F9BA +:1007E000F5FAF8E7CC33002040420F000034002037 +:1007F000F54D002070B50D4614461E4602F012FA63 :1008000050B9022E10D1012C0ED112A3D3E900232E :10081000C5E90023012007E0282C10D005D8012CC1 :1008200009D0052C0FD0002070BD302CFBD10BA3BC @@ -135,24 +135,24 @@ :10085000AFF30080401DA12026812A0B78F6339F3C :1008600093CACD8D9E6AC421818A46EE264172725A :10087000DF25D7B7F017304A39059E5638B50546FB -:100880000E4C0021013500F0BBFBA4F82C55B4F848 -:100890002C0500F09DFB78B1B4F82C0500F0A8FB06 -:1008A000014648B9B4F82C0500F0AAFBB4F82C3581 -:1008B0000133A4F82C35EAE738BD00BF9848002082 +:100880000E4C0021013500F0B9FBA4F82C55B4F84A +:100890002C0500F09BFB78B1B4F82C0500F0A6FB0A +:1008A000014648B9B4F82C0500F0A8FBB4F82C3583 +:1008B0000133A4F82C35EAE738BD00BFC04800205A :1008C00010B50A4B0A4A1A6003F5805393F8482082 -:1008D0003AB95C6C2CB1204600F08AFE204603F049 -:1008E000F5FDBDE81040034800F082BED83300207B -:1008F000C4450008084400202DE9F04F8FB000AF38 -:1009000005460C4602F060F9002849D1237E022BEF -:100910001BD1E38A012B18D101F03CFE0646FFF7FC +:1008D0003AB95C6C2CB1204600F088FE204603F04B +:1008E00097FEBDE81040034800F080BE00340020B1 +:1008F00008470008304400202DE9F04F8FB000AFCA +:1009000005460C4602F08EF9002849D1237E022BC1 +:100910001BD1E38A012B18D101F06AFE0646FFF7CE :10092000E5FD03464FF4C870DFF8C482B3FBF0F274 :1009300006F5167602FB103316FA83F3C8F800307A :10094000E37E33B9A34B00221A703C37BD46BDE8A5 -:10095000F08F07F12401204600F0A6FC0028F4D116 +:10095000F08F07F12401204600F0A4FC0028F4D118 :1009600007F11400FFF7DAFD97F8264007F11401AC -:10097000224607F1270003F0C1FD0028E2D10F2C29 +:10097000224607F1270003F063FE0028E2D10F2C86 :1009800008D8944B1C70D8F80030A3F51673C8F83B -:100990000030DAE797F82410284602F00DF9D4E782 +:100990000030DAE797F82410284602F03BF9D4E754 :1009A000E38A282B2BD010D8012B23D0052BCCD1B8 :1009B000BFF34F8F8849894BCA6802F4E062134342 :1009C000CB60BFF34F8F00BFFDE7302BBDD1844E0E @@ -161,26 +161,26 @@ :1009F000F5D1AAE721462846FFF7A0FDA5E7214645 :100A00002846FFF703FEA0E7B2F8EC507B6005F143 :100A100003094FEA99094FEA8902D11DC908A8EBD9 -:100A2000C1039D46EB460021584600F023FB04F12C -:100A3000EE012A463144584600F00AFB7B6813B9A0 -:100A4000012000F0BBFA96F8D20000F0C1FA04468B -:100A500030B9307200F0DCFA204600F0AFFAB1E0B5 +:100A2000C1039D46EB460021584600F021FB04F12E +:100A3000EE012A463144584600F008FB7B6813B9A2 +:100A4000012000F0B9FA96F8D20000F0BFFA04468F +:100A500030B9307200F0DAFA204600F0ADFAB1E0B9 :100A6000D6F8D4203AB996F8D200B6F82C258242AE :100A700001D8FFF703FFD6F8D4202A44944208D2C5 :100A800096F8D200B6F82C250130824201D8FFF743 -:100A9000F5FE70685FFA89F2594600F0F3FA08B97A +:100A9000F5FE70685FFA89F2594600F0F1FA08B97C :100AA000C54679E0726896F8D2002A447260D6F89A -:100AB000D42005EB0209C6F8D49000F089FA8145EC +:100AB000D42005EB0209C6F8D49000F087FA8145EE :100AC00009D396F8D220D6F8D4000132001B86F85C :100AD000D220C6F8D400FF2D0FD80024347200F0C5 -:100AE00097FA204600F06AFA00F004FD3D4B1881A9 +:100AE00095FA204600F068FA00F002FD3D4B1881AF :100AF00008B9FFF7A3FCC54627E7BB6896F8D900FD :100B00000AFB0362FB68D2F8E41082F8E83001F5D2 :100B10008061C2F8E030C2F8E410FFF7D5FDFFF7BE :100B200023FE96F8D920013202F0030286F8D9207C :100B3000B6E74FF48A7A0AFB02F505F1EA0131447F -:100B4000204600F087FCF86000287FF4FEAE3544B4 -:100B5000012285F8E82001F01DFDD5F8E020D6ED52 +:100B4000204600F085FCF86000287FF4FEAE3544B6 +:100B5000012285F8E82001F04BFDD5F8E020D6ED24 :100B6000007ADFED216A801A192838BF192040F673 :100B7000B832904228BF1046B8EE677A07EE900A66 :100B8000F8EEE77A67EEA67ADFED186AE7EE267AE6 @@ -188,958 +188,985 @@ :100BA00073680AFB02F4321992F8E81059B1D2F8CE :100BB000E4108B42E8463FF427AF002182F8E810AA :100BC000C2F8E010C5467368064A9B0A01331381D8 -:100BD000BBE600BF9D33002000ED00E00400FA05F5 -:100BE000984800208C230020CDCCCC3D6666663F23 -:100BF000A0330020014B1870704700BF98230020DD +:100BD000BBE600BFC533002000ED00E00400FA05CD +:100BE000C0480020B4230020CDCCCC3D6666663FD3 +:100BF000C8330020014B1870704700BFC02300208D :100C000038B54FF00054134B22689A4220D1124B52 :100C1000627D12481A70237D03724FF48073C0F80E :100C2000F8314FF40073C0F80C3300254FF44073D3 :100C3000C0F820340A49C0F8E450C922093000F055 -:100C400007FAE0222946204600F014FA012038BDB8 -:100C50000020FCE79AAD44C5982300209848002066 -:100C60001600002037B500F045FC194D19492881C0 -:100C700002236B7100220123174801F07BF8002347 +:100C400005FAE0222946204600F012FA012038BDBC +:100C50000020FCE79AAD44C5C0230020C048002016 +:100C60001600002037B500F043FC194D19492881C2 +:100C700002236B7100220123174801F097F800232B :100C80000193164B164900931648174B4FF48052A8 -:100C900001F06AFF154B197811B1124801F08CFF71 -:100CA00001F078FC0446FFF721FC4FF4C873B0FB59 +:100C900001F098FF154B197811B1124801F0BAFF15 +:100CA00001F0A6FC0446FFF721FC4FF4C873B0FB2B :100CB000F3F202FB130304F5167010FA83F00C4BE9 -:100CC000186003F00FF908B10F232B8103B030BD7A -:100CD0008C23002040420F00D8330020F507000885 -:100CE0009C230020A4330020F9080008982300204A -:100CF000A03300202DE9F04F2DED028B90A7D7E90E +:100CC000186003F055FB08B10F232B8103B030BD32 +:100CD000B423002040420F0000340020F507000834 +:100CE000C4230020CC330020F9080008C0230020D2 +:100CF000C83300202DE9F04F2DED028B90A7D7E9E6 :100D000000670FF24429D9E90089884C95B00DADF0 :100D10009FED848BFFF728FDDFF834B200230C939E :100D2000ADF83C300D936B6000230DF125028DED85 :100D3000008B4FF0010A09A958468DF825308DF82F -:100D400024A001F08FFB9DF824200023002A40F00E -:100D5000AF80204601F038FF0546002847D1DFF874 -:100D6000F4B101F017FCDBF8003098423FD301F0FA -:100D700011FC0790FFF7BAFB079A4FF4C873B0FB5A +:100D400024A001F0BDFB9DF824200023002A40F0E0 +:100D5000AF80204601F066FF0546002847D1DFF846 +:100D6000F4B101F045FCDBF8003098423FD301F0CC +:100D70003FFC0790FFF7BAFB079A4FF4C873B0FB2C :100D8000F3F101FB130302F5167010FA83F0CBF8B0 :100D90000000DFF8C4B19BF800100791002914BFD0 :100DA0002B46534610A88DF83030FFF7B7FB079954 :100DB000C1F11002D2B2062A10AB28BF0622194494 -:100DC0000DF13100079200F043F9079A0CAB039341 +:100DC0000DF13100079200F041F9079A0CAB039343 :100DD000182302930132564BD2B2CDE900A30492FC -:100DE0003B463246204601F035FF8BF8005001F0BB -:100DF000D1FB504A504D1368C31AB3F57A7F32D3F2 -:100E0000106001F0C9FB02460B46204601F0BAFF14 -:100E1000204601F0D9FE30B32B7ADFF840A1002B39 -:100E200014BF032302238AF8053001F0B3FB0DF150 +:100DE0003B463246204601F063FF8BF8005001F08D +:100DF000FFFB504A504D1368C31AB3F57A7F32D3C4 +:100E0000106001F0F7FB02460B46204601F0E8FFB8 +:100E1000204601F007FF30B32B7ADFF840A1002B0A +:100E200014BF032302238AF8053001F0E1FB0DF122 :100E3000400B4FF47A730122B0FBF3F05946CAF825 -:100E40000000504600F008FA182302933B4B019330 +:100E40000000504600F006FA182302933B4B019332 :100E500080B240F25513CDE903B0009342464B46B1 -:100E6000204601F0F7FE2B7AB3B101F093FB4FF06F +:100E6000204601F025FF2B7AB3B101F0C1FB4FF012 :100E7000000A83464FF48A7295F8D900504400F076 :100E8000030002FB005393F8E810002934D00AF164 -:100E9000010ABAF1040FEFD1C82002F0D9FC2B7A75 +:100E9000010ABAF1040FEFD1C82002F01DFF2B7A2E :100EA000002B7FF434AF15B0BDEC028BBDE8F08FA2 :100EB0004FF0904110A84A6982F010024A61194629 -:100EC000102200F0D7F80DF126030AAA0CA9584603 -:100ED00000F018FE95E8030011AB83E803009DF8CD +:100EC000102200F0D5F80DF126030AAA0CA9584605 +:100ED00000F016FE95E8030011AB83E803009DF8CF :100EE0003C308DF84C300C9B109310A9DDE90A239F -:100EF000204602F01BF917E7D3F8E01049B12B6840 +:100EF000204602F049F917E7D3F8E01049B12B6812 :100F0000FA2B38BFFA23ABEB01010533B1EB430FEA :100F1000BDD3FFF7D9FB4FF48A720028B7D1BBE7E6 -:100F2000AFF300800000000000000000A4330020A8 -:100F30009C330020C84D002098480020CC4D002054 +:100F2000AFF300800000000000000000CC33002080 +:100F3000C4330020F04D0020C0480020F44D0020B4 :100F4000401DA12026812A0BF1C6A7C1D068080F39 -:100F5000D8330020A03300209D3300208C230020B4 -:100F600008B5054800F074FEBDE80840034A04498E -:100F7000002003F0A5BA00BFD8330020084E00209F -:100F8000C10800087047000070B502F0FDFD094E71 -:100F9000094D3080002428683388834208D902F044 -:100FA000EFFD2B6804440133B4F5104F2B60F2D3EE -:100FB00070BD00BFFC4D0020D04D002002F096BE59 -:100FC00000F10060920000F5104002F019BE000030 -:100FD000054B1A68054B1B889B1A834202D91044A3 -:100FE00002F0CEBD00207047D04D0020FC4D002007 -:100FF000024B1B68184402F0C9BD00BFD04D002051 -:10100000024B1B68184402F0D3BD00BFD04D002036 -:10101000064991F8243033B10023086A81F824305E -:101020000822FFF7CDBF0120704700BFD44D00203C -:10103000022802BF4FF0904310229A6170470000CF -:10104000022802BF4FF090434FF480129A6170471C -:1010500010B50023934203D0CC5CC4540133F9E7AC -:1010600010BD000003460246D01A12F9011B0029E8 -:10107000FAD1704702440346934202D003F8011BA1 -:10108000FAE770472DE9F8431F4D144695F82420E0 -:101090000746884652BBDFF870909CB395F8243021 -:1010A0002BB92022FF2148462F62FFF7E3FF95F876 -:1010B0002400C0F10802A24228BF2246D6B241460F -:1010C000920005EB8000FFF7C3FF95F82430A41BC6 -:1010D0001E44F6B2082E17449044E4B285F824600A -:1010E000DBD1FFF795FF0028D7D108E02B6A03EB8F -:1010F00082038342CFD0FFF78BFF0028CBD10020A3 -:10110000BDE8F8830120FBE7D44D00202DE9F0472E -:101110000D46044600219046284640F27912FFF71A -:10112000A9FF234620220021284601F0A1FF231D0C -:1011300002222021284601F09BFF631D0322222169 -:10114000284601F095FFA31D03222521284601F022 -:101150008FFF04F1080310222821284601F088FFA0 -:1011600004F1100308223821284601F081FF04F120 -:10117000110308224021284601F07AFF04F11203EE -:1011800008224821284601F073FF04F114032022AD -:101190005021284601F06CFF04F118034022702111 -:1011A000284601F065FF04F120030822B0212846FB -:1011B00001F05EFF04F121030822B821284601F066 -:1011C00057FF04F12207C0263B4631460822284635 -:1011D000083601F04DFFB6F5A07F07F10107F3D106 -:1011E00004F1320308223146284601F041FF00276E -:1011F00004F1330A94F832304FEAC7099F4209F5E7 -:10120000A47615D3B8F1000F08D1314604F59973CF -:101210000722284601F02CFF09F24F16274694F8C2 -:1012200032213B1B93420CD3F01DC008BDE8F08770 -:101230000AEB070308223146284601F019FF01375F -:10124000D8E707F2331331460822284601F010FF91 -:1012500008360137E3E7000013B5044608460021CD -:1012600001602346C0F803102022019001F000FF26 -:101270000198231D0222202101F0FAFE0198631D2E -:101280000322222101F0F4FE0198A31D032225214F -:1012900001F0EEFE019804F108031022282101F06C -:1012A000E7FE072002B010BDF7B50023047F0091D0 -:1012B0000E4607221946054601F09EFD731C009359 -:1012C000012200230721284601F096FDC4B9B31C72 -:1012D0000093052223460821284601F08DFD0D24A8 -:1012E0003746B278BB1B934211D32B7FA88A0734B1 -:1012F000E408BBB9844294BF0020012003B0F0BDD4 -:10130000AB8ADB00083BDB08B3700824E8E7FB1C72 -:101310000093214600230822284601F06DFD083481 -:101320000137DEE7201A18BF0120E7E7F7B50023F1 -:10133000047F00910E4608221946054601F05CFD27 -:10134000731CC4B90822009311462346284601F0B5 -:1013500053FD1024012372785F1C013B934211D38B -:101360002B7FA88A0734E408BBB9844294BF0020CD -:10137000012003B0F0BDAB8ADB00083BDB087370D3 -:101380000824E7E7F31900932146002308222846A2 -:1013900001F032FD08343B46DDE7201A18BF01207A -:1013A000E7E70000F8B50E46054614460021812205 -:1013B0003046FFF75FFE2B4608220021304601F041 -:1013C00057FE7CB96B1C07220821304601F050FE05 -:1013D0000F2401236A785F1C013B934204D3E01D74 -:1013E000C008F8BD0824F4E7EB192146082230466E -:1013F00001F03EFE08343B46ECE70000F8B50E462F -:10140000054614460021CE223046FFF733FE2B4618 -:1014100028220021304601F02BFE7CB905F108039B -:1014200008222821304601F023FE30242F462A7A54 -:101430007B1B934204D3E01DC008F8BD2824F5E7C8 -:1014400007F1090321460822304601F011FE083455 -:101450000137ECE7F7B5047F00910E460123102217 -:101460000021054601F0C8FCC4B9B31C0093092251 -:1014700023461021284601F0BFFC19243746728804 -:10148000BB1B9A4211D82B7FA88A0734E408BBB94A -:10149000844294BF0020012003B0F0BDAB8ADB0082 -:1014A000103BDB0873801024E8E73B1D00932146C6 -:1014B00000230822284601F09FFC08340137DEE7AC -:1014C000201A18BF0120E7E730B5094D0A449142C0 -:1014D0000DD011F8013B5840082340F30004013BB4 -:1014E0002C4013F0FF0384EA5000F6D1EFE730BD43 -:1014F0002083B8EDF7B5384A106851686B4603C3CE -:101500006A4636493648082303F008F8044600289E -:1015100033D10A25334A106851686B4603C36A46C3 -:1015200031492F48082302F0F9FF0446002849D02A -:101530000369B3F55C3F45D8B0F8661041F2B54297 -:1015400091423FD1294A024402F15C018B4239D3D6 -:101550005C3B234900209E1AFFF7B6FF3246074640 -:1015600004F164010020FFF7AFFFA3689F4229D177 -:10157000E368984208BF002524E00369B3F55C3FA7 -:1015800027D8418B41F2B542914220D1174A0244FB -:1015900002F110018B4218D3103B114900209D1A13 -:1015A000FFF792FF2A46064604F118010020FFF7D4 -:1015B0008BFFA3689E4202D1E368984201D00D25BB -:1015C000A8E70025284603B0F0BD1025A2E70C25AA -:1015D000A0E70B259EE700BF94450008DC6F0300E1 -:1015E000009000089D450008906F03000870FFF709 -:1015F00010B5037C044613B9006802F077FF20465B -:1016000010BD00000023BFF35B8FC360BFF35B8F8F -:10161000BFF35B8F8360BFF35B8F7047BFF35B8F5C -:101620000068BFF35B8F704770B505460C30FFF75D -:10163000F5FF05F1080604463046FFF7EFFFA0422C -:1016400006D930466D68FFF7E9FF2544281A70BDBA -:101650003046FFF7E3FF201AF9E7000070B50546B2 -:10166000406898B105F10800FFF7D8FF05F10C06B6 -:1016700004463046FFF7D2FF8442304694BF6D687F -:101680000025FFF7CBFF013C2C44201A70BD000061 -:1016900038B50C460546FFF7C7FFA04210D305F149 -:1016A0000800FFF7BBFF04446868B4FBF0F100FBDF -:1016B0001144BFF35B8F0120AC60BFF35B8F38BD7B -:1016C0000020FCE72DE9F041144607460D46FFF7E0 -:1016D000C5FF844228BF0446D4B1B84658F80C6B05 -:1016E0004046FFF79BFF3044286040467E68FFF786 -:1016F00095FF331A9C4203D86C600120BDE8F0814D -:101700006B60A41B3B68AB602044E8600220F5E7F7 -:101710002046F3E738B50C460546FFF79FFFA04289 -:1017200010D305F10C00FFF779FF04446868B4FB9F -:10173000F0F100FB1144BFF35B8F0120EC60BFF3BD -:101740005B8F38BD0020FCE72DE9FF4188466946E4 -:101750000746FFF7B7FF6C4606B204EBC606002546 -:10176000B44209D06268206808EB0501FFF770FCFD -:10177000636808341D44F3E729463846FFF7CAFF7B -:10178000284604B0BDE8F081F8B505460C300F4698 -:10179000FFF744FF05F1080604463046FFF73EFF19 -:1017A000A042304688BF6C68FFF738FF201A3860C7 -:1017B00020B130462C68FFF731FF2044F8BD00000F -:1017C00073B5144606460D46FFF72EFF844228BF28 -:1017D00004460190DCB101A93046FFF7D5FF019B1B -:1017E00033B93268C5E90233C5E9002401200CE0B1 -:1017F0009C4238BF01942860019868608442F5D902 -:101800003368AB60241AEC60022002B070BD204641 -:10181000FBE700002DE9FF410F466946FFF7D0FFC7 -:101820006C4600B204EBC0050026AC4209D0D4F8E7 -:10183000048054F8081BB8194246FFF709FC4644D7 -:10184000F3E7304604B0BDE8F081000038B5054646 -:10185000FFF7E0FF044601462846FFF719FF204640 -:1018600038BD00007047000010B4134602681468C9 -:101870000022A4465DF8044B6047000000F580504C -:1018800090F859047047000000F5805090F8520419 -:101890007047000000F5805090F958047047000030 -:1018A00050207047302383F3118800F58052D2F81E -:1018B0009C34D2F898041844D2F894341844D2F8DE -:1018C0007C341844D2F88C341844D2F88834184444 -:1018D000002383F31188704700F58050C0F854143A -:1018E0000120704738B5C26A936923F00103936100 -:1018F000044600F04FFE0546E36A9B69DB0706D508 -:1019000000F048FE431BFA2BF6D9002004E004F552 -:101910008054012084F8520438BD00002DE9F04FB6 -:101920000C4600F5805185B01F4691F85234BDF841 -:101930003890054690469BB1D1F878340133C1F810 -:1019400078342368980006D4237B082B0BD9627B5C -:101950000AB10F2B07D9D1F87C340133C1F87C349C -:101960004FF0FF3010E0302383F31188EB6AD3F897 -:10197000C42012F4001B0AD0D1F880340133C1F81E -:101980008034002080F3118805B0BDE8F08FD3F8D3 -:10199000C4302068C3F3014A6B6A4822002812FB56 -:1019A0000A33B4BF40F080408004186022685200BF -:1019B00044BF40F000501860207B4FEA0A6242EAC0 -:1019C00000425A60607B4FEA4A1610B342F440125C -:1019D0005A60D1F8B0240132C1F8B024AA1902F536 -:1019E0008352117B41F020011173207B039300F09F -:1019F0002DFE039B033080105FFA8BF282420BF1C5 -:101A0000010B0DDA04EB820103EB8202496891605D -:101A1000F2E7AA1902F58352117B60F34511E3E75F -:101A2000EB6A012202FA0AF2C3F8CC2005EB4A1154 -:101A3000AB1903F5825301F58251C3E904871831CC -:101A4000234604F10C0253F8040B41F8040B9342B3 -:101A5000F9D11B880B802E4441F2680346F803A09D -:101A600006F5805609F0030396F86C2043F0100346 -:101A700022F01F02134386F86C30002383F3118891 -:101A8000CDF8009042463B462146284600F0A4FD92 -:101A9000012079E713B500F580540191606CFFF7E0 -:101AA000DDFD1F280AD90199606C2022FFF74CFE4A -:101AB000A0F120035842584102B010BD0020FBE7BE -:101AC00008B5302383F3118800F58050406CFFF790 -:101AD00099FD002383F3118808BD000000220260F5 -:101AE000828142608260704710B500220023C0E905 -:101AF00000230023044603810C30FFF7EFFF20464C -:101B000010BD00002DE9F0479A4688B00746884688 -:101B10009146302383F3118807F580546846FFF718 -:101B2000E3FF606CFFF780FD1F282DD9606C202239 -:101B30006946FFF78BFE202826D194F852341BB358 -:101B400003AD444605AB2E4603CE9E422060616045 -:101B5000354604F10804F6D130682060B388A380CC -:101B6000DDE90023C9E90023BDF80830AAF80030F8 -:101B7000002383F3118853464A464146384608B04D -:101B8000BDE8F04700F016BD002080F3118808B0D2 -:101B9000BDE8F0872DE9F84F00230646C0E9013380 -:101BA000284B46F8303B00F58154054688463746B9 -:101BB000103438462037FFF797FFA742F9D105F5D3 -:101BC00080544FF4805326630026C4E90D366764C1 -:101BD000012305F5835705F5A359E66384F84030E2 -:101BE00084F84830103709F110094FF0000A4FF01F -:101BF000000B47E908ABA7F11800FFF76FFF20378C -:101C000047F8286C4F45F4D184F85884A4F85A64F6 -:101C1000A4F85C64A4F85E6484F86064A4F8626468 -:101C2000A4F86464A4F8666484F86864B8F1000FEA -:101C300002D0054800F0A8FC044BEB622846BDE842 -:101C4000F88F00BFC4450008A845000800640040A4 -:101C500010B5044B197804464A1C1A70FFF79AFF16 -:101C6000204610BD054E00202DE9F04300295FD02D -:101C70003048314BB3FBF1F381428CBF0A20112075 -:101C8000451EB3FBF0F700FB1730ECB220B1022D7C -:101C90002846F5D8002037E07D1EB5F5806F33D299 -:101CA000C4EBC40808F103034FEAE30EC3F3C70310 -:101CB000A4EB030C0EF101094FF47A705FFA8CF675 -:101CC0000EFB000E59FA8CFCBEFBFCFCBCF5617FE0 -:101CD0001CDC1FFA8CF4581C56FA80F04743164857 -:101CE000B0FBF7F7B942D5D1013BDBB20F2BD1D80E -:101CF000711EC9B207294FF0000005D81071148079 -:101D00005580537191710120BDE8F08308F1FF33D4 -:101D10004FEAE30CC3F3C703E41A0CF1010EE6B279 -:101D20000CFB00005EFA84F4B0FBF4F4A4B2D2E73A -:101D30000846E9E73F420F000024F4000B4B10B5C2 -:101D40004FF45472044600211846FFF793F9084BEC -:101D5000A3614033E361D8332362F0336362E36A03 -:101D600060610022C3F8C02010BD00BF00A4004085 -:101D700070A400402DE9F04F00F58055984695F885 -:101D80005834012B89B004468946174604D90026E9 -:101D9000304609B0BDE8F08F914A52F8231009B9D6 -:101DA00042F823008F48C4F80C90017884F8108022 -:101DB00099B9302383F311888B4B9A6D42F00072EE -:101DC0009A659A6B42F000729A639A6B22F00072E5 -:101DD0009A630123037081F3118895F851647EB9E9 -:101DE000302383F311880321152001F02DFC0321FA -:101DF000162001F029FC012385F8513486F311885F -:101E0000302383F31188E26A936923F0100393610E -:101E100000F0C0FB8246E36A9E6916F0080609D00E -:101E200000F0B8FBA0EB0A03FA2BF4D9002686F3E6 -:101E30001188ADE79A6942F001029A6100F0AAFBAD -:101E40008246E36A9A69D00706D400F0A3FBA0EBB0 -:101E50000A03FA2BF5D9E9E79A6942F002029A617E -:101E6000E36A4FF0000AC3F854A08AF31188686C43 -:101E7000FFF7C8FB04F5825B0BF1100B2022002159 -:101E80006846FFF7F7F802A8FFF728FECDF818A07C -:101E90006A460BEB06030DF1180E9446BCE80300EE -:101EA000F44518605960624603F10803F5D1DCF887 -:101EB0000000186020369CF804201A71B6F5806F77 -:101EC000DCD1002304F5A25285F8503485F8533450 -:101ED0001A3249462046FFF7C7FE064690B9E26A25 -:101EE000936923F00103936100F054FB0546E36A14 -:101EF0009B69D9077FF54BAF00F04CFB431BFA2BD6 -:101F0000F5D944E795F85F0495F85E24C5F86C941C -:101F1000000240EA426095F86024E36A1043B5F895 -:101F20005C2440EA0240D8614FB304F5A352023268 -:101F300039462046FFF798FE90B9E26A936923F08C -:101F40000103936100F026FB0546E36A9B69DA070B -:101F50007FF51DAF00F01EFB431BFA2BF5D916E7EA -:101F600095F8683495F86714C5F870741B0143EA56 -:101F70000123B5F86414E26A43EA0143D3602046C2 -:101F8000FFF7DCFE002385F85934E36A6FF0404226 -:101F90001A65E36A154A5A65E36A44229A65E36A58 -:101FA0000722C3F8DC20E36A03229045DA653FF498 -:101FB000EFAEE26A936923F00103936100F0EAFA5D -:101FC0000746E36A9B69DB0705D500F0E3FAC31B0C -:101FD000FA2BF6D9DBE6012385F85234D8E600BFA8 -:101FE000004E0020044E0020001002409B0008001C -:101FF0002DE9F04F054689B090469946002741F2F9 -:10200000680A00F58056EB6AD3F8D430FB40D80755 -:1020100051D505EB471252444FEA471B1379190774 -:1020200049D4D6F884340133C6F8843405F5A55371 -:10203000C3E9008913799A0648BFD6F8B43405EB92 -:102040000B0248BF0133524448BFC6F8B434137979 -:1020500043F008031371DB0722D596F85334FBB124 -:1020600005F58254183468465C44FFF73DFD03AB28 -:1020700004F1080C206861681A4603C208346445FC -:102080001346F7D120681060A2889A800123ADF82A -:1020900008302B68CDE90089DB6B694628469847F4 -:1020A000D6F8A834D6F854040133C6F8A83410B1D1 -:1020B00003681B6998470137202FA4D109B0BDE8F8 -:1020C000F08F00002DE9F04F8DB004460F4600F070 -:1020D00063FA82468946002F56D1E36AD3F89020EE -:1020E000920141BF04F58051D1F898240132C1F822 -:1020F0009824D3F89020160703D100200DB0BDE836 -:10210000F08FD3F89050E669C5F30125482303FB0F -:102110000566E8464046FFF7E1FC326851004ABFD9 -:1021200022F06043C2F38A4343F00043920048BF69 -:1021300043F080430093736813F400131FBF04F54A -:10214000805201238DF80D30D2F8B8340EBF8DF8CF -:102150000D300133C2F8B834F38803F00F038DF863 -:102160000C304FF0000B9DF80C0000F06FFA5FFA96 -:102170008BF3984220D9F2180CA90B44127A03F879 -:102180002C2C0BF1010BEEE7012FB6D1E36AD3F84B -:102190009820950141BF04F58051D1F8982401326F -:1021A000C1F89824D3F898201007A6D0D3F89850F7 -:1021B000266AC5F30125A9E7EFB9E36AC3F894508D -:1021C00004A8FFF791FC98E80F0007AD07C52B8026 -:1021D0000023ADF8183023682046CDE904A9DB6B55 -:1021E00004A9984704F5805458B1D4F890340133C9 -:1021F000C4F8903482E7012F04BFE36AC3F89C500F -:10220000DEE7D4F894340133C4F89434012075E740 -:102210002DE9F04105460F4600F580540126394668 -:102220002846FFF74FFF10B184F85364F7E7D4F85E -:10223000A834D4F854040133C4F8A83420B1036896 -:10224000BDE8F0411B691847BDE8F081F0B5C36AED -:102250001A6C12F47F0F2BD000F580541B6CC4F85D -:10226000AC3441F26805002347194FF0010C00EB34 -:1022700043122A445E01117911F0020F15D049076B -:1022800013D4B959C66AD6F8C8E00CFA01F111EABC -:102290000E0F0AD0C6F8D010117941F00401117167 -:1022A000D4F88C240132C4F88C240133202BDED1E5 -:1022B000F0BD000010B5254C254B226802B338B3A1 -:1022C0001A6D12060ED580221A6500F065F950EAE3 -:1022D00001020B4602D0013861F10003024620687A -:1022E000FFF786FE1A4A136D1B032AD523684FF4A5 -:1022F000002103F580531165012283F8592420E061 -:1023000001221A6508221A654FF480621A6510BD11 -:10231000196DC80702D4196D890705D50321196500 -:1023200010460021FFF774FF094B1A6D100702D405 -:102330001A6DD10605D518221A6520680121FFF70C -:1023400067FF2068BDE81040FFF780BF004E002007 -:102350000064004008B5302383F31188FFF776FF4F -:10236000002383F3118808BDC36AD3F8C40080F446 -:102370000010C0F34050704708B5302383F3118834 -:1023800000F58050406CFFF74FF9002383F311886C -:1023900043090CBF0120002008BD000000F5805358 -:1023A00093F8592462B1C16A8A6922F001028A61F4 -:1023B000D3F89C240132C3F89C24002283F85924CA -:1023C000704700002DE9F743302181F3118800F5B3 -:1023D00082511031002541F2680E4FF0010800F5DE -:1023E000805C00EB45147444267977071CD4F6060C -:1023F0001AD5D0F82C908E69D9F8C87008FA06F66C -:102400003E4211D04F6801970F689742019F9F414C -:102410000AD2C9F8D060267946F004062671DCF8A5 -:1024200088440134CCF888440135202D01F1200185 -:10243000D7D1002383F3118803B0BDE8F0830000F7 -:10244000F8B51E46002313700F4605461446FFF7E5 -:1024500093FF80F0010038701EB12846FFF784FF1B -:102460002070F8BD2DE9F04F85B09946DDE90EA347 -:102470000D4602931378019391F800B080461646FA -:1024800000F08AF82B7804460F4613B93378002BF6 -:1024900041D022463B464046FFF794FFFFF75AFFE4 -:1024A000FFF77CFF4B4632462946FFF7C9FF2B78E2 -:1024B00033B1BBF1000F03D0012005B0BDE8F08FB0 -:1024C000337813B1019B002BF6D108F580530393A9 -:1024D000029B544577EB03031DD2039BD3F85404AE -:1024E000C8B10368AAEB04011B6898474B46324603 -:1024F00029464046FFF7A4FF2B7813B1BBF1000F2C -:10250000DAD1337813B1019B002BD5D100F044F818 -:1025100004460F46DCE70020CFE7000008B50020A6 -:10252000FFF7C8FEBDE8084001F050B808B501202B -:10253000FFF7C0FEBDE8084001F048B800B59BB009 -:10254000EFF3098168226846FEF782FDEFF3058309 -:10255000014B9B6BFEE700BF00ED00E008B5FFF705 -:10256000EDFF000000B59BB0EFF3098168226846DB -:10257000FEF76EFDEFF30583014B5B6BFEE700BFDB -:1025800000ED00E0FEE700000FB408B5029801F08E -:102590000FF9FEE701F0EEBB01F0D0BB13B56C46BE -:1025A00084E80600031D94E8030083E80500012089 -:1025B00002B010BD73B58568019155B11B885B07EA -:1025C00007D4D0E900369B6B9847019AC1B23046D8 -:1025D000A847012002B070BDF0B5866889B00546F5 -:1025E0000C465EB1BDF838305B070AD4D0E900373D -:1025F0009B6B98472246C1B23846B047012009B0CC -:10260000F0BD00220023CDE900230023ADF80830FF -:102610000A4603AB01F10806106851681C4603C462 -:102620000832B2422346F7D1106820609288A28017 -:10263000FFF7B2FF0423ADF808302B68CDE90001A5 -:10264000DB6B694628469847D8E70000082817D969 -:1026500009280CD00A280CD00B280CD00C280CD040 -:102660000D280CD00E2814BF4020302070470C20BD -:1026700070471020704714207047182070472020A2 -:10268000704700002DE9F041456A15B94162BDE887 -:10269000F0814B6823F06047C3F38A464FEAD37E4C -:1026A000C3F3807816EA230638BF3E46AC462B4675 -:1026B0005A68BEEBD27F22F060440AD0002A18DAB2 -:1026C000A40CB44217D19D420FD10D60DEE7134632 -:1026D000EEE7A74207D102F08044C2F38072424580 -:1026E0000BD054B1EFE708D2EDE7CCF800100B6047 -:1026F000CDE7B44201D0B442E5D81A689C46002A1E -:10270000E5D11960C3E700002DE9F047089D01F00D -:1027100007044FEAD508224405F0070500EBD10075 -:102720004FF47F49944201D1BDE8F08704F00707D8 -:1027300005F0070A57453E4638BF5646C6F108061B -:10274000111B8E4228BF0E46E10808EBD50E415CF6 -:1027500013F80EC0B94029FA06F721FA0AF1FFB2C0 -:102760008CEA010147FA0AF739408CEA010C03F8B8 -:102770000EC034443544D5E780EA0120082341F2F5 -:10278000210201B24000002980B203F1FF33B8BF3B -:10279000504013F0FF03F4D17047000038B50C46E9 -:1027A0008D18A54200D138BD14F8011BFFF7E4FFD6 -:1027B000F7E7000042684AB11368436043898189A2 -:1027C00001339BB29942438138BF838110467047E1 -:1027D00070B588B0202204460D4668460021FEF7F9 -:1027E00049FC20460495FFF7E5FF024658B16B46C9 -:1027F000054608AE1C4603CCB442286069602346F7 -:1028000005F10805F6D1104608B070BD082817D9A3 -:1028100009280CD00A280CD00B280CD00C280CD07E -:102820000D280CD00E2814BF4020302070470C20FB -:1028300070471020704714207047182070472020E0 -:1028400070470000082817D90C280CD910280CD97B -:1028500014280CD918280CD920280CD930288CBF62 -:102860000F200E207047092070470A2070470B2068 -:1028700070470C2070470D20704700002DE9F84389 -:10288000078C072F04461ED9D0E9029800254FF681 -:10289000FF73C5F12006A5F1200029FA05F108FA19 -:1028A00006F628FA00F031430143C9B21846FFF793 -:1028B00063FF0835402D0346EBD1E1693A46BDE898 -:1028C000F843FFF76BBF4FF6FF70BDE8F8830000D9 -:1028D00010B54B6823B9CA8A63F30902CA8210BDD6 -:1028E00004691A681C600361C38A013BC3824A60A1 -:1028F000EFE700002DE9F84F1D46CB8A0F46C3F3E2 -:1029000009010529814692460B4630D00020AAB223 -:1029100007F11A049EB2042E1FFA80F80FD89045D2 -:1029200003F1010306D3FB8A0A4462F30903FB8225 -:1029300001201AE01AF80060E6540130EAE79045F9 -:10294000F1D2A1F1050B1C237C68BBFBF3F203FB66 -:1029500012BB1FFA8BF6002C45D14846FFF72AFF21 -:10296000044638B978606FF00200BDE8F88F4FF088 -:102970000008E6E7002606607860ADB24FF0000B75 -:10298000454510D90AEB0803221D13F8011B915588 -:10299000B1B208F101081B291FFA88F82BD0454570 -:1029A00006F10106F1D8FB8AC3F30902154465F369 -:1029B0000903BCE7013292B21C462368002BF9D10F -:1029C0006B1F0B441C21B3FBF1F301339BB29A4202 -:1029D000D3D2BBF1000FD0D14846FFF7EBFE20B9B0 -:1029E000C4F800B0BFE70122E7E7C0F800B05E46D8 -:1029F00020600446C1E74545D5D94846FFF7DAFED1 -:102A000008B92060AFE7C0F800B000262060044697 -:102A1000B6E700002DE9F04F2DED028B1C4683B088 -:102A20005B69019207468846002B00F09A80238C50 -:102A30002BB1E269002A00F09480072B35D807F10A -:102A40000C00FFF7B7FE054638B96FF002052846BF -:102A500003B0BDEC028BBDE8F08F14220021FEF71D -:102A600009FB228CE16905F10800FEF7F1FA208CE0 -:102A7000013080B2FFF7E6FEFFF7C8FE013880B2F2 -:102A80002084013028746369228C1B782A4403F067 -:102A90001F0363F03F0348F000411372384669603A -:102AA0002946FFF7EFFD0125D1E700F10C034FF0B8 -:102AB000000908EE103A4FF0800A4E464D4618EED7 -:102AC000100AFFF777FE83460028BED014220021AB -:102AD000FEF7D0FA002E3AD1019BABF80830022263 -:102AE0000BF1080E1FFA82FC0CF10100BCF1060F7D -:102AF000218C80B201D88E422BD3FFF7A3FEFFF7C3 -:102B000085FE62691278013802F01F028E4208BF0A -:102B10004FF0400A42EA49121BFA80F14AEA020ADF -:102B2000013048F0004281F808A08BF81000CBF883 -:102B3000042059463846FFF7A5FD238C0135B342E2 -:102B40002DB289F001094FF0000AB8D17FE70022C9 -:102B5000C6E7E169895D0EF802100136B6B20132AE -:102B6000C0E76FF0010572E7F8B515460E46302252 -:102B7000002104461F46FEF77DFA069B6360B5F50B -:102B8000001F079BA76034BF6A094FF6FF72A3625C -:102B900097B2E66104F1100000239A4206D80023A0 -:102BA0000360A782E3822383E360F8BD06600133FC -:102BB00030462036F1E7000003781BB94BB2002BFA -:102BC000C8BF01707047000000787047F8B50C4628 -:102BD000C969074611B9238C002B37D1257E1F2DDB -:102BE00034D8387828BB228C072A2CD8268A36F08D -:102BF00003032BD14FF6FF70FFF7D0FD20F001004B -:102C00003102400441EA0561400C41EA40254FF69B -:102C1000FF72234629463846FFF7FCFE002807DDF1 -:102C2000626913780133DBB21F2B88BF0023137056 -:102C3000F8BD218A2D0645EA012505432046FFF708 -:102C40001DFE0246E5E76FF00300F1E76FF00100BB -:102C5000EEE7000070B58AB004461646002128222F -:102C600068461D46FEF706FABDF83830ADF810305C -:102C70000F9B05939DF840308DF81830119B0793FA -:102C80006946BDF84830ADF820302046CDE90265F0 -:102C9000FFF79CFF0AB070BD2DE9F041D3690546EE -:102CA0000C4616460BB9138C5BBB377E1F2F28D8FA -:102CB00095F80080B8F1000F26D03046FFF7DEFD12 -:102CC0003378210241EAC33141EA0801338A41EAFB -:102CD000076141EA03410246334641F0800128463C -:102CE000FFF798FE00280ADD3378012B07D17269BF -:102CF00013780133DBB21F2B88BF00231370BDE8AC -:102D0000F0816FF00100FAE76FF00300F7E70000D1 -:102D1000F0B58BB004460D461746002128226846C0 -:102D20001E46FEF7A7F99DF84C305A1E53425341F8 -:102D30008DF800309DF84030ADF81030119B0593B0 -:102D40009DF848308DF81830149B07936A46BDF8FB -:102D50005430ADF8203029462046CDE90276FFF701 -:102D60009BFF0BB0F0BD0000406A00B1043070471B -:102D7000436A1A68426202691A600361C38A013BAE -:102D8000C38270472DE9F041D0F82080194E1446D7 -:102D90001D464146002709B9BDE8F081D1E902236B -:102DA000A21A65EB0303964277EB03031ED2036A74 -:102DB0008B420DD1FFF78CFD036A1B680362036928 -:102DC0000B60C38A0161016A013BC3828846E2E766 -:102DD000FFF77EFD0B68C8F8003003690B60C38AFB -:102DE0000161013BC382D8F80010D4E78846096826 -:102DF000D1E700BF80841E002DE9F04F8BB00D4657 -:102E0000DDF8509014469B468046002800F019815A -:102E1000B9F1000F00F01581531E3F2B00F2118114 -:102E2000012A03D1BBF1000F40F00B810023CDE953 -:102E30000833B8F81430B5EBC30F4FEAC30703D318 -:102E400000200BB0BDE8F08F2B199F42D8F80C3052 -:102E50003ABF7F1BFFB227461BB9D8F81030002BB2 -:102E60007AD0272D4ED8C5F12806B7424FF000037F -:102E70002CBFF6B23E4600932946D8F8080008ABAE -:102E80003246FFF741FCA7EB060A35445FFA8AFA9F -:102E9000B8F8143003F10053053BDB000493D8F875 -:102EA0000C3003932821039B13B1BAF1000F2CD1EE -:102EB000D8F8100040B1BAF1000F05D0009608AB69 -:102EC0005246691AFFF720FC38B2002FB8D06607C7 -:102ED0000AD00AAB03EBD401624211F8083C02F0BD -:102EE0000702134101F8083C082C3CD9102C40F291 -:102EF000B580202C40F2B780BBF1000F00F09C8021 -:102F0000082334E0BA460026C2E7049BE02B28BF22 -:102F1000E02306930B44AB42059314D95A1B039844 -:102F20000096924534BF5246D2B2691A08AB0430BB -:102F30000792FFF7E9FB079A1644AAEB020A154429 -:102F4000F6B25FFA8AFA049B069A05999B1A0493D3 -:102F5000039B1B680393A6E70093D8F8080008AB0F -:102F60003A462946AEE7BBF1000F13D00123B4EB7C -:102F7000C30F6CD0082C12D89DF82030621E23FAA3 -:102F800002F2D50706D54FF0FF3202FA04F42343CC -:102F90008DF820309DF8203089F8003051E7102C52 -:102FA00012D8BDF82030621E23FA02F2D10706D5EE -:102FB0004FF0FF3202FA04F42343ADF82030BDF89D -:102FC0002030A9F800303CE7202C0FD80899631E68 -:102FD00021FA03F3DA0705D54FF0FF3202FA04F4C1 -:102FE0000C430894089BC9F800302AE7402C2BD0EA -:102FF000DDE90865611EC4F12102A4F1210326FA6E -:1030000001F105FA02F225FA03F311431943CB0744 -:1030100012D50122A4F12003C4F1200102FA03F326 -:1030200022FA01F1A240524243EA010363EB430357 -:1030300032432B43CDE90823DDE90823C9E9002306 -:10304000FFE66FF00100FCE66FF00800F9E6082CDF -:10305000A0D9102CB3D9202CEED8C3E7BBF1000FB8 -:10306000ADD0022383E7BBF1000FBBD004237EE782 -:1030700030B5012A144638BF0124402C85B028BF42 -:1030800040240025012ACDE9025518D81B788DF877 -:10309000083063070AD004AB03EBD405624215F88D -:1030A000083C02F00702934005F8083C00910346F3 -:1030B0002246002102A8FFF727FB05B030BD082AF1 -:1030C000E4D9102A03D81B88ADF80830E1E7202A9C -:1030D0008DBFD3E900231B680293CDE90223D8E713 -:1030E00010B5CB681BB98B600B618B8210BD046976 -:1030F0001A681C600361C38A013BC382CA60F0E79F -:1031000003064CBFC0F3C0300220704708B502462A -:10311000FFF7F6FF022806D15306C2F30F2001D1B4 -:1031200000F0030008BDC2F30740FBE72DE9F04FB4 -:1031300093B0CDE903230A6804461046FFF7E0FF89 -:10314000022814BFC2F306260026002A0D46824636 -:1031500080F2F28112F0C04940F0EE81097B002933 -:1031600000F0EA81022803D02378B34240F0E781DF -:10317000C2F304630693104602F07F030593FFF742 -:10318000C5FF059B29444FEA834848EA0A4848EAB4 -:103190004668CE7800230022CDE90823F309834650 -:1031A00048EA0008029367D0059B009302466768CF -:1031B000534608A92046B847002800F0C381276A73 -:1031C0004FB9414604F10C00FFF702FB074690B9E6 -:1031D0006FF0020054E03B6998450DD03F68002F26 -:1031E000F9D1414604F10C00FFF7F2FA0746002836 -:1031F000EED0236A3B60276297F817C006F01F08DD -:10320000CCF3840CACEB08001FFA80FE0028B8BF9A -:103210000EF12000A8EB0C031FFA83FED7E9022170 -:10322000B8BF00B2002B0793BEBF0EF120031BB244 -:10323000079352EA010338D0039BDFF824E39A1A7C -:10324000049B4FF0000C63EB010196457CEB0103FE -:103250002BD36B7B97F81AE0734519D1029B002B97 -:1032600078D0012821DC7868F8B9DFF8F0C29445FD -:1032700070EB010316D337E0276A27B96FF00C0013 -:1032800013B0BDE8F08F3B699845B5D03F68F4E7CF -:10329000B24890427CEB010301D30020F0E7029B8F -:1032A000002BFAD0079B0F2B17DCFA7DB30002F03E -:1032B000030203F07C031343FB7539462046FFF7F6 -:1032C00007FB6B7BBB76029B3BB9FB7DC3F38402A0 -:1032D000013262F38603FB75D0E76A7BBB7E9A42BC -:1032E000DBD1029B002B35D0B309022B32D0039BDC -:1032F000BB60049BFB60142200210DA8FDF7BAFE01 -:10330000039B0A93049B0B932B1D0C932B7BADF813 -:103310003EB0013BDBB2ADF83C30069B8DF842304D -:10332000059B8DF8433094F82C308DF840A083F045 -:1033300001038DF844308DF84180A3680AA9204626 -:103340009847FB7DC3F38403013303F01F039B0203 -:10335000FB82A2E7FB7DC6F34012B2EBD31F40F025 -:10336000F480C3F38403434540F0F280029A2B7B40 -:10337000B609002A4DD0F2075DD4032B40F2EB8052 -:10338000039BBB60049BFB602B7BAE1D033BDBB24E -:103390003246394604F10C00FFF7ACFA00280CDA8B -:1033A00039462046FFF794FAFB7DC3F384030133CB -:1033B00003F01F039B02FB820AE7DDE90884AB8868 -:1033C0003B834FF6FF73C9F12000A9F1200228FAD0 -:1033D00009F104FA00F0014324FA02F211431846FD -:1033E000C9B2FFF7C9F909F10809B9F1400F03465D -:1033F000E9D1B8822A7B033AD2B23146FFF7CEF93F -:10340000FB7DB882DA43C2F3C01262F3C713FB75C7 -:1034100043E786B92E1D013BDBB23246394604F143 -:103420000C00FFF767FA0028BADB2A7BB88A013A5A -:10343000D2B23146E2E7F98AC1F30901013B04291E -:10344000DAB25BD8281D002307F11B069A4208D97F -:1034500010F801CB06F801C0013101330529DBB2B8 -:10346000F4D103990A9104990B91934207F11B013E -:103470000C9138BF043379680D9134BF55FA83F34A -:1034800000230E93FB8AADF83EB0C3F309031A4440 -:10349000069B8DF84230059B8DF8433094F82C3014 -:1034A000ADF83C2083F001038DF8443000238DF803 -:1034B00040A08DF841807B602A7BB88A013A291DA3 -:1034C000FFF76CF93B8BB882834203D1A3680AA94A -:1034D0002046984720460AA9FFF702FEFB7DBA8ADC -:1034E000C3F38403013303F01F039B02FB823B8B76 -:1034F0009A420CBF00206FF01000C1E67B68002BE1 -:10350000AFD0052001E01C3033461E68002EFAD1F2 -:10351000091A081D2E1D184401EB090CBCF11B0FE4 -:103520005FFA89F39DD89A429BD916F8013B00F8BF -:10353000013B09F10109EFE76FF00900A0E66FF028 -:103540000A009DE66FF00B009AE66FF00D0097E61B -:103550006FF00E0094E66FF00F0091E640420F000E -:1035600080841E00EFF3098305494A6B22F00102B3 -:103570004A63683383F30988002383F31188704713 -:1035800000EF00E0302080F3118862B60C4B0D4A4A -:10359000D96821F4E0610904090C0A43DA60D3F820 -:1035A000FC20094942F08072C3F8FC200A6842F00E -:1035B00001020A602022DA7783F82200704700BFF8 -:1035C00000ED00E00003FA05001000E010B5302324 -:1035D00083F311880E4B5B6813F4006314D0F1EE93 -:1035E000103AEFF30984683C4FF08073E361094BB4 -:1035F000DB6B236684F3098800F0A4F810B1064B56 -:10360000A36110BD054BFBE783F31188F9E700BF09 -:1036100000ED00E000EF00E03F0300084203000877 -:103620004FF0E023002258684FF0FF31930003F180 -:10363000604303F5614301329042C3F88010C3F840 -:103640008011F3D27047000000F1604303F561433D -:103650000901C9B283F80013012200F01F039A4048 -:1036600043099B0003F1604303F56143C3F88021E4 -:103670001A60704700230375826803691B689968A4 -:103680009142FBD25A6803604260106058607047F4 -:1036900000230375826803691B6899689142FBD80F -:1036A0005A680360426010605860704708B5084669 -:1036B000302383F311880B7D032B05D0042B0DD011 -:1036C0002BB983F3118808BD8B6900221A604FF073 -:1036D000FF338361FFF7CEFF0023F2E7D1E9003229 -:1036E00013605A60F3E70000FFF7C4BF054BD968C9 -:1036F0000875186802681A60536001220275D86064 -:10370000FCF708BE104E002030B50C4BDD684B1C9A -:1037100087B004460FD02B46094A684600F02AF9C4 -:103720002046FFF7E3FF009B13B1684600F02CF939 -:10373000A86907B030BDFFF7D9FFF9E7104E0020A8 -:10374000AD360008044B1A68DB6890689B689842A5 -:1037500094BF002001207047104E0020084B10B588 -:103760001C68D86822681A60536001222275DC60E8 -:10377000FFF78EFF01462046BDE81040FCF7CABDAA -:10378000104E002038B5074C074908480123002592 -:103790002370656000F0ECFB0223237085F3118831 -:1037A00038BD00BF7850002008460008104E0020A9 -:1037B00008B572B6044B186500F0ACFA00F05AFB7D -:1037C000024B03221A70FEE7104E002078500020B2 -:1037D00000F010B98B60022308618B8208467047A5 -:1037E0008368A3F1840243F8142C026943F8442C43 -:1037F000426943F8402C094A43F8242CC26843F834 -:10380000182C022203F80C2C002203F80B2C044A7B -:1038100043F8102CA3F12000704700BF2D030008CF -:10382000104E002008B5FFF7DBFFBDE80840FFF7AA -:103830005BBF0000024BDB6898610F20FFF756BFAB -:10384000104E0020302383F31188FFF7F3BF0000F0 -:1038500008B50146302383F311880820FFF754FF91 -:10386000002383F3118808BD10B503689C68A24249 -:103870000CD85C688A600B604C6021605960996864 -:103880008A1A9A604FF0FF33836010BD1B68121BC9 -:10389000ECE700000A2938BF0A2170B504460D463E -:1038A0000A26601900F05EFB00F04AFB041BA542EB -:1038B00003D8751C2E460446F3E70A2E04D9BDE84A -:1038C0007040012000F094BB70BD0000F8B5144BAF -:1038D0000D46D96103F1100141600A2A196982601D -:1038E00038BF0A22016048601861A818144600F029 -:1038F0002BFB0A2700F024FB431BA342064606D3FA -:103900007C1C281900F02EFB27463546F2E70A2FCB -:1039100004D9BDE8F840012000F06ABBF8BD00BF43 -:10392000104E0020F8B506460D4600F009FB0F4A80 -:10393000134653F8107F9F4206D12A46014630466F -:10394000BDE8F840FFF7C2BFD169BB68441A2C1923 -:1039500028BF2C46A34202D92946FFF79BFF2246E7 -:1039600031460348BDE8F840FFF77EBF104E002007 -:10397000204E002010B4C0E9032300235DF8044B5F -:103980004361FFF7CFBF000010B5194C236998427F -:103990000DD0D0E90032816813605A609A680A44F9 -:1039A0009A60002303604FF0FF33A36110BD2346EC -:1039B000026843F8102F53600022026022699A4285 -:1039C00003D1BDE8104000F0C7BA936881680B448A -:1039D000936000F0B5FA2269E1699268441AA24244 -:1039E000E4D91144BDE81040091AFFF753BF00BFE6 -:1039F000104E00202DE9F047DFF8BC8008F11007D9 -:103A00002C4ED8F8105000F09BFAD8F81C40AA6849 -:103A1000031B9A423ED81444D5E900324FF0000906 -:103A2000C8F81C4013605A60C5F80090D8F81030F0 -:103A3000B34201D100F090FA89F31188D5E903313E -:103A400028469847302383F311886B69002BD8D020 -:103A500000F076FA6A69A0EB04094A4582460DD265 -:103A6000022000F0C5FA0022D8F81030B34208D185 -:103A700051462846BDE8F047FFF728BF121A2244F6 -:103A8000F2E712EB090938BF4A4629463846FFF7E4 -:103A9000EBFEB5E7D8F81030B34208D01444211A31 -:103AA000C8F81C00A960BDE8F047FFF7F3BEBDE809 -:103AB000F08700BF204E0020104E002038B500F0E7 -:103AC0003FFA054AD2E90845031B181945F10001E0 -:103AD000C2E9080138BD00BF104E00200020704729 -:103AE000FEE70000704700004FF0FF307047000015 -:103AF000BFF34F8F024A1369DB03FCD4704700BF4A -:103B00000020024008B5094B1B7873B9FFF7F0FF9E -:103B1000074B5A69002ABFBF064A9A6002F18832F1 -:103B20009A601A6822F480621A6008BD90500020E2 -:103B3000002002402301674508B50B4B1B7893B961 -:103B4000FFF7D6FF094B5A6942F000425A611A68E2 -:103B500042F480521A601A6822F480521A601A687D -:103B600042F480621A6008BD90500020002002409C -:103B70007F289ABF00F58030C00200207047000007 -:103B80004FF4006070470000802070477F2808B520 -:103B90000BD8FFF7EDFF00F500630268013204D196 -:103BA00004308342F9D1012008BD0020FCE7000069 -:103BB0007F2810B504461FD8FFF79AFFFFF7A2FF32 -:103BC0000E4BF3221A6102225A615A6942EAC0027C -:103BD0005A615A6942F480325A61FFF789FF4FF403 -:103BE0000061FFF7C5FF00F041F9FFF7A5FF204690 -:103BF000BDE81040FFF7CABF002010BD0020024002 -:103C00002DE9F84340EA020313F00703144606D0F7 -:103C1000304B40F233321A600020BDE8F88385183B -:103C20002D4A95420CD92B4A4FF44E711160F3E79F -:103C3000031D1B684A68934208D1083C08300831CC -:103C4000072C14D902680B689A42F1D0FFF75AFF8B -:103C5000FFF74EFF214E08314FF001084FF00009E9 -:103C6000012CA1F1080706D8FFF766FF01E0002C40 -:103C7000ECD10120D1E7C6F81480054651F8083C84 -:103C800045F8043B51F8043C4360FFF731FF3369CA -:103C900043F001033361C6F81490026851F8083C00 -:103CA0009A420CD00B4B4FF458721A600C4B1860B0 -:103CB0000C4B1C600C4B1F60FFF73EFFACE72D6800 -:103CC00051F8043C9D4201F10801EBD1083C083059 -:103CD000C6E700BF8C50002000000408002002400E -:103CE000805000208850002084500020084908B5EA -:103CF0000B7828B11BB9FFF705FF01230B7008BD36 -:103D0000002BFCD0BDE808400870FFF715BF00BFCE -:103D10009050002008B54FF4C0314FF0005000F033 -:103D2000A7F8BDE808404FF480414FF0805000F004 -:103D30009FB80000084600F0D9BB000038B5EFF38B -:103D400011859DB9EFF30584C4F30804302334B121 -:103D500083F31188FFF7B2FE85F3118838BD83F332 -:103D60001188FFF7ABFE84F3118838BDBDE83840F9 -:103D7000FFF7A4BE38B5FFF7E1FF114C114AC008A8 -:103D800040EA4170A0FB025EC908A0FB040C1CEBDA -:103D9000050CA1FB04404FF000035B41A1FB0212A4 -:103DA0001CEB040C43EB000011EB0E0142F100028E -:103DB000411842F10000090941EA007038BD00BF16 -:103DC000CFF753E3A59BC4200244D2B2904200D166 -:103DD0007047431C800000F1804000F514500068DB -:103DE00041F8040BD8B2F1E7124B10B5D3F890406C -:103DF000240409D4D3F89040C3F89040D3F89040FD -:103E000044F40044C3F890400B4C2368024443F44C -:103E100080732360D2B2904200D110BD431C800059 -:103E200000F1804000F5145051F8044B0460D8B202 -:103E3000F1E700BF001002400070004007B501220A -:103E400001A90020FFF7C0FF019803B05DF804FB53 -:103E500013B50446FFF7F2FFA04205D0012201A9E5 -:103E600000200194FFF7C0FF02B010BD70470000B2 -:103E70007047000070470000074B45F255521A602A -:103E800002225A6040F6FF729A604CF6CC421A60E9 -:103E9000024B01221A7070470030004098500020F9 -:103EA000034B1B781BB1034B4AF6AA221A607047DA -:103EB0009850002000300040054B1A6832B902F1DA -:103EC000804202F50432D2F894201A60704700BF95 -:103ED00094500020024B4FF40002C3F89420704726 -:103EE0000010024008B5FFF7E7FF024B1868C0F367 -:103EF000407008BD9450002070470000FEE70000AD -:103F00000A4B0B480B4A90420BD30B4BDA1C121A8C -:103F1000C11E22F003028B4238BF00220021FDF7B0 -:103F2000A9B853F8041B40F8041BECE764470008E9 -:103F30001C5100201C5100201C51002000F0C2B870 -:103F40004FF08043586A70474FF080430022586317 -:103F50001A610222DA6070474FF080430022DA6073 -:103F6000704700004FF0804358637047FEE7000041 -:103F700070B51B4B01630025044686B0586085620E -:103F80000E46FFF7FFFA04F11003C4E904334FF0C3 -:103F9000FF33C4E90635C4E90044A560E562FFF7D4 -:103FA000CFFF2B460246C4E9082304F134010D4A31 -:103FB000256580232046FFF70DFC0123E0600A4AB7 -:103FC0000375009272680192B268CDE90223074B33 -:103FD0006846CDE90435FFF725FC06B070BD00BF8B -:103FE0007850002014460008194600086D3F00086C -:103FF000024AD36A1843D062704700BF104E0020B7 -:104000004B6843608B688360CB68C3600B69436116 -:104010004B6903628B6943620B6803607047000061 -:1040200008B5204BDA6A42F07F02DA62DA6A22F0DF -:104030007F02DA62DA6ADA6C42F07F02DA64DA6E00 -:1040400042F07F02DA66184ADB6E11464FF090406C -:10405000FFF7D6FF02F11C0100F58060FFF7D0FFEB -:1040600002F1380100F58060FFF7CAFF02F1540148 -:1040700000F58060FFF7C4FF02F1700100F5806079 -:10408000FFF7BEFF02F18C0100F58060FFF7B8FF7B -:1040900002F1A80100F58060FFF7B2FFBDE808401B -:1040A00000F050B8001002402046000808B500F0AB -:1040B000EDF9FFF767FBBDE80840FFF7FDBE000024 -:1040C000704700000F4B9A6D42F001029A659A6F9B -:1040D00042F001029A670C4A9B6F936843F0010318 -:1040E00093604FF08043A7229A624FF0FF32DA626A -:1040F00000229A615A63DA605A6001225A611A609A -:10410000704700BF00100240002004E04FF08042E2 -:1041100008B51169D3680B40D9B2C9439B07116137 -:1041200007D5302383F31188FFF752FB002383F375 -:10413000118808BD08B5FFF773FABDE8084000F024 -:1041400081B900004E4B4FF0FF319A6A99629A6A2A -:1041500000229A62986AD86A60F07F00D862D86AB2 -:1041600000F07F00D862D86A186B1963186B1A6365 -:10417000186B986B9963986B9A63986BD86BD9633B -:10418000D86BDA63D86B186C1964196C1A64196CE3 -:10419000196E41F001011966D3F8801021F0010178 -:1041A000C3F88010D3F88010996D41F08051996563 -:1041B000996F21F080519967996F32494FF400400F -:1041C0008860CA600A624A628A62CA620A634A6393 -:1041D0008A63CA630A644A648A64CA640A654A656F -:1041E0004A604FF48072C1F880204FF440720A6038 -:1041F0004A6912F48062FBD1D3F8901011F4407F29 -:104200001EBF4FF48031C3F89010C3F89020D3F84C -:10421000982042F00102C3F89820D3F89820920722 -:10422000FBD51A6842F480321A601A689003FCD5F4 -:10423000D3F8902022F00322C3F89020124ADA60CB -:104240001A6842F080721A601A689101FCD50F4911 -:104250000F4800229A60C3F888100E49C3F89C20CA -:10426000016002684A401207FBD19A6842F00302DB -:104270009A609A6802F00C020C2AFAD1704700BFCB -:104280000010024000700040132A610155010050E7 -:104290000020024004070400074A08B5536903F0F0 -:1042A0000103536123B1054A13680BB15068984765 -:1042B000BDE80840FFF78AB9000401409C50002087 -:1042C000074A08B5536903F00203536123B1054A55 -:1042D00093680BB1D0689847BDE80840FFF776B9FE -:1042E000000401409C500020074A08B5536903F0C0 -:1042F0000403536123B1054A13690BB15069984710 -:10430000BDE80840FFF762B9000401409C5000205E -:10431000074A08B5536903F00803536123B1054AFE -:1043200093690BB1D0699847BDE80840FFF74EB9D3 -:10433000000401409C500020074A08B5536903F06F -:104340001003536123B1054A136A0BB1506A9847B1 -:10435000BDE80840FFF73AB9000401409C50002036 -:10436000164B10B55C6904F478725A61A30604D543 -:10437000134A936A0BB1D06A9847600604D5104A75 -:10438000136B0BB1506B9847210604D50C4A936B05 -:104390000BB1D06B9847E20504D5094A136C0BB1F9 -:1043A000506C9847A30504D5054A936C0BB1D06CAB -:1043B0009847BDE81040FFF709B900BF000401406D -:1043C0009C500020194B10B55C6904F47C425A6182 -:1043D000620504D5164A136D0BB1506D984723053D -:1043E00004D5134A936D0BB1D06D9847E00404D502 -:1043F0000F4A136E0BB1506E9847A10404D50C4AB6 -:10440000936E0BB1D06E9847620404D5084A136FBF -:104410000BB1506F9847230404D5054A936F0BB135 -:10442000D06F9847BDE81040FFF7D0B800040140B6 -:104430009C50002008B5FFF769FEBDE80840FFF773 -:10444000C5B80000062108B50846FFF7FDF80621AB -:104450000720FFF7F9F806210820FFF7F5F80621F5 -:104460000920FFF7F1F806210A20FFF7EDF80621F1 -:104470001720FFF7E9F806212820FFF7E5F8BDE847 -:10448000084007211C20FFF7DFB8000008B5FFF740 -:1044900051FE00F007F8FFF713FEBDE80840FFF7F4 -:1044A0004DBD00000023054A19460133102BC2E917 -:1044B000001102F10802F8D1704700BF9C500020A3 -:1044C0000B460146184600F003B8000000F00EB895 -:1044D00010B5054C13462CB10A4601460220AFF335 -:1044E000008010BD2046FCE700000000024B0146A2 -:1044F0001868FFF71FBC00BF1823002010B5013952 -:104500000244904201D1002005E0037811F8014FE8 -:10451000A34201D0181B10BD0130F2E72DE9F04194 -:10452000A3B1C91A17780144044603F1FF3C8C4239 -:10453000204601D9002009E00578BD4204F10104BC -:10454000F5D10CEB0405D618A54201D1BDE8F081E8 -:1045500015F8018D16F801EDF045F5D0E7E70000FC -:10456000034611F8012B03F8012B002AF9D17047FB -:10457000696E2E7369657272616165726F737061C5 -:1045800063652E547275654E617650726F2D473497 -:104590000000000040A2E4F1646891060041A3E538 -:1045A000F2656992070000004261642043414E4970 -:1045B0006661636520696E6465782E000000000006 -:1045C00000000000751D0008691800086524000837 -:1045D000D91800081D190008051B0008E518000877 -:1045E000A1180008A51800087D1800086518000823 -:1045F000C11A0008891800089D25000895180008B0 -:10460000951A00086330000004460008684E002038 -:10461000785000206D61696E0069646C650000006F -:104620000001942A00000000AAAAAAAA00001424EB -:10463000FFFF0000000000000090090000040000DF -:1046400000000000AAA6AAAA00000000DFFF0000E8 -:10465000000000000000000000000000000000005A -:10466000AAAAAAAA00000000FFFF000000000000A4 -:10467000000000000000000000000000AAAAAAAA92 -:1046800000000000FFFF000000000000000000002C -:104690000000000000000000AAAAAAAA0000000072 -:1046A000FFFF00000000000000000000000000000C -:1046B00000000000AAAAAAAA00000000FFFF000054 -:1046C00000000000000000000000000000000000EA -:1046D000AAAAAAAA00000000FFFF00000000000034 -:1046E0000000000000000000B51400000000000001 -:1046F0000070030000000000FE2A0100D204000048 -:104700001C2300200000000000000000000000004A -:104710000000000000000000000000000000000099 -:104720000000000000000000000000000000000089 -:104730000000000000000000000000000000000079 -:104740000000000000000000000000000000000069 -:104750000000000000000000000000000000000059 -:044760000000000055 +:100F500000340020C8330020C5330020B423002013 +:100F600008B5054800F072FEBDE80840034A044990 +:100F7000002003F047BB00BF00340020304E0020AB +:100F8000C108000870B503F043F8094E094D3080E0 +:100F9000002428683388834208D903F035F82B6889 +:100FA00004440133B4F5104F2B60F2D370BD00BF81 +:100FB000244E0020F84D002003F0DCB800F1006062 +:100FC000920000F5104003F05FB80000054B1A686E +:100FD000054B1B889B1A834202D9104403F014B8B6 +:100FE00000207047F84D0020244E0020024B1B6863 +:100FF000184403F00FB800BFF84D0020024B1B68E7 +:10100000184403F019B800BFF84D0020064991F8C4 +:10101000243033B10023086A81F824300822FFF716 +:10102000CDBF0120704700BFFC4D0020022802BF49 +:101030004FF0904310229A6170470000022802BFCF +:101040004FF090434FF480129A61704710B500231F +:10105000934203D0CC5CC4540133F9E710BD0000C7 +:1010600003460246D01A12F9011B0029FAD1704733 +:1010700002440346934202D003F8011BFAE770478B +:101080002DE9F8431F4D144695F82420074688465D +:1010900052BBDFF870909CB395F824302BB9202216 +:1010A000FF2148462F62FFF7E3FF95F82400C0F1C7 +:1010B0000802A24228BF2246D6B24146920005EB62 +:1010C0008000FFF7C3FF95F82430A41B1E44F6B23E +:1010D000082E17449044E4B285F82460DBD1FFF772 +:1010E00095FF0028D7D108E02B6A03EB82038342E7 +:1010F000CFD0FFF78BFF0028CBD10020BDE8F883CD +:101100000120FBE7FC4D00202DE9F0470D46044689 +:1011100000219046284640F27912FFF7A9FF2346A6 +:1011200020220021284601F0D1FF231D0222202188 +:10113000284601F0CBFF631D03222221284601F03F +:10114000C5FFA31D03222521284601F0BFFF04F19E +:10115000080310222821284601F0B8FF04F11003EB +:1011600008223821284601F0B1FF04F111030822BA +:101170004021284601F0AAFF04F112030822482169 +:10118000284601F0A3FF04F1140320225021284631 +:1011900001F09CFF04F1180340227021284601F061 +:1011A00095FF04F120030822B021284601F08EFFAC +:1011B00004F121030822B821284601F087FF04F139 +:1011C0002207C0263B46314608222846083601F051 +:1011D0007DFFB6F5A07F07F10107F3D104F13203DB +:1011E00008223146284601F071FF002704F1330A36 +:1011F00094F832304FEAC7099F4209F5A47615D317 +:10120000B8F1000F08D1314604F59973072228463A +:1012100001F05CFF09F24F16274694F832213B1B80 +:1012200093420CD3F01DC008BDE8F0870AEB07031A +:1012300008223146284601F049FF0137D8E707F276 +:10124000331331460822284601F040FF08360137A3 +:10125000E3E7000013B50446084600210160234679 +:10126000C0F803102022019001F030FF0198231DE7 +:101270000222202101F02AFF0198631D032222216E +:1012800001F024FF0198A31D0322252101F01EFF78 +:10129000019804F108031022282101F017FF07200C +:1012A00002B010BDF7B50023047F00910E4607225F +:1012B0001946054601F0CEFD731C00930122002360 +:1012C0000721284601F0C6FDC4B9B31C00930522CE +:1012D00023460821284601F0BDFD0D243746B2788B +:1012E000BB1B934211D32B7FA88A0734E408BBB9F8 +:1012F000844294BF0020012003B0F0BDAB8ADB0024 +:10130000083BDB08B3700824E8E7FB1C0093214688 +:1013100000230822284601F09DFD08340137DEE74E +:10132000201A18BF0120E7E7F7B50023047F0091DA +:101330000E4608221946054601F08CFD731CC4B9FF +:101340000822009311462346284601F083FD10240D +:10135000012372785F1C013B934211D32B7FA88A33 +:101360000734E408BBB9844294BF0020012003B0D5 +:10137000F0BDAB8ADB00083BDB0873700824E7E7AD +:10138000F3190093214600230822284601F062FD4C +:1013900008343B46DDE7201A18BF0120E7E70000CC +:1013A000F8B50E4605461446002181223046FFF767 +:1013B0005FFE2B4608220021304601F087FE7CB9F3 +:1013C0006B1C07220821304601F080FE0F24012308 +:1013D0006A785F1C013B934204D3E01DC008F8BD4E +:1013E0000824F4E7EB1921460822304601F06EFE8E +:1013F00008343B46ECE70000F8B50E4605461446B7 +:101400000021CE223046FFF733FE2B462822002152 +:10141000304601F05BFE7CB905F108030822282163 +:10142000304601F053FE30242F462A7A7B1B93422C +:1014300004D3E01DC008F8BD2824F5E707F109032F +:1014400021460822304601F041FE08340137ECE71E +:10145000F7B5047F00910E460123102200210546B6 +:1014600001F0F8FCC4B9B31C0093092223461021F3 +:10147000284601F0EFFC192437467288BB1B9A42BC +:1014800011D82B7FA88A0734E408BBB9844294BFE3 +:101490000020012003B0F0BDAB8ADB00103BDB086D +:1014A00073801024E8E73B1D0093214600230822A7 +:1014B000284601F0CFFC08340137DEE7201A18BFB8 +:1014C0000120E7E730B5094D0A4491420DD011F8EB +:1014D000013B5840082340F30004013B2C4013F02B +:1014E000FF0384EA5000F6D1EFE730BD2083B8ED6A +:1014F000F7B5384A106851686B4603C36A463649E7 +:101500003648082303F0ACF80446002833D10A25F6 +:10151000334A106851686B4603C36A4631492F4805 +:10152000082303F09DF80446002849D00369B3F569 +:101530005C3F45D8B0F8661041F2B54291423FD1C8 +:10154000294A024402F15C018B4239D35C3B2349B6 +:1015500000209E1AFFF7B6FF3246074604F16401E9 +:101560000020FFF7AFFFA3689F4229D1E3689842AC +:1015700008BF002524E00369B3F55C3F27D8418B01 +:1015800041F2B542914220D1174A024402F11001C2 +:101590008B4218D3103B114900209D1AFFF792FF90 +:1015A0002A46064604F118010020FFF78BFFA368C6 +:1015B0009E4202D1E368984201D00D25A8E700259C +:1015C000284603B0F0BD1025A2E70C25A0E70B25A7 +:1015D0009EE700BFD8460008DC6F030000900008BB +:1015E000E1460008906F03000870FFF710B5037C18 +:1015F000044613B9006803F01BF8204610BD000034 +:101600000023BFF35B8FC360BFF35B8FBFF35B8FC0 +:101610008360BFF35B8F7047BFF35B8F0068BFF3DE +:101620005B8F704770B505460C30FFF7F5FF05F18D +:10163000080604463046FFF7EFFFA04206D93046C1 +:101640006D68FFF7E9FF2544281A70BD3046FFF7A3 +:10165000E3FF201AF9E7000070B50546406898B12D +:1016600005F10800FFF7D8FF05F10C0604463046E7 +:10167000FFF7D2FF8442304694BF6D680025FFF724 +:10168000CBFF013C2C44201A70BD000038B50C463D +:101690000546FFF7C7FFA04210D305F10800FFF78A +:1016A000BBFF04446868B4FBF0F100FB1144BFF3D6 +:1016B0005B8F0120AC60BFF35B8F38BD0020FCE77F +:1016C0002DE9F041144607460D46FFF7C5FF844259 +:1016D00028BF0446D4B1B84658F80C6B4046FFF713 +:1016E0009BFF3044286040467E68FFF795FF331A21 +:1016F0009C4203D86C600120BDE8F0816B60A41BA4 +:101700003B68AB602044E8600220F5E72046F3E741 +:1017100038B50C460546FFF79FFFA04210D305F1F0 +:101720000C00FFF779FF04446868B4FBF0F100FB9C +:101730001144BFF35B8F0120EC60BFF35B8F38BDBA +:101740000020FCE72DE9FF41884669460746FFF780 +:10175000B7FF6C4606B204EBC6060025B44209D0BA +:101760006268206808EB0501FFF770FC63680834C5 +:101770001D44F3E729463846FFF7CAFF284604B060 +:10178000BDE8F081F8B505460C300F46FFF744FF81 +:1017900005F1080604463046FFF73EFFA0423046FA +:1017A00088BF6C68FFF738FF201A386020B13046D8 +:1017B0002C68FFF731FF2044F8BD000073B51446D4 +:1017C00006460D46FFF72EFF844228BF04460190CF +:1017D000DCB101A93046FFF7D5FF019B33B9326870 +:1017E000C5E90233C5E9002401200CE09C4238BF62 +:1017F00001942860019868608442F5D93368AB6031 +:10180000241AEC60022002B070BD2046FBE7000005 +:101810002DE9FF410F466946FFF7D0FF6C4600B245 +:1018200004EBC0050026AC4209D0D4F8048054F87B +:10183000081BB8194246FFF709FC4644F3E7304657 +:1018400004B0BDE8F081000038B50546FFF7E0FFC1 +:10185000044601462846FFF719FF204638BD000020 +:101860007047000010B41346026814680022A446B2 +:101870005DF8044B6047000000F5805090F8590473 +:101880007047000000F5805090F852047047000047 +:1018900000F5805090F958047047000050207047C0 +:1018A000302383F3118800F58052D2F89C34D2F8AB +:1018B00098041844D2F894341844D2F87C3418446C +:1018C000D2F88C341844D2F888341844002383F3B7 +:1018D0001188704700F58050C0F8541401207047FB +:1018E00038B5C26A936923F001039361044600F09E +:1018F0007FFE0546E36A9B69DB0706D500F078FEAC +:10190000431BFA2BF6D9002004E004F58054012093 +:1019100084F8520438BD00002DE9F04F0C4600F564 +:10192000805185B01F4691F85234BDF83890054675 +:1019300090469BB1D1F878340133C1F878342368EC +:10194000980006D4237B082B0BD9627B0AB10F2B9E +:1019500007D9D1F87C340133C1F87C344FF0FF3023 +:1019600010E0302383F31188EB6AD3F8C42012F41B +:10197000001B0AD0D1F880340133C1F88034002034 +:1019800080F3118805B0BDE8F08FD3F8C43020682B +:10199000C3F3014A6B6A4822002812FB0A33B4BF22 +:1019A00040F08040800418602268520044BF40F03C +:1019B00000501860207B4FEA0A6242EA00425A60F7 +:1019C000607B4FEA4A1610B342F440125A60D1F8D5 +:1019D000B0240132C1F8B024AA1902F58352117B58 +:1019E00041F020011173207B039300F05DFE039B07 +:1019F000033080105FFA8BF282420BF1010B0DDA9B +:101A000004EB820103EB820249689160F2E7AA19B4 +:101A100002F58352117B60F34511E3E7EB6A012283 +:101A200002FA0AF2C3F8CC2005EB4A11AB1903F510 +:101A3000825301F58251C3E904871831234604F12A +:101A40000C0253F8040B41F8040B9342F9D11B88A4 +:101A50000B802E4441F2680346F803A006F5805639 +:101A600009F0030396F86C2043F0100322F01F02E4 +:101A7000134386F86C30002383F31188CDF800906F +:101A800042463B462146284600F0D4FD012079E736 +:101A900013B500F580540191606CFFF7DDFD1F2840 +:101AA0000AD90199606C2022FFF74CFEA0F12003B7 +:101AB0005842584102B010BD0020FBE708B5302362 +:101AC00083F3118800F58050406CFFF799FD0023E7 +:101AD00083F3118808BD0000002202608281426009 +:101AE0008260704710B500220023C0E90023002364 +:101AF000044603810C30FFF7EFFF204610BD0000C5 +:101B00002DE9F0479A4688B007468846914630232B +:101B100083F3118807F580546846FFF7E3FF606C94 +:101B2000FFF780FD1F282DD9606C20226946FFF742 +:101B30008BFE202826D194F852341BB303AD4446C3 +:101B400005AB2E4603CE9E4220606160354604F10F +:101B50000804F6D130682060B388A380DDE9002353 +:101B6000C9E90023BDF80830AAF80030002383F348 +:101B7000118853464A464146384608B0BDE8F0470A +:101B800000F046BD002080F3118808B0BDE8F08762 +:101B90002DE9F84F00230646C0E90133284B46F8EB +:101BA000303B00F5815405468846374610343846A8 +:101BB0002037FFF797FFA742F9D105F580544FF47E +:101BC000805326630026C4E90D366764012305F5BA +:101BD000835705F5A359E66384F8403084F848300C +:101BE000103709F110094FF0000A4FF0000B47E9D8 +:101BF00008ABA7F11800FFF76FFF203747F8286CF4 +:101C00004F45F4D184F85884A4F85A64A4F85C646D +:101C1000A4F85E6484F86064A4F86264A4F8646460 +:101C2000A4F8666484F86864B8F1000F02D005482F +:101C300000F0D8FC044BEB622846BDE8F88F00BFEB +:101C400008470008EC4600080064004010B5044B4B +:101C5000197804464A1C1A70FFF79AFF204610BDF7 +:101C60002D4E00202DE9F84315460C4600295CD086 +:101C7000022001F019FE2E49B0FBF4F78C428CBF14 +:101C80000A2111214B1EB7FBF1F601FB1671DAB2E6 +:101C900021B1022B1946F5D8002032E0731EB3F5AE +:101CA000806FF9D2C2EBC20808F103014FEAE10EDE +:101CB000C1F3C701A2EB010C0EF101094FF47A73D5 +:101CC0005FFA8CF70EFB033E59FA8CFCBEFBFCFC62 +:101CD000BCF5617F17DC1FFA8CF34A1C57FA82F2BD +:101CE0007243B0FBF2F08442D6D14A1E0F2AD3D8F9 +:101CF0007A1E072AD0D801202B806E802871697146 +:101D0000AF71BDE8F88308F1FF314FEAE10CC1F390 +:101D1000C701521A0CF1010ED7B20CFB03335EFA65 +:101D200082F2B3FBF2F39BB2D7E70846E9E700BFC4 +:101D30003F420F0030B50D4B0D4D05201C786C4314 +:101D40008C420ED15978518099785171D97891711E +:101D5000197911715B7903EB83035B001380012018 +:101D600030BD013803F10603E8D1F9E74847000820 +:101D700040420F000B4B10B54FF454720446002143 +:101D80001846FFF775F9084BA3614033E361D83378 +:101D90002362F0336362E36A60610022C3F8C0200B +:101DA00010BD00BF00A4004070A400402DE9F04F1A +:101DB00000F580551F4695F85834012B89B004462C +:101DC0008946904604D90026304609B0BDE8F08F18 +:101DD0009A4A52F8231009B942F823009848C4F8E7 +:101DE0000C900178277499B9302383F31188954BAF +:101DF0009A6D42F000729A659A6B42F000729A6393 +:101E00009A6B22F000729A630123037081F31188A8 +:101E100095F851647EB9302383F31188032115208E +:101E200001F056FE0321162001F052FE012385F831 +:101E3000513486F31188302383F31188E26A936961 +:101E400023F01003936100F0D3FB8246E36A9E699E +:101E500016F0080609D000F0CBFBA0EB0A03FA2B22 +:101E6000F4D9002686F31188AEE79A6942F00102A0 +:101E70009A6100F0BDFB8246E36A9A69D00706D4F6 +:101E800000F0B6FBA0EB0A03FA2BF5D9E9E79A6953 +:101E900042F002029A61E36A4FF0000AC3F854A0CC +:101EA0008AF31188686CFFF7ABFB04F5825B0BF1DA +:101EB000100B202200216846FFF7DAF802A8FFF78E +:101EC0000BFECDF818A06A460BEB06030DF1180EB9 +:101ED0009446BCE80300F44518605960624603F17B +:101EE0000803F5D1DCF80000186020369CF80420C7 +:101EF0001A71B6F5806FDCD1002304F5A25285F883 +:101F0000503485F853341A3249462046FFF7AAFE6A +:101F1000064690B9E26A936923F00103936100F0E9 +:101F200067FB0546E36A9B69D9077FF54CAF00F074 +:101F30005FFB431BFA2BF5D945E795F85E34C5F8EE +:101F40006C94591E95F85F34E26A013B1B0243EA28 +:101F5000416395F8601401390B43B5F85C140139FD +:101F600043EA0143D361B8F1000F36D004F5A35220 +:101F7000023241462046FFF7DDFE90B9E26A9369DE +:101F800023F00103936100F033FB0546E36A9B698C +:101F9000DA077FF518AF00F02BFB431BFA2BF5D9BE +:101FA00011E795F86724C5F87084511E95F86824E8 +:101FB000E36A013A120142EA012295F866140139F6 +:101FC0000A43B5F86414013942EA014242F40002BE +:101FD000DA60E36A4FF420629A642046FFF7CAFE93 +:101FE000002385F85934E36A6FF040421A65E36ACA +:101FF000154A5A65E36A44229A65E36A0722C3F8E0 +:10200000DC20E36A03229742DA653FF4DDAEE26A40 +:10201000936923F00103936100F0EAFA0746E36A4B +:102020009B69DB0705D500F0E3FAC31BFA2BF6D951 +:10203000C9E6012385F85234C6E600BF284E0020C9 +:102040002C4E0020001002409B0008002DE9F04FAC +:10205000054689B090469946002741F2680A00F586 +:102060008056EB6AD3F8D430FB40D80751D505EB46 +:10207000471252444FEA471B1379190749D4D6F83F +:1020800084340133C6F8843405F5A553C3E90089C7 +:1020900013799A0648BFD6F8B43405EB0B0248BF53 +:1020A0000133524448BFC6F8B434137943F00803EF +:1020B0001371DB0722D596F85334FBB105F5825432 +:1020C000183468465C44FFF70DFD03AB04F1080CBF +:1020D000206861681A4603C2083464451346F7D184 +:1020E00020681060A2889A800123ADF808302B6820 +:1020F000CDE90089DB6B694628469847D6F8A834B5 +:10210000D6F854040133C6F8A83410B103681B692B +:1021100098470137202FA4D109B0BDE8F08F000007 +:102120002DE9F04F8DB004460F4600F063FA824669 +:102130008946002F56D1E36AD3F89020920141BF1F +:1021400004F58051D1F898240132C1F89824D3F8CD +:102150009020160703D100200DB0BDE8F08FD3F812 +:102160009050E669C5F30125482303FB0566E84660 +:102170004046FFF7B1FC326851004ABF22F060438D +:10218000C2F38A4343F00043920048BF43F08043C8 +:102190000093736813F400131FBF04F580520123EA +:1021A0008DF80D30D2F8B8340EBF8DF80D300133F4 +:1021B000C2F8B834F38803F00F038DF80C304FF0F9 +:1021C000000B9DF80C0000F06FFA5FFA8BF3984259 +:1021D00020D9F2180CA90B44127A03F82C2C0BF11D +:1021E000010BEEE7012FB6D1E36AD3F898209501F1 +:1021F00041BF04F58051D1F898240132C1F89824E8 +:10220000D3F898201007A6D0D3F89850266AC5F3C3 +:102210000125A9E7EFB9E36AC3F8945004A8FFF7D2 +:1022200061FC98E80F0007AD07C52B800023ADF8CF +:10223000183023682046CDE904A9DB6B04A9984730 +:1022400004F5805458B1D4F890340133C4F8903474 +:1022500082E7012F04BFE36AC3F89C50DEE7D4F89D +:1022600094340133C4F89434012075E72DE9F0412A +:1022700005460F4600F58054012639462846FFF7EB +:102280004FFF10B184F85364F7E7D4F8A834D4F8BA +:1022900054040133C4F8A83420B10368BDE8F04108 +:1022A0001B691847BDE8F081F0B5C36A1A6C12F4D7 +:1022B0007F0F2BD000F580541B6CC4F8AC3441F276 +:1022C0006805002347194FF0010C00EB43122A4424 +:1022D0005E01117911F0020F15D0490713D4B959D5 +:1022E000C66AD6F8C8E00CFA01F111EA0E0F0AD05E +:1022F000C6F8D010117941F004011171D4F88C2482 +:102300000132C4F88C240133202BDED1F0BD000053 +:1023100010B5254C254B226802B338B31A6D12064E +:102320000ED580221A6500F065F950EA01020B46CD +:1023300002D0013861F1000302462068FFF786FEF3 +:102340001A4A136D1B032AD523684FF4002103F5A5 +:1023500080531165012283F8592420E001221A6577 +:1023600008221A654FF480621A6510BD196DC807FE +:1023700002D4196D890705D503211965104600217E +:10238000FFF774FF094B1A6D100702D41A6DD106BE +:1023900005D518221A6520680121FFF767FF20681C +:1023A000BDE81040FFF780BF284E002000640040C9 +:1023B00008B5302383F31188FFF776FF002383F3FA +:1023C000118808BDC36AD3F8C40080F40010C0F3BC +:1023D0004050704708B5302383F3118800F58050D2 +:1023E000406CFFF71FF9002383F3118843090CBFEA +:1023F0000120002008BD000000F5805393F8592407 +:1024000062B1C16A8A6922F001028A61D3F89C2410 +:102410000132C3F89C24002283F85924704700003D +:102420002DE9F743302181F3118800F582511031F5 +:10243000002541F2680E4FF0010800F5805C00EBCA +:1024400045147444267977071CD4F6061AD5D0F8BB +:102450002C908E69D9F8C87008FA06F63E4211D061 +:102460004F6801970F689742019F9F410AD2C9F8B0 +:10247000D060267946F004062671DCF888440134E1 +:10248000CCF888440135202D01F12001D7D100235B +:1024900083F3118803B0BDE8F0830000F8B51E4651 +:1024A000002313700F4605461446FFF793FF80F094 +:1024B000010038701EB12846FFF784FF2070F8BD78 +:1024C0002DE9F04F85B09946DDE90EA30D46029344 +:1024D0001378019391F800B08046164600F08AF810 +:1024E0002B7804460F4613B93378002B41D022468F +:1024F0003B464046FFF794FFFFF75AFFFFF77CFF8C +:102500004B4632462946FFF7C9FF2B7833B1BBF162 +:10251000000F03D0012005B0BDE8F08F337813B170 +:10252000019B002BF6D108F580530393029B544581 +:1025300077EB03031DD2039BD3F85404C8B103689F +:10254000AAEB04011B6898474B4632462946404691 +:10255000FFF7A4FF2B7813B1BBF1000FDAD133786A +:1025600013B1019B002BD5D100F044F804460F466F +:10257000DCE70020CFE7000008B50020FFF7C8FE29 +:10258000BDE8084001F050B808B50120FFF7C0FED3 +:10259000BDE8084001F048B800B59BB0EFF30981F1 +:1025A00068226846FEF752FDEFF30583014B9B6BF3 +:1025B000FEE700BF00ED00E008B5FFF7EDFF00000B +:1025C00000B59BB0EFF3098168226846FEF73EFD37 +:1025D000EFF30583014B5B6BFEE700BF00ED00E00E +:1025E000FEE700000FB408B5029801F025FBFEE7F6 +:1025F00001F006BE01F0E8BD13B56C4684E80600A4 +:10260000031D94E8030083E80500012002B010BD1B +:1026100073B58568019155B11B885B0707D4D0E974 +:1026200000369B6B9847019AC1B23046A8470120FB +:1026300002B070BDF0B5866889B005460C465EB143 +:10264000BDF838305B070AD4D0E900379B6B984758 +:102650002246C1B23846B047012009B0F0BD002281 +:102660000023CDE900230023ADF808300A4603AB70 +:1026700001F10806106851681C4603C40832B242D2 +:102680002346F7D1106820609288A280FFF7B2FF3E +:102690000423ADF808302B68CDE90001DB6B6946F7 +:1026A00028469847D8E70000082817D909280CD0F1 +:1026B0000A280CD00B280CD00C280CD00D280CD0DC +:1026C0000E2814BF4020302070470C207047102087 +:1026D0007047142070471820704720207047000072 +:1026E0002DE9F041456A15B94162BDE8F0814B68BA +:1026F00023F06047C3F38A464FEAD37EC3F3807862 +:1027000016EA230638BF3E46AC462B465A68BEEB57 +:10271000D27F22F060440AD0002A18DAA40CB44216 +:1027200017D19D420FD10D60DEE71346EEE7A742B9 +:1027300007D102F08044C2F3807242450BD054B1FD +:10274000EFE708D2EDE7CCF800100B60CDE7B4421C +:1027500001D0B442E5D81A689C46002AE5D1196038 +:10276000C3E700002DE9F047089D01F007044FEA98 +:10277000D508224405F0070500EBD1004FF47F494E +:10278000944201D1BDE8F08704F0070705F0070A7D +:1027900057453E4638BF5646C6F10806111B8E42C5 +:1027A00028BF0E46E10808EBD50E415C13F80EC0B9 +:1027B000B94029FA06F721FA0AF1FFB28CEA0101C1 +:1027C00047FA0AF739408CEA010C03F80EC034448A +:1027D0003544D5E780EA0120082341F2210201B205 +:1027E0004000002980B203F1FF33B8BF504013F01E +:1027F000FF03F4D17047000038B50C468D18A54290 +:1028000000D138BD14F8011BFFF7E4FFF7E7000023 +:1028100042684AB1136843604389818901339BB29E +:102820009942438138BF83811046704770B588B0A4 +:10283000202204460D4668460021FEF719FC20467A +:102840000495FFF7E5FF024658B16B46054608AE12 +:102850001C4603CCB44228606960234605F1080594 +:10286000F6D1104608B070BD082817D909280CD039 +:102870000A280CD00B280CD00C280CD00D280CD01A +:102880000E2814BF4020302070470C2070471020C5 +:1028900070471420704718207047202070470000B0 +:1028A000082817D90C280CD910280CD914280CD9B1 +:1028B00018280CD920280CD930288CBF0F200E20C6 +:1028C0007047092070470A2070470B2070470C2082 +:1028D00070470D20704700002DE9F843078C072F43 +:1028E00004461ED9D0E9029800254FF6FF73C5F1C2 +:1028F0002006A5F1200029FA05F108FA06F628FAC3 +:1029000000F031430143C9B21846FFF763FF0835B1 +:10291000402D0346EBD1E1693A46BDE8F843FFF7A5 +:102920006BBF4FF6FF70BDE8F883000010B54B6831 +:1029300023B9CA8A63F30902CA8210BD04691A68FE +:102940001C600361C38A013BC3824A60EFE7000059 +:102950002DE9F84F1D46CB8A0F46C3F3090105291F +:10296000814692460B4630D00020AAB207F11A04E5 +:102970009EB2042E1FFA80F80FD8904503F1010390 +:1029800006D3FB8A0A4462F30903FB8201201AE0A2 +:102990001AF80060E6540130EAE79045F1D2A1F15F +:1029A000050B1C237C68BBFBF3F203FB12BB1FFA75 +:1029B0008BF6002C45D14846FFF72AFF044638B96C +:1029C00078606FF00200BDE8F88F4FF00008E6E78E +:1029D000002606607860ADB24FF0000B454510D977 +:1029E0000AEB0803221D13F8011B9155B1B208F13F +:1029F00001081B291FFA88F82BD0454506F101066E +:102A0000F1D8FB8AC3F30902154465F30903BCE757 +:102A1000013292B21C462368002BF9D16B1F0B4484 +:102A20001C21B3FBF1F301339BB29A42D3D2BBF129 +:102A3000000FD0D14846FFF7EBFE20B9C4F800B034 +:102A4000BFE70122E7E7C0F800B05E462060044619 +:102A5000C1E74545D5D94846FFF7DAFE08B92060F9 +:102A6000AFE7C0F800B0002620600446B6E70000DB +:102A70002DE9F04F2DED028B1C4683B05B6901926E +:102A800007468846002B00F09A80238C2BB1E26920 +:102A9000002A00F09480072B35D807F10C00FFF7CF +:102AA000B7FE054638B96FF00205284603B0BDEC05 +:102AB000028BBDE8F08F14220021FEF7D9FA228C98 +:102AC000E16905F10800FEF7C1FA208C013080B2FF +:102AD000FFF7E6FEFFF7C8FE013880B22084013020 +:102AE00028746369228C1B782A4403F01F0363F067 +:102AF0003F0348F000411372384669602946FFF7EA +:102B0000EFFD0125D1E700F10C034FF0000908EEBD +:102B1000103A4FF0800A4E464D4618EE100AFFF765 +:102B200077FE83460028BED014220021FEF7A0FACB +:102B3000002E3AD1019BABF8083002220BF1080EAF +:102B40001FFA82FC0CF10100BCF1060F218C80B24F +:102B500001D88E422BD3FFF7A3FEFFF785FE6269F3 +:102B60001278013802F01F028E4208BF4FF0400A6F +:102B700042EA49121BFA80F14AEA020A013048F09F +:102B8000004281F808A08BF81000CBF804205946C9 +:102B90003846FFF7A5FD238C0135B3422DB289F0ED +:102BA00001094FF0000AB8D17FE70022C6E7E169CA +:102BB000895D0EF802100136B6B20132C0E76FF03F +:102BC000010572E7F8B515460E463022002104468D +:102BD0001F46FEF74DFA069B6360B5F5001F079B85 +:102BE000A76034BF6A094FF6FF72A36297B2E6612D +:102BF00004F1100000239A4206D800230360A78244 +:102C0000E3822383E360F8BD06600133304620365B +:102C1000F1E7000003781BB94BB2002BC8BF01706D +:102C20007047000000787047F8B50C46C969074640 +:102C300011B9238C002B37D1257E1F2D34D838783D +:102C400028BB228C072A2CD8268A36F003032BD1E6 +:102C50004FF6FF70FFF7D0FD20F001003102400475 +:102C600041EA0561400C41EA40254FF6FF722346D8 +:102C700029463846FFF7FCFE002807DD6269137815 +:102C80000133DBB21F2B88BF00231370F8BD218AEC +:102C90002D0645EA012505432046FFF71DFE0246A5 +:102CA000E5E76FF00300F1E76FF00100EEE70000E9 +:102CB00070B58AB0044616460021282268461D4693 +:102CC000FEF7D6F9BDF83830ADF810300F9B0593FC +:102CD0009DF840308DF81830119B07936946BDF878 +:102CE0004830ADF820302046CDE90265FFF79CFF63 +:102CF0000AB070BD2DE9F041D36905460C46164671 +:102D00000BB9138C5BBB377E1F2F28D895F800803A +:102D1000B8F1000F26D03046FFF7DEFD33782102F0 +:102D200041EAC33141EA0801338A41EA076141EAD5 +:102D300003410246334641F080012846FFF798FEE2 +:102D400000280ADD3378012B07D17269137801332B +:102D5000DBB21F2B88BF00231370BDE8F0816FF03A +:102D60000100FAE76FF00300F7E70000F0B58BB061 +:102D700004460D4617460021282268461E46FEF7E7 +:102D800077F99DF84C305A1E534253418DF800306C +:102D90009DF84030ADF81030119B05939DF84830F8 +:102DA0008DF81830149B07936A46BDF85430ADF87F +:102DB000203029462046CDE90276FFF79BFF0BB075 +:102DC000F0BD0000406A00B104307047436A1A68E1 +:102DD000426202691A600361C38A013BC382704781 +:102DE0002DE9F041D0F82080194E14461D46414689 +:102DF000002709B9BDE8F081D1E90223A21A65EBE9 +:102E00000303964277EB03031ED2036A8B420DD174 +:102E1000FFF78CFD036A1B68036203690B60C38ABA +:102E20000161016A013BC3828846E2E7FFF77EFD4C +:102E30000B68C8F8003003690B60C38A0161013B6D +:102E4000C382D8F80010D4E788460968D1E700BFEC +:102E500080841E002DE9F04F8BB00D46DDF85090B8 +:102E600014469B468046002800F01981B9F1000FF6 +:102E700000F01581531E3F2B00F21181012A03D16E +:102E8000BBF1000F40F00B810023CDE90833B8F807 +:102E90001430B5EBC30F4FEAC30703D300200BB0C8 +:102EA000BDE8F08F2B199F42D8F80C303ABF7F1B3A +:102EB000FFB227461BB9D8F81030002B7AD0272D47 +:102EC0004ED8C5F12806B7424FF000032CBFF6B22A +:102ED0003E4600932946D8F8080008AB3246FFF773 +:102EE00041FCA7EB060A35445FFA8AFAB8F81430B9 +:102EF00003F10053053BDB000493D8F80C30039337 +:102F00002821039B13B1BAF1000F2CD1D8F810007F +:102F100040B1BAF1000F05D0009608AB5246691ACD +:102F2000FFF720FC38B2002FB8D066070AD00AABF2 +:102F300003EBD401624211F8083C02F0070213418E +:102F400001F8083C082C3CD9102C40F2B580202C0C +:102F500040F2B780BBF1000F00F09C80082334E002 +:102F6000BA460026C2E7049BE02B28BFE023069365 +:102F70000B44AB42059314D95A1B03980096924513 +:102F800034BF5246D2B2691A08AB04300792FFF739 +:102F9000E9FB079A1644AAEB020A1544F6B25FFA57 +:102FA0008AFA049B069A05999B1A0493039B1B6853 +:102FB0000393A6E70093D8F8080008AB3A462946E1 +:102FC000AEE7BBF1000F13D00123B4EBC30F6CD0FD +:102FD000082C12D89DF82030621E23FA02F2D50781 +:102FE00006D54FF0FF3202FA04F423438DF8203067 +:102FF0009DF8203089F8003051E7102C12D8BDF828 +:103000002030621E23FA02F2D10706D54FF0FF32BC +:1030100002FA04F42343ADF82030BDF82030A9F8BB +:1030200000303CE7202C0FD80899631E21FA03F3E7 +:10303000DA0705D54FF0FF3202FA04F40C43089486 +:10304000089BC9F800302AE7402C2BD0DDE9086541 +:10305000611EC4F12102A4F1210326FA01F105FA4F +:1030600002F225FA03F311431943CB0712D50122CB +:10307000A4F12003C4F1200102FA03F322FA01F1C2 +:10308000A240524243EA010363EB430332432B4322 +:10309000CDE90823DDE90823C9E90023FFE66FF045 +:1030A0000100FCE66FF00800F9E6082CA0D9102C0E +:1030B000B3D9202CEED8C3E7BBF1000FADD002236B +:1030C00083E7BBF1000FBBD004237EE730B5012AB4 +:1030D000144638BF0124402C85B028BF4024002569 +:1030E000012ACDE9025518D81B788DF808306307FE +:1030F0000AD004AB03EBD405624215F8083C02F099 +:103100000702934005F8083C00910346224600213F +:1031100002A8FFF727FB05B030BD082AE4D9102A22 +:1031200003D81B88ADF80830E1E7202A8DBFD3E92A +:1031300000231B680293CDE90223D8E710B5CB68C2 +:103140001BB98B600B618B8210BD04691A681C600F +:103150000361C38A013BC382CA60F0E703064CBF28 +:10316000C0F3C0300220704708B50246FFF7F6FFF3 +:10317000022806D15306C2F30F2001D100F003004C +:1031800008BDC2F30740FBE72DE9F04F93B0CDE94E +:1031900003230A6804461046FFF7E0FF022814BF25 +:1031A000C2F306260026002A0D46824680F2F281EE +:1031B00012F0C04940F0EE81097B002900F0EA815D +:1031C000022803D02378B34240F0E781C2F30463BE +:1031D0000693104602F07F030593FFF7C5FF059B9A +:1031E00029444FEA834848EA0A4848EA4668CE78C4 +:1031F00000230022CDE90823F309834648EA0008AA +:10320000029367D0059B009302466768534608A95E +:103210002046B847002800F0C381276A4FB94146CD +:1032200004F10C00FFF702FB074690B96FF00200B3 +:1032300054E03B6998450DD03F68002FF9D14146D5 +:1032400004F10C00FFF7F2FA07460028EED0236ADB +:103250003B60276297F817C006F01F08CCF3840C78 +:10326000ACEB08001FFA80FE0028B8BF0EF120006A +:10327000A8EB0C031FFA83FED7E90221B8BF00B206 +:10328000002B0793BEBF0EF120031BB2079352EA37 +:10329000010338D0039BDFF824E39A1A049B4FF014 +:1032A000000C63EB010196457CEB01032BD36B7B98 +:1032B00097F81AE0734519D1029B002B78D00128AA +:1032C00021DC7868F8B9DFF8F0C2944570EB0103AF +:1032D00016D337E0276A27B96FF00C0013B0BDE8AA +:1032E000F08F3B699845B5D03F68F4E7B24890420B +:1032F0007CEB010301D30020F0E7029B002BFAD006 +:10330000079B0F2B17DCFA7DB30002F0030203F0DA +:103310007C031343FB7539462046FFF707FB6B7BA5 +:10332000BB76029B3BB9FB7DC3F38402013262F39F +:103330008603FB75D0E76A7BBB7E9A42DBD1029B9A +:10334000002B35D0B309022B32D0039BBB60049B0A +:10335000FB60142200210DA8FDF78AFE039B0A934F +:10336000049B0B932B1D0C932B7BADF83EB0013BC4 +:10337000DBB2ADF83C30069B8DF84230059B8DF8F2 +:10338000433094F82C308DF840A083F001038DF881 +:1033900044308DF84180A3680AA920469847FB7DF8 +:1033A000C3F38403013303F01F039B02FB82A2E7F4 +:1033B000FB7DC6F34012B2EBD31F40F0F480C3F3A1 +:1033C0008403434540F0F280029A2B7BB609002A21 +:1033D0004DD0F2075DD4032B40F2EB80039BBB6022 +:1033E000049BFB602B7BAE1D033BDBB232463946B0 +:1033F00004F10C00FFF7ACFA00280CDA394620463D +:10340000FFF794FAFB7DC3F38403013303F01F033A +:103410009B02FB820AE7DDE90884AB883B834FF619 +:10342000FF73C9F12000A9F1200228FA09F104FA7A +:1034300000F0014324FA02F211431846C9B2FFF723 +:10344000C9F909F10809B9F1400F0346E9D1B88279 +:103450002A7B033AD2B23146FFF7CEF9FB7DB88220 +:10346000DA43C2F3C01262F3C713FB7543E786B9B0 +:103470002E1D013BDBB23246394604F10C00FFF74A +:1034800067FA0028BADB2A7BB88A013AD2B2314601 +:10349000E2E7F98AC1F30901013B0429DAB25BD8FA +:1034A000281D002307F11B069A4208D910F801CB0A +:1034B00006F801C0013101330529DBB2F4D10399CB +:1034C0000A9104990B91934207F11B010C9138BFAB +:1034D000043379680D9134BF55FA83F300230E93BA +:1034E000FB8AADF83EB0C3F309031A44069B8DF87E +:1034F0004230059B8DF8433094F82C30ADF83C20D9 +:1035000083F001038DF8443000238DF840A08DF83E +:1035100041807B602A7BB88A013A291DFFF76CF94C +:103520003B8BB882834203D1A3680AA920469847FF +:1035300020460AA9FFF702FEFB7DBA8AC3F3840383 +:10354000013303F01F039B02FB823B8B9A420CBFAB +:1035500000206FF01000C1E67B68002BAFD0052083 +:1035600001E01C3033461E68002EFAD1091A081DEE +:103570002E1D184401EB090CBCF11B0F5FFA89F3F7 +:103580009DD89A429BD916F8013B00F8013B09F1FE +:103590000109EFE76FF00900A0E66FF00A009DE671 +:1035A0006FF00B009AE66FF00D0097E66FF00E00DB +:1035B00094E66FF00F0091E640420F0080841E00F9 +:1035C000EFF3098305494A6B22F001024A6368332D +:1035D00083F30988002383F31188704700EF00E02C +:1035E000302080F3118862B60C4B0D4AD96821F463 +:1035F000E0610904090C0A43DA60D3F8FC200949A8 +:1036000042F08072C3F8FC200A6842F001020A60AE +:103610002022DA7783F82200704700BF00ED00E037 +:103620000003FA05001000E010B5302383F3118881 +:103630000E4B5B6813F4006314D0F1EE103AEFF315 +:103640000984683C4FF08073E361094BDB6B2366B0 +:1036500084F3098800F0BAFA10B1064BA36110BDDB +:10366000054BFBE783F31188F9E700BF00ED00E0AD +:1036700000EF00E03F03000842030008434B4FF413 +:10368000007270B51A605A6912F4C06FFBD1404BDA +:103690009A6802F00C02042A20D01A6842F4807260 +:1036A0001A601A685205FCD501229A609A6802F0E5 +:1036B0000C02042AFAD13749374A0A600A6812F024 +:1036C0000F02FBD1C3F8982063221A601A68960390 +:1036D000FCD42E4A4FF48071C2F88010C468E50310 +:1036E00006D51A6842F480321A601A689103FCD534 +:1036F000C269D20709D5D3F8982042F00102C3F875 +:103700009820D3F898209607FBD54269DA6044F4F4 +:1037100080721A6004F0807111B11A689501FBD5AE +:10372000996802691B4E22F0030501F00301294349 +:10373000996085693560316869400907FBD1134993 +:1037400005680D6046684E608068C1F880006E04B0 +:1037500017D448698505FCD4996802F0030021F06C +:1037600003010143996092009968514011F00C0FD8 +:10377000FAD1E2055EBF1A6822F480721A60002056 +:1037800070BD48698005FCD5E6E700BF00700040C9 +:1037900000100240002002400006040008B500F0BE +:1037A00083F9BDE8084000F05BB9000010B5394C62 +:1037B0003948A36A4FF0FF32A262A36A0023A362D2 +:1037C000A16AE16A61F07F01E162E16A01F07F01D3 +:1037D000E162E16A216B2263216B2363216BA16BA0 +:1037E000A263A16BA363A16BE16BE263E16BE36393 +:1037F000E16B216C2264226C2364226C226E42F005 +:1038000001022266D4F8802022F00102C4F8802050 +:10381000D4F88020A26D42F08052A265A26F22F0FF +:103820008052A267A26F1D4A4FF400419160D3609D +:10383000136253629362D362136353639363D363DC +:10384000136453649364D36413655365116841F43E +:1038500080711160D4F8902012F4407F1EBF4FF4A5 +:103860008032C4F89020C4F890300D4A0023A36041 +:10387000C4F88820C4F89C30FFF700FF10B1094855 +:1038800000F0DAF9D4F8903023F00323C4F8903034 +:1038900010BD00BF001002407047000800700040DB +:1038A0005501005168470008014B53F8200070474C +:1038B00018230020074A08B5536903F00103536138 +:1038C00023B1054A13680BB150689847BDE808401A +:1038D000FFF7AABE00040140C4500020074A08B503 +:1038E000536903F00203536123B1054A93680BB196 +:1038F000D0689847BDE80840FFF796BE0004014035 +:10390000C4500020074A08B5536903F0040353610B +:1039100023B1054A13690BB150699847BDE80840C7 +:10392000FFF782BE00040140C4500020074A08B5DA +:10393000536903F00803536123B1054A93690BB13E +:10394000D0699847BDE80840FFF76EBE000401400B +:10395000C4500020074A08B5536903F010035361AF +:1039600023B1054A136A0BB1506A9847BDE8084075 +:10397000FFF75ABE00040140C4500020164B10B59A +:103980005C6904F478725A61A30604D5134A936AF9 +:103990000BB1D06A9847600604D5104A136B0BB17F +:1039A000506B9847210604D50C4A936B0BB1D06B32 +:1039B0009847E20504D5094A136C0BB1506C98473F +:1039C000A30504D5054A936C0BB1D06C9847BDE8AC +:1039D0001040FFF729BE00BF00040140C450002082 +:1039E000194B10B55C6904F47C425A61620504D538 +:1039F000164A136D0BB1506D9847230504D5134A31 +:103A0000936D0BB1D06D9847E00404D50F4A136E47 +:103A10000BB1506E9847A10404D50C4A936E0BB1BC +:103A2000D06E9847620404D5084A136F0BB1506FEB +:103A30009847230404D5054A936F0BB1D06F98477C +:103A4000BDE81040FFF7F0BD00040140C450002065 +:103A500008B500F0F3FCBDE80840FFF7E5BD000045 +:103A6000062108B5084600F033F80621072000F0CB +:103A70002FF80621082000F02BF80621092000F07D +:103A800027F806210A2000F023F80621172000F06D +:103A90001FF80621282000F01BF8BDE80840072188 +:103AA0001C2000F015B800004FF0E02300225868F9 +:103AB0004FF0FF31930003F1604303F5614301329E +:103AC0009042C3F88010C3F88011F3D27047000011 +:103AD00000F1604303F561430901C9B283F80013A3 +:103AE000012200F01F039A4043099B0003F1604349 +:103AF00003F56143C3F880211A6070470023037502 +:103B0000826803691B6899689142FBD25A68036016 +:103B10004260106058607047002303758268036933 +:103B20001B6899689142FBD85A6803604260106034 +:103B30005860704708B50846302383F311880B7D21 +:103B4000032B05D0042B0DD02BB983F3118808BDAE +:103B50008B6900221A604FF0FF338361FFF7CEFFBD +:103B60000023F2E7D1E9003213605A60F3E7000066 +:103B7000FFF7C4BF054BD9680875186802681A605A +:103B8000536001220275D860FCF7C4BB384E002098 +:103B900030B50C4BDD684B1C87B004460FD02B466C +:103BA000094A684600F02AF92046FFF7E3FF009B28 +:103BB00013B1684600F02CF9A86907B030BDFFF7D3 +:103BC000D9FFF9E7384E0020353B0008044B1A684E +:103BD000DB6890689B68984294BF00200120704782 +:103BE000384E0020084B10B51C68D86822681A604F +:103BF000536001222275DC60FFF78EFF01462046EC +:103C0000BDE81040FCF786BB384E002038B5074CA5 +:103C100007490848012300252370656000F03CFC3B +:103C20000223237085F3118838BD00BFA050002007 +:103C300094470008384E002008B572B6044B18654A +:103C400000F0ACFA00F05CFB024B03221A70FEE7B6 +:103C5000384E0020A050002000F010B98B600223E5 +:103C600008618B82084670478368A3F1840243F899 +:103C7000142C026943F8442C426943F8402C094A49 +:103C800043F8242CC26843F8182C022203F80C2CA9 +:103C9000002203F80B2C044A43F8102CA3F1200057 +:103CA000704700BF2D030008384E002008B5FFF70D +:103CB000DBFFBDE80840FFF75BBF0000024BDB689D +:103CC00098610F20FFF756BF384E0020302383F352 +:103CD0001188FFF7F3BF000008B50146302383F3D6 +:103CE00011880820FFF754FF002383F3118808BDD3 +:103CF00010B503689C68A2420CD85C688A600B60AF +:103D00004C602160596099688A1A9A604FF0FF33BD +:103D1000836010BD1B68121BECE700000A2938BF46 +:103D20000A2170B504460D460A26601900F0AEFB64 +:103D300000F09AFB041BA54203D8751C2E460446CE +:103D4000F3E70A2E04D9BDE87040012000F0E4BB7F +:103D500070BD0000F8B5144B0D46D96103F1100198 +:103D600041600A2A1969826038BF0A2201604860EE +:103D70001861A818144600F07BFB0A2700F074FBBA +:103D8000431BA342064606D37C1C281900F07EFB89 +:103D900027463546F2E70A2F04D9BDE8F84001204E +:103DA00000F0BABBF8BD00BF384E0020F8B506469B +:103DB0000D4600F059FB0F4A134653F8107F9F42FF +:103DC00006D12A4601463046BDE8F840FFF7C2BF9B +:103DD000D169BB68441A2C1928BF2C46A34202D9CA +:103DE0002946FFF79BFF224631460348BDE8F840CD +:103DF000FFF77EBF384E0020484E002010B4C0E9C7 +:103E0000032300235DF8044B4361FFF7CFBF00009D +:103E100010B5194C236998420DD0D0E90032816861 +:103E200013605A609A680A449A60002303604FF056 +:103E3000FF33A36110BD2346026843F8102F53607F +:103E40000022026022699A4203D1BDE8104000F0CE +:103E500017BB936881680B44936000F005FB2269EF +:103E6000E1699268441AA242E4D91144BDE81040C5 +:103E7000091AFFF753BF00BF384E00202DE9F04765 +:103E8000DFF8BC8008F110072C4ED8F8105000F075 +:103E9000EBFAD8F81C40AA68031B9A423ED8144497 +:103EA000D5E900324FF00009C8F81C4013605A6091 +:103EB000C5F80090D8F81030B34201D100F0E0FA14 +:103EC00089F31188D5E9033128469847302383F3D5 +:103ED00011886B69002BD8D000F0C6FA6A69A0EB94 +:103EE00004094A4582460DD2022000F015FB00224B +:103EF000D8F81030B34208D151462846BDE8F04703 +:103F0000FFF728BF121A2244F2E712EB090938BF63 +:103F10004A4629463846FFF7EBFEB5E7D8F8103099 +:103F2000B34208D01444211AC8F81C00A960BDE8A7 +:103F3000F047FFF7F3BEBDE8F08700BF484E002012 +:103F4000384E002038B500F08FFA054AD2E908450E +:103F5000031B181945F10001C2E9080138BD00BF73 +:103F6000384E002000207047FEE700007047000038 +:103F70004FF0FF3070470000BFF34F8F024A1369C4 +:103F8000DB03FCD4704700BF0020024008B5094B9A +:103F90001B7873B9FFF7F0FF074B5A69002ABFBFC0 +:103FA000064A9A6002F188329A601A6822F48062A6 +:103FB0001A6008BDB8500020002002402301674568 +:103FC00008B50B4B1B7893B9FFF7D6FF094B5A691D +:103FD00042F000425A611A6842F480521A601A682C +:103FE00022F480521A601A6842F480621A6008BD96 +:103FF000B8500020002002407F289ABF00F5803092 +:10400000C0020020704700004FF4006070470000BD +:10401000802070477F2808B50BD8FFF7EDFF00F52B +:1040200000630268013204D104308342F9D10120D7 +:1040300008BD0020FCE700007F2810B504461FD80B +:10404000FFF79AFFFFF7A2FF0E4BF3221A6102223D +:104050005A615A6942EAC0025A615A6942F480328E +:104060005A61FFF789FF4FF40061FFF7C5FF00F0C9 +:1040700043F9FFF7A5FF2046BDE81040FFF7CABF90 +:10408000002010BD002002402DE9F84340EA020361 +:1040900013F00703144606D0304B40F241321A6049 +:1040A0000020BDE8F88385182D4A95420CD92B4A8B +:1040B00040F246311160F3E7031D1B684A689342E2 +:1040C00008D1083C08300831072C14D902680B6865 +:1040D0009A42F1D0FFF75AFFFFF74EFF214E083109 +:1040E0004FF001084FF00009012CA1F1080706D894 +:1040F000FFF766FF01E0002CECD10120D1E7C6F804 +:104100001480054651F8083C45F8043B51F8043C3E +:104110004360FFF731FF336943F001033361C6F8B1 +:104120001490026851F8083C9A420CD00B4B40F2B4 +:104130006E321A600C4B18600C4B1C600C4B1F60ED +:10414000FFF73EFFACE72D6851F8043C9D4201F1BA +:104150000801EBD1083C0830C6E700BFB45000208E +:104160000000040800200240A8500020B0500020A9 +:10417000AC500020084908B50B7828B11BB9FFF7EF +:1041800005FF01230B7008BD002BFCD0BDE80840E3 +:104190000870FFF715BF00BFB850002008B50649EA +:1041A000064800F0ABF8BDE808404FF480414FF0FE +:1041B000805000F0A3B800BF007F01000001002084 +:1041C000084600F035BA000038B5EFF311859DB907 +:1041D000EFF30584C4F30804302334B183F311886A +:1041E000FFF7B0FE85F3118838BD83F31188FFF720 +:1041F000A9FE84F3118838BDBDE83840FFF7A2BEA0 +:1042000038B5FFF7E1FF114C114AC00840EA417090 +:10421000A0FB025EC908A0FB040C1CEB050CA1FB73 +:1042200004404FF000035B41A1FB02121CEB040CA5 +:1042300043EB000011EB0E0142F10002411842F184 +:104240000000090941EA007038BD00BFCFF753E311 +:10425000A59BC4200244D2B2904200D17047431CB7 +:10426000800000F1804000F51450006841F8040B14 +:10427000D8B2F1E7124B10B5D3F89040240409D41A +:10428000D3F89040C3F89040D3F8904044F40044F1 +:10429000C3F890400B4C2368024443F480732360BE +:1042A000D2B2904200D110BD431C800000F180408A +:1042B00000F5145051F8044B0460D8B2F1E700BF88 +:1042C000001002400070004007B5012201A9002043 +:1042D000FFF7C0FF019803B05DF804FB13B5044677 +:1042E000FFF7F2FFA04205D0012201A900200194AE +:1042F000FFF7C0FF02B010BD70470000704700001C +:1043000070470000074B45F255521A6002225A606E +:1043100040F6FF729A604CF6CC421A60024B0122C2 +:104320001A70704700300040C0500020034B1B78CB +:104330001BB1034B4AF6AA221A607047C0500020F6 +:1043400000300040054B1A6832B902F1804202F594 +:104350000432D2F894201A60704700BFBC5000208D +:10436000024B4FF40002C3F8942070470010024043 +:1043700008B5FFF7E7FF024B1868C0F3407008BDAF +:10438000BC50002070470000FEE700000A4B0B48BD +:104390000B4A90420BD30B4BDA1C121AC11E22F0AF +:1043A00003028B4238BF00220021FCF761BE53F8A4 +:1043B000041B40F8041BECE714490008445100209A +:1043C00044510020445100200023054A194601337E +:1043D000102BC2E9001102F10802F8D1704700BFAA +:1043E000C450002008B5124B9A6D42F001029A6544 +:1043F0009A6F42F001029A670E4A9B6F936843F0EE +:10440000010393600620FFF74FFA0B4BB0FBF3F06C +:104410004FF080434FF0FF3201389862DA62002299 +:104420009A615A63DA605A6001225A611A6008BDC3 +:1044300000100240002004E040420F004FF0804294 +:1044400008B51169D3680B40D9B2C9439B07116104 +:1044500007D5302383F31188FFF7FEFB002383F396 +:10446000118808BDFFF7BEBF4FF08043586A704700 +:104470004FF08043002258631A610222DA607047CD +:104480004FF080430022DA60704700004FF0804315 +:1044900058637047FEE7000070B51B4B01630025B1 +:1044A000044686B0586085620E46FFF799F804F11D +:1044B0001003C4E904334FF0FF33C4E90635C4E9FF +:1044C0000044A560E562FFF7CFFF2B460246C4E932 +:1044D000082304F134010D4A256580232046FFF7A7 +:1044E000BDFB0123E0600A4A0375009272680192E5 +:1044F000B268CDE90223074B6846CDE90435FFF7E2 +:10450000D5FB06B070BD00BFA0500020A04700083A +:10451000A547000895440008024AD36A1843D062B0 +:10452000704700BF384E00204B6843608B68836043 +:10453000CB68C3600B6943614B6903628B6943625B +:104540000B6803607047000008B5204BDA6A42F040 +:104550007F02DA62DA6A22F07F02DA62DA6ADA6C01 +:1045600042F07F02DA64DA6E42F07F02DA66184ABD +:10457000DB6E11464FF09040FFF7D6FF02F11C01B1 +:1045800000F58060FFF7D0FF02F1380100F5806090 +:10459000FFF7CAFF02F1540100F58060FFF7C4FF86 +:1045A00002F1700100F58060FFF7BEFF02F18C019F +:1045B00000F58060FFF7B8FF02F1A80100F5806008 +:1045C000FFF7B2FFBDE80840FFF7F0B80010024067 +:1045D000AC47000808B500F009F8FFF717FBBDE885 +:1045E0000840FFF7AFBE00007047000008B5FFF7B6 +:1045F000D5F8FFF7E9FEFFF7F7FFBDE80840FFF742 +:1046000031BF00000B460146184600F003B8000019 +:1046100000F00EB810B5054C13462CB10A46014601 +:104620000220AFF3008010BD2046FCE70000000030 +:10463000024B01461868FFF7C3BD00BF40230020AE +:1046400010B501390244904201D1002005E0037801 +:1046500011F8014FA34201D0181B10BD0130F2E741 +:104660002DE9F041A3B1C91A17780144044603F1BA +:10467000FF3C8C42204601D9002009E00578BD426C +:1046800004F10104F5D10CEB0405D618A54201D1C3 +:10469000BDE8F08115F8018D16F801EDF045F5D073 +:1046A000E7E70000034611F8012B03F8012B002A6D +:1046B000F9D17047696E2E736965727261616572B6 +:1046C0006F73706163652E547275654E61765072BA +:1046D0006F2D47340000000040A2E4F164689106A9 +:1046E0000041A3E5F2656992070000004261642081 +:1046F00043414E496661636520696E6465782E00AA +:104700000000000000000000AD1D00086518000852 +:10471000C1240008D518000819190008011B000859 +:10472000E11800089D180008A11800087918000871 +:1047300061180008BD1A000885180008F92500084E +:1047400091180008911A000801040E05054B020299 +:104750000E05054B04010E05054B05010B04044B2A +:104760000801060303460000636C6B737763000067 +:104770000003000000000000000100000000010133 +:1047800003000000132831010407040001000000A9 +:104790006330000090470008904E0020A050002099 +:1047A0006D61696E0069646C650000001001942AF7 +:1047B000000000009AAAAAAA00001424FBFF00002F +:1047C000000000000090090000040000000000004C +:1047D000AAA6AAAA00000000DFFF00000000000057 +:1047E000000000000000000000000000AAAAAAAA21 +:1047F00000000000FFFF00000000000000000000BB +:104800000000000000000000AAAAAAAA0000000000 +:10481000FFFF00000000000000000000000000009A +:1048200000000000AAAAAAAA00000000FFFF0000E2 +:104830000000000000000000000000000000000078 +:10484000AAAAAAAA00000000FFFF000000000000C2 +:10485000000000000000000000000000AAAAAAAAB0 +:1048600000000000FFFF000000000000000000004A +:10487000B5140000000000000070030000000000FC +:10488000FE2A0100D2040000006889096D8BB9027C +:1048900000B4C404006889090068890900688909AE +:1048A000006889090068890900688909000000001A +:1048B0004423002000000000000000000000000071 +:1048C00000000000000000000000000000000000E8 +:1048D00000000000000000000000000000000000D8 +:1048E00000000000000000000000000000000000C8 +:1048F00000000000000000000000000000000000B8 +:1049000000000000000000000000000000000000A7 +:0449100000000000A3 :00000001FF diff --git a/Tools/bootloaders/Sierra-TrueNavPro_bl.bin b/Tools/bootloaders/Sierra-TrueNavPro_bl.bin old mode 100644 new mode 100755 index 156c1b588eeede..590377496982d7 Binary files a/Tools/bootloaders/Sierra-TrueNavPro_bl.bin and b/Tools/bootloaders/Sierra-TrueNavPro_bl.bin differ diff --git a/Tools/bootloaders/Sierra-TrueNorth_bl.bin b/Tools/bootloaders/Sierra-TrueNorth_bl.bin old mode 100644 new mode 100755 index f03c94358947ac..dea074102898d9 Binary files a/Tools/bootloaders/Sierra-TrueNorth_bl.bin and b/Tools/bootloaders/Sierra-TrueNorth_bl.bin differ diff --git a/Tools/bootloaders/Sierra-TrueSpeed_bl.bin b/Tools/bootloaders/Sierra-TrueSpeed_bl.bin old mode 100644 new mode 100755 index 216fbb887ca5ef..e771932c712148 Binary files a/Tools/bootloaders/Sierra-TrueSpeed_bl.bin and b/Tools/bootloaders/Sierra-TrueSpeed_bl.bin differ diff --git a/Tools/bootloaders/ZubaxGNSS_bl.bin b/Tools/bootloaders/ZubaxGNSS_bl.bin index a3eaf5eb2ec827..fdf74b4bccb199 100755 Binary files a/Tools/bootloaders/ZubaxGNSS_bl.bin and b/Tools/bootloaders/ZubaxGNSS_bl.bin differ diff --git a/Tools/bootloaders/ZubaxGNSS_bl.elf b/Tools/bootloaders/ZubaxGNSS_bl.elf index aaf300ca07199c..0219c9c985908f 100755 Binary files a/Tools/bootloaders/ZubaxGNSS_bl.elf and b/Tools/bootloaders/ZubaxGNSS_bl.elf differ diff --git a/Tools/bootloaders/ZubaxGNSS_bl.hex b/Tools/bootloaders/ZubaxGNSS_bl.hex index 48dccd0022483e..9ed6b6d79b60ca 100644 --- a/Tools/bootloaders/ZubaxGNSS_bl.hex +++ b/Tools/bootloaders/ZubaxGNSS_bl.hex @@ -1,27 +1,27 @@ :020000040800F2 -:10000000000200203D08000879290008492900085D -:1000100065290008492900085D2900083F080008F3 -:100020003F0800083F0800083F0800087139000831 -:100030003F0800083F0800083F0800087545000811 -:100040003F0800083F0800083F0800083F08000874 -:100050003F0800083F080008A9420008D5420008F0 -:10006000014300082D430008594300083F080008D9 -:100070003F0800083F0800083F0800083F08000844 -:100080003F0800083F0800083F080008FD28000856 -:1000900029290008392900083F080008854300087D -:1000A0003F0800083F0800083F0800083F08000814 -:1000B0003F0800083F0800083F0800083F08000804 -:1000C0003F0800083F0800083F0800083F080008F4 -:1000D0003F0800083F0800083F0800083F080008E4 -:1000E000ED4300083F0800083F0800083F080008EB -:1000F0003F0800083F0800083F0800083F080008C4 -:100100003F0800083F0800083F0800083F080008B3 -:100110003F0800083F0800083F0800083F080008A3 -:100120003F0800083F0800083F0800083F08000893 -:100130003F0800083F0800083F0800083F08000883 -:100140003F0800083F0800083F0800083F08000873 -:100150003F0800083F0800083F0800083F08000863 -:10016000AD150008000000000000000000000000C5 +:10000000000200203505000881260008512600085E +:100010006D260008512600086526000837050008EF +:10002000370500083705000837050008793600084D +:10003000370500083705000837050008A542000805 +:1000400037050008370500083705000837050008A0 +:100050003705000837050008D93F000805400008AB +:10006000314000085D40000889400008370500085D +:100070003705000837050008370500083705000870 +:100080003705000837050008370500080526000871 +:10009000312600084126000837050008B540000851 +:1000A0003705000837050008370500083705000840 +:1000B0003705000837050008370500083705000830 +:1000C0003705000837050008370500083705000820 +:1000D0003705000837050008370500083705000810 +:1000E0001D410008370500083705000837050008DE +:1000F00037050008370500083705000837050008F0 +:1001000037050008370500083705000837050008DF +:1001100037050008370500083705000837050008CF +:1001200037050008370500083705000837050008BF +:1001300037050008370500083705000837050008AF +:10014000370500083705000837050008370500089F +:10015000370500083705000837050008370500088F +:10016000A5120008000000000000000000000000D0 :100170004FF0FF0C1CEAD0521EBF1CEAD15392EA8A :100180000C0F93EA0C0F6FD01A4480EA010C400266 :1001900018BF5FEA41211ED04FF0006343EA5010C0 @@ -82,1082 +82,1037 @@ :100500009E03B3EB126209D44FEA002343F0004389 :1005100023FA02F070474FF00000704712F1610FAC :1005200001D1420202D14FF0FF3070474FF000007E -:10053000704700BF53B94AB9002908BF00281CBF43 -:100540004FF0FF314FF0FF3000F076B9ADF1080CFD -:100550006DE904CE00F006F8DDF804E0DDE90223E1 -:1005600004B070472DE9F047089E0D4604468846C2 -:10057000002B4DD18A42944668D9B2FA82F252B128 -:1005800001FA02F3C2F1200120FA01F10CFA02FC97 -:1005900041EA030894404FEA1C41B8FBF1F71FFA07 -:1005A0008CFE01FB178807FB0EF0230C43EA08437F -:1005B00098420AD91CEB030307F1FF3580F01E8136 -:1005C000984240F21B81023F63441B1AB3FBF1F0D7 -:1005D00001FB103300FB0EFEA4B244EA0344A6451F -:1005E0000AD91CEB040400F1FF3380F00981A64511 -:1005F00040F20681644402380021A4EB0E0440EA74 -:1006000007401EB10023D440C6E90043BDE8F0878F -:100610008B4208D9002E00F0EE800021C6E90005CB -:100620000846BDE8F087B3FA83F100294AD1AB420E -:1006300002D3824200F2FC80841A65EB030301209E -:100640009846002EE2D0C6E90048DFE702B9FFDE97 -:10065000B2FA82F2002A40F09180A1EB0C00012155 -:100660004FEA1C471FFA8CFEB0FBF7F307FB1300A1 -:10067000250C45EA00450EFB03F0A84208D91CEB07 -:10068000050503F1FF3802D2A84200F2CE804346AE -:100690002D1AB5FBF7F007FB10550EFB00FEA4B2B8 -:1006A00044EA0544A64508D91CEB040400F1FF35D3 -:1006B00002D2A64500F2B6802846A4EB0E0440EA1A -:1006C00003409EE7C1F120078B4022FA07FC4CEA69 -:1006D000030C25FA07FA4FEA1C49BAFBF9F820FA8D -:1006E00007F309FB18AA8D401FFA8CFE1D4300FA80 -:1006F00001F308FB0EF02C0C44EA0A44A04202FA73 -:1007000001F20BD91CEB040408F1FF3A80F0888059 -:10071000A04240F28580A8F102086444241AB4FB88 -:10072000F9F009FB104400FB0EFEADB245EA0444AB -:10073000A64508D91CEB040400F1FF356CD2A64590 -:100740006AD90238644440EA0840A0FB0295A4EB51 -:100750000E04AC42C846AE4656D353D0002E69D0E4 -:10076000B3EB080264EB0E0422FA01F304FA07F774 -:100770001F43CC40C6E90074002147E70CFA02FC95 -:10078000C2F1200125FA01F34FEA1C4720FA01F1DA -:1007900095400D43B3FBF7F107FB11331FFA8CFEB5 -:1007A000280C40EA034001FB0EF3834204FA02F4F2 -:1007B00008D91CEB000001F1FF382FD283422DD95C -:1007C00002396044C01AB0FBF7F307FB1300ADB267 -:1007D00045EA004503FB0EF0A84208D91CEB0505CD -:1007E00003F1FF3816D2A84214D9023B6544281AF7 -:1007F00043EA014138E73146304607E72F46E4E651 -:100800001846F9E64B45A9D2B9EB020865EB0C0E88 -:100810000138A3E74346EAE7284694E74146D1E793 -:10082000D0467BE76444023847E7023B65442FE744 -:10083000084606E73146E9E6704700BF02E000F0EF -:1008400000F8FEE772B6264880F30888254880F352 -:100850000988254825490860022080F31488BFF3E1 -:100860006F8F03F045FC03F0A9FC4FF05530204991 -:100870001B4A91423CBF41F8040BFAE71D49194A53 -:1008800091423CBF41F8040BFAE71B491B4A1C4B41 -:100890009A423EBF51F8040B42F8040BF8E70020DF -:1008A0001849194A91423CBF41F8040BFAE703F09A -:1008B00023FC03F085FC154C154DAC4203DA54F8CB -:1008C000041B8847F9E700F03FF8124C124DAC4288 -:1008D00003DA54F8041B8847F9E703F00BBC000067 -:1008E00000020020000800200000000808ED00E0E1 -:1008F000000100200002002010480008000800202D -:1009000080080020800800203025002060010008B9 -:100910006401000864010008640100082DE9F04F3B -:10092000C1F80CD0C3689D46BDE8F08F002383F367 -:1009300011882846A047002003F096F9FEE703F04F -:10094000F9F800DFFEE70000F8B500F041FE314A9B -:10095000536823F0E06343F0905343F480435360C3 -:1009600003F060FB074603F0AFFB0546C8BB2A4B0C -:100970009F4236D001339F4236D0284B27F0FF02EA -:100980009A4234D1F8B200F03BFC2E4642F2107489 -:1009900000F03CFC08B10024264601F00FF950B3EA -:1009A0000024032000F03EF8264635B11C4B9F4240 -:1009B00003D0002403F080FB2646002003F03CFB1C -:1009C0000EB100F045F800F08DFC00F003FE01F0E0 -:1009D000DBFF0546ACB900F0CDFC012003F04AF97D -:1009E000F8E72E460024D3E704460126D0E7064662 -:1009F00041F28834CCE7002CD7D04FF47A7401262A -:100A0000D3E701F0C1FF431BA342E4D900F020F873 -:100A1000DDE700BF00000140010007B0000008B0A2 -:100A2000263A09B0084B187003280CD8DFE800F00C -:100A300008050208022000F035BE022000F02ABEA0 -:100A40000022024B5A607047800800208408002072 -:100A500038B501F0B3F830B103221F4B1A700022F1 -:100A60001E4B5A6038BD1E4B1E4A19680131F9D021 -:100A700004339342F9D11C4C194DD4F80428AA42EE -:100A8000F0D31A4B9B6803F1006303F508439A42C5 -:100A9000E8D203F0E5FA03F0F7FA002000F0C0FD19 -:100AA0000220FFF7BFFF124BDA690022DA61D96931 -:100AB00099699A619B6972B64FF0E023C3F8085DAB -:100AC0003021D4F80038D4F8042881F311889D46E9 -:100AD00083F308881047C5E78008002084080020B9 -:100AE0000088000820880008008000080008002016 -:100AF0000010024049F26900084A136899B21B0CC1 -:100B000000FB013344F250611360054B186882B258 -:100B1000000C01FB0200186080B27047180800202A -:100B20001408002010B504460021102200F0D6FD64 -:100B3000034B03CB206061601868A06010BD00BF4C -:100B4000E8F7FF1F2DE9F0410026ADF54E7D6CACB6 -:100B500040F2751207460D460EA831460D9600F07C -:100B6000BDFD4FF4C4723146204600F0B7FD01F0E0 -:100B70000BFF4FF47A72B0FBF2F0264B0DF1340804 -:100B8000186093E80700022384E807000DF5E97078 -:100B90002382FFF7C7FF4EF603531F4907A823849C -:100BA00003F0B4FD17230DF2E32284F832310DF186 -:100BB0002C0C07AB1E4603CE6645106051603346D1 -:100BC00002F10802F6D130681060B188B37920468E -:100BD000918093714146012200F0CCFD00230393E4 -:100BE000AB7E80B2029305F1190301930123CDE995 -:100BF00004800093384605A3D3E90023E97E02F080 -:100C000087FA0DF54E7DBDE8F08100BF9E6AC421D4 -:100C1000818A46EE8C0800201C4700082DE9F0412F -:100C20002C4C8046237A0D46DAB05BBB284627A9B8 -:100C300000F0B0FE0746002842D19DF89D60C82E06 -:100C40003ED801464FF4A662204600F047FD4FF41F -:100C50008073C4F8F8314FF40073C4F80C334FF4C8 -:100C600040733246C4F820340DF19E0104F10900AE -:100C700000F022FD9DF89C302644777223720BB958 -:100C8000EB7E23728122002106AC27A800F026FD0E -:100C90000122214627A800F0B9FE00230393AB7E72 -:100CA00080B2029305F1190301932823CDE9044092 -:100CB0000093404605A3D3E90023E97E02F028FA19 -:100CC0005AB0BDE8F08100BFAFF3008026417272D8 -:100CD000DF25D7B7A81D0020F0B54FF48A75002492 -:100CE000234EF1B005FB006596F8D830D822214696 -:100CF00085F8DC3085F8E8403AA800F0EFFC06F112 -:100D0000090000F0E3FCD5F8E430C2B206AF8DF87C -:100D1000F00006F109010DF1F100CDE93A3400F0DF -:100D2000CBFC394601223AA800F09CFE80B2CDE906 -:100D3000047008230127CDE9023706F1D803019397 -:100D40003023317A00930B4807A3D3E9002302F044 -:100D5000DFF9A04206DD01F017FEC5F8E0003846D5 -:100D600071B0F0BD2046FBE778F6339F93CACD8D76 -:100D7000A81D0020A41800202DE9F0411D4D1E4E95 -:100D80001E4F86B0284602F0EFF9034658B3002400 -:100D9000CDE90344ADF81440027B02948DF8142091 -:100DA0009968406803AA03C21B68DFF8548043F0C7 -:100DB0000043029301F0EAFD821941F10003384635 -:100DC000009402A901F0D6F8A04205DD284602F001 -:100DD000CFF988F80040D5E798F80030072B05D800 -:100DE000013388F8003006B0BDE8F081014802F018 -:100DF000BFF9F8E7A418002040420F00D8180020DF -:100E0000DD22002070B50D4614461E4602F0DCF8C7 -:100E100050B9022E10D1012C0ED112A3D3E9002318 -:100E20000120C5E9002307E0282C10D005D8012CAB -:100E300009D0052C0FD0002070BD302CFBD10BA3A6 -:100E4000D3E90023ECE70BA3D3E90023E8E70BA3E6 -:100E5000D3E90023E4E70BA3D3E90023E0E700BFD5 -:100E6000AFF30080401DA12026812A0B78F6339F26 -:100E700093CACD8D9E6AC421818A46EE2641727244 -:100E8000DF25D7B7F017304A39059E5638B50546E5 -:100E90000E4C0021013500F0E5FBA4F82C55B4F808 -:100EA0002C0500F0C7FB78B1B4F82C0500F0D2FB9C -:100EB000014648B9B4F82C0500F0D4FBB4F82C3541 -:100EC0000133A4F82C35EAE738BD00BFA81D002087 -:100ED00010B50A4B0A4A1A6093F8602442B9D3F855 -:100EE0005C442CB1204600F0E7FE204603F050FBA6 -:100EF000BDE81040034800F0DFBE00BFD818002056 -:100F000070470008201D00202DE9F04F8FB000AF82 -:100F100005460C4602F058F8002848D1237E022BE3 -:100F20001AD1E38A012B17D101F02EFD0646FFF7F7 -:100F3000E1FD4FF4C873B0FBF3F202FB1303DFF8DB -:100F4000A0829BB206F516763344C8F80030E37EE3 -:100F500033B90022A34B1A703C37BD46BDE8F08F71 -:100F6000204607F1240100F0D3FC0028F4D107F15A -:100F70001400FFF7D7FD97F8264007F11401224629 -:100F800007F1270003F04EFB0028E2D10F2C08D810 -:100F9000944B1C70D8F80030A3F51673C8F80030D5 -:100FA000DAE7284697F8241002F006F8D4E7E38A37 -:100FB000282B2BD010D8012B23D0052BCCD1BFF35D -:100FC0004F8F8949894BCA6802F4E0621343CB60B2 -:100FD000BFF34F8F00BFFDE7302BBDD1844EE17EC4 -:100FE000327A9142B8D131460022607E91F8DC50CD -:100FF000854200F0A5800132042A01F58A71F5D1FD -:10100000AAE721462846FFF79DFDA5E72146284689 -:10101000FFF704FEA0E7B2F8EC507B6005F103098E -:101020004FEA99094FEA8902D11DC908A8EBC1030B -:101030009D46EB460021584600F050FB04F1EE01BE -:101040002A465846314400F037FB7B6813B901202B -:1010500000F0E6FA96F8D20000F0ECFA044630B957 -:10106000307200F007FB204600F0DAFAB0E0D6F864 -:10107000D4203AB996F8D200B6F82C25824201D88D -:10108000FFF704FFD6F8D4202A44944208D296F8F9 -:10109000D200B6F82C250130824201D8FFF7F6FEC7 -:1010A000594670685FFA89F200F020FB08B9C5461E -:1010B00078E0726896F8D2002A447260D6F8D4209C -:1010C00005EB0209C6F8D49000F0B4FA814509D3C3 -:1010D00096F8D220D6F8D4000132001B86F8D22030 -:1010E000C6F8D400FF2D0FD80024347200F0C2FAE5 -:1010F000204600F095FA00F061FD3E4B188108B9DA -:10110000FFF7A6FCC54627E7BB6896F8D9000AFB9F -:101110000362D2F8E410FB6801F5806182F8E830E0 -:10112000C2F8E030C2F8E410FFF7D6FDFFF724FE66 -:1011300096F8D920013202F0030286F8D920B6E7EA -:101140004FF48A7A0AFB02F505F1EA0120463144A0 -:1011500000F0B4FCF86000287FF4FEAE01223544B4 -:1011600085F8E82001F010FCD5F8E020801A192855 -:1011700040F6B83238BF1920904228BF1046FFF71A -:1011800061F91D49FEF7F4FF04463068FFF75AF98C -:101190001A49FEF7EDFF01462046FFF7A3F8FFF7D7 -:1011A000A9F9306096F8D930BB60BA6873680AFB59 -:1011B00002F4321992F8E81059B1D2F8E410E84676 -:1011C0008B423FF428AF002182F8E810C2F8E0100B -:1011D000C5467368074A9B0A01331381BCE600BF0A -:1011E000A01800209D18002000ED00E00400FA0582 -:1011F000A81D00208C080020CDCCCC3D6666663F43 -:10120000014B1870704700BF9808002030B54FF0B0 -:1012100000542B4B226885B09A4207D002F05EFF43 -:10122000044620BB0024204605B030BD627D254B1E -:1012300025481A70237D002503724FF48073C0F88F -:10124000F8314FF40073C0F80C334FF44073C922E7 -:10125000C0F820341D49C0F8E450093000F02CFAE1 -:101260002046E022294600F039FA0124DBE7184A3B -:10127000184DD36943F00073D361AA6D164B9A429F -:10128000D0D12B6E013B7E2BCCD8144A01AB07CAC0 -:1012900083E807001846032100F060FC6B6D834271 -:1012A0004FF00003BED12A6D8A4203BFAB652A6EA0 -:1012B000044B1C4601BF1A70EA6D094B1A60B2E775 -:1012C0009AAD44C598080020A81D002016000020F3 -:1012D00000100240006600405041A0B05866004037 -:1012E0001008002037B500F069FC0223184D0122D8 -:1012F0006B71184B28811968174801F0F3F9002326 -:101300000193164B164900934FF48052154B164823 -:1013100001F028FE154B197811B1134801F04CFE6D -:1013200001F032FB0446FFF7E5FB4FF4C873B0FB56 -:10133000F3F202FB130304F516709BB218440C4B36 -:10134000186002F0C1FE08B10F232B8103B030BD3D -:101350008C08002010080020D8180020050E000876 -:101360009C080020090F0008A418002098080020FD -:10137000A01800202DE9F04F0FF22829D9E90089A3 -:101380007E4C93B0FFF7F8FC00230BAE7C4FDFF8E8 -:10139000F4A10A93ADF834300B9373604FF0000B57 -:1013A000002200230125CDE9002338465B460DF1DC -:1013B0001D0207A98DF81C508DF81DB001F044F9ED -:1013C0009DF81C30002B40F0A080204601F0FCFD71 -:1013D0000646002845D101F0D7FA6B4F3B6898428A -:1013E0003FD301F0D1FA8246FFF784FB4FF4C87374 -:1013F000B0FBF3F202FB130083B20AF51670184437 -:101400003860624F0EA897F800B0BBF1000F14BF10 -:1014100033462B46CBF1100A5FFA8AFA8DF8283052 -:10142000FFF780FBBAF1060F28BF4FF0060A0EAB9C -:1014300003EB0B0152460DF1290000F03DF90AAB18 -:10144000039318230AF101020293514BD2B2CDE962 -:1014500000530492204647A3D3E9002301F0FAFD8C -:101460003E7001F091FA4B4A4B4D1368C31AB3F525 -:101470007A7F2ED3106001F089FA02460B4620468F -:1014800001F080FE204601F09FFD10B32B7A434E01 -:10149000002B14BF03230223737101F075FA4FF47C -:1014A0007A73B0FBF3F00EAF01223060394630465C -:1014B00000F006FA18230293394B80B2019340F2F0 -:1014C0005513CDE90370009342464B46204601F088 -:1014D000C1FD2B7AB3B101F057FA002607464FF44D -:1014E0008A7A95F8D900304400F003000AFB0053D3 -:1014F00093F8E8206AB30136042EF2D12B7A002B40 -:101500007FF440AF13B0BDE8F08FDAF80C305946E5 -:1015100083F00803CAF80C3010220EA800F0DEF8A1 -:101520000DF11E0308AA0AA9384600F019FE96E834 -:1015300003000FAB83E803009DF8343020468DF89C -:1015400044300A9B0EA90E93DDE9082301F0F0FF59 -:1015500024E7D3F8E02042B12B68BA1AFA2B38BF3F -:10156000FA230533B2EB430FC5D3FFF7B5FB0028D1 -:10157000C1D1C3E7401DA12026812A0BA418002059 -:10158000D8180020000C0140A01800209D18002051 -:101590009C180020D8220020A81D00208C080020C4 -:1015A000DC220020F1C6A7C1D068080F08B50548A5 -:1015B00000F06CFEBDE808400020034A034902F039 -:1015C000E1BF00BFD818002018230020D10E00086A -:1015D0007047000070B502F0F9FB00250E4C0F4E6D -:1015E00020803068238883420CD800252088013869 -:1015F00002F0E8FB23880544013BB5F5805F2380BA -:10160000F4D370BD02F0DEFB336805440133B5F559 -:10161000084F3360E5D3E8E70C230020E0220020E8 -:1016200002F062BC00F10060920000F5084002F098 -:1016300007BC0000054B1A68054B1B889B1A8342A8 -:1016400002D9104402F0BEBB00207047E022002007 -:101650000C230020024B1B68184402F0B9BB00BFEA -:10166000E0220020024B1B68184402F0C3BB00BFFD -:10167000E0220020064991F8243033B100230822EB -:10168000086A81F82430FFF7CDBF0120704700BF02 -:10169000E4220020022802BF0822014B1A61704791 -:1016A000000C0140022802BF4FF40022014B1A61D6 -:1016B000704700BF000C0140002310B5934203D0D7 -:1016C000CC5CC4540133F9E710BD00000346024668 -:1016D000D01A12F9011B0029FAD1704703460244BF -:1016E000934202D003F8011BFAE770472DE9F84353 -:1016F0001F4D144695F824200746884652BBDFF854 -:1017000070909CB395F824302BB92022FF214846D5 -:101710002F62FFF7E3FF95F824004146C0F108026D -:10172000A24228BF224605EB8000D6B29200FFF706 -:10173000C3FF95F82430A41B1E44F6B2082E1744AC -:101740009044E4B285F82460DBD1FFF793FF0028D2 -:10175000D7D108E02B6A03EB82038342CFD0FFF797 -:1017600089FF0028CBD10020BDE8F8830120FBE7EA -:10177000E42200202DE9F0470D4604460021904662 -:10178000284640F27912FFF7A9FF234620220021C4 -:10179000284601F06FFE022220212846231D01F079 -:1017A00069FE032222212846631D01F063FE032205 -:1017B00025212846A31D01F05DFE10222821284680 -:1017C00004F1080301F056FE08223821284604F1EE -:1017D000100301F04FFE08224021284604F11103B6 -:1017E00001F048FE08224821284604F1120301F0C6 -:1017F00041FE20225021284604F1140301F03AFE54 -:1018000040227021284604F1180301F033FE08221B -:10181000B021284604F1200301F02CFE0822B82153 -:10182000284604F1210301F025FEC02604F1220719 -:101830003B46314608222846083601F01BFEB6F525 -:10184000A07F07F10107F3D108223146284604F1B1 -:10185000320301F00FFE002704F1330A94F832300E -:101860004FEAC7099F4209F5A47615D3B8F1000FD6 -:1018700008D131460722284604F5997301F0FAFD94 -:1018800009F24F16274694F832213B1B93420CD3A2 -:10189000F01DC008BDE8F0870AEB070308223146B7 -:1018A000284601F0E7FD0137D8E7314607F2331348 -:1018B0000822284601F0DEFD08360137E3E7000084 -:1018C00038B50C460021054621600346C4F80310D4 -:1018D0002046202201F0CEFD20462B1D0222202191 -:1018E00001F0C8FD20466B1D0322222101F0C2FD3C -:1018F0002046AB1D0322252101F0BCFD204610220D -:10190000282105F1080301F0B5FD072038BD0000CE -:101910000023F7B50E460546047F072200911946BD -:1019200001F06AFC731C0093012200230721284662 -:1019300001F062FCC4B9B31C0093052223460821C0 -:10194000284601F059FC0D243746B278BB1B934260 -:1019500011D32B7FE01DC008AC8ABBB9A04294BF55 -:101960000020012003B0F0BDAB8A0824DB00083B57 -:10197000DB08B370E8E7FB1C214600930822002334 -:10198000284601F039FC08340137DEE7001B18BF98 -:101990000120E7E70023F7B50E46047F08220091F7 -:1019A0001946054601F028FC731CC4B908220093AF -:1019B00011462346284601F01FFC102401237278AB -:1019C0005F1C013B934211D32B7FE01DC008AC8A02 -:1019D000BBB9A04294BF0020012003B0F0BDAB8A88 -:1019E0000824DB00083BDB087370E7E7F3192146A6 -:1019F000009308220023284601F0FEFB08343B46F2 -:101A0000DDE7001B18BF0120E7E70000F8B50E4630 -:101A100005461446002181223046FFF75FFE2B4623 -:101A200008220021304601F025FD7CB9072208215B -:101A300030466B1C01F01EFD0F2401236A785F1CE9 -:101A4000013B934204D3E01DC008F8BD0824F4E72D -:101A50002146EB190822304601F00CFD08343B46C4 -:101A6000ECE70000F8B50E46054614460021CE22EC -:101A70003046FFF733FE2B4628220021304601F086 -:101A8000F9FC7CB908222821304605F1080301F051 -:101A9000F1FC30242F462A7A7B1B934204D3E01DAD -:101AA000C008F8BD2824F5E7214607F109030822FC -:101AB000304601F0DFFC08340137ECE7F7B5047F6E -:101AC0000E460091012310220021054601F094FBEF -:101AD000C4B9B31C0093092223461021284601F003 -:101AE0008BFB192437467288BB1B9A4211D82B7F77 -:101AF000E01DC008AC8ABBB9A04294BF0020012001 -:101B000003B0F0BDAB8A1024DB00103BDB08738010 -:101B1000E8E73B1D2146009308220023284601F0F8 -:101B20006BFB08340137DEE7001B18BF0120E7E735 -:101B300030B5094D0A4491420DD011F8013B58408F -:101B4000082340F30004013B2C4013F0FF0384EA18 -:101B50005000F6D1EFE730BD2083B8ED4FF0FF33F2 -:101B6000F7B500EB81061946DFF848C0DFF848E01A -:101B7000B0421BD050F8042B01AF0192042217F899 -:101B8000014B81EA046108240D46DB184941013C00 -:101B9000002DBCBF83EA0C0381EA0E0114F0FF04A0 -:101BA000F2D1013A12F0FF02E9D1E1E7D843C9438B -:101BB00003B0F0BD9336EAA9EBE1F042F7B56B460E -:101BC000374A106851686A4603C3082335493648C6 -:101BD00002F038FD0446002833D10A256B46334A0B -:101BE000106851686A4603C3082331492E4802F041 -:101BF00029FD0446002849D00369B3F55E3F45D866 -:101C000040F2ED32B0F8661091423FD1294A0244C9 -:101C100002F15C018B4239D35C3B234900209E1AC0 -:101C2000FFF786FF07463246002004F16401FFF704 -:101C30007FFFA3689F4229D1E368984208BF00252F -:101C400024E00369B3F55E3F27D840F2ED32418BC3 -:101C5000914220D1174A024402F110018B4218D35D -:101C6000103B114900209D1AFFF762FF06462A46E5 -:101C7000002004F11801FFF75BFFA3689E4202D128 -:101C8000E368984201D00D25A8E70025284603B057 -:101C9000F0BD1025A2E70C25A0E70B259EE700BFAD -:101CA00034470008DC770300008800083D4700083F -:101CB000907703000878FFF710B5037C044613B94A -:101CC000006802F0A7FC204610BD00000023BFF30F -:101CD0005B8FC360BFF35B8FBFF35B8F8360BFF32A -:101CE0005B8F7047BFF35B8F0068BFF35B8F7047FC -:101CF00070B505460C30FFF7F5FF05F10806044600 -:101D00003046FFF7EFFFA04206D930466D68FFF777 -:101D1000E9FF2C44201A70BD3046FFF7E3FFF9E7D6 -:101D200070B505464068A0B105F10800FFF7DAFF7D -:101D300005F10C0604463046FFF7D4FF844288BF05 -:101D40000025304698BF6D68FFF7CCFF013C2C445E -:101D5000201A70BD38B50C460546FFF7C9FFA042F2 -:101D600010D305F10800FFF7BDFF04446868BFF316 -:101D70005B8FB4FBF0F100FB1144AC60BFF35B8FF1 -:101D8000012038BD0020FCE72DE9F041144607464C -:101D90000D46FFF7C5FF844228BF0446D4B1B846BC -:101DA00058F80C6B4046FFF79DFF06442E604046F6 -:101DB0007E68FFF797FF331A9C4203D801206C60BE -:101DC000BDE8F0816B603B68A61B0644AB60022057 -:101DD000EE60F5E72046F3E738B50C460546FFF719 -:101DE0009FFFA04210D305F10C00FFF77BFF0444D6 -:101DF0006868BFF35B8FB4FBF0F100FB1144EC604B -:101E0000BFF35B8F012038BD0020FCE72DE9FF41C7 -:101E10000F46694606466C46FFF7B6FF002504EB01 -:101E2000C008444508D0626820687919FFF744FC6F -:101E3000636808341D44F4E729463046FFF7CCFFB9 -:101E4000284604B0BDE8F081F8B505460C300F46D1 -:101E5000FFF748FF05F1080604463046FFF742FF4A -:101E6000A042304688BF6C68FFF73CFF201A3860FC -:101E700020B130462C68FFF735FF2044F8BD000044 -:101E8000F7B5174606460D46FFF732FFB84204463F -:101E900028BF3C460190DCB1304601A9FFF7D4FFD2 -:101EA000019B33B93268C5E90233C5E9002401203A -:101EB0000CE09C4238BF019428600198844268601D -:101EC000F5D9241A02203368EC60AB6003B0F0BD92 -:101ED0002046FBE72DE9FF410E466946FFF7D0FF9C -:101EE0006C46002504EBC007BC4209D0D4F804803E -:101EF0007019424654F8081BFFF7DEFB4544F3E730 -:101F0000284604B0BDE8F08138B50546FFF7E2FF8A -:101F1000044601462846FFF71DFF204638BD000055 -:101F2000302383F3118862B670470000002383F3E7 -:101F3000118862B67047000010B4026854681A46EF -:101F4000234610BC1847000001207047002070474E -:101F50000020704770470000002070470E20704737 -:101F600090F8C804C0F340007047000090F9C9041D -:101F700070470000F7B50C681E4614F00054BDF819 -:101F800020706AD10B7B082B67D8FFF7C9FF456922 -:101F9000AB685B010CD4AB681B0108D4AC6814F0CF -:101FA000805458D1FFF7C2FF204603B0F0BD012492 -:101FB0000B6804F1180C002BBABFDB0043F00403DC -:101FC0005B054FEA0C1C45F80C300B684FEA041C0B -:101FD00013F0804F1CBF05EB0C0EDEF88031AC44D3 -:101FE0001CBF43F00203CEF880310B7B05EB0415D8 -:101FF000CCF884318B68C5F88C314B68C5F88831D2 -:102000000D46DCF8803143F00103CCF8803100EB61 -:102010004413C3F86824C3F86C6401F10C0C03F595 -:102020008E6355F804EB654543F804EBF9D12D8830 -:1020300024341D8000EB4414257907F0030325F0B8 -:102040000B052B432371FFF771FF3346009700F018 -:10205000BDFC0120A9E70224AAE74FF0FF30A4E766 -:1020600038B50446D0F85C040D46FFF759FE1F282A -:102070000AD920222946D4F85C04FFF7C7FEA0F154 -:1020800020035842584138BD0020FCE708B5FFF74F -:1020900047FFD0F85C04FFF719FEBDE80840FFF7E2 -:1020A00045BF00000022026082814260826070476A -:1020B0000022002310B5C0E9002300230446038159 -:1020C0000C30FFF7EFFF204610BD0000F0B590F890 -:1020D000C8340D4613F0040FC3F3800108BF114646 -:1020E00005F1240661F3820380F8C83400EB46133F -:1020F0001B790446D80789B02DD572B319072CD4A3 -:1021000004EB45156846FFF7D3FF05F58E6303AA78 -:1021100005F58F65174618685968083303C7AB4241 -:102120003A46F7D11868694638609B882046BB80DC -:10213000DDE90E23CDE900230123ADF80830236843 -:10214000DB6B984704EB461423791A075CBF43F016 -:102150000803237101E0002AF4D109B0F0BD0000AA -:102160002DE9F047054688B068469A46884691466C -:10217000FFF7D6FEFFF79CFFD5F85C04FFF7B8FD2C -:102180001F282AD920226946D5F85C04FFF7BCFE37 -:10219000202822D1444603AE05AB374603CF9F42E9 -:1021A000206061603E4604F10804F6D1386841467B -:1021B0002060BB882846A380DDE90023C9E900230D -:1021C000BDF808304A46AAF80030FFF7AFFE534684 -:1021D00008B0BDE8F04700F0E7BB0020FFF7A6FE1F -:1021E00008B0BDE8F087000000232DE9F047044661 -:1021F000C0E90133224B0E4640F8183BFFF752FF6F -:1022000004F1480704F12800FFF752FF3D4604F5AA -:10221000896828462035FFF74BFF4545F9D14FF433 -:102220008063C4F84874C4F84C34002701234FF08D -:1022300000084FF00009C4F85C54C4F85074C4F8A6 -:10224000547484F8583484F8603404F5916504F5C6 -:102250009D6A45E90889A5F11800FFF723FF20359D -:1022600045F8287C5545F4D184F8C96416B1054871 -:1022700000F084FB044B20466361BDE8F08700BF9B -:1022800070470008484700080064004010B5044645 -:10229000034B19784A1C1A70FFF7A6FF204610BDA1 -:1022A000142300202DE9F04300294FD0284F294B5B -:1022B000B7FBF1F499428CBF0A231123B4FBF3FC62 -:1022C000581E03FB1C43C5B22BB102280346F5D8A8 -:1022D0000020BDE8F0830CF1FF36B6F5806FF7D231 -:1022E0004FF47A74C5EBC50E0EF103034FEAE30910 -:1022F00009FB0444C3F3C703E81AC0B209F101089B -:102300008044B4FBF8F4B4F5617FC2BF0EF1FF3333 -:10231000C3F3C703E81A03F10104C8BFC0B2E4B2B3 -:1023200004440CFB04F4B7FBF4F4A142D0D1013B0C -:10233000DBB20F2BCCD80138C0B20728C8D8002197 -:102340001071168001209170D370C2E70846C0E773 -:10235000005125023F420F0070B505460E464FF46E -:102360007A746B6901205B6803F00103B34204D007 -:1023700001F080FC013CF4D1204670BD30B54269CB -:10238000936913F0700F16D000230B4C936103F187 -:10239000240200EB421211794D0709D5890707D5B0 -:1023A000416954F823508D60117941F00401117195 -:1023B0000133032BEBD130BD5C47000873B51D46DC -:1023C000436916469A680446D20709D501219A68DE -:1023D0009960C2F340020021CDE90065FFF776FE67 -:1023E00063699A68D1050BD54FF480719A682046CD -:1023F0009960C2F340220121CDE90065FFF766FE36 -:1024000063699A68D2030BD54FF480319A682046ED -:102410009960C2F340420221CDE90065FFF756FE04 -:10242000204602B0BDE87040FFF7A8BFF8B50446EB -:10243000466900296AD106F10C073868800768D020 -:10244000386806EB01104FEA011CD0F8B011D0F843 -:10245000B051490746BFED0845F000456D0DA56137 -:10246000D0F8B011890744BF45F08045A561D0F888 -:10247000B40106EB0C0100F00F0084F82400D1F841 -:10248000B80104F124052077D1F8B801000A60777B -:10249000D1F8B801000CA077D1F8B801000EE077B0 -:1024A000D1F8BC0184F82000D1F8BC01000A84F8FE -:1024B0002100D1F8BC01000C84F82200D1F8BC1135 -:1024C00004F13400090E84F823103821396004F136 -:1024D000180151F8046BA94240F8046BF9D109883E -:1024E0000180C4E90A2300232146238651F8283BB2 -:1024F0002046DB6B984794F8C834204643F0040329 -:1025000084F8C834BDE8F840FFF738BF06F110077B -:1025100093E7F8BD10B5044600F038FA02460B46C2 -:1025200052EA030102D0013A63F10003044908684A -:1025300020B12146BDE81040FFF778BF10BD00BFB5 -:1025400010230020F8B500211E46FFF7E9FC124FCA -:1025500000F58D6501F1240400EB4414237913F098 -:10256000040F0FD1DB060DD5D5E900C39445B34167 -:1025700008D2436957F821C0C3F808C0237943F053 -:10258000040323710131032905F12005E2D1BDE8DF -:10259000F840FFF7CBBC00BF5C47000808B5FFF769 -:1025A000BFFCFFF7EBFEBDE80840FFF7BFBC000033 -:1025B000F8B54369044698680E4600F0E050B0F163 -:1025C000E05F1DD0D8B1FFF7ABFC002504F58E67A6 -:1025D00004EB451393F884341A0706D50135032D0F -:1025E00007F12007F4D1012007E05B07F6D4394654 -:1025F000304600F025FA0028F0D1FFF797FCF8BD2F -:102600000120FCE708B5FFF78BFCD0F85C04FFF76E -:102610006FFBFFF78BFC43090CBF0120002008BDB6 -:10262000F8B51D46002313700F4606461446FFF703 -:10263000E9FF80F00100387025B129463046FFF7E8 -:10264000B7FF2070F8BD0000F8B50C4615461E46D1 -:10265000074600F09BF90B462178024609B9287815 -:1026600050B13846FFF76EFFFFF798FF33462A4612 -:102670002146FFF7D5FF0120F8BD000010B5FFF798 -:102680004FFC174B0446DA6942F00072DA611A69AE -:1026900042F000721A611A6922F000721A61FFF7A3 -:1026A00045FC90F8C834DB0718D4B9B103211320D6 -:1026B000FFF736FC01F0ACF90321142001F0A8F972 -:1026C0000321152001F0A4F994F8C83443F0010364 -:1026D00084F8C834BDE81040FFF728BC10BD00BF27 -:1026E000001002402DE9F04790F8C9340446012B50 -:1026F0000F46154688B07DD87F4E56F823200AB97C -:1027000046F82300D6F80090E7602574B9F1000F71 -:1027100062D094F8C934012B6ED04FF0000801212B -:102720002046FFF7ABFFFFF7FBFB6269012113684F -:10273000204623F0020313606269136843F001032B -:1027400013606369C3F81480FFF7F0FBFFF704FE22 -:10275000002800F09280D4F85C04FFF7B7FAA14695 -:1027600004F1600A202200216846FEF7B7FF02A8A4 -:10277000FFF798FC6A46CDF8188009F58D630DF1D6 -:10278000180C164603CE664518605960324603F1B0 -:102790000803F6D1306809F1200918603279CA457A -:1027A0001A71DFD1002694F8C8346A466FF38203A9 -:1027B00084F8C83439462046ADF80060ADF80260B0 -:1027C0008DF80460FFF76EFD636948BB4FF400426B -:1027D0001A6008B0BDE8F0874FF49A6001F0DAFEA5 -:1027E000804610B14946FFF7FFFCC6F80080B8F1FB -:1027F000000F8ED10020ECE7306803681B6B984710 -:102800000146002889D13068FFF738FF30682A4632 -:10281000036839465B68984700287FF47EAFE9E794 -:102820006122022D0CBF4FF0004100211A609DF87B -:1028300002309DF803201B06120402F4702203F0FC -:1028400040731343BDF800202046C2F3090213432E -:102850009DF80420120502F4E002134362690B4361 -:10286000D3611322636931465A616269136823F0A8 -:1028700001031360FFF770FD08B96369A6E794F8D8 -:10288000C93493BB6169D1F8002242F00102C1F85A -:1028900000226169D1F8002222F47C5222F00E025B -:1028A000C1F800226169D1F8002242F46062C1F8E7 -:1028B000002241F6FF716269C2F814326269C2F8FF -:1028C00004326269C2F80C126269C2F8403262696D -:1028D000C2F8443201226369C3F81C226269D2F84B -:1028E000003223F00103C2F8003294F8C83443F0F8 -:1028F000020384F8C8346CE71023002008B500F008 -:1029000045F802460B4652EA030102D0013A63F150 -:1029100000030449086808B1FFF750FDBDE808400E -:1029200001F054B81023002008B50020FFF7F2FD95 -:10293000BDE8084001F04AB808B50120FFF7EAFDFC -:10294000BDE8084001F042B8EFF30983EFF30583D7 -:10295000014B9B6BFEE700BF00ED00E008B5FFF701 -:10296000F3FF0000EFF30983EFF30583014B5B6B8B -:10297000FEE700BF00ED00E0FEE700000FB408B581 -:10298000029801F00DF9FEE701F0FABA01F0D2BAAF -:1029900013B56C4684E80600031D94E8030083E841 -:1029A0000500012002B010BDF8B586680D4656B18D -:1029B0001B885B0707D4D0E900379B6B98472A46F2 -:1029C000C1B23846B0470120F8BD0000F0B58668B6 -:1029D00005460C4689B05EB1BDF838305B070AD4B5 -:1029E000D0E900379B6B98472246C1B23846B047C2 -:1029F000012009B0F0BD00220023CDE9002300230F -:102A00000A46ADF8083001F1080603AB1C46106811 -:102A10005168083203C4B2422346F7D110682060DF -:102A20009288A280FFF7B2FF0423ADF808302B682C -:102A3000CDE90001DB6B694628469847D8E70000DE -:102A400030B503680968DD0FB5EBD17F23F0604432 -:102A500021F060424FEAD1700BD0002BB8BFA40C1C -:102A60000029B8BF920C944202D034BF012000204C -:102A700030BD944205D1C1F38070C3F380738342AB -:102A8000F6D194422CBF00200120F1E72DE9F0415E -:102A9000456A15B94162BDE8F0814B68AC4623F048 -:102AA0006047C3F38A4616EA230638BF3E464FEA1C -:102AB000D37EC3F380782B465A68BEEBD27F22F0D8 -:102AC00060440AD0002A18DAA40CB44217D19D42FF -:102AD0000FD10D60DEE71346EEE7A74207D102F003 -:102AE0008044C2F3807242450BD054B1EFE708D264 -:102AF000EDE7CCF800100B60CDE7B44201D0B44252 -:102B0000E5D81A689C46002AE5D11960C3E70000A1 -:102B10002DE9F0474FF47F49089D01F007044FEA83 -:102B2000D508224405F0070500EBD100944201D1FD -:102B3000BDE8F08704F0070705F0070A57453E4651 -:102B400038BF5646111BC6F108068E4228BF0E46F6 -:102B5000E108415C08EBD50E13F80EC0B94029FA24 -:102B600006F721FA0AF1FFB28CEA010147FA0AF7E7 -:102B700039408CEA010C03F80EC034443544D5E7E3 -:102B8000082341F2210280EA012001B2400000291D -:102B900080B203F1FF33B8BF504013F0FF03F4D10C -:102BA0007047000038B50C468D18A54200D138BDDD -:102BB00014F8011BFFF7E4FFF7E700000346406845 -:102BC00048B1026899895A605A89013292B2914299 -:102BD0005A8138BF9A81704770B504460D4688B057 -:102BE000202200216846FEF779FD20460495FFF774 -:102BF000E5FF024658B16B46054608AE1C4603CCBD -:102C0000B44228606960234605F10805F6D11046F4 -:102C100008B070BD082817D909280CD00A280CD094 -:102C20000B280CD00C280CD00D280CD00E2814BF6B -:102C30004020302070470C2070471020704714202F -:102C4000704718207047202070470000082817D9C7 -:102C50000C280CD910280CD914280CD918280CD9F8 -:102C600020280CD930288CBF0F200E207047092057 -:102C700070470A2070470B2070470C2070470D20CA -:102C8000704700002DE9F843078C0446072F1ED932 -:102C9000D0E9029800254FF6FF73C5F12006A5F193 -:102CA000200029FA05F108FA06F628FA00F0314367 -:102CB0000143C9B21846FFF763FF0835402D0346AC -:102CC000EBD13A46E169BDE8F843FFF76BBF4FF639 -:102CD000FF70BDE8F883000010B54B6823B9CA8ABD -:102CE00063F30902CA8210BD04691A681C6003619B -:102CF000C38A013BC3824A60EFE700002DE9F84F29 -:102D00001D46CB8A0F46C3F3090105298146924629 -:102D10000B4630D00020AAB207F11A049EB2042E4E -:102D20001FFA80F80FD8904503F1010306D3FB8A00 -:102D30000A4462F309030120FB821AE01AF80060DA -:102D40000130E654EAE79045F1D21C23A1F1050BCE -:102D5000BBFBF3F203FB12BB7C681FFA8BF6002C63 -:102D600045D14846FFF72AFF044638B978606FF02E -:102D70000200BDE8F88F4FF00008E6E70026066085 -:102D800078604FF0000BADB2454510D90AEB08034F -:102D9000221D13F8011B08F101089155B1B21B293E -:102DA0001FFA88F82BD0454506F10106F1D8FB8AB9 -:102DB000C3F30902154465F30903BCE71C4601325D -:102DC00092B22368002BF9D16B1F0B441C21B3FB7B -:102DD000F1F301339BB29A42D3D2BBF1000FD0D1B1 -:102DE0004846FFF7EBFE20B9C4F800B0BFE7012268 -:102DF000E7E7C0F800B05E4620600446C1E74545FD -:102E0000D5D94846FFF7DAFE08B92060AFE7C0F829 -:102E100000B0002620600446B6E700002DE9F74F19 -:102E20001C465B69074688460092002B00F097809D -:102E3000238C2BB1E269002A00F09180072B33D854 -:102E400007F10C00FFF7BAFE054628B96FF002053E -:102E5000284603B0BDE8F08F14220021FEF73EFCA7 -:102E6000228CE16905F10800FEF726FC208C48F071 -:102E70000041013080B2FFF7E9FEFFF7CBFE0138D9 -:102E800080B22084013028746369228C1B782A4424 -:102E900003F01F0363F03F0313723846696029464D -:102EA000FFF7F4FD0125D3E74FF000094FF0800A4A -:102EB0004E464D4600F10C0301930198FFF77EFE4C -:102EC00083460028C2D014220021FEF707FC002E02 -:102ED0003BD10222009BABF808300BF1080E1FFA21 -:102EE00082FC0CF10100BCF1060F218C80B201D8EC -:102EF0008E422CD3FFF7AAFEFFF78CFE8E4208BF4E -:102F00004FF0400A62690138127880B202F01F0265 -:102F100042EA49120BEB00014AEA020A013048F08A -:102F2000004281F808A08BF8100059463846CBF8CB -:102F30000420FFF7ABFD238C0135B3424FF0000AAC -:102F40002DB289F00109B8D182E70022C5E7E16915 -:102F5000895D01360EF80210B6B20132BFE76FF09C -:102F6000010575E7F8B5044615460E4630220021E6 -:102F70001F46FEF7B3FB069BB5F5001F6360079B7A -:102F800028BF4FF6FF72A3624FF0000338BF6A09F3 -:102F9000A760E66197B204F110009A4206D80023B8 -:102FA0000360A782E3822383E360F8BD06600133F8 -:102FB00030462036F1E7000003781BB94BB2002BF6 -:102FC000C8BF01707047000000787047F8B50C4624 -:102FD000C969074611B9238C002B37D1257E1F2DD7 -:102FE00034D8387828BB228C072A2CD8268A36F089 -:102FF00003032BD14FF6FF70FFF7D4FD4FF6FF729E -:1030000020F001003602400446EA0565400C45EA1E -:103010004025234629463846FFF700FF002807DDF4 -:10302000626913780133DBB21F2B88BF0023137052 -:10303000F8BD218A2D0645EA012505432046FFF704 -:1030400021FE0246E5E76FF00300F1E76FF00100B3 -:10305000EEE7000070B504461D4616468AB02822E9 -:1030600000216846FEF73AFBBDF838306946ADF8F6 -:1030700010300F9B204605939DF84030CDE9026546 -:103080008DF81830119B0793BDF84830ADF820300B -:10309000FFF79CFF0AB070BD2DE9F041D3690546EA -:1030A0000C4616460BB9138C5BBB377E1F2F28D8F6 -:1030B00095F80080B8F1000F26D03046FFF7E2FD0A -:1030C0003378210241EAC33141EA0801338A41EAF7 -:1030D000076141EA034102463346284641F0800138 -:1030E000FFF79CFE00280ADD3378012B07D17269B7 -:1030F00013780133DBB21F2B88BF00231370BDE8A8 -:10310000F0816FF00100FAE76FF00300F7E70000CD -:10311000F0B504460D461E4617468BB02822002106 -:103120006846FEF7DBFA9DF84C3029465A1E53429A -:1031300053418DF800309DF840306A46ADF81030AC -:10314000119B204605939DF84830CDE902768DF815 -:103150001830149B0793BDF85430ADF82030FFF7BA -:103160009BFF0BB0F0BD0000406A00B10430704717 -:10317000436A1A68426202691A600361C38A013BAA -:10318000C38270472DE9F041D0F8208014461D46D7 -:1031900041460027174E09B9BDE8F081D1E9022365 -:1031A000A21A65EB0303964277EB03031ED2036A70 -:1031B0008B420DD1FFF790FD036A1B680362036920 -:1031C0000B60C38A0161016A013B8846C382E2E762 -:1031D000FFF782FD0B68C8F8003003690B60C38AF3 -:1031E0000161013BC382D8F80010D4E78846096822 -:1031F000D1E700BF80841E002DE9F04F8BB00D4653 -:1032000014469B468046DDF85090002800F01A8155 -:10321000B9F1000F00F01681531E3F2B00F212810E -:10322000012A03D1BBF1000F40F00C810023CDE94E -:103230000833B8F81430B5EBC30F4FEAC30703D314 -:1032400000200BB0BDE8F08F2B199F42D8F80C304E -:1032500036BF7F1B2746FFB21BB9D8F81030002BB2 -:103260007BD0272D4ED8C5F12806B7424FF000037A -:1032700034BF3E46F6B2009329463246D8F80800DD -:1032800008ABFFF745FCA7EB060A35445FFA8AFA5C -:103290002821B8F8143003F10053053BDB000493F8 -:1032A000D8F80C300393039B13B1BAF1000F2CD163 -:1032B000D8F8100040B1BAF1000F05D05246009680 -:1032C00008AB691AFFF724FC38B2002FB8D06607A4 -:1032D0000AD00AAB03EBD40111F8083C624202F0B9 -:1032E0000702134101F8083C082C3DD9102C40F28C -:1032F000B680202C40F2B880BBF1000F00F09D801A -:10330000082335E0BA460026C2E7049BE02B28BF1D -:10331000E02306930B44AB42059315D95A1B924503 -:1033200038BF5246039828BFD2B20096691A08AB3C -:1033300004300792FFF7ECFB079A1644AAEB020A47 -:103340001544F6B25FFA8AFA049B069A05999B1A0D -:103350000493039B1B680393A5E700933A46294611 -:10336000D8F8080008ABADE7BBF1000F13D001237C -:10337000B4EBC30F6CD0082C12D89DF82030621E1D -:1033800023FA02F2D50706D54FF0FF3202FA04F411 -:1033900023438DF820309DF8203089F8003050E725 -:1033A000102C12D8BDF82030621E23FA02F2D10789 -:1033B00006D54FF0FF3202FA04F42343ADF8203073 -:1033C000BDF82030A9F800303BE7202C0FD8089931 -:1033D000631E21FA03F3DA0705D54FF0FF3202FA34 -:1033E00004F40C430894089BC9F8003029E7402CEA -:1033F0002BD0DDE90865611EC4F12102A4F121038F -:1034000026FA01F105FA02F225FA03F311431943F2 -:10341000CB0712D50122A4F12003C4F1200102FA46 -:1034200003F322FA01F1A240524243EA010363EBA3 -:10343000430332432B43CDE90823DDE90823C9E9DF -:103440000023FEE66FF00100FBE66FF00800F8E6EF -:10345000082CA0D9102CB3D9202CEED8C3E7BBF18F -:10346000000FADD0022383E7BBF1000FBBD00423D4 -:103470007EE70000012A30B5144638BF012200253E -:10348000402A28BF402285B0012CCDE9025517D82B -:103490001B788DF8083053070AD004AB03EBD20534 -:1034A00015F8083C544204F00704A34005F8083C12 -:1034B0000346009102A80021FFF72AFB05B030BDAA -:1034C000082CE5D9102C03D81B88ADF80830E2E7AA -:1034D000202C02D81B680293DDE7D3E90045CDE933 -:1034E0000245D8E710B5CB681BB98B600B618B82A6 -:1034F00010BD04691A681C600361C38A013BC38262 -:10350000CA60F0E703064CBFC0F3C030022070472A -:1035100008B50246FFF7F6FF022806D15306C2F3AC -:103520000F2001D100F0030008BDC2F30740FBE704 -:103530002DE9F04F93B0CDE903230A680446104605 -:10354000FFF7E0FF02280CBF0026C2F30626002A80 -:103550000D46824680F2F98112F0C04940F0F581B3 -:10356000097B002900F0F181022803D02378B342BF -:1035700040F0EE81C2F304631046069302F07F032D -:103580000593FFF7C5FF059B00224FEA8348002300 -:1035900048EA0A48294448EA4668CE78CDE9082333 -:1035A000F309834648EA0008029367D0059B024668 -:1035B000009320465346676808A9B847002800F0E2 -:1035C000CA81276A4FB9414604F10C00FFF704FB9A -:1035D000074690B96FF0020054E03B6998450DD062 -:1035E0003F68002FF9D1414604F10C00FFF7F4FACF -:1035F00007460028EED0236A3B60276297F817C081 -:1036000006F01F08CCF3840CACEB08001FFA80FE18 -:103610000028B8BF0EF12000A8EB0C031FFA83FEB0 -:10362000B8BF00B2002B0793BEBF0EF120031BB240 -:103630000793D7E9022152EA010338D04FF0000C7A -:10364000039BDFF8F8E19A1A049B63EB01019645AE -:103650007CEB01032BD36B7B97F81AE0734519D1F0 -:10366000029B002B78D0012821DC7868F8B9DFF8BC -:10367000D0C1944570EB010316D337E0276A27B910 -:103680006FF00C0013B0BDE8F08F3B699845B5D0E2 -:103690003F68F4E76A4890427CEB010301D30020C5 -:1036A000F0E7029B002BFAD0079B0F2B17DCFA7D6B -:1036B000B30002F0030203F07C031343FB753946A9 -:1036C0002046FFF709FB6B7BBB76029B3BB9FB7D7A -:1036D000C3F38402013262F38603FB75D0E76A7B91 -:1036E000BB7E9A42DBD1029B002B35D0B309022B63 -:1036F00032D0039B1422BB60049B0021FB600DA809 -:10370000FDF7ECFF039B20460A93049BADF83EB007 -:103710000B932B1D0C932B7B8DF840A0013BDBB250 -:10372000ADF83C30069B8DF841808DF84230059B0A -:103730000AA98DF8433094F82C3083F001038DF8FA -:103740004430A3689847FB7DC3F38403013303F03F -:103750001F039B02FB82A2E7FB7DC6F34012B2EB84 -:10376000D31F40F0FB80C3F38403434540F0F9804E -:10377000029A2B7BB609002A4DD0F20762D4032BA4 -:1037800040F2F280039BAE1DBB60049B3246FB609F -:103790002B7B3946033BDBB204F10C00FFF7AEFA9A -:1037A00000280CDA39462046FFF796FAFB7DC3F372 -:1037B0008403013303F01F039B02FB820AE7AB88FB -:1037C000DDE908843B834FF6FF73C9F12000A9F1BE -:1037D000200228FA09F104FA00F0014324FA02F267 -:1037E00011431846C9B2FFF7CBF909F10809B9F13D -:1037F000400F0346E9D13146B8822A7B033AD2B260 -:10380000FFF7D0F9FB7DB882DA43C2F3C01262F34E -:10381000C713FB7543E7AEB92E1D013B324639464F -:10382000DBB204F10C00FFF769FA0028BADB2A7B4F -:103830003146013AB88AD2B2E2E700BF80841E0066 -:1038400040420F00F98A013BC1F309010429DAB2B1 -:103850005DD80023281D07F11B069A4208D910F8ED -:1038600001CB013306F801C001310529DBB2F4D1E7 -:10387000934228BF0023039938BF04330A91049967 -:1038800038BFDBB20B9107F11B010C91796838BF8F -:103890005B190D910E93FB8AADF83EB0C3F309039B -:1038A0001A44069BADF83C208DF84230059B8DF8FC -:1038B00040A08DF8433094F82C308DF8418083F08F -:1038C00001038DF8443000237B602A7BB88A013ADB -:1038D000291DFFF767F93B8BB882834203D120464D -:1038E000A3680AA9984720460AA9FFF7FBFDFB7DBC -:1038F000BA8AC3F38403013303F01F039B02FB82E4 -:103900003B8B9A420CBF00206FF01000BAE67B6838 -:10391000002BADD0052001E033461C301E68002E80 -:10392000FAD1091A081D2E1D184401EB090CBCF12F -:103930001B0F5FFA89F39BD89A4299D916F8013B7D -:1039400009F1010900F8013BEFE76FF0090099E682 -:103950006FF00A0096E66FF00B0093E66FF00D0033 -:1039600090E66FF00E008DE66FF00F008AE600BF64 -:10397000EFF30983203383F30988002383F311884D -:1039800070470000302080F3118862B60C4B0D4A5E -:10399000D96821F4E0610904090C0A43DA60D3F81C -:1039A000FC20094942F08072C3F8FC200A6842F00A -:1039B00001020A602022DA7783F82200704700BFF4 -:1039C00000ED00E00003FA05001000E0302310B520 -:1039D00083F311880B4B5B6813F400630FD0EFF394 -:1039E00009844FF08073203CE36184F3098800F080 -:1039F00095F810B1044BA36110BD044BFBE783F3B2 -:103A00001188F9E700ED00E03F09000842090008CD -:103A10000122090100F1604303F56143C9B283F853 -:103A2000001300F01F039A4043099B0003F1604319 -:103A300003F56143C3F880211A607047090100F162 -:103A40006040C9B200F56D4001767047002382687E -:103A5000037503691B6899689142FBD25A68036039 -:103A600042601060586070470023826803750369E4 -:103A70001B6899689142FBD85A68036042601060E5 -:103A80005860704708B50846302383F311880B7DD2 -:103A9000032B05D0042B0DD02BB983F3118808BD5F -:103AA00000228B691A604FF0FF338361FFF7CEFF6E -:103AB0000023F2E7D1E9003213605A60F3E7000017 -:103AC000FFF7C4BF054BD9680875186802685360D2 -:103AD0001A6001220275D860FCF720BF2023002065 -:103AE00030B50C4B0446DD684B1C87B00FD02B461D -:103AF0006846094A00F0E2F82046FFF7E3FF009B22 -:103B000013B1684600F0E2F8A86907B030BDFFF7CE -:103B1000D9FFF9E720230020853A0008044B1A68F2 -:103B2000DB6890689B68984294BF00200120704732 -:103B300020230020084B10B51C68D8682268536009 -:103B40001A6001222275DC60FFF78EFF01462046D5 -:103B5000BDE81040FCF7E2BE20230020044B1A68A9 -:103B6000DB6892689B689A4201D9FFF7E3BF704710 -:103B70002023002038B501230025064C06490748BC -:103B80002370656000F0D8FA0223237085F3118852 -:103B900038BD00BF78240020B4470008202300204F -:103BA00008B572B6044B186500F0B2F900F056FA89 -:103BB0000322024B1A70FEE7202300207824002005 -:103BC00000F096B8EFF3118020B9EFF305833022AF -:103BD00082F311887047000010B530B9EFF3058407 -:103BE000C4F3080414B180F3118810BDFFF7B6FFC9 -:103BF00084F31188F9E700008B60022308618B824F -:103C0000084670478368A3F1440243F8142C026904 -:103C100043F8442C426943F8402C094A43F8242CC9 -:103C2000C268A3F1200043F8182C022203F80C2CE0 -:103C3000002203F80B2C034A43F8102C704700BFF6 -:103C40002D0900082023002008B5FFF7DBFFBDE8A1 -:103C50000840FFF735BF0000024BDB6898610F207A -:103C6000FFF730BF20230020302383F31188FFF7B4 -:103C7000F3BF000008B50146302383F31188082004 -:103C8000FFF72EFF002383F3118808BD10B50A4CFF -:103C900023699A6891420CD85A6881600360426037 -:103CA00010609A685860511A99604FF0FF33A36111 -:103CB00010BD1B68891AECE720230020C0E903230C -:103CC000002310B410BC4361FFF7E0BF03688168B4 -:103CD0009A680A449A60426813605A6000234FF061 -:103CE000FF320360014B9A61704700BF2023002020 -:103CF00070B5124D2A46EB690133EB6152F8103F63 -:103D0000934206D030269A68013A9A602C69A368DB -:103D100003B170BDD4E900210A605160236083F3D0 -:103D200011882046D4E90331984786F311886169E8 -:103D30000029EBD02046FFF7A9FFE7E7202300206A -:103D400000207047FEE70000704700004FF0FF3092 -:103D500070470000BFF34F8F024AD368DB07FCD4E3 -:103D6000704700BF0020024008B5074B1B7853B9CD -:103D7000FFF7F0FF054B1A69120641BF044A5A606B -:103D800002F188325A6008BD9024002000200240D1 -:103D90002301674508B5054B1B7833B9FFF7DAFFF8 -:103DA000034A136943F08003136108BD9024002087 -:103DB000002002407F289ABF00F58030C00200201A -:103DC000704700004FF4006070470000802070478B -:103DD0007F2808B50BD8FFF7EDFF00F500630268F8 -:103DE000013204D104308342F9D1012008BD002002 -:103DF000FCE700007F2810B504461CD8FFF7AAFF97 -:103E0000FFF7B2FFF3220D4B4FF40061DA6002229C -:103E10001A61FFF7CFFF58611A6942F040021A6138 -:103E2000FFF798FF00F016F9FFF7B4FF2046BDE852 -:103E30001040FFF7CDBF002010BD00BF00200240A2 -:103E40002DE9F843054612F00100144606D040F271 -:103E5000F32200201E4B1A60BDE8F8831D4BAA1800 -:103E60009A4204D94FF43E72194B1A60F4E7FFF7F7 -:103E70007BFF4FF00109FFF76DFFDFF85C806D1AE3 -:103E8000012C0F4605EB010603D8FFF783FF012045 -:103E9000E2E73B88C8F8109033800020FFF75AFF14 -:103EA000C8F81000338831F8022B9BB29A420CD02C -:103EB00040F20F32064B1A60084B1E60084B1C6024 -:103EC000084B1F60FFF766FFC6E7023CD8E700BF5C -:103ED0008C240020000004080020024080240020E0 -:103EE0008824002084240020084908B50B7828B1D4 -:103EF0001BB9FFF739FF01230B7008BD002BFCD065 -:103F0000BDE808400870FFF745BF00BF90240020BF -:103F10004FF480314FF0005000F09EB80846114633 -:103F200000F05ABB012000F057BB0000084600F02B -:103F300071BB000070B5FFF745FE4FF47A710D4B71 -:103F40000D4EDB69326801FB03F3934237BF0B4A26 -:103F50000A495168156836BF4C1CD1E900545460B9 -:103F60005D1944F100043360FFF736FE2846214610 -:103F700070BD00BF2023002094240020982400203E -:103F800070B5FFF71FFE4FF47A710F4B0F4EDB69D0 -:103F9000326801FB03F3934237BF0D4A0C49516865 -:103FA00015683ABF4C1C5460D1E900545D1944F1C6 -:103FB00000043360FFF710FE4FF47A7200232846A6 -:103FC0002146FCF7B7FA70BD20230020942400207E -:103FD0009824002010B5094C013AD2B2FF2A00D132 -:103FE00010BD500854F82030013054F820009BB226 -:103FF00043EA004341F8043BEEE700BF046C004095 -:1040000010B50748013AD2B2FF2A00D110BD0C8882 -:10401000530840F823404C88013340F82340F1E72F -:10402000046C004007B50122002001A9FFF7D2FF70 -:10403000019803B05DF804FB13B50446FFF7F2FFE7 -:10404000A04205D00122002001A90194FFF7D8FF6A -:1040500002B010BD704700007047000070470000BC -:1040600045F25552064B1A6002225A6040F6FF7222 -:104070009A604CF6CC421A600122024B1A707047CB -:1040800000300040A4240020034B1B781BB14AF6EB -:10409000AA22024B1A607047A4240020003000407E -:1040A000044B1A682AB902F1804202F50432526ABE -:1040B0001A607047A02400204FF08072014B5A62B2 -:1040C000704700BF0010024008B5FFF7E9FF024B40 -:1040D0001868C0F3407008BDA024002008B5FFF7A1 -:1040E000DFFF024B1868C0F3007008BDA024002059 -:1040F00070470000FEE700000A4B0B480B4A904255 -:104100000BD30B4BC11EDA1C121A22F003028B4296 -:1041100038BF00220021FDF7E1BA53F8041B40F834 -:10412000041BECE7904800083025002030250020D3 -:1041300030250020FEE7000070B5002504461A4B2C -:1041400086B05860856201630E46FFF71BFC04F1E0 -:104150001003C4E904334FF0FF33A361134BE5614F -:10416000D9692B460A462046C4E9082304F13401E4 -:104170008023C4E900440E4AA560E5622565FFF787 -:104180003BFD01230B4AE0600375009272686846AC -:104190000192B268CDE90223074BCDE90435FFF760 -:1041A00053FD06B070BD00BF7824002020230020FE -:1041B000C0470008C54700083541000800F030B886 -:1041C00008B500F06DF9FFF7D5FCBDE80840FFF732 -:1041D00067BF0000704700004FF0FF310E4B1A69B7 -:1041E00019611A6900221A611869D868D960D968FA -:1041F000DA60DA68DA6942F08052DA61DA69DA693B -:1042000042F00062DA61054ADB69136843F48073A7 -:10421000136000F025B900BF00100240007000409C -:104220001E4B1A6842F001021A601A689007FCD50A -:104230005A6822F003025A605A6812F00C02FBD14D -:10424000196801F0F90119605A601A6842F4803265 -:104250001A601A689103FCD54EF63162DA625A6828 -:1042600042F4E8125A601A6842F080721A601A68C2 -:104270009201FCD50A4A0B495A6012220A600A6868 -:1042800002F00702022AFAD15A6842F002025A608A -:104290005A6802F00C02082AFAD170470010024056 -:1042A00000641D0000200240084A08B551691368E7 -:1042B0000B4003F00103536123B1054A13680BB1AE -:1042C00050689847BDE80840FFF780BB00040140F4 -:1042D000A8240020084A08B5516913680B4003F070 -:1042E0000203536123B1054A93680BB1D068984724 -:1042F000BDE80840FFF76ABB00040140A824002085 -:10430000084A08B5516913680B4003F00403536170 -:1043100023B1054A13690BB150699847BDE80840BD -:10432000FFF754BB00040140A8240020084A08B548 -:10433000516913680B4003F00803536123B1054A28 -:1043400093690BB1D0699847BDE80840FFF73EBBC1 -:1043500000040140A8240020084A08B551691368E8 -:104360000B4003F01003536123B1054A136A0BB1EC -:10437000506A9847BDE80840FFF728BB0004014099 -:10438000A8240020174B10B55A691C68144004F487 -:1043900078725A61A30604D5134A936A0BB1D06AA6 -:1043A0009847600604D5104A136B0BB1506B9847C1 -:1043B000210604D50C4A936B0BB1D06B9847E205EC -:1043C00004D5094A136C0BB1506C9847A30504D56A -:1043D000054A936C0BB1D06C9847BDE81040FFF7CD -:1043E000F5BA00BF00040140A82400201A4B10B504 -:1043F0005A691C68144004F47C425A61620504D571 -:10440000164A136D0BB1506D9847230504D5134A16 -:10441000936D0BB1D06D9847E00404D50F4A136E2D -:104420000BB1506E9847A10404D50C4A936E0BB1A2 -:10443000D06E9847620404D5084A136F0BB1506FD1 -:104440009847230404D5054A936F0BB1D06F984762 -:10445000BDE81040FFF7BABA00040140A8240020CC -:10446000062108B50846FFF7D3FA06210720FFF713 -:10447000CFFA06210820FFF7CBFA06210920FFF723 -:10448000C7FA06210A20FFF7C3FA06211720FFF713 -:10449000BFFABDE8084006212820FFF7B9BA00009E -:1044A00008B5FFF799FE044800F00AF8FFF792FEFE -:1044B000BDE8084000F002B8CC47000800F042B860 -:1044C000002319461C4A0133102BC2E9001102F1E6 -:1044D0000802F8D1194B9A6942F07D029A619B69F2 -:1044E0000268174BDA6082685A6042681A60C268D4 -:1044F00003F58063DA6042695A6002691A60826972 -:10450000C3F80C24026AC3F80424C269C3F8002467 -:10451000426AC3F80C28C26AC3F80428826AC3F846 -:104520000028026BC3F80C2C826BC3F8042C426B7E -:10453000C3F8002C704700BFA824002000100240E0 -:10454000000801404FF0E023044A08215A6100228C -:104550009A6107220B201A61FFF770BA3F19010018 -:1045600008B5302383F31188FFF72AFB002383F378 -:10457000118808BD08B5FFF7F3FFBDE80840FFF755 -:1045800025BA00000B460146184600F02DB8000081 -:1045900000F040B8012838BF012010B5044620467D -:1045A00000F030F830B900F007F808B900F00CF866 -:1045B0008047F4E710BD0000024B1868BFF35B8F23 -:1045C000704700BF28250020062008B500F082F8BB -:1045D0000120FFF7B7FB0000024B0A4601461868AE -:1045E000FFF79CBC1C08002010B504460448134685 -:1045F00020B10A4602202146AFF3008010BD00BF63 -:1046000000000000024B01461868FFF78BBC00BF9A -:104610001C080020024B01461868FFF787BC00BF4A -:104620001C08002010B501390244904201D100203D -:1046300005E0037811F8014FA34201D0181B10BD0B -:104640000130F2E72DE9F0419BB10446C91A177811 -:10465000014403F1FF3C8C42204601D9002008E0D0 -:1046600005780134BD42F6D10CEB0405D618A542FD -:1046700001D1BDE8F08115F8018D16F801EDF04586 -:10468000F5D0E8E71F2938B504460D4604D91623AE -:1046900003604FF0FF3038BD426C12B152F8213048 -:1046A0004BB9204600F030F82A4601462046BDE8C6 -:1046B000384000F017B8012B0AD0591C03D116233B -:1046C00003600120E7E70024284642F82540984788 -:1046D0000020E0E7024B01461868FFF7D3BF00BF98 -:1046E0001C08002038B50023064D04460846114634 -:1046F0002B60FFF72BFB431C02D12B6803B1236017 -:1047000038BD00BF2C250020FFF71ABB034611F867 -:10471000012B03F8012B002AF9D170476F72672E25 -:104720006172647570696C6F742E5A756261784736 -:104730004E53530040A2E4F1646891060041A3E5A2 -:10474000F2656992070000004261642043414E49CE -:104750006661636520696E6465782E0080000000E4 -:104760000080000000008000000000000000000049 -:10477000391F0008E526000849260008491F0008DF -:10478000751F0008612100084D1F00085D1F00080B -:10479000511F0008591F0008551F00088D200008F0 -:1047A000611F0008912900086D1F000861200008A2 -:1047B00063300000B04700087823002078240020F0 -:1047C0006D61696E0069646C650000000C88000012 -:1047D000447B444444544424800E00004414111487 -:1047E000947B444400000000444444444444444412 -:1047F0000400000044424444444444440000000097 -:1048000044444444444444445CBDFF7F01000000F0 -:10481000ED0300000000000000680300000000003D -:1048200040420F00FE2A0100D204000020080020B0 -:104830000000000000000000000000000000000078 -:104840000000000000000000000000000000000068 -:104850000000000000000000000000000000000058 -:104860000000000000000000000000000000000048 -:104870000000000000000000000000000000000038 -:104880000000000000000000000000000000000028 +:10053000704700BF02E000F000F8FEE772B6264800 +:1005400080F30888254880F30988254825490860F4 +:10055000022080F31488BFF36F8F03F061FC03F077 +:10056000C5FC4FF0553020491B4A91423CBF41F831 +:10057000040BFAE71D49194A91423CBF41F8040BAC +:10058000FAE71B491B4A1C4B9A423EBF51F8040B29 +:1005900042F8040BF8E700201849194A91423CBF81 +:1005A00041F8040BFAE703F03FFC03F0A1FC154C03 +:1005B000154DAC4203DA54F8041B8847F9E700F004 +:1005C0003FF8124C124DAC4203DA54F8041B884732 +:1005D000F9E703F027BC000000020020000800201B +:1005E0000000000808ED00E00001002000020020EB +:1005F00038450008000800208008002080080020FE +:100600002C25002060010008640100086401000836 +:10061000640100082DE9F04FC1F80CD0C3689D4675 +:10062000BDE8F08F002383F311882846A0470020FF +:1006300003F078F9FEE703F001F900DFFEE70000C0 +:10064000F8B500F041FE314A536823F0E06343F00F +:10065000905343F48043536003F07CFB074603F060 +:10066000CBFB0546B8BB2A4B9F4234D001339F4297 +:1006700034D0284B27F0FF029A4232D1F8B200F072 +:100680003BFC2E4642F2107400F03CFC08B1002402 +:10069000264601F00DF940B30024032000F03EF897 +:1006A000264635B11C4B9F4203D0002403F09CFB2F +:1006B0002646002003F058FB0EB100F045F800F08C +:1006C0008DFC01F0E5FF0546BCB900F0CFFC012030 +:1006D00003F02EF9F8E72E460024D5E7044601265C +:1006E000D2E7064641F28834CEE741F288339C4295 +:1006F00004BF4FF47A740126D3E701F0C9FF431B0E +:10070000A342E2D900F020F8DBE700BF000001407F +:10071000010007B0000008B0263A09B0084B187075 +:1007200003280CD8DFE800F008050208022000F0DA +:1007300033BE022000F028BE0022024B5A607047F0 +:10074000800800208408002038B501F0B1F830B1ED +:1007500003221F4B1A7000221E4B5A6038BD1E4BDD +:100760001E4A19680131F9D004339342F9D11C4C67 +:10077000194DD4F80428AA42F0D31A4B9B6803F110 +:10078000006303F508439A42E8D203F001FB03F04B +:1007900013FB002000F0BEFD0220FFF7BFFF124B4D +:1007A000DA690022DA61D96999699A619B6972B63E +:1007B0004FF0E023C3F8085D3021D4F80038D4F8B6 +:1007C000042881F311889D4683F308881047C5E704 +:1007D0008008002084080020008800082088000885 +:1007E00000800008000800200010024049F2690063 +:1007F000084A136899B21B0C00FB013344F25061A4 +:100800001360054B186882B2000C01FB02001860EF +:1008100080B27047180800201408002010B5044664 +:100820000021102200F0D4FD034B03CB2060616057 +:100830001868A06010BD00BFE8F7FF1F2DE9F04168 +:100840000026ADF54E7D6CAC40F2751207460D46A4 +:100850000EA831460D9600F0BBFD4FF4C472314630 +:10086000204600F0B5FD01F013FF4FF47A72B0FBA3 +:10087000F2F0264B0DF13408186093E807000223CC +:1008800084E807000DF5E9702382FFF7C7FF4EF6F5 +:1008900003531F4907A8238403F0D0FD17230DF24B +:1008A000E32284F832310DF12C0C07AB1E4603CE47 +:1008B000664510605160334602F10802F6D1306897 +:1008C0001060B188B379204691809371414601222E +:1008D00000F0CAFD00230393AB7E80B2029305F1C2 +:1008E000190301930123CDE904800093384605A341 +:1008F000D3E90023E97E02F08FFA0DF54E7DBDE8C5 +:10090000F08100BF9E6AC421818A46EE8C080020D7 +:100910004C4400082DE9F0412C4C8046237A0D46CA +:10092000DAB05BBB284627A900F0AEFE07460028D8 +:1009300042D19DF89D60C82E3ED801464FF4A66274 +:10094000204600F045FD4FF48073C4F8F8314FF4B1 +:100950000073C4F80C334FF440733246C4F82034AB +:100960000DF19E0104F1090000F020FD9DF89C307E +:100970002644777223720BB9EB7E23728122002109 +:1009800006AC27A800F024FD0122214627A800F08C +:10099000B7FE00230393AB7E80B2029305F11903E7 +:1009A00001932823CDE904400093404605A3D3E9F1 +:1009B0000023E97E02F030FA5AB0BDE8F08100BFB2 +:1009C000AFF3008026417272DF25D7B7B01D00203B +:1009D000F0B54FF48A750024234EF1B005FB006595 +:1009E00096F8D830D822214685F8DC3085F8E840E2 +:1009F0003AA800F0EDFC06F1090000F0E1FCD5F8A2 +:100A0000E430C2B206AF8DF8F00006F109010DF135 +:100A1000F100CDE93A3400F0C9FC394601223AA888 +:100A200000F09AFE80B2CDE9047008230127CDE9D9 +:100A3000023706F1D80301933023317A00930B4833 +:100A400007A3D3E9002302F0E7F9A04206DD01F095 +:100A50001FFEC5F8E000384671B0F0BD2046FBE748 +:100A600078F6339F93CACD8DB01D0020A4180020C6 +:100A70002DE9F0411D4D1E4E1E4F86B0284602F056 +:100A8000F7F9034658B30024CDE90344ADF8144008 +:100A9000027B02948DF814209968406803AA03C26F +:100AA0001B68DFF8548043F00043029301F0F2FD2D +:100AB000821941F100033846009402A901F0CAF8F6 +:100AC000A04205DD284602F0D7F988F80040D5E7B6 +:100AD00098F80030072B05D8013388F8003006B0AD +:100AE000BDE8F081014802F0C7F9F8E7A41800203A +:100AF00040420F00D8180020E522002070B50D46B6 +:100B000014461E4602F0E4F850B9022E10D1012C12 +:100B10000ED112A3D3E900230120C5E9002307E089 +:100B2000282C10D005D8012C09D0052C0FD000207E +:100B300070BD302CFBD10BA3D3E90023ECE70BA352 +:100B4000D3E90023E8E70BA3D3E90023E4E70BA3F1 +:100B5000D3E90023E0E700BFAFF30080401DA120F0 +:100B600026812A0B78F6339F93CACD8D9E6AC421C5 +:100B7000818A46EE26417272DF25D7B7F017304AD8 +:100B800039059E5638B505460E4C0021013500F05A +:100B9000E3FBA4F82C55B4F82C0500F0C5FB78B1A4 +:100BA000B4F82C0500F0D0FB014648B9B4F82C0588 +:100BB00000F0D2FBB4F82C350133A4F82C35EAE769 +:100BC00038BD00BFB01D002010B50A4B0A4A1A609C +:100BD00093F8602442B9D3F85C442CB1204600F06D +:100BE000E5FE204603F06CFBBDE81040034800F032 +:100BF000DDBE00BFD8180020A0440008201D002042 +:100C00002DE9F04F8FB000AF05460C4602F060F8BA +:100C1000002848D1237E022B1AD1E38A012B17D159 +:100C200001F036FD0646FFF7E1FD4FF4C873B0FB57 +:100C3000F3F202FB1303DFF8A0829BB206F51676EF +:100C40003344C8F80030E37E33B90022A34B1A7056 +:100C50003C37BD46BDE8F08F204607F1240100F087 +:100C6000D1FC0028F4D107F11400FFF7D7FD97F865 +:100C7000264007F11401224607F1270003F06AFB22 +:100C80000028E2D10F2C08D8944B1C70D8F8003003 +:100C9000A3F51673C8F80030DAE7284697F8241051 +:100CA00002F00EF8D4E7E38A282B2BD010D8012BC2 +:100CB00023D0052BCCD1BFF34F8F8949894BCA680C +:100CC00002F4E0621343CB60BFF34F8F00BFFDE738 +:100CD000302BBDD1844EE17E327A9142B8D131467B +:100CE0000022607E91F8DC50854200F0A580013240 +:100CF000042A01F58A71F5D1AAE721462846FFF7B3 +:100D00009DFDA5E721462846FFF704FEA0E7B2F8BF +:100D1000EC507B6005F103094FEA99094FEA89021B +:100D2000D11DC908A8EBC1039D46EB4600215846DA +:100D300000F04EFB04F1EE012A465846314400F023 +:100D400035FB7B6813B9012000F0E4FA96F8D20075 +:100D500000F0EAFA044630B9307200F005FB204694 +:100D600000F0D8FAB0E0D6F8D4203AB996F8D2001C +:100D7000B6F82C25824201D8FFF704FFD6F8D4201C +:100D80002A44944208D296F8D200B6F82C250130B5 +:100D9000824201D8FFF7F6FE594670685FFA89F281 +:100DA00000F01EFB08B9C54678E0726896F8D200DC +:100DB0002A447260D6F8D42005EB0209C6F8D49014 +:100DC00000F0B2FA814509D396F8D220D6F8D400C3 +:100DD0000132001B86F8D220C6F8D400FF2D0FD8B0 +:100DE0000024347200F0C0FA204600F093FA00F0BC +:100DF0005FFD3E4B188108B9FFF7A6FCC54627E703 +:100E0000BB6896F8D9000AFB0362D2F8E410FB68CD +:100E100001F5806182F8E830C2F8E030C2F8E410F1 +:100E2000FFF7D6FDFFF724FE96F8D920013202F035 +:100E3000030286F8D920B6E74FF48A7A0AFB02F556 +:100E400005F1EA012046314400F0B2FCF8600028C8 +:100E50007FF4FEAE0122354485F8E82001F018FC4D +:100E6000D5F8E020801A192840F6B83238BF19208A +:100E7000904228BF1046FFF7E5FA1D49FFF778F9C1 +:100E800004463068FFF7DEFA1A49FFF771F90146A8 +:100E90002046FFF727FAFFF72DFB306096F8D93090 +:100EA000BB60BA6873680AFB02F4321992F8E81062 +:100EB00059B1D2F8E410E8468B423FF428AF002144 +:100EC00082F8E810C2F8E010C5467368074A9B0A2A +:100ED00001331381BCE600BFA01800209D1800203C +:100EE00000ED00E00400FA05B01D00208C08002091 +:100EF000CDCCCC3D6666663F014B1870704700BF95 +:100F00009808002030B54FF000542B4B226885B074 +:100F10009A4207D002F07AFF044620BB0024204604 +:100F200005B030BD627D254B25481A70237D002514 +:100F300003724FF48073C0F8F8314FF40073C0F8B7 +:100F40000C334FF44073C922C0F820341D49C0F857 +:100F5000E450093000F02AFA2046E022294600F049 +:100F600037FA0124DBE7184A184DD36943F00073C0 +:100F7000D361AA6D164B9A42D0D12B6E013B7E2BCA +:100F8000CCD8144A01AB07CA83E8070018460321EE +:100F900000F05EFC6B6D83424FF00003BED12A6D02 +:100FA0008A4203BFAB652A6E044B1C4601BF1A7010 +:100FB000EA6D094B1A60B2E79AAD44C59808002063 +:100FC000B01D002016000020001002400066004006 +:100FD0005041A0B0586600401008002037B500F01E +:100FE00067FC0223184D01226B71184B2881196888 +:100FF000174801F0F9F900230193164B16490093A5 +:101000004FF48052154B164801F030FE154B1978FD +:1010100011B1134801F054FE01F03AFB0446FFF70A +:10102000E5FB4FF4C873B0FBF3F202FB130304F5C6 +:1010300016709BB218440C4B186002F0DDFE08B12C +:101040000F232B8103B030BD8C0800201008002036 +:10105000D8180020FD0A00089C080020010C000898 +:10106000A418002098080020A01800202DE9F04FB7 +:101070000FF22829D9E900897E4C93B0FFF7F8FCDC +:1010800000230BAE7C4FDFF8F4A10A93ADF83430A7 +:101090000B9373604FF0000B002200230125CDE974 +:1010A000002338465B460DF11D0207A98DF81C5040 +:1010B0008DF81DB001F04AF99DF81C30002B40F06E +:1010C000A080204601F004FE0646002845D101F02C +:1010D000DFFA6B4F3B6898423FD301F0D9FA824662 +:1010E000FFF784FB4FF4C873B0FBF3F202FB13006D +:1010F00083B20AF5167018443860624F0EA897F84C +:1011000000B0BBF1000F14BF33462B46CBF1100AE1 +:101110005FFA8AFA8DF82830FFF780FBBAF1060FE4 +:1011200028BF4FF0060A0EAB03EB0B0152460DF140 +:10113000290000F03BF90AAB039318230AF10102DE +:101140000293514BD2B2CDE900530492204647A3FB +:10115000D3E9002301F002FE3E7001F099FA4B4AF8 +:101160004B4D1368C31AB3F57A7F2ED3106001F08C +:1011700091FA02460B46204601F088FE204601F017 +:10118000A7FD10B32B7A434E002B14BF0323022379 +:10119000737101F07DFA4FF47A73B0FBF3F00EAF88 +:1011A000012230603946304600F004FA18230293D9 +:1011B000394B80B2019340F25513CDE9037000938F +:1011C00042464B46204601F0C9FD2B7AB3B101F0EF +:1011D0005FFA002607464FF48A7A95F8D900304422 +:1011E00000F003000AFB005393F8E8206AB30136CD +:1011F000042EF2D12B7A002B7FF440AF13B0BDE860 +:10120000F08FDAF80C30594683F00803CAF80C3036 +:1012100010220EA800F0DCF80DF11E0308AA0AA99E +:10122000384600F00DFE96E803000FAB83E803009C +:101230009DF8343020468DF844300A9B0EA90E9359 +:10124000DDE9082301F0F8FF24E7D3F8E02042B1FC +:101250002B68BA1AFA2B38BFFA230533B2EB430FC7 +:10126000C5D3FFF7B5FB0028C1D1C3E7401DA120BE +:1012700026812A0BA4180020D8180020000C014059 +:10128000A01800209D1800209C180020E0220020BB +:10129000B01D00208C080020E4220020F1C6A7C168 +:1012A000D068080F08B5054800F062FEBDE80840A8 +:1012B0000020034A034902F0FDBF00BFD8180020F8 +:1012C00020230020C90B000870B502F0EBFB0025BD +:1012D0000E4C0F4E20803068238883420CD80025A6 +:1012E0002088013802F0DAFB23880544013BB5F57C +:1012F000805F2380F4D370BD02F0D0FB33680544D7 +:101300000133B5F5084F3360E5D3E8E71423002037 +:10131000E822002002F054BC00F10060920000F5C9 +:10132000084002F0F9BB0000054B1A68054B1B880A +:101330009B1A834202D9104402F0B0BB00207047D0 +:10134000E822002014230020024B1B68184402F0FE +:10135000ABBB00BFE8220020024B1B68184402F020 +:10136000B5BB00BFE8220020064991F8243033B114 +:1013700000230822086A81F82430FFF7CDBF01203E +:10138000704700BFEC220020022802BF0822014B58 +:101390001A617047000C0140022802BF4FF400227E +:1013A000014B1A61704700BF000C0140002310B5CB +:1013B000934203D0CC5CC4540133F9E710BD000064 +:1013C00003460246D01A12F9011B0029FAD17047D0 +:1013D00003460244934202D003F8011BFAE7704728 +:1013E0002DE9F8431F4D144695F8242007468846FA +:1013F00052BBDFF870909CB395F824302BB92022B3 +:10140000FF2148462F62FFF7E3FF95F8240041468D +:10141000C0F10802A24228BF224605EB8000D6B2E6 +:101420009200FFF7C3FF95F82430A41B1E44F6B2C8 +:10143000082E17449044E4B285F82460DBD1FFF70E +:1014400093FF0028D7D108E02B6A03EB8203834285 +:10145000CFD0FFF789FF0028CBD10020BDE8F8836B +:101460000120FBE7EC2200202DE9F0470D46044661 +:1014700000219046284640F27912FFF7A9FF234643 +:1014800020220021284601F079FE02222021284650 +:10149000231D01F073FE032222212846631D01F063 +:1014A0006DFE032225212846A31D01F067FE1022B0 +:1014B0002821284604F1080301F060FE08223821A3 +:1014C000284604F1100301F059FE08224021284665 +:1014D00004F1110301F052FE08224821284604F1CC +:1014E000120301F04BFE20225021284604F1140380 +:1014F00001F044FE40227021284604F1180301F057 +:101500003DFE0822B021284604F1200301F036FEFA +:101510000822B821284604F1210301F02FFEC0263D +:1015200004F122073B46314608222846083601F0DE +:1015300025FEB6F5A07F07F10107F3D10822314659 +:10154000284604F1320301F019FE002704F1330AA2 +:1015500094F832304FEAC7099F4209F5A47615D3B3 +:10156000B8F1000F08D131460722284604F59973D7 +:1015700001F004FE09F24F16274694F832213B1B76 +:1015800093420CD3F01DC008BDE8F0870AEB0703B7 +:1015900008223146284601F0F1FD0137D8E73146EF +:1015A00007F233130822284601F0E8FD0836013718 +:1015B000E3E7000038B50C460021054621600346EC +:1015C000C4F803102046202201F0D8FD20462B1D30 +:1015D0000222202101F0D2FD20466B1D0322222190 +:1015E00001F0CCFD2046AB1D0322252101F0C6FDF4 +:1015F00020461022282105F1080301F0BFFD072035 +:1016000038BD00000023F7B50E460546047F0722CB +:101610000091194601F074FC731C00930122002311 +:101620000721284601F06CFCC4B9B31C00930522C5 +:1016300023460821284601F063FC0D243746B27882 +:10164000BB1B934211D32B7FE01DC008AC8ABBB9F2 +:10165000A04294BF0020012003B0F0BDAB8A082453 +:10166000DB00083BDB08B370E8E7FB1C2146009376 +:1016700008220023284601F043FC08340137DEE746 +:10168000001B18BF0120E7E70023F7B50E46047FD3 +:10169000082200911946054601F032FC731CC4B9BA +:1016A0000822009311462346284601F029FC102405 +:1016B000012372785F1C013B934211D32B7FE01D05 +:1016C000C008AC8ABBB9A04294BF0020012003B07F +:1016D000F0BDAB8A0824DB00083BDB087370E7E74A +:1016E000F3192146009308220023284601F008FC44 +:1016F00008343B46DDE7001B18BF0120E7E7000088 +:10170000F8B50E4605461446002181223046FFF703 +:101710005FFE2B4608220021304601F02FFD7CB9E8 +:101720000722082130466B1C01F028FD0F240123FD +:101730006A785F1C013B934204D3E01DC008F8BDEA +:101740000824F4E72146EB190822304601F016FD83 +:1017500008343B46ECE70000F8B50E460546144653 +:101760000021CE223046FFF733FE2B4628220021EF +:10177000304601F003FD7CB908222821304605F1EE +:10178000080301F0FBFC30242F462A7A7B1B93428E +:1017900004D3E01DC008F8BD2824F5E7214607F171 +:1017A00009030822304601F0E9FC08340137ECE770 +:1017B000F7B5047F0E460091012310220021054653 +:1017C00001F09EFBC4B9B31C0093092223461021EB +:1017D000284601F095FB192437467288BB1B9A42B4 +:1017E00011D82B7FE01DC008AC8ABBB9A04294BFC2 +:1017F0000020012003B0F0BDAB8A1024DB00103BB9 +:10180000DB087380E8E73B1D214600930822002394 +:10181000284601F075FB08340137DEE7001B18BFCE +:101820000120E7E730B5094D0A4491420DD011F887 +:10183000013B5840082340F30004013B2C4013F0C7 +:10184000FF0384EA5000F6D1EFE730BD2083B8ED06 +:101850004FF0FF33F7B500EB81061946DFF848C0BB +:10186000DFF848E0B0421BD050F8042B01AF0192E2 +:10187000042217F8014B81EA046108240D46DB18A5 +:101880004941013C002DBCBF83EA0C0381EA0E01F3 +:1018900014F0FF04F2D1013A12F0FF02E9D1E1E7BE +:1018A000D843C94303B0F0BD9336EAA9EBE1F04257 +:1018B000F7B56B46374A106851686A4603C3082378 +:1018C0003549364802F056FD0446002833D10A2532 +:1018D0006B46334A106851686A4603C3082331498E +:1018E0002E4802F047FD0446002849D00369B3F5AD +:1018F0005E3F45D840F2ED32B0F8661091423FD1DC +:10190000294A024402F15C018B4239D35C3B2349F2 +:1019100000209E1AFFF786FF07463246002004F19A +:101920006401FFF77FFFA3689F4229D1E3689842D3 +:1019300008BF002524E00369B3F55E3F27D840F2D5 +:10194000ED32418B914220D1174A024402F110013D +:101950008B4218D3103B114900209D1AFFF762FFFC +:1019600006462A46002004F11801FFF75BFFA36832 +:101970009E4202D1E368984201D00D25A8E70025D8 +:10198000284603B0F0BD1025A2E70C25A0E70B25E3 +:101990009EE700BF64440008DC770300008800086D +:1019A0006D440008907703000878FFF710B5037CBA +:1019B000044613B9006802F0C5FC204610BD0000C3 +:1019C0000023BFF35B8FC360BFF35B8FBFF35B8FFD +:1019D0008360BFF35B8F7047BFF35B8F0068BFF31B +:1019E0005B8F704770B505460C30FFF7F5FF05F1CA +:1019F000080604463046FFF7EFFFA04206D93046FE +:101A00006D68FFF7E9FF2C44201A70BD3046FFF7E0 +:101A1000E3FFF9E770B505464068A0B105F108009D +:101A2000FFF7DAFF05F10C0604463046FFF7D4FF56 +:101A3000844288BF0025304698BF6D68FFF7CCFF11 +:101A4000013C2C44201A70BD38B50C460546FFF702 +:101A5000C9FFA04210D305F10800FFF7BDFF044401 +:101A60006868BFF35B8FB4FBF0F100FB1144AC601E +:101A7000BFF35B8F012038BD0020FCE72DE9F0416A +:101A8000144607460D46FFF7C5FF844228BF0446AB +:101A9000D4B1B84658F80C6B4046FFF79DFF06449A +:101AA0002E6040467E68FFF797FF331A9C4203D8AA +:101AB00001206C60BDE8F0816B603B68A61B0644AA +:101AC000AB600220EE60F5E72046F3E738B50C4640 +:101AD0000546FFF79FFFA04210D305F10C00FFF76A +:101AE0007BFF04446868BFF35B8FB4FBF0F100FB3D +:101AF0001144EC60BFF35B8F012038BD0020FCE790 +:101B00002DE9FF410F46694606466C46FFF7B6FFD2 +:101B1000002504EBC008444508D0626820687919A4 +:101B2000FFF744FC636808341D44F4E72946304657 +:101B3000FFF7CCFF284604B0BDE8F081F8B50546B4 +:101B40000C300F46FFF748FF05F108060446304603 +:101B5000FFF742FFA042304688BF6C68FFF73CFFAA +:101B6000201A386020B130462C68FFF735FF20443A +:101B7000F8BD0000F7B5174606460D46FFF732FFE1 +:101B8000B842044628BF3C460190DCB1304601A96A +:101B9000FFF7D4FF019B33B93268C5E90233C5E9C9 +:101BA000002401200CE09C4238BF01942860019879 +:101BB00084426860F5D9241A02203368EC60AB6077 +:101BC00003B0F0BD2046FBE72DE9FF410E46694614 +:101BD000FFF7D0FF6C46002504EBC007BC4209D0DC +:101BE000D4F804807019424654F8081BFFF7DEFB56 +:101BF0004544F3E7284604B0BDE8F08138B5054612 +:101C0000FFF7E2FF044601462846FFF71DFF204686 +:101C100038BD000010B4026854681A46234610BC50 +:101C200018470000002070470020704770470000F0 +:101C3000002070470E20704790F8C804C0F34000A1 +:101C40007047000090F9D00470470000C0F8CC1431 +:101C500001207047F7B50C68BDF8207014F00054EF +:101C60006BD10D7B082D68D8302585F31188456927 +:101C7000AE6876010CD4AC68240108D4AC6814F0CA +:101C8000805458D184F31188204603B0F0BD01245C +:101C90000E6804F1180C002EBABFF60046F00406D8 +:101CA00076054FEA0C1C45F80C600E684FEA041CE0 +:101CB00016F0804F1CBF05EB0C0EDEF88061AC44C3 +:101CC0001CBF46F00206CEF880610E7B05EB0415C2 +:101CD000CCF884618E68C5F88C614E68C5F888615F +:101CE0000E46DCF8805145F00105CCF8805100EB40 +:101CF0004415C5F86824C5F86C3401F10C0C05F5E1 +:101D00008E6556F804EB664545F804EBF9D1368844 +:101D100024342E8000EB4414267907F0030526F0C6 +:101D20000B0635432571002484F31188009700F0D9 +:101D3000D1FC0120A9E70224AAE74FF0FF30A4E775 +:101D400038B50446D0F85C040D46FFF763FE1F2843 +:101D50000AD920222946D4F85C04FFF7D1FEA0F16D +:101D600020035842584138BD0020FCE708B5302315 +:101D700083F31188D0F85C04FFF722FE002383F37D +:101D8000118808BD00220260828142608260704733 +:101D90000022002310B5C0E900230023044603817C +:101DA0000C30FFF7EFFF204610BD0000F0B590F8B3 +:101DB000C8340D4613F0040FC3F3800108BF114669 +:101DC00005F1240661F3820380F8C83400EB461362 +:101DD0001B790446D80789B02DD572B319072CD4C6 +:101DE00004EB45156846FFF7D3FF05F58E6303AA9C +:101DF00005F58F65174618685968083303C7AB4265 +:101E00003A46F7D11868694638609B882046BB80FF +:101E1000DDE90E23CDE900230123ADF80830236866 +:101E2000DB6B984704EB461423791A075CBF43F039 +:101E30000803237101E0002AF4D109B0F0BD0000CD +:101E40002DE9F0479A46054688469146302388B0EA +:101E500083F311886846FFF79BFFD5F85C04FFF712 +:101E6000C1FD1F282BD920226946D5F85C04FFF755 +:101E7000C5FE202823D1444603AE05AB374603CF29 +:101E80009F42206061603E4604F10804F6D1386844 +:101E90002060BB88A380DDE90023C9E90023BDF8E9 +:101EA0000830AAF80030002383F3118853464A46CD +:101EB0004146284608B0BDE8F04700F0F9BB0020D5 +:101EC00080F3118808B0BDE8F087000000232DE9F9 +:101ED000F0470446C0E90133224B0E4640F8183B58 +:101EE000FFF750FF04F1480704F12800FFF750FF07 +:101EF0003D4604F5896828462035FFF749FF4545EA +:101F0000F9D14FF48063C4F84874C4F84C34002706 +:101F100001234FF000084FF00009C4F85C54C4F8E6 +:101F20005074C4F8547484F8583484F8603404F558 +:101F3000916504F59D6A45E90889A5F11800FFF748 +:101F400021FF203545F8287C5545F4D184F8D0642C +:101F500016B1054800F096FB044B20466361BDE8CE +:101F6000F08700BFA04400087844000800640040E7 +:101F700010B50446034B19784A1C1A70FFF7A6FFE8 +:101F8000204610BD1C2300202DE9F04300294FD02E +:101F9000284F294BB7FBF1F499428CBF0A23112338 +:101FA000B4FBF3FC581E03FB1C43C5B22BB1022843 +:101FB0000346F5D80020BDE8F0830CF1FF36B6F5F6 +:101FC000806FF7D24FF47A74C5EBC50E0EF10303A0 +:101FD0004FEAE30909FB0444C3F3C703E81AC0B29C +:101FE00009F101088044B4FBF8F4B4F5617FC2BF85 +:101FF0000EF1FF33C3F3C703E81A03F10104C8BFAE +:10200000C0B2E4B204440CFB04F4B7FBF4F4A14204 +:10201000D0D1013BDBB20F2BCCD80138C0B207289E +:10202000C8D800211071168001209170D370C2E7CA +:102030000846C0E7005125023F420F0070B5054633 +:102040000E464FF47A746B6901205B6803F001035C +:10205000B34204D001F06CFC013CF4D1204670BDC9 +:1020600030B54269936913F0700F16D000230B4C02 +:10207000936103F1240200EB421211794D0709D557 +:10208000890707D5416954F823508D60117941F0D3 +:10209000040111710133032BEBD130BD8C440008D6 +:1020A00073B51D46436916469A680446D20709D59A +:1020B00001219A689960C2F340020021CDE90065D0 +:1020C000FFF774FE63699A68D1050BD54FF48071F0 +:1020D0009A6820469960C2F340220121CDE900654B +:1020E000FFF764FE63699A68D2030BD54FF4803121 +:1020F0009A6820469960C2F340420221CDE900650A +:10210000FFF754FED4F8CC0410B103681B6998475C +:10211000204602B0BDE87040FFF7A2BFF8B5044604 +:102120004669002970D106F10C07386880076ED027 +:10213000386806EB01104FEA011CD0F8B011D0F856 +:10214000B051490746BFED0845F000456D0DA5614A +:10215000D0F8B011890744BF45F08045A561D0F89B +:10216000B40106EB0C0100F00F0084F82400D1F854 +:10217000B80104F124052077D1F8B801000A60778E +:10218000D1F8B801000CA077D1F8B801000EE077C3 +:10219000D1F8BC0184F82000D1F8BC01000A84F811 +:1021A0002100D1F8BC01000C84F82200D1F8BC1148 +:1021B00004F13400090E84F823103821396004F149 +:1021C000180151F8046BA94240F8046BF9D1098851 +:1021D0000180C4E90A2300232146238651F8283BC5 +:1021E0002046DB6B984794F8C834D4F8CC0443F00D +:1021F000040384F8C83410B103681B69984720466B +:10220000BDE8F840FFF72CBF06F110078DE7F8BDD9 +:1022100010B5044600F03EFA02460B4652EA0301AE +:1022200002D0013A63F100030449086820B1214655 +:10223000BDE81040FFF772BF10BD00BF182300209B +:10224000F0B5302181F311880021124F00F58D6522 +:1022500001F1240400EB4414267916F0040F0FD189 +:10226000F6060DD5D5E900C694459E4108D24669CB +:1022700057F821C0C6F808C0267946F00406267132 +:102280000131032905F12005E2D1002383F31188F0 +:10229000F0BD00BF8C44000808B5302383F31188DB +:1022A000FFF7DEFE002383F3118808BDF8B543690C +:1022B000044698680E4600F0E050B0F1E05F1FD091 +:1022C000E8B1302383F31188002504F58E6704EB11 +:1022D000451393F884341A0706D50135032D07F109 +:1022E0002007F4D1012007E05B07F6D439463046D9 +:1022F00000F02AFA0028F0D1002383F31188F8BDFA +:102300000120FCE708B5302383F31188D0F85C0482 +:10231000FFF768FB002383F3118843090CBF0120FA +:10232000002008BDF8B51D46002313700F46064671 +:102330001446FFF7E7FF80F00100387025B1294609 +:102340003046FFF7B3FF2070F8BD0000F8B50C462B +:1023500015461E46074600F09DF90B4621780246B9 +:1023600009B9287850B13846FFF76AFFFFF794FFA4 +:1023700033462A462146FFF7D5FF0120F8BD00006D +:1023800038B50446302080F31188164BDA6942F0E4 +:102390000072DA611A6942F000721A611A6922F059 +:1023A00000721A61002383F3118894F8C83413F083 +:1023B000010516D1A9B180F311880321132001F082 +:1023C000ABF90321142001F0A7F90321152001F036 +:1023D000A3F994F8C83443F0010384F8C83485F3B2 +:1023E000118838BD001002402DE9F04790F8D03434 +:1023F0000446012B0F46154688B07ED8804E56F80D +:1024000023200AB946F82300D6F80090E760257427 +:10241000B9F1000F63D094F8D034012B6FD00121B3 +:102420002046FFF7ADFF302383F311884FF00008FB +:102430006269136823F0020313606269136843F052 +:10244000010313606369C3F8148088F311880121C4 +:102450002046FFF7F3FD002800F09280D4F85C04DA +:10246000FFF7AEFAA14604F1600A20220021684677 +:10247000FEF7AEFF02A8FFF785FC6A46CDF818808C +:1024800009F58D630DF1180C164603CE66451860EC +:102490005960324603F10803F6D1306809F120098A +:1024A00018603279CA451A71DFD1002694F8C83411 +:1024B0006A466FF3820384F8C83439462046ADF883 +:1024C0000060ADF802608DF80460FFF75DFD6369A0 +:1024D00048BB4FF400421A6008B0BDE8F0874FF4E3 +:1024E0009B6001F0EFFE804610B14946FFF7EEFC1D +:1024F000C6F80080B8F1000F8DD10020ECE73068FD +:1025000003681B6B98470146002888D13068FFF7A5 +:1025100037FF30682A46036839465B6898470028C9 +:102520007FF47DAFE9E76122022D0CBF4FF000413F +:1025300000211A609DF802309DF803201B0612044A +:1025400002F4702203F040731343BDF800202046CC +:10255000C2F3090213439DF80420120502F4E002BD +:10256000134362690B43D3611322636931465A6195 +:102570006269136823F001031360FFF75FFD08B978 +:102580006369A6E794F8D03493BB6169D1F800225F +:1025900042F00102C1F800226169D1F8002222F460 +:1025A0007C5222F00E02C1F800226169D1F80022AB +:1025B00042F46062C1F8002241F6FF716269C2F81C +:1025C00014326269C2F804326269C2F80C1262699C +:1025D000C2F840326269C2F8443201226369C3F82A +:1025E0001C226269D2F8003223F00103C2F80032E3 +:1025F00094F8C83443F0020384F8C8346CE700BF91 +:102600001823002008B500F045F802460B4652EAB0 +:10261000030102D0013A63F100030449086808B1DC +:10262000FFF73EFDBDE8084001F054B81823002034 +:1026300008B50020FFF7ECFDBDE8084001F04AB8FE +:1026400008B50120FFF7E4FDBDE8084001F042B8FD +:10265000EFF30983EFF30583014B9B6BFEE700BFAC +:1026600000ED00E008B5FFF7F3FF0000EFF309838A +:10267000EFF30583014B5B6BFEE700BF00ED00E06D +:10268000FEE700000FB408B5029801F001F9FEE77B +:1026900001F010BB01F0BCBA13B56C4684E806002B +:1026A000031D94E8030083E80500012002B010BD7B +:1026B000F8B586680D4656B11B885B0707D4D0E98C +:1026C00000379B6B98472A46C1B23846B047012075 +:1026D000F8BD0000F0B5866805460C4689B05EB1CD +:1026E000BDF838305B070AD4D0E900379B6B9847B8 +:1026F0002246C1B23846B047012009B0F0BD0022E1 +:102700000023CDE9002300230A46ADF8083001F18B +:10271000080603AB1C4610685168083203C4B24275 +:102720002346F7D1106820609288A280FFF7B2FF9D +:102730000423ADF808302B68CDE90001DB6B694656 +:1027400028469847D8E7000030B503680968DD0FD0 +:10275000B5EBD17F23F0604421F060424FEAD170A5 +:102760000BD0002BB8BFA40C0029B8BF920C944228 +:1027700002D034BF0120002030BD944205D1C1F306 +:102780008070C3F380738342F6D194422CBF002043 +:102790000120F1E72DE9F041456A15B94162BDE834 +:1027A000F0814B68AC4623F06047C3F38A4616EAD3 +:1027B000230638BF3E464FEAD37EC3F380782B46CC +:1027C0005A68BEEBD27F22F060440AD0002A18DAA1 +:1027D000A40CB44217D19D420FD10D60DEE7134621 +:1027E000EEE7A74207D102F08044C2F3807242456F +:1027F0000BD054B1EFE708D2EDE7CCF800100B6036 +:10280000CDE7B44201D0B442E5D81A689C46002A0C +:10281000E5D11960C3E700002DE9F0474FF47F4987 +:10282000089D01F007044FEAD508224405F007058A +:1028300000EBD100944201D1BDE8F08704F0070716 +:1028400005F0070A57453E4638BF5646111BC6F1EC +:1028500008068E4228BF0E46E108415C08EBD50E03 +:1028600013F80EC0B94029FA06F721FA0AF1FFB2AF +:102870008CEA010147FA0AF739408CEA010C03F8A7 +:102880000EC034443544D5E7082341F2210280EAE2 +:10289000012001B24000002980B203F1FF33B8BF2C +:1028A000504013F0FF03F4D17047000038B50C46D8 +:1028B0008D18A54200D138BD14F8011BFFF7E4FFC5 +:1028C000F7E700000346406848B1026899895A60FA +:1028D0005A89013292B291425A8138BF9A81704727 +:1028E00070B504460D4688B0202200216846FEF7E8 +:1028F0006FFD20460495FFF7E5FF024658B16B4691 +:10290000054608AE1C4603CCB442286069602346E5 +:1029100005F10805F6D1104608B070BD082817D992 +:1029200009280CD00A280CD00B280CD00C280CD06D +:102930000D280CD00E2814BF4020302070470C20EA +:1029400070471020704714207047182070472020CF +:1029500070470000082817D90C280CD910280CD96A +:1029600014280CD918280CD920280CD930288CBF51 +:102970000F200E207047092070470A2070470B2057 +:1029800070470C2070470D20704700002DE9F84378 +:10299000078C0446072F1ED9D0E9029800254FF670 +:1029A000FF73C5F12006A5F1200029FA05F108FA08 +:1029B00006F628FA00F031430143C9B21846FFF782 +:1029C00063FF0835402D0346EBD13A46E169BDE887 +:1029D000F843FFF76BBF4FF6FF70BDE8F8830000C8 +:1029E00010B54B6823B9CA8A63F30902CA8210BDC5 +:1029F00004691A681C600361C38A013BC3824A6090 +:102A0000EFE700002DE9F84F1D46CB8A0F46C3F3D0 +:102A100009010529814692460B4630D00020AAB212 +:102A200007F11A049EB2042E1FFA80F80FD89045C1 +:102A300003F1010306D3FB8A0A4462F30903012070 +:102A4000FB821AE01AF800600130E654EAE790458C +:102A5000F1D21C23A1F1050BBBFBF3F203FB12BB6C +:102A60007C681FFA8BF6002C45D14846FFF72AFFF9 +:102A7000044638B978606FF00200BDE8F88F4FF077 +:102A80000008E6E70026066078604FF0000BADB264 +:102A9000454510D90AEB0803221D13F8011B08F164 +:102AA00001089155B1B21B291FFA88F82BD0454572 +:102AB00006F10106F1D8FB8AC3F30902154465F358 +:102AC0000903BCE71C46013292B22368002BF9D1FE +:102AD0006B1F0B441C21B3FBF1F301339BB29A42F1 +:102AE000D3D2BBF1000FD0D14846FFF7EBFE20B99F +:102AF000C4F800B0BFE70122E7E7C0F800B05E46C7 +:102B000020600446C1E74545D5D94846FFF7DAFEBF +:102B100008B92060AFE7C0F800B000262060044686 +:102B2000B6E700002DE9F74F1C465B69074688466B +:102B30000092002B00F09780238C2BB1E269002AD1 +:102B400000F09180072B33D807F10C00FFF7BAFE95 +:102B5000054628B96FF00205284603B0BDE8F08F9E +:102B600014220021FEF734FC228CE16905F10800F3 +:102B7000FEF71CFC208C48F00041013080B2FFF7CA +:102B8000E9FEFFF7CBFE013880B2208401302874C3 +:102B90006369228C1B782A4403F01F0363F03F0310 +:102BA0001372384669602946FFF7F4FD0125D3E723 +:102BB0004FF000094FF0800A4E464D4600F10C03DD +:102BC00001930198FFF77EFE83460028C2D01422AD +:102BD0000021FEF7FDFB002E3BD10222009BABF84B +:102BE00008300BF1080E1FFA82FC0CF10100BCF159 +:102BF000060F218C80B201D88E422CD3FFF7AAFE9B +:102C0000FFF78CFE8E4208BF4FF0400A6269013820 +:102C1000127880B202F01F0242EA49120BEB000167 +:102C20004AEA020A013048F0004281F808A08BF815 +:102C3000100059463846CBF80420FFF7ABFD238C33 +:102C40000135B3424FF0000A2DB289F00109B8D125 +:102C500082E70022C5E7E169895D01360EF80210BE +:102C6000B6B20132BFE76FF0010575E7F8B504466B +:102C700015460E46302200211F46FEF7A9FB069B93 +:102C8000B5F5001F6360079B28BF4FF6FF72A36274 +:102C90004FF0000338BF6A09A760E66197B204F1FC +:102CA00010009A4206D800230360A782E3822383A0 +:102CB000E360F8BD0660013330462036F1E70000DE +:102CC00003781BB94BB2002BC8BF017070470000DE +:102CD00000787047F8B50C46C969074611B9238CCE +:102CE000002B37D1257E1F2D34D8387828BB228C75 +:102CF000072A2CD8268A36F003032BD14FF6FF7013 +:102D0000FFF7D4FD4FF6FF7220F0010036024004B9 +:102D100046EA0565400C45EA4025234629463846E3 +:102D2000FFF700FF002807DD626913780133DBB28B +:102D30001F2B88BF00231370F8BD218A2D0645EA9A +:102D4000012505432046FFF721FE0246E5E76FF027 +:102D50000300F1E76FF00100EEE7000070B50446F4 +:102D60001D4616468AB0282200216846FEF730FB31 +:102D7000BDF838306946ADF810300F9B20460593FA +:102D80009DF84030CDE902658DF81830119B07930E +:102D9000BDF84830ADF82030FFF79CFF0AB070BD99 +:102DA0002DE9F041D36905460C4616460BB9138C44 +:102DB0005BBB377E1F2F28D895F80080B8F1000F35 +:102DC00026D03046FFF7E2FD3378210241EAC331D5 +:102DD00041EA0801338A41EA076141EA03410246B8 +:102DE0003346284641F08001FFF79CFE00280ADDAB +:102DF0003378012B07D1726913780133DBB21F2BB3 +:102E000088BF00231370BDE8F0816FF00100FAE77E +:102E10006FF00300F7E70000F0B504460D461E46CC +:102E200017468BB0282200216846FEF7D1FA9DF89C +:102E30004C3029465A1E534253418DF800309DF8BC +:102E400040306A46ADF81030119B204605939DF83E +:102E50004830CDE902768DF81830149B0793BDF801 +:102E60005430ADF82030FFF79BFF0BB0F0BD0000F1 +:102E7000406A00B104307047436A1A6842620269CE +:102E80001A600361C38A013BC38270472DE9F04198 +:102E9000D0F8208014461D4641460027174E09B938 +:102EA000BDE8F081D1E90223A21A65EB0303964243 +:102EB00077EB03031ED2036A8B420DD1FFF790FD1F +:102EC000036A1B68036203690B60C38A0161016ABC +:102ED000013B8846C382E2E7FFF782FD0B68C8F832 +:102EE000003003690B60C38A0161013BC382D8F8DB +:102EF0000010D4E788460968D1E700BF80841E002F +:102F00002DE9F04F8BB00D4614469B468046DDF808 +:102F10005090002800F01A81B9F1000F00F01681DE +:102F2000531E3F2B00F21281012A03D1BBF1000F87 +:102F300040F00C810023CDE90833B8F81430B5EB2C +:102F4000C30F4FEAC30703D300200BB0BDE8F08FD7 +:102F50002B199F42D8F80C3036BF7F1B2746FFB293 +:102F60001BB9D8F81030002B7BD0272D4ED8C5F1D7 +:102F70002806B7424FF0000334BF3E46F6B2009336 +:102F800029463246D8F8080008ABFFF745FCA7EB06 +:102F9000060A35445FFA8AFA2821B8F8143003F19A +:102FA0000053053BDB000493D8F80C300393039BDC +:102FB00013B1BAF1000F2CD1D8F8100040B1BAF11A +:102FC000000F05D05246009608AB691AFFF724FCA3 +:102FD00038B2002FB8D066070AD00AAB03EBD40191 +:102FE00011F8083C624202F00702134101F8083C64 +:102FF000082C3DD9102C40F2B680202C40F2B8802D +:10300000BBF1000F00F09D80082335E0BA46002692 +:10301000C2E7049BE02B28BFE02306930B44AB429E +:10302000059315D95A1B924538BF5246039828BFBD +:10303000D2B20096691A08AB04300792FFF7ECFB96 +:10304000079A1644AAEB020A1544F6B25FFA8AFA06 +:10305000049B069A05999B1A0493039B1B68039390 +:10306000A5E700933A462946D8F8080008ABADE733 +:10307000BBF1000F13D00123B4EBC30F6CD0082CAD +:1030800012D89DF82030621E23FA02F2D50706D529 +:103090004FF0FF3202FA04F423438DF820309DF8FC +:1030A000203089F8003050E7102C12D8BDF82030BD +:1030B000621E23FA02F2D10706D54FF0FF3202FA60 +:1030C00004F42343ADF82030BDF82030A9F80030D7 +:1030D0003BE7202C0FD80899631E21FA03F3DA0787 +:1030E00005D54FF0FF3202FA04F40C430894089B14 +:1030F000C9F8003029E7402C2BD0DDE90865611EB6 +:10310000C4F12102A4F1210326FA01F105FA02F229 +:1031100025FA03F311431943CB0712D50122A4F179 +:103120002003C4F1200102FA03F322FA01F1A240C4 +:10313000524243EA010363EB430332432B43CDE99D +:103140000823DDE90823C9E90023FEE66FF001004A +:10315000FBE66FF00800F8E6082CA0D9102CB3D9D4 +:10316000202CEED8C3E7BBF1000FADD0022383E7DC +:10317000BBF1000FBBD004237EE70000012A30B56D +:10318000144638BF01220025402A28BF402285B0BE +:10319000012CCDE9025517D81B788DF8083053075C +:1031A0000AD004AB03EBD20515F8083C544204F0F6 +:1031B0000704A34005F8083C0346009102A800213B +:1031C000FFF72AFB05B030BD082CE5D9102C03D839 +:1031D0001B88ADF80830E2E7202C02D81B68029368 +:1031E000DDE7D3E90045CDE90245D8E710B5CB6866 +:1031F0001BB98B600B618B8210BD04691A681C605F +:103200000361C38A013BC382CA60F0E703064CBF77 +:10321000C0F3C0300220704708B50246FFF7F6FF42 +:10322000022806D15306C2F30F2001D100F003009B +:1032300008BDC2F30740FBE72DE9F04F93B0CDE99D +:1032400003230A6804461046FFF7E0FF02280CBF7C +:103250000026C2F30626002A0D46824680F2F98136 +:1032600012F0C04940F0F581097B002900F0F1819E +:10327000022803D02378B34240F0EE81C2F3046306 +:103280001046069302F07F030593FFF7C5FF059BE9 +:1032900000224FEA8348002348EA0A48294448EAC2 +:1032A0004668CE78CDE90823F309834648EA00084A +:1032B000029367D0059B02460093204653466768F9 +:1032C00008A9B847002800F0CA81276A4FB94146CB +:1032D00004F10C00FFF704FB074690B96FF0020001 +:1032E00054E03B6998450DD03F68002FF9D1414625 +:1032F00004F10C00FFF7F4FA07460028EED0236A29 +:103300003B60276297F817C006F01F08CCF3840CC7 +:10331000ACEB08001FFA80FE0028B8BF0EF12000B9 +:10332000A8EB0C031FFA83FEB8BF00B2002B079373 +:10333000BEBF0EF120031BB20793D7E9022152EA68 +:10334000010338D04FF0000C039BDFF8F8E19A1A24 +:10335000049B63EB010196457CEB01032BD36B7B54 +:1033600097F81AE0734519D1029B002B78D00128F9 +:1033700021DC7868F8B9DFF8D0C1944570EB01031F +:1033800016D337E0276A27B96FF00C0013B0BDE8F9 +:10339000F08F3B699845B5D03F68F4E76A489042A2 +:1033A0007CEB010301D30020F0E7029B002BFAD055 +:1033B000079B0F2B17DCFA7DB30002F0030203F02A +:1033C0007C031343FB7539462046FFF709FB6B7BF3 +:1033D000BB76029B3BB9FB7DC3F38402013262F3EF +:1033E0008603FB75D0E76A7BBB7E9A42DBD1029BEA +:1033F000002B35D0B309022B32D0039B1422BB60C3 +:10340000049B0021FB600DA8FDF7E2FF039B204613 +:103410000A93049BADF83EB00B932B1D0C932B7BB2 +:103420008DF840A0013BDBB2ADF83C30069B8DF837 +:1034300041808DF84230059B0AA98DF8433094F8FD +:103440002C3083F001038DF84430A3689847FB7D4E +:10345000C3F38403013303F01F039B02FB82A2E743 +:10346000FB7DC6F34012B2EBD31F40F0FB80C3F3E9 +:103470008403434540F0F980029A2B7BB609002A69 +:103480004DD0F20762D4032B40F2F280039BAE1DB5 +:10349000BB60049B3246FB602B7B3946033BDBB2AF +:1034A00004F10C00FFF7AEFA00280CDA394620468A +:1034B000FFF796FAFB7DC3F38403013303F01F0388 +:1034C0009B02FB820AE7AB88DDE908843B834FF669 +:1034D000FF73C9F12000A9F1200228FA09F104FACA +:1034E00000F0014324FA02F211431846C9B2FFF773 +:1034F000CBF909F10809B9F1400F0346E9D131468A +:10350000B8822A7B033AD2B2FFF7D0F9FB7DB882AA +:10351000DA43C2F3C01262F3C713FB7543E7AEB9D7 +:103520002E1D013B32463946DBB204F10C00FFF799 +:1035300069FA0028BADB2A7B3146013AB88AD2B24E +:10354000E2E700BF80841E0040420F00F98A013B81 +:10355000C1F309010429DAB25DD80023281D07F15F +:103560001B069A4208D910F801CB013306F801C0B6 +:1035700001310529DBB2F4D1934228BF002303991E +:1035800038BF04330A91049938BFDBB20B9107F1BD +:103590001B010C91796838BF5B190D910E93FB8A62 +:1035A000ADF83EB0C3F309031A44069BADF83C20C6 +:1035B0008DF84230059B8DF840A08DF8433094F88B +:1035C0002C308DF8418083F001038DF844300023C6 +:1035D0007B602A7BB88A013A291DFFF767F93B8B8C +:1035E000B882834203D12046A3680AA9984720469F +:1035F0000AA9FFF7FBFDFB7DBA8AC3F384030133FD +:1036000003F01F039B02FB823B8B9A420CBF0020FE +:103610006FF01000BAE67B68002BADD0052001E00A +:1036200033461C301E68002EFAD1091A081D2E1DC3 +:10363000184401EB090CBCF11B0F5FFA89F39BD80E +:103640009A4299D916F8013B09F1010900F8013BAA +:10365000EFE76FF0090099E66FF00A0096E66FF069 +:103660000B0093E66FF00D0090E66FF00E008DE614 +:103670006FF00F008AE600BFEFF30983203383F376 +:103680000988002383F3118870470000302080F3FD +:10369000118862B60C4B0D4AD96821F4E061090427 +:1036A000090C0A43DA60D3F8FC20094942F0807221 +:1036B000C3F8FC200A6842F001020A602022DA778F +:1036C00083F82200704700BF00ED00E00003FA0518 +:1036D000001000E0302310B583F311880B4B5B68BA +:1036E00013F400630FD0EFF309844FF08073203C94 +:1036F000E36184F3098800F095F810B1044BA361ED +:1037000010BD044BFBE783F31188F9E700ED00E0FF +:10371000370600083A0600080122090100F160435B +:1037200003F56143C9B283F8001300F01F039A4008 +:1037300043099B0003F1604303F56143C3F8802113 +:103740001A607047090100F16040C9B200F56D4090 +:103750000176704700238268037503691B689968C6 +:103760009142FBD25A680360426010605860704713 +:1037700000238268037503691B6899689142FBD82E +:103780005A680360426010605860704708B5084688 +:10379000302383F311880B7D032B05D0042B0DD030 +:1037A0002BB983F3118808BD00228B691A604FF092 +:1037B000FF338361FFF7CEFF0023F2E7D1E9003248 +:1037C00013605A60F3E70000FFF7C4BF054BD968E8 +:1037D00008751868026853601A6001220275D86083 +:1037E000FCF718BF2823002030B50C4B0446DD68D9 +:1037F0004B1C87B00FD02B466846094A00F0BCF836 +:103800002046FFF7E3FF009B13B1684600F0BCF8C9 +:10381000A86907B030BDFFF7D9FFF9E728230020DA +:103820008D370008044B1A68DB6890689B689842E3 +:1038300094BF00200120704728230020084B10B5BA +:103840001C68D868226853601A6001222275DC6007 +:10385000FFF78EFF01462046BDE81040FCF7DABEB8 +:103860002823002038B501230025064C06490748C7 +:103870002370656000F0F8FA0223237085F3118845 +:1038800038BD00BF80240020E44400082823002025 +:1038900008B572B6044B186500F0A6F900F076FA88 +:1038A0000322024B1A70FEE7282300208024002008 +:1038B00000F07CB88B60022308618B820846704759 +:1038C0008368A3F1440243F8142C026943F8442CA2 +:1038D000426943F8402C094A43F8242CC268A3F1FA +:1038E000200043F8182C022203F80C2C002203F8C5 +:1038F0000B2C034A43F8102C704700BF2506000824 +:103900002823002008B5FFF7DBFFBDE80840FFF7DC +:103910005BBF0000024BDB6898610F20FFF756BFCA +:1039200028230020302383F31188FFF7F3BF000022 +:1039300008B50146302383F311880820FFF754FFB0 +:10394000002383F3118808BD10B50A4C23699A68D7 +:1039500091420CD85A6881600360426010609A6896 +:103960005860511A99604FF0FF33A36110BD1B6876 +:10397000891AECE728230020C0E90323002310B4B0 +:1039800010BC4361FFF7E0BF036881689A680A448E +:103990009A60426813605A6000234FF0FF32036060 +:1039A000014B9A61704700BF2823002070B5124D6B +:1039B0002A46EB690133EB6152F8103F934206D07F +:1039C00030269A68013A9A602C69A36803B170BDE9 +:1039D000D4E900210A605160236083F311882046F6 +:1039E000D4E90331984786F3118861690029EBD047 +:1039F0002046FFF7A9FFE7E728230020054A30B556 +:103A0000D369D2E908451B1B181945F10001C2E929 +:103A1000080130BD2823002000207047FEE7000089 +:103A2000704700004FF0FF3070470000BFF34F8F2A +:103A3000024AD368DB07FCD4704700BF0020024075 +:103A400008B5074B1B7853B9FFF7F0FF054B1A6910 +:103A5000120641BF044A5A6002F188325A6008BD1A +:103A600098240020002002402301674508B5054B3B +:103A70001B7833B9FFF7DAFF034A136943F0800379 +:103A8000136108BD98240020002002407F289ABFBF +:103A900000F58030C0020020704700004FF4006045 +:103AA00070470000802070477F2808B50BD8FFF7CB +:103AB000EDFF00F500630268013204D10430834257 +:103AC000F9D1012008BD0020FCE700007F2810B5D7 +:103AD00004461CD8FFF7AAFFFFF7B2FFF3220D4BF5 +:103AE0004FF40061DA6002221A61FFF7CFFF5861DC +:103AF0001A6942F040021A61FFF798FF00F042F99C +:103B0000FFF7B4FF2046BDE81040FFF7CDBF00200F +:103B100010BD00BF002002402DE9F843054612F019 +:103B20000100144606D040F2033200201E4B1A60FA +:103B3000BDE8F8831D4BAA189A4204D94FF442728B +:103B4000194B1A60F4E7FFF77BFF4FF00109FFF70D +:103B50006DFFDFF85C806D1A012C0F4605EB010646 +:103B600003D8FFF783FF0120E2E73B88C8F81090F5 +:103B700033800020FFF75AFFC8F81000338831F86F +:103B8000022B9BB29A420CD040F21F32064B1A60B5 +:103B9000084B1E60084B1C60084B1F60FFF766FF58 +:103BA000C6E7023CD8E700BF9424002000000408C8 +:103BB0000020024088240020902400208C24002033 +:103BC000084908B50B7828B11BB9FFF739FF012365 +:103BD0000B7008BD002BFCD0BDE808400870FFF753 +:103BE00045BF00BF982400204FF47F41014800F0FA +:103BF000CBB800BF000100200846114600F084BB8E +:103C0000012000F081BB0000084600F09BBB0000D3 +:103C100038B5EFF31185BDBBEFF30584C4F3080499 +:103C20003023C4B183F31188FFF7E8FE44014B0150 +:103C3000241A43EAD06363EB0103A2009B0012182D +:103C400043EA947341EB0301C900D00041EA527189 +:103C500085F3118838BD83F31188FFF7CFFE450146 +:103C60004B012D1A43EAD06363EB0103AA009B00CA +:103C7000121843EA957341EB0301C900D00041EAF1 +:103C8000527184F3118838BDFFF7B8FE44014B012F +:103C9000241A43EAD06363EB0103A2009B001218CD +:103CA00043EA947341EB0301C900D00041EA527129 +:103CB00038BD00BF38B5FFF7ABFF00230F4A104CEB +:103CC000C00840EA4170A0FB025EC908A0FB040CDA +:103CD000A1FB0440A1FB02121CEB050C5B411CEB99 +:103CE000040C43EB000011EB0E0142F100024118FD +:103CF00042F10000090941EA007038BDA59BC420CB +:103D0000CFF753E310B5094C013AD2B2FF2A00D1E4 +:103D100010BD500854F82030013054F820009BB2F8 +:103D200043EA004341F8043BEEE700BF046C004067 +:103D300010B50748013AD2B2FF2A00D110BD0C8855 +:103D4000530840F823404C88013340F82340F1E702 +:103D5000046C004007B50122002001A9FFF7D2FF43 +:103D6000019803B05DF804FB13B50446FFF7F2FFBA +:103D7000A04205D00122002001A90194FFF7D8FF3D +:103D800002B010BD7047000070470000704700008F +:103D900045F25552064B1A6002225A6040F6FF72F5 +:103DA0009A604CF6CC421A600122024B1A7070479E +:103DB00000300040A0240020034B1B781BB14AF6C2 +:103DC000AA22024B1A607047A02400200030004055 +:103DD000044B1A682AB902F1804202F50432526A91 +:103DE0001A6070479C2400204FF08072014B5A6289 +:103DF000704700BF0010024008B5FFF7E9FF024B13 +:103E00001868C0F3407008BD9C24002008B5FFF777 +:103E1000DFFF024B1868C0F3007008BD9C2400202F +:103E200070470000FEE700000A4B0B480B4A904227 +:103E30000BD30B4BC11EDA1C121A22F003028B4269 +:103E400038BF00220021FDF7C3BA53F8041B40F825 +:103E5000041BECE7B84500082C2500202C25002089 +:103E60002C250020FEE7000070B5002504461A4B03 +:103E700086B05860856201630E46FFF707FC04F1C7 +:103E80001003C4E904334FF0FF33A361134BE56122 +:103E9000D9692B460A462046C4E9082304F13401B7 +:103EA0008023C4E900440E4AA560E5622565FFF75A +:103EB00001FD01230B4AE0600375009272686846B9 +:103EC0000192B268CDE90223074BCDE90435FFF733 +:103ED00019FD06B070BD00BF8024002028230020FB +:103EE000F0440008F5440008653E000800F030B8D2 +:103EF00008B500F06DF9FFF7B5FCBDE80840FFF725 +:103F000067BF0000704700004FF0FF310E4B1A6989 +:103F100019611A6900221A611869D868D960D968CC +:103F2000DA60DA68DA6942F08052DA61DA69DA690D +:103F300042F00062DA61054ADB69136843F480737A +:103F4000136000F025B900BF00100240007000406F +:103F50001E4B1A6842F001021A601A689007FCD5DD +:103F60005A6822F003025A605A6812F00C02FBD120 +:103F7000196801F0F90119605A601A6842F4803238 +:103F80001A601A689103FCD54EF63162DA625A68FB +:103F900042F4E8125A601A6842F080721A601A6895 +:103FA0009201FCD50A4A0B495A6012220A600A683B +:103FB00002F00702022AFAD15A6842F002025A605D +:103FC0005A6802F00C02082AFAD170470010024029 +:103FD00000641D0000200240084A08B551691368BA +:103FE0000B4003F00103536123B1054A13680BB181 +:103FF00050689847BDE80840FFF76CBB00040140DB +:10400000A4240020084A08B5516913680B4003F046 +:104010000203536123B1054A93680BB1D0689847F6 +:10402000BDE80840FFF756BB00040140A42400206F +:10403000084A08B5516913680B4003F00403536143 +:1040400023B1054A13690BB150699847BDE8084090 +:10405000FFF740BB00040140A4240020084A08B533 +:10406000516913680B4003F00803536123B1054AFB +:1040700093690BB1D0699847BDE80840FFF72ABBA8 +:1040800000040140A4240020084A08B551691368BF +:104090000B4003F01003536123B1054A136A0BB1BF +:1040A000506A9847BDE80840FFF714BB0004014080 +:1040B000A4240020174B10B55A691C68144004F45E +:1040C00078725A61A30604D5134A936A0BB1D06A79 +:1040D0009847600604D5104A136B0BB1506B984794 +:1040E000210604D50C4A936B0BB1D06B9847E205BF +:1040F00004D5094A136C0BB1506C9847A30504D53D +:10410000054A936C0BB1D06C9847BDE81040FFF79F +:10411000E1BA00BF00040140A42400201A4B10B5EE +:104120005A691C68144004F47C425A61620504D543 +:10413000164A136D0BB1506D9847230504D5134AE9 +:10414000936D0BB1D06D9847E00404D50F4A136E00 +:104150000BB1506E9847A10404D50C4A936E0BB175 +:10416000D06E9847620404D5084A136F0BB1506FA4 +:104170009847230404D5054A936F0BB1D06F984735 +:10418000BDE81040FFF7A6BA00040140A4240020B7 +:10419000062108B50846FFF7BFFA06210720FFF7FA +:1041A000BBFA06210820FFF7B7FA06210920FFF71E +:1041B000B3FA06210A20FFF7AFFA06211720FFF70E +:1041C000ABFABDE8084006212820FFF7A5BA000099 +:1041D00008B5FFF799FE044800F00AF8FFF792FED1 +:1041E000BDE8084000F002B8FC44000800F042B806 +:1041F000002319461C4A0133102BC2E9001102F1B9 +:104200000802F8D1194B9A6942F07D029A619B69C4 +:104210000268174BDA6082685A6042681A60C268A6 +:1042200003F58063DA6042695A6002691A60826944 +:10423000C3F80C24026AC3F80424C269C3F800243A +:10424000426AC3F80C28C26AC3F80428826AC3F819 +:104250000028026BC3F80C2C826BC3F8042C426B51 +:10426000C3F8002C704700BFA424002000100240B7 +:10427000000801404FF0E023044A08215A6100225F +:104280009A6107220B201A61FFF75CBA3F190100FF +:1042900008B5302383F31188FFF70AFB002383F36B +:1042A000118808BD08B5FFF7F3FFBDE80840FFF728 +:1042B00011BA00000B460146184600F02DB8000068 +:1042C00000F040B8012838BF012010B50446204650 +:1042D00000F030F830B900F007F808B900F00CF839 +:1042E0008047F4E710BD0000024B1868BFF35B8FF6 +:1042F000704700BF24250020062008B500F082F892 +:104300000120FFF78BFB0000024B0A4601461868AC +:10431000FFF772BC1C08002010B504460448134681 +:1043200020B10A4602202146AFF3008010BD00BF35 +:1043300000000000024B01461868FFF761BC00BF97 +:104340001C080020024B01461868FFF75DBC00BF47 +:104350001C08002010B501390244904201D1002010 +:1043600005E0037811F8014FA34201D0181B10BDDE +:104370000130F2E72DE9F0419BB10446C91A1778E4 +:10438000014403F1FF3C8C42204601D9002008E0A3 +:1043900005780134BD42F6D10CEB0405D618A542D0 +:1043A00001D1BDE8F08115F8018D16F801EDF04559 +:1043B000F5D0E8E71F2938B504460D4604D9162381 +:1043C00003604FF0FF3038BD426C12B152F821301B +:1043D0004BB9204600F030F82A4601462046BDE899 +:1043E000384000F017B8012B0AD0591C03D116230E +:1043F00003600120E7E70024284642F8254098475B +:104400000020E0E7024B01461868FFF7D3BF00BF6A +:104410001C08002038B50023064D04460846114606 +:104420002B60FFF7FFFA431C02D12B6803B1236016 +:1044300038BD00BF28250020FFF7EEBA034611F86B +:10444000012B03F8012B002AF9D170476F72672EF8 +:104450006172647570696C6F742E5A756261784709 +:104460004E53530040A2E4F1646891060041A3E575 +:10447000F2656992070000004261642043414E49A1 +:104480006661636520696E6465782E0080000000B7 +:10449000008000000000800000000000000000001C +:1044A000151C0008E92300084D2300084D1C0008D6 +:1044B000551C0008411E0008251C0008351C00087A +:1044C000291C0008311C00082D1C00086D1D000867 +:1044D000391C000899260008451C0008411D0008E9 +:1044E00063300000E0440008802300208024002086 +:1044F0006D61696E0069646C650000000C880000E5 +:10450000447B444444544424800E00004414111459 +:10451000947B4444000000004444444444444444E4 +:104520000400000044424444444444440000000069 +:104530004444444444444444ED030000000000006B +:10454000006803000000000040420F00FE2A010046 +:10455000D20400002008002000000000000000003D +:10456000000000000000000000000000000000004B +:10457000000000000000000000000000000000003B +:10458000000000000000000000000000000000002B +:10459000000000000000000000000000000000001B +:1045A000000000000000000000000000000000000B +:0845B000000000000000000003 :00000001FF diff --git a/Tools/bootloaders/f103-ADSB_bl.bin b/Tools/bootloaders/f103-ADSB_bl.bin index 7e698ca14ea11f..e5b39d3ed4c582 100755 Binary files a/Tools/bootloaders/f103-ADSB_bl.bin and b/Tools/bootloaders/f103-ADSB_bl.bin differ diff --git a/Tools/bootloaders/f103-ADSB_bl.elf b/Tools/bootloaders/f103-ADSB_bl.elf index 9776e83a7c9680..6367e054e64bc5 100755 Binary files a/Tools/bootloaders/f103-ADSB_bl.elf and b/Tools/bootloaders/f103-ADSB_bl.elf differ diff --git a/Tools/bootloaders/f103-ADSB_bl.hex b/Tools/bootloaders/f103-ADSB_bl.hex index 1cd83a81d0fc07..9e8b46c7b04f8b 100644 --- a/Tools/bootloaders/f103-ADSB_bl.hex +++ b/Tools/bootloaders/f103-ADSB_bl.hex @@ -1,26 +1,26 @@ :020000040800F2 -:10000000000900202D080008B11C0008811C000810 -:100010009D1C0008811C0008951C00082F08000882 -:100020002F0800082F0800082F080008E5370008EF -:100030002F0800082F0800082F080008F93C0008C6 -:100040002F0800082F0800082F0800082F080008B4 -:100050002F0800082F080008293A0008553A000820 -:10006000813A0008AD3A0008D93A00082F08000884 -:100070002F0800082F0800082F0800082F08000884 -:100080002F0800082F0800082F080008AD2C0008D2 -:10009000192D00086D2D0008C12D0008053B000832 -:1000A0002F0800082F0800082F0800082F08000854 -:1000B0002F0800082F0800082F0800082F08000844 -:1000C0002F0800082F0800082F0800082F08000834 -:1000D0002F0800082F0800082F0800082F08000824 -:1000E0006D3B00082F0800082F0800082F080008A3 -:1000F0002F0800082F0800082F0800082F08000804 -:100100002F0800082F0800082F0800082F080008F3 -:100110002F0800082F0800082F0800082F080008E3 -:100120002F0800082F0800082F0800082F080008D3 -:100130002F0800082F0800082F0800082F080008C3 -:100140002F0800082F0800082F0800082F080008B3 -:100150002F0800082F0800082F0800082F080008A3 +:100000000009002025050008A11900087119000841 +:100010008D190008711900088519000827050008C6 +:10002000270500082705000827050008F9340008FF +:100030002705000827050008270500080D3A0008D5 +:1000400027050008270500082705000827050008E0 +:1000500027050008270500083D3700086937000814 +:1000600095370008C1370008ED370008270500085C +:1000700027050008270500082705000827050008B0 +:100080002705000827050008270500089D29000806 +:10009000092A00085D2A0008B12A0008193800085A +:1000A0002705000827050008270500082705000880 +:1000B0002705000827050008270500082705000870 +:1000C0002705000827050008270500082705000860 +:1000D0002705000827050008270500082705000850 +:1000E00081380008270500082705000827050008B3 +:1000F0002705000827050008270500082705000830 +:10010000270500082705000827050008270500081F +:10011000270500082705000827050008270500080F +:1001200027050008270500082705000827050008FF +:1001300027050008270500082705000827050008EF +:1001400027050008270500082705000827050008DF +:1001500027050008270500082705000827050008CF :100160004FF0FF0C1CEAD0521EBF1CEAD15392EA9A :100170000C0F93EA0C0F6FD01A4480EA010C400276 :1001800018BF5FEA41211ED04FF0006343EA5010D0 @@ -81,917 +81,870 @@ :1004F0009E03B3EB126209D44FEA002343F000439A :1005000023FA02F070474FF00000704712F1610FBC :1005100001D1420202D14FF0FF3070474FF000008E -:10052000704700BF53B94AB9002908BF00281CBF53 -:100530004FF0FF314FF0FF3000F076B9ADF1080C0D -:100540006DE904CE00F006F8DDF804E0DDE90223F1 -:1005500004B070472DE9F047089E0D4604468846D2 -:10056000002B4DD18A42944668D9B2FA82F252B138 -:1005700001FA02F3C2F1200120FA01F10CFA02FCA7 -:1005800041EA030894404FEA1C41B8FBF1F71FFA17 -:100590008CFE01FB178807FB0EF0230C43EA08438F -:1005A00098420AD91CEB030307F1FF3580F01E8146 -:1005B000984240F21B81023F63441B1AB3FBF1F0E7 -:1005C00001FB103300FB0EFEA4B244EA0344A6452F -:1005D0000AD91CEB040400F1FF3380F00981A64521 -:1005E00040F20681644402380021A4EB0E0440EA84 -:1005F00007401EB10023D440C6E90043BDE8F087A0 -:100600008B4208D9002E00F0EE800021C6E90005DB -:100610000846BDE8F087B3FA83F100294AD1AB421E -:1006200002D3824200F2FC80841A65EB03030120AE -:100630009846002EE2D0C6E90048DFE702B9FFDEA7 -:10064000B2FA82F2002A40F09180A1EB0C00012165 -:100650004FEA1C471FFA8CFEB0FBF7F307FB1300B1 -:10066000250C45EA00450EFB03F0A84208D91CEB17 -:10067000050503F1FF3802D2A84200F2CE804346BE -:100680002D1AB5FBF7F007FB10550EFB00FEA4B2C8 -:1006900044EA0544A64508D91CEB040400F1FF35E3 -:1006A00002D2A64500F2B6802846A4EB0E0440EA2A -:1006B00003409EE7C1F120078B4022FA07FC4CEA79 -:1006C000030C25FA07FA4FEA1C49BAFBF9F820FA9D -:1006D00007F309FB18AA8D401FFA8CFE1D4300FA90 -:1006E00001F308FB0EF02C0C44EA0A44A04202FA83 -:1006F00001F20BD91CEB040408F1FF3A80F088806A -:10070000A04240F28580A8F102086444241AB4FB98 -:10071000F9F009FB104400FB0EFEADB245EA0444BB -:10072000A64508D91CEB040400F1FF356CD2A645A0 -:100730006AD90238644440EA0840A0FB0295A4EB61 -:100740000E04AC42C846AE4656D353D0002E69D0F4 -:10075000B3EB080264EB0E0422FA01F304FA07F784 -:100760001F43CC40C6E90074002147E70CFA02FCA5 -:10077000C2F1200125FA01F34FEA1C4720FA01F1EA -:1007800095400D43B3FBF7F107FB11331FFA8CFEC5 -:10079000280C40EA034001FB0EF3834204FA02F402 -:1007A00008D91CEB000001F1FF382FD283422DD96C -:1007B00002396044C01AB0FBF7F307FB1300ADB277 -:1007C00045EA004503FB0EF0A84208D91CEB0505DD -:1007D00003F1FF3816D2A84214D9023B6544281A07 -:1007E00043EA014138E73146304607E72F46E4E661 -:1007F0001846F9E64B45A9D2B9EB020865EB0C0E99 -:100800000138A3E74346EAE7284694E74146D1E7A3 -:10081000D0467BE76444023847E7023B65442FE754 -:10082000084606E73146E9E6704700BF02E000F0FF -:1008300000F8FEE772B6264880F30888254880F362 -:100840000988254825490860022080F31488BFF3F1 -:100850006F8F03F017F803F07BF84FF05530204905 -:100860001B4A91423CBF41F8040BFAE71D49194A63 -:1008700091423CBF41F8040BFAE71B491B4A1C4B51 -:100880009A423EBF51F8040B42F8040BF8E70020EF -:100890001849194A91423CBF41F8040BFAE702F0AB -:1008A000F5FF03F057F8154C154DAC4203DA54F838 -:1008B000041B8847F9E700F03FF8124C124DAC4298 -:1008C00003DA54F8041B8847F9E702F0DDBF0000A3 -:1008D00000090020001100200000000808ED00E0E1 -:1008E0000001002000090020083E0008001100203F -:1008F0002411002028110020E025002060010008BC -:100900006001000860010008600100082DE9F04F57 -:10091000C1F80CD0C3689D46BDE8F08F002383F377 -:1009200011882846A047002002F010FDFEE702F0E3 -:1009300083FC00DFFEE70000F8B500F03DFE02F0AA -:10094000EFFE074602F03AFF0546002840D12C4B47 -:100950009F423DD001339F423DD02A4B27F0FF02FA -:100960009A423BD1F8B200F003FC2E4642F21074DA -:1009700000F004FC08B10024264601F007F988B312 -:100980000024032000F044F8264635B11E4B9F4258 -:1009900003D0002402F00AFF2646002002F0CAFE1F -:1009A0001A4B9B6813F0400322D00EB100F046F8BA -:1009B00000F044FC00F002FE01F07CF90546CCB1E9 -:1009C00001F078F9401BA04214D900F037F8F3E7A2 -:1009D0002E460024CCE704460126C9E706464FF41C -:1009E0007A74C5E7002CD0D04FF47A740126CCE796 -:1009F0001C46DDE700F0D4FC012002F0ADFCDEE790 -:100A0000010007B0000008B0263A09B0000C014010 -:100A1000084B187003280CD8DFE800F0080502081E -:100A2000022000F027BE022000F01CBE0022024B74 -:100A30005A607047281100202C11002038B501F0B1 -:100A4000A5F830B103221F4B1A7000221E4B5A60CA -:100A500038BD1E4B1E4A19680131F9D00433934248 -:100A6000F9D11C4C194DD4F80424AA42F0D31A4BE6 -:100A70009B6803F1006303F5C8439A42E8D202F091 -:100A800069FE02F07BFE002000F0B2FD0220FFF7BD -:100A9000BFFF124BDA690022DA61D96999699A615C -:100AA0009B6972B64FF0E023C3F8085D3021D4F89B -:100AB0000034D4F8042481F311889D4683F3088818 -:100AC0001047C5E7281100202C1100200064000801 -:100AD000206400080060000800110020001002409F -:100AE00049F26900084A136899B21B0C00FB0133F4 -:100AF00044F250611360054B186882B2000C01FB90 -:100B00000200186080B27047201100201C110020E4 -:100B100010B504460021102200F0C8FD034B03CBA2 -:100B2000206061601868A06010BD00BFE8F7FF1F7B -:100B30002DE9F0410026ADF54E7D6CAC40F275120A -:100B400007460D460EA831460D9600F0AFFD4FF456 -:100B5000C4723146204600F0A9FD01F0ABF84FF415 -:100B60007A72B0FBF2F0264B0DF13408186093E86E -:100B70000700022384E807000DF5E9702382FFF7E0 -:100B8000C7FF4EF603031F4907A8238403F0ECF8C0 -:100B900017230DF2E32284F832310DF12C0C07AB50 -:100BA0001E4603CE664510605160334602F10802CE -:100BB000F6D130681060B188B37920469180937186 -:100BC0004146012200F0BEFD00230393AB7E80B2BC -:100BD000029305F1190301930123CDE904800093E9 -:100BE000384605A3D3E90023E97E01F0A9FB0DF502 -:100BF0004E7DBDE8F08100BF9E6AC421818A46EE29 -:100C000034110020783D00082DE9F041264D804642 -:100C10002B7A0C46DAB0FBB9204627A900F0A2FED9 -:100C20000746002836D19DF89D60C82E32D801466F -:100C30004FF4FA72284600F039FD32460DF19E015C -:100C400005F1090000F020FD9DF89C302E447772DC -:100C50002B720BB9E37E2B728122002106AD27A8EF -:100C600000F024FD0122294627A800F0B7FE00234A -:100C70000393A37E80B2029304F119030193282306 -:100C8000CDE904500093404605A3D3E90023E17E5B -:100C900001F056FB5AB0BDE8F08100BFAFF3008011 -:100CA00026417272DF25D7B77C210020F0B54FF4C2 -:100CB0008A750024234EF1B005FB006596F8D83004 -:100CC000D822214685F8DC3085F8E8403AA800F0C3 -:100CD000EDFC06F1090000F0E1FCD5F8E430C2B209 -:100CE00006AF8DF8F00006F109010DF1F100CDE934 -:100CF0003A3400F0C9FC394601223AA800F09AFEC5 -:100D000080B2CDE9047008230127CDE9023706F14E -:100D1000D80301933023317A00930B4807A3D3E91A -:100D2000002301F00DFBA04206DD00F0C3FFC5F873 -:100D3000E000384671B0F0BD2046FBE778F6339FFF -:100D400093CACD8D7C2100204C210020F0B51E4E91 -:100D50001E4F1F4D85B0304601F01EFB044660B3A8 -:100D600010220021684600F0A1FC4FF00003227B16 -:100D70006068A16862F303038DF8003002AB03C31F -:100D8000019B2268384662F31C0301939DF80030F2 -:100D90006A4643F020038DF800300023194602F024 -:100DA00087F9044620B9304601F0FAFA2C70D2E7F0 -:100DB0002B78072B03D801332B7005B0F0BD024808 -:100DC00001F0EEFAF9E700BF4C210020A823002033 -:100DD0007523002070B50D4614461E4601F00CFA2E -:100DE00050B9022E10D1012C0ED112A3D3E9002349 -:100DF0000120C5E9002307E0282C10D005D8012CDC -:100E000009D0052C0FD0002070BD302CFBD10BA3D6 -:100E1000D3E90023ECE70BA3D3E90023E8E70BA316 -:100E2000D3E90023E4E70BA3D3E90023E0E700BF05 -:100E3000AFF30080401DA12026812A0B78F6339F56 -:100E400093CACD8D9E6AC421818A46EE2641727274 -:100E5000DF25D7B7F017304A39059E5638B5054615 -:100E60000E4C0021013500F0E5FBA4F8F051B4F878 -:100E7000F00100F0C7FB78B1B4F8F00100F0D2FB4C -:100E8000014648B9B4F8F00100F0D4FBB4F8F031F1 -:100E90000133A4F8F031EAE738BD00BF7C2100201F -:100EA0002DE9F04F8DB000AF04460D4601F0A4F9D6 -:100EB000002846D12B7E022B1AD1EB8A012B17D1A9 -:100EC00000F0F8FE0646FFF70BFE4FF4C873B0FBC8 -:100ED000F3F202FB1303DFF878829BB206F5167675 -:100EE0003344C8F80030EB7E33B90022994B1A70B6 -:100EF0003437BD46BDE8F08F284607F11C0100F0ED -:100F0000EFFC0028F4D107F10C00FFF701FEBD7FD4 -:100F100007F10C012A4607F11F0002F0F5FE002838 -:100F2000E3D10F2D08D88B4B1D70D8F80030A3F5F6 -:100F30001673C8F80030DBE72046397F01F054F91A -:100F4000D6E7EB8A282B6BD010D8012B63D0052B6A -:100F5000CED1BFF34F8F8049804BCA6802F4E06264 -:100F60001343CB60BFF34F8F00BFFDE7302BBFD1E2 -:100F70007B4CEA7E237A9A42BAD194F8DC206B7ECD -:100F80009A42B5D1284604F1EA0100F07FFD0646F9 -:100F90000028ADD1012384F8E83000F08BFED4F8AE -:100FA000E030C01A192840F6B83338BF19209842EB -:100FB00028BF1846FFF73EFA6A49FFF7D1F8054601 -:100FC0002068FFF737FA6849FFF7CAF80146284654 -:100FD000FFF780F9FFF786FA20604FF48A7194F8E2 -:100FE000D9307B607A68636801FB02F5621992F878 -:100FF000E80050B1D2F8E400E946834215D000235E -:1010000082F8E830C2F8E030CD466368574A9B0A60 -:10101000013313816CE729462046FFF789FD67E716 -:1010200029462046FFF7F0FD62E7B2F8EC803B600E -:1010300008F1030A4FEA9A0A4FEA8A02D11DC90849 -:10104000A9EBC1039D46EB460021584600F02EFB5C -:1010500005F1EE0142465846214400F015FB3B687D -:1010600013B9012000F0C4FA94F8D20000F0CAFAD3 -:10107000054630B9207200F0E5FA284600F0B8FACB -:10108000C2E7D4F8D4303BB994F8D200B4F8F031C8 -:10109000834201D8FFF7E2FED4F8D43043449D42A6 -:1010A00008D294F8D200B4F8F0310130834201D86C -:1010B000FFF7D4FE594660685FFA8AF200F0FEFA44 -:1010C00008B9CD4689E7636894F8D2004344636069 -:1010D000D4F8D43008EB030AC4F8D4A000F092FA94 -:1010E000824509D394F8D230D4F8D4000133401BA0 -:1010F00084F8D230C4F8D400B8F1FF0F0FD800251F -:10110000257200F09FFA284600F072FA00F03EFDCA -:10111000164B188108B9FFF791FCCD46E8E64FF46D -:101120008A727B6894F8D90002FB0343D3F8E42069 -:1011300083F8E86002F58072C3F8E060C3F8E42049 -:10114000FFF7B4FDFFF702FE84F8D960B9E700BFEE -:10115000482100204521002000ED00E00400FA05B0 -:101160007C210020CDCCCC3D6666663F341100204A -:10117000014B1870704700BF4011002030B54FF090 -:101180000054254B226885B09A4207D002F020FB1C -:101190000446C0B90024204605B030BD0025627D5C -:1011A0001E4B1F481A70237DC92203721D49C0F8C7 -:1011B000E450093000F068FA2046E022294600F0A9 -:1011C00075FA0124E7E7184A184DD36943F0007314 -:1011D000D361AA6D164B9A42DCD12B6E013B7E2B5C -:1011E000D8D8144A01AB07CA83E807001846032180 -:1011F00000F09CFC6B6D83424FF00003CAD12A6D56 -:101200008A4203BFAB652A6E044B1C4601BF1A70AD -:10121000EA6D094B1A60BEE79AAD44C54011002043 -:101220007C210020160000200010024000660040D3 -:101230005041A0B058660040181100202DE9F0433D -:1012400085B000F0A3FC0223494C63710023029394 -:10125000484B2081D3F800C0BCF57A7F12D3464FAB -:10126000464BB7FBFCF59C458CBF0A231123B5FB0D -:10127000F3F603FB1652591EC8B2002A3ED00229CB -:101280000B46F4D89DF80B303D495A1E9DF80A30A4 -:101290003C48013B1B0443EA0253BDF80820013AD5 -:1012A00013434B6001F0F4FE00230193364B3749A2 -:1012B00000934FF48052364B364800F06BFF364BAC -:1012C000197811B1334800F08FFF00F0F3FC0546A8 -:1012D000FFF706FC4FF4C873B0FBF3F202FB1303F5 -:1012E00005F516709BB218442C4B186002F066FA94 -:1012F00008B10F23238105B0BDE8F083731EB3F559 -:10130000806FBFD24FF47A75C0EBC00E0EF10303AD -:101310004FEAE30909FB0555C3F3C703C11AC9B274 -:1013200009F101088844B5FBF8F5B5F5617F08D9E6 -:101330000EF1FF33C3F3C703C11A581E0F28C9B2F9 -:1013400014D84A1E072A8CBF00220122581800FB1D -:101350000660B7FBF0F7BC4594D1002A92D0ADF8F7 -:1013600008608DF80A308DF80B108BE71346EDE717 -:101370003411002018110020005125023F420F00B7 -:1013800010110020A8230020D50D000844110020D2 -:10139000A10E00084C21002040110020482100200F -:1013A0002DE9F04F80A7D7E900670FF20429D9E9AA -:1013B0000089734D93B00DF1300AFFF7C7FC182276 -:1013C0000021504600F072F9DFF8B8B16E4C0023EE -:1013D00052461946584601F093FE014650BB102272 -:1013E00008A800F063F9E36883F01003E36000F0FD -:1013F00063FC0DF1240C0B4612A9024611E903000F -:101400008CE803009DF83410C1F30300890649BF3E -:101410000E99BDF83810C1F31C0141F0004158BFCE -:10142000C1F30A018DF82C000891284608A901F0A3 -:1014300097F9CCE7284600F0DFFE0446002847D1A4 -:1014400000F038FCDFF844B1DBF8003098423FD3BD -:1014500000F030FC0790FFF743FB4FF4C873B0FB7C -:10146000F3F101FB1300079A83B202F516701844DA -:10147000CBF80000DFF818B18DF820409BF8001081 -:1014800011B901238DF8203050460791FFF740FB3A -:1014900007990DF12100C1F11004E4B2062C28BF18 -:1014A00006245144224600F0EFF808AB03931823BA -:1014B0000293384B013401930123E4B20093324686 -:1014C0003B462846049400F0DDFE00238BF80030F4 -:1014D00000F0F0FB304A314C1368C31AB3F57A7F41 -:1014E00030D3106000F0E8FB02460B46284600F0BF -:1014F00061FF284600F080FE20B3237ADFF8A0B019 -:10150000002B14BF032302238BF8053000F0D2FB1D -:101510004FF47A73B0FBF3F00122CBF80000514690 -:10152000584600F0B5F9182302931E4B80B2019380 -:1015300040F25513CDE903A0009342464B4628469E -:1015400000F0A0FE237ABBB100F0B4FB94F8E830C1 -:1015500073B9D4F8E03043B1C01A2368FA2B38BF0E -:10156000FA230533B0EB430F02D30020FFF79EFBB5 -:10157000237A002B7FF41FAF13B0BDE8F08F00BFBC -:101580004C210020A8230020000801404821002011 -:101590004521002044210020702300207C210020D0 -:1015A0003411002074230020401DA12026812A0B25 -:1015B000F1C6A7C1D068080F7047000070B501F0F0 -:1015C00095FF0024084E094D3080286833888342F7 -:1015D00008D901F087FF2B6804440133B4F5C84FE4 -:1015E0002B60F2D370BD00BFA4230020782300201D -:1015F00002F00AB800F10060920000F5C84001F066 -:10160000AFBF0000054B1A68054B1B889B1A83422D -:1016100002D9104401F066BF0020704778230020F3 -:10162000A4230020024B1B68184401F061BF00BFD7 -:1016300078230020024B1B68184401F06BBF00BFE9 -:1016400078230020064991F8243033B10023082282 -:10165000086A81F82430FFF7CDBF0120704700BF32 -:101660007C230020022802BF1022014B1A61704720 -:1016700000080140022802BF4FF48012014B1A619A -:10168000704700BF00080140002310B5934203D00B -:10169000CC5CC4540133F9E710BD00000346024698 -:1016A000D01A12F9011B0029FAD1704703460244EF -:1016B000934202D003F8011BFAE770472DE9F84383 -:1016C0001F4D144695F824200746884652BBDFF884 -:1016D00070909CB395F824302BB92022FF21484606 -:1016E0002F62FFF7E3FF95F824004146C0F108029E -:1016F000A24228BF224605EB8000D6B29200FFF737 -:10170000C3FF95F82430A41B1E44F6B2082E1744DC -:101710009044E4B285F82460DBD1FFF793FF002802 -:10172000D7D108E02B6A03EB82038342CFD0FFF7C7 -:1017300089FF0028CBD10020BDE8F8830120FBE71A -:101740007C2300202DE9F0470D46044600219046F9 -:10175000284640F27912FFF7A9FF234620220021F4 -:10176000284600F09FFF022220212846231D00F07A -:1017700099FF032222212846631D00F093FF0322D4 -:1017800025212846A31D00F08DFF10222821284680 -:1017900004F1080300F086FF08223821284604F1EE -:1017A000100300F07FFF08224021284604F11103B6 -:1017B00000F078FF08224821284604F1120300F0C7 -:1017C00071FF20225021284604F1140300F06AFF23 -:1017D00040227021284604F1180300F063FF08221C -:1017E000B021284604F1200300F05CFF0822B82154 -:1017F000284604F1210300F055FFC02604F122071A -:101800003B46314608222846083600F04BFFB6F525 -:10181000A07F07F10107F3D108223146284604F1E1 -:10182000320300F03FFF002704F1330A94F832300E -:101830004FEAC7099F4209F5A47615D3B8F1000F06 -:1018400008D131460722284604F5997300F02AFF93 -:1018500009F24F16274694F832213B1B93420CD3D2 -:10186000F01DC008BDE8F0870AEB070308223146E7 -:10187000284600F017FF0137D8E7314607F2331347 -:101880000822284600F00EFF08360137E3E7000083 -:1018900038B50C460021054621600346C4F8031004 -:1018A0002046202200F0FEFE20462B1D0222202191 -:1018B00000F0F8FE20466B1D0322222100F0F2FE0C -:1018C0002046AB1D0322252100F0ECFE204610220D -:1018D000282105F1080300F0E5FE072038BD0000CF -:1018E0000023F7B50E460546047F072200911946EE -:1018F00000F09AFD731C0093012200230721284663 -:1019000000F092FDC4B9B31C0093052223460821C0 -:10191000284600F089FD0D243746B278BB1B934260 -:1019200011D32B7FE01DC008AC8ABBB9A04294BF85 -:101930000020012003B0F0BDAB8A0824DB00083B87 -:10194000DB08B370E8E7FB1C214600930822002364 -:10195000284600F069FD08340137DEE7001B18BF98 -:101960000120E7E70023F7B50E46047F0822009127 -:101970001946054600F058FD731CC4B908220093AF -:1019800011462346284600F04FFD102401237278AB -:101990005F1C013B934211D32B7FE01DC008AC8A32 -:1019A000BBB9A04294BF0020012003B0F0BDAB8AB8 -:1019B0000824DB00083BDB087370E7E7F3192146D6 -:1019C000009308220023284600F02EFD08343B46F1 -:1019D000DDE7001B18BF0120E7E70000F8B50E4661 -:1019E00005461446002181223046FFF75FFE2B4654 -:1019F00008220021304600F055FE7CB9072208215C -:101A000030466B1C00F04EFE0F2401236A785F1CE9 -:101A1000013B934204D3E01DC008F8BD0824F4E75D -:101A20002146EB190822304600F03CFE08343B46C4 -:101A3000ECE70000F8B50E46054614460021CE221C -:101A40003046FFF733FE2B4628220021304600F0B7 -:101A500029FE7CB908222821304605F1080300F050 -:101A600021FE30242F462A7A7B1B934204D3E01DAB -:101A7000C008F8BD2824F5E7214607F1090308222C -:101A8000304600F00FFE08340137ECE7F7B5047F6D -:101A90000E460091012310220021054600F0C4FCEF -:101AA000C4B9B31C0093092223461021284600F034 -:101AB000BBFC192437467288BB1B9A4211D82B7F76 -:101AC000E01DC008AC8ABBB9A04294BF0020012031 -:101AD00003B0F0BDAB8A1024DB00103BDB08738041 -:101AE000E8E73B1D2146009308220023284600F02A -:101AF0009BFC08340137DEE7001B18BF0120E7E735 -:101B000030B5094D0A4491420DD011F8013B5840BF -:101B1000082340F30004013B2C4013F0FF0384EA48 -:101B20005000F6D1EFE730BD2083B8ED4FF0FF3322 -:101B3000F7B500EB81061946DFF848C0DFF848E04A -:101B4000B0421BD050F8042B01AF0192042217F8C9 -:101B5000014B81EA046108240D46DB184941013C30 -:101B6000002DBCBF83EA0C0381EA0E0114F0FF04D0 -:101B7000F2D1013A12F0FF02E9D1E1E7D843C943BB -:101B800003B0F0BD9336EAA9EBE1F042F7B56B463E -:101B9000354A106851686A4603C3082333493448FC -:101BA00002F0C2F8044690BB0A256B46314A106821 -:101BB00051686A4603C308232F492D4802F0B4F840 -:101BC0000446002847D00369B3F5CE3F43D8B0F8A8 -:101BD0006620B2F57A7F3ED1284A024402F15C01C8 -:101BE0008B4238D35C3B224900209E1AFFF788FFC6 -:101BF00007463246002004F16401FFF781FFA36825 -:101C00009F4228D1E368984208BF002523E003697A -:101C1000B3F5CE3F26D8428BB2F57A7F20D1174A52 -:101C2000024402F110018B4218D3103B10490020EE -:101C30009D1AFFF765FF06462A46002004F11801A9 -:101C4000FFF75EFFA3689E4202D1E368984201D08D -:101C50000D25AAE70025284603B0F0BD1025A4E70E -:101C60000C25A2E70B25A0E7903D0008DC9B0100B6 -:101C700000640008993D0008909B0100089CFFF754 -:101C8000EFF30983EFF30583014B9B6BFEE700BF86 -:101C900000ED00E008B5FFF7F3FF0000EFF3098364 -:101CA000EFF30583014B5B6BFEE700BF00ED00E047 -:101CB000FEE7000001F0E2BC01F0BABC2DE9F04102 -:101CC000456A15B94162BDE8F0814B68AC4623F026 -:101CD0006047C3F38A4616EA230638BF3E464FEAFA -:101CE000D37EC3F380782B465A68BEEBD27F22F0B6 -:101CF00060440AD0002A18DAA40CB44217D19D42DD -:101D00000FD10D60DEE71346EEE7A74207D102F0E0 -:101D10008044C2F3807242450BD054B1EFE708D241 -:101D2000EDE7CCF800100B60CDE7B44201D0B4422F -:101D3000E5D81A689C46002AE5D11960C3E700007F -:101D40002DE9F0474FF47F49089D01F007044FEA61 -:101D5000D508224405F0070500EBD100944201D1DB -:101D6000BDE8F08704F0070705F0070A57453E462F -:101D700038BF5646111BC6F108068E4228BF0E46D4 -:101D8000E108415C08EBD50E13F80EC0B94029FA02 -:101D900006F721FA0AF1FFB28CEA010147FA0AF7C5 -:101DA00039408CEA010C03F80EC034443544D5E7C1 -:101DB000082341F2210280EA012001B240000029FB -:101DC00080B203F1FF33B8BF504013F0FF03F4D1EA -:101DD0007047000038B50C468D18A54200D138BDBB -:101DE00014F8011BFFF7E4FFF7E700000346406823 -:101DF00048B1026899895A605A89013292B2914277 -:101E00005A8138BF9A81704770B504460D4688B034 -:101E1000202200216846FFF749FC20460495FFF781 -:101E2000E5FF024658B16B46054608AE1C4603CC9A -:101E3000B44228606960234605F10805F6D11046D2 -:101E400008B070BD082817D909280CD00A280CD072 -:101E50000B280CD00C280CD00D280CD00E2814BF49 -:101E60004020302070470C2070471020704714200D -:101E7000704718207047202070470000082817D9A5 -:101E80000C280CD910280CD914280CD918280CD9D6 -:101E900020280CD930288CBF0F200E207047092035 -:101EA00070470A2070470B2070470C2070470D20A8 -:101EB000704700002DE9F843078C0446072F1ED910 -:101EC000D0E9029800254FF6FF73C5F12006A5F171 -:101ED000200029FA05F108FA06F628FA00F0314345 -:101EE0000143C9B21846FFF763FF0835402D03468A -:101EF000EBD13A46E169BDE8F843FFF76BBF4FF617 -:101F0000FF70BDE8F883000010B54B6823B9CA8A9A -:101F100063F30902CA8210BD04691A681C60036178 -:101F2000C38A013BC3824A60EFE700002DE9F84F06 -:101F30001D46CB8A0F46C3F3090105298146924607 -:101F40000B4630D00020AAB207F11A049EB2042E2C -:101F50001FFA80F80FD8904503F1010306D3FB8ADE -:101F60000A4462F309030120FB821AE01AF80060B8 -:101F70000130E654EAE79045F1D21C23A1F1050BAC -:101F8000BBFBF3F203FB12BB7C681FFA8BF6002C41 -:101F900045D14846FFF72AFF044638B978606FF00C -:101FA0000200BDE8F88F4FF00008E6E70026066063 -:101FB00078604FF0000BADB2454510D90AEB08032D -:101FC000221D13F8011B08F101089155B1B21B291C -:101FD0001FFA88F82BD0454506F10106F1D8FB8A97 -:101FE000C3F30902154465F30903BCE71C4601323B -:101FF00092B22368002BF9D16B1F0B441C21B3FB59 -:10200000F1F301339BB29A42D3D2BBF1000FD0D18E -:102010004846FFF7EBFE20B9C4F800B0BFE7012245 -:10202000E7E7C0F800B05E4620600446C1E74545DA -:10203000D5D94846FFF7DAFE08B92060AFE7C0F807 -:1020400000B0002620600446B6E700002DE9F74FF7 -:102050001C465B69074688460092002B00F097807B -:10206000238C2BB1E269002A00F09180072B33D832 -:1020700007F10C00FFF7BAFE054628B96FF002051C -:10208000284603B0BDE8F08F14220021FFF70EFBB5 -:10209000228CE16905F10800FFF7F6FA208C48F080 -:1020A0000041013080B2FFF7E9FEFFF7CBFE0138B7 -:1020B00080B22084013028746369228C1B782A4402 -:1020C00003F01F0363F03F0313723846696029462B -:1020D000FFF7F4FD0125D3E74FF000094FF0800A28 -:1020E0004E464D4600F10C0301930198FFF77EFE2A -:1020F00083460028C2D014220021FFF7D7FA002E11 -:102100003BD10222009BABF808300BF1080E1FFAFE -:1021100082FC0CF10100BCF1060F218C80B201D8C9 -:102120008E422CD3FFF7AAFEFFF78CFE8E4208BF2B -:102130004FF0400A62690138127880B202F01F0243 -:1021400042EA49120BEB00014AEA020A013048F068 -:10215000004281F808A08BF8100059463846CBF8A9 -:102160000420FFF7ABFD238C0135B3424FF0000A8A -:102170002DB289F00109B8D182E70022C5E7E169F3 -:10218000895D01360EF80210B6B20132BFE76FF07A -:10219000010575E7F8B5044615460E4630220021C4 -:1021A0001F46FFF783FA069BB5F5001F6360079B88 -:1021B00028BF4FF6FF72A3624FF0000338BF6A09D1 -:1021C000A760E66197B204F110009A4206D8002396 -:1021D0000360A782E3822383E360F8BD06600133D6 -:1021E00030462036F1E7000003781BB94BB2002BD4 -:1021F000C8BF01707047000000787047F8B50C4602 -:10220000C969074611B9238C002B37D1257E1F2DB4 -:1022100034D8387828BB228C072A2CD8268A36F066 -:1022200003032BD14FF6FF70FFF7D4FD4FF6FF727B -:1022300020F001003602400446EA0565400C45EAFC -:102240004025234629463846FFF700FF002807DDD2 -:10225000626913780133DBB21F2B88BF0023137030 -:10226000F8BD218A2D0645EA012505432046FFF7E2 -:1022700021FE0246E5E76FF00300F1E76FF0010091 -:10228000EEE7000070B504461D4616468AB02822C7 -:1022900000216846FFF70AFABDF838306946ADF804 -:1022A00010300F9B204605939DF84030CDE9026524 -:1022B0008DF81830119B0793BDF84830ADF82030E9 -:1022C000FFF79CFF0AB070BD2DE9F041D3690546C8 -:1022D0000C4616460BB9138C5BBB377E1F2F28D8D4 -:1022E00095F80080B8F1000F26D03046FFF7E2FDE8 -:1022F0003378210241EAC33141EA0801338A41EAD5 -:10230000076141EA034102463346284641F0800115 -:10231000FFF79CFE00280ADD3378012B07D1726994 -:1023200013780133DBB21F2B88BF00231370BDE885 -:10233000F0816FF00100FAE76FF00300F7E70000AB -:10234000F0B504460D461E4617468BB028220021E4 -:102350006846FFF7ABF99DF84C3029465A1E5342A8 -:1023600053418DF800309DF840306A46ADF810308A -:10237000119B204605939DF84830CDE902768DF8F3 -:102380001830149B0793BDF85430ADF82030FFF798 -:102390009BFF0BB0F0BD0000406A00B104307047F5 -:1023A000436A1A68426202691A600361C38A013B88 -:1023B000C38270472DE9F041D0F8208014461D46B5 -:1023C00041460027174E09B9BDE8F081D1E9022343 -:1023D000A21A65EB0303964277EB03031ED2036A4E -:1023E0008B420DD1FFF790FD036A1B6803620369FE -:1023F0000B60C38A0161016A013B8846C382E2E740 -:10240000FFF782FD0B68C8F8003003690B60C38AD0 -:102410000161013BC382D8F80010D4E788460968FF -:10242000D1E700BF80841E002DE9F04F8BB00D4630 -:1024300014469B468046DDF85090002800F01A8133 -:10244000B9F1000F00F01681531E3F2B00F21281EC -:10245000012A03D1BBF1000F40F00C810023CDE92C -:102460000833B8F81430B5EBC30F4FEAC30703D3F2 -:1024700000200BB0BDE8F08F2B199F42D8F80C302C -:1024800036BF7F1B2746FFB21BB9D8F81030002B90 -:102490007BD0272D4ED8C5F12806B7424FF0000358 -:1024A00034BF3E46F6B2009329463246D8F80800BB -:1024B00008ABFFF745FCA7EB060A35445FFA8AFA3A -:1024C0002821B8F8143003F10053053BDB000493D6 -:1024D000D8F80C300393039B13B1BAF1000F2CD141 -:1024E000D8F8100040B1BAF1000F05D0524600965E -:1024F00008AB691AFFF724FC38B2002FB8D0660782 -:102500000AD00AAB03EBD40111F8083C624202F096 -:102510000702134101F8083C082C3DD9102C40F269 -:10252000B680202C40F2B880BBF1000F00F09D80F7 -:10253000082335E0BA460026C2E7049BE02B28BFFB -:10254000E02306930B44AB42059315D95A1B9245E1 -:1025500038BF5246039828BFD2B20096691A08AB1A -:1025600004300792FFF7ECFB079A1644AAEB020A25 -:102570001544F6B25FFA8AFA049B069A05999B1AEB -:102580000493039B1B680393A5E700933A462946EF -:10259000D8F8080008ABADE7BBF1000F13D001235A -:1025A000B4EBC30F6CD0082C12D89DF82030621EFB -:1025B00023FA02F2D50706D54FF0FF3202FA04F4EF -:1025C00023438DF820309DF8203089F8003050E703 -:1025D000102C12D8BDF82030621E23FA02F2D10767 -:1025E00006D54FF0FF3202FA04F42343ADF8203051 -:1025F000BDF82030A9F800303BE7202C0FD808990F -:10260000631E21FA03F3DA0705D54FF0FF3202FA11 -:1026100004F40C430894089BC9F8003029E7402CC7 -:102620002BD0DDE90865611EC4F12102A4F121036C -:1026300026FA01F105FA02F225FA03F311431943D0 -:10264000CB0712D50122A4F12003C4F1200102FA24 -:1026500003F322FA01F1A240524243EA010363EB81 -:10266000430332432B43CDE90823DDE90823C9E9BD -:102670000023FEE66FF00100FBE66FF00800F8E6CD -:10268000082CA0D9102CB3D9202CEED8C3E7BBF16D -:10269000000FADD0022383E7BBF1000FBBD00423B2 -:1026A0007EE70000012A30B5144638BF012200251C -:1026B000402A28BF402285B0012CCDE9025517D809 -:1026C0001B788DF8083053070AD004AB03EBD20512 -:1026D00015F8083C544204F00704A34005F8083CF0 -:1026E0000346009102A80021FFF72AFB05B030BD88 -:1026F000082CE5D9102C03D81B88ADF80830E2E788 -:10270000202C02D81B680293DDE7D3E90045CDE910 -:102710000245D8E710B5CB681BB98B600B618B8283 -:1027200010BD04691A681C600361C38A013BC3823F -:10273000CA60F0E703064CBFC0F3C0300220704708 -:1027400008B50246FFF7F6FF022806D15306C2F38A -:102750000F2001D100F0030008BDC2F30740FBE7E2 -:102760002DE9F04F93B0CDE903230A6804461046E3 -:10277000FFF7E0FF02280CBF0026C2F30626002A5E -:102780000D46824680F2F98112F0C04940F0F58191 -:10279000097B002900F0F181022803D02378B3429D -:1027A00040F0EE81C2F304631046069302F07F030B -:1027B0000593FFF7C5FF059B00224FEA83480023DE -:1027C00048EA0A48294448EA4668CE78CDE9082311 -:1027D000F309834648EA0008029367D0059B024646 -:1027E000009320465346676808A9B847002800F0C0 -:1027F000CA81276A4FB9414604F10C00FFF704FB78 -:10280000074690B96FF0020054E03B6998450DD03F -:102810003F68002FF9D1414604F10C00FFF7F4FAAC -:1028200007460028EED0236A3B60276297F817C05E -:1028300006F01F08CCF3840CACEB08001FFA80FEF6 -:102840000028B8BF0EF12000A8EB0C031FFA83FE8E -:10285000B8BF00B2002B0793BEBF0EF120031BB21E -:102860000793D7E9022152EA010338D04FF0000C58 -:10287000039BDFF8F8E19A1A049B63EB010196458C -:102880007CEB01032BD36B7B97F81AE0734519D1CE -:10289000029B002B78D0012821DC7868F8B9DFF89A -:1028A000D0C1944570EB010316D337E0276A27B9EE -:1028B0006FF00C0013B0BDE8F08F3B699845B5D0C0 -:1028C0003F68F4E76A4890427CEB010301D30020A3 -:1028D000F0E7029B002BFAD0079B0F2B17DCFA7D49 -:1028E000B30002F0030203F07C031343FB75394687 -:1028F0002046FFF709FB6B7BBB76029B3BB9FB7D58 -:10290000C3F38402013262F38603FB75D0E76A7B6E -:10291000BB7E9A42DBD1029B002B35D0B309022B40 -:1029200032D0039B1422BB60049B0021FB600DA8E6 -:10293000FEF7BCFE039B20460A93049BADF83EB015 -:102940000B932B1D0C932B7B8DF840A0013BDBB22E -:10295000ADF83C30069B8DF841808DF84230059BE8 -:102960000AA98DF8433094F82C3083F001038DF8D8 -:102970004430A3689847FB7DC3F38403013303F01D -:102980001F039B02FB82A2E7FB7DC6F34012B2EB62 -:10299000D31F40F0FB80C3F38403434540F0F9802C -:1029A000029A2B7BB609002A4DD0F20762D4032B82 -:1029B00040F2F280039BAE1DBB60049B3246FB607D -:1029C0002B7B3946033BDBB204F10C00FFF7AEFA78 -:1029D00000280CDA39462046FFF796FAFB7DC3F350 -:1029E0008403013303F01F039B02FB820AE7AB88D9 -:1029F000DDE908843B834FF6FF73C9F12000A9F19C -:102A0000200228FA09F104FA00F0014324FA02F244 -:102A100011431846C9B2FFF7CBF909F10809B9F11A -:102A2000400F0346E9D13146B8822A7B033AD2B23D -:102A3000FFF7D0F9FB7DB882DA43C2F3C01262F32C -:102A4000C713FB7543E7AEB92E1D013B324639462D -:102A5000DBB204F10C00FFF769FA0028BADB2A7B2D -:102A60003146013AB88AD2B2E2E700BF80841E0044 -:102A700040420F00F98A013BC1F309010429DAB28F -:102A80005DD80023281D07F11B069A4208D910F8CB -:102A900001CB013306F801C001310529DBB2F4D1C5 -:102AA000934228BF0023039938BF04330A91049945 -:102AB00038BFDBB20B9107F11B010C91796838BF6D -:102AC0005B190D910E93FB8AADF83EB0C3F3090379 -:102AD0001A44069BADF83C208DF84230059B8DF8DA -:102AE00040A08DF8433094F82C308DF8418083F06D -:102AF00001038DF8443000237B602A7BB88A013AB9 -:102B0000291DFFF767F93B8BB882834203D120462A -:102B1000A3680AA9984720460AA9FFF7FBFDFB7D99 -:102B2000BA8AC3F38403013303F01F039B02FB82C1 -:102B30003B8B9A420CBF00206FF01000BAE67B6816 -:102B4000002BADD0052001E033461C301E68002E5E -:102B5000FAD1091A081D2E1D184401EB090CBCF10D -:102B60001B0F5FFA89F39BD89A4299D916F8013B5B -:102B700009F1010900F8013BEFE76FF0090099E660 -:102B80006FF00A0096E66FF00B0093E66FF00D0011 -:102B900090E66FF00E008DE66FF00F008AE600BF42 -:102BA000F0B53F4D3F4FEB6943F00073EB61EB69CC -:102BB0003D4B9B6AD3F800623E4046F00106C3F8E5 -:102BC0000062D3F800423C4044EA002444F001048F -:102BD000C3F80042002955D000200646C3F81C0265 -:102BE000C3F80402C3F80C02C3F8140203EBC004D8 -:102BF00001300E28C4F84062C4F84462F6D10027C0 -:102C00004FF0010C9678148816F0010F18BFD3F816 -:102C100004E20CFA04F01CBF40EA0E0EC3F804E212 -:102C200016F0020F18BFD3F80CE203EBC4041CBF6C -:102C300040EA0E0EC3F80CE2760748BFD3F81462E0 -:102C400007F1010744BF0643C3F814625668B9424E -:102C5000C4F84062966802F10C02C4F84462D3F8EA -:102C60001C4240EA0400C3F81C02CBD1D3F8002276 -:102C700022F00102C3F80022EB6923F00073EB613C -:102C8000EB69F0BD0122C3F84012C3F84412C3F847 -:102C90000412C3F81412C3F80C22C3F81C22E5E78F -:102CA000001002400000FFFFA8230020184A08B5CA -:102CB000916A8B688B6013F0010104D013F00C0F44 -:102CC00018BF4FF48031D80506D513F4406F14BFF8 -:102CD00041F4003141F00201D80306D513F4402F2E -:102CE00014BF41F4802141F00401D3690BB10848BD -:102CF0009847302383F311880021064800F048FBF1 -:102D0000002383F31188BDE8084000F099BD00BF9F -:102D1000A8230020B023002038B5124CA36ADD6838 -:102D2000AA0712D05A6922F002025A61A36913B1AC -:102D3000012120469847302383F3118800210A4857 -:102D400000F026FB002383F31188EB0606D5102143 -:102D5000A36AD960236A0BB102489847BDE838409E -:102D600000F06EBDA8230020B823002038B5124C17 -:102D7000A36A1D69AA0712D05A6922F010025A618B -:102D8000A36913B1022120469847302383F31188A9 -:102D900000210A4800F0FCFA002383F31188EB06B7 -:102DA00006D51021A36A1961236A0BB1024898471E -:102DB000BDE8384000F044BDA8230020B82300201F -:102DC00038B50F4CA36A5D682A075D600AD50422F6 -:102DD00022701A6822F002021A60636A13B100219D -:102DE000204698476B0706D5A36A9969236A13B1F1 -:102DF000034809049847BDE8384000F021BD00BFF2 -:102E0000A823002010B50E4C204600F02FF90D4BE2 -:102E10000B211320A36200F009F90B21142000F00C -:102E200005F90B21152000F001F90B21162000F007 -:102E3000FDF8BDE8104000220E201146FFF7B0BE9D -:102E4000A8230020006400400F4B10B598420446B0 -:102E500005D10E4BDA6942F00072DA61DB690122BA -:102E6000A36A1A60A36A5A68D20707D562685168D4 -:102E70001268D9611A60064A5A6110BD0121082002 -:102E800000F0B0F9EEE700BFA823002000100240D8 -:102E90005B87010003291AD8DFE801F0020A0F144A -:102EA000836A9B6813F0E05F14BF01200020704725 -:102EB000836A9868C0F380607047836A9868C0F33B -:102EC000C0607047836A9868C0F300707047002044 -:102ED0007047000010B5032927D8DFE801F002276A -:102EE0002B2F836A9968C1F30161183103EB011339 -:102EF0001078840648BF5468C0F3001158BF948806 -:102F00004FEA410148BF41EAC40100F00F00586098 -:102F100048BF41F00401906858BF41EA4451D2686B -:102F200041F001019860DA60196010BD836A03F511 -:102F3000C073DDE7836A03F5C873D9E7836A03F5D5 -:102F4000D073D5E701290AD002290FD081B9836A4D -:102F5000DA68920701D1186903E001207047836A9B -:102F6000D86810F0030018BF01207047836AF2E7A9 -:102F70000020704710B539B9836AD96889071BD119 -:102F80001B699C0704D110BD012915D00229FAD173 -:102F9000816AD1F8C031D1F8C441D1F8C8011061BB -:102FA000D1F8CC015061202008610869800717D151 -:102FB000486940F0100012E0816AD1F8B031D1F8D0 -:102FC000B441D1F8B8011061D1F8BC0150612020A2 -:102FD000C860C868800703D1486940F002004861B2 -:102FE000C3F34000C3F38001000140EA41111079AE -:102FF00020F030000143117189064BBF916811899F -:10300000DB085B0D4CBF63F31C0163F30A0113790A -:1030100048BF916064F3030313714FEA14234FEA2E -:10302000144458BF118113705480ACE70122090188 -:1030300000F1604303F56143C9B283F8001300F067 -:103040001F039A4043099B0003F1604303F561436A -:10305000C3F880211A607047090100F16040C9B2CD -:1030600000F56D4001767047FFF7CCBE0123037079 -:10307000002300F10802C0E9022200F11002C0E9B9 -:103080000422C0E90633C0E90833436070470000FA -:1030900010B53023044683F3118802234160037086 -:1030A000FFF7D2FE04230020237080F3118810BDA7 -:1030B0002DE9F0411F4604460D461646302383F3A2 -:1030C000118800F108082378052B0DD029462046E9 -:1030D000FFF7E0FE40B1204632462946FFF7FAFEF0 -:1030E000002080F3118808E03946404600F040F99E -:1030F0000028E8D0002383F31188BDE8F0810000A8 -:103100002DE9F0411F4604460D461646302383F351 -:10311000118800F110082378052B0DD02946204690 -:10312000FFF710FF40B1204632462946FFF722FF45 -:10313000002080F3118808E03946404600F018F975 -:103140000028E8D0002383F31188BDE8F081000057 -:1031500000238268037503691B6899689142FBD25A -:103160005A680360426010605860704700238268AC -:10317000037503691B6899689142FBD85A6803601C -:10318000426010605860704708B50846302383F3EA -:1031900011880B7D032B05D0042B0DD02BB983F3A5 -:1031A000118808BD00228B691A604FF0FF338361DC -:1031B000FFF7CEFF0023F2E7D1E9003213605A6037 -:1031C000F3E70000FFF7C4BF054BD968087518681E -:1031D000026853601A6001220275D860FDF796BB41 -:1031E000D823002030B50C4B0446DD684B1C87B05B -:1031F0000FD02B466846094A00F0F0F82046FFF74A -:10320000E3FF009B13B1684600F0F0F8A86907B02F -:1032100030BDFFF7D9FFF9E7D82300208931000836 -:10322000044B1A68DB6890689B68984294BF002042 -:1032300001207047D8230020084B10B51C68D868BF -:10324000226853601A6001222275DC60FFF78EFF4E -:1032500001462046BDE81040FDF758BBD8230020AA -:10326000044B1A68DB6892689B689A4201D9FFF7A1 -:10327000E3BF7047D823002038B501230025064C52 -:10328000064907482370656000F020FB0223237085 -:1032900085F3118838BD00BF30250020A83D000807 -:1032A000D823002000F0B4B8EFF3118020B9EFF379 -:1032B0000583302282F311887047000010B530B9C1 -:1032C000EFF30584C4F3080414B180F3118810BD32 -:1032D000FFF7C6FF84F31188F9E700008B60022333 -:1032E00008618B82084670478368A3F1440243F863 -:1032F000142C026943F8442C426943F8402C094AD3 -:1033000043F8242CC268A3F1200043F8182C0222B1 -:1033100003F80C2C002203F80B2C034A43F8102C62 -:10332000704700BF1D090008D823002008B5FFF72B -:10333000DBFFBDE80840FFF745BF0000024BDB683C -:1033400098610F20FFF740BFD8230020302383F37C -:103350001188FFF7F3BF000008B50146302383F35F -:1033600011880820FFF73EFF002383F3118808BD72 -:10337000064BDB6839B1426818605A6013604360DD -:103380000420FFF72FBF4FF0FF307047D8230020F5 -:1033900038B504460D462068844200D138BD036824 -:1033A00023605C608561FFF70DFFF4E710B50A4C00 -:1033B00023699A6891420CD85A6881600360426020 -:1033C00010609A685860511A99604FF0FF33A361FA -:1033D00010BD1B68891AECE7D8230020C0E903233D -:1033E000002310B410BC4361FFF7E0BF036881689D -:1033F0009A680A449A60426813605A6000234FF04A -:10340000FF320360014B9A61704700BFD823002050 -:1034100070B5124D2A46EB690133EB6152F8103F4B -:10342000934206D030269A68013A9A602C69A368C4 -:1034300003B170BDD4E900210A605160236083F3B9 -:1034400011882046D4E90331984786F311886169D1 -:103450000029EBD02046FFF7A9FFE7E7D82300209B -:1034600000207047FEE70000704700004FF0FF307B -:1034700070470000BFF34F8F024AD368DB07FCD4CC -:10348000704700BF0020024008B5074B1B7853B9B6 -:10349000FFF7F0FF054B1A69120641BF044A5A6054 -:1034A00002F188325A6008BD482500200020024001 -:1034B0002301674508B5054B1B7833B9FFF7DAFFE1 -:1034C000034A136943F08003136108BD48250020B7 -:1034D000002002407F289ABF00F5003080020020C3 -:1034E000704700004FF480607047000080207047F4 -:1034F0007F2808B50BD8FFF7EDFF00F58063026861 -:10350000013204D104308342F9D1012008BD0020EA -:10351000FCE700007F2810B504461CD8FFF7AAFF7F -:10352000FFF7B2FFF3220D4B4FF48061DA60022205 -:103530001A61FFF7CFFF58611A6942F040021A6121 -:10354000FFF798FF00F004F9FFF7B4FF2046BDE84D -:103550001040FFF7CDBF002010BD00BF002002408B -:103560002DE9F843054612F00100144606D040F25A -:10357000F32200201E4B1A60BDE8F8831D4BAA18E9 -:103580009A4204D94FF43E72194B1A60F4E7FFF7E0 -:103590007BFF4FF00109FFF76DFFDFF85C806D1ACC -:1035A000012C0F4605EB010603D8FFF783FF01202E -:1035B000E2E73B88C8F8109033800020FFF75AFFFD -:1035C000C8F81000338831F8022B9BB29A420CD015 -:1035D00040F20F32064B1A60084B1E60084B1C600D -:1035E000084B1F60FFF766FFC6E7023CD8E700BF45 -:1035F0004425002000000208002002403825002059 -:10360000402500203C250020084908B50B7828B14A -:103610001BB9FFF739FF01230B7008BD002BFCD04D -:10362000BDE808400870FFF745BF00BF48250020EF -:1036300070B5FFF739FE4FF47A710D4B0D4EDB6913 -:10364000326801FB03F3934237BF0B4A0A495168C2 -:10365000156836BF4C1CD1E9005454605D1944F123 -:1036600000043360FFF72AFE2846214670BD00BFE4 -:10367000D82300204C2500205025002070B5FFF7EE -:1036800013FE4FF47A710F4B0F4EDB69326801FB6A -:1036900003F3934237BF0D4A0C49516815683ABF8E -:1036A0004C1C5460D1E900545D1944F100043360AE -:1036B000FFF704FE4FF47A72002328462146FCF7F8 -:1036C00031FF70BDD82300204C250020502500205C -:1036D00010B5094C013AD2B2FF2A00D110BD5008F2 -:1036E00054F82030013054F820009BB243EA0043E4 -:1036F00041F8043BEEE700BF046C004010B50748FA -:10370000013AD2B2FF2A00D110BD0C88530840F80C -:1037100023404C88013340F82340F1E7046C00401B -:1037200007B50122002001A9FFF7D2FF019803B0DD -:103730005DF804FB13B50446FFF7F2FFA04205D085 -:103740000122002001A90194FFF7D8FF02B010BDAB -:103750007047000045F25552064B1A6002225A602B -:1037600040F6FF729A604CF6CC421A600122024B7E -:103770001A707047003000405C250020034B1B7816 -:103780001BB14AF6AA22024B1A6070475C25002042 -:1037900000300040044B1A682AB902F1804202F559 -:1037A0000432526A1A607047582500204FF0807228 -:1037B000014B5A62704700BF0010024008B5FFF786 -:1037C000E9FF024B1868C0F3407008BD582500207F -:1037D00008B5FFF7DFFF024B1868C0F3007008BDA3 -:1037E00058250020EFF30983203383F30988002351 -:1037F00083F3118870470000302080F3118862B68F -:103800000C4B0D4AD96821F4E0610904090C0A4304 -:10381000DA60D3F8FC20094942F08072C3F8FC203A -:103820000A6842F001020A602022DA7783F8220057 -:10383000704700BF00ED00E00003FA05001000E053 -:10384000302310B583F311880B4B5B6813F40063CE -:103850000FD0EFF309844FF08073203CE36184F3D1 -:103860000988FFF7DDFC10B1044BA36110BD044BC8 -:10387000FBE783F31188F9E700ED00E02F0900086A -:103880003209000870470000FEE700000A4B0B48B1 -:103890000B4A90420BD30B4BC11EDA1C121A22F0BA -:1038A00003028B4238BF00220021FDF7FFBE53F810 -:1038B000041B40F8041BECE72C3E0008E025002028 -:1038C000E0250020E0250020FEE7000070B500257F -:1038D00004461A4B86B05860856201630E46FFF7B6 -:1038E0008BFF04F11003C4E904334FF0FF33A361ED -:1038F000134BE561D9692B460A462046C4E90823E3 -:1039000004F134018023C4E900440E4AA560E56255 -:103910002565FFF7E3FC01230B4AE0600375009285 -:10392000726868460192B268CDE90223074BCDE97F -:103930000435FFF7FBFC06B070BD00BF302500204A -:10394000D8230020B43D0008B93D0008C93800085C -:1039500000F030B808B500F063F9FFF78DFCBDE862 -:103960000840FFF717BF0000704700004FF0FF311D -:103970000E4B1A6919611A6900221A611869D86810 -:10398000D960D968DA60DA68DA6942F08052DA61BF -:10399000DA69DA6942F00062DA61054ADB691368C4 -:1039A00043F48073136000F01BB900BF00100240A5 -:1039B00000700040194B1A6842F001021A601A6840 -:1039C0009007FCD51A6802F0F9021A6000225A60CA -:1039D0005A6812F00C0FFBD11A6842F480321A6058 -:1039E0001A689103FCD55A6842F4E8125A601A68C2 -:1039F00042F080721A601A689201FCD51221084ABE -:103A00005A60084A11605A6842F002025A605A68C5 -:103A100002F00C02082AFAD1704700BF00100240E1 -:103A200000641D0000200240084A08B5516913686F -:103A30000B4003F00103536123B1054A13680BB136 -:103A400050689847BDE80840FFF7FABE00040140FF -:103A500060250020084A08B5516913680B4003F03F -:103A60000203536123B1054A93680BB1D0689847AC -:103A7000BDE80840FFF7E4BE0004014060250020D7 -:103A8000084A08B5516913680B4003F004035361F9 -:103A900023B1054A13690BB150699847BDE8084046 -:103AA000FFF7CEBE0004014060250020084A08B59B -:103AB000516913680B4003F00803536123B1054AB1 -:103AC00093690BB1D0699847BDE80840FFF7B8BECD -:103AD0000004014060250020084A08B551691368B8 -:103AE0000B4003F01003536123B1054A136A0BB175 -:103AF000506A9847BDE80840FFF7A2BE00040140A5 -:103B000060250020174B10B55A691C68144004F456 -:103B100078725A61A30604D5134A936A0BB1D06A2E -:103B20009847600604D5104A136B0BB1506B984749 -:103B3000210604D50C4A936B0BB1D06B9847E20574 -:103B400004D5094A136C0BB1506C9847A30504D5F2 -:103B5000054A936C0BB1D06C9847BDE81040FFF755 -:103B60006FBE00BF00040140602500201A4B10B555 -:103B70005A691C68144004F47C425A61620504D5F9 -:103B8000164A136D0BB1506D9847230504D5134A9F -:103B9000936D0BB1D06D9847E00404D50F4A136EB6 -:103BA0000BB1506E9847A10404D50C4A936E0BB12B -:103BB000D06E9847620404D5084A136F0BB1506F5A -:103BC0009847230404D5054A936F0BB1D06F9847EB -:103BD000BDE81040FFF734BE00040140602500201E -:103BE000062108B50846FFF721FA06210720FFF74E -:103BF0001DFA06210820FFF719FA06210920FFF710 -:103C000015FA06210A20FFF711FA06211720FFF7FF -:103C10000DFABDE8084006212820FFF707BA00008A -:103C200008B5FFF7A3FE054800F00CF8FFF71CFAF3 -:103C3000FFF79AFEBDE8084000F002B8C03D00085A -:103C400000F042B8002319461C4A0133102BC2E988 -:103C5000001102F10802F8D1194B9A6942F07D0275 -:103C60009A619B690268174BDA6082685A60426801 -:103C70001A60C26803F58063DA6042695A600269BB -:103C80001A608269C3F80C24026AC3F80424C2696A -:103C9000C3F80024426AC3F80C28C26AC3F8042897 -:103CA000826AC3F80028026BC3F80C2C826BC3F83D -:103CB000042C426BC3F8002C704700BF6025002025 -:103CC00000100240000801404FF0E023044A0821A0 -:103CD0005A6100229A6107220B201A61FFF7BCB9D2 -:103CE0003F19010008B5302383F31188FFF7DAFA92 -:103CF000002383F3118808BD08B5FFF7F3FFBDE883 -:103D00000840FFF79DBD000010B501390244904204 -:103D100001D1002005E0037811F8014FA34201D042 -:103D2000181B10BD0130F2E72DE9F0419BB10446AC -:103D3000C91A1778014403F1FF3C8C42204601D98F -:103D4000002008E005780134BD42F6D10CEB0405F3 -:103D5000D618A54201D1BDE8F08115F8018D16F8FD -:103D600001EDF045F5D0E8E7034611F8012B03F823 -:103D7000012B002AF9D170476F72672E617264754A -:103D800070696C6F742E663130332D41445342009C -:103D900040A2E4F1646891060041A3E5F2656992EE -:103DA0000700000063300000A43D0008302400201C -:103DB000302500206D61696E0069646C650000004B -:103DC00000180000444441444454494401000000A8 -:103DD00042444444444444440000000044444444B5 -:103DE00044444444000000004444444444444444A3 -:103DF00000000000444444444444444458C7FF7F06 -:103E00000100000000000000E803000000000000C6 -:103E1000009C0100000000006400000000000000A1 -:0C3E200040420F00FE2A0100D204000006 +:10052000704700BF02E000F000F8FEE772B6264810 +:1005300080F30888254880F3098825482549086004 +:10054000022080F31488BFF36F8F03F025F803F0C7 +:1005500089F84FF0553020491B4A91423CBF41F881 +:10056000040BFAE71D49194A91423CBF41F8040BBC +:10057000FAE71B491B4A1C4B9A423EBF51F8040B39 +:1005800042F8040BF8E700201849194A91423CBF91 +:1005900041F8040BFAE703F003F803F065F8154C93 +:1005A000154DAC4203DA54F8041B8847F9E700F014 +:1005B0003FF8124C124DAC4203DA54F8041B884742 +:1005C000F9E702F0EBBF0000000900200011002055 +:1005D0000000000808ED00E00001002000090020F4 +:1005E000103B0008001100202411002028110020D9 +:1005F000D4250020600100086001000860010008A7 +:10060000600100082DE9F04FC1F80CD0C3689D4689 +:10061000BDE8F08F002383F311882846A04700200F +:1006200002F0E6FCFEE702F07FFC00DFFEE70000E0 +:10063000F8B500F03BFE02F0FDFE074602F048FF71 +:10064000064600283ED12B4B9F423BD001339F42B0 +:100650003BD0294B27F0FF029A4239D1F8B200F083 +:1006600001FC354642F2107400F002FC08B100248F +:10067000254601F003F978B30024032000F042F886 +:10068000254636B11D4B9F4203D0002402F018FFCF +:100690002546002002F0D8FE194B9B6813F040035A +:1006A0001FD00DB100F044F800F042FC01F07AF9DF +:1006B0000546C4B101F076F9401BA04213D900F001 +:1006C00037F8F3E735460024CEE704460125CBE7AB +:1006D00005464FF47A74C7E7B4F57A7F08BF012561 +:1006E000CFE71C46E0E700F0D5FC012002F086FCD5 +:1006F000DFE700BF010007B0000008B0263A09B0EC +:10070000000C0140084B187003280CD8DFE800F0FB +:1007100008050208022000F025BE022000F01ABEE3 +:100720000022024B5A607047281100202C11002033 +:1007300038B501F0A3F830B103221F4B1A70002224 +:100740001E4B5A6038BD1E4B1E4A19680131F9D044 +:1007500004339342F9D11C4C194DD4F80424AA4215 +:10076000F0D31A4B9B6803F1006303F5C8439A4228 +:10077000E8D202F079FE02F08BFE002000F0B0FD1E +:100780000220FFF7BFFF124BDA690022DA61D96954 +:1007900099699A619B6972B64FF0E023C3F8085DCE +:1007A0003021D4F80034D4F8042481F311889D4614 +:1007B00083F308881047C5E7281100202C1100207A +:1007C0000064000820640008006000080011002098 +:1007D0000010024049F26900084A136899B21B0CE4 +:1007E00000FB013344F250611360054B186882B27C +:1007F000000C01FB0200186080B27047201100203D +:100800001C11002010B504460021102200F0C6FD86 +:10081000034B03CB206061601868A06010BD00BF6F +:10082000E8F7FF1F2DE9F0410026ADF54E7D6CACD9 +:1008300040F2751207460D460EA831460D9600F09F +:10084000ADFD4FF4C4723146204600F0A7FD01F023 +:10085000A9F84FF47A72B0FBF2F0264B0DF1340890 +:10086000186093E80700022384E807000DF5E9709B +:100870002382FFF7C7FF4EF603031F4907A823840F +:1008800003F0FCF817230DF2E32284F832310DF166 +:100890002C0C07AB1E4603CE6645106051603346F4 +:1008A00002F10802F6D130681060B188B3792046B1 +:1008B000918093714146012200F0BCFD0023039317 +:1008C000AB7E80B2029305F1190301930123CDE9B8 +:1008D00004800093384605A3D3E90023E97E01F0A4 +:1008E000A7FB0DF54E7DBDE8F08100BF9E6AC421D7 +:1008F000818A46EE341100208C3A00082DE9F0413F +:10090000264D80462B7A0C46DAB0FBB9204627A943 +:1009100000F0A0FE0746002836D19DF89D60C82E45 +:1009200032D801464FF4FA72284600F037FD3246BD +:100930000DF19E0105F1090000F01EFD9DF89C30AF +:100940002E4477722B720BB9E37E2B728122002129 +:1009500006AD27A800F022FD0122294627A800F0B5 +:10096000B5FE00230393A37E80B2029304F1190322 +:1009700001932823CDE904500093404605A3D3E911 +:100980000023E17E01F054FB5AB0BDE8F08100BFC6 +:10099000AFF3008026417272DF25D7B77C2100209B +:1009A000F0B54FF48A750024234EF1B005FB0065C5 +:1009B00096F8D830D822214685F8DC3085F8E84012 +:1009C0003AA800F0EBFC06F1090000F0DFFCD5F8D6 +:1009D000E430C2B206AF8DF8F00006F109010DF166 +:1009E000F100CDE93A3400F0C7FC394601223AA8BB +:1009F00000F098FE80B2CDE9047008230127CDE90C +:100A0000023706F1D80301933023317A00930B4863 +:100A100007A3D3E9002301F00BFBA04206DD00F0A1 +:100A2000C1FFC5F8E000384671B0F0BD2046FBE7D5 +:100A300078F6339F93CACD8D7C2100204C21002075 +:100A4000F0B51E4E1E4F1F4D85B0304601F01CFB09 +:100A5000044660B310220021684600F09FFC4FF06E +:100A60000003227B6068A16862F303038DF8003005 +:100A700002AB03C3019B2268384662F31C03019357 +:100A80009DF800306A4643F020038DF800300023C3 +:100A9000194602F085F9044620B9304601F0F8FA0B +:100AA0002C70D2E72B78072B03D801332B7005B0BD +:100AB000F0BD024801F0ECFAF9E700BF4C2100203C +:100AC000A82300207523002070B50D4614461E464D +:100AD00001F00AFA50B9022E10D1012C0ED112A346 +:100AE000D3E900230120C5E9002307E0282C10D01A +:100AF00005D8012C09D0052C0FD0002070BD302C5A +:100B0000FBD10BA3D3E90023ECE70BA3D3E900232C +:100B1000E8E70BA3D3E90023E4E70BA3D3E9002321 +:100B2000E0E700BFAFF30080401DA12026812A0B23 +:100B300078F6339F93CACD8D9E6AC421818A46EE92 +:100B400026417272DF25D7B7F017304A39059E5615 +:100B500038B505460E4C0021013500F0E3FBA4F842 +:100B6000F051B4F8F00100F0C5FB78B1B4F8F00131 +:100B700000F0D0FB014648B9B4F8F00100F0D2FB18 +:100B8000B4F8F0310133A4F8F031EAE738BD00BF22 +:100B90007C2100202DE9F04F8DB000AF04460D46BA +:100BA00001F0A2F9002846D12B7E022B1AD1EB8A44 +:100BB000012B17D100F0F6FE0646FFF70BFE4FF4AF +:100BC000C873B0FBF3F202FB1303DFF878829BB229 +:100BD00006F516763344C8F80030EB7E33B90022B0 +:100BE000994B1A703437BD46BDE8F08F284607F19F +:100BF0001C0100F0EDFC0028F4D107F10C00FFF718 +:100C000001FEBD7F07F10C012A4607F11F0002F02B +:100C100005FF0028E3D10F2D08D88B4B1D70D8F8A5 +:100C20000030A3F51673C8F80030DBE72046397FA3 +:100C300001F052F9D6E7EB8A282B6BD010D8012BA4 +:100C400063D0052BCED1BFF34F8F8049804BCA684C +:100C500002F4E0621343CB60BFF34F8F00BFFDE7A8 +:100C6000302BBFD17B4CEA7E237A9A42BAD194F8DA +:100C7000DC206B7E9A42B5D1284604F1EA0100F0EF +:100C80007DFD06460028ADD1012384F8E83000F050 +:100C900089FED4F8E030C01A192840F6B83338BFBE +:100CA0001920984228BF1846FFF7C4FB6A49FFF78E +:100CB00057FA05462068FFF7BDFB6849FFF750FA71 +:100CC00001462846FFF706FBFFF70CFC20604FF4B7 +:100CD0008A7194F8D9307B607A68636801FB02F509 +:100CE000621992F8E80050B1D2F8E400E946834274 +:100CF00015D0002382F8E830C2F8E030CD466368B2 +:100D0000574A9B0A013313816CE729462046FFF7B7 +:100D100089FD67E729462046FFF7F0FD62E7B2F854 +:100D2000EC803B6008F1030A4FEA9A0A4FEA8A0214 +:100D3000D11DC908A9EBC1039D46EB4600215846C9 +:100D400000F02CFB05F1EE0142465846214400F02C +:100D500013FB3B6813B9012000F0C2FA94F8D200EB +:100D600000F0C8FA054630B9207200F0E3FA2846D0 +:100D700000F0B6FAC2E7D4F8D4303BB994F8D20008 +:100D8000B4F8F031834201D8FFF7E2FED4F8D43052 +:100D900043449D4208D294F8D200B4F8F0310130B7 +:100DA000834201D8FFF7D4FE594660685FFA8AF2A1 +:100DB00000F0FCFA08B9CD4689E7636894F8D200E0 +:100DC00043446360D4F8D43008EB030AC4F8D4A0D9 +:100DD00000F090FA824509D394F8D230D4F8D400C8 +:100DE0000133401B84F8D230C4F8D400B8F1FF0FAF +:100DF0000FD80025257200F09DFA284600F070FA01 +:100E000000F03CFD164B188108B9FFF791FCCD4668 +:100E1000E8E64FF48A727B6894F8D90002FB03433A +:100E2000D3F8E42083F8E86002F58072C3F8E0604C +:100E3000C3F8E420FFF7B4FDFFF702FE84F8D960A1 +:100E4000B9E700BF482100204521002000ED00E067 +:100E50000400FA057C210020CDCCCC3D6666663FBF +:100E600034110020014B1870704700BF4011002062 +:100E700030B54FF00054254B226885B09A4207D018 +:100E800002F030FB0446C0B90024204605B030BD56 +:100E90000025627D1E4B1F481A70237DC9220372F4 +:100EA0001D49C0F8E450093000F066FA2046E022FF +:100EB000294600F073FA0124E7E7184A184DD36970 +:100EC00043F00073D361AA6D164B9A42DCD12B6EAE +:100ED000013B7E2BD8D8144A01AB07CA83E8070030 +:100EE0001846032100F09AFC6B6D83424FF000031B +:100EF000CAD12A6D8A4203BFAB652A6E044B1C46D9 +:100F000001BF1A70EA6D094B1A60BEE79AAD44C57D +:100F1000401100207C21002016000020001002401B +:100F2000006600405041A0B05866004018110020F3 +:100F30002DE9F04385B000F0A1FC0223494C637118 +:100F400000230293484B2081D3F800C0BCF57A7F80 +:100F500012D3464F464BB7FBFCF59C458CBF0A238A +:100F60001123B5FBF3F603FB1652591EC8B2002A33 +:100F70003ED002290B46F4D89DF80B303D495A1E4D +:100F80009DF80A303C48013B1B0443EA0253BDF87C +:100F90000820013A13434B6001F0F2FE0023019355 +:100FA000364B374900934FF48052364B364800F0A9 +:100FB00069FF364B197811B1334800F08DFF00F00E +:100FC000F1FC0546FFF706FC4FF4C873B0FBF3F2E3 +:100FD00002FB130305F516709BB218442C4B1860E6 +:100FE00002F076FA08B10F23238105B0BDE8F08343 +:100FF000731EB3F5806FBFD24FF47A75C0EBC00E8D +:101000000EF103034FEAE30909FB0555C3F3C703D8 +:10101000C11AC9B209F101088844B5FBF8F5B5F564 +:10102000617F08D90EF1FF33C3F3C703C11A581EFD +:101030000F28C9B214D84A1E072A8CBF00220122E9 +:10104000581800FB0660B7FBF0F7BC4594D1002AA6 +:1010500092D0ADF808608DF80A308DF80B108BE750 +:101060001346EDE73411002018110020005125022D +:101070003F420F0010110020A8230020C90A0008D9 +:1010800044110020950B00084C2100204011002045 +:10109000482100202DE9F04F80A7D7E900670FF223 +:1010A0000429D9E90089734D93B00DF1300AFFF797 +:1010B000C7FC18220021504600F070F9DFF8B8B1E3 +:1010C0006E4C002352461946584601F091FE0146E7 +:1010D00050BB102208A800F061F9E36883F0100308 +:1010E000E36000F061FC0DF1240C0B4612A90246EE +:1010F00011E903008CE803009DF83410C1F30300EC +:10110000890649BF0E99BDF83810C1F31C0141F0A2 +:10111000004158BFC1F30A018DF82C000891284600 +:1011200008A901F095F9CCE7284600F0DDFE044659 +:10113000002847D100F036FCDFF844B1DBF800307E +:1011400098423FD300F02EFC0790FFF743FB4FF48B +:10115000C873B0FBF3F101FB1300079A83B202F5E9 +:1011600016701844CBF80000DFF818B18DF8204055 +:101170009BF8001011B901238DF8203050460791DB +:10118000FFF740FB07990DF12100C1F11004E4B213 +:10119000062C28BF06245144224600F0EDF808AB87 +:1011A000039318230293384B013401930123E4B2D3 +:1011B000009332463B462846049400F0DBFE0023B1 +:1011C0008BF8003000F0EEFB304A314C1368C31A44 +:1011D000B3F57A7F30D3106000F0E6FB02460B4691 +:1011E000284600F05FFF284600F07EFE20B3237AF9 +:1011F000DFF8A0B0002B14BF032302238BF80530C7 +:1012000000F0D0FB4FF47A73B0FBF3F00122CBF87F +:1012100000005146584600F0B3F9182302931E4BC4 +:1012200080B2019340F25513CDE903A000934246EA +:101230004B46284600F09EFE237ABBB100F0B2FB7D +:1012400094F8E83073B9D4F8E03043B1C01A236899 +:10125000FA2B38BFFA230533B0EB430F02D300203B +:10126000FFF79EFB237A002B7FF41FAF13B0BDE87E +:10127000F08F00BF4C210020A8230020000801406F +:101280004821002045210020442100207023002017 +:101290007C2100203411002074230020401DA12057 +:1012A00026812A0BF1C6A7C1D068080F70B501F0DE +:1012B0007DFF0024084E094D308028683388834222 +:1012C00008D901F06FFF2B6804440133B4F5C84F0F +:1012D0002B60F2D370BD00BFA42300207823002030 +:1012E00001F0F2BF00F10060920000F5C84001F08B +:1012F00097BF0000054B1A68054B1B889B1A834259 +:1013000002D9104401F04EBF00207047782300201E +:10131000A4230020024B1B68184401F049BF00BF02 +:1013200078230020024B1B68184401F053BF00BF14 +:1013300078230020064991F8243033B10023082295 +:10134000086A81F82430FFF7CDBF0120704700BF45 +:101350007C230020022802BF1022014B1A61704733 +:1013600000080140022802BF4FF48012014B1A61AD +:10137000704700BF00080140002310B5934203D01E +:10138000CC5CC4540133F9E710BD000003460246AB +:10139000D01A12F9011B0029FAD170470346024402 +:1013A000934202D003F8011BFAE770472DE9F84396 +:1013B0001F4D144695F824200746884652BBDFF897 +:1013C00070909CB395F824302BB92022FF21484619 +:1013D0002F62FFF7E3FF95F824004146C0F10802B1 +:1013E000A24228BF224605EB8000D6B29200FFF74A +:1013F000C3FF95F82430A41B1E44F6B2082E1744F0 +:101400009044E4B285F82460DBD1FFF793FF002815 +:10141000D7D108E02B6A03EB82038342CFD0FFF7DA +:1014200089FF0028CBD10020BDE8F8830120FBE72D +:101430007C2300202DE9F0470D460446002190460C +:10144000284640F27912FFF7A9FF23462022002107 +:10145000284600F09FFF022220212846231D00F08D +:1014600099FF032222212846631D00F093FF0322E7 +:1014700025212846A31D00F08DFF10222821284693 +:1014800004F1080300F086FF08223821284604F101 +:10149000100300F07FFF08224021284604F11103C9 +:1014A00000F078FF08224821284604F1120300F0DA +:1014B00071FF20225021284604F1140300F06AFF36 +:1014C00040227021284604F1180300F063FF08222F +:1014D000B021284604F1200300F05CFF0822B82167 +:1014E000284604F1210300F055FFC02604F122072D +:1014F0003B46314608222846083600F04BFFB6F539 +:10150000A07F07F10107F3D108223146284604F1F4 +:10151000320300F03FFF002704F1330A94F8323021 +:101520004FEAC7099F4209F5A47615D3B8F1000F19 +:1015300008D131460722284604F5997300F02AFFA6 +:1015400009F24F16274694F832213B1B93420CD3E5 +:10155000F01DC008BDE8F0870AEB070308223146FA +:10156000284600F017FF0137D8E7314607F233135A +:101570000822284600F00EFF08360137E3E7000096 +:1015800038B50C460021054621600346C4F8031017 +:101590002046202200F0FEFE20462B1D02222021A4 +:1015A00000F0F8FE20466B1D0322222100F0F2FE1F +:1015B0002046AB1D0322252100F0ECFE2046102220 +:1015C000282105F1080300F0E5FE072038BD0000E2 +:1015D0000023F7B50E460546047F07220091194601 +:1015E00000F09AFD731C0093012200230721284676 +:1015F00000F092FDC4B9B31C0093052223460821D4 +:10160000284600F089FD0D243746B278BB1B934273 +:1016100011D32B7FE01DC008AC8ABBB9A04294BF98 +:101620000020012003B0F0BDAB8A0824DB00083B9A +:10163000DB08B370E8E7FB1C214600930822002377 +:10164000284600F069FD08340137DEE7001B18BFAB +:101650000120E7E70023F7B50E46047F082200913A +:101660001946054600F058FD731CC4B908220093C2 +:1016700011462346284600F04FFD102401237278BE +:101680005F1C013B934211D32B7FE01DC008AC8A45 +:10169000BBB9A04294BF0020012003B0F0BDAB8ACB +:1016A0000824DB00083BDB087370E7E7F3192146E9 +:1016B000009308220023284600F02EFD08343B4604 +:1016C000DDE7001B18BF0120E7E70000F8B50E4674 +:1016D00005461446002181223046FFF75FFE2B4667 +:1016E00008220021304600F055FE7CB9072208216F +:1016F00030466B1C00F04EFE0F2401236A785F1CFD +:10170000013B934204D3E01DC008F8BD0824F4E770 +:101710002146EB190822304600F03CFE08343B46D7 +:10172000ECE70000F8B50E46054614460021CE222F +:101730003046FFF733FE2B4628220021304600F0CA +:1017400029FE7CB908222821304605F1080300F063 +:1017500021FE30242F462A7A7B1B934204D3E01DBE +:10176000C008F8BD2824F5E7214607F1090308223F +:10177000304600F00FFE08340137ECE7F7B5047F80 +:101780000E460091012310220021054600F0C4FC02 +:10179000C4B9B31C0093092223461021284600F047 +:1017A000BBFC192437467288BB1B9A4211D82B7F89 +:1017B000E01DC008AC8ABBB9A04294BF0020012044 +:1017C00003B0F0BDAB8A1024DB00103BDB08738054 +:1017D000E8E73B1D2146009308220023284600F03D +:1017E0009BFC08340137DEE7001B18BF0120E7E748 +:1017F00030B5094D0A4491420DD011F8013B5840D3 +:10180000082340F30004013B2C4013F0FF0384EA5B +:101810005000F6D1EFE730BD2083B8ED4FF0FF3335 +:10182000F7B500EB81061946DFF848C0DFF848E05D +:10183000B0421BD050F8042B01AF0192042217F8DC +:10184000014B81EA046108240D46DB184941013C43 +:10185000002DBCBF83EA0C0381EA0E0114F0FF04E3 +:10186000F2D1013A12F0FF02E9D1E1E7D843C943CE +:1018700003B0F0BD9336EAA9EBE1F042F7B56B4651 +:10188000354A106851686A4603C30823334934480F +:1018900002F0D4F8044690BB0A256B46314A106822 +:1018A00051686A4603C308232F492D4802F0C6F841 +:1018B0000446002847D00369B3F5CE3F43D8B0F8BB +:1018C0006620B2F57A7F3ED1284A024402F15C01DB +:1018D0008B4238D35C3B224900209E1AFFF788FFD9 +:1018E00007463246002004F16401FFF781FFA36838 +:1018F0009F4228D1E368984208BF002523E003698E +:10190000B3F5CE3F26D8428BB2F57A7F20D1174A65 +:10191000024402F110018B4218D3103B1049002001 +:101920009D1AFFF765FF06462A46002004F11801BC +:10193000FFF75EFFA3689E4202D1E368984201D0A0 +:101940000D25AAE70025284603B0F0BD1025A4E721 +:101950000C25A2E70B25A0E7A43A0008DC9B0100B8 +:1019600000640008AD3A0008909B0100089CFFF756 +:10197000EFF30983EFF30583014B9B6BFEE700BF99 +:1019800000ED00E008B5FFF7F3FF0000EFF3098377 +:10199000EFF30583014B5B6BFEE700BF00ED00E05A +:1019A000FEE7000001F0F6BC01F0A2BC2DE9F04119 +:1019B000456A15B94162BDE8F0814B68AC4623F039 +:1019C0006047C3F38A4616EA230638BF3E464FEA0D +:1019D000D37EC3F380782B465A68BEEBD27F22F0C9 +:1019E00060440AD0002A18DAA40CB44217D19D42F0 +:1019F0000FD10D60DEE71346EEE7A74207D102F0F4 +:101A00008044C2F3807242450BD054B1EFE708D254 +:101A1000EDE7CCF800100B60CDE7B44201D0B44242 +:101A2000E5D81A689C46002AE5D11960C3E7000092 +:101A30002DE9F0474FF47F49089D01F007044FEA74 +:101A4000D508224405F0070500EBD100944201D1EE +:101A5000BDE8F08704F0070705F0070A57453E4642 +:101A600038BF5646111BC6F108068E4228BF0E46E7 +:101A7000E108415C08EBD50E13F80EC0B94029FA15 +:101A800006F721FA0AF1FFB28CEA010147FA0AF7D8 +:101A900039408CEA010C03F80EC034443544D5E7D4 +:101AA000082341F2210280EA012001B2400000290E +:101AB00080B203F1FF33B8BF504013F0FF03F4D1FD +:101AC0007047000038B50C468D18A54200D138BDCE +:101AD00014F8011BFFF7E4FFF7E700000346406836 +:101AE00048B1026899895A605A89013292B291428A +:101AF0005A8138BF9A81704770B504460D4688B048 +:101B0000202200216846FFF749FC20460495FFF794 +:101B1000E5FF024658B16B46054608AE1C4603CCAD +:101B2000B44228606960234605F10805F6D11046E5 +:101B300008B070BD082817D909280CD00A280CD085 +:101B40000B280CD00C280CD00D280CD00E2814BF5C +:101B50004020302070470C20704710207047142020 +:101B6000704718207047202070470000082817D9B8 +:101B70000C280CD910280CD914280CD918280CD9E9 +:101B800020280CD930288CBF0F200E207047092048 +:101B900070470A2070470B2070470C2070470D20BB +:101BA000704700002DE9F843078C0446072F1ED923 +:101BB000D0E9029800254FF6FF73C5F12006A5F184 +:101BC000200029FA05F108FA06F628FA00F0314358 +:101BD0000143C9B21846FFF763FF0835402D03469D +:101BE000EBD13A46E169BDE8F843FFF76BBF4FF62A +:101BF000FF70BDE8F883000010B54B6823B9CA8AAE +:101C000063F30902CA8210BD04691A681C6003618B +:101C1000C38A013BC3824A60EFE700002DE9F84F19 +:101C20001D46CB8A0F46C3F309010529814692461A +:101C30000B4630D00020AAB207F11A049EB2042E3F +:101C40001FFA80F80FD8904503F1010306D3FB8AF1 +:101C50000A4462F309030120FB821AE01AF80060CB +:101C60000130E654EAE79045F1D21C23A1F1050BBF +:101C7000BBFBF3F203FB12BB7C681FFA8BF6002C54 +:101C800045D14846FFF72AFF044638B978606FF01F +:101C90000200BDE8F88F4FF00008E6E70026066076 +:101CA00078604FF0000BADB2454510D90AEB080340 +:101CB000221D13F8011B08F101089155B1B21B292F +:101CC0001FFA88F82BD0454506F10106F1D8FB8AAA +:101CD000C3F30902154465F30903BCE71C4601324E +:101CE00092B22368002BF9D16B1F0B441C21B3FB6C +:101CF000F1F301339BB29A42D3D2BBF1000FD0D1A2 +:101D00004846FFF7EBFE20B9C4F800B0BFE7012258 +:101D1000E7E7C0F800B05E4620600446C1E74545ED +:101D2000D5D94846FFF7DAFE08B92060AFE7C0F81A +:101D300000B0002620600446B6E700002DE9F74F0A +:101D40001C465B69074688460092002B00F097808E +:101D5000238C2BB1E269002A00F09180072B33D845 +:101D600007F10C00FFF7BAFE054628B96FF002052F +:101D7000284603B0BDE8F08F14220021FFF70EFBC8 +:101D8000228CE16905F10800FFF7F6FA208C48F093 +:101D90000041013080B2FFF7E9FEFFF7CBFE0138CA +:101DA00080B22084013028746369228C1B782A4415 +:101DB00003F01F0363F03F0313723846696029463E +:101DC000FFF7F4FD0125D3E74FF000094FF0800A3B +:101DD0004E464D4600F10C0301930198FFF77EFE3D +:101DE00083460028C2D014220021FFF7D7FA002E24 +:101DF0003BD10222009BABF808300BF1080E1FFA12 +:101E000082FC0CF10100BCF1060F218C80B201D8DC +:101E10008E422CD3FFF7AAFEFFF78CFE8E4208BF3E +:101E20004FF0400A62690138127880B202F01F0256 +:101E300042EA49120BEB00014AEA020A013048F07B +:101E4000004281F808A08BF8100059463846CBF8BC +:101E50000420FFF7ABFD238C0135B3424FF0000A9D +:101E60002DB289F00109B8D182E70022C5E7E16906 +:101E7000895D01360EF80210B6B20132BFE76FF08D +:101E8000010575E7F8B5044615460E4630220021D7 +:101E90001F46FFF783FA069BB5F5001F6360079B9B +:101EA00028BF4FF6FF72A3624FF0000338BF6A09E4 +:101EB000A760E66197B204F110009A4206D80023A9 +:101EC0000360A782E3822383E360F8BD06600133E9 +:101ED00030462036F1E7000003781BB94BB2002BE7 +:101EE000C8BF01707047000000787047F8B50C4615 +:101EF000C969074611B9238C002B37D1257E1F2DC8 +:101F000034D8387828BB228C072A2CD8268A36F079 +:101F100003032BD14FF6FF70FFF7D4FD4FF6FF728E +:101F200020F001003602400446EA0565400C45EA0F +:101F30004025234629463846FFF700FF002807DDE5 +:101F4000626913780133DBB21F2B88BF0023137043 +:101F5000F8BD218A2D0645EA012505432046FFF7F5 +:101F600021FE0246E5E76FF00300F1E76FF00100A4 +:101F7000EEE7000070B504461D4616468AB02822DA +:101F800000216846FFF70AFABDF838306946ADF817 +:101F900010300F9B204605939DF84030CDE9026537 +:101FA0008DF81830119B0793BDF84830ADF82030FC +:101FB000FFF79CFF0AB070BD2DE9F041D3690546DB +:101FC0000C4616460BB9138C5BBB377E1F2F28D8E7 +:101FD00095F80080B8F1000F26D03046FFF7E2FDFB +:101FE0003378210241EAC33141EA0801338A41EAE8 +:101FF000076141EA034102463346284641F0800129 +:10200000FFF79CFE00280ADD3378012B07D17269A7 +:1020100013780133DBB21F2B88BF00231370BDE898 +:10202000F0816FF00100FAE76FF00300F7E70000BE +:10203000F0B504460D461E4617468BB028220021F7 +:102040006846FFF7ABF99DF84C3029465A1E5342BB +:1020500053418DF800309DF840306A46ADF810309D +:10206000119B204605939DF84830CDE902768DF806 +:102070001830149B0793BDF85430ADF82030FFF7AB +:102080009BFF0BB0F0BD0000406A00B10430704708 +:10209000436A1A68426202691A600361C38A013B9B +:1020A000C38270472DE9F041D0F8208014461D46C8 +:1020B00041460027174E09B9BDE8F081D1E9022356 +:1020C000A21A65EB0303964277EB03031ED2036A61 +:1020D0008B420DD1FFF790FD036A1B680362036911 +:1020E0000B60C38A0161016A013B8846C382E2E753 +:1020F000FFF782FD0B68C8F8003003690B60C38AE4 +:102100000161013BC382D8F80010D4E78846096812 +:10211000D1E700BF80841E002DE9F04F8BB00D4643 +:1021200014469B468046DDF85090002800F01A8146 +:10213000B9F1000F00F01681531E3F2B00F21281FF +:10214000012A03D1BBF1000F40F00C810023CDE93F +:102150000833B8F81430B5EBC30F4FEAC30703D305 +:1021600000200BB0BDE8F08F2B199F42D8F80C303F +:1021700036BF7F1B2746FFB21BB9D8F81030002BA3 +:102180007BD0272D4ED8C5F12806B7424FF000036B +:1021900034BF3E46F6B2009329463246D8F80800CE +:1021A00008ABFFF745FCA7EB060A35445FFA8AFA4D +:1021B0002821B8F8143003F10053053BDB000493E9 +:1021C000D8F80C300393039B13B1BAF1000F2CD154 +:1021D000D8F8100040B1BAF1000F05D05246009671 +:1021E00008AB691AFFF724FC38B2002FB8D0660795 +:1021F0000AD00AAB03EBD40111F8083C624202F0AA +:102200000702134101F8083C082C3DD9102C40F27C +:10221000B680202C40F2B880BBF1000F00F09D800A +:10222000082335E0BA460026C2E7049BE02B28BF0E +:10223000E02306930B44AB42059315D95A1B9245F4 +:1022400038BF5246039828BFD2B20096691A08AB2D +:1022500004300792FFF7ECFB079A1644AAEB020A38 +:102260001544F6B25FFA8AFA049B069A05999B1AFE +:102270000493039B1B680393A5E700933A46294602 +:10228000D8F8080008ABADE7BBF1000F13D001236D +:10229000B4EBC30F6CD0082C12D89DF82030621E0E +:1022A00023FA02F2D50706D54FF0FF3202FA04F402 +:1022B00023438DF820309DF8203089F8003050E716 +:1022C000102C12D8BDF82030621E23FA02F2D1077A +:1022D00006D54FF0FF3202FA04F42343ADF8203064 +:1022E000BDF82030A9F800303BE7202C0FD8089922 +:1022F000631E21FA03F3DA0705D54FF0FF3202FA25 +:1023000004F40C430894089BC9F8003029E7402CDA +:102310002BD0DDE90865611EC4F12102A4F121037F +:1023200026FA01F105FA02F225FA03F311431943E3 +:10233000CB0712D50122A4F12003C4F1200102FA37 +:1023400003F322FA01F1A240524243EA010363EB94 +:10235000430332432B43CDE90823DDE90823C9E9D0 +:102360000023FEE66FF00100FBE66FF00800F8E6E0 +:10237000082CA0D9102CB3D9202CEED8C3E7BBF180 +:10238000000FADD0022383E7BBF1000FBBD00423C5 +:102390007EE70000012A30B5144638BF012200252F +:1023A000402A28BF402285B0012CCDE9025517D81C +:1023B0001B788DF8083053070AD004AB03EBD20525 +:1023C00015F8083C544204F00704A34005F8083C03 +:1023D0000346009102A80021FFF72AFB05B030BD9B +:1023E000082CE5D9102C03D81B88ADF80830E2E79B +:1023F000202C02D81B680293DDE7D3E90045CDE924 +:102400000245D8E710B5CB681BB98B600B618B8296 +:1024100010BD04691A681C600361C38A013BC38252 +:10242000CA60F0E703064CBFC0F3C030022070471B +:1024300008B50246FFF7F6FF022806D15306C2F39D +:102440000F2001D100F0030008BDC2F30740FBE7F5 +:102450002DE9F04F93B0CDE903230A6804461046F6 +:10246000FFF7E0FF02280CBF0026C2F30626002A71 +:102470000D46824680F2F98112F0C04940F0F581A4 +:10248000097B002900F0F181022803D02378B342B0 +:1024900040F0EE81C2F304631046069302F07F031E +:1024A0000593FFF7C5FF059B00224FEA83480023F1 +:1024B00048EA0A48294448EA4668CE78CDE9082324 +:1024C000F309834648EA0008029367D0059B024659 +:1024D000009320465346676808A9B847002800F0D3 +:1024E000CA81276A4FB9414604F10C00FFF704FB8B +:1024F000074690B96FF0020054E03B6998450DD053 +:102500003F68002FF9D1414604F10C00FFF7F4FABF +:1025100007460028EED0236A3B60276297F817C071 +:1025200006F01F08CCF3840CACEB08001FFA80FE09 +:102530000028B8BF0EF12000A8EB0C031FFA83FEA1 +:10254000B8BF00B2002B0793BEBF0EF120031BB231 +:102550000793D7E9022152EA010338D04FF0000C6B +:10256000039BDFF8F8E19A1A049B63EB010196459F +:102570007CEB01032BD36B7B97F81AE0734519D1E1 +:10258000029B002B78D0012821DC7868F8B9DFF8AD +:10259000D0C1944570EB010316D337E0276A27B901 +:1025A0006FF00C0013B0BDE8F08F3B699845B5D0D3 +:1025B0003F68F4E76A4890427CEB010301D30020B6 +:1025C000F0E7029B002BFAD0079B0F2B17DCFA7D5C +:1025D000B30002F0030203F07C031343FB7539469A +:1025E0002046FFF709FB6B7BBB76029B3BB9FB7D6B +:1025F000C3F38402013262F38603FB75D0E76A7B82 +:10260000BB7E9A42DBD1029B002B35D0B309022B53 +:1026100032D0039B1422BB60049B0021FB600DA8F9 +:10262000FEF7BCFE039B20460A93049BADF83EB028 +:102630000B932B1D0C932B7B8DF840A0013BDBB241 +:10264000ADF83C30069B8DF841808DF84230059BFB +:102650000AA98DF8433094F82C3083F001038DF8EB +:102660004430A3689847FB7DC3F38403013303F030 +:102670001F039B02FB82A2E7FB7DC6F34012B2EB75 +:10268000D31F40F0FB80C3F38403434540F0F9803F +:10269000029A2B7BB609002A4DD0F20762D4032B95 +:1026A00040F2F280039BAE1DBB60049B3246FB6090 +:1026B0002B7B3946033BDBB204F10C00FFF7AEFA8B +:1026C00000280CDA39462046FFF796FAFB7DC3F363 +:1026D0008403013303F01F039B02FB820AE7AB88EC +:1026E000DDE908843B834FF6FF73C9F12000A9F1AF +:1026F000200228FA09F104FA00F0014324FA02F258 +:1027000011431846C9B2FFF7CBF909F10809B9F12D +:10271000400F0346E9D13146B8822A7B033AD2B250 +:10272000FFF7D0F9FB7DB882DA43C2F3C01262F33F +:10273000C713FB7543E7AEB92E1D013B3246394640 +:10274000DBB204F10C00FFF769FA0028BADB2A7B40 +:102750003146013AB88AD2B2E2E700BF80841E0057 +:1027600040420F00F98A013BC1F309010429DAB2A2 +:102770005DD80023281D07F11B069A4208D910F8DE +:1027800001CB013306F801C001310529DBB2F4D1D8 +:10279000934228BF0023039938BF04330A91049958 +:1027A00038BFDBB20B9107F11B010C91796838BF80 +:1027B0005B190D910E93FB8AADF83EB0C3F309038C +:1027C0001A44069BADF83C208DF84230059B8DF8ED +:1027D00040A08DF8433094F82C308DF8418083F080 +:1027E00001038DF8443000237B602A7BB88A013ACC +:1027F000291DFFF767F93B8BB882834203D120463E +:10280000A3680AA9984720460AA9FFF7FBFDFB7DAC +:10281000BA8AC3F38403013303F01F039B02FB82D4 +:102820003B8B9A420CBF00206FF01000BAE67B6829 +:10283000002BADD0052001E033461C301E68002E71 +:10284000FAD1091A081D2E1D184401EB090CBCF120 +:102850001B0F5FFA89F39BD89A4299D916F8013B6E +:1028600009F1010900F8013BEFE76FF0090099E673 +:102870006FF00A0096E66FF00B0093E66FF00D0024 +:1028800090E66FF00E008DE66FF00F008AE600BF55 +:10289000F0B53F4D3F4FEB6943F00073EB61EB69DF +:1028A0003D4B9B6AD3F800623E4046F00106C3F8F8 +:1028B0000062D3F800423C4044EA002444F00104A2 +:1028C000C3F80042002955D000200646C3F81C0278 +:1028D000C3F80402C3F80C02C3F8140203EBC004EB +:1028E00001300E28C4F84062C4F84462F6D10027D3 +:1028F0004FF0010C9678148816F0010F18BFD3F82A +:1029000004E20CFA04F01CBF40EA0E0EC3F804E225 +:1029100016F0020F18BFD3F80CE203EBC4041CBF7F +:1029200040EA0E0EC3F80CE2760748BFD3F81462F3 +:1029300007F1010744BF0643C3F814625668B94261 +:10294000C4F84062966802F10C02C4F84462D3F8FD +:102950001C4240EA0400C3F81C02CBD1D3F8002289 +:1029600022F00102C3F80022EB6923F00073EB614F +:10297000EB69F0BD0122C3F84012C3F84412C3F85A +:102980000412C3F81412C3F80C22C3F81C22E5E7A2 +:10299000001002400000FFFFA8230020184A08B5DD +:1029A000916A8B688B6013F0010104D013F00C0F57 +:1029B00018BF4FF48031D80506D513F4406F14BF0B +:1029C00041F4003141F00201D80306D513F4402F41 +:1029D00014BF41F4802141F00401D3690BB10848D0 +:1029E0009847302383F311880021064800F022FB2A +:1029F000002383F31188BDE8084000F0ABBD00BFA1 +:102A0000A8230020B023002038B5124CA36ADD684B +:102A1000AA0712D05A6922F002025A61A36913B1BF +:102A2000012120469847302383F3118800210A486A +:102A300000F000FB002383F31188EB0606D510217C +:102A4000A36AD960236A0BB102489847BDE83840B1 +:102A500000F080BDA8230020B823002038B5124C18 +:102A6000A36A1D69AA0712D05A6922F010025A619E +:102A7000A36913B1022120469847302383F31188BC +:102A800000210A4800F0D6FA002383F31188EB06F0 +:102A900006D51021A36A1961236A0BB10248984731 +:102AA000BDE8384000F056BDA8230020B823002020 +:102AB00038B50F4CA36A5D682A075D600AD5042209 +:102AC00022701A6822F002021A60636A13B10021B0 +:102AD000204698476B0706D5A36A9969236A13B104 +:102AE000034809049847BDE8384000F033BD00BFF3 +:102AF000A823002010B50E4C204600F02FF90D4BF6 +:102B00000B211320A36200F009F90B21142000F01F +:102B100005F90B21152000F001F90B21162000F01A +:102B2000FDF8BDE8104000220E201146FFF7B0BEB0 +:102B3000A8230020006400400F4B10B598420446C3 +:102B400005D10E4BDA6942F00072DA61DB690122CD +:102B5000A36A1A60A36A5A68D20707D562685168E7 +:102B60001268D9611A60064A5A6110BD0121082015 +:102B700000F0B0F9EEE700BFA823002000100240EB +:102B80005B87010003291AD8DFE801F0020A0F145D +:102B9000836A9B6813F0E05F14BF01200020704738 +:102BA000836A9868C0F380607047836A9868C0F34E +:102BB000C0607047836A9868C0F300707047002057 +:102BC0007047000010B5032927D8DFE801F002277D +:102BD0002B2F836A9968C1F30161183103EB01134C +:102BE0001078840648BF5468C0F3001158BF948819 +:102BF0004FEA410148BF41EAC40100F00F005860AC +:102C000048BF41F00401906858BF41EA4451D2687E +:102C100041F001019860DA60196010BD836A03F524 +:102C2000C073DDE7836A03F5C873D9E7836A03F5E8 +:102C3000D073D5E701290AD002290FD081B9836A60 +:102C4000DA68920701D1186903E001207047836AAE +:102C5000D86810F0030018BF01207047836AF2E7BC +:102C60000020704710B539B9836AD96889071BD12C +:102C70001B699C0704D110BD012915D00229FAD186 +:102C8000816AD1F8C031D1F8C441D1F8C8011061CE +:102C9000D1F8CC015061202008610869800717D164 +:102CA000486940F0100012E0816AD1F8B031D1F8E3 +:102CB000B441D1F8B8011061D1F8BC0150612020B5 +:102CC000C860C868800703D1486940F002004861C5 +:102CD000C3F34000C3F38001000140EA41111079C1 +:102CE00020F030000143117189064BBF91681189B2 +:102CF000DB085B0D4CBF63F31C0163F30A0113791E +:102D000048BF916064F3030313714FEA14234FEA41 +:102D1000144458BF118113705480ACE7012209019B +:102D200000F1604303F56143C9B283F8001300F07A +:102D30001F039A4043099B0003F1604303F561437D +:102D4000C3F880211A607047090100F16040C9B2E0 +:102D500000F56D4001767047FFF7CCBE012303708C +:102D6000002300F10802C0E9022200F11002C0E9CC +:102D70000422C0E90633C0E908334360704700000D +:102D800010B53023044683F3118802234160037099 +:102D9000FFF7D2FE04230020237080F3118810BDBA +:102DA0002DE9F0411F4604460D461646302383F3B5 +:102DB000118800F108082378052B0DD029462046FC +:102DC000FFF7E0FE40B1204632462946FFF7FAFE03 +:102DD000002080F3118808E03946404600F01AF9D7 +:102DE0000028E8D0002383F31188BDE8F0810000BB +:102DF0002DE9F0411F4604460D461646302383F365 +:102E0000118800F110082378052B0DD029462046A3 +:102E1000FFF710FF40B1204632462946FFF722FF58 +:102E2000002080F3118808E03946404600F0F2F8AF +:102E30000028E8D0002383F31188BDE8F08100006A +:102E400000238268037503691B6899689142FBD26D +:102E50005A680360426010605860704700238268BF +:102E6000037503691B6899689142FBD85A6803602F +:102E7000426010605860704708B50846302383F3FD +:102E800011880B7D032B05D0042B0DD02BB983F3B8 +:102E9000118808BD00228B691A604FF0FF338361EF +:102EA000FFF7CEFF0023F2E7D1E9003213605A604A +:102EB000F3E70000FFF7C4BF054BD9680875186831 +:102EC000026853601A6001220275D860FDF79ABB50 +:102ED000D823002030B50C4B0446DD684B1C87B06E +:102EE0000FD02B466846094A00F0CAF82046FFF783 +:102EF000E3FF009B13B1684600F0CAF8A86907B069 +:102F000030BDFFF7D9FFF9E7D8230020792E00085C +:102F1000044B1A68DB6890689B68984294BF002055 +:102F200001207047D8230020084B10B51C68D868D2 +:102F3000226853601A6001222275DC60FFF78EFF61 +:102F400001462046BDE81040FDF75CBBD8230020B9 +:102F500038B501230025064C0649074823706560F3 +:102F600000F03EFB0223237085F3118838BD00BFBB +:102F700030250020BC3A0008D823002000F09AB881 +:102F80008B60022308618B82084670478368A3F137 +:102F9000440243F8142C026943F8442C426943F874 +:102FA000402C094A43F8242CC268A3F1200043F8BE +:102FB000182C022203F80C2C002203F80B2C034AD5 +:102FC00043F8102C704700BF15060008D8230020D6 +:102FD00008B5FFF7DBFFBDE80840FFF76BBF000057 +:102FE000024BDB6898610F20FFF766BFD8230020F3 +:102FF000302383F31188FFF7F3BF000008B50146C3 +:10300000302383F311880820FFF764FF002383F344 +:10301000118808BD064BDB6839B1426818605A60F8 +:10302000136043600420FFF755BF4FF0FF30704737 +:10303000D823002038B504460D462068844200D1CC +:1030400038BD036823605C608561FFF733FFF4E7F8 +:1030500010B50A4C23699A6891420CD85A6881606D +:103060000360426010609A685860511A99604FF08E +:10307000FF33A36110BD1B68891AECE7D823002039 +:10308000C0E90323002310B410BC4361FFF7E0BF85 +:10309000036881689A680A449A60426813605A60BB +:1030A00000234FF0FF320360014B9A61704700BF6D +:1030B000D823002070B5124D2A46EB690133EB612D +:1030C00052F8103F934206D030269A68013A9A602F +:1030D0002C69A36803B170BDD4E900210A60516076 +:1030E000236083F311882046D4E90331984786F39F +:1030F000118861690029EBD02046FFF7A9FFE7E7B7 +:10310000D8230020054A30B5D369D2E908451B1BF6 +:10311000181945F10001C2E9080130BDD82300208B +:1031200000207047FEE70000704700004FF0FF30BE +:1031300070470000BFF34F8F024AD368DB07FCD40F +:10314000704700BF0020024008B5074B1B7853B9F9 +:10315000FFF7F0FF054B1A69120641BF044A5A6097 +:1031600002F188325A6008BD482500200020024044 +:103170002301674508B5054B1B7833B9FFF7DAFF24 +:10318000034A136943F08003136108BD48250020FA +:10319000002002407F289ABF00F500308002002006 +:1031A000704700004FF48060704700008020704737 +:1031B0007F2808B50BD8FFF7EDFF00F580630268A4 +:1031C000013204D104308342F9D1012008BD00202E +:1031D000FCE700007F2810B504461CD8FFF7AAFFC3 +:1031E000FFF7B2FFF3220D4B4FF48061DA60022249 +:1031F0001A61FFF7CFFF58611A6942F040021A6165 +:10320000FFF798FF00F02EF9FFF7B4FF2046BDE866 +:103210001040FFF7CDBF002010BD00BF00200240CE +:103220002DE9F843054612F00100144606D040F29D +:10323000033200201E4B1A60BDE8F8831D4BAA180C +:103240009A4204D94FF44272194B1A60F4E7FFF71F +:103250007BFF4FF00109FFF76DFFDFF85C806D1A0F +:10326000012C0F4605EB010603D8FFF783FF012071 +:10327000E2E73B88C8F8109033800020FFF75AFF40 +:10328000C8F81000338831F8022B9BB29A420CD058 +:1032900040F21F32064B1A60084B1E60084B1C6040 +:1032A000084B1F60FFF766FFC6E7023CD8E700BF88 +:1032B000442500200000020800200240382500209C +:1032C000402500203C250020084908B50B7828B18E +:1032D0001BB9FFF739FF01230B7008BD002BFCD091 +:1032E000BDE808400870FFF745BF00BF4825002033 +:1032F00038B5EFF31185BDBBEFF30584C4F30804C3 +:103300003023C4B183F31188FFF7FCFE44014B0165 +:10331000241A43EAD06363EB0103A2009B00121856 +:1033200043EA947341EB0301C900D00041EA5271B2 +:1033300085F3118838BD83F31188FFF7E3FE45015B +:103340004B012D1A43EAD06363EB0103AA009B00F3 +:10335000121843EA957341EB0301C900D00041EA1A +:10336000527184F3118838BDFFF7CCFE44014B0144 +:10337000241A43EAD06363EB0103A2009B001218F6 +:1033800043EA947341EB0301C900D00041EA527152 +:1033900038BD00BF38B5FFF7ABFF00230F4A104C14 +:1033A000C00840EA4170A0FB025EC908A0FB040C03 +:1033B000A1FB0440A1FB02121CEB050C5B411CEBC2 +:1033C000040C43EB000011EB0E0142F10002411826 +:1033D00042F10000090941EA007038BDA59BC420F4 +:1033E000CFF753E310B5094C013AD2B2FF2A00D10E +:1033F00010BD500854F82030013054F820009BB222 +:1034000043EA004341F8043BEEE700BF046C004090 +:1034100010B50748013AD2B2FF2A00D110BD0C887E +:10342000530840F823404C88013340F82340F1E72B +:10343000046C004007B50122002001A9FFF7D2FF6C +:10344000019803B05DF804FB13B50446FFF7F2FFE3 +:10345000A04205D00122002001A90194FFF7D8FF66 +:1034600002B010BD7047000045F25552064B1A607D +:1034700002225A6040F6FF729A604CF6CC421A6003 +:103480000122024B1A707047003000405025002086 +:10349000034B1B781BB14AF6AA22024B1A607047F5 +:1034A0005025002000300040044B1A682AB902F170 +:1034B000804202F50432526A1A6070474C2500209F +:1034C0004FF08072014B5A62704700BF00100240FB +:1034D00008B5FFF7E9FF024B1868C0F3407008BD5C +:1034E0004C25002008B5FFF7DFFF024B1868C0F33A +:1034F000007008BD4C250020EFF30983203383F3CF +:103500000988002383F3118870470000302080F37E +:10351000118862B60C4B0D4AD96821F4E0610904A8 +:10352000090C0A43DA60D3F8FC20094942F08072A2 +:10353000C3F8FC200A6842F001020A602022DA7710 +:1035400083F82200704700BF00ED00E00003FA0599 +:10355000001000E0302310B583F311880B4B5B683B +:1035600013F400630FD0EFF309844FF08073203C15 +:10357000E36184F30988FFF7CBFC10B1044BA3612E +:1035800010BD044BFBE783F31188F9E700ED00E081 +:10359000270600082A06000870470000FEE7000022 +:1035A0000A4B0B480B4A90420BD30B4BC11EDA1C43 +:1035B000121A22F003028B4238BF00220021FDF7CD +:1035C000EDBE53F8041B40F8041BECE7343B000845 +:1035D000D4250020D4250020D4250020FEE70000BB +:1035E00070B5002504461A4B86B0586085620163A9 +:1035F0000E46FFF78BFF04F11003C4E904334FF0CC +:10360000FF33A361134BE561D9692B460A46204677 +:10361000C4E9082304F134018023C4E900440E4ABC +:10362000A560E5622565FFF7ABFC01230B4AE0606E +:1036300003750092726868460192B268CDE9022370 +:10364000074BCDE90435FFF7C3FC06B070BD00BFE2 +:1036500030250020D8230020C83A0008CD3A0008C1 +:10366000DD35000800F030B808B500F063F9FFF769 +:103670006FFCBDE80840FFF717BF0000704700006F +:103680004FF0FF310E4B1A6919611A6900221A6155 +:103690001869D868D960D968DA60DA68DA6942F0FE +:1036A0008052DA61DA69DA6942F00062DA61054A69 +:1036B000DB69136843F48073136000F01BB900BF2B +:1036C0000010024000700040194B1A6842F00102DD +:1036D0001A601A689007FCD51A6802F0F9021A609D +:1036E00000225A605A6812F00C0FFBD11A6842F49B +:1036F00080321A601A689103FCD55A6842F4E812C5 +:103700005A601A6842F080721A601A689201FCD5F9 +:103710001221084A5A60084A11605A6842F00202AF +:103720005A605A6802F00C02082AFAD1704700BFAA +:103730000010024000641D0000200240084A08B545 +:10374000516913680B4003F00103536123B1054A2B +:1037500013680BB150689847BDE80840FFF7FABE00 +:103760000004014054250020084A08B55169136837 +:103770000B4003F00203536123B1054A93680BB178 +:10378000D0689847BDE80840FFF7E4BE0004014058 +:1037900054250020084A08B5516913680B4003F00E +:1037A0000403536123B1054A13690BB1506998476B +:1037B000BDE80840FFF7CEBE0004014054250020BC +:1037C000084A08B5516913680B4003F008035361B8 +:1037D00023B1054A93690BB1D0699847BDE8084009 +:1037E000FFF7B8BE0004014054250020084A08B580 +:1037F000516913680B4003F01003536123B1054A6C +:10380000136A0BB1506A9847BDE80840FFF7A2BEA3 +:103810000004014054250020174B10B55A691C685C +:10382000144004F478725A61A30604D5134A936ACB +:103830000BB1D06A9847600604D5104A136B0BB1E0 +:10384000506B9847210604D50C4A936B0BB1D06B93 +:103850009847E20504D5094A136C0BB1506C9847A0 +:10386000A30504D5054A936C0BB1D06C9847BDE80D +:103870001040FFF76FBE00BF000401405425002038 +:103880001A4B10B55A691C68144004F47C425A6102 +:10389000620504D5164A136D0BB1506D9847230588 +:1038A00004D5134A936D0BB1D06D9847E00404D54D +:1038B0000F4A136E0BB1506E9847A10404D50C4A01 +:1038C000936E0BB1D06E9847620404D5084A136F0B +:1038D0000BB1506F9847230404D5054A936F0BB181 +:1038E000D06F9847BDE81040FFF734BE0004014098 +:1038F00054250020062108B50846FFF70FFA0621D7 +:103900000720FFF70BFA06210820FFF707FA062128 +:103910000920FFF703FA06210A20FFF7FFF9062125 +:103920001720FFF7FBF9BDE8084006212820FFF724 +:10393000F5B9000008B5FFF7A3FE054800F00CF844 +:10394000FFF70AFAFFF79AFEBDE8084000F002B858 +:10395000D43A000800F042B8002319461C4A01334B +:10396000102BC2E9001102F10802F8D1194B9A6933 +:1039700042F07D029A619B690268174BDA608268A7 +:103980005A6042681A60C26803F58063DA6042696F +:103990005A6002691A608269C3F80C24026AC3F88B +:1039A0000424C269C3F80024426AC3F80C28C26A1E +:1039B000C3F80428826AC3F80028026BC3F80C2CF1 +:1039C000826BC3F8042C426BC3F8002C704700BF15 +:1039D0005425002000100240000801404FF0E02371 +:1039E000044A08215A6100229A6107220B201A61B9 +:1039F000FFF7AAB93F19010008B5302383F31188F6 +:103A0000FFF7BCFA002383F3118808BD08B5FFF760 +:103A1000F3FFBDE80840FFF79DBD000010B5013978 +:103A20000244904201D1002005E0037811F8014FD3 +:103A3000A34201D0181B10BD0130F2E72DE9F0417F +:103A40009BB10446C91A1778014403F1FF3C8C422C +:103A5000204601D9002008E005780134BD42F6D1A6 +:103A60000CEB0405D618A54201D1BDE8F08115F88C +:103A7000018D16F801EDF045F5D0E8E7034611F8A1 +:103A8000012B03F8012B002AF9D170476F72672EC2 +:103A90006172647570696C6F742E663130332D41BC +:103AA0004453420040A2E4F1646891060041A3E55A +:103AB000F26569920700000063300000B83A000820 +:103AC00030240020302500206D61696E0069646C2F +:103AD0006500000000180000444441444454494437 +:103AE00001000000424444444444444400000000B7 +:103AF0004444444444444444000000004444444496 +:103B00004444444400000000444444444444444485 +:103B1000E803000000000000009C0100000000001D +:103B2000640000000000000040420F00FE2A010077 +:043B3000D2040000BB :00000001FF diff --git a/Tools/bootloaders/f103-Airspeed_bl.bin b/Tools/bootloaders/f103-Airspeed_bl.bin index 9e902bbc231556..0e9f9717928a7b 100755 Binary files a/Tools/bootloaders/f103-Airspeed_bl.bin and b/Tools/bootloaders/f103-Airspeed_bl.bin differ diff --git a/Tools/bootloaders/f103-Airspeed_bl.elf b/Tools/bootloaders/f103-Airspeed_bl.elf index 2756e4071d7194..a6698a04181eca 100755 Binary files a/Tools/bootloaders/f103-Airspeed_bl.elf and b/Tools/bootloaders/f103-Airspeed_bl.elf differ diff --git a/Tools/bootloaders/f103-Airspeed_bl.hex b/Tools/bootloaders/f103-Airspeed_bl.hex index 11db8402437a6e..f178c60d7e2453 100644 --- a/Tools/bootloaders/f103-Airspeed_bl.hex +++ b/Tools/bootloaders/f103-Airspeed_bl.hex @@ -1,26 +1,26 @@ :020000040800F2 -:10000000000900202D080008B11C0008811C000810 -:100010009D1C0008811C0008951C00082F08000882 -:100020002F0800082F0800082F080008E5370008EF -:100030002F0800082F0800082F080008F93C0008C6 -:100040002F0800082F0800082F0800082F080008B4 -:100050002F0800082F080008293A0008553A000820 -:10006000813A0008AD3A0008D93A00082F08000884 -:100070002F0800082F0800082F0800082F08000884 -:100080002F0800082F0800082F080008AD2C0008D2 -:10009000192D00086D2D0008C12D0008053B000832 -:1000A0002F0800082F0800082F0800082F08000854 -:1000B0002F0800082F0800082F0800082F08000844 -:1000C0002F0800082F0800082F0800082F08000834 -:1000D0002F0800082F0800082F0800082F08000824 -:1000E0006D3B00082F0800082F0800082F080008A3 -:1000F0002F0800082F0800082F0800082F08000804 -:100100002F0800082F0800082F0800082F080008F3 -:100110002F0800082F0800082F0800082F080008E3 -:100120002F0800082F0800082F0800082F080008D3 -:100130002F0800082F0800082F0800082F080008C3 -:100140002F0800082F0800082F0800082F080008B3 -:100150002F0800082F0800082F0800082F080008A3 +:100000000009002025050008A11900087119000841 +:100010008D190008711900088519000827050008C6 +:10002000270500082705000827050008F9340008FF +:100030002705000827050008270500080D3A0008D5 +:1000400027050008270500082705000827050008E0 +:1000500027050008270500083D3700086937000814 +:1000600095370008C1370008ED370008270500085C +:1000700027050008270500082705000827050008B0 +:100080002705000827050008270500089D29000806 +:10009000092A00085D2A0008B12A0008193800085A +:1000A0002705000827050008270500082705000880 +:1000B0002705000827050008270500082705000870 +:1000C0002705000827050008270500082705000860 +:1000D0002705000827050008270500082705000850 +:1000E00081380008270500082705000827050008B3 +:1000F0002705000827050008270500082705000830 +:10010000270500082705000827050008270500081F +:10011000270500082705000827050008270500080F +:1001200027050008270500082705000827050008FF +:1001300027050008270500082705000827050008EF +:1001400027050008270500082705000827050008DF +:1001500027050008270500082705000827050008CF :100160004FF0FF0C1CEAD0521EBF1CEAD15392EA9A :100170000C0F93EA0C0F6FD01A4480EA010C400276 :1001800018BF5FEA41211ED04FF0006343EA5010D0 @@ -81,917 +81,870 @@ :1004F0009E03B3EB126209D44FEA002343F000439A :1005000023FA02F070474FF00000704712F1610FBC :1005100001D1420202D14FF0FF3070474FF000008E -:10052000704700BF53B94AB9002908BF00281CBF53 -:100530004FF0FF314FF0FF3000F076B9ADF1080C0D -:100540006DE904CE00F006F8DDF804E0DDE90223F1 -:1005500004B070472DE9F047089E0D4604468846D2 -:10056000002B4DD18A42944668D9B2FA82F252B138 -:1005700001FA02F3C2F1200120FA01F10CFA02FCA7 -:1005800041EA030894404FEA1C41B8FBF1F71FFA17 -:100590008CFE01FB178807FB0EF0230C43EA08438F -:1005A00098420AD91CEB030307F1FF3580F01E8146 -:1005B000984240F21B81023F63441B1AB3FBF1F0E7 -:1005C00001FB103300FB0EFEA4B244EA0344A6452F -:1005D0000AD91CEB040400F1FF3380F00981A64521 -:1005E00040F20681644402380021A4EB0E0440EA84 -:1005F00007401EB10023D440C6E90043BDE8F087A0 -:100600008B4208D9002E00F0EE800021C6E90005DB -:100610000846BDE8F087B3FA83F100294AD1AB421E -:1006200002D3824200F2FC80841A65EB03030120AE -:100630009846002EE2D0C6E90048DFE702B9FFDEA7 -:10064000B2FA82F2002A40F09180A1EB0C00012165 -:100650004FEA1C471FFA8CFEB0FBF7F307FB1300B1 -:10066000250C45EA00450EFB03F0A84208D91CEB17 -:10067000050503F1FF3802D2A84200F2CE804346BE -:100680002D1AB5FBF7F007FB10550EFB00FEA4B2C8 -:1006900044EA0544A64508D91CEB040400F1FF35E3 -:1006A00002D2A64500F2B6802846A4EB0E0440EA2A -:1006B00003409EE7C1F120078B4022FA07FC4CEA79 -:1006C000030C25FA07FA4FEA1C49BAFBF9F820FA9D -:1006D00007F309FB18AA8D401FFA8CFE1D4300FA90 -:1006E00001F308FB0EF02C0C44EA0A44A04202FA83 -:1006F00001F20BD91CEB040408F1FF3A80F088806A -:10070000A04240F28580A8F102086444241AB4FB98 -:10071000F9F009FB104400FB0EFEADB245EA0444BB -:10072000A64508D91CEB040400F1FF356CD2A645A0 -:100730006AD90238644440EA0840A0FB0295A4EB61 -:100740000E04AC42C846AE4656D353D0002E69D0F4 -:10075000B3EB080264EB0E0422FA01F304FA07F784 -:100760001F43CC40C6E90074002147E70CFA02FCA5 -:10077000C2F1200125FA01F34FEA1C4720FA01F1EA -:1007800095400D43B3FBF7F107FB11331FFA8CFEC5 -:10079000280C40EA034001FB0EF3834204FA02F402 -:1007A00008D91CEB000001F1FF382FD283422DD96C -:1007B00002396044C01AB0FBF7F307FB1300ADB277 -:1007C00045EA004503FB0EF0A84208D91CEB0505DD -:1007D00003F1FF3816D2A84214D9023B6544281A07 -:1007E00043EA014138E73146304607E72F46E4E661 -:1007F0001846F9E64B45A9D2B9EB020865EB0C0E99 -:100800000138A3E74346EAE7284694E74146D1E7A3 -:10081000D0467BE76444023847E7023B65442FE754 -:10082000084606E73146E9E6704700BF02E000F0FF -:1008300000F8FEE772B6264880F30888254880F362 -:100840000988254825490860022080F31488BFF3F1 -:100850006F8F03F017F803F07BF84FF05530204905 -:100860001B4A91423CBF41F8040BFAE71D49194A63 -:1008700091423CBF41F8040BFAE71B491B4A1C4B51 -:100880009A423EBF51F8040B42F8040BF8E70020EF -:100890001849194A91423CBF41F8040BFAE702F0AB -:1008A000F5FF03F057F8154C154DAC4203DA54F838 -:1008B000041B8847F9E700F03FF8124C124DAC4298 -:1008C00003DA54F8041B8847F9E702F0DDBF0000A3 -:1008D00000090020001100200000000808ED00E0E1 -:1008E0000001002000090020083E0008001100203F -:1008F0002411002028110020E025002060010008BC -:100900006001000860010008600100082DE9F04F57 -:10091000C1F80CD0C3689D46BDE8F08F002383F377 -:1009200011882846A047002002F010FDFEE702F0E3 -:1009300083FC00DFFEE70000F8B500F03DFE02F0AA -:10094000EFFE074602F03AFF0546002840D12C4B47 -:100950009F423DD001339F423DD02A4B27F0FF02FA -:100960009A423BD1F8B200F003FC2E4642F21074DA -:1009700000F004FC08B10024264601F007F988B312 -:100980000024032000F044F8264635B11E4B9F4258 -:1009900003D0002402F00AFF2646002002F0CAFE1F -:1009A0001A4B9B6813F0400322D00EB100F046F8BA -:1009B00000F044FC00F002FE01F07CF90546CCB1E9 -:1009C00001F078F9401BA04214D900F037F8F3E7A2 -:1009D0002E460024CCE704460126C9E706464FF41C -:1009E0007A74C5E7002CD0D04FF47A740126CCE796 -:1009F0001C46DDE700F0D4FC012002F0ADFCDEE790 -:100A0000010007B0000008B0263A09B0000C014010 -:100A1000084B187003280CD8DFE800F0080502081E -:100A2000022000F027BE022000F01CBE0022024B74 -:100A30005A607047281100202C11002038B501F0B1 -:100A4000A5F830B103221F4B1A7000221E4B5A60CA -:100A500038BD1E4B1E4A19680131F9D00433934248 -:100A6000F9D11C4C194DD4F80424AA42F0D31A4BE6 -:100A70009B6803F1006303F5C8439A42E8D202F091 -:100A800069FE02F07BFE002000F0B2FD0220FFF7BD -:100A9000BFFF124BDA690022DA61D96999699A615C -:100AA0009B6972B64FF0E023C3F8085D3021D4F89B -:100AB0000034D4F8042481F311889D4683F3088818 -:100AC0001047C5E7281100202C1100200064000801 -:100AD000206400080060000800110020001002409F -:100AE00049F26900084A136899B21B0C00FB0133F4 -:100AF00044F250611360054B186882B2000C01FB90 -:100B00000200186080B27047201100201C110020E4 -:100B100010B504460021102200F0C8FD034B03CBA2 -:100B2000206061601868A06010BD00BFE8F7FF1F7B -:100B30002DE9F0410026ADF54E7D6CAC40F275120A -:100B400007460D460EA831460D9600F0AFFD4FF456 -:100B5000C4723146204600F0A9FD01F0ABF84FF415 -:100B60007A72B0FBF2F0264B0DF13408186093E86E -:100B70000700022384E807000DF5E9702382FFF7E0 -:100B8000C7FF4EF603031F4906A8238403F0ECF8C1 -:100B90001B230DF2E32284F832310DF1300C06AB49 -:100BA0001E4603CE664510605160334602F10802CE -:100BB000F6D13188B37820461180937041460122E6 -:100BC00000F0C0FD00230393AB7E80B2029305F1D9 -:100BD000190301930123CDE904800093384606A34D -:100BE000D3E90023E97E01F0ABFB0DF54E7DBDE8B6 -:100BF000F08100BFAFF300809E6AC421818A46EE77 -:100C000034110020783D00082DE9F041264D804642 -:100C10002B7A0C46DAB0FBB9204627A900F0A2FED9 -:100C20000746002836D19DF89D60C82E32D801466F -:100C30004FF4FA72284600F039FD32460DF19E015C -:100C400005F1090000F020FD9DF89C302E447772DC -:100C50002B720BB9E37E2B728122002106AD27A8EF -:100C600000F024FD0122294627A800F0B7FE00234A -:100C70000393A37E80B2029304F119030193282306 -:100C8000CDE904500093404605A3D3E90023E17E5B -:100C900001F056FB5AB0BDE8F08100BFAFF3008011 -:100CA00026417272DF25D7B77C210020F0B54FF4C2 -:100CB0008A750024234EF1B005FB006596F8D83004 -:100CC000D822214685F8DC3085F8E8403AA800F0C3 -:100CD000EDFC06F1090000F0E1FCD5F8E430C2B209 -:100CE00006AF8DF8F00006F109010DF1F100CDE934 -:100CF0003A3400F0C9FC394601223AA800F09AFEC5 -:100D000080B2CDE9047008230127CDE9023706F14E -:100D1000D80301933023317A00930B4807A3D3E91A -:100D2000002301F00DFBA04206DD00F0C3FFC5F873 -:100D3000E000384671B0F0BD2046FBE778F6339FFF -:100D400093CACD8D7C2100204C210020F0B51E4E91 -:100D50001E4F1F4D85B0304601F01EFB044660B3A8 -:100D600010220021684600F0A1FC4FF00003227B16 -:100D70006068A16862F303038DF8003002AB03C31F -:100D8000019B2268384662F31C0301939DF80030F2 -:100D90006A4643F020038DF800300023194602F024 -:100DA00087F9044620B9304601F0FAFA2C70D2E7F0 -:100DB0002B78072B03D801332B7005B0F0BD024808 -:100DC00001F0EEFAF9E700BF4C210020A823002033 -:100DD0007523002070B50D4614461E4601F00CFA2E -:100DE00050B9022E10D1012C0ED112A3D3E9002349 -:100DF0000120C5E9002307E0282C10D005D8012CDC -:100E000009D0052C0FD0002070BD302CFBD10BA3D6 -:100E1000D3E90023ECE70BA3D3E90023E8E70BA316 -:100E2000D3E90023E4E70BA3D3E90023E0E700BF05 -:100E3000AFF30080401DA12026812A0B78F6339F56 -:100E400093CACD8D9E6AC421818A46EE2641727274 -:100E5000DF25D7B7F017304A39059E5638B5054615 -:100E60000E4C0021013500F0E5FBA4F8F051B4F878 -:100E7000F00100F0C7FB78B1B4F8F00100F0D2FB4C -:100E8000014648B9B4F8F00100F0D4FBB4F8F031F1 -:100E90000133A4F8F031EAE738BD00BF7C2100201F -:100EA0002DE9F04F8DB000AF04460D4601F0A4F9D6 -:100EB000002846D12B7E022B1AD1EB8A012B17D1A9 -:100EC00000F0F8FE0646FFF70BFE4FF4C873B0FBC8 -:100ED000F3F202FB1303DFF878829BB206F5167675 -:100EE0003344C8F80030EB7E33B90022994B1A70B6 -:100EF0003437BD46BDE8F08F284607F11C0100F0ED -:100F0000EFFC0028F4D107F10C00FFF701FEBD7FD4 -:100F100007F10C012A4607F11F0002F0F5FE002838 -:100F2000E3D10F2D08D88B4B1D70D8F80030A3F5F6 -:100F30001673C8F80030DBE72046397F01F054F91A -:100F4000D6E7EB8A282B6BD010D8012B63D0052B6A -:100F5000CED1BFF34F8F8049804BCA6802F4E06264 -:100F60001343CB60BFF34F8F00BFFDE7302BBFD1E2 -:100F70007B4CEA7E237A9A42BAD194F8DC206B7ECD -:100F80009A42B5D1284604F1EA0100F07FFD0646F9 -:100F90000028ADD1012384F8E83000F08BFED4F8AE -:100FA000E030C01A192840F6B83338BF19209842EB -:100FB00028BF1846FFF73EFA6A49FFF7D1F8054601 -:100FC0002068FFF737FA6849FFF7CAF80146284654 -:100FD000FFF780F9FFF786FA20604FF48A7194F8E2 -:100FE000D9307B607A68636801FB02F5621992F878 -:100FF000E80050B1D2F8E400E946834215D000235E -:1010000082F8E830C2F8E030CD466368574A9B0A60 -:10101000013313816CE729462046FFF789FD67E716 -:1010200029462046FFF7F0FD62E7B2F8EC803B600E -:1010300008F1030A4FEA9A0A4FEA8A02D11DC90849 -:10104000A9EBC1039D46EB460021584600F02EFB5C -:1010500005F1EE0142465846214400F015FB3B687D -:1010600013B9012000F0C4FA94F8D20000F0CAFAD3 -:10107000054630B9207200F0E5FA284600F0B8FACB -:10108000C2E7D4F8D4303BB994F8D200B4F8F031C8 -:10109000834201D8FFF7E2FED4F8D43043449D42A6 -:1010A00008D294F8D200B4F8F0310130834201D86C -:1010B000FFF7D4FE594660685FFA8AF200F0FEFA44 -:1010C00008B9CD4689E7636894F8D2004344636069 -:1010D000D4F8D43008EB030AC4F8D4A000F092FA94 -:1010E000824509D394F8D230D4F8D4000133401BA0 -:1010F00084F8D230C4F8D400B8F1FF0F0FD800251F -:10110000257200F09FFA284600F072FA00F03EFDCA -:10111000164B188108B9FFF791FCCD46E8E64FF46D -:101120008A727B6894F8D90002FB0343D3F8E42069 -:1011300083F8E86002F58072C3F8E060C3F8E42049 -:10114000FFF7B4FDFFF702FE84F8D960B9E700BFEE -:10115000482100204521002000ED00E00400FA05B0 -:101160007C210020CDCCCC3D6666663F341100204A -:10117000014B1870704700BF4011002030B54FF090 -:101180000054254B226885B09A4207D002F020FB1C -:101190000446C0B90024204605B030BD0025627D5C -:1011A0001E4B1F481A70237DC92203721D49C0F8C7 -:1011B000E450093000F068FA2046E022294600F0A9 -:1011C00075FA0124E7E7184A184DD36943F0007314 -:1011D000D361AA6D164B9A42DCD12B6E013B7E2B5C -:1011E000D8D8144A01AB07CA83E807001846032180 -:1011F00000F09CFC6B6D83424FF00003CAD12A6D56 -:101200008A4203BFAB652A6E044B1C4601BF1A70AD -:10121000EA6D094B1A60BEE79AAD44C54011002043 -:101220007C210020160000200010024000660040D3 -:101230005041A0B058660040181100202DE9F0433D -:1012400085B000F0A3FC0223494C63710023029394 -:10125000484B2081D3F800C0BCF57A7F12D3464FAB -:10126000464BB7FBFCF59C458CBF0A231123B5FB0D -:10127000F3F603FB1652591EC8B2002A3ED00229CB -:101280000B46F4D89DF80B303D495A1E9DF80A30A4 -:101290003C48013B1B0443EA0253BDF80820013AD5 -:1012A00013434B6001F0F4FE00230193364B3749A2 -:1012B00000934FF48052364B364800F06BFF364BAC -:1012C000197811B1334800F08FFF00F0F3FC0546A8 -:1012D000FFF706FC4FF4C873B0FBF3F202FB1303F5 -:1012E00005F516709BB218442C4B186002F066FA94 -:1012F00008B10F23238105B0BDE8F083731EB3F559 -:10130000806FBFD24FF47A75C0EBC00E0EF10303AD -:101310004FEAE30909FB0555C3F3C703C11AC9B274 -:1013200009F101088844B5FBF8F5B5F5617F08D9E6 -:101330000EF1FF33C3F3C703C11A581E0F28C9B2F9 -:1013400014D84A1E072A8CBF00220122581800FB1D -:101350000660B7FBF0F7BC4594D1002A92D0ADF8F7 -:1013600008608DF80A308DF80B108BE71346EDE717 -:101370003411002018110020005125023F420F00B7 -:1013800010110020A8230020D50D000844110020D2 -:10139000A10E00084C21002040110020482100200F -:1013A0002DE9F04F80A7D7E900670FF20429D9E9AA -:1013B0000089734D93B00DF1300AFFF7C7FC182276 -:1013C0000021504600F072F9DFF8B8B16E4C0023EE -:1013D00052461946584601F093FE014650BB102272 -:1013E00008A800F063F9E36883F01003E36000F0FD -:1013F00063FC0DF1240C0B4612A9024611E903000F -:101400008CE803009DF83410C1F30300890649BF3E -:101410000E99BDF83810C1F31C0141F0004158BFCE -:10142000C1F30A018DF82C000891284608A901F0A3 -:1014300097F9CCE7284600F0DFFE0446002847D1A4 -:1014400000F038FCDFF844B1DBF8003098423FD3BD -:1014500000F030FC0790FFF743FB4FF4C873B0FB7C -:10146000F3F101FB1300079A83B202F516701844DA -:10147000CBF80000DFF818B18DF820409BF8001081 -:1014800011B901238DF8203050460791FFF740FB3A -:1014900007990DF12100C1F11004E4B2062C28BF18 -:1014A00006245144224600F0EFF808AB03931823BA -:1014B0000293384B013401930123E4B20093324686 -:1014C0003B462846049400F0DDFE00238BF80030F4 -:1014D00000F0F0FB304A314C1368C31AB3F57A7F41 -:1014E00030D3106000F0E8FB02460B46284600F0BF -:1014F00061FF284600F080FE20B3237ADFF8A0B019 -:10150000002B14BF032302238BF8053000F0D2FB1D -:101510004FF47A73B0FBF3F00122CBF80000514690 -:10152000584600F0B5F9182302931E4B80B2019380 -:1015300040F25513CDE903A0009342464B4628469E -:1015400000F0A0FE237ABBB100F0B4FB94F8E830C1 -:1015500073B9D4F8E03043B1C01A2368FA2B38BF0E -:10156000FA230533B0EB430F02D30020FFF79EFBB5 -:10157000237A002B7FF41FAF13B0BDE8F08F00BFBC -:101580004C210020A8230020000801404821002011 -:101590004521002044210020702300207C210020D0 -:1015A0003411002074230020401DA12026812A0B25 -:1015B000F1C6A7C1D068080F7047000070B501F0F0 -:1015C00095FF0024084E094D3080286833888342F7 -:1015D00008D901F087FF2B6804440133B4F5C84FE4 -:1015E0002B60F2D370BD00BFA4230020782300201D -:1015F00002F00AB800F10060920000F5C84001F066 -:10160000AFBF0000054B1A68054B1B889B1A83422D -:1016100002D9104401F066BF0020704778230020F3 -:10162000A4230020024B1B68184401F061BF00BFD7 -:1016300078230020024B1B68184401F06BBF00BFE9 -:1016400078230020064991F8243033B10023082282 -:10165000086A81F82430FFF7CDBF0120704700BF32 -:101660007C230020022802BF1022014B1A61704720 -:1016700000080140022802BF4FF48012014B1A619A -:10168000704700BF00080140002310B5934203D00B -:10169000CC5CC4540133F9E710BD00000346024698 -:1016A000D01A12F9011B0029FAD1704703460244EF -:1016B000934202D003F8011BFAE770472DE9F84383 -:1016C0001F4D144695F824200746884652BBDFF884 -:1016D00070909CB395F824302BB92022FF21484606 -:1016E0002F62FFF7E3FF95F824004146C0F108029E -:1016F000A24228BF224605EB8000D6B29200FFF737 -:10170000C3FF95F82430A41B1E44F6B2082E1744DC -:101710009044E4B285F82460DBD1FFF793FF002802 -:10172000D7D108E02B6A03EB82038342CFD0FFF7C7 -:1017300089FF0028CBD10020BDE8F8830120FBE71A -:101740007C2300202DE9F0470D46044600219046F9 -:10175000284640F27912FFF7A9FF234620220021F4 -:10176000284600F09FFF022220212846231D00F07A -:1017700099FF032222212846631D00F093FF0322D4 -:1017800025212846A31D00F08DFF10222821284680 -:1017900004F1080300F086FF08223821284604F1EE -:1017A000100300F07FFF08224021284604F11103B6 -:1017B00000F078FF08224821284604F1120300F0C7 -:1017C00071FF20225021284604F1140300F06AFF23 -:1017D00040227021284604F1180300F063FF08221C -:1017E000B021284604F1200300F05CFF0822B82154 -:1017F000284604F1210300F055FFC02604F122071A -:101800003B46314608222846083600F04BFFB6F525 -:10181000A07F07F10107F3D108223146284604F1E1 -:10182000320300F03FFF002704F1330A94F832300E -:101830004FEAC7099F4209F5A47615D3B8F1000F06 -:1018400008D131460722284604F5997300F02AFF93 -:1018500009F24F16274694F832213B1B93420CD3D2 -:10186000F01DC008BDE8F0870AEB070308223146E7 -:10187000284600F017FF0137D8E7314607F2331347 -:101880000822284600F00EFF08360137E3E7000083 -:1018900038B50C460021054621600346C4F8031004 -:1018A0002046202200F0FEFE20462B1D0222202191 -:1018B00000F0F8FE20466B1D0322222100F0F2FE0C -:1018C0002046AB1D0322252100F0ECFE204610220D -:1018D000282105F1080300F0E5FE072038BD0000CF -:1018E0000023F7B50E460546047F072200911946EE -:1018F00000F09AFD731C0093012200230721284663 -:1019000000F092FDC4B9B31C0093052223460821C0 -:10191000284600F089FD0D243746B278BB1B934260 -:1019200011D32B7FE01DC008AC8ABBB9A04294BF85 -:101930000020012003B0F0BDAB8A0824DB00083B87 -:10194000DB08B370E8E7FB1C214600930822002364 -:10195000284600F069FD08340137DEE7001B18BF98 -:101960000120E7E70023F7B50E46047F0822009127 -:101970001946054600F058FD731CC4B908220093AF -:1019800011462346284600F04FFD102401237278AB -:101990005F1C013B934211D32B7FE01DC008AC8A32 -:1019A000BBB9A04294BF0020012003B0F0BDAB8AB8 -:1019B0000824DB00083BDB087370E7E7F3192146D6 -:1019C000009308220023284600F02EFD08343B46F1 -:1019D000DDE7001B18BF0120E7E70000F8B50E4661 -:1019E00005461446002181223046FFF75FFE2B4654 -:1019F00008220021304600F055FE7CB9072208215C -:101A000030466B1C00F04EFE0F2401236A785F1CE9 -:101A1000013B934204D3E01DC008F8BD0824F4E75D -:101A20002146EB190822304600F03CFE08343B46C4 -:101A3000ECE70000F8B50E46054614460021CE221C -:101A40003046FFF733FE2B4628220021304600F0B7 -:101A500029FE7CB908222821304605F1080300F050 -:101A600021FE30242F462A7A7B1B934204D3E01DAB -:101A7000C008F8BD2824F5E7214607F1090308222C -:101A8000304600F00FFE08340137ECE7F7B5047F6D -:101A90000E460091012310220021054600F0C4FCEF -:101AA000C4B9B31C0093092223461021284600F034 -:101AB000BBFC192437467288BB1B9A4211D82B7F76 -:101AC000E01DC008AC8ABBB9A04294BF0020012031 -:101AD00003B0F0BDAB8A1024DB00103BDB08738041 -:101AE000E8E73B1D2146009308220023284600F02A -:101AF0009BFC08340137DEE7001B18BF0120E7E735 -:101B000030B5094D0A4491420DD011F8013B5840BF -:101B1000082340F30004013B2C4013F0FF0384EA48 -:101B20005000F6D1EFE730BD2083B8ED4FF0FF3322 -:101B3000F7B500EB81061946DFF848C0DFF848E04A -:101B4000B0421BD050F8042B01AF0192042217F8C9 -:101B5000014B81EA046108240D46DB184941013C30 -:101B6000002DBCBF83EA0C0381EA0E0114F0FF04D0 -:101B7000F2D1013A12F0FF02E9D1E1E7D843C943BB -:101B800003B0F0BD9336EAA9EBE1F042F7B56B463E -:101B9000354A106851686A4603C3082333493448FC -:101BA00002F0C2F8044690BB0A256B46314A106821 -:101BB00051686A4603C308232F492D4802F0B4F840 -:101BC0000446002847D00369B3F5CE3F43D8B0F8A8 -:101BD0006620B2F57A7F3ED1284A024402F15C01C8 -:101BE0008B4238D35C3B224900209E1AFFF788FFC6 -:101BF00007463246002004F16401FFF781FFA36825 -:101C00009F4228D1E368984208BF002523E003697A -:101C1000B3F5CE3F26D8428BB2F57A7F20D1174A52 -:101C2000024402F110018B4218D3103B10490020EE -:101C30009D1AFFF765FF06462A46002004F11801A9 -:101C4000FFF75EFFA3689E4202D1E368984201D08D -:101C50000D25AAE70025284603B0F0BD1025A4E70E -:101C60000C25A2E70B25A0E7943D0008DC9B0100B2 -:101C7000006400089D3D0008909B0100089CFFF750 -:101C8000EFF30983EFF30583014B9B6BFEE700BF86 -:101C900000ED00E008B5FFF7F3FF0000EFF3098364 -:101CA000EFF30583014B5B6BFEE700BF00ED00E047 -:101CB000FEE7000001F0E2BC01F0BABC2DE9F04102 -:101CC000456A15B94162BDE8F0814B68AC4623F026 -:101CD0006047C3F38A4616EA230638BF3E464FEAFA -:101CE000D37EC3F380782B465A68BEEBD27F22F0B6 -:101CF00060440AD0002A18DAA40CB44217D19D42DD -:101D00000FD10D60DEE71346EEE7A74207D102F0E0 -:101D10008044C2F3807242450BD054B1EFE708D241 -:101D2000EDE7CCF800100B60CDE7B44201D0B4422F -:101D3000E5D81A689C46002AE5D11960C3E700007F -:101D40002DE9F0474FF47F49089D01F007044FEA61 -:101D5000D508224405F0070500EBD100944201D1DB -:101D6000BDE8F08704F0070705F0070A57453E462F -:101D700038BF5646111BC6F108068E4228BF0E46D4 -:101D8000E108415C08EBD50E13F80EC0B94029FA02 -:101D900006F721FA0AF1FFB28CEA010147FA0AF7C5 -:101DA00039408CEA010C03F80EC034443544D5E7C1 -:101DB000082341F2210280EA012001B240000029FB -:101DC00080B203F1FF33B8BF504013F0FF03F4D1EA -:101DD0007047000038B50C468D18A54200D138BDBB -:101DE00014F8011BFFF7E4FFF7E700000346406823 -:101DF00048B1026899895A605A89013292B2914277 -:101E00005A8138BF9A81704770B504460D4688B034 -:101E1000202200216846FFF749FC20460495FFF781 -:101E2000E5FF024658B16B46054608AE1C4603CC9A -:101E3000B44228606960234605F10805F6D11046D2 -:101E400008B070BD082817D909280CD00A280CD072 -:101E50000B280CD00C280CD00D280CD00E2814BF49 -:101E60004020302070470C2070471020704714200D -:101E7000704718207047202070470000082817D9A5 -:101E80000C280CD910280CD914280CD918280CD9D6 -:101E900020280CD930288CBF0F200E207047092035 -:101EA00070470A2070470B2070470C2070470D20A8 -:101EB000704700002DE9F843078C0446072F1ED910 -:101EC000D0E9029800254FF6FF73C5F12006A5F171 -:101ED000200029FA05F108FA06F628FA00F0314345 -:101EE0000143C9B21846FFF763FF0835402D03468A -:101EF000EBD13A46E169BDE8F843FFF76BBF4FF617 -:101F0000FF70BDE8F883000010B54B6823B9CA8A9A -:101F100063F30902CA8210BD04691A681C60036178 -:101F2000C38A013BC3824A60EFE700002DE9F84F06 -:101F30001D46CB8A0F46C3F3090105298146924607 -:101F40000B4630D00020AAB207F11A049EB2042E2C -:101F50001FFA80F80FD8904503F1010306D3FB8ADE -:101F60000A4462F309030120FB821AE01AF80060B8 -:101F70000130E654EAE79045F1D21C23A1F1050BAC -:101F8000BBFBF3F203FB12BB7C681FFA8BF6002C41 -:101F900045D14846FFF72AFF044638B978606FF00C -:101FA0000200BDE8F88F4FF00008E6E70026066063 -:101FB00078604FF0000BADB2454510D90AEB08032D -:101FC000221D13F8011B08F101089155B1B21B291C -:101FD0001FFA88F82BD0454506F10106F1D8FB8A97 -:101FE000C3F30902154465F30903BCE71C4601323B -:101FF00092B22368002BF9D16B1F0B441C21B3FB59 -:10200000F1F301339BB29A42D3D2BBF1000FD0D18E -:102010004846FFF7EBFE20B9C4F800B0BFE7012245 -:10202000E7E7C0F800B05E4620600446C1E74545DA -:10203000D5D94846FFF7DAFE08B92060AFE7C0F807 -:1020400000B0002620600446B6E700002DE9F74FF7 -:102050001C465B69074688460092002B00F097807B -:10206000238C2BB1E269002A00F09180072B33D832 -:1020700007F10C00FFF7BAFE054628B96FF002051C -:10208000284603B0BDE8F08F14220021FFF70EFBB5 -:10209000228CE16905F10800FFF7F6FA208C48F080 -:1020A0000041013080B2FFF7E9FEFFF7CBFE0138B7 -:1020B00080B22084013028746369228C1B782A4402 -:1020C00003F01F0363F03F0313723846696029462B -:1020D000FFF7F4FD0125D3E74FF000094FF0800A28 -:1020E0004E464D4600F10C0301930198FFF77EFE2A -:1020F00083460028C2D014220021FFF7D7FA002E11 -:102100003BD10222009BABF808300BF1080E1FFAFE -:1021100082FC0CF10100BCF1060F218C80B201D8C9 -:102120008E422CD3FFF7AAFEFFF78CFE8E4208BF2B -:102130004FF0400A62690138127880B202F01F0243 -:1021400042EA49120BEB00014AEA020A013048F068 -:10215000004281F808A08BF8100059463846CBF8A9 -:102160000420FFF7ABFD238C0135B3424FF0000A8A -:102170002DB289F00109B8D182E70022C5E7E169F3 -:10218000895D01360EF80210B6B20132BFE76FF07A -:10219000010575E7F8B5044615460E4630220021C4 -:1021A0001F46FFF783FA069BB5F5001F6360079B88 -:1021B00028BF4FF6FF72A3624FF0000338BF6A09D1 -:1021C000A760E66197B204F110009A4206D8002396 -:1021D0000360A782E3822383E360F8BD06600133D6 -:1021E00030462036F1E7000003781BB94BB2002BD4 -:1021F000C8BF01707047000000787047F8B50C4602 -:10220000C969074611B9238C002B37D1257E1F2DB4 -:1022100034D8387828BB228C072A2CD8268A36F066 -:1022200003032BD14FF6FF70FFF7D4FD4FF6FF727B -:1022300020F001003602400446EA0565400C45EAFC -:102240004025234629463846FFF700FF002807DDD2 -:10225000626913780133DBB21F2B88BF0023137030 -:10226000F8BD218A2D0645EA012505432046FFF7E2 -:1022700021FE0246E5E76FF00300F1E76FF0010091 -:10228000EEE7000070B504461D4616468AB02822C7 -:1022900000216846FFF70AFABDF838306946ADF804 -:1022A00010300F9B204605939DF84030CDE9026524 -:1022B0008DF81830119B0793BDF84830ADF82030E9 -:1022C000FFF79CFF0AB070BD2DE9F041D3690546C8 -:1022D0000C4616460BB9138C5BBB377E1F2F28D8D4 -:1022E00095F80080B8F1000F26D03046FFF7E2FDE8 -:1022F0003378210241EAC33141EA0801338A41EAD5 -:10230000076141EA034102463346284641F0800115 -:10231000FFF79CFE00280ADD3378012B07D1726994 -:1023200013780133DBB21F2B88BF00231370BDE885 -:10233000F0816FF00100FAE76FF00300F7E70000AB -:10234000F0B504460D461E4617468BB028220021E4 -:102350006846FFF7ABF99DF84C3029465A1E5342A8 -:1023600053418DF800309DF840306A46ADF810308A -:10237000119B204605939DF84830CDE902768DF8F3 -:102380001830149B0793BDF85430ADF82030FFF798 -:102390009BFF0BB0F0BD0000406A00B104307047F5 -:1023A000436A1A68426202691A600361C38A013B88 -:1023B000C38270472DE9F041D0F8208014461D46B5 -:1023C00041460027174E09B9BDE8F081D1E9022343 -:1023D000A21A65EB0303964277EB03031ED2036A4E -:1023E0008B420DD1FFF790FD036A1B6803620369FE -:1023F0000B60C38A0161016A013B8846C382E2E740 -:10240000FFF782FD0B68C8F8003003690B60C38AD0 -:102410000161013BC382D8F80010D4E788460968FF -:10242000D1E700BF80841E002DE9F04F8BB00D4630 -:1024300014469B468046DDF85090002800F01A8133 -:10244000B9F1000F00F01681531E3F2B00F21281EC -:10245000012A03D1BBF1000F40F00C810023CDE92C -:102460000833B8F81430B5EBC30F4FEAC30703D3F2 -:1024700000200BB0BDE8F08F2B199F42D8F80C302C -:1024800036BF7F1B2746FFB21BB9D8F81030002B90 -:102490007BD0272D4ED8C5F12806B7424FF0000358 -:1024A00034BF3E46F6B2009329463246D8F80800BB -:1024B00008ABFFF745FCA7EB060A35445FFA8AFA3A -:1024C0002821B8F8143003F10053053BDB000493D6 -:1024D000D8F80C300393039B13B1BAF1000F2CD141 -:1024E000D8F8100040B1BAF1000F05D0524600965E -:1024F00008AB691AFFF724FC38B2002FB8D0660782 -:102500000AD00AAB03EBD40111F8083C624202F096 -:102510000702134101F8083C082C3DD9102C40F269 -:10252000B680202C40F2B880BBF1000F00F09D80F7 -:10253000082335E0BA460026C2E7049BE02B28BFFB -:10254000E02306930B44AB42059315D95A1B9245E1 -:1025500038BF5246039828BFD2B20096691A08AB1A -:1025600004300792FFF7ECFB079A1644AAEB020A25 -:102570001544F6B25FFA8AFA049B069A05999B1AEB -:102580000493039B1B680393A5E700933A462946EF -:10259000D8F8080008ABADE7BBF1000F13D001235A -:1025A000B4EBC30F6CD0082C12D89DF82030621EFB -:1025B00023FA02F2D50706D54FF0FF3202FA04F4EF -:1025C00023438DF820309DF8203089F8003050E703 -:1025D000102C12D8BDF82030621E23FA02F2D10767 -:1025E00006D54FF0FF3202FA04F42343ADF8203051 -:1025F000BDF82030A9F800303BE7202C0FD808990F -:10260000631E21FA03F3DA0705D54FF0FF3202FA11 -:1026100004F40C430894089BC9F8003029E7402CC7 -:102620002BD0DDE90865611EC4F12102A4F121036C -:1026300026FA01F105FA02F225FA03F311431943D0 -:10264000CB0712D50122A4F12003C4F1200102FA24 -:1026500003F322FA01F1A240524243EA010363EB81 -:10266000430332432B43CDE90823DDE90823C9E9BD -:102670000023FEE66FF00100FBE66FF00800F8E6CD -:10268000082CA0D9102CB3D9202CEED8C3E7BBF16D -:10269000000FADD0022383E7BBF1000FBBD00423B2 -:1026A0007EE70000012A30B5144638BF012200251C -:1026B000402A28BF402285B0012CCDE9025517D809 -:1026C0001B788DF8083053070AD004AB03EBD20512 -:1026D00015F8083C544204F00704A34005F8083CF0 -:1026E0000346009102A80021FFF72AFB05B030BD88 -:1026F000082CE5D9102C03D81B88ADF80830E2E788 -:10270000202C02D81B680293DDE7D3E90045CDE910 -:102710000245D8E710B5CB681BB98B600B618B8283 -:1027200010BD04691A681C600361C38A013BC3823F -:10273000CA60F0E703064CBFC0F3C0300220704708 -:1027400008B50246FFF7F6FF022806D15306C2F38A -:102750000F2001D100F0030008BDC2F30740FBE7E2 -:102760002DE9F04F93B0CDE903230A6804461046E3 -:10277000FFF7E0FF02280CBF0026C2F30626002A5E -:102780000D46824680F2F98112F0C04940F0F58191 -:10279000097B002900F0F181022803D02378B3429D -:1027A00040F0EE81C2F304631046069302F07F030B -:1027B0000593FFF7C5FF059B00224FEA83480023DE -:1027C00048EA0A48294448EA4668CE78CDE9082311 -:1027D000F309834648EA0008029367D0059B024646 -:1027E000009320465346676808A9B847002800F0C0 -:1027F000CA81276A4FB9414604F10C00FFF704FB78 -:10280000074690B96FF0020054E03B6998450DD03F -:102810003F68002FF9D1414604F10C00FFF7F4FAAC -:1028200007460028EED0236A3B60276297F817C05E -:1028300006F01F08CCF3840CACEB08001FFA80FEF6 -:102840000028B8BF0EF12000A8EB0C031FFA83FE8E -:10285000B8BF00B2002B0793BEBF0EF120031BB21E -:102860000793D7E9022152EA010338D04FF0000C58 -:10287000039BDFF8F8E19A1A049B63EB010196458C -:102880007CEB01032BD36B7B97F81AE0734519D1CE -:10289000029B002B78D0012821DC7868F8B9DFF89A -:1028A000D0C1944570EB010316D337E0276A27B9EE -:1028B0006FF00C0013B0BDE8F08F3B699845B5D0C0 -:1028C0003F68F4E76A4890427CEB010301D30020A3 -:1028D000F0E7029B002BFAD0079B0F2B17DCFA7D49 -:1028E000B30002F0030203F07C031343FB75394687 -:1028F0002046FFF709FB6B7BBB76029B3BB9FB7D58 -:10290000C3F38402013262F38603FB75D0E76A7B6E -:10291000BB7E9A42DBD1029B002B35D0B309022B40 -:1029200032D0039B1422BB60049B0021FB600DA8E6 -:10293000FEF7BCFE039B20460A93049BADF83EB015 -:102940000B932B1D0C932B7B8DF840A0013BDBB22E -:10295000ADF83C30069B8DF841808DF84230059BE8 -:102960000AA98DF8433094F82C3083F001038DF8D8 -:102970004430A3689847FB7DC3F38403013303F01D -:102980001F039B02FB82A2E7FB7DC6F34012B2EB62 -:10299000D31F40F0FB80C3F38403434540F0F9802C -:1029A000029A2B7BB609002A4DD0F20762D4032B82 -:1029B00040F2F280039BAE1DBB60049B3246FB607D -:1029C0002B7B3946033BDBB204F10C00FFF7AEFA78 -:1029D00000280CDA39462046FFF796FAFB7DC3F350 -:1029E0008403013303F01F039B02FB820AE7AB88D9 -:1029F000DDE908843B834FF6FF73C9F12000A9F19C -:102A0000200228FA09F104FA00F0014324FA02F244 -:102A100011431846C9B2FFF7CBF909F10809B9F11A -:102A2000400F0346E9D13146B8822A7B033AD2B23D -:102A3000FFF7D0F9FB7DB882DA43C2F3C01262F32C -:102A4000C713FB7543E7AEB92E1D013B324639462D -:102A5000DBB204F10C00FFF769FA0028BADB2A7B2D -:102A60003146013AB88AD2B2E2E700BF80841E0044 -:102A700040420F00F98A013BC1F309010429DAB28F -:102A80005DD80023281D07F11B069A4208D910F8CB -:102A900001CB013306F801C001310529DBB2F4D1C5 -:102AA000934228BF0023039938BF04330A91049945 -:102AB00038BFDBB20B9107F11B010C91796838BF6D -:102AC0005B190D910E93FB8AADF83EB0C3F3090379 -:102AD0001A44069BADF83C208DF84230059B8DF8DA -:102AE00040A08DF8433094F82C308DF8418083F06D -:102AF00001038DF8443000237B602A7BB88A013AB9 -:102B0000291DFFF767F93B8BB882834203D120462A -:102B1000A3680AA9984720460AA9FFF7FBFDFB7D99 -:102B2000BA8AC3F38403013303F01F039B02FB82C1 -:102B30003B8B9A420CBF00206FF01000BAE67B6816 -:102B4000002BADD0052001E033461C301E68002E5E -:102B5000FAD1091A081D2E1D184401EB090CBCF10D -:102B60001B0F5FFA89F39BD89A4299D916F8013B5B -:102B700009F1010900F8013BEFE76FF0090099E660 -:102B80006FF00A0096E66FF00B0093E66FF00D0011 -:102B900090E66FF00E008DE66FF00F008AE600BF42 -:102BA000F0B53F4D3F4FEB6943F00073EB61EB69CC -:102BB0003D4B9B6AD3F800623E4046F00106C3F8E5 -:102BC0000062D3F800423C4044EA002444F001048F -:102BD000C3F80042002955D000200646C3F81C0265 -:102BE000C3F80402C3F80C02C3F8140203EBC004D8 -:102BF00001300E28C4F84062C4F84462F6D10027C0 -:102C00004FF0010C9678148816F0010F18BFD3F816 -:102C100004E20CFA04F01CBF40EA0E0EC3F804E212 -:102C200016F0020F18BFD3F80CE203EBC4041CBF6C -:102C300040EA0E0EC3F80CE2760748BFD3F81462E0 -:102C400007F1010744BF0643C3F814625668B9424E -:102C5000C4F84062966802F10C02C4F84462D3F8EA -:102C60001C4240EA0400C3F81C02CBD1D3F8002276 -:102C700022F00102C3F80022EB6923F00073EB613C -:102C8000EB69F0BD0122C3F84012C3F84412C3F847 -:102C90000412C3F81412C3F80C22C3F81C22E5E78F -:102CA000001002400000FFFFA8230020184A08B5CA -:102CB000916A8B688B6013F0010104D013F00C0F44 -:102CC00018BF4FF48031D80506D513F4406F14BFF8 -:102CD00041F4003141F00201D80306D513F4402F2E -:102CE00014BF41F4802141F00401D3690BB10848BD -:102CF0009847302383F311880021064800F048FBF1 -:102D0000002383F31188BDE8084000F099BD00BF9F -:102D1000A8230020B023002038B5124CA36ADD6838 -:102D2000AA0712D05A6922F002025A61A36913B1AC -:102D3000012120469847302383F3118800210A4857 -:102D400000F026FB002383F31188EB0606D5102143 -:102D5000A36AD960236A0BB102489847BDE838409E -:102D600000F06EBDA8230020B823002038B5124C17 -:102D7000A36A1D69AA0712D05A6922F010025A618B -:102D8000A36913B1022120469847302383F31188A9 -:102D900000210A4800F0FCFA002383F31188EB06B7 -:102DA00006D51021A36A1961236A0BB1024898471E -:102DB000BDE8384000F044BDA8230020B82300201F -:102DC00038B50F4CA36A5D682A075D600AD50422F6 -:102DD00022701A6822F002021A60636A13B100219D -:102DE000204698476B0706D5A36A9969236A13B1F1 -:102DF000034809049847BDE8384000F021BD00BFF2 -:102E0000A823002010B50E4C204600F02FF90D4BE2 -:102E10000B211320A36200F009F90B21142000F00C -:102E200005F90B21152000F001F90B21162000F007 -:102E3000FDF8BDE8104000220E201146FFF7B0BE9D -:102E4000A8230020006400400F4B10B598420446B0 -:102E500005D10E4BDA6942F00072DA61DB690122BA -:102E6000A36A1A60A36A5A68D20707D562685168D4 -:102E70001268D9611A60064A5A6110BD0121082002 -:102E800000F0B0F9EEE700BFA823002000100240D8 -:102E90005B87010003291AD8DFE801F0020A0F144A -:102EA000836A9B6813F0E05F14BF01200020704725 -:102EB000836A9868C0F380607047836A9868C0F33B -:102EC000C0607047836A9868C0F300707047002044 -:102ED0007047000010B5032927D8DFE801F002276A -:102EE0002B2F836A9968C1F30161183103EB011339 -:102EF0001078840648BF5468C0F3001158BF948806 -:102F00004FEA410148BF41EAC40100F00F00586098 -:102F100048BF41F00401906858BF41EA4451D2686B -:102F200041F001019860DA60196010BD836A03F511 -:102F3000C073DDE7836A03F5C873D9E7836A03F5D5 -:102F4000D073D5E701290AD002290FD081B9836A4D -:102F5000DA68920701D1186903E001207047836A9B -:102F6000D86810F0030018BF01207047836AF2E7A9 -:102F70000020704710B539B9836AD96889071BD119 -:102F80001B699C0704D110BD012915D00229FAD173 -:102F9000816AD1F8C031D1F8C441D1F8C8011061BB -:102FA000D1F8CC015061202008610869800717D151 -:102FB000486940F0100012E0816AD1F8B031D1F8D0 -:102FC000B441D1F8B8011061D1F8BC0150612020A2 -:102FD000C860C868800703D1486940F002004861B2 -:102FE000C3F34000C3F38001000140EA41111079AE -:102FF00020F030000143117189064BBF916811899F -:10300000DB085B0D4CBF63F31C0163F30A0113790A -:1030100048BF916064F3030313714FEA14234FEA2E -:10302000144458BF118113705480ACE70122090188 -:1030300000F1604303F56143C9B283F8001300F067 -:103040001F039A4043099B0003F1604303F561436A -:10305000C3F880211A607047090100F16040C9B2CD -:1030600000F56D4001767047FFF7CCBE0123037079 -:10307000002300F10802C0E9022200F11002C0E9B9 -:103080000422C0E90633C0E90833436070470000FA -:1030900010B53023044683F3118802234160037086 -:1030A000FFF7D2FE04230020237080F3118810BDA7 -:1030B0002DE9F0411F4604460D461646302383F3A2 -:1030C000118800F108082378052B0DD029462046E9 -:1030D000FFF7E0FE40B1204632462946FFF7FAFEF0 -:1030E000002080F3118808E03946404600F040F99E -:1030F0000028E8D0002383F31188BDE8F0810000A8 -:103100002DE9F0411F4604460D461646302383F351 -:10311000118800F110082378052B0DD02946204690 -:10312000FFF710FF40B1204632462946FFF722FF45 -:10313000002080F3118808E03946404600F018F975 -:103140000028E8D0002383F31188BDE8F081000057 -:1031500000238268037503691B6899689142FBD25A -:103160005A680360426010605860704700238268AC -:10317000037503691B6899689142FBD85A6803601C -:10318000426010605860704708B50846302383F3EA -:1031900011880B7D032B05D0042B0DD02BB983F3A5 -:1031A000118808BD00228B691A604FF0FF338361DC -:1031B000FFF7CEFF0023F2E7D1E9003213605A6037 -:1031C000F3E70000FFF7C4BF054BD968087518681E -:1031D000026853601A6001220275D860FDF796BB41 -:1031E000D823002030B50C4B0446DD684B1C87B05B -:1031F0000FD02B466846094A00F0F0F82046FFF74A -:10320000E3FF009B13B1684600F0F0F8A86907B02F -:1032100030BDFFF7D9FFF9E7D82300208931000836 -:10322000044B1A68DB6890689B68984294BF002042 -:1032300001207047D8230020084B10B51C68D868BF -:10324000226853601A6001222275DC60FFF78EFF4E -:1032500001462046BDE81040FDF758BBD8230020AA -:10326000044B1A68DB6892689B689A4201D9FFF7A1 -:10327000E3BF7047D823002038B501230025064C52 -:10328000064907482370656000F020FB0223237085 -:1032900085F3118838BD00BF30250020AC3D000803 -:1032A000D823002000F0B4B8EFF3118020B9EFF379 -:1032B0000583302282F311887047000010B530B9C1 -:1032C000EFF30584C4F3080414B180F3118810BD32 -:1032D000FFF7C6FF84F31188F9E700008B60022333 -:1032E00008618B82084670478368A3F1440243F863 -:1032F000142C026943F8442C426943F8402C094AD3 -:1033000043F8242CC268A3F1200043F8182C0222B1 -:1033100003F80C2C002203F80B2C034A43F8102C62 -:10332000704700BF1D090008D823002008B5FFF72B -:10333000DBFFBDE80840FFF745BF0000024BDB683C -:1033400098610F20FFF740BFD8230020302383F37C -:103350001188FFF7F3BF000008B50146302383F35F -:1033600011880820FFF73EFF002383F3118808BD72 -:10337000064BDB6839B1426818605A6013604360DD -:103380000420FFF72FBF4FF0FF307047D8230020F5 -:1033900038B504460D462068844200D138BD036824 -:1033A00023605C608561FFF70DFFF4E710B50A4C00 -:1033B00023699A6891420CD85A6881600360426020 -:1033C00010609A685860511A99604FF0FF33A361FA -:1033D00010BD1B68891AECE7D8230020C0E903233D -:1033E000002310B410BC4361FFF7E0BF036881689D -:1033F0009A680A449A60426813605A6000234FF04A -:10340000FF320360014B9A61704700BFD823002050 -:1034100070B5124D2A46EB690133EB6152F8103F4B -:10342000934206D030269A68013A9A602C69A368C4 -:1034300003B170BDD4E900210A605160236083F3B9 -:1034400011882046D4E90331984786F311886169D1 -:103450000029EBD02046FFF7A9FFE7E7D82300209B -:1034600000207047FEE70000704700004FF0FF307B -:1034700070470000BFF34F8F024AD368DB07FCD4CC -:10348000704700BF0020024008B5074B1B7853B9B6 -:10349000FFF7F0FF054B1A69120641BF044A5A6054 -:1034A00002F188325A6008BD482500200020024001 -:1034B0002301674508B5054B1B7833B9FFF7DAFFE1 -:1034C000034A136943F08003136108BD48250020B7 -:1034D000002002407F289ABF00F5003080020020C3 -:1034E000704700004FF480607047000080207047F4 -:1034F0007F2808B50BD8FFF7EDFF00F58063026861 -:10350000013204D104308342F9D1012008BD0020EA -:10351000FCE700007F2810B504461CD8FFF7AAFF7F -:10352000FFF7B2FFF3220D4B4FF48061DA60022205 -:103530001A61FFF7CFFF58611A6942F040021A6121 -:10354000FFF798FF00F004F9FFF7B4FF2046BDE84D -:103550001040FFF7CDBF002010BD00BF002002408B -:103560002DE9F843054612F00100144606D040F25A -:10357000F32200201E4B1A60BDE8F8831D4BAA18E9 -:103580009A4204D94FF43E72194B1A60F4E7FFF7E0 -:103590007BFF4FF00109FFF76DFFDFF85C806D1ACC -:1035A000012C0F4605EB010603D8FFF783FF01202E -:1035B000E2E73B88C8F8109033800020FFF75AFFFD -:1035C000C8F81000338831F8022B9BB29A420CD015 -:1035D00040F20F32064B1A60084B1E60084B1C600D -:1035E000084B1F60FFF766FFC6E7023CD8E700BF45 -:1035F0004425002000000208002002403825002059 -:10360000402500203C250020084908B50B7828B14A -:103610001BB9FFF739FF01230B7008BD002BFCD04D -:10362000BDE808400870FFF745BF00BF48250020EF -:1036300070B5FFF739FE4FF47A710D4B0D4EDB6913 -:10364000326801FB03F3934237BF0B4A0A495168C2 -:10365000156836BF4C1CD1E9005454605D1944F123 -:1036600000043360FFF72AFE2846214670BD00BFE4 -:10367000D82300204C2500205025002070B5FFF7EE -:1036800013FE4FF47A710F4B0F4EDB69326801FB6A -:1036900003F3934237BF0D4A0C49516815683ABF8E -:1036A0004C1C5460D1E900545D1944F100043360AE -:1036B000FFF704FE4FF47A72002328462146FCF7F8 -:1036C00031FF70BDD82300204C250020502500205C -:1036D00010B5094C013AD2B2FF2A00D110BD5008F2 -:1036E00054F82030013054F820009BB243EA0043E4 -:1036F00041F8043BEEE700BF046C004010B50748FA -:10370000013AD2B2FF2A00D110BD0C88530840F80C -:1037100023404C88013340F82340F1E7046C00401B -:1037200007B50122002001A9FFF7D2FF019803B0DD -:103730005DF804FB13B50446FFF7F2FFA04205D085 -:103740000122002001A90194FFF7D8FF02B010BDAB -:103750007047000045F25552064B1A6002225A602B -:1037600040F6FF729A604CF6CC421A600122024B7E -:103770001A707047003000405C250020034B1B7816 -:103780001BB14AF6AA22024B1A6070475C25002042 -:1037900000300040044B1A682AB902F1804202F559 -:1037A0000432526A1A607047582500204FF0807228 -:1037B000014B5A62704700BF0010024008B5FFF786 -:1037C000E9FF024B1868C0F3407008BD582500207F -:1037D00008B5FFF7DFFF024B1868C0F3007008BDA3 -:1037E00058250020EFF30983203383F30988002351 -:1037F00083F3118870470000302080F3118862B68F -:103800000C4B0D4AD96821F4E0610904090C0A4304 -:10381000DA60D3F8FC20094942F08072C3F8FC203A -:103820000A6842F001020A602022DA7783F8220057 -:10383000704700BF00ED00E00003FA05001000E053 -:10384000302310B583F311880B4B5B6813F40063CE -:103850000FD0EFF309844FF08073203CE36184F3D1 -:103860000988FFF7DDFC10B1044BA36110BD044BC8 -:10387000FBE783F31188F9E700ED00E02F0900086A -:103880003209000870470000FEE700000A4B0B48B1 -:103890000B4A90420BD30B4BC11EDA1C121A22F0BA -:1038A00003028B4238BF00220021FDF7FFBE53F810 -:1038B000041B40F8041BECE72C3E0008E025002028 -:1038C000E0250020E0250020FEE7000070B500257F -:1038D00004461A4B86B05860856201630E46FFF7B6 -:1038E0008BFF04F11003C4E904334FF0FF33A361ED -:1038F000134BE561D9692B460A462046C4E90823E3 -:1039000004F134018023C4E900440E4AA560E56255 -:103910002565FFF7E3FC01230B4AE0600375009285 -:10392000726868460192B268CDE90223074BCDE97F -:103930000435FFF7FBFC06B070BD00BF302500204A -:10394000D8230020B83D0008BD3D0008C938000854 -:1039500000F030B808B500F063F9FFF78DFCBDE862 -:103960000840FFF717BF0000704700004FF0FF311D -:103970000E4B1A6919611A6900221A611869D86810 -:10398000D960D968DA60DA68DA6942F08052DA61BF -:10399000DA69DA6942F00062DA61054ADB691368C4 -:1039A00043F48073136000F01BB900BF00100240A5 -:1039B00000700040194B1A6842F001021A601A6840 -:1039C0009007FCD51A6802F0F9021A6000225A60CA -:1039D0005A6812F00C0FFBD11A6842F480321A6058 -:1039E0001A689103FCD55A6842F4E8125A601A68C2 -:1039F00042F080721A601A689201FCD51221084ABE -:103A00005A60084A11605A6842F002025A605A68C5 -:103A100002F00C02082AFAD1704700BF00100240E1 -:103A200000641D0000200240084A08B5516913686F -:103A30000B4003F00103536123B1054A13680BB136 -:103A400050689847BDE80840FFF7FABE00040140FF -:103A500060250020084A08B5516913680B4003F03F -:103A60000203536123B1054A93680BB1D0689847AC -:103A7000BDE80840FFF7E4BE0004014060250020D7 -:103A8000084A08B5516913680B4003F004035361F9 -:103A900023B1054A13690BB150699847BDE8084046 -:103AA000FFF7CEBE0004014060250020084A08B59B -:103AB000516913680B4003F00803536123B1054AB1 -:103AC00093690BB1D0699847BDE80840FFF7B8BECD -:103AD0000004014060250020084A08B551691368B8 -:103AE0000B4003F01003536123B1054A136A0BB175 -:103AF000506A9847BDE80840FFF7A2BE00040140A5 -:103B000060250020174B10B55A691C68144004F456 -:103B100078725A61A30604D5134A936A0BB1D06A2E -:103B20009847600604D5104A136B0BB1506B984749 -:103B3000210604D50C4A936B0BB1D06B9847E20574 -:103B400004D5094A136C0BB1506C9847A30504D5F2 -:103B5000054A936C0BB1D06C9847BDE81040FFF755 -:103B60006FBE00BF00040140602500201A4B10B555 -:103B70005A691C68144004F47C425A61620504D5F9 -:103B8000164A136D0BB1506D9847230504D5134A9F -:103B9000936D0BB1D06D9847E00404D50F4A136EB6 -:103BA0000BB1506E9847A10404D50C4A936E0BB12B -:103BB000D06E9847620404D5084A136F0BB1506F5A -:103BC0009847230404D5054A936F0BB1D06F9847EB -:103BD000BDE81040FFF734BE00040140602500201E -:103BE000062108B50846FFF721FA06210720FFF74E -:103BF0001DFA06210820FFF719FA06210920FFF710 -:103C000015FA06210A20FFF711FA06211720FFF7FF -:103C10000DFABDE8084006212820FFF707BA00008A -:103C200008B5FFF7A3FE054800F00CF8FFF71CFAF3 -:103C3000FFF79AFEBDE8084000F002B8C43D000856 -:103C400000F042B8002319461C4A0133102BC2E988 -:103C5000001102F10802F8D1194B9A6942F07D0275 -:103C60009A619B690268174BDA6082685A60426801 -:103C70001A60C26803F58063DA6042695A600269BB -:103C80001A608269C3F80C24026AC3F80424C2696A -:103C9000C3F80024426AC3F80C28C26AC3F8042897 -:103CA000826AC3F80028026BC3F80C2C826BC3F83D -:103CB000042C426BC3F8002C704700BF6025002025 -:103CC00000100240000801404FF0E023044A0821A0 -:103CD0005A6100229A6107220B201A61FFF7BCB9D2 -:103CE0003F19010008B5302383F31188FFF7DAFA92 -:103CF000002383F3118808BD08B5FFF7F3FFBDE883 -:103D00000840FFF79DBD000010B501390244904204 -:103D100001D1002005E0037811F8014FA34201D042 -:103D2000181B10BD0130F2E72DE9F0419BB10446AC -:103D3000C91A1778014403F1FF3C8C42204601D98F -:103D4000002008E005780134BD42F6D10CEB0405F3 -:103D5000D618A54201D1BDE8F08115F8018D16F8FD -:103D600001EDF045F5D0E8E7034611F8012B03F823 -:103D7000012B002AF9D170476F72672E617264754A -:103D800070696C6F742E663130332D4169727370B7 -:103D90006565640040A2E4F1646891060041A3E512 -:103DA000F26569920700000063300000A83D00083A -:103DB00030240020302500206D61696E0069646C3C -:103DC0006500000000180000444441444454494444 -:103DD00001000000424444444444444400000000C4 -:103DE00044444444444444440000000044444444A3 -:103DF0004444444400000000444444444444444493 -:103E000054C7FF7F01000000E8030000000000002D -:103E1000009C0100000000006400000000000000A1 -:0C3E200040420F00FE2A0100D204000006 +:10052000704700BF02E000F000F8FEE772B6264810 +:1005300080F30888254880F3098825482549086004 +:10054000022080F31488BFF36F8F03F025F803F0C7 +:1005500089F84FF0553020491B4A91423CBF41F881 +:10056000040BFAE71D49194A91423CBF41F8040BBC +:10057000FAE71B491B4A1C4B9A423EBF51F8040B39 +:1005800042F8040BF8E700201849194A91423CBF91 +:1005900041F8040BFAE703F003F803F065F8154C93 +:1005A000154DAC4203DA54F8041B8847F9E700F014 +:1005B0003FF8124C124DAC4203DA54F8041B884742 +:1005C000F9E702F0EBBF0000000900200011002055 +:1005D0000000000808ED00E00001002000090020F4 +:1005E000183B0008001100202411002028110020D1 +:1005F000D4250020600100086001000860010008A7 +:10060000600100082DE9F04FC1F80CD0C3689D4689 +:10061000BDE8F08F002383F311882846A04700200F +:1006200002F0E6FCFEE702F07FFC00DFFEE70000E0 +:10063000F8B500F03BFE02F0FDFE074602F048FF71 +:10064000064600283ED12B4B9F423BD001339F42B0 +:100650003BD0294B27F0FF029A4239D1F8B200F083 +:1006600001FC354642F2107400F002FC08B100248F +:10067000254601F003F978B30024032000F042F886 +:10068000254636B11D4B9F4203D0002402F018FFCF +:100690002546002002F0D8FE194B9B6813F040035A +:1006A0001FD00DB100F044F800F042FC01F07AF9DF +:1006B0000546C4B101F076F9401BA04213D900F001 +:1006C00037F8F3E735460024CEE704460125CBE7AB +:1006D00005464FF47A74C7E7B4F57A7F08BF012561 +:1006E000CFE71C46E0E700F0D5FC012002F086FCD5 +:1006F000DFE700BF010007B0000008B0263A09B0EC +:10070000000C0140084B187003280CD8DFE800F0FB +:1007100008050208022000F025BE022000F01ABEE3 +:100720000022024B5A607047281100202C11002033 +:1007300038B501F0A3F830B103221F4B1A70002224 +:100740001E4B5A6038BD1E4B1E4A19680131F9D044 +:1007500004339342F9D11C4C194DD4F80424AA4215 +:10076000F0D31A4B9B6803F1006303F5C8439A4228 +:10077000E8D202F079FE02F08BFE002000F0B0FD1E +:100780000220FFF7BFFF124BDA690022DA61D96954 +:1007900099699A619B6972B64FF0E023C3F8085DCE +:1007A0003021D4F80034D4F8042481F311889D4614 +:1007B00083F308881047C5E7281100202C1100207A +:1007C0000064000820640008006000080011002098 +:1007D0000010024049F26900084A136899B21B0CE4 +:1007E00000FB013344F250611360054B186882B27C +:1007F000000C01FB0200186080B27047201100203D +:100800001C11002010B504460021102200F0C6FD86 +:10081000034B03CB206061601868A06010BD00BF6F +:10082000E8F7FF1F2DE9F0410026ADF54E7D6CACD9 +:1008300040F2751207460D460EA831460D9600F09F +:10084000ADFD4FF4C4723146204600F0A7FD01F023 +:10085000A9F84FF47A72B0FBF2F0264B0DF1340890 +:10086000186093E80700022384E807000DF5E9709B +:100870002382FFF7C7FF4EF603031F4906A8238410 +:1008800003F0FCF81B230DF2E32284F832310DF162 +:10089000300C06AB1E4603CE6645106051603346F1 +:1008A00002F10802F6D13188B378204611809370A6 +:1008B0004146012200F0BEFD00230393AB7E80B2CF +:1008C000029305F1190301930123CDE904800093FC +:1008D000384606A3D3E90023E97E01F0A9FB0DF514 +:1008E0004E7DBDE8F08100BFAFF300809E6AC42159 +:1008F000818A46EE341100208C3A00082DE9F0413F +:10090000264D80462B7A0C46DAB0FBB9204627A943 +:1009100000F0A0FE0746002836D19DF89D60C82E45 +:1009200032D801464FF4FA72284600F037FD3246BD +:100930000DF19E0105F1090000F01EFD9DF89C30AF +:100940002E4477722B720BB9E37E2B728122002129 +:1009500006AD27A800F022FD0122294627A800F0B5 +:10096000B5FE00230393A37E80B2029304F1190322 +:1009700001932823CDE904500093404605A3D3E911 +:100980000023E17E01F054FB5AB0BDE8F08100BFC6 +:10099000AFF3008026417272DF25D7B77C2100209B +:1009A000F0B54FF48A750024234EF1B005FB0065C5 +:1009B00096F8D830D822214685F8DC3085F8E84012 +:1009C0003AA800F0EBFC06F1090000F0DFFCD5F8D6 +:1009D000E430C2B206AF8DF8F00006F109010DF166 +:1009E000F100CDE93A3400F0C7FC394601223AA8BB +:1009F00000F098FE80B2CDE9047008230127CDE90C +:100A0000023706F1D80301933023317A00930B4863 +:100A100007A3D3E9002301F00BFBA04206DD00F0A1 +:100A2000C1FFC5F8E000384671B0F0BD2046FBE7D5 +:100A300078F6339F93CACD8D7C2100204C21002075 +:100A4000F0B51E4E1E4F1F4D85B0304601F01CFB09 +:100A5000044660B310220021684600F09FFC4FF06E +:100A60000003227B6068A16862F303038DF8003005 +:100A700002AB03C3019B2268384662F31C03019357 +:100A80009DF800306A4643F020038DF800300023C3 +:100A9000194602F085F9044620B9304601F0F8FA0B +:100AA0002C70D2E72B78072B03D801332B7005B0BD +:100AB000F0BD024801F0ECFAF9E700BF4C2100203C +:100AC000A82300207523002070B50D4614461E464D +:100AD00001F00AFA50B9022E10D1012C0ED112A346 +:100AE000D3E900230120C5E9002307E0282C10D01A +:100AF00005D8012C09D0052C0FD0002070BD302C5A +:100B0000FBD10BA3D3E90023ECE70BA3D3E900232C +:100B1000E8E70BA3D3E90023E4E70BA3D3E9002321 +:100B2000E0E700BFAFF30080401DA12026812A0B23 +:100B300078F6339F93CACD8D9E6AC421818A46EE92 +:100B400026417272DF25D7B7F017304A39059E5615 +:100B500038B505460E4C0021013500F0E3FBA4F842 +:100B6000F051B4F8F00100F0C5FB78B1B4F8F00131 +:100B700000F0D0FB014648B9B4F8F00100F0D2FB18 +:100B8000B4F8F0310133A4F8F031EAE738BD00BF22 +:100B90007C2100202DE9F04F8DB000AF04460D46BA +:100BA00001F0A2F9002846D12B7E022B1AD1EB8A44 +:100BB000012B17D100F0F6FE0646FFF70BFE4FF4AF +:100BC000C873B0FBF3F202FB1303DFF878829BB229 +:100BD00006F516763344C8F80030EB7E33B90022B0 +:100BE000994B1A703437BD46BDE8F08F284607F19F +:100BF0001C0100F0EDFC0028F4D107F10C00FFF718 +:100C000001FEBD7F07F10C012A4607F11F0002F02B +:100C100005FF0028E3D10F2D08D88B4B1D70D8F8A5 +:100C20000030A3F51673C8F80030DBE72046397FA3 +:100C300001F052F9D6E7EB8A282B6BD010D8012BA4 +:100C400063D0052BCED1BFF34F8F8049804BCA684C +:100C500002F4E0621343CB60BFF34F8F00BFFDE7A8 +:100C6000302BBFD17B4CEA7E237A9A42BAD194F8DA +:100C7000DC206B7E9A42B5D1284604F1EA0100F0EF +:100C80007DFD06460028ADD1012384F8E83000F050 +:100C900089FED4F8E030C01A192840F6B83338BFBE +:100CA0001920984228BF1846FFF7C4FB6A49FFF78E +:100CB00057FA05462068FFF7BDFB6849FFF750FA71 +:100CC00001462846FFF706FBFFF70CFC20604FF4B7 +:100CD0008A7194F8D9307B607A68636801FB02F509 +:100CE000621992F8E80050B1D2F8E400E946834274 +:100CF00015D0002382F8E830C2F8E030CD466368B2 +:100D0000574A9B0A013313816CE729462046FFF7B7 +:100D100089FD67E729462046FFF7F0FD62E7B2F854 +:100D2000EC803B6008F1030A4FEA9A0A4FEA8A0214 +:100D3000D11DC908A9EBC1039D46EB4600215846C9 +:100D400000F02CFB05F1EE0142465846214400F02C +:100D500013FB3B6813B9012000F0C2FA94F8D200EB +:100D600000F0C8FA054630B9207200F0E3FA2846D0 +:100D700000F0B6FAC2E7D4F8D4303BB994F8D20008 +:100D8000B4F8F031834201D8FFF7E2FED4F8D43052 +:100D900043449D4208D294F8D200B4F8F0310130B7 +:100DA000834201D8FFF7D4FE594660685FFA8AF2A1 +:100DB00000F0FCFA08B9CD4689E7636894F8D200E0 +:100DC00043446360D4F8D43008EB030AC4F8D4A0D9 +:100DD00000F090FA824509D394F8D230D4F8D400C8 +:100DE0000133401B84F8D230C4F8D400B8F1FF0FAF +:100DF0000FD80025257200F09DFA284600F070FA01 +:100E000000F03CFD164B188108B9FFF791FCCD4668 +:100E1000E8E64FF48A727B6894F8D90002FB03433A +:100E2000D3F8E42083F8E86002F58072C3F8E0604C +:100E3000C3F8E420FFF7B4FDFFF702FE84F8D960A1 +:100E4000B9E700BF482100204521002000ED00E067 +:100E50000400FA057C210020CDCCCC3D6666663FBF +:100E600034110020014B1870704700BF4011002062 +:100E700030B54FF00054254B226885B09A4207D018 +:100E800002F030FB0446C0B90024204605B030BD56 +:100E90000025627D1E4B1F481A70237DC9220372F4 +:100EA0001D49C0F8E450093000F066FA2046E022FF +:100EB000294600F073FA0124E7E7184A184DD36970 +:100EC00043F00073D361AA6D164B9A42DCD12B6EAE +:100ED000013B7E2BD8D8144A01AB07CA83E8070030 +:100EE0001846032100F09AFC6B6D83424FF000031B +:100EF000CAD12A6D8A4203BFAB652A6E044B1C46D9 +:100F000001BF1A70EA6D094B1A60BEE79AAD44C57D +:100F1000401100207C21002016000020001002401B +:100F2000006600405041A0B05866004018110020F3 +:100F30002DE9F04385B000F0A1FC0223494C637118 +:100F400000230293484B2081D3F800C0BCF57A7F80 +:100F500012D3464F464BB7FBFCF59C458CBF0A238A +:100F60001123B5FBF3F603FB1652591EC8B2002A33 +:100F70003ED002290B46F4D89DF80B303D495A1E4D +:100F80009DF80A303C48013B1B0443EA0253BDF87C +:100F90000820013A13434B6001F0F2FE0023019355 +:100FA000364B374900934FF48052364B364800F0A9 +:100FB00069FF364B197811B1334800F08DFF00F00E +:100FC000F1FC0546FFF706FC4FF4C873B0FBF3F2E3 +:100FD00002FB130305F516709BB218442C4B1860E6 +:100FE00002F076FA08B10F23238105B0BDE8F08343 +:100FF000731EB3F5806FBFD24FF47A75C0EBC00E8D +:101000000EF103034FEAE30909FB0555C3F3C703D8 +:10101000C11AC9B209F101088844B5FBF8F5B5F564 +:10102000617F08D90EF1FF33C3F3C703C11A581EFD +:101030000F28C9B214D84A1E072A8CBF00220122E9 +:10104000581800FB0660B7FBF0F7BC4594D1002AA6 +:1010500092D0ADF808608DF80A308DF80B108BE750 +:101060001346EDE73411002018110020005125022D +:101070003F420F0010110020A8230020C90A0008D9 +:1010800044110020950B00084C2100204011002045 +:10109000482100202DE9F04F80A7D7E900670FF223 +:1010A0000429D9E90089734D93B00DF1300AFFF797 +:1010B000C7FC18220021504600F070F9DFF8B8B1E3 +:1010C0006E4C002352461946584601F091FE0146E7 +:1010D00050BB102208A800F061F9E36883F0100308 +:1010E000E36000F061FC0DF1240C0B4612A90246EE +:1010F00011E903008CE803009DF83410C1F30300EC +:10110000890649BF0E99BDF83810C1F31C0141F0A2 +:10111000004158BFC1F30A018DF82C000891284600 +:1011200008A901F095F9CCE7284600F0DDFE044659 +:10113000002847D100F036FCDFF844B1DBF800307E +:1011400098423FD300F02EFC0790FFF743FB4FF48B +:10115000C873B0FBF3F101FB1300079A83B202F5E9 +:1011600016701844CBF80000DFF818B18DF8204055 +:101170009BF8001011B901238DF8203050460791DB +:10118000FFF740FB07990DF12100C1F11004E4B213 +:10119000062C28BF06245144224600F0EDF808AB87 +:1011A000039318230293384B013401930123E4B2D3 +:1011B000009332463B462846049400F0DBFE0023B1 +:1011C0008BF8003000F0EEFB304A314C1368C31A44 +:1011D000B3F57A7F30D3106000F0E6FB02460B4691 +:1011E000284600F05FFF284600F07EFE20B3237AF9 +:1011F000DFF8A0B0002B14BF032302238BF80530C7 +:1012000000F0D0FB4FF47A73B0FBF3F00122CBF87F +:1012100000005146584600F0B3F9182302931E4BC4 +:1012200080B2019340F25513CDE903A000934246EA +:101230004B46284600F09EFE237ABBB100F0B2FB7D +:1012400094F8E83073B9D4F8E03043B1C01A236899 +:10125000FA2B38BFFA230533B0EB430F02D300203B +:10126000FFF79EFB237A002B7FF41FAF13B0BDE87E +:10127000F08F00BF4C210020A8230020000801406F +:101280004821002045210020442100207023002017 +:101290007C2100203411002074230020401DA12057 +:1012A00026812A0BF1C6A7C1D068080F70B501F0DE +:1012B0007DFF0024084E094D308028683388834222 +:1012C00008D901F06FFF2B6804440133B4F5C84F0F +:1012D0002B60F2D370BD00BFA42300207823002030 +:1012E00001F0F2BF00F10060920000F5C84001F08B +:1012F00097BF0000054B1A68054B1B889B1A834259 +:1013000002D9104401F04EBF00207047782300201E +:10131000A4230020024B1B68184401F049BF00BF02 +:1013200078230020024B1B68184401F053BF00BF14 +:1013300078230020064991F8243033B10023082295 +:10134000086A81F82430FFF7CDBF0120704700BF45 +:101350007C230020022802BF1022014B1A61704733 +:1013600000080140022802BF4FF48012014B1A61AD +:10137000704700BF00080140002310B5934203D01E +:10138000CC5CC4540133F9E710BD000003460246AB +:10139000D01A12F9011B0029FAD170470346024402 +:1013A000934202D003F8011BFAE770472DE9F84396 +:1013B0001F4D144695F824200746884652BBDFF897 +:1013C00070909CB395F824302BB92022FF21484619 +:1013D0002F62FFF7E3FF95F824004146C0F10802B1 +:1013E000A24228BF224605EB8000D6B29200FFF74A +:1013F000C3FF95F82430A41B1E44F6B2082E1744F0 +:101400009044E4B285F82460DBD1FFF793FF002815 +:10141000D7D108E02B6A03EB82038342CFD0FFF7DA +:1014200089FF0028CBD10020BDE8F8830120FBE72D +:101430007C2300202DE9F0470D460446002190460C +:10144000284640F27912FFF7A9FF23462022002107 +:10145000284600F09FFF022220212846231D00F08D +:1014600099FF032222212846631D00F093FF0322E7 +:1014700025212846A31D00F08DFF10222821284693 +:1014800004F1080300F086FF08223821284604F101 +:10149000100300F07FFF08224021284604F11103C9 +:1014A00000F078FF08224821284604F1120300F0DA +:1014B00071FF20225021284604F1140300F06AFF36 +:1014C00040227021284604F1180300F063FF08222F +:1014D000B021284604F1200300F05CFF0822B82167 +:1014E000284604F1210300F055FFC02604F122072D +:1014F0003B46314608222846083600F04BFFB6F539 +:10150000A07F07F10107F3D108223146284604F1F4 +:10151000320300F03FFF002704F1330A94F8323021 +:101520004FEAC7099F4209F5A47615D3B8F1000F19 +:1015300008D131460722284604F5997300F02AFFA6 +:1015400009F24F16274694F832213B1B93420CD3E5 +:10155000F01DC008BDE8F0870AEB070308223146FA +:10156000284600F017FF0137D8E7314607F233135A +:101570000822284600F00EFF08360137E3E7000096 +:1015800038B50C460021054621600346C4F8031017 +:101590002046202200F0FEFE20462B1D02222021A4 +:1015A00000F0F8FE20466B1D0322222100F0F2FE1F +:1015B0002046AB1D0322252100F0ECFE2046102220 +:1015C000282105F1080300F0E5FE072038BD0000E2 +:1015D0000023F7B50E460546047F07220091194601 +:1015E00000F09AFD731C0093012200230721284676 +:1015F00000F092FDC4B9B31C0093052223460821D4 +:10160000284600F089FD0D243746B278BB1B934273 +:1016100011D32B7FE01DC008AC8ABBB9A04294BF98 +:101620000020012003B0F0BDAB8A0824DB00083B9A +:10163000DB08B370E8E7FB1C214600930822002377 +:10164000284600F069FD08340137DEE7001B18BFAB +:101650000120E7E70023F7B50E46047F082200913A +:101660001946054600F058FD731CC4B908220093C2 +:1016700011462346284600F04FFD102401237278BE +:101680005F1C013B934211D32B7FE01DC008AC8A45 +:10169000BBB9A04294BF0020012003B0F0BDAB8ACB +:1016A0000824DB00083BDB087370E7E7F3192146E9 +:1016B000009308220023284600F02EFD08343B4604 +:1016C000DDE7001B18BF0120E7E70000F8B50E4674 +:1016D00005461446002181223046FFF75FFE2B4667 +:1016E00008220021304600F055FE7CB9072208216F +:1016F00030466B1C00F04EFE0F2401236A785F1CFD +:10170000013B934204D3E01DC008F8BD0824F4E770 +:101710002146EB190822304600F03CFE08343B46D7 +:10172000ECE70000F8B50E46054614460021CE222F +:101730003046FFF733FE2B4628220021304600F0CA +:1017400029FE7CB908222821304605F1080300F063 +:1017500021FE30242F462A7A7B1B934204D3E01DBE +:10176000C008F8BD2824F5E7214607F1090308223F +:10177000304600F00FFE08340137ECE7F7B5047F80 +:101780000E460091012310220021054600F0C4FC02 +:10179000C4B9B31C0093092223461021284600F047 +:1017A000BBFC192437467288BB1B9A4211D82B7F89 +:1017B000E01DC008AC8ABBB9A04294BF0020012044 +:1017C00003B0F0BDAB8A1024DB00103BDB08738054 +:1017D000E8E73B1D2146009308220023284600F03D +:1017E0009BFC08340137DEE7001B18BF0120E7E748 +:1017F00030B5094D0A4491420DD011F8013B5840D3 +:10180000082340F30004013B2C4013F0FF0384EA5B +:101810005000F6D1EFE730BD2083B8ED4FF0FF3335 +:10182000F7B500EB81061946DFF848C0DFF848E05D +:10183000B0421BD050F8042B01AF0192042217F8DC +:10184000014B81EA046108240D46DB184941013C43 +:10185000002DBCBF83EA0C0381EA0E0114F0FF04E3 +:10186000F2D1013A12F0FF02E9D1E1E7D843C943CE +:1018700003B0F0BD9336EAA9EBE1F042F7B56B4651 +:10188000354A106851686A4603C30823334934480F +:1018900002F0D4F8044690BB0A256B46314A106822 +:1018A00051686A4603C308232F492D4802F0C6F841 +:1018B0000446002847D00369B3F5CE3F43D8B0F8BB +:1018C0006620B2F57A7F3ED1284A024402F15C01DB +:1018D0008B4238D35C3B224900209E1AFFF788FFD9 +:1018E00007463246002004F16401FFF781FFA36838 +:1018F0009F4228D1E368984208BF002523E003698E +:10190000B3F5CE3F26D8428BB2F57A7F20D1174A65 +:10191000024402F110018B4218D3103B1049002001 +:101920009D1AFFF765FF06462A46002004F11801BC +:10193000FFF75EFFA3689E4202D1E368984201D0A0 +:101940000D25AAE70025284603B0F0BD1025A4E721 +:101950000C25A2E70B25A0E7A83A0008DC9B0100B4 +:1019600000640008B13A0008909B0100089CFFF752 +:10197000EFF30983EFF30583014B9B6BFEE700BF99 +:1019800000ED00E008B5FFF7F3FF0000EFF3098377 +:10199000EFF30583014B5B6BFEE700BF00ED00E05A +:1019A000FEE7000001F0F6BC01F0A2BC2DE9F04119 +:1019B000456A15B94162BDE8F0814B68AC4623F039 +:1019C0006047C3F38A4616EA230638BF3E464FEA0D +:1019D000D37EC3F380782B465A68BEEBD27F22F0C9 +:1019E00060440AD0002A18DAA40CB44217D19D42F0 +:1019F0000FD10D60DEE71346EEE7A74207D102F0F4 +:101A00008044C2F3807242450BD054B1EFE708D254 +:101A1000EDE7CCF800100B60CDE7B44201D0B44242 +:101A2000E5D81A689C46002AE5D11960C3E7000092 +:101A30002DE9F0474FF47F49089D01F007044FEA74 +:101A4000D508224405F0070500EBD100944201D1EE +:101A5000BDE8F08704F0070705F0070A57453E4642 +:101A600038BF5646111BC6F108068E4228BF0E46E7 +:101A7000E108415C08EBD50E13F80EC0B94029FA15 +:101A800006F721FA0AF1FFB28CEA010147FA0AF7D8 +:101A900039408CEA010C03F80EC034443544D5E7D4 +:101AA000082341F2210280EA012001B2400000290E +:101AB00080B203F1FF33B8BF504013F0FF03F4D1FD +:101AC0007047000038B50C468D18A54200D138BDCE +:101AD00014F8011BFFF7E4FFF7E700000346406836 +:101AE00048B1026899895A605A89013292B291428A +:101AF0005A8138BF9A81704770B504460D4688B048 +:101B0000202200216846FFF749FC20460495FFF794 +:101B1000E5FF024658B16B46054608AE1C4603CCAD +:101B2000B44228606960234605F10805F6D11046E5 +:101B300008B070BD082817D909280CD00A280CD085 +:101B40000B280CD00C280CD00D280CD00E2814BF5C +:101B50004020302070470C20704710207047142020 +:101B6000704718207047202070470000082817D9B8 +:101B70000C280CD910280CD914280CD918280CD9E9 +:101B800020280CD930288CBF0F200E207047092048 +:101B900070470A2070470B2070470C2070470D20BB +:101BA000704700002DE9F843078C0446072F1ED923 +:101BB000D0E9029800254FF6FF73C5F12006A5F184 +:101BC000200029FA05F108FA06F628FA00F0314358 +:101BD0000143C9B21846FFF763FF0835402D03469D +:101BE000EBD13A46E169BDE8F843FFF76BBF4FF62A +:101BF000FF70BDE8F883000010B54B6823B9CA8AAE +:101C000063F30902CA8210BD04691A681C6003618B +:101C1000C38A013BC3824A60EFE700002DE9F84F19 +:101C20001D46CB8A0F46C3F309010529814692461A +:101C30000B4630D00020AAB207F11A049EB2042E3F +:101C40001FFA80F80FD8904503F1010306D3FB8AF1 +:101C50000A4462F309030120FB821AE01AF80060CB +:101C60000130E654EAE79045F1D21C23A1F1050BBF +:101C7000BBFBF3F203FB12BB7C681FFA8BF6002C54 +:101C800045D14846FFF72AFF044638B978606FF01F +:101C90000200BDE8F88F4FF00008E6E70026066076 +:101CA00078604FF0000BADB2454510D90AEB080340 +:101CB000221D13F8011B08F101089155B1B21B292F +:101CC0001FFA88F82BD0454506F10106F1D8FB8AAA +:101CD000C3F30902154465F30903BCE71C4601324E +:101CE00092B22368002BF9D16B1F0B441C21B3FB6C +:101CF000F1F301339BB29A42D3D2BBF1000FD0D1A2 +:101D00004846FFF7EBFE20B9C4F800B0BFE7012258 +:101D1000E7E7C0F800B05E4620600446C1E74545ED +:101D2000D5D94846FFF7DAFE08B92060AFE7C0F81A +:101D300000B0002620600446B6E700002DE9F74F0A +:101D40001C465B69074688460092002B00F097808E +:101D5000238C2BB1E269002A00F09180072B33D845 +:101D600007F10C00FFF7BAFE054628B96FF002052F +:101D7000284603B0BDE8F08F14220021FFF70EFBC8 +:101D8000228CE16905F10800FFF7F6FA208C48F093 +:101D90000041013080B2FFF7E9FEFFF7CBFE0138CA +:101DA00080B22084013028746369228C1B782A4415 +:101DB00003F01F0363F03F0313723846696029463E +:101DC000FFF7F4FD0125D3E74FF000094FF0800A3B +:101DD0004E464D4600F10C0301930198FFF77EFE3D +:101DE00083460028C2D014220021FFF7D7FA002E24 +:101DF0003BD10222009BABF808300BF1080E1FFA12 +:101E000082FC0CF10100BCF1060F218C80B201D8DC +:101E10008E422CD3FFF7AAFEFFF78CFE8E4208BF3E +:101E20004FF0400A62690138127880B202F01F0256 +:101E300042EA49120BEB00014AEA020A013048F07B +:101E4000004281F808A08BF8100059463846CBF8BC +:101E50000420FFF7ABFD238C0135B3424FF0000A9D +:101E60002DB289F00109B8D182E70022C5E7E16906 +:101E7000895D01360EF80210B6B20132BFE76FF08D +:101E8000010575E7F8B5044615460E4630220021D7 +:101E90001F46FFF783FA069BB5F5001F6360079B9B +:101EA00028BF4FF6FF72A3624FF0000338BF6A09E4 +:101EB000A760E66197B204F110009A4206D80023A9 +:101EC0000360A782E3822383E360F8BD06600133E9 +:101ED00030462036F1E7000003781BB94BB2002BE7 +:101EE000C8BF01707047000000787047F8B50C4615 +:101EF000C969074611B9238C002B37D1257E1F2DC8 +:101F000034D8387828BB228C072A2CD8268A36F079 +:101F100003032BD14FF6FF70FFF7D4FD4FF6FF728E +:101F200020F001003602400446EA0565400C45EA0F +:101F30004025234629463846FFF700FF002807DDE5 +:101F4000626913780133DBB21F2B88BF0023137043 +:101F5000F8BD218A2D0645EA012505432046FFF7F5 +:101F600021FE0246E5E76FF00300F1E76FF00100A4 +:101F7000EEE7000070B504461D4616468AB02822DA +:101F800000216846FFF70AFABDF838306946ADF817 +:101F900010300F9B204605939DF84030CDE9026537 +:101FA0008DF81830119B0793BDF84830ADF82030FC +:101FB000FFF79CFF0AB070BD2DE9F041D3690546DB +:101FC0000C4616460BB9138C5BBB377E1F2F28D8E7 +:101FD00095F80080B8F1000F26D03046FFF7E2FDFB +:101FE0003378210241EAC33141EA0801338A41EAE8 +:101FF000076141EA034102463346284641F0800129 +:10200000FFF79CFE00280ADD3378012B07D17269A7 +:1020100013780133DBB21F2B88BF00231370BDE898 +:10202000F0816FF00100FAE76FF00300F7E70000BE +:10203000F0B504460D461E4617468BB028220021F7 +:102040006846FFF7ABF99DF84C3029465A1E5342BB +:1020500053418DF800309DF840306A46ADF810309D +:10206000119B204605939DF84830CDE902768DF806 +:102070001830149B0793BDF85430ADF82030FFF7AB +:102080009BFF0BB0F0BD0000406A00B10430704708 +:10209000436A1A68426202691A600361C38A013B9B +:1020A000C38270472DE9F041D0F8208014461D46C8 +:1020B00041460027174E09B9BDE8F081D1E9022356 +:1020C000A21A65EB0303964277EB03031ED2036A61 +:1020D0008B420DD1FFF790FD036A1B680362036911 +:1020E0000B60C38A0161016A013B8846C382E2E753 +:1020F000FFF782FD0B68C8F8003003690B60C38AE4 +:102100000161013BC382D8F80010D4E78846096812 +:10211000D1E700BF80841E002DE9F04F8BB00D4643 +:1021200014469B468046DDF85090002800F01A8146 +:10213000B9F1000F00F01681531E3F2B00F21281FF +:10214000012A03D1BBF1000F40F00C810023CDE93F +:102150000833B8F81430B5EBC30F4FEAC30703D305 +:1021600000200BB0BDE8F08F2B199F42D8F80C303F +:1021700036BF7F1B2746FFB21BB9D8F81030002BA3 +:102180007BD0272D4ED8C5F12806B7424FF000036B +:1021900034BF3E46F6B2009329463246D8F80800CE +:1021A00008ABFFF745FCA7EB060A35445FFA8AFA4D +:1021B0002821B8F8143003F10053053BDB000493E9 +:1021C000D8F80C300393039B13B1BAF1000F2CD154 +:1021D000D8F8100040B1BAF1000F05D05246009671 +:1021E00008AB691AFFF724FC38B2002FB8D0660795 +:1021F0000AD00AAB03EBD40111F8083C624202F0AA +:102200000702134101F8083C082C3DD9102C40F27C +:10221000B680202C40F2B880BBF1000F00F09D800A +:10222000082335E0BA460026C2E7049BE02B28BF0E +:10223000E02306930B44AB42059315D95A1B9245F4 +:1022400038BF5246039828BFD2B20096691A08AB2D +:1022500004300792FFF7ECFB079A1644AAEB020A38 +:102260001544F6B25FFA8AFA049B069A05999B1AFE +:102270000493039B1B680393A5E700933A46294602 +:10228000D8F8080008ABADE7BBF1000F13D001236D +:10229000B4EBC30F6CD0082C12D89DF82030621E0E +:1022A00023FA02F2D50706D54FF0FF3202FA04F402 +:1022B00023438DF820309DF8203089F8003050E716 +:1022C000102C12D8BDF82030621E23FA02F2D1077A +:1022D00006D54FF0FF3202FA04F42343ADF8203064 +:1022E000BDF82030A9F800303BE7202C0FD8089922 +:1022F000631E21FA03F3DA0705D54FF0FF3202FA25 +:1023000004F40C430894089BC9F8003029E7402CDA +:102310002BD0DDE90865611EC4F12102A4F121037F +:1023200026FA01F105FA02F225FA03F311431943E3 +:10233000CB0712D50122A4F12003C4F1200102FA37 +:1023400003F322FA01F1A240524243EA010363EB94 +:10235000430332432B43CDE90823DDE90823C9E9D0 +:102360000023FEE66FF00100FBE66FF00800F8E6E0 +:10237000082CA0D9102CB3D9202CEED8C3E7BBF180 +:10238000000FADD0022383E7BBF1000FBBD00423C5 +:102390007EE70000012A30B5144638BF012200252F +:1023A000402A28BF402285B0012CCDE9025517D81C +:1023B0001B788DF8083053070AD004AB03EBD20525 +:1023C00015F8083C544204F00704A34005F8083C03 +:1023D0000346009102A80021FFF72AFB05B030BD9B +:1023E000082CE5D9102C03D81B88ADF80830E2E79B +:1023F000202C02D81B680293DDE7D3E90045CDE924 +:102400000245D8E710B5CB681BB98B600B618B8296 +:1024100010BD04691A681C600361C38A013BC38252 +:10242000CA60F0E703064CBFC0F3C030022070471B +:1024300008B50246FFF7F6FF022806D15306C2F39D +:102440000F2001D100F0030008BDC2F30740FBE7F5 +:102450002DE9F04F93B0CDE903230A6804461046F6 +:10246000FFF7E0FF02280CBF0026C2F30626002A71 +:102470000D46824680F2F98112F0C04940F0F581A4 +:10248000097B002900F0F181022803D02378B342B0 +:1024900040F0EE81C2F304631046069302F07F031E +:1024A0000593FFF7C5FF059B00224FEA83480023F1 +:1024B00048EA0A48294448EA4668CE78CDE9082324 +:1024C000F309834648EA0008029367D0059B024659 +:1024D000009320465346676808A9B847002800F0D3 +:1024E000CA81276A4FB9414604F10C00FFF704FB8B +:1024F000074690B96FF0020054E03B6998450DD053 +:102500003F68002FF9D1414604F10C00FFF7F4FABF +:1025100007460028EED0236A3B60276297F817C071 +:1025200006F01F08CCF3840CACEB08001FFA80FE09 +:102530000028B8BF0EF12000A8EB0C031FFA83FEA1 +:10254000B8BF00B2002B0793BEBF0EF120031BB231 +:102550000793D7E9022152EA010338D04FF0000C6B +:10256000039BDFF8F8E19A1A049B63EB010196459F +:102570007CEB01032BD36B7B97F81AE0734519D1E1 +:10258000029B002B78D0012821DC7868F8B9DFF8AD +:10259000D0C1944570EB010316D337E0276A27B901 +:1025A0006FF00C0013B0BDE8F08F3B699845B5D0D3 +:1025B0003F68F4E76A4890427CEB010301D30020B6 +:1025C000F0E7029B002BFAD0079B0F2B17DCFA7D5C +:1025D000B30002F0030203F07C031343FB7539469A +:1025E0002046FFF709FB6B7BBB76029B3BB9FB7D6B +:1025F000C3F38402013262F38603FB75D0E76A7B82 +:10260000BB7E9A42DBD1029B002B35D0B309022B53 +:1026100032D0039B1422BB60049B0021FB600DA8F9 +:10262000FEF7BCFE039B20460A93049BADF83EB028 +:102630000B932B1D0C932B7B8DF840A0013BDBB241 +:10264000ADF83C30069B8DF841808DF84230059BFB +:102650000AA98DF8433094F82C3083F001038DF8EB +:102660004430A3689847FB7DC3F38403013303F030 +:102670001F039B02FB82A2E7FB7DC6F34012B2EB75 +:10268000D31F40F0FB80C3F38403434540F0F9803F +:10269000029A2B7BB609002A4DD0F20762D4032B95 +:1026A00040F2F280039BAE1DBB60049B3246FB6090 +:1026B0002B7B3946033BDBB204F10C00FFF7AEFA8B +:1026C00000280CDA39462046FFF796FAFB7DC3F363 +:1026D0008403013303F01F039B02FB820AE7AB88EC +:1026E000DDE908843B834FF6FF73C9F12000A9F1AF +:1026F000200228FA09F104FA00F0014324FA02F258 +:1027000011431846C9B2FFF7CBF909F10809B9F12D +:10271000400F0346E9D13146B8822A7B033AD2B250 +:10272000FFF7D0F9FB7DB882DA43C2F3C01262F33F +:10273000C713FB7543E7AEB92E1D013B3246394640 +:10274000DBB204F10C00FFF769FA0028BADB2A7B40 +:102750003146013AB88AD2B2E2E700BF80841E0057 +:1027600040420F00F98A013BC1F309010429DAB2A2 +:102770005DD80023281D07F11B069A4208D910F8DE +:1027800001CB013306F801C001310529DBB2F4D1D8 +:10279000934228BF0023039938BF04330A91049958 +:1027A00038BFDBB20B9107F11B010C91796838BF80 +:1027B0005B190D910E93FB8AADF83EB0C3F309038C +:1027C0001A44069BADF83C208DF84230059B8DF8ED +:1027D00040A08DF8433094F82C308DF8418083F080 +:1027E00001038DF8443000237B602A7BB88A013ACC +:1027F000291DFFF767F93B8BB882834203D120463E +:10280000A3680AA9984720460AA9FFF7FBFDFB7DAC +:10281000BA8AC3F38403013303F01F039B02FB82D4 +:102820003B8B9A420CBF00206FF01000BAE67B6829 +:10283000002BADD0052001E033461C301E68002E71 +:10284000FAD1091A081D2E1D184401EB090CBCF120 +:102850001B0F5FFA89F39BD89A4299D916F8013B6E +:1028600009F1010900F8013BEFE76FF0090099E673 +:102870006FF00A0096E66FF00B0093E66FF00D0024 +:1028800090E66FF00E008DE66FF00F008AE600BF55 +:10289000F0B53F4D3F4FEB6943F00073EB61EB69DF +:1028A0003D4B9B6AD3F800623E4046F00106C3F8F8 +:1028B0000062D3F800423C4044EA002444F00104A2 +:1028C000C3F80042002955D000200646C3F81C0278 +:1028D000C3F80402C3F80C02C3F8140203EBC004EB +:1028E00001300E28C4F84062C4F84462F6D10027D3 +:1028F0004FF0010C9678148816F0010F18BFD3F82A +:1029000004E20CFA04F01CBF40EA0E0EC3F804E225 +:1029100016F0020F18BFD3F80CE203EBC4041CBF7F +:1029200040EA0E0EC3F80CE2760748BFD3F81462F3 +:1029300007F1010744BF0643C3F814625668B94261 +:10294000C4F84062966802F10C02C4F84462D3F8FD +:102950001C4240EA0400C3F81C02CBD1D3F8002289 +:1029600022F00102C3F80022EB6923F00073EB614F +:10297000EB69F0BD0122C3F84012C3F84412C3F85A +:102980000412C3F81412C3F80C22C3F81C22E5E7A2 +:10299000001002400000FFFFA8230020184A08B5DD +:1029A000916A8B688B6013F0010104D013F00C0F57 +:1029B00018BF4FF48031D80506D513F4406F14BF0B +:1029C00041F4003141F00201D80306D513F4402F41 +:1029D00014BF41F4802141F00401D3690BB10848D0 +:1029E0009847302383F311880021064800F022FB2A +:1029F000002383F31188BDE8084000F0ABBD00BFA1 +:102A0000A8230020B023002038B5124CA36ADD684B +:102A1000AA0712D05A6922F002025A61A36913B1BF +:102A2000012120469847302383F3118800210A486A +:102A300000F000FB002383F31188EB0606D510217C +:102A4000A36AD960236A0BB102489847BDE83840B1 +:102A500000F080BDA8230020B823002038B5124C18 +:102A6000A36A1D69AA0712D05A6922F010025A619E +:102A7000A36913B1022120469847302383F31188BC +:102A800000210A4800F0D6FA002383F31188EB06F0 +:102A900006D51021A36A1961236A0BB10248984731 +:102AA000BDE8384000F056BDA8230020B823002020 +:102AB00038B50F4CA36A5D682A075D600AD5042209 +:102AC00022701A6822F002021A60636A13B10021B0 +:102AD000204698476B0706D5A36A9969236A13B104 +:102AE000034809049847BDE8384000F033BD00BFF3 +:102AF000A823002010B50E4C204600F02FF90D4BF6 +:102B00000B211320A36200F009F90B21142000F01F +:102B100005F90B21152000F001F90B21162000F01A +:102B2000FDF8BDE8104000220E201146FFF7B0BEB0 +:102B3000A8230020006400400F4B10B598420446C3 +:102B400005D10E4BDA6942F00072DA61DB690122CD +:102B5000A36A1A60A36A5A68D20707D562685168E7 +:102B60001268D9611A60064A5A6110BD0121082015 +:102B700000F0B0F9EEE700BFA823002000100240EB +:102B80005B87010003291AD8DFE801F0020A0F145D +:102B9000836A9B6813F0E05F14BF01200020704738 +:102BA000836A9868C0F380607047836A9868C0F34E +:102BB000C0607047836A9868C0F300707047002057 +:102BC0007047000010B5032927D8DFE801F002277D +:102BD0002B2F836A9968C1F30161183103EB01134C +:102BE0001078840648BF5468C0F3001158BF948819 +:102BF0004FEA410148BF41EAC40100F00F005860AC +:102C000048BF41F00401906858BF41EA4451D2687E +:102C100041F001019860DA60196010BD836A03F524 +:102C2000C073DDE7836A03F5C873D9E7836A03F5E8 +:102C3000D073D5E701290AD002290FD081B9836A60 +:102C4000DA68920701D1186903E001207047836AAE +:102C5000D86810F0030018BF01207047836AF2E7BC +:102C60000020704710B539B9836AD96889071BD12C +:102C70001B699C0704D110BD012915D00229FAD186 +:102C8000816AD1F8C031D1F8C441D1F8C8011061CE +:102C9000D1F8CC015061202008610869800717D164 +:102CA000486940F0100012E0816AD1F8B031D1F8E3 +:102CB000B441D1F8B8011061D1F8BC0150612020B5 +:102CC000C860C868800703D1486940F002004861C5 +:102CD000C3F34000C3F38001000140EA41111079C1 +:102CE00020F030000143117189064BBF91681189B2 +:102CF000DB085B0D4CBF63F31C0163F30A0113791E +:102D000048BF916064F3030313714FEA14234FEA41 +:102D1000144458BF118113705480ACE7012209019B +:102D200000F1604303F56143C9B283F8001300F07A +:102D30001F039A4043099B0003F1604303F561437D +:102D4000C3F880211A607047090100F16040C9B2E0 +:102D500000F56D4001767047FFF7CCBE012303708C +:102D6000002300F10802C0E9022200F11002C0E9CC +:102D70000422C0E90633C0E908334360704700000D +:102D800010B53023044683F3118802234160037099 +:102D9000FFF7D2FE04230020237080F3118810BDBA +:102DA0002DE9F0411F4604460D461646302383F3B5 +:102DB000118800F108082378052B0DD029462046FC +:102DC000FFF7E0FE40B1204632462946FFF7FAFE03 +:102DD000002080F3118808E03946404600F01AF9D7 +:102DE0000028E8D0002383F31188BDE8F0810000BB +:102DF0002DE9F0411F4604460D461646302383F365 +:102E0000118800F110082378052B0DD029462046A3 +:102E1000FFF710FF40B1204632462946FFF722FF58 +:102E2000002080F3118808E03946404600F0F2F8AF +:102E30000028E8D0002383F31188BDE8F08100006A +:102E400000238268037503691B6899689142FBD26D +:102E50005A680360426010605860704700238268BF +:102E6000037503691B6899689142FBD85A6803602F +:102E7000426010605860704708B50846302383F3FD +:102E800011880B7D032B05D0042B0DD02BB983F3B8 +:102E9000118808BD00228B691A604FF0FF338361EF +:102EA000FFF7CEFF0023F2E7D1E9003213605A604A +:102EB000F3E70000FFF7C4BF054BD9680875186831 +:102EC000026853601A6001220275D860FDF79ABB50 +:102ED000D823002030B50C4B0446DD684B1C87B06E +:102EE0000FD02B466846094A00F0CAF82046FFF783 +:102EF000E3FF009B13B1684600F0CAF8A86907B069 +:102F000030BDFFF7D9FFF9E7D8230020792E00085C +:102F1000044B1A68DB6890689B68984294BF002055 +:102F200001207047D8230020084B10B51C68D868D2 +:102F3000226853601A6001222275DC60FFF78EFF61 +:102F400001462046BDE81040FDF75CBBD8230020B9 +:102F500038B501230025064C0649074823706560F3 +:102F600000F03EFB0223237085F3118838BD00BFBB +:102F700030250020C03A0008D823002000F09AB87D +:102F80008B60022308618B82084670478368A3F137 +:102F9000440243F8142C026943F8442C426943F874 +:102FA000402C094A43F8242CC268A3F1200043F8BE +:102FB000182C022203F80C2C002203F80B2C034AD5 +:102FC00043F8102C704700BF15060008D8230020D6 +:102FD00008B5FFF7DBFFBDE80840FFF76BBF000057 +:102FE000024BDB6898610F20FFF766BFD8230020F3 +:102FF000302383F31188FFF7F3BF000008B50146C3 +:10300000302383F311880820FFF764FF002383F344 +:10301000118808BD064BDB6839B1426818605A60F8 +:10302000136043600420FFF755BF4FF0FF30704737 +:10303000D823002038B504460D462068844200D1CC +:1030400038BD036823605C608561FFF733FFF4E7F8 +:1030500010B50A4C23699A6891420CD85A6881606D +:103060000360426010609A685860511A99604FF08E +:10307000FF33A36110BD1B68891AECE7D823002039 +:10308000C0E90323002310B410BC4361FFF7E0BF85 +:10309000036881689A680A449A60426813605A60BB +:1030A00000234FF0FF320360014B9A61704700BF6D +:1030B000D823002070B5124D2A46EB690133EB612D +:1030C00052F8103F934206D030269A68013A9A602F +:1030D0002C69A36803B170BDD4E900210A60516076 +:1030E000236083F311882046D4E90331984786F39F +:1030F000118861690029EBD02046FFF7A9FFE7E7B7 +:10310000D8230020054A30B5D369D2E908451B1BF6 +:10311000181945F10001C2E9080130BDD82300208B +:1031200000207047FEE70000704700004FF0FF30BE +:1031300070470000BFF34F8F024AD368DB07FCD40F +:10314000704700BF0020024008B5074B1B7853B9F9 +:10315000FFF7F0FF054B1A69120641BF044A5A6097 +:1031600002F188325A6008BD482500200020024044 +:103170002301674508B5054B1B7833B9FFF7DAFF24 +:10318000034A136943F08003136108BD48250020FA +:10319000002002407F289ABF00F500308002002006 +:1031A000704700004FF48060704700008020704737 +:1031B0007F2808B50BD8FFF7EDFF00F580630268A4 +:1031C000013204D104308342F9D1012008BD00202E +:1031D000FCE700007F2810B504461CD8FFF7AAFFC3 +:1031E000FFF7B2FFF3220D4B4FF48061DA60022249 +:1031F0001A61FFF7CFFF58611A6942F040021A6165 +:10320000FFF798FF00F02EF9FFF7B4FF2046BDE866 +:103210001040FFF7CDBF002010BD00BF00200240CE +:103220002DE9F843054612F00100144606D040F29D +:10323000033200201E4B1A60BDE8F8831D4BAA180C +:103240009A4204D94FF44272194B1A60F4E7FFF71F +:103250007BFF4FF00109FFF76DFFDFF85C806D1A0F +:10326000012C0F4605EB010603D8FFF783FF012071 +:10327000E2E73B88C8F8109033800020FFF75AFF40 +:10328000C8F81000338831F8022B9BB29A420CD058 +:1032900040F21F32064B1A60084B1E60084B1C6040 +:1032A000084B1F60FFF766FFC6E7023CD8E700BF88 +:1032B000442500200000020800200240382500209C +:1032C000402500203C250020084908B50B7828B18E +:1032D0001BB9FFF739FF01230B7008BD002BFCD091 +:1032E000BDE808400870FFF745BF00BF4825002033 +:1032F00038B5EFF31185BDBBEFF30584C4F30804C3 +:103300003023C4B183F31188FFF7FCFE44014B0165 +:10331000241A43EAD06363EB0103A2009B00121856 +:1033200043EA947341EB0301C900D00041EA5271B2 +:1033300085F3118838BD83F31188FFF7E3FE45015B +:103340004B012D1A43EAD06363EB0103AA009B00F3 +:10335000121843EA957341EB0301C900D00041EA1A +:10336000527184F3118838BDFFF7CCFE44014B0144 +:10337000241A43EAD06363EB0103A2009B001218F6 +:1033800043EA947341EB0301C900D00041EA527152 +:1033900038BD00BF38B5FFF7ABFF00230F4A104C14 +:1033A000C00840EA4170A0FB025EC908A0FB040C03 +:1033B000A1FB0440A1FB02121CEB050C5B411CEBC2 +:1033C000040C43EB000011EB0E0142F10002411826 +:1033D00042F10000090941EA007038BDA59BC420F4 +:1033E000CFF753E310B5094C013AD2B2FF2A00D10E +:1033F00010BD500854F82030013054F820009BB222 +:1034000043EA004341F8043BEEE700BF046C004090 +:1034100010B50748013AD2B2FF2A00D110BD0C887E +:10342000530840F823404C88013340F82340F1E72B +:10343000046C004007B50122002001A9FFF7D2FF6C +:10344000019803B05DF804FB13B50446FFF7F2FFE3 +:10345000A04205D00122002001A90194FFF7D8FF66 +:1034600002B010BD7047000045F25552064B1A607D +:1034700002225A6040F6FF729A604CF6CC421A6003 +:103480000122024B1A707047003000405025002086 +:10349000034B1B781BB14AF6AA22024B1A607047F5 +:1034A0005025002000300040044B1A682AB902F170 +:1034B000804202F50432526A1A6070474C2500209F +:1034C0004FF08072014B5A62704700BF00100240FB +:1034D00008B5FFF7E9FF024B1868C0F3407008BD5C +:1034E0004C25002008B5FFF7DFFF024B1868C0F33A +:1034F000007008BD4C250020EFF30983203383F3CF +:103500000988002383F3118870470000302080F37E +:10351000118862B60C4B0D4AD96821F4E0610904A8 +:10352000090C0A43DA60D3F8FC20094942F08072A2 +:10353000C3F8FC200A6842F001020A602022DA7710 +:1035400083F82200704700BF00ED00E00003FA0599 +:10355000001000E0302310B583F311880B4B5B683B +:1035600013F400630FD0EFF309844FF08073203C15 +:10357000E36184F30988FFF7CBFC10B1044BA3612E +:1035800010BD044BFBE783F31188F9E700ED00E081 +:10359000270600082A06000870470000FEE7000022 +:1035A0000A4B0B480B4A90420BD30B4BC11EDA1C43 +:1035B000121A22F003028B4238BF00220021FDF7CD +:1035C000EDBE53F8041B40F8041BECE73C3B00083D +:1035D000D4250020D4250020D4250020FEE70000BB +:1035E00070B5002504461A4B86B0586085620163A9 +:1035F0000E46FFF78BFF04F11003C4E904334FF0CC +:10360000FF33A361134BE561D9692B460A46204677 +:10361000C4E9082304F134018023C4E900440E4ABC +:10362000A560E5622565FFF7ABFC01230B4AE0606E +:1036300003750092726868460192B268CDE9022370 +:10364000074BCDE90435FFF7C3FC06B070BD00BFE2 +:1036500030250020D8230020CC3A0008D13A0008B9 +:10366000DD35000800F030B808B500F063F9FFF769 +:103670006FFCBDE80840FFF717BF0000704700006F +:103680004FF0FF310E4B1A6919611A6900221A6155 +:103690001869D868D960D968DA60DA68DA6942F0FE +:1036A0008052DA61DA69DA6942F00062DA61054A69 +:1036B000DB69136843F48073136000F01BB900BF2B +:1036C0000010024000700040194B1A6842F00102DD +:1036D0001A601A689007FCD51A6802F0F9021A609D +:1036E00000225A605A6812F00C0FFBD11A6842F49B +:1036F00080321A601A689103FCD55A6842F4E812C5 +:103700005A601A6842F080721A601A689201FCD5F9 +:103710001221084A5A60084A11605A6842F00202AF +:103720005A605A6802F00C02082AFAD1704700BFAA +:103730000010024000641D0000200240084A08B545 +:10374000516913680B4003F00103536123B1054A2B +:1037500013680BB150689847BDE80840FFF7FABE00 +:103760000004014054250020084A08B55169136837 +:103770000B4003F00203536123B1054A93680BB178 +:10378000D0689847BDE80840FFF7E4BE0004014058 +:1037900054250020084A08B5516913680B4003F00E +:1037A0000403536123B1054A13690BB1506998476B +:1037B000BDE80840FFF7CEBE0004014054250020BC +:1037C000084A08B5516913680B4003F008035361B8 +:1037D00023B1054A93690BB1D0699847BDE8084009 +:1037E000FFF7B8BE0004014054250020084A08B580 +:1037F000516913680B4003F01003536123B1054A6C +:10380000136A0BB1506A9847BDE80840FFF7A2BEA3 +:103810000004014054250020174B10B55A691C685C +:10382000144004F478725A61A30604D5134A936ACB +:103830000BB1D06A9847600604D5104A136B0BB1E0 +:10384000506B9847210604D50C4A936B0BB1D06B93 +:103850009847E20504D5094A136C0BB1506C9847A0 +:10386000A30504D5054A936C0BB1D06C9847BDE80D +:103870001040FFF76FBE00BF000401405425002038 +:103880001A4B10B55A691C68144004F47C425A6102 +:10389000620504D5164A136D0BB1506D9847230588 +:1038A00004D5134A936D0BB1D06D9847E00404D54D +:1038B0000F4A136E0BB1506E9847A10404D50C4A01 +:1038C000936E0BB1D06E9847620404D5084A136F0B +:1038D0000BB1506F9847230404D5054A936F0BB181 +:1038E000D06F9847BDE81040FFF734BE0004014098 +:1038F00054250020062108B50846FFF70FFA0621D7 +:103900000720FFF70BFA06210820FFF707FA062128 +:103910000920FFF703FA06210A20FFF7FFF9062125 +:103920001720FFF7FBF9BDE8084006212820FFF724 +:10393000F5B9000008B5FFF7A3FE054800F00CF844 +:10394000FFF70AFAFFF79AFEBDE8084000F002B858 +:10395000D83A000800F042B8002319461C4A013347 +:10396000102BC2E9001102F10802F8D1194B9A6933 +:1039700042F07D029A619B690268174BDA608268A7 +:103980005A6042681A60C26803F58063DA6042696F +:103990005A6002691A608269C3F80C24026AC3F88B +:1039A0000424C269C3F80024426AC3F80C28C26A1E +:1039B000C3F80428826AC3F80028026BC3F80C2CF1 +:1039C000826BC3F8042C426BC3F8002C704700BF15 +:1039D0005425002000100240000801404FF0E02371 +:1039E000044A08215A6100229A6107220B201A61B9 +:1039F000FFF7AAB93F19010008B5302383F31188F6 +:103A0000FFF7BCFA002383F3118808BD08B5FFF760 +:103A1000F3FFBDE80840FFF79DBD000010B5013978 +:103A20000244904201D1002005E0037811F8014FD3 +:103A3000A34201D0181B10BD0130F2E72DE9F0417F +:103A40009BB10446C91A1778014403F1FF3C8C422C +:103A5000204601D9002008E005780134BD42F6D1A6 +:103A60000CEB0405D618A54201D1BDE8F08115F88C +:103A7000018D16F801EDF045F5D0E8E7034611F8A1 +:103A8000012B03F8012B002AF9D170476F72672EC2 +:103A90006172647570696C6F742E663130332D41BC +:103AA000697273706565640040A2E4F16468910610 +:103AB0000041A3E5F2656992070000006330000051 +:103AC000BC3A000830240020302500206D61696E6A +:103AD0000069646C65000000001800004444414423 +:103AE0004454494401000000424444444444444492 +:103AF00000000000444444444444444400000000A6 +:103B00004444444444444444000000004444444485 +:103B10004444444400000000E803000000000000AA +:103B2000009C010000000000640000000000000094 +:0C3B300040420F00FE2A0100D2040000F9 :00000001FF diff --git a/Tools/bootloaders/f103-GPS_bl.bin b/Tools/bootloaders/f103-GPS_bl.bin index 5b6a77a88f3fd6..93f5cd3265c417 100755 Binary files a/Tools/bootloaders/f103-GPS_bl.bin and b/Tools/bootloaders/f103-GPS_bl.bin differ diff --git a/Tools/bootloaders/f103-GPS_bl.hex b/Tools/bootloaders/f103-GPS_bl.hex index 301d4e22175d65..d0268c3c3546fe 100644 --- a/Tools/bootloaders/f103-GPS_bl.hex +++ b/Tools/bootloaders/f103-GPS_bl.hex @@ -1,26 +1,26 @@ :020000040800F2 -:10000000000900202D080008B11C0008811C000810 -:100010009D1C0008811C0008951C00082F08000882 -:100020002F0800082F0800082F080008E5370008EF -:100030002F0800082F0800082F080008F93C0008C6 -:100040002F0800082F0800082F0800082F080008B4 -:100050002F0800082F080008293A0008553A000820 -:10006000813A0008AD3A0008D93A00082F08000884 -:100070002F0800082F0800082F0800082F08000884 -:100080002F0800082F0800082F080008AD2C0008D2 -:10009000192D00086D2D0008C12D0008053B000832 -:1000A0002F0800082F0800082F0800082F08000854 -:1000B0002F0800082F0800082F0800082F08000844 -:1000C0002F0800082F0800082F0800082F08000834 -:1000D0002F0800082F0800082F0800082F08000824 -:1000E0006D3B00082F0800082F0800082F080008A3 -:1000F0002F0800082F0800082F0800082F08000804 -:100100002F0800082F0800082F0800082F080008F3 -:100110002F0800082F0800082F0800082F080008E3 -:100120002F0800082F0800082F0800082F080008D3 -:100130002F0800082F0800082F0800082F080008C3 -:100140002F0800082F0800082F0800082F080008B3 -:100150002F0800082F0800082F0800082F080008A3 +:100000000009002025050008A11900087119000841 +:100010008D190008711900088519000827050008C6 +:10002000270500082705000827050008F9340008FF +:100030002705000827050008270500080D3A0008D5 +:1000400027050008270500082705000827050008E0 +:1000500027050008270500083D3700086937000814 +:1000600095370008C1370008ED370008270500085C +:1000700027050008270500082705000827050008B0 +:100080002705000827050008270500089D29000806 +:10009000092A00085D2A0008B12A0008193800085A +:1000A0002705000827050008270500082705000880 +:1000B0002705000827050008270500082705000870 +:1000C0002705000827050008270500082705000860 +:1000D0002705000827050008270500082705000850 +:1000E00081380008270500082705000827050008B3 +:1000F0002705000827050008270500082705000830 +:10010000270500082705000827050008270500081F +:10011000270500082705000827050008270500080F +:1001200027050008270500082705000827050008FF +:1001300027050008270500082705000827050008EF +:1001400027050008270500082705000827050008DF +:1001500027050008270500082705000827050008CF :100160004FF0FF0C1CEAD0521EBF1CEAD15392EA9A :100170000C0F93EA0C0F6FD01A4480EA010C400276 :1001800018BF5FEA41211ED04FF0006343EA5010D0 @@ -81,917 +81,870 @@ :1004F0009E03B3EB126209D44FEA002343F000439A :1005000023FA02F070474FF00000704712F1610FBC :1005100001D1420202D14FF0FF3070474FF000008E -:10052000704700BF53B94AB9002908BF00281CBF53 -:100530004FF0FF314FF0FF3000F076B9ADF1080C0D -:100540006DE904CE00F006F8DDF804E0DDE90223F1 -:1005500004B070472DE9F047089E0D4604468846D2 -:10056000002B4DD18A42944668D9B2FA82F252B138 -:1005700001FA02F3C2F1200120FA01F10CFA02FCA7 -:1005800041EA030894404FEA1C41B8FBF1F71FFA17 -:100590008CFE01FB178807FB0EF0230C43EA08438F -:1005A00098420AD91CEB030307F1FF3580F01E8146 -:1005B000984240F21B81023F63441B1AB3FBF1F0E7 -:1005C00001FB103300FB0EFEA4B244EA0344A6452F -:1005D0000AD91CEB040400F1FF3380F00981A64521 -:1005E00040F20681644402380021A4EB0E0440EA84 -:1005F00007401EB10023D440C6E90043BDE8F087A0 -:100600008B4208D9002E00F0EE800021C6E90005DB -:100610000846BDE8F087B3FA83F100294AD1AB421E -:1006200002D3824200F2FC80841A65EB03030120AE -:100630009846002EE2D0C6E90048DFE702B9FFDEA7 -:10064000B2FA82F2002A40F09180A1EB0C00012165 -:100650004FEA1C471FFA8CFEB0FBF7F307FB1300B1 -:10066000250C45EA00450EFB03F0A84208D91CEB17 -:10067000050503F1FF3802D2A84200F2CE804346BE -:100680002D1AB5FBF7F007FB10550EFB00FEA4B2C8 -:1006900044EA0544A64508D91CEB040400F1FF35E3 -:1006A00002D2A64500F2B6802846A4EB0E0440EA2A -:1006B00003409EE7C1F120078B4022FA07FC4CEA79 -:1006C000030C25FA07FA4FEA1C49BAFBF9F820FA9D -:1006D00007F309FB18AA8D401FFA8CFE1D4300FA90 -:1006E00001F308FB0EF02C0C44EA0A44A04202FA83 -:1006F00001F20BD91CEB040408F1FF3A80F088806A -:10070000A04240F28580A8F102086444241AB4FB98 -:10071000F9F009FB104400FB0EFEADB245EA0444BB -:10072000A64508D91CEB040400F1FF356CD2A645A0 -:100730006AD90238644440EA0840A0FB0295A4EB61 -:100740000E04AC42C846AE4656D353D0002E69D0F4 -:10075000B3EB080264EB0E0422FA01F304FA07F784 -:100760001F43CC40C6E90074002147E70CFA02FCA5 -:10077000C2F1200125FA01F34FEA1C4720FA01F1EA -:1007800095400D43B3FBF7F107FB11331FFA8CFEC5 -:10079000280C40EA034001FB0EF3834204FA02F402 -:1007A00008D91CEB000001F1FF382FD283422DD96C -:1007B00002396044C01AB0FBF7F307FB1300ADB277 -:1007C00045EA004503FB0EF0A84208D91CEB0505DD -:1007D00003F1FF3816D2A84214D9023B6544281A07 -:1007E00043EA014138E73146304607E72F46E4E661 -:1007F0001846F9E64B45A9D2B9EB020865EB0C0E99 -:100800000138A3E74346EAE7284694E74146D1E7A3 -:10081000D0467BE76444023847E7023B65442FE754 -:10082000084606E73146E9E6704700BF02E000F0FF -:1008300000F8FEE772B6264880F30888254880F362 -:100840000988254825490860022080F31488BFF3F1 -:100850006F8F03F017F803F07BF84FF05530204905 -:100860001B4A91423CBF41F8040BFAE71D49194A63 -:1008700091423CBF41F8040BFAE71B491B4A1C4B51 -:100880009A423EBF51F8040B42F8040BF8E70020EF -:100890001849194A91423CBF41F8040BFAE702F0AB -:1008A000F5FF03F057F8154C154DAC4203DA54F838 -:1008B000041B8847F9E700F03FF8124C124DAC4298 -:1008C00003DA54F8041B8847F9E702F0DDBF0000A3 -:1008D00000090020001100200000000808ED00E0E1 -:1008E0000001002000090020083E0008001100203F -:1008F0002411002028110020E025002060010008BC -:100900006001000860010008600100082DE9F04F57 -:10091000C1F80CD0C3689D46BDE8F08F002383F377 -:1009200011882846A047002002F010FDFEE702F0E3 -:1009300083FC00DFFEE70000F8B500F03DFE02F0AA -:10094000EFFE074602F03AFF0546002840D12C4B47 -:100950009F423DD001339F423DD02A4B27F0FF02FA -:100960009A423BD1F8B200F003FC2E4642F21074DA -:1009700000F004FC08B10024264601F007F988B312 -:100980000024032000F044F8264635B11E4B9F4258 -:1009900003D0002402F00AFF2646002002F0CAFE1F -:1009A0001A4B9B6813F0400322D00EB100F046F8BA -:1009B00000F044FC00F002FE01F07CF90546CCB1E9 -:1009C00001F078F9401BA04214D900F037F8F3E7A2 -:1009D0002E460024CCE704460126C9E706464FF41C -:1009E0007A74C5E7002CD0D04FF47A740126CCE796 -:1009F0001C46DDE700F0D4FC012002F0ADFCDEE790 -:100A0000010007B0000008B0263A09B0000C014010 -:100A1000084B187003280CD8DFE800F0080502081E -:100A2000022000F027BE022000F01CBE0022024B74 -:100A30005A607047281100202C11002038B501F0B1 -:100A4000A5F830B103221F4B1A7000221E4B5A60CA -:100A500038BD1E4B1E4A19680131F9D00433934248 -:100A6000F9D11C4C194DD4F80424AA42F0D31A4BE6 -:100A70009B6803F1006303F5C8439A42E8D202F091 -:100A800069FE02F07BFE002000F0B2FD0220FFF7BD -:100A9000BFFF124BDA690022DA61D96999699A615C -:100AA0009B6972B64FF0E023C3F8085D3021D4F89B -:100AB0000034D4F8042481F311889D4683F3088818 -:100AC0001047C5E7281100202C1100200064000801 -:100AD000206400080060000800110020001002409F -:100AE00049F26900084A136899B21B0C00FB0133F4 -:100AF00044F250611360054B186882B2000C01FB90 -:100B00000200186080B27047201100201C110020E4 -:100B100010B504460021102200F0C8FD034B03CBA2 -:100B2000206061601868A06010BD00BFE8F7FF1F7B -:100B30002DE9F0410026ADF54E7D6CAC40F275120A -:100B400007460D460EA831460D9600F0AFFD4FF456 -:100B5000C4723146204600F0A9FD01F0ABF84FF415 -:100B60007A72B0FBF2F0264B0DF13408186093E86E -:100B70000700022384E807000DF5E9702382FFF7E0 -:100B8000C7FF4EF603031F4907A8238403F0ECF8C0 -:100B900016230DF2E32284F832310DF12C0C07AB51 -:100BA0001E4603CE664510605160334602F10802CE -:100BB000F6D1306841461060B38820469380012208 -:100BC00000F0C0FD00230393AB7E80B2029305F1D9 -:100BD000190301930123CDE904800093384606A34D -:100BE000D3E90023E97E01F0ABFB0DF54E7DBDE8B6 -:100BF000F08100BFAFF300809E6AC421818A46EE77 -:100C000034110020783D00082DE9F041264D804642 -:100C10002B7A0C46DAB0FBB9204627A900F0A2FED9 -:100C20000746002836D19DF89D60C82E32D801466F -:100C30004FF4FA72284600F039FD32460DF19E015C -:100C400005F1090000F020FD9DF89C302E447772DC -:100C50002B720BB9E37E2B728122002106AD27A8EF -:100C600000F024FD0122294627A800F0B7FE00234A -:100C70000393A37E80B2029304F119030193282306 -:100C8000CDE904500093404605A3D3E90023E17E5B -:100C900001F056FB5AB0BDE8F08100BFAFF3008011 -:100CA00026417272DF25D7B77C210020F0B54FF4C2 -:100CB0008A750024234EF1B005FB006596F8D83004 -:100CC000D822214685F8DC3085F8E8403AA800F0C3 -:100CD000EDFC06F1090000F0E1FCD5F8E430C2B209 -:100CE00006AF8DF8F00006F109010DF1F100CDE934 -:100CF0003A3400F0C9FC394601223AA800F09AFEC5 -:100D000080B2CDE9047008230127CDE9023706F14E -:100D1000D80301933023317A00930B4807A3D3E91A -:100D2000002301F00DFBA04206DD00F0C3FFC5F873 -:100D3000E000384671B0F0BD2046FBE778F6339FFF -:100D400093CACD8D7C2100204C210020F0B51E4E91 -:100D50001E4F1F4D85B0304601F01EFB044660B3A8 -:100D600010220021684600F0A1FC4FF00003227B16 -:100D70006068A16862F303038DF8003002AB03C31F -:100D8000019B2268384662F31C0301939DF80030F2 -:100D90006A4643F020038DF800300023194602F024 -:100DA00087F9044620B9304601F0FAFA2C70D2E7F0 -:100DB0002B78072B03D801332B7005B0F0BD024808 -:100DC00001F0EEFAF9E700BF4C210020A823002033 -:100DD0007523002070B50D4614461E4601F00CFA2E -:100DE00050B9022E10D1012C0ED112A3D3E9002349 -:100DF0000120C5E9002307E0282C10D005D8012CDC -:100E000009D0052C0FD0002070BD302CFBD10BA3D6 -:100E1000D3E90023ECE70BA3D3E90023E8E70BA316 -:100E2000D3E90023E4E70BA3D3E90023E0E700BF05 -:100E3000AFF30080401DA12026812A0B78F6339F56 -:100E400093CACD8D9E6AC421818A46EE2641727274 -:100E5000DF25D7B7F017304A39059E5638B5054615 -:100E60000E4C0021013500F0E5FBA4F8F051B4F878 -:100E7000F00100F0C7FB78B1B4F8F00100F0D2FB4C -:100E8000014648B9B4F8F00100F0D4FBB4F8F031F1 -:100E90000133A4F8F031EAE738BD00BF7C2100201F -:100EA0002DE9F04F8DB000AF04460D4601F0A4F9D6 -:100EB000002846D12B7E022B1AD1EB8A012B17D1A9 -:100EC00000F0F8FE0646FFF70BFE4FF4C873B0FBC8 -:100ED000F3F202FB1303DFF878829BB206F5167675 -:100EE0003344C8F80030EB7E33B90022994B1A70B6 -:100EF0003437BD46BDE8F08F284607F11C0100F0ED -:100F0000EFFC0028F4D107F10C00FFF701FEBD7FD4 -:100F100007F10C012A4607F11F0002F0F5FE002838 -:100F2000E3D10F2D08D88B4B1D70D8F80030A3F5F6 -:100F30001673C8F80030DBE72046397F01F054F91A -:100F4000D6E7EB8A282B6BD010D8012B63D0052B6A -:100F5000CED1BFF34F8F8049804BCA6802F4E06264 -:100F60001343CB60BFF34F8F00BFFDE7302BBFD1E2 -:100F70007B4CEA7E237A9A42BAD194F8DC206B7ECD -:100F80009A42B5D1284604F1EA0100F07FFD0646F9 -:100F90000028ADD1012384F8E83000F08BFED4F8AE -:100FA000E030C01A192840F6B83338BF19209842EB -:100FB00028BF1846FFF73EFA6A49FFF7D1F8054601 -:100FC0002068FFF737FA6849FFF7CAF80146284654 -:100FD000FFF780F9FFF786FA20604FF48A7194F8E2 -:100FE000D9307B607A68636801FB02F5621992F878 -:100FF000E80050B1D2F8E400E946834215D000235E -:1010000082F8E830C2F8E030CD466368574A9B0A60 -:10101000013313816CE729462046FFF789FD67E716 -:1010200029462046FFF7F0FD62E7B2F8EC803B600E -:1010300008F1030A4FEA9A0A4FEA8A02D11DC90849 -:10104000A9EBC1039D46EB460021584600F02EFB5C -:1010500005F1EE0142465846214400F015FB3B687D -:1010600013B9012000F0C4FA94F8D20000F0CAFAD3 -:10107000054630B9207200F0E5FA284600F0B8FACB -:10108000C2E7D4F8D4303BB994F8D200B4F8F031C8 -:10109000834201D8FFF7E2FED4F8D43043449D42A6 -:1010A00008D294F8D200B4F8F0310130834201D86C -:1010B000FFF7D4FE594660685FFA8AF200F0FEFA44 -:1010C00008B9CD4689E7636894F8D2004344636069 -:1010D000D4F8D43008EB030AC4F8D4A000F092FA94 -:1010E000824509D394F8D230D4F8D4000133401BA0 -:1010F00084F8D230C4F8D400B8F1FF0F0FD800251F -:10110000257200F09FFA284600F072FA00F03EFDCA -:10111000164B188108B9FFF791FCCD46E8E64FF46D -:101120008A727B6894F8D90002FB0343D3F8E42069 -:1011300083F8E86002F58072C3F8E060C3F8E42049 -:10114000FFF7B4FDFFF702FE84F8D960B9E700BFEE -:10115000482100204521002000ED00E00400FA05B0 -:101160007C210020CDCCCC3D6666663F341100204A -:10117000014B1870704700BF4011002030B54FF090 -:101180000054254B226885B09A4207D002F020FB1C -:101190000446C0B90024204605B030BD0025627D5C -:1011A0001E4B1F481A70237DC92203721D49C0F8C7 -:1011B000E450093000F068FA2046E022294600F0A9 -:1011C00075FA0124E7E7184A184DD36943F0007314 -:1011D000D361AA6D164B9A42DCD12B6E013B7E2B5C -:1011E000D8D8144A01AB07CA83E807001846032180 -:1011F00000F09CFC6B6D83424FF00003CAD12A6D56 -:101200008A4203BFAB652A6E044B1C4601BF1A70AD -:10121000EA6D094B1A60BEE79AAD44C54011002043 -:101220007C210020160000200010024000660040D3 -:101230005041A0B058660040181100202DE9F0433D -:1012400085B000F0A3FC0223494C63710023029394 -:10125000484B2081D3F800C0BCF57A7F12D3464FAB -:10126000464BB7FBFCF59C458CBF0A231123B5FB0D -:10127000F3F603FB1652591EC8B2002A3ED00229CB -:101280000B46F4D89DF80B303D495A1E9DF80A30A4 -:101290003C48013B1B0443EA0253BDF80820013AD5 -:1012A00013434B6001F0F4FE00230193364B3749A2 -:1012B00000934FF48052364B364800F06BFF364BAC -:1012C000197811B1334800F08FFF00F0F3FC0546A8 -:1012D000FFF706FC4FF4C873B0FBF3F202FB1303F5 -:1012E00005F516709BB218442C4B186002F066FA94 -:1012F00008B10F23238105B0BDE8F083731EB3F559 -:10130000806FBFD24FF47A75C0EBC00E0EF10303AD -:101310004FEAE30909FB0555C3F3C703C11AC9B274 -:1013200009F101088844B5FBF8F5B5F5617F08D9E6 -:101330000EF1FF33C3F3C703C11A581E0F28C9B2F9 -:1013400014D84A1E072A8CBF00220122581800FB1D -:101350000660B7FBF0F7BC4594D1002A92D0ADF8F7 -:1013600008608DF80A308DF80B108BE71346EDE717 -:101370003411002018110020005125023F420F00B7 -:1013800010110020A8230020D50D000844110020D2 -:10139000A10E00084C21002040110020482100200F -:1013A0002DE9F04F80A7D7E900670FF20429D9E9AA -:1013B0000089734D93B00DF1300AFFF7C7FC182276 -:1013C0000021504600F072F9DFF8B8B16E4C0023EE -:1013D00052461946584601F093FE014650BB102272 -:1013E00008A800F063F9E36883F01003E36000F0FD -:1013F00063FC0DF1240C0B4612A9024611E903000F -:101400008CE803009DF83410C1F30300890649BF3E -:101410000E99BDF83810C1F31C0141F0004158BFCE -:10142000C1F30A018DF82C000891284608A901F0A3 -:1014300097F9CCE7284600F0DFFE0446002847D1A4 -:1014400000F038FCDFF844B1DBF8003098423FD3BD -:1014500000F030FC0790FFF743FB4FF4C873B0FB7C -:10146000F3F101FB1300079A83B202F516701844DA -:10147000CBF80000DFF818B18DF820409BF8001081 -:1014800011B901238DF8203050460791FFF740FB3A -:1014900007990DF12100C1F11004E4B2062C28BF18 -:1014A00006245144224600F0EFF808AB03931823BA -:1014B0000293384B013401930123E4B20093324686 -:1014C0003B462846049400F0DDFE00238BF80030F4 -:1014D00000F0F0FB304A314C1368C31AB3F57A7F41 -:1014E00030D3106000F0E8FB02460B46284600F0BF -:1014F00061FF284600F080FE20B3237ADFF8A0B019 -:10150000002B14BF032302238BF8053000F0D2FB1D -:101510004FF47A73B0FBF3F00122CBF80000514690 -:10152000584600F0B5F9182302931E4B80B2019380 -:1015300040F25513CDE903A0009342464B4628469E -:1015400000F0A0FE237ABBB100F0B4FB94F8E830C1 -:1015500073B9D4F8E03043B1C01A2368FA2B38BF0E -:10156000FA230533B0EB430F02D30020FFF79EFBB5 -:10157000237A002B7FF41FAF13B0BDE8F08F00BFBC -:101580004C210020A8230020000801404821002011 -:101590004521002044210020702300207C210020D0 -:1015A0003411002074230020401DA12026812A0B25 -:1015B000F1C6A7C1D068080F7047000070B501F0F0 -:1015C00095FF0024084E094D3080286833888342F7 -:1015D00008D901F087FF2B6804440133B4F5C84FE4 -:1015E0002B60F2D370BD00BFA4230020782300201D -:1015F00002F00AB800F10060920000F5C84001F066 -:10160000AFBF0000054B1A68054B1B889B1A83422D -:1016100002D9104401F066BF0020704778230020F3 -:10162000A4230020024B1B68184401F061BF00BFD7 -:1016300078230020024B1B68184401F06BBF00BFE9 -:1016400078230020064991F8243033B10023082282 -:10165000086A81F82430FFF7CDBF0120704700BF32 -:101660007C230020022802BF1022014B1A61704720 -:1016700000080140022802BF4FF48012014B1A619A -:10168000704700BF00080140002310B5934203D00B -:10169000CC5CC4540133F9E710BD00000346024698 -:1016A000D01A12F9011B0029FAD1704703460244EF -:1016B000934202D003F8011BFAE770472DE9F84383 -:1016C0001F4D144695F824200746884652BBDFF884 -:1016D00070909CB395F824302BB92022FF21484606 -:1016E0002F62FFF7E3FF95F824004146C0F108029E -:1016F000A24228BF224605EB8000D6B29200FFF737 -:10170000C3FF95F82430A41B1E44F6B2082E1744DC -:101710009044E4B285F82460DBD1FFF793FF002802 -:10172000D7D108E02B6A03EB82038342CFD0FFF7C7 -:1017300089FF0028CBD10020BDE8F8830120FBE71A -:101740007C2300202DE9F0470D46044600219046F9 -:10175000284640F27912FFF7A9FF234620220021F4 -:10176000284600F09FFF022220212846231D00F07A -:1017700099FF032222212846631D00F093FF0322D4 -:1017800025212846A31D00F08DFF10222821284680 -:1017900004F1080300F086FF08223821284604F1EE -:1017A000100300F07FFF08224021284604F11103B6 -:1017B00000F078FF08224821284604F1120300F0C7 -:1017C00071FF20225021284604F1140300F06AFF23 -:1017D00040227021284604F1180300F063FF08221C -:1017E000B021284604F1200300F05CFF0822B82154 -:1017F000284604F1210300F055FFC02604F122071A -:101800003B46314608222846083600F04BFFB6F525 -:10181000A07F07F10107F3D108223146284604F1E1 -:10182000320300F03FFF002704F1330A94F832300E -:101830004FEAC7099F4209F5A47615D3B8F1000F06 -:1018400008D131460722284604F5997300F02AFF93 -:1018500009F24F16274694F832213B1B93420CD3D2 -:10186000F01DC008BDE8F0870AEB070308223146E7 -:10187000284600F017FF0137D8E7314607F2331347 -:101880000822284600F00EFF08360137E3E7000083 -:1018900038B50C460021054621600346C4F8031004 -:1018A0002046202200F0FEFE20462B1D0222202191 -:1018B00000F0F8FE20466B1D0322222100F0F2FE0C -:1018C0002046AB1D0322252100F0ECFE204610220D -:1018D000282105F1080300F0E5FE072038BD0000CF -:1018E0000023F7B50E460546047F072200911946EE -:1018F00000F09AFD731C0093012200230721284663 -:1019000000F092FDC4B9B31C0093052223460821C0 -:10191000284600F089FD0D243746B278BB1B934260 -:1019200011D32B7FE01DC008AC8ABBB9A04294BF85 -:101930000020012003B0F0BDAB8A0824DB00083B87 -:10194000DB08B370E8E7FB1C214600930822002364 -:10195000284600F069FD08340137DEE7001B18BF98 -:101960000120E7E70023F7B50E46047F0822009127 -:101970001946054600F058FD731CC4B908220093AF -:1019800011462346284600F04FFD102401237278AB -:101990005F1C013B934211D32B7FE01DC008AC8A32 -:1019A000BBB9A04294BF0020012003B0F0BDAB8AB8 -:1019B0000824DB00083BDB087370E7E7F3192146D6 -:1019C000009308220023284600F02EFD08343B46F1 -:1019D000DDE7001B18BF0120E7E70000F8B50E4661 -:1019E00005461446002181223046FFF75FFE2B4654 -:1019F00008220021304600F055FE7CB9072208215C -:101A000030466B1C00F04EFE0F2401236A785F1CE9 -:101A1000013B934204D3E01DC008F8BD0824F4E75D -:101A20002146EB190822304600F03CFE08343B46C4 -:101A3000ECE70000F8B50E46054614460021CE221C -:101A40003046FFF733FE2B4628220021304600F0B7 -:101A500029FE7CB908222821304605F1080300F050 -:101A600021FE30242F462A7A7B1B934204D3E01DAB -:101A7000C008F8BD2824F5E7214607F1090308222C -:101A8000304600F00FFE08340137ECE7F7B5047F6D -:101A90000E460091012310220021054600F0C4FCEF -:101AA000C4B9B31C0093092223461021284600F034 -:101AB000BBFC192437467288BB1B9A4211D82B7F76 -:101AC000E01DC008AC8ABBB9A04294BF0020012031 -:101AD00003B0F0BDAB8A1024DB00103BDB08738041 -:101AE000E8E73B1D2146009308220023284600F02A -:101AF0009BFC08340137DEE7001B18BF0120E7E735 -:101B000030B5094D0A4491420DD011F8013B5840BF -:101B1000082340F30004013B2C4013F0FF0384EA48 -:101B20005000F6D1EFE730BD2083B8ED4FF0FF3322 -:101B3000F7B500EB81061946DFF848C0DFF848E04A -:101B4000B0421BD050F8042B01AF0192042217F8C9 -:101B5000014B81EA046108240D46DB184941013C30 -:101B6000002DBCBF83EA0C0381EA0E0114F0FF04D0 -:101B7000F2D1013A12F0FF02E9D1E1E7D843C943BB -:101B800003B0F0BD9336EAA9EBE1F042F7B56B463E -:101B9000354A106851686A4603C3082333493448FC -:101BA00002F0C2F8044690BB0A256B46314A106821 -:101BB00051686A4603C308232F492D4802F0B4F840 -:101BC0000446002847D00369B3F5CE3F43D8B0F8A8 -:101BD0006620B2F57A7F3ED1284A024402F15C01C8 -:101BE0008B4238D35C3B224900209E1AFFF788FFC6 -:101BF00007463246002004F16401FFF781FFA36825 -:101C00009F4228D1E368984208BF002523E003697A -:101C1000B3F5CE3F26D8428BB2F57A7F20D1174A52 -:101C2000024402F110018B4218D3103B10490020EE -:101C30009D1AFFF765FF06462A46002004F11801A9 -:101C4000FFF75EFFA3689E4202D1E368984201D08D -:101C50000D25AAE70025284603B0F0BD1025A4E70E -:101C60000C25A2E70B25A0E7903D0008DC9B0100B6 -:101C700000640008993D0008909B0100089CFFF754 -:101C8000EFF30983EFF30583014B9B6BFEE700BF86 -:101C900000ED00E008B5FFF7F3FF0000EFF3098364 -:101CA000EFF30583014B5B6BFEE700BF00ED00E047 -:101CB000FEE7000001F0E2BC01F0BABC2DE9F04102 -:101CC000456A15B94162BDE8F0814B68AC4623F026 -:101CD0006047C3F38A4616EA230638BF3E464FEAFA -:101CE000D37EC3F380782B465A68BEEBD27F22F0B6 -:101CF00060440AD0002A18DAA40CB44217D19D42DD -:101D00000FD10D60DEE71346EEE7A74207D102F0E0 -:101D10008044C2F3807242450BD054B1EFE708D241 -:101D2000EDE7CCF800100B60CDE7B44201D0B4422F -:101D3000E5D81A689C46002AE5D11960C3E700007F -:101D40002DE9F0474FF47F49089D01F007044FEA61 -:101D5000D508224405F0070500EBD100944201D1DB -:101D6000BDE8F08704F0070705F0070A57453E462F -:101D700038BF5646111BC6F108068E4228BF0E46D4 -:101D8000E108415C08EBD50E13F80EC0B94029FA02 -:101D900006F721FA0AF1FFB28CEA010147FA0AF7C5 -:101DA00039408CEA010C03F80EC034443544D5E7C1 -:101DB000082341F2210280EA012001B240000029FB -:101DC00080B203F1FF33B8BF504013F0FF03F4D1EA -:101DD0007047000038B50C468D18A54200D138BDBB -:101DE00014F8011BFFF7E4FFF7E700000346406823 -:101DF00048B1026899895A605A89013292B2914277 -:101E00005A8138BF9A81704770B504460D4688B034 -:101E1000202200216846FFF749FC20460495FFF781 -:101E2000E5FF024658B16B46054608AE1C4603CC9A -:101E3000B44228606960234605F10805F6D11046D2 -:101E400008B070BD082817D909280CD00A280CD072 -:101E50000B280CD00C280CD00D280CD00E2814BF49 -:101E60004020302070470C2070471020704714200D -:101E7000704718207047202070470000082817D9A5 -:101E80000C280CD910280CD914280CD918280CD9D6 -:101E900020280CD930288CBF0F200E207047092035 -:101EA00070470A2070470B2070470C2070470D20A8 -:101EB000704700002DE9F843078C0446072F1ED910 -:101EC000D0E9029800254FF6FF73C5F12006A5F171 -:101ED000200029FA05F108FA06F628FA00F0314345 -:101EE0000143C9B21846FFF763FF0835402D03468A -:101EF000EBD13A46E169BDE8F843FFF76BBF4FF617 -:101F0000FF70BDE8F883000010B54B6823B9CA8A9A -:101F100063F30902CA8210BD04691A681C60036178 -:101F2000C38A013BC3824A60EFE700002DE9F84F06 -:101F30001D46CB8A0F46C3F3090105298146924607 -:101F40000B4630D00020AAB207F11A049EB2042E2C -:101F50001FFA80F80FD8904503F1010306D3FB8ADE -:101F60000A4462F309030120FB821AE01AF80060B8 -:101F70000130E654EAE79045F1D21C23A1F1050BAC -:101F8000BBFBF3F203FB12BB7C681FFA8BF6002C41 -:101F900045D14846FFF72AFF044638B978606FF00C -:101FA0000200BDE8F88F4FF00008E6E70026066063 -:101FB00078604FF0000BADB2454510D90AEB08032D -:101FC000221D13F8011B08F101089155B1B21B291C -:101FD0001FFA88F82BD0454506F10106F1D8FB8A97 -:101FE000C3F30902154465F30903BCE71C4601323B -:101FF00092B22368002BF9D16B1F0B441C21B3FB59 -:10200000F1F301339BB29A42D3D2BBF1000FD0D18E -:102010004846FFF7EBFE20B9C4F800B0BFE7012245 -:10202000E7E7C0F800B05E4620600446C1E74545DA -:10203000D5D94846FFF7DAFE08B92060AFE7C0F807 -:1020400000B0002620600446B6E700002DE9F74FF7 -:102050001C465B69074688460092002B00F097807B -:10206000238C2BB1E269002A00F09180072B33D832 -:1020700007F10C00FFF7BAFE054628B96FF002051C -:10208000284603B0BDE8F08F14220021FFF70EFBB5 -:10209000228CE16905F10800FFF7F6FA208C48F080 -:1020A0000041013080B2FFF7E9FEFFF7CBFE0138B7 -:1020B00080B22084013028746369228C1B782A4402 -:1020C00003F01F0363F03F0313723846696029462B -:1020D000FFF7F4FD0125D3E74FF000094FF0800A28 -:1020E0004E464D4600F10C0301930198FFF77EFE2A -:1020F00083460028C2D014220021FFF7D7FA002E11 -:102100003BD10222009BABF808300BF1080E1FFAFE -:1021100082FC0CF10100BCF1060F218C80B201D8C9 -:102120008E422CD3FFF7AAFEFFF78CFE8E4208BF2B -:102130004FF0400A62690138127880B202F01F0243 -:1021400042EA49120BEB00014AEA020A013048F068 -:10215000004281F808A08BF8100059463846CBF8A9 -:102160000420FFF7ABFD238C0135B3424FF0000A8A -:102170002DB289F00109B8D182E70022C5E7E169F3 -:10218000895D01360EF80210B6B20132BFE76FF07A -:10219000010575E7F8B5044615460E4630220021C4 -:1021A0001F46FFF783FA069BB5F5001F6360079B88 -:1021B00028BF4FF6FF72A3624FF0000338BF6A09D1 -:1021C000A760E66197B204F110009A4206D8002396 -:1021D0000360A782E3822383E360F8BD06600133D6 -:1021E00030462036F1E7000003781BB94BB2002BD4 -:1021F000C8BF01707047000000787047F8B50C4602 -:10220000C969074611B9238C002B37D1257E1F2DB4 -:1022100034D8387828BB228C072A2CD8268A36F066 -:1022200003032BD14FF6FF70FFF7D4FD4FF6FF727B -:1022300020F001003602400446EA0565400C45EAFC -:102240004025234629463846FFF700FF002807DDD2 -:10225000626913780133DBB21F2B88BF0023137030 -:10226000F8BD218A2D0645EA012505432046FFF7E2 -:1022700021FE0246E5E76FF00300F1E76FF0010091 -:10228000EEE7000070B504461D4616468AB02822C7 -:1022900000216846FFF70AFABDF838306946ADF804 -:1022A00010300F9B204605939DF84030CDE9026524 -:1022B0008DF81830119B0793BDF84830ADF82030E9 -:1022C000FFF79CFF0AB070BD2DE9F041D3690546C8 -:1022D0000C4616460BB9138C5BBB377E1F2F28D8D4 -:1022E00095F80080B8F1000F26D03046FFF7E2FDE8 -:1022F0003378210241EAC33141EA0801338A41EAD5 -:10230000076141EA034102463346284641F0800115 -:10231000FFF79CFE00280ADD3378012B07D1726994 -:1023200013780133DBB21F2B88BF00231370BDE885 -:10233000F0816FF00100FAE76FF00300F7E70000AB -:10234000F0B504460D461E4617468BB028220021E4 -:102350006846FFF7ABF99DF84C3029465A1E5342A8 -:1023600053418DF800309DF840306A46ADF810308A -:10237000119B204605939DF84830CDE902768DF8F3 -:102380001830149B0793BDF85430ADF82030FFF798 -:102390009BFF0BB0F0BD0000406A00B104307047F5 -:1023A000436A1A68426202691A600361C38A013B88 -:1023B000C38270472DE9F041D0F8208014461D46B5 -:1023C00041460027174E09B9BDE8F081D1E9022343 -:1023D000A21A65EB0303964277EB03031ED2036A4E -:1023E0008B420DD1FFF790FD036A1B6803620369FE -:1023F0000B60C38A0161016A013B8846C382E2E740 -:10240000FFF782FD0B68C8F8003003690B60C38AD0 -:102410000161013BC382D8F80010D4E788460968FF -:10242000D1E700BF80841E002DE9F04F8BB00D4630 -:1024300014469B468046DDF85090002800F01A8133 -:10244000B9F1000F00F01681531E3F2B00F21281EC -:10245000012A03D1BBF1000F40F00C810023CDE92C -:102460000833B8F81430B5EBC30F4FEAC30703D3F2 -:1024700000200BB0BDE8F08F2B199F42D8F80C302C -:1024800036BF7F1B2746FFB21BB9D8F81030002B90 -:102490007BD0272D4ED8C5F12806B7424FF0000358 -:1024A00034BF3E46F6B2009329463246D8F80800BB -:1024B00008ABFFF745FCA7EB060A35445FFA8AFA3A -:1024C0002821B8F8143003F10053053BDB000493D6 -:1024D000D8F80C300393039B13B1BAF1000F2CD141 -:1024E000D8F8100040B1BAF1000F05D0524600965E -:1024F00008AB691AFFF724FC38B2002FB8D0660782 -:102500000AD00AAB03EBD40111F8083C624202F096 -:102510000702134101F8083C082C3DD9102C40F269 -:10252000B680202C40F2B880BBF1000F00F09D80F7 -:10253000082335E0BA460026C2E7049BE02B28BFFB -:10254000E02306930B44AB42059315D95A1B9245E1 -:1025500038BF5246039828BFD2B20096691A08AB1A -:1025600004300792FFF7ECFB079A1644AAEB020A25 -:102570001544F6B25FFA8AFA049B069A05999B1AEB -:102580000493039B1B680393A5E700933A462946EF -:10259000D8F8080008ABADE7BBF1000F13D001235A -:1025A000B4EBC30F6CD0082C12D89DF82030621EFB -:1025B00023FA02F2D50706D54FF0FF3202FA04F4EF -:1025C00023438DF820309DF8203089F8003050E703 -:1025D000102C12D8BDF82030621E23FA02F2D10767 -:1025E00006D54FF0FF3202FA04F42343ADF8203051 -:1025F000BDF82030A9F800303BE7202C0FD808990F -:10260000631E21FA03F3DA0705D54FF0FF3202FA11 -:1026100004F40C430894089BC9F8003029E7402CC7 -:102620002BD0DDE90865611EC4F12102A4F121036C -:1026300026FA01F105FA02F225FA03F311431943D0 -:10264000CB0712D50122A4F12003C4F1200102FA24 -:1026500003F322FA01F1A240524243EA010363EB81 -:10266000430332432B43CDE90823DDE90823C9E9BD -:102670000023FEE66FF00100FBE66FF00800F8E6CD -:10268000082CA0D9102CB3D9202CEED8C3E7BBF16D -:10269000000FADD0022383E7BBF1000FBBD00423B2 -:1026A0007EE70000012A30B5144638BF012200251C -:1026B000402A28BF402285B0012CCDE9025517D809 -:1026C0001B788DF8083053070AD004AB03EBD20512 -:1026D00015F8083C544204F00704A34005F8083CF0 -:1026E0000346009102A80021FFF72AFB05B030BD88 -:1026F000082CE5D9102C03D81B88ADF80830E2E788 -:10270000202C02D81B680293DDE7D3E90045CDE910 -:102710000245D8E710B5CB681BB98B600B618B8283 -:1027200010BD04691A681C600361C38A013BC3823F -:10273000CA60F0E703064CBFC0F3C0300220704708 -:1027400008B50246FFF7F6FF022806D15306C2F38A -:102750000F2001D100F0030008BDC2F30740FBE7E2 -:102760002DE9F04F93B0CDE903230A6804461046E3 -:10277000FFF7E0FF02280CBF0026C2F30626002A5E -:102780000D46824680F2F98112F0C04940F0F58191 -:10279000097B002900F0F181022803D02378B3429D -:1027A00040F0EE81C2F304631046069302F07F030B -:1027B0000593FFF7C5FF059B00224FEA83480023DE -:1027C00048EA0A48294448EA4668CE78CDE9082311 -:1027D000F309834648EA0008029367D0059B024646 -:1027E000009320465346676808A9B847002800F0C0 -:1027F000CA81276A4FB9414604F10C00FFF704FB78 -:10280000074690B96FF0020054E03B6998450DD03F -:102810003F68002FF9D1414604F10C00FFF7F4FAAC -:1028200007460028EED0236A3B60276297F817C05E -:1028300006F01F08CCF3840CACEB08001FFA80FEF6 -:102840000028B8BF0EF12000A8EB0C031FFA83FE8E -:10285000B8BF00B2002B0793BEBF0EF120031BB21E -:102860000793D7E9022152EA010338D04FF0000C58 -:10287000039BDFF8F8E19A1A049B63EB010196458C -:102880007CEB01032BD36B7B97F81AE0734519D1CE -:10289000029B002B78D0012821DC7868F8B9DFF89A -:1028A000D0C1944570EB010316D337E0276A27B9EE -:1028B0006FF00C0013B0BDE8F08F3B699845B5D0C0 -:1028C0003F68F4E76A4890427CEB010301D30020A3 -:1028D000F0E7029B002BFAD0079B0F2B17DCFA7D49 -:1028E000B30002F0030203F07C031343FB75394687 -:1028F0002046FFF709FB6B7BBB76029B3BB9FB7D58 -:10290000C3F38402013262F38603FB75D0E76A7B6E -:10291000BB7E9A42DBD1029B002B35D0B309022B40 -:1029200032D0039B1422BB60049B0021FB600DA8E6 -:10293000FEF7BCFE039B20460A93049BADF83EB015 -:102940000B932B1D0C932B7B8DF840A0013BDBB22E -:10295000ADF83C30069B8DF841808DF84230059BE8 -:102960000AA98DF8433094F82C3083F001038DF8D8 -:102970004430A3689847FB7DC3F38403013303F01D -:102980001F039B02FB82A2E7FB7DC6F34012B2EB62 -:10299000D31F40F0FB80C3F38403434540F0F9802C -:1029A000029A2B7BB609002A4DD0F20762D4032B82 -:1029B00040F2F280039BAE1DBB60049B3246FB607D -:1029C0002B7B3946033BDBB204F10C00FFF7AEFA78 -:1029D00000280CDA39462046FFF796FAFB7DC3F350 -:1029E0008403013303F01F039B02FB820AE7AB88D9 -:1029F000DDE908843B834FF6FF73C9F12000A9F19C -:102A0000200228FA09F104FA00F0014324FA02F244 -:102A100011431846C9B2FFF7CBF909F10809B9F11A -:102A2000400F0346E9D13146B8822A7B033AD2B23D -:102A3000FFF7D0F9FB7DB882DA43C2F3C01262F32C -:102A4000C713FB7543E7AEB92E1D013B324639462D -:102A5000DBB204F10C00FFF769FA0028BADB2A7B2D -:102A60003146013AB88AD2B2E2E700BF80841E0044 -:102A700040420F00F98A013BC1F309010429DAB28F -:102A80005DD80023281D07F11B069A4208D910F8CB -:102A900001CB013306F801C001310529DBB2F4D1C5 -:102AA000934228BF0023039938BF04330A91049945 -:102AB00038BFDBB20B9107F11B010C91796838BF6D -:102AC0005B190D910E93FB8AADF83EB0C3F3090379 -:102AD0001A44069BADF83C208DF84230059B8DF8DA -:102AE00040A08DF8433094F82C308DF8418083F06D -:102AF00001038DF8443000237B602A7BB88A013AB9 -:102B0000291DFFF767F93B8BB882834203D120462A -:102B1000A3680AA9984720460AA9FFF7FBFDFB7D99 -:102B2000BA8AC3F38403013303F01F039B02FB82C1 -:102B30003B8B9A420CBF00206FF01000BAE67B6816 -:102B4000002BADD0052001E033461C301E68002E5E -:102B5000FAD1091A081D2E1D184401EB090CBCF10D -:102B60001B0F5FFA89F39BD89A4299D916F8013B5B -:102B700009F1010900F8013BEFE76FF0090099E660 -:102B80006FF00A0096E66FF00B0093E66FF00D0011 -:102B900090E66FF00E008DE66FF00F008AE600BF42 -:102BA000F0B53F4D3F4FEB6943F00073EB61EB69CC -:102BB0003D4B9B6AD3F800623E4046F00106C3F8E5 -:102BC0000062D3F800423C4044EA002444F001048F -:102BD000C3F80042002955D000200646C3F81C0265 -:102BE000C3F80402C3F80C02C3F8140203EBC004D8 -:102BF00001300E28C4F84062C4F84462F6D10027C0 -:102C00004FF0010C9678148816F0010F18BFD3F816 -:102C100004E20CFA04F01CBF40EA0E0EC3F804E212 -:102C200016F0020F18BFD3F80CE203EBC4041CBF6C -:102C300040EA0E0EC3F80CE2760748BFD3F81462E0 -:102C400007F1010744BF0643C3F814625668B9424E -:102C5000C4F84062966802F10C02C4F84462D3F8EA -:102C60001C4240EA0400C3F81C02CBD1D3F8002276 -:102C700022F00102C3F80022EB6923F00073EB613C -:102C8000EB69F0BD0122C3F84012C3F84412C3F847 -:102C90000412C3F81412C3F80C22C3F81C22E5E78F -:102CA000001002400000FFFFA8230020184A08B5CA -:102CB000916A8B688B6013F0010104D013F00C0F44 -:102CC00018BF4FF48031D80506D513F4406F14BFF8 -:102CD00041F4003141F00201D80306D513F4402F2E -:102CE00014BF41F4802141F00401D3690BB10848BD -:102CF0009847302383F311880021064800F048FBF1 -:102D0000002383F31188BDE8084000F099BD00BF9F -:102D1000A8230020B023002038B5124CA36ADD6838 -:102D2000AA0712D05A6922F002025A61A36913B1AC -:102D3000012120469847302383F3118800210A4857 -:102D400000F026FB002383F31188EB0606D5102143 -:102D5000A36AD960236A0BB102489847BDE838409E -:102D600000F06EBDA8230020B823002038B5124C17 -:102D7000A36A1D69AA0712D05A6922F010025A618B -:102D8000A36913B1022120469847302383F31188A9 -:102D900000210A4800F0FCFA002383F31188EB06B7 -:102DA00006D51021A36A1961236A0BB1024898471E -:102DB000BDE8384000F044BDA8230020B82300201F -:102DC00038B50F4CA36A5D682A075D600AD50422F6 -:102DD00022701A6822F002021A60636A13B100219D -:102DE000204698476B0706D5A36A9969236A13B1F1 -:102DF000034809049847BDE8384000F021BD00BFF2 -:102E0000A823002010B50E4C204600F02FF90D4BE2 -:102E10000B211320A36200F009F90B21142000F00C -:102E200005F90B21152000F001F90B21162000F007 -:102E3000FDF8BDE8104000220E201146FFF7B0BE9D -:102E4000A8230020006400400F4B10B598420446B0 -:102E500005D10E4BDA6942F00072DA61DB690122BA -:102E6000A36A1A60A36A5A68D20707D562685168D4 -:102E70001268D9611A60064A5A6110BD0121082002 -:102E800000F0B0F9EEE700BFA823002000100240D8 -:102E90005B87010003291AD8DFE801F0020A0F144A -:102EA000836A9B6813F0E05F14BF01200020704725 -:102EB000836A9868C0F380607047836A9868C0F33B -:102EC000C0607047836A9868C0F300707047002044 -:102ED0007047000010B5032927D8DFE801F002276A -:102EE0002B2F836A9968C1F30161183103EB011339 -:102EF0001078840648BF5468C0F3001158BF948806 -:102F00004FEA410148BF41EAC40100F00F00586098 -:102F100048BF41F00401906858BF41EA4451D2686B -:102F200041F001019860DA60196010BD836A03F511 -:102F3000C073DDE7836A03F5C873D9E7836A03F5D5 -:102F4000D073D5E701290AD002290FD081B9836A4D -:102F5000DA68920701D1186903E001207047836A9B -:102F6000D86810F0030018BF01207047836AF2E7A9 -:102F70000020704710B539B9836AD96889071BD119 -:102F80001B699C0704D110BD012915D00229FAD173 -:102F9000816AD1F8C031D1F8C441D1F8C8011061BB -:102FA000D1F8CC015061202008610869800717D151 -:102FB000486940F0100012E0816AD1F8B031D1F8D0 -:102FC000B441D1F8B8011061D1F8BC0150612020A2 -:102FD000C860C868800703D1486940F002004861B2 -:102FE000C3F34000C3F38001000140EA41111079AE -:102FF00020F030000143117189064BBF916811899F -:10300000DB085B0D4CBF63F31C0163F30A0113790A -:1030100048BF916064F3030313714FEA14234FEA2E -:10302000144458BF118113705480ACE70122090188 -:1030300000F1604303F56143C9B283F8001300F067 -:103040001F039A4043099B0003F1604303F561436A -:10305000C3F880211A607047090100F16040C9B2CD -:1030600000F56D4001767047FFF7CCBE0123037079 -:10307000002300F10802C0E9022200F11002C0E9B9 -:103080000422C0E90633C0E90833436070470000FA -:1030900010B53023044683F3118802234160037086 -:1030A000FFF7D2FE04230020237080F3118810BDA7 -:1030B0002DE9F0411F4604460D461646302383F3A2 -:1030C000118800F108082378052B0DD029462046E9 -:1030D000FFF7E0FE40B1204632462946FFF7FAFEF0 -:1030E000002080F3118808E03946404600F040F99E -:1030F0000028E8D0002383F31188BDE8F0810000A8 -:103100002DE9F0411F4604460D461646302383F351 -:10311000118800F110082378052B0DD02946204690 -:10312000FFF710FF40B1204632462946FFF722FF45 -:10313000002080F3118808E03946404600F018F975 -:103140000028E8D0002383F31188BDE8F081000057 -:1031500000238268037503691B6899689142FBD25A -:103160005A680360426010605860704700238268AC -:10317000037503691B6899689142FBD85A6803601C -:10318000426010605860704708B50846302383F3EA -:1031900011880B7D032B05D0042B0DD02BB983F3A5 -:1031A000118808BD00228B691A604FF0FF338361DC -:1031B000FFF7CEFF0023F2E7D1E9003213605A6037 -:1031C000F3E70000FFF7C4BF054BD968087518681E -:1031D000026853601A6001220275D860FDF796BB41 -:1031E000D823002030B50C4B0446DD684B1C87B05B -:1031F0000FD02B466846094A00F0F0F82046FFF74A -:10320000E3FF009B13B1684600F0F0F8A86907B02F -:1032100030BDFFF7D9FFF9E7D82300208931000836 -:10322000044B1A68DB6890689B68984294BF002042 -:1032300001207047D8230020084B10B51C68D868BF -:10324000226853601A6001222275DC60FFF78EFF4E -:1032500001462046BDE81040FDF758BBD8230020AA -:10326000044B1A68DB6892689B689A4201D9FFF7A1 -:10327000E3BF7047D823002038B501230025064C52 -:10328000064907482370656000F020FB0223237085 -:1032900085F3118838BD00BF30250020A83D000807 -:1032A000D823002000F0B4B8EFF3118020B9EFF379 -:1032B0000583302282F311887047000010B530B9C1 -:1032C000EFF30584C4F3080414B180F3118810BD32 -:1032D000FFF7C6FF84F31188F9E700008B60022333 -:1032E00008618B82084670478368A3F1440243F863 -:1032F000142C026943F8442C426943F8402C094AD3 -:1033000043F8242CC268A3F1200043F8182C0222B1 -:1033100003F80C2C002203F80B2C034A43F8102C62 -:10332000704700BF1D090008D823002008B5FFF72B -:10333000DBFFBDE80840FFF745BF0000024BDB683C -:1033400098610F20FFF740BFD8230020302383F37C -:103350001188FFF7F3BF000008B50146302383F35F -:1033600011880820FFF73EFF002383F3118808BD72 -:10337000064BDB6839B1426818605A6013604360DD -:103380000420FFF72FBF4FF0FF307047D8230020F5 -:1033900038B504460D462068844200D138BD036824 -:1033A00023605C608561FFF70DFFF4E710B50A4C00 -:1033B00023699A6891420CD85A6881600360426020 -:1033C00010609A685860511A99604FF0FF33A361FA -:1033D00010BD1B68891AECE7D8230020C0E903233D -:1033E000002310B410BC4361FFF7E0BF036881689D -:1033F0009A680A449A60426813605A6000234FF04A -:10340000FF320360014B9A61704700BFD823002050 -:1034100070B5124D2A46EB690133EB6152F8103F4B -:10342000934206D030269A68013A9A602C69A368C4 -:1034300003B170BDD4E900210A605160236083F3B9 -:1034400011882046D4E90331984786F311886169D1 -:103450000029EBD02046FFF7A9FFE7E7D82300209B -:1034600000207047FEE70000704700004FF0FF307B -:1034700070470000BFF34F8F024AD368DB07FCD4CC -:10348000704700BF0020024008B5074B1B7853B9B6 -:10349000FFF7F0FF054B1A69120641BF044A5A6054 -:1034A00002F188325A6008BD482500200020024001 -:1034B0002301674508B5054B1B7833B9FFF7DAFFE1 -:1034C000034A136943F08003136108BD48250020B7 -:1034D000002002407F289ABF00F5003080020020C3 -:1034E000704700004FF480607047000080207047F4 -:1034F0007F2808B50BD8FFF7EDFF00F58063026861 -:10350000013204D104308342F9D1012008BD0020EA -:10351000FCE700007F2810B504461CD8FFF7AAFF7F -:10352000FFF7B2FFF3220D4B4FF48061DA60022205 -:103530001A61FFF7CFFF58611A6942F040021A6121 -:10354000FFF798FF00F004F9FFF7B4FF2046BDE84D -:103550001040FFF7CDBF002010BD00BF002002408B -:103560002DE9F843054612F00100144606D040F25A -:10357000F32200201E4B1A60BDE8F8831D4BAA18E9 -:103580009A4204D94FF43E72194B1A60F4E7FFF7E0 -:103590007BFF4FF00109FFF76DFFDFF85C806D1ACC -:1035A000012C0F4605EB010603D8FFF783FF01202E -:1035B000E2E73B88C8F8109033800020FFF75AFFFD -:1035C000C8F81000338831F8022B9BB29A420CD015 -:1035D00040F20F32064B1A60084B1E60084B1C600D -:1035E000084B1F60FFF766FFC6E7023CD8E700BF45 -:1035F0004425002000000208002002403825002059 -:10360000402500203C250020084908B50B7828B14A -:103610001BB9FFF739FF01230B7008BD002BFCD04D -:10362000BDE808400870FFF745BF00BF48250020EF -:1036300070B5FFF739FE4FF47A710D4B0D4EDB6913 -:10364000326801FB03F3934237BF0B4A0A495168C2 -:10365000156836BF4C1CD1E9005454605D1944F123 -:1036600000043360FFF72AFE2846214670BD00BFE4 -:10367000D82300204C2500205025002070B5FFF7EE -:1036800013FE4FF47A710F4B0F4EDB69326801FB6A -:1036900003F3934237BF0D4A0C49516815683ABF8E -:1036A0004C1C5460D1E900545D1944F100043360AE -:1036B000FFF704FE4FF47A72002328462146FCF7F8 -:1036C00031FF70BDD82300204C250020502500205C -:1036D00010B5094C013AD2B2FF2A00D110BD5008F2 -:1036E00054F82030013054F820009BB243EA0043E4 -:1036F00041F8043BEEE700BF046C004010B50748FA -:10370000013AD2B2FF2A00D110BD0C88530840F80C -:1037100023404C88013340F82340F1E7046C00401B -:1037200007B50122002001A9FFF7D2FF019803B0DD -:103730005DF804FB13B50446FFF7F2FFA04205D085 -:103740000122002001A90194FFF7D8FF02B010BDAB -:103750007047000045F25552064B1A6002225A602B -:1037600040F6FF729A604CF6CC421A600122024B7E -:103770001A707047003000405C250020034B1B7816 -:103780001BB14AF6AA22024B1A6070475C25002042 -:1037900000300040044B1A682AB902F1804202F559 -:1037A0000432526A1A607047582500204FF0807228 -:1037B000014B5A62704700BF0010024008B5FFF786 -:1037C000E9FF024B1868C0F3407008BD582500207F -:1037D00008B5FFF7DFFF024B1868C0F3007008BDA3 -:1037E00058250020EFF30983203383F30988002351 -:1037F00083F3118870470000302080F3118862B68F -:103800000C4B0D4AD96821F4E0610904090C0A4304 -:10381000DA60D3F8FC20094942F08072C3F8FC203A -:103820000A6842F001020A602022DA7783F8220057 -:10383000704700BF00ED00E00003FA05001000E053 -:10384000302310B583F311880B4B5B6813F40063CE -:103850000FD0EFF309844FF08073203CE36184F3D1 -:103860000988FFF7DDFC10B1044BA36110BD044BC8 -:10387000FBE783F31188F9E700ED00E02F0900086A -:103880003209000870470000FEE700000A4B0B48B1 -:103890000B4A90420BD30B4BC11EDA1C121A22F0BA -:1038A00003028B4238BF00220021FDF7FFBE53F810 -:1038B000041B40F8041BECE72C3E0008E025002028 -:1038C000E0250020E0250020FEE7000070B500257F -:1038D00004461A4B86B05860856201630E46FFF7B6 -:1038E0008BFF04F11003C4E904334FF0FF33A361ED -:1038F000134BE561D9692B460A462046C4E90823E3 -:1039000004F134018023C4E900440E4AA560E56255 -:103910002565FFF7E3FC01230B4AE0600375009285 -:10392000726868460192B268CDE90223074BCDE97F -:103930000435FFF7FBFC06B070BD00BF302500204A -:10394000D8230020B43D0008B93D0008C93800085C -:1039500000F030B808B500F063F9FFF78DFCBDE862 -:103960000840FFF717BF0000704700004FF0FF311D -:103970000E4B1A6919611A6900221A611869D86810 -:10398000D960D968DA60DA68DA6942F08052DA61BF -:10399000DA69DA6942F00062DA61054ADB691368C4 -:1039A00043F48073136000F01BB900BF00100240A5 -:1039B00000700040194B1A6842F001021A601A6840 -:1039C0009007FCD51A6802F0F9021A6000225A60CA -:1039D0005A6812F00C0FFBD11A6842F480321A6058 -:1039E0001A689103FCD55A6842F4E8125A601A68C2 -:1039F00042F080721A601A689201FCD51221084ABE -:103A00005A60084A11605A6842F002025A605A68C5 -:103A100002F00C02082AFAD1704700BF00100240E1 -:103A200000641D0000200240084A08B5516913686F -:103A30000B4003F00103536123B1054A13680BB136 -:103A400050689847BDE80840FFF7FABE00040140FF -:103A500060250020084A08B5516913680B4003F03F -:103A60000203536123B1054A93680BB1D0689847AC -:103A7000BDE80840FFF7E4BE0004014060250020D7 -:103A8000084A08B5516913680B4003F004035361F9 -:103A900023B1054A13690BB150699847BDE8084046 -:103AA000FFF7CEBE0004014060250020084A08B59B -:103AB000516913680B4003F00803536123B1054AB1 -:103AC00093690BB1D0699847BDE80840FFF7B8BECD -:103AD0000004014060250020084A08B551691368B8 -:103AE0000B4003F01003536123B1054A136A0BB175 -:103AF000506A9847BDE80840FFF7A2BE00040140A5 -:103B000060250020174B10B55A691C68144004F456 -:103B100078725A61A30604D5134A936A0BB1D06A2E -:103B20009847600604D5104A136B0BB1506B984749 -:103B3000210604D50C4A936B0BB1D06B9847E20574 -:103B400004D5094A136C0BB1506C9847A30504D5F2 -:103B5000054A936C0BB1D06C9847BDE81040FFF755 -:103B60006FBE00BF00040140602500201A4B10B555 -:103B70005A691C68144004F47C425A61620504D5F9 -:103B8000164A136D0BB1506D9847230504D5134A9F -:103B9000936D0BB1D06D9847E00404D50F4A136EB6 -:103BA0000BB1506E9847A10404D50C4A936E0BB12B -:103BB000D06E9847620404D5084A136F0BB1506F5A -:103BC0009847230404D5054A936F0BB1D06F9847EB -:103BD000BDE81040FFF734BE00040140602500201E -:103BE000062108B50846FFF721FA06210720FFF74E -:103BF0001DFA06210820FFF719FA06210920FFF710 -:103C000015FA06210A20FFF711FA06211720FFF7FF -:103C10000DFABDE8084006212820FFF707BA00008A -:103C200008B5FFF7A3FE054800F00CF8FFF71CFAF3 -:103C3000FFF79AFEBDE8084000F002B8C03D00085A -:103C400000F042B8002319461C4A0133102BC2E988 -:103C5000001102F10802F8D1194B9A6942F07D0275 -:103C60009A619B690268174BDA6082685A60426801 -:103C70001A60C26803F58063DA6042695A600269BB -:103C80001A608269C3F80C24026AC3F80424C2696A -:103C9000C3F80024426AC3F80C28C26AC3F8042897 -:103CA000826AC3F80028026BC3F80C2C826BC3F83D -:103CB000042C426BC3F8002C704700BF6025002025 -:103CC00000100240000801404FF0E023044A0821A0 -:103CD0005A6100229A6107220B201A61FFF7BCB9D2 -:103CE0003F19010008B5302383F31188FFF7DAFA92 -:103CF000002383F3118808BD08B5FFF7F3FFBDE883 -:103D00000840FFF79DBD000010B501390244904204 -:103D100001D1002005E0037811F8014FA34201D042 -:103D2000181B10BD0130F2E72DE9F0419BB10446AC -:103D3000C91A1778014403F1FF3C8C42204601D98F -:103D4000002008E005780134BD42F6D10CEB0405F3 -:103D5000D618A54201D1BDE8F08115F8018D16F8FD -:103D600001EDF045F5D0E8E7034611F8012B03F823 -:103D7000012B002AF9D170476F72672E617264754A -:103D800070696C6F742E663130332D4750530000CC -:103D900040A2E4F1646891060041A3E5F2656992EE -:103DA0000700000063300000A43D0008302400201C -:103DB000302500206D61696E0069646C650000004B -:103DC00000180000444441444454494401000000A8 -:103DD00042444444444444440000000044444444B5 -:103DE00044444444000000004444444444444444A3 -:103DF00000000000444444444444444458C7FF7F06 -:103E00000100000000000000E803000000000000C6 -:103E1000009C0100000000006400000000000000A1 -:0C3E200040420F00FE2A0100D204000006 +:10052000704700BF02E000F000F8FEE772B6264810 +:1005300080F30888254880F3098825482549086004 +:10054000022080F31488BFF36F8F03F025F803F0C7 +:1005500089F84FF0553020491B4A91423CBF41F881 +:10056000040BFAE71D49194A91423CBF41F8040BBC +:10057000FAE71B491B4A1C4B9A423EBF51F8040B39 +:1005800042F8040BF8E700201849194A91423CBF91 +:1005900041F8040BFAE703F003F803F065F8154C93 +:1005A000154DAC4203DA54F8041B8847F9E700F014 +:1005B0003FF8124C124DAC4203DA54F8041B884742 +:1005C000F9E702F0EBBF0000000900200011002055 +:1005D0000000000808ED00E00001002000090020F4 +:1005E000103B0008001100202411002028110020D9 +:1005F000D4250020600100086001000860010008A7 +:10060000600100082DE9F04FC1F80CD0C3689D4689 +:10061000BDE8F08F002383F311882846A04700200F +:1006200002F0E6FCFEE702F07FFC00DFFEE70000E0 +:10063000F8B500F03BFE02F0FDFE074602F048FF71 +:10064000064600283ED12B4B9F423BD001339F42B0 +:100650003BD0294B27F0FF029A4239D1F8B200F083 +:1006600001FC354642F2107400F002FC08B100248F +:10067000254601F003F978B30024032000F042F886 +:10068000254636B11D4B9F4203D0002402F018FFCF +:100690002546002002F0D8FE194B9B6813F040035A +:1006A0001FD00DB100F044F800F042FC01F07AF9DF +:1006B0000546C4B101F076F9401BA04213D900F001 +:1006C00037F8F3E735460024CEE704460125CBE7AB +:1006D00005464FF47A74C7E7B4F57A7F08BF012561 +:1006E000CFE71C46E0E700F0D5FC012002F086FCD5 +:1006F000DFE700BF010007B0000008B0263A09B0EC +:10070000000C0140084B187003280CD8DFE800F0FB +:1007100008050208022000F025BE022000F01ABEE3 +:100720000022024B5A607047281100202C11002033 +:1007300038B501F0A3F830B103221F4B1A70002224 +:100740001E4B5A6038BD1E4B1E4A19680131F9D044 +:1007500004339342F9D11C4C194DD4F80424AA4215 +:10076000F0D31A4B9B6803F1006303F5C8439A4228 +:10077000E8D202F079FE02F08BFE002000F0B0FD1E +:100780000220FFF7BFFF124BDA690022DA61D96954 +:1007900099699A619B6972B64FF0E023C3F8085DCE +:1007A0003021D4F80034D4F8042481F311889D4614 +:1007B00083F308881047C5E7281100202C1100207A +:1007C0000064000820640008006000080011002098 +:1007D0000010024049F26900084A136899B21B0CE4 +:1007E00000FB013344F250611360054B186882B27C +:1007F000000C01FB0200186080B27047201100203D +:100800001C11002010B504460021102200F0C6FD86 +:10081000034B03CB206061601868A06010BD00BF6F +:10082000E8F7FF1F2DE9F0410026ADF54E7D6CACD9 +:1008300040F2751207460D460EA831460D9600F09F +:10084000ADFD4FF4C4723146204600F0A7FD01F023 +:10085000A9F84FF47A72B0FBF2F0264B0DF1340890 +:10086000186093E80700022384E807000DF5E9709B +:100870002382FFF7C7FF4EF603031F4907A823840F +:1008800003F0FCF816230DF2E32284F832310DF167 +:100890002C0C07AB1E4603CE6645106051603346F4 +:1008A00002F10802F6D1306841461060B388204654 +:1008B0009380012200F0BEFD00230393AB7E80B243 +:1008C000029305F1190301930123CDE904800093FC +:1008D000384606A3D3E90023E97E01F0A9FB0DF514 +:1008E0004E7DBDE8F08100BFAFF300809E6AC42159 +:1008F000818A46EE341100208C3A00082DE9F0413F +:10090000264D80462B7A0C46DAB0FBB9204627A943 +:1009100000F0A0FE0746002836D19DF89D60C82E45 +:1009200032D801464FF4FA72284600F037FD3246BD +:100930000DF19E0105F1090000F01EFD9DF89C30AF +:100940002E4477722B720BB9E37E2B728122002129 +:1009500006AD27A800F022FD0122294627A800F0B5 +:10096000B5FE00230393A37E80B2029304F1190322 +:1009700001932823CDE904500093404605A3D3E911 +:100980000023E17E01F054FB5AB0BDE8F08100BFC6 +:10099000AFF3008026417272DF25D7B77C2100209B +:1009A000F0B54FF48A750024234EF1B005FB0065C5 +:1009B00096F8D830D822214685F8DC3085F8E84012 +:1009C0003AA800F0EBFC06F1090000F0DFFCD5F8D6 +:1009D000E430C2B206AF8DF8F00006F109010DF166 +:1009E000F100CDE93A3400F0C7FC394601223AA8BB +:1009F00000F098FE80B2CDE9047008230127CDE90C +:100A0000023706F1D80301933023317A00930B4863 +:100A100007A3D3E9002301F00BFBA04206DD00F0A1 +:100A2000C1FFC5F8E000384671B0F0BD2046FBE7D5 +:100A300078F6339F93CACD8D7C2100204C21002075 +:100A4000F0B51E4E1E4F1F4D85B0304601F01CFB09 +:100A5000044660B310220021684600F09FFC4FF06E +:100A60000003227B6068A16862F303038DF8003005 +:100A700002AB03C3019B2268384662F31C03019357 +:100A80009DF800306A4643F020038DF800300023C3 +:100A9000194602F085F9044620B9304601F0F8FA0B +:100AA0002C70D2E72B78072B03D801332B7005B0BD +:100AB000F0BD024801F0ECFAF9E700BF4C2100203C +:100AC000A82300207523002070B50D4614461E464D +:100AD00001F00AFA50B9022E10D1012C0ED112A346 +:100AE000D3E900230120C5E9002307E0282C10D01A +:100AF00005D8012C09D0052C0FD0002070BD302C5A +:100B0000FBD10BA3D3E90023ECE70BA3D3E900232C +:100B1000E8E70BA3D3E90023E4E70BA3D3E9002321 +:100B2000E0E700BFAFF30080401DA12026812A0B23 +:100B300078F6339F93CACD8D9E6AC421818A46EE92 +:100B400026417272DF25D7B7F017304A39059E5615 +:100B500038B505460E4C0021013500F0E3FBA4F842 +:100B6000F051B4F8F00100F0C5FB78B1B4F8F00131 +:100B700000F0D0FB014648B9B4F8F00100F0D2FB18 +:100B8000B4F8F0310133A4F8F031EAE738BD00BF22 +:100B90007C2100202DE9F04F8DB000AF04460D46BA +:100BA00001F0A2F9002846D12B7E022B1AD1EB8A44 +:100BB000012B17D100F0F6FE0646FFF70BFE4FF4AF +:100BC000C873B0FBF3F202FB1303DFF878829BB229 +:100BD00006F516763344C8F80030EB7E33B90022B0 +:100BE000994B1A703437BD46BDE8F08F284607F19F +:100BF0001C0100F0EDFC0028F4D107F10C00FFF718 +:100C000001FEBD7F07F10C012A4607F11F0002F02B +:100C100005FF0028E3D10F2D08D88B4B1D70D8F8A5 +:100C20000030A3F51673C8F80030DBE72046397FA3 +:100C300001F052F9D6E7EB8A282B6BD010D8012BA4 +:100C400063D0052BCED1BFF34F8F8049804BCA684C +:100C500002F4E0621343CB60BFF34F8F00BFFDE7A8 +:100C6000302BBFD17B4CEA7E237A9A42BAD194F8DA +:100C7000DC206B7E9A42B5D1284604F1EA0100F0EF +:100C80007DFD06460028ADD1012384F8E83000F050 +:100C900089FED4F8E030C01A192840F6B83338BFBE +:100CA0001920984228BF1846FFF7C4FB6A49FFF78E +:100CB00057FA05462068FFF7BDFB6849FFF750FA71 +:100CC00001462846FFF706FBFFF70CFC20604FF4B7 +:100CD0008A7194F8D9307B607A68636801FB02F509 +:100CE000621992F8E80050B1D2F8E400E946834274 +:100CF00015D0002382F8E830C2F8E030CD466368B2 +:100D0000574A9B0A013313816CE729462046FFF7B7 +:100D100089FD67E729462046FFF7F0FD62E7B2F854 +:100D2000EC803B6008F1030A4FEA9A0A4FEA8A0214 +:100D3000D11DC908A9EBC1039D46EB4600215846C9 +:100D400000F02CFB05F1EE0142465846214400F02C +:100D500013FB3B6813B9012000F0C2FA94F8D200EB +:100D600000F0C8FA054630B9207200F0E3FA2846D0 +:100D700000F0B6FAC2E7D4F8D4303BB994F8D20008 +:100D8000B4F8F031834201D8FFF7E2FED4F8D43052 +:100D900043449D4208D294F8D200B4F8F0310130B7 +:100DA000834201D8FFF7D4FE594660685FFA8AF2A1 +:100DB00000F0FCFA08B9CD4689E7636894F8D200E0 +:100DC00043446360D4F8D43008EB030AC4F8D4A0D9 +:100DD00000F090FA824509D394F8D230D4F8D400C8 +:100DE0000133401B84F8D230C4F8D400B8F1FF0FAF +:100DF0000FD80025257200F09DFA284600F070FA01 +:100E000000F03CFD164B188108B9FFF791FCCD4668 +:100E1000E8E64FF48A727B6894F8D90002FB03433A +:100E2000D3F8E42083F8E86002F58072C3F8E0604C +:100E3000C3F8E420FFF7B4FDFFF702FE84F8D960A1 +:100E4000B9E700BF482100204521002000ED00E067 +:100E50000400FA057C210020CDCCCC3D6666663FBF +:100E600034110020014B1870704700BF4011002062 +:100E700030B54FF00054254B226885B09A4207D018 +:100E800002F030FB0446C0B90024204605B030BD56 +:100E90000025627D1E4B1F481A70237DC9220372F4 +:100EA0001D49C0F8E450093000F066FA2046E022FF +:100EB000294600F073FA0124E7E7184A184DD36970 +:100EC00043F00073D361AA6D164B9A42DCD12B6EAE +:100ED000013B7E2BD8D8144A01AB07CA83E8070030 +:100EE0001846032100F09AFC6B6D83424FF000031B +:100EF000CAD12A6D8A4203BFAB652A6E044B1C46D9 +:100F000001BF1A70EA6D094B1A60BEE79AAD44C57D +:100F1000401100207C21002016000020001002401B +:100F2000006600405041A0B05866004018110020F3 +:100F30002DE9F04385B000F0A1FC0223494C637118 +:100F400000230293484B2081D3F800C0BCF57A7F80 +:100F500012D3464F464BB7FBFCF59C458CBF0A238A +:100F60001123B5FBF3F603FB1652591EC8B2002A33 +:100F70003ED002290B46F4D89DF80B303D495A1E4D +:100F80009DF80A303C48013B1B0443EA0253BDF87C +:100F90000820013A13434B6001F0F2FE0023019355 +:100FA000364B374900934FF48052364B364800F0A9 +:100FB00069FF364B197811B1334800F08DFF00F00E +:100FC000F1FC0546FFF706FC4FF4C873B0FBF3F2E3 +:100FD00002FB130305F516709BB218442C4B1860E6 +:100FE00002F076FA08B10F23238105B0BDE8F08343 +:100FF000731EB3F5806FBFD24FF47A75C0EBC00E8D +:101000000EF103034FEAE30909FB0555C3F3C703D8 +:10101000C11AC9B209F101088844B5FBF8F5B5F564 +:10102000617F08D90EF1FF33C3F3C703C11A581EFD +:101030000F28C9B214D84A1E072A8CBF00220122E9 +:10104000581800FB0660B7FBF0F7BC4594D1002AA6 +:1010500092D0ADF808608DF80A308DF80B108BE750 +:101060001346EDE73411002018110020005125022D +:101070003F420F0010110020A8230020C90A0008D9 +:1010800044110020950B00084C2100204011002045 +:10109000482100202DE9F04F80A7D7E900670FF223 +:1010A0000429D9E90089734D93B00DF1300AFFF797 +:1010B000C7FC18220021504600F070F9DFF8B8B1E3 +:1010C0006E4C002352461946584601F091FE0146E7 +:1010D00050BB102208A800F061F9E36883F0100308 +:1010E000E36000F061FC0DF1240C0B4612A90246EE +:1010F00011E903008CE803009DF83410C1F30300EC +:10110000890649BF0E99BDF83810C1F31C0141F0A2 +:10111000004158BFC1F30A018DF82C000891284600 +:1011200008A901F095F9CCE7284600F0DDFE044659 +:10113000002847D100F036FCDFF844B1DBF800307E +:1011400098423FD300F02EFC0790FFF743FB4FF48B +:10115000C873B0FBF3F101FB1300079A83B202F5E9 +:1011600016701844CBF80000DFF818B18DF8204055 +:101170009BF8001011B901238DF8203050460791DB +:10118000FFF740FB07990DF12100C1F11004E4B213 +:10119000062C28BF06245144224600F0EDF808AB87 +:1011A000039318230293384B013401930123E4B2D3 +:1011B000009332463B462846049400F0DBFE0023B1 +:1011C0008BF8003000F0EEFB304A314C1368C31A44 +:1011D000B3F57A7F30D3106000F0E6FB02460B4691 +:1011E000284600F05FFF284600F07EFE20B3237AF9 +:1011F000DFF8A0B0002B14BF032302238BF80530C7 +:1012000000F0D0FB4FF47A73B0FBF3F00122CBF87F +:1012100000005146584600F0B3F9182302931E4BC4 +:1012200080B2019340F25513CDE903A000934246EA +:101230004B46284600F09EFE237ABBB100F0B2FB7D +:1012400094F8E83073B9D4F8E03043B1C01A236899 +:10125000FA2B38BFFA230533B0EB430F02D300203B +:10126000FFF79EFB237A002B7FF41FAF13B0BDE87E +:10127000F08F00BF4C210020A8230020000801406F +:101280004821002045210020442100207023002017 +:101290007C2100203411002074230020401DA12057 +:1012A00026812A0BF1C6A7C1D068080F70B501F0DE +:1012B0007DFF0024084E094D308028683388834222 +:1012C00008D901F06FFF2B6804440133B4F5C84F0F +:1012D0002B60F2D370BD00BFA42300207823002030 +:1012E00001F0F2BF00F10060920000F5C84001F08B +:1012F00097BF0000054B1A68054B1B889B1A834259 +:1013000002D9104401F04EBF00207047782300201E +:10131000A4230020024B1B68184401F049BF00BF02 +:1013200078230020024B1B68184401F053BF00BF14 +:1013300078230020064991F8243033B10023082295 +:10134000086A81F82430FFF7CDBF0120704700BF45 +:101350007C230020022802BF1022014B1A61704733 +:1013600000080140022802BF4FF48012014B1A61AD +:10137000704700BF00080140002310B5934203D01E +:10138000CC5CC4540133F9E710BD000003460246AB +:10139000D01A12F9011B0029FAD170470346024402 +:1013A000934202D003F8011BFAE770472DE9F84396 +:1013B0001F4D144695F824200746884652BBDFF897 +:1013C00070909CB395F824302BB92022FF21484619 +:1013D0002F62FFF7E3FF95F824004146C0F10802B1 +:1013E000A24228BF224605EB8000D6B29200FFF74A +:1013F000C3FF95F82430A41B1E44F6B2082E1744F0 +:101400009044E4B285F82460DBD1FFF793FF002815 +:10141000D7D108E02B6A03EB82038342CFD0FFF7DA +:1014200089FF0028CBD10020BDE8F8830120FBE72D +:101430007C2300202DE9F0470D460446002190460C +:10144000284640F27912FFF7A9FF23462022002107 +:10145000284600F09FFF022220212846231D00F08D +:1014600099FF032222212846631D00F093FF0322E7 +:1014700025212846A31D00F08DFF10222821284693 +:1014800004F1080300F086FF08223821284604F101 +:10149000100300F07FFF08224021284604F11103C9 +:1014A00000F078FF08224821284604F1120300F0DA +:1014B00071FF20225021284604F1140300F06AFF36 +:1014C00040227021284604F1180300F063FF08222F +:1014D000B021284604F1200300F05CFF0822B82167 +:1014E000284604F1210300F055FFC02604F122072D +:1014F0003B46314608222846083600F04BFFB6F539 +:10150000A07F07F10107F3D108223146284604F1F4 +:10151000320300F03FFF002704F1330A94F8323021 +:101520004FEAC7099F4209F5A47615D3B8F1000F19 +:1015300008D131460722284604F5997300F02AFFA6 +:1015400009F24F16274694F832213B1B93420CD3E5 +:10155000F01DC008BDE8F0870AEB070308223146FA +:10156000284600F017FF0137D8E7314607F233135A +:101570000822284600F00EFF08360137E3E7000096 +:1015800038B50C460021054621600346C4F8031017 +:101590002046202200F0FEFE20462B1D02222021A4 +:1015A00000F0F8FE20466B1D0322222100F0F2FE1F +:1015B0002046AB1D0322252100F0ECFE2046102220 +:1015C000282105F1080300F0E5FE072038BD0000E2 +:1015D0000023F7B50E460546047F07220091194601 +:1015E00000F09AFD731C0093012200230721284676 +:1015F00000F092FDC4B9B31C0093052223460821D4 +:10160000284600F089FD0D243746B278BB1B934273 +:1016100011D32B7FE01DC008AC8ABBB9A04294BF98 +:101620000020012003B0F0BDAB8A0824DB00083B9A +:10163000DB08B370E8E7FB1C214600930822002377 +:10164000284600F069FD08340137DEE7001B18BFAB +:101650000120E7E70023F7B50E46047F082200913A +:101660001946054600F058FD731CC4B908220093C2 +:1016700011462346284600F04FFD102401237278BE +:101680005F1C013B934211D32B7FE01DC008AC8A45 +:10169000BBB9A04294BF0020012003B0F0BDAB8ACB +:1016A0000824DB00083BDB087370E7E7F3192146E9 +:1016B000009308220023284600F02EFD08343B4604 +:1016C000DDE7001B18BF0120E7E70000F8B50E4674 +:1016D00005461446002181223046FFF75FFE2B4667 +:1016E00008220021304600F055FE7CB9072208216F +:1016F00030466B1C00F04EFE0F2401236A785F1CFD +:10170000013B934204D3E01DC008F8BD0824F4E770 +:101710002146EB190822304600F03CFE08343B46D7 +:10172000ECE70000F8B50E46054614460021CE222F +:101730003046FFF733FE2B4628220021304600F0CA +:1017400029FE7CB908222821304605F1080300F063 +:1017500021FE30242F462A7A7B1B934204D3E01DBE +:10176000C008F8BD2824F5E7214607F1090308223F +:10177000304600F00FFE08340137ECE7F7B5047F80 +:101780000E460091012310220021054600F0C4FC02 +:10179000C4B9B31C0093092223461021284600F047 +:1017A000BBFC192437467288BB1B9A4211D82B7F89 +:1017B000E01DC008AC8ABBB9A04294BF0020012044 +:1017C00003B0F0BDAB8A1024DB00103BDB08738054 +:1017D000E8E73B1D2146009308220023284600F03D +:1017E0009BFC08340137DEE7001B18BF0120E7E748 +:1017F00030B5094D0A4491420DD011F8013B5840D3 +:10180000082340F30004013B2C4013F0FF0384EA5B +:101810005000F6D1EFE730BD2083B8ED4FF0FF3335 +:10182000F7B500EB81061946DFF848C0DFF848E05D +:10183000B0421BD050F8042B01AF0192042217F8DC +:10184000014B81EA046108240D46DB184941013C43 +:10185000002DBCBF83EA0C0381EA0E0114F0FF04E3 +:10186000F2D1013A12F0FF02E9D1E1E7D843C943CE +:1018700003B0F0BD9336EAA9EBE1F042F7B56B4651 +:10188000354A106851686A4603C30823334934480F +:1018900002F0D4F8044690BB0A256B46314A106822 +:1018A00051686A4603C308232F492D4802F0C6F841 +:1018B0000446002847D00369B3F5CE3F43D8B0F8BB +:1018C0006620B2F57A7F3ED1284A024402F15C01DB +:1018D0008B4238D35C3B224900209E1AFFF788FFD9 +:1018E00007463246002004F16401FFF781FFA36838 +:1018F0009F4228D1E368984208BF002523E003698E +:10190000B3F5CE3F26D8428BB2F57A7F20D1174A65 +:10191000024402F110018B4218D3103B1049002001 +:101920009D1AFFF765FF06462A46002004F11801BC +:10193000FFF75EFFA3689E4202D1E368984201D0A0 +:101940000D25AAE70025284603B0F0BD1025A4E721 +:101950000C25A2E70B25A0E7A43A0008DC9B0100B8 +:1019600000640008AD3A0008909B0100089CFFF756 +:10197000EFF30983EFF30583014B9B6BFEE700BF99 +:1019800000ED00E008B5FFF7F3FF0000EFF3098377 +:10199000EFF30583014B5B6BFEE700BF00ED00E05A +:1019A000FEE7000001F0F6BC01F0A2BC2DE9F04119 +:1019B000456A15B94162BDE8F0814B68AC4623F039 +:1019C0006047C3F38A4616EA230638BF3E464FEA0D +:1019D000D37EC3F380782B465A68BEEBD27F22F0C9 +:1019E00060440AD0002A18DAA40CB44217D19D42F0 +:1019F0000FD10D60DEE71346EEE7A74207D102F0F4 +:101A00008044C2F3807242450BD054B1EFE708D254 +:101A1000EDE7CCF800100B60CDE7B44201D0B44242 +:101A2000E5D81A689C46002AE5D11960C3E7000092 +:101A30002DE9F0474FF47F49089D01F007044FEA74 +:101A4000D508224405F0070500EBD100944201D1EE +:101A5000BDE8F08704F0070705F0070A57453E4642 +:101A600038BF5646111BC6F108068E4228BF0E46E7 +:101A7000E108415C08EBD50E13F80EC0B94029FA15 +:101A800006F721FA0AF1FFB28CEA010147FA0AF7D8 +:101A900039408CEA010C03F80EC034443544D5E7D4 +:101AA000082341F2210280EA012001B2400000290E +:101AB00080B203F1FF33B8BF504013F0FF03F4D1FD +:101AC0007047000038B50C468D18A54200D138BDCE +:101AD00014F8011BFFF7E4FFF7E700000346406836 +:101AE00048B1026899895A605A89013292B291428A +:101AF0005A8138BF9A81704770B504460D4688B048 +:101B0000202200216846FFF749FC20460495FFF794 +:101B1000E5FF024658B16B46054608AE1C4603CCAD +:101B2000B44228606960234605F10805F6D11046E5 +:101B300008B070BD082817D909280CD00A280CD085 +:101B40000B280CD00C280CD00D280CD00E2814BF5C +:101B50004020302070470C20704710207047142020 +:101B6000704718207047202070470000082817D9B8 +:101B70000C280CD910280CD914280CD918280CD9E9 +:101B800020280CD930288CBF0F200E207047092048 +:101B900070470A2070470B2070470C2070470D20BB +:101BA000704700002DE9F843078C0446072F1ED923 +:101BB000D0E9029800254FF6FF73C5F12006A5F184 +:101BC000200029FA05F108FA06F628FA00F0314358 +:101BD0000143C9B21846FFF763FF0835402D03469D +:101BE000EBD13A46E169BDE8F843FFF76BBF4FF62A +:101BF000FF70BDE8F883000010B54B6823B9CA8AAE +:101C000063F30902CA8210BD04691A681C6003618B +:101C1000C38A013BC3824A60EFE700002DE9F84F19 +:101C20001D46CB8A0F46C3F309010529814692461A +:101C30000B4630D00020AAB207F11A049EB2042E3F +:101C40001FFA80F80FD8904503F1010306D3FB8AF1 +:101C50000A4462F309030120FB821AE01AF80060CB +:101C60000130E654EAE79045F1D21C23A1F1050BBF +:101C7000BBFBF3F203FB12BB7C681FFA8BF6002C54 +:101C800045D14846FFF72AFF044638B978606FF01F +:101C90000200BDE8F88F4FF00008E6E70026066076 +:101CA00078604FF0000BADB2454510D90AEB080340 +:101CB000221D13F8011B08F101089155B1B21B292F +:101CC0001FFA88F82BD0454506F10106F1D8FB8AAA +:101CD000C3F30902154465F30903BCE71C4601324E +:101CE00092B22368002BF9D16B1F0B441C21B3FB6C +:101CF000F1F301339BB29A42D3D2BBF1000FD0D1A2 +:101D00004846FFF7EBFE20B9C4F800B0BFE7012258 +:101D1000E7E7C0F800B05E4620600446C1E74545ED +:101D2000D5D94846FFF7DAFE08B92060AFE7C0F81A +:101D300000B0002620600446B6E700002DE9F74F0A +:101D40001C465B69074688460092002B00F097808E +:101D5000238C2BB1E269002A00F09180072B33D845 +:101D600007F10C00FFF7BAFE054628B96FF002052F +:101D7000284603B0BDE8F08F14220021FFF70EFBC8 +:101D8000228CE16905F10800FFF7F6FA208C48F093 +:101D90000041013080B2FFF7E9FEFFF7CBFE0138CA +:101DA00080B22084013028746369228C1B782A4415 +:101DB00003F01F0363F03F0313723846696029463E +:101DC000FFF7F4FD0125D3E74FF000094FF0800A3B +:101DD0004E464D4600F10C0301930198FFF77EFE3D +:101DE00083460028C2D014220021FFF7D7FA002E24 +:101DF0003BD10222009BABF808300BF1080E1FFA12 +:101E000082FC0CF10100BCF1060F218C80B201D8DC +:101E10008E422CD3FFF7AAFEFFF78CFE8E4208BF3E +:101E20004FF0400A62690138127880B202F01F0256 +:101E300042EA49120BEB00014AEA020A013048F07B +:101E4000004281F808A08BF8100059463846CBF8BC +:101E50000420FFF7ABFD238C0135B3424FF0000A9D +:101E60002DB289F00109B8D182E70022C5E7E16906 +:101E7000895D01360EF80210B6B20132BFE76FF08D +:101E8000010575E7F8B5044615460E4630220021D7 +:101E90001F46FFF783FA069BB5F5001F6360079B9B +:101EA00028BF4FF6FF72A3624FF0000338BF6A09E4 +:101EB000A760E66197B204F110009A4206D80023A9 +:101EC0000360A782E3822383E360F8BD06600133E9 +:101ED00030462036F1E7000003781BB94BB2002BE7 +:101EE000C8BF01707047000000787047F8B50C4615 +:101EF000C969074611B9238C002B37D1257E1F2DC8 +:101F000034D8387828BB228C072A2CD8268A36F079 +:101F100003032BD14FF6FF70FFF7D4FD4FF6FF728E +:101F200020F001003602400446EA0565400C45EA0F +:101F30004025234629463846FFF700FF002807DDE5 +:101F4000626913780133DBB21F2B88BF0023137043 +:101F5000F8BD218A2D0645EA012505432046FFF7F5 +:101F600021FE0246E5E76FF00300F1E76FF00100A4 +:101F7000EEE7000070B504461D4616468AB02822DA +:101F800000216846FFF70AFABDF838306946ADF817 +:101F900010300F9B204605939DF84030CDE9026537 +:101FA0008DF81830119B0793BDF84830ADF82030FC +:101FB000FFF79CFF0AB070BD2DE9F041D3690546DB +:101FC0000C4616460BB9138C5BBB377E1F2F28D8E7 +:101FD00095F80080B8F1000F26D03046FFF7E2FDFB +:101FE0003378210241EAC33141EA0801338A41EAE8 +:101FF000076141EA034102463346284641F0800129 +:10200000FFF79CFE00280ADD3378012B07D17269A7 +:1020100013780133DBB21F2B88BF00231370BDE898 +:10202000F0816FF00100FAE76FF00300F7E70000BE +:10203000F0B504460D461E4617468BB028220021F7 +:102040006846FFF7ABF99DF84C3029465A1E5342BB +:1020500053418DF800309DF840306A46ADF810309D +:10206000119B204605939DF84830CDE902768DF806 +:102070001830149B0793BDF85430ADF82030FFF7AB +:102080009BFF0BB0F0BD0000406A00B10430704708 +:10209000436A1A68426202691A600361C38A013B9B +:1020A000C38270472DE9F041D0F8208014461D46C8 +:1020B00041460027174E09B9BDE8F081D1E9022356 +:1020C000A21A65EB0303964277EB03031ED2036A61 +:1020D0008B420DD1FFF790FD036A1B680362036911 +:1020E0000B60C38A0161016A013B8846C382E2E753 +:1020F000FFF782FD0B68C8F8003003690B60C38AE4 +:102100000161013BC382D8F80010D4E78846096812 +:10211000D1E700BF80841E002DE9F04F8BB00D4643 +:1021200014469B468046DDF85090002800F01A8146 +:10213000B9F1000F00F01681531E3F2B00F21281FF +:10214000012A03D1BBF1000F40F00C810023CDE93F +:102150000833B8F81430B5EBC30F4FEAC30703D305 +:1021600000200BB0BDE8F08F2B199F42D8F80C303F +:1021700036BF7F1B2746FFB21BB9D8F81030002BA3 +:102180007BD0272D4ED8C5F12806B7424FF000036B +:1021900034BF3E46F6B2009329463246D8F80800CE +:1021A00008ABFFF745FCA7EB060A35445FFA8AFA4D +:1021B0002821B8F8143003F10053053BDB000493E9 +:1021C000D8F80C300393039B13B1BAF1000F2CD154 +:1021D000D8F8100040B1BAF1000F05D05246009671 +:1021E00008AB691AFFF724FC38B2002FB8D0660795 +:1021F0000AD00AAB03EBD40111F8083C624202F0AA +:102200000702134101F8083C082C3DD9102C40F27C +:10221000B680202C40F2B880BBF1000F00F09D800A +:10222000082335E0BA460026C2E7049BE02B28BF0E +:10223000E02306930B44AB42059315D95A1B9245F4 +:1022400038BF5246039828BFD2B20096691A08AB2D +:1022500004300792FFF7ECFB079A1644AAEB020A38 +:102260001544F6B25FFA8AFA049B069A05999B1AFE +:102270000493039B1B680393A5E700933A46294602 +:10228000D8F8080008ABADE7BBF1000F13D001236D +:10229000B4EBC30F6CD0082C12D89DF82030621E0E +:1022A00023FA02F2D50706D54FF0FF3202FA04F402 +:1022B00023438DF820309DF8203089F8003050E716 +:1022C000102C12D8BDF82030621E23FA02F2D1077A +:1022D00006D54FF0FF3202FA04F42343ADF8203064 +:1022E000BDF82030A9F800303BE7202C0FD8089922 +:1022F000631E21FA03F3DA0705D54FF0FF3202FA25 +:1023000004F40C430894089BC9F8003029E7402CDA +:102310002BD0DDE90865611EC4F12102A4F121037F +:1023200026FA01F105FA02F225FA03F311431943E3 +:10233000CB0712D50122A4F12003C4F1200102FA37 +:1023400003F322FA01F1A240524243EA010363EB94 +:10235000430332432B43CDE90823DDE90823C9E9D0 +:102360000023FEE66FF00100FBE66FF00800F8E6E0 +:10237000082CA0D9102CB3D9202CEED8C3E7BBF180 +:10238000000FADD0022383E7BBF1000FBBD00423C5 +:102390007EE70000012A30B5144638BF012200252F +:1023A000402A28BF402285B0012CCDE9025517D81C +:1023B0001B788DF8083053070AD004AB03EBD20525 +:1023C00015F8083C544204F00704A34005F8083C03 +:1023D0000346009102A80021FFF72AFB05B030BD9B +:1023E000082CE5D9102C03D81B88ADF80830E2E79B +:1023F000202C02D81B680293DDE7D3E90045CDE924 +:102400000245D8E710B5CB681BB98B600B618B8296 +:1024100010BD04691A681C600361C38A013BC38252 +:10242000CA60F0E703064CBFC0F3C030022070471B +:1024300008B50246FFF7F6FF022806D15306C2F39D +:102440000F2001D100F0030008BDC2F30740FBE7F5 +:102450002DE9F04F93B0CDE903230A6804461046F6 +:10246000FFF7E0FF02280CBF0026C2F30626002A71 +:102470000D46824680F2F98112F0C04940F0F581A4 +:10248000097B002900F0F181022803D02378B342B0 +:1024900040F0EE81C2F304631046069302F07F031E +:1024A0000593FFF7C5FF059B00224FEA83480023F1 +:1024B00048EA0A48294448EA4668CE78CDE9082324 +:1024C000F309834648EA0008029367D0059B024659 +:1024D000009320465346676808A9B847002800F0D3 +:1024E000CA81276A4FB9414604F10C00FFF704FB8B +:1024F000074690B96FF0020054E03B6998450DD053 +:102500003F68002FF9D1414604F10C00FFF7F4FABF +:1025100007460028EED0236A3B60276297F817C071 +:1025200006F01F08CCF3840CACEB08001FFA80FE09 +:102530000028B8BF0EF12000A8EB0C031FFA83FEA1 +:10254000B8BF00B2002B0793BEBF0EF120031BB231 +:102550000793D7E9022152EA010338D04FF0000C6B +:10256000039BDFF8F8E19A1A049B63EB010196459F +:102570007CEB01032BD36B7B97F81AE0734519D1E1 +:10258000029B002B78D0012821DC7868F8B9DFF8AD +:10259000D0C1944570EB010316D337E0276A27B901 +:1025A0006FF00C0013B0BDE8F08F3B699845B5D0D3 +:1025B0003F68F4E76A4890427CEB010301D30020B6 +:1025C000F0E7029B002BFAD0079B0F2B17DCFA7D5C +:1025D000B30002F0030203F07C031343FB7539469A +:1025E0002046FFF709FB6B7BBB76029B3BB9FB7D6B +:1025F000C3F38402013262F38603FB75D0E76A7B82 +:10260000BB7E9A42DBD1029B002B35D0B309022B53 +:1026100032D0039B1422BB60049B0021FB600DA8F9 +:10262000FEF7BCFE039B20460A93049BADF83EB028 +:102630000B932B1D0C932B7B8DF840A0013BDBB241 +:10264000ADF83C30069B8DF841808DF84230059BFB +:102650000AA98DF8433094F82C3083F001038DF8EB +:102660004430A3689847FB7DC3F38403013303F030 +:102670001F039B02FB82A2E7FB7DC6F34012B2EB75 +:10268000D31F40F0FB80C3F38403434540F0F9803F +:10269000029A2B7BB609002A4DD0F20762D4032B95 +:1026A00040F2F280039BAE1DBB60049B3246FB6090 +:1026B0002B7B3946033BDBB204F10C00FFF7AEFA8B +:1026C00000280CDA39462046FFF796FAFB7DC3F363 +:1026D0008403013303F01F039B02FB820AE7AB88EC +:1026E000DDE908843B834FF6FF73C9F12000A9F1AF +:1026F000200228FA09F104FA00F0014324FA02F258 +:1027000011431846C9B2FFF7CBF909F10809B9F12D +:10271000400F0346E9D13146B8822A7B033AD2B250 +:10272000FFF7D0F9FB7DB882DA43C2F3C01262F33F +:10273000C713FB7543E7AEB92E1D013B3246394640 +:10274000DBB204F10C00FFF769FA0028BADB2A7B40 +:102750003146013AB88AD2B2E2E700BF80841E0057 +:1027600040420F00F98A013BC1F309010429DAB2A2 +:102770005DD80023281D07F11B069A4208D910F8DE +:1027800001CB013306F801C001310529DBB2F4D1D8 +:10279000934228BF0023039938BF04330A91049958 +:1027A00038BFDBB20B9107F11B010C91796838BF80 +:1027B0005B190D910E93FB8AADF83EB0C3F309038C +:1027C0001A44069BADF83C208DF84230059B8DF8ED +:1027D00040A08DF8433094F82C308DF8418083F080 +:1027E00001038DF8443000237B602A7BB88A013ACC +:1027F000291DFFF767F93B8BB882834203D120463E +:10280000A3680AA9984720460AA9FFF7FBFDFB7DAC +:10281000BA8AC3F38403013303F01F039B02FB82D4 +:102820003B8B9A420CBF00206FF01000BAE67B6829 +:10283000002BADD0052001E033461C301E68002E71 +:10284000FAD1091A081D2E1D184401EB090CBCF120 +:102850001B0F5FFA89F39BD89A4299D916F8013B6E +:1028600009F1010900F8013BEFE76FF0090099E673 +:102870006FF00A0096E66FF00B0093E66FF00D0024 +:1028800090E66FF00E008DE66FF00F008AE600BF55 +:10289000F0B53F4D3F4FEB6943F00073EB61EB69DF +:1028A0003D4B9B6AD3F800623E4046F00106C3F8F8 +:1028B0000062D3F800423C4044EA002444F00104A2 +:1028C000C3F80042002955D000200646C3F81C0278 +:1028D000C3F80402C3F80C02C3F8140203EBC004EB +:1028E00001300E28C4F84062C4F84462F6D10027D3 +:1028F0004FF0010C9678148816F0010F18BFD3F82A +:1029000004E20CFA04F01CBF40EA0E0EC3F804E225 +:1029100016F0020F18BFD3F80CE203EBC4041CBF7F +:1029200040EA0E0EC3F80CE2760748BFD3F81462F3 +:1029300007F1010744BF0643C3F814625668B94261 +:10294000C4F84062966802F10C02C4F84462D3F8FD +:102950001C4240EA0400C3F81C02CBD1D3F8002289 +:1029600022F00102C3F80022EB6923F00073EB614F +:10297000EB69F0BD0122C3F84012C3F84412C3F85A +:102980000412C3F81412C3F80C22C3F81C22E5E7A2 +:10299000001002400000FFFFA8230020184A08B5DD +:1029A000916A8B688B6013F0010104D013F00C0F57 +:1029B00018BF4FF48031D80506D513F4406F14BF0B +:1029C00041F4003141F00201D80306D513F4402F41 +:1029D00014BF41F4802141F00401D3690BB10848D0 +:1029E0009847302383F311880021064800F022FB2A +:1029F000002383F31188BDE8084000F0ABBD00BFA1 +:102A0000A8230020B023002038B5124CA36ADD684B +:102A1000AA0712D05A6922F002025A61A36913B1BF +:102A2000012120469847302383F3118800210A486A +:102A300000F000FB002383F31188EB0606D510217C +:102A4000A36AD960236A0BB102489847BDE83840B1 +:102A500000F080BDA8230020B823002038B5124C18 +:102A6000A36A1D69AA0712D05A6922F010025A619E +:102A7000A36913B1022120469847302383F31188BC +:102A800000210A4800F0D6FA002383F31188EB06F0 +:102A900006D51021A36A1961236A0BB10248984731 +:102AA000BDE8384000F056BDA8230020B823002020 +:102AB00038B50F4CA36A5D682A075D600AD5042209 +:102AC00022701A6822F002021A60636A13B10021B0 +:102AD000204698476B0706D5A36A9969236A13B104 +:102AE000034809049847BDE8384000F033BD00BFF3 +:102AF000A823002010B50E4C204600F02FF90D4BF6 +:102B00000B211320A36200F009F90B21142000F01F +:102B100005F90B21152000F001F90B21162000F01A +:102B2000FDF8BDE8104000220E201146FFF7B0BEB0 +:102B3000A8230020006400400F4B10B598420446C3 +:102B400005D10E4BDA6942F00072DA61DB690122CD +:102B5000A36A1A60A36A5A68D20707D562685168E7 +:102B60001268D9611A60064A5A6110BD0121082015 +:102B700000F0B0F9EEE700BFA823002000100240EB +:102B80005B87010003291AD8DFE801F0020A0F145D +:102B9000836A9B6813F0E05F14BF01200020704738 +:102BA000836A9868C0F380607047836A9868C0F34E +:102BB000C0607047836A9868C0F300707047002057 +:102BC0007047000010B5032927D8DFE801F002277D +:102BD0002B2F836A9968C1F30161183103EB01134C +:102BE0001078840648BF5468C0F3001158BF948819 +:102BF0004FEA410148BF41EAC40100F00F005860AC +:102C000048BF41F00401906858BF41EA4451D2687E +:102C100041F001019860DA60196010BD836A03F524 +:102C2000C073DDE7836A03F5C873D9E7836A03F5E8 +:102C3000D073D5E701290AD002290FD081B9836A60 +:102C4000DA68920701D1186903E001207047836AAE +:102C5000D86810F0030018BF01207047836AF2E7BC +:102C60000020704710B539B9836AD96889071BD12C +:102C70001B699C0704D110BD012915D00229FAD186 +:102C8000816AD1F8C031D1F8C441D1F8C8011061CE +:102C9000D1F8CC015061202008610869800717D164 +:102CA000486940F0100012E0816AD1F8B031D1F8E3 +:102CB000B441D1F8B8011061D1F8BC0150612020B5 +:102CC000C860C868800703D1486940F002004861C5 +:102CD000C3F34000C3F38001000140EA41111079C1 +:102CE00020F030000143117189064BBF91681189B2 +:102CF000DB085B0D4CBF63F31C0163F30A0113791E +:102D000048BF916064F3030313714FEA14234FEA41 +:102D1000144458BF118113705480ACE7012209019B +:102D200000F1604303F56143C9B283F8001300F07A +:102D30001F039A4043099B0003F1604303F561437D +:102D4000C3F880211A607047090100F16040C9B2E0 +:102D500000F56D4001767047FFF7CCBE012303708C +:102D6000002300F10802C0E9022200F11002C0E9CC +:102D70000422C0E90633C0E908334360704700000D +:102D800010B53023044683F3118802234160037099 +:102D9000FFF7D2FE04230020237080F3118810BDBA +:102DA0002DE9F0411F4604460D461646302383F3B5 +:102DB000118800F108082378052B0DD029462046FC +:102DC000FFF7E0FE40B1204632462946FFF7FAFE03 +:102DD000002080F3118808E03946404600F01AF9D7 +:102DE0000028E8D0002383F31188BDE8F0810000BB +:102DF0002DE9F0411F4604460D461646302383F365 +:102E0000118800F110082378052B0DD029462046A3 +:102E1000FFF710FF40B1204632462946FFF722FF58 +:102E2000002080F3118808E03946404600F0F2F8AF +:102E30000028E8D0002383F31188BDE8F08100006A +:102E400000238268037503691B6899689142FBD26D +:102E50005A680360426010605860704700238268BF +:102E6000037503691B6899689142FBD85A6803602F +:102E7000426010605860704708B50846302383F3FD +:102E800011880B7D032B05D0042B0DD02BB983F3B8 +:102E9000118808BD00228B691A604FF0FF338361EF +:102EA000FFF7CEFF0023F2E7D1E9003213605A604A +:102EB000F3E70000FFF7C4BF054BD9680875186831 +:102EC000026853601A6001220275D860FDF79ABB50 +:102ED000D823002030B50C4B0446DD684B1C87B06E +:102EE0000FD02B466846094A00F0CAF82046FFF783 +:102EF000E3FF009B13B1684600F0CAF8A86907B069 +:102F000030BDFFF7D9FFF9E7D8230020792E00085C +:102F1000044B1A68DB6890689B68984294BF002055 +:102F200001207047D8230020084B10B51C68D868D2 +:102F3000226853601A6001222275DC60FFF78EFF61 +:102F400001462046BDE81040FDF75CBBD8230020B9 +:102F500038B501230025064C0649074823706560F3 +:102F600000F03EFB0223237085F3118838BD00BFBB +:102F700030250020BC3A0008D823002000F09AB881 +:102F80008B60022308618B82084670478368A3F137 +:102F9000440243F8142C026943F8442C426943F874 +:102FA000402C094A43F8242CC268A3F1200043F8BE +:102FB000182C022203F80C2C002203F80B2C034AD5 +:102FC00043F8102C704700BF15060008D8230020D6 +:102FD00008B5FFF7DBFFBDE80840FFF76BBF000057 +:102FE000024BDB6898610F20FFF766BFD8230020F3 +:102FF000302383F31188FFF7F3BF000008B50146C3 +:10300000302383F311880820FFF764FF002383F344 +:10301000118808BD064BDB6839B1426818605A60F8 +:10302000136043600420FFF755BF4FF0FF30704737 +:10303000D823002038B504460D462068844200D1CC +:1030400038BD036823605C608561FFF733FFF4E7F8 +:1030500010B50A4C23699A6891420CD85A6881606D +:103060000360426010609A685860511A99604FF08E +:10307000FF33A36110BD1B68891AECE7D823002039 +:10308000C0E90323002310B410BC4361FFF7E0BF85 +:10309000036881689A680A449A60426813605A60BB +:1030A00000234FF0FF320360014B9A61704700BF6D +:1030B000D823002070B5124D2A46EB690133EB612D +:1030C00052F8103F934206D030269A68013A9A602F +:1030D0002C69A36803B170BDD4E900210A60516076 +:1030E000236083F311882046D4E90331984786F39F +:1030F000118861690029EBD02046FFF7A9FFE7E7B7 +:10310000D8230020054A30B5D369D2E908451B1BF6 +:10311000181945F10001C2E9080130BDD82300208B +:1031200000207047FEE70000704700004FF0FF30BE +:1031300070470000BFF34F8F024AD368DB07FCD40F +:10314000704700BF0020024008B5074B1B7853B9F9 +:10315000FFF7F0FF054B1A69120641BF044A5A6097 +:1031600002F188325A6008BD482500200020024044 +:103170002301674508B5054B1B7833B9FFF7DAFF24 +:10318000034A136943F08003136108BD48250020FA +:10319000002002407F289ABF00F500308002002006 +:1031A000704700004FF48060704700008020704737 +:1031B0007F2808B50BD8FFF7EDFF00F580630268A4 +:1031C000013204D104308342F9D1012008BD00202E +:1031D000FCE700007F2810B504461CD8FFF7AAFFC3 +:1031E000FFF7B2FFF3220D4B4FF48061DA60022249 +:1031F0001A61FFF7CFFF58611A6942F040021A6165 +:10320000FFF798FF00F02EF9FFF7B4FF2046BDE866 +:103210001040FFF7CDBF002010BD00BF00200240CE +:103220002DE9F843054612F00100144606D040F29D +:10323000033200201E4B1A60BDE8F8831D4BAA180C +:103240009A4204D94FF44272194B1A60F4E7FFF71F +:103250007BFF4FF00109FFF76DFFDFF85C806D1A0F +:10326000012C0F4605EB010603D8FFF783FF012071 +:10327000E2E73B88C8F8109033800020FFF75AFF40 +:10328000C8F81000338831F8022B9BB29A420CD058 +:1032900040F21F32064B1A60084B1E60084B1C6040 +:1032A000084B1F60FFF766FFC6E7023CD8E700BF88 +:1032B000442500200000020800200240382500209C +:1032C000402500203C250020084908B50B7828B18E +:1032D0001BB9FFF739FF01230B7008BD002BFCD091 +:1032E000BDE808400870FFF745BF00BF4825002033 +:1032F00038B5EFF31185BDBBEFF30584C4F30804C3 +:103300003023C4B183F31188FFF7FCFE44014B0165 +:10331000241A43EAD06363EB0103A2009B00121856 +:1033200043EA947341EB0301C900D00041EA5271B2 +:1033300085F3118838BD83F31188FFF7E3FE45015B +:103340004B012D1A43EAD06363EB0103AA009B00F3 +:10335000121843EA957341EB0301C900D00041EA1A +:10336000527184F3118838BDFFF7CCFE44014B0144 +:10337000241A43EAD06363EB0103A2009B001218F6 +:1033800043EA947341EB0301C900D00041EA527152 +:1033900038BD00BF38B5FFF7ABFF00230F4A104C14 +:1033A000C00840EA4170A0FB025EC908A0FB040C03 +:1033B000A1FB0440A1FB02121CEB050C5B411CEBC2 +:1033C000040C43EB000011EB0E0142F10002411826 +:1033D00042F10000090941EA007038BDA59BC420F4 +:1033E000CFF753E310B5094C013AD2B2FF2A00D10E +:1033F00010BD500854F82030013054F820009BB222 +:1034000043EA004341F8043BEEE700BF046C004090 +:1034100010B50748013AD2B2FF2A00D110BD0C887E +:10342000530840F823404C88013340F82340F1E72B +:10343000046C004007B50122002001A9FFF7D2FF6C +:10344000019803B05DF804FB13B50446FFF7F2FFE3 +:10345000A04205D00122002001A90194FFF7D8FF66 +:1034600002B010BD7047000045F25552064B1A607D +:1034700002225A6040F6FF729A604CF6CC421A6003 +:103480000122024B1A707047003000405025002086 +:10349000034B1B781BB14AF6AA22024B1A607047F5 +:1034A0005025002000300040044B1A682AB902F170 +:1034B000804202F50432526A1A6070474C2500209F +:1034C0004FF08072014B5A62704700BF00100240FB +:1034D00008B5FFF7E9FF024B1868C0F3407008BD5C +:1034E0004C25002008B5FFF7DFFF024B1868C0F33A +:1034F000007008BD4C250020EFF30983203383F3CF +:103500000988002383F3118870470000302080F37E +:10351000118862B60C4B0D4AD96821F4E0610904A8 +:10352000090C0A43DA60D3F8FC20094942F08072A2 +:10353000C3F8FC200A6842F001020A602022DA7710 +:1035400083F82200704700BF00ED00E00003FA0599 +:10355000001000E0302310B583F311880B4B5B683B +:1035600013F400630FD0EFF309844FF08073203C15 +:10357000E36184F30988FFF7CBFC10B1044BA3612E +:1035800010BD044BFBE783F31188F9E700ED00E081 +:10359000270600082A06000870470000FEE7000022 +:1035A0000A4B0B480B4A90420BD30B4BC11EDA1C43 +:1035B000121A22F003028B4238BF00220021FDF7CD +:1035C000EDBE53F8041B40F8041BECE7343B000845 +:1035D000D4250020D4250020D4250020FEE70000BB +:1035E00070B5002504461A4B86B0586085620163A9 +:1035F0000E46FFF78BFF04F11003C4E904334FF0CC +:10360000FF33A361134BE561D9692B460A46204677 +:10361000C4E9082304F134018023C4E900440E4ABC +:10362000A560E5622565FFF7ABFC01230B4AE0606E +:1036300003750092726868460192B268CDE9022370 +:10364000074BCDE90435FFF7C3FC06B070BD00BFE2 +:1036500030250020D8230020C83A0008CD3A0008C1 +:10366000DD35000800F030B808B500F063F9FFF769 +:103670006FFCBDE80840FFF717BF0000704700006F +:103680004FF0FF310E4B1A6919611A6900221A6155 +:103690001869D868D960D968DA60DA68DA6942F0FE +:1036A0008052DA61DA69DA6942F00062DA61054A69 +:1036B000DB69136843F48073136000F01BB900BF2B +:1036C0000010024000700040194B1A6842F00102DD +:1036D0001A601A689007FCD51A6802F0F9021A609D +:1036E00000225A605A6812F00C0FFBD11A6842F49B +:1036F00080321A601A689103FCD55A6842F4E812C5 +:103700005A601A6842F080721A601A689201FCD5F9 +:103710001221084A5A60084A11605A6842F00202AF +:103720005A605A6802F00C02082AFAD1704700BFAA +:103730000010024000641D0000200240084A08B545 +:10374000516913680B4003F00103536123B1054A2B +:1037500013680BB150689847BDE80840FFF7FABE00 +:103760000004014054250020084A08B55169136837 +:103770000B4003F00203536123B1054A93680BB178 +:10378000D0689847BDE80840FFF7E4BE0004014058 +:1037900054250020084A08B5516913680B4003F00E +:1037A0000403536123B1054A13690BB1506998476B +:1037B000BDE80840FFF7CEBE0004014054250020BC +:1037C000084A08B5516913680B4003F008035361B8 +:1037D00023B1054A93690BB1D0699847BDE8084009 +:1037E000FFF7B8BE0004014054250020084A08B580 +:1037F000516913680B4003F01003536123B1054A6C +:10380000136A0BB1506A9847BDE80840FFF7A2BEA3 +:103810000004014054250020174B10B55A691C685C +:10382000144004F478725A61A30604D5134A936ACB +:103830000BB1D06A9847600604D5104A136B0BB1E0 +:10384000506B9847210604D50C4A936B0BB1D06B93 +:103850009847E20504D5094A136C0BB1506C9847A0 +:10386000A30504D5054A936C0BB1D06C9847BDE80D +:103870001040FFF76FBE00BF000401405425002038 +:103880001A4B10B55A691C68144004F47C425A6102 +:10389000620504D5164A136D0BB1506D9847230588 +:1038A00004D5134A936D0BB1D06D9847E00404D54D +:1038B0000F4A136E0BB1506E9847A10404D50C4A01 +:1038C000936E0BB1D06E9847620404D5084A136F0B +:1038D0000BB1506F9847230404D5054A936F0BB181 +:1038E000D06F9847BDE81040FFF734BE0004014098 +:1038F00054250020062108B50846FFF70FFA0621D7 +:103900000720FFF70BFA06210820FFF707FA062128 +:103910000920FFF703FA06210A20FFF7FFF9062125 +:103920001720FFF7FBF9BDE8084006212820FFF724 +:10393000F5B9000008B5FFF7A3FE054800F00CF844 +:10394000FFF70AFAFFF79AFEBDE8084000F002B858 +:10395000D43A000800F042B8002319461C4A01334B +:10396000102BC2E9001102F10802F8D1194B9A6933 +:1039700042F07D029A619B690268174BDA608268A7 +:103980005A6042681A60C26803F58063DA6042696F +:103990005A6002691A608269C3F80C24026AC3F88B +:1039A0000424C269C3F80024426AC3F80C28C26A1E +:1039B000C3F80428826AC3F80028026BC3F80C2CF1 +:1039C000826BC3F8042C426BC3F8002C704700BF15 +:1039D0005425002000100240000801404FF0E02371 +:1039E000044A08215A6100229A6107220B201A61B9 +:1039F000FFF7AAB93F19010008B5302383F31188F6 +:103A0000FFF7BCFA002383F3118808BD08B5FFF760 +:103A1000F3FFBDE80840FFF79DBD000010B5013978 +:103A20000244904201D1002005E0037811F8014FD3 +:103A3000A34201D0181B10BD0130F2E72DE9F0417F +:103A40009BB10446C91A1778014403F1FF3C8C422C +:103A5000204601D9002008E005780134BD42F6D1A6 +:103A60000CEB0405D618A54201D1BDE8F08115F88C +:103A7000018D16F801EDF045F5D0E8E7034611F8A1 +:103A8000012B03F8012B002AF9D170476F72672EC2 +:103A90006172647570696C6F742E663130332D47B6 +:103AA0005053000040A2E4F1646891060041A3E590 +:103AB000F26569920700000063300000B83A000820 +:103AC00030240020302500206D61696E0069646C2F +:103AD0006500000000180000444441444454494437 +:103AE00001000000424444444444444400000000B7 +:103AF0004444444444444444000000004444444496 +:103B00004444444400000000444444444444444485 +:103B1000E803000000000000009C0100000000001D +:103B2000640000000000000040420F00FE2A010077 +:043B3000D2040000BB :00000001FF diff --git a/Tools/bootloaders/f103-HWESC_bl.bin b/Tools/bootloaders/f103-HWESC_bl.bin index 1ff1cd6a394bca..13633ea1dffc64 100755 Binary files a/Tools/bootloaders/f103-HWESC_bl.bin and b/Tools/bootloaders/f103-HWESC_bl.bin differ diff --git a/Tools/bootloaders/f103-HWESC_bl.hex b/Tools/bootloaders/f103-HWESC_bl.hex index 9dcc716daf87d0..92994d12b64922 100644 --- a/Tools/bootloaders/f103-HWESC_bl.hex +++ b/Tools/bootloaders/f103-HWESC_bl.hex @@ -1,26 +1,26 @@ :020000040800F2 -:10000000000900202D080008A91C0008791C000820 -:10001000951C0008791C00088D1C00082F0800089A -:100020002F0800082F0800082F080008DD370008F7 -:100030002F0800082F0800082F080008F13C0008CE -:100040002F0800082F0800082F0800082F080008B4 -:100050002F0800082F080008213A00084D3A000830 -:10006000793A0008A53A0008D13A00082F0800089C -:100070002F0800082F0800082F0800082F08000884 -:100080002F0800082F0800082F080008A52C0008DA -:10009000112D0008652D0008B92D0008FD3A000853 -:1000A0002F0800082F0800082F0800082F08000854 -:1000B0002F0800082F0800082F0800082F08000844 -:1000C0002F0800082F0800082F0800082F08000834 -:1000D0002F0800082F0800082F0800082F08000824 -:1000E000653B00082F0800082F0800082F080008AB -:1000F0002F0800082F0800082F0800082F08000804 -:100100002F0800082F0800082F0800082F080008F3 -:100110002F0800082F0800082F0800082F080008E3 -:100120002F0800082F0800082F0800082F080008D3 -:100130002F0800082F0800082F0800082F080008C3 -:100140002F0800082F0800082F0800082F080008B3 -:100150002F0800082F0800082F0800082F080008A3 +:100000000009002025050008991900086919000851 +:1000100085190008691900087D19000827050008DE +:10002000270500082705000827050008F134000807 +:10003000270500082705000827050008053A0008DD +:1000400027050008270500082705000827050008E0 +:100050002705000827050008353700086137000824 +:100060008D370008B9370008E53700082705000874 +:1000700027050008270500082705000827050008B0 +:10008000270500082705000827050008952900080E +:10009000012A0008552A0008A92A0008113800087A +:1000A0002705000827050008270500082705000880 +:1000B0002705000827050008270500082705000870 +:1000C0002705000827050008270500082705000860 +:1000D0002705000827050008270500082705000850 +:1000E00079380008270500082705000827050008BB +:1000F0002705000827050008270500082705000830 +:10010000270500082705000827050008270500081F +:10011000270500082705000827050008270500080F +:1001200027050008270500082705000827050008FF +:1001300027050008270500082705000827050008EF +:1001400027050008270500082705000827050008DF +:1001500027050008270500082705000827050008CF :100160004FF0FF0C1CEAD0521EBF1CEAD15392EA9A :100170000C0F93EA0C0F6FD01A4480EA010C400276 :1001800018BF5FEA41211ED04FF0006343EA5010D0 @@ -81,917 +81,870 @@ :1004F0009E03B3EB126209D44FEA002343F000439A :1005000023FA02F070474FF00000704712F1610FBC :1005100001D1420202D14FF0FF3070474FF000008E -:10052000704700BF53B94AB9002908BF00281CBF53 -:100530004FF0FF314FF0FF3000F076B9ADF1080C0D -:100540006DE904CE00F006F8DDF804E0DDE90223F1 -:1005500004B070472DE9F047089E0D4604468846D2 -:10056000002B4DD18A42944668D9B2FA82F252B138 -:1005700001FA02F3C2F1200120FA01F10CFA02FCA7 -:1005800041EA030894404FEA1C41B8FBF1F71FFA17 -:100590008CFE01FB178807FB0EF0230C43EA08438F -:1005A00098420AD91CEB030307F1FF3580F01E8146 -:1005B000984240F21B81023F63441B1AB3FBF1F0E7 -:1005C00001FB103300FB0EFEA4B244EA0344A6452F -:1005D0000AD91CEB040400F1FF3380F00981A64521 -:1005E00040F20681644402380021A4EB0E0440EA84 -:1005F00007401EB10023D440C6E90043BDE8F087A0 -:100600008B4208D9002E00F0EE800021C6E90005DB -:100610000846BDE8F087B3FA83F100294AD1AB421E -:1006200002D3824200F2FC80841A65EB03030120AE -:100630009846002EE2D0C6E90048DFE702B9FFDEA7 -:10064000B2FA82F2002A40F09180A1EB0C00012165 -:100650004FEA1C471FFA8CFEB0FBF7F307FB1300B1 -:10066000250C45EA00450EFB03F0A84208D91CEB17 -:10067000050503F1FF3802D2A84200F2CE804346BE -:100680002D1AB5FBF7F007FB10550EFB00FEA4B2C8 -:1006900044EA0544A64508D91CEB040400F1FF35E3 -:1006A00002D2A64500F2B6802846A4EB0E0440EA2A -:1006B00003409EE7C1F120078B4022FA07FC4CEA79 -:1006C000030C25FA07FA4FEA1C49BAFBF9F820FA9D -:1006D00007F309FB18AA8D401FFA8CFE1D4300FA90 -:1006E00001F308FB0EF02C0C44EA0A44A04202FA83 -:1006F00001F20BD91CEB040408F1FF3A80F088806A -:10070000A04240F28580A8F102086444241AB4FB98 -:10071000F9F009FB104400FB0EFEADB245EA0444BB -:10072000A64508D91CEB040400F1FF356CD2A645A0 -:100730006AD90238644440EA0840A0FB0295A4EB61 -:100740000E04AC42C846AE4656D353D0002E69D0F4 -:10075000B3EB080264EB0E0422FA01F304FA07F784 -:100760001F43CC40C6E90074002147E70CFA02FCA5 -:10077000C2F1200125FA01F34FEA1C4720FA01F1EA -:1007800095400D43B3FBF7F107FB11331FFA8CFEC5 -:10079000280C40EA034001FB0EF3834204FA02F402 -:1007A00008D91CEB000001F1FF382FD283422DD96C -:1007B00002396044C01AB0FBF7F307FB1300ADB277 -:1007C00045EA004503FB0EF0A84208D91CEB0505DD -:1007D00003F1FF3816D2A84214D9023B6544281A07 -:1007E00043EA014138E73146304607E72F46E4E661 -:1007F0001846F9E64B45A9D2B9EB020865EB0C0E99 -:100800000138A3E74346EAE7284694E74146D1E7A3 -:10081000D0467BE76444023847E7023B65442FE754 -:10082000084606E73146E9E6704700BF02E000F0FF -:1008300000F8FEE772B6264880F30888254880F362 -:100840000988254825490860022080F31488BFF3F1 -:100850006F8F03F013F803F077F84FF0553020490D -:100860001B4A91423CBF41F8040BFAE71D49194A63 -:1008700091423CBF41F8040BFAE71B491B4A1C4B51 -:100880009A423EBF51F8040B42F8040BF8E70020EF -:100890001849194A91423CBF41F8040BFAE702F0AB -:1008A000F1FF03F053F8154C154DAC4203DA54F840 -:1008B000041B8847F9E700F03FF8124C124DAC4298 -:1008C00003DA54F8041B8847F9E702F0D9BF0000A7 -:1008D00000090020001100200000000808ED00E0E1 -:1008E0000001002000090020003E00080011002047 -:1008F0002411002028110020E025002060010008BC -:100900006001000860010008600100082DE9F04F57 -:10091000C1F80CD0C3689D46BDE8F08F002383F377 -:1009200011882846A047002002F00CFDFEE702F0E7 -:100930007FFC00DFFEE70000F8B500F039FE02F0B2 -:10094000EBFE074602F036FF0546002840D12C4B4F -:100950009F423DD001339F423DD02A4B27F0FF02FA -:100960009A423BD1F8B200F0FFFB2E4642F21074DF -:1009700000F000FC08B10024264601F003F988B31A -:100980000024032000F044F8264635B11E4B9F4258 -:1009900003D0002402F006FF2646002002F0C6FE27 -:1009A0001A4B9B6813F0400322D00EB100F046F8BA -:1009B00000F040FC00F0FEFD01F078F90546CCB1F6 -:1009C00001F074F9401BA04214D900F037F8F3E7A6 -:1009D0002E460024CCE704460126C9E706464FF41C -:1009E0007A74C5E7002CD0D04FF47A740126CCE796 -:1009F0001C46DDE700F0D0FC012002F0A9FCDEE798 -:100A0000010007B0000008B0263A09B0000C014010 -:100A1000084B187003280CD8DFE800F0080502081E -:100A2000022000F023BE022000F018BE0022024B7C -:100A30005A607047281100202C11002038B501F0B1 -:100A4000A1F830B103221F4B1A7000221E4B5A60CE -:100A500038BD1E4B1E4A19680131F9D00433934248 -:100A6000F9D11C4C194DD4F80424AA42F0D31A4BE6 -:100A70009B6803F1006303F5C8439A42E8D202F091 -:100A800065FE02F077FE002000F0AEFD0220FFF7C9 -:100A9000BFFF124BDA690022DA61D96999699A615C -:100AA0009B6972B64FF0E023C3F8085D3021D4F89B -:100AB0000034D4F8042481F311889D4683F3088818 -:100AC0001047C5E7281100202C1100200064000801 -:100AD000206400080060000800110020001002409F -:100AE00049F26900084A136899B21B0C00FB0133F4 -:100AF00044F250611360054B186882B2000C01FB90 -:100B00000200186080B27047201100201C110020E4 -:100B100010B504460021102200F0C4FD034B03CBA6 -:100B2000206061601868A06010BD00BFE8F7FF1F7B -:100B30002DE9F0410026ADF54E7D6CAC40F275120A -:100B400007460D460EA831460D9600F0ABFD314626 -:100B50004FF4C472204600F0A5FD01F0A7F84FF451 -:100B60007A72B0FBF2F0244B0DF13408186093E870 -:100B70000700022384E807000DF5E9702382FFF7E0 -:100B8000C7FF4EF603031D4906A8238403F0E8F8C7 -:100B900018230DF2E32684F832310DF1300C6B444A -:100BA0001A4603CA624530607160134606F10806B2 -:100BB000F6D141460122204600F0C0FD00230393F8 -:100BC000AB7E80B2029305F1190301930123CDE9B5 -:100BD00004800093384606A3D3E90023E97E01F0A0 -:100BE000ABFB0DF54E7DBDE8F08100BFAFF300809B -:100BF0009E6AC421818A46EE34110020703D0008AF -:100C00002DE9F041264D80462B7A0C46DAB0FBB92F -:100C1000204627A900F0A2FE0746002836D19DF8FD -:100C20009D60C82E32D801464FF4FA72284600F073 -:100C300039FD32460DF19E0105F1090000F020FD5D -:100C40009DF89C302E4477722B720BB9E37E2B7289 -:100C50008122002106AD27A800F024FD01222946AB -:100C600027A800F0B7FE00230393A37E80B202936F -:100C700004F1190301932823CDE904500093404661 -:100C800005A3D3E90023E17E01F056FB5AB0BDE88D -:100C9000F08100BFAFF3008026417272DF25D7B725 -:100CA0007C210020F0B54FF48A750024234EF1B06A -:100CB00005FB006596F8D830D822214685F8DC304F -:100CC00085F8E8403AA800F0EDFC06F1090000F0D4 -:100CD000E1FCD5F8E430C2B206AF8DF8F00006F1C1 -:100CE00009010DF1F100CDE93A3400F0C9FC3946B3 -:100CF00001223AA800F09AFE80B2CDE904700823E0 -:100D00000127CDE9023706F1D80301933023317A68 -:100D100000930B4807A3D3E9002301F00DFBA04289 -:100D200006DD00F0C3FFC5F8E000384671B0F0BD45 -:100D30002046FBE778F6339F93CACD8D7C210020B7 -:100D40004C210020F0B51E4E1E4F1F4D85B0304681 -:100D500001F01EFB044660B310220021684600F03B -:100D6000A1FC4FF00003227B6068A16862F30303DB -:100D70008DF8003002AB03C3019B2268384662F352 -:100D80001C0301939DF800306A4643F020038DF860 -:100D900000300023194602F087F9044620B9304696 -:100DA00001F0FAFA2C70D2E72B78072B03D8013325 -:100DB0002B7005B0F0BD024801F0EEFAF9E700BF74 -:100DC0004C210020A82300207523002070B50D467B -:100DD00014461E4601F00CFA50B9022E10D1012C17 -:100DE0000ED112A3D3E900230120C5E9002307E0B7 -:100DF000282C10D005D8012C09D0052C0FD00020AC -:100E000070BD302CFBD10BA3D3E90023ECE70BA37F -:100E1000D3E90023E8E70BA3D3E90023E4E70BA31E -:100E2000D3E90023E0E700BFAFF30080401DA1201D -:100E300026812A0B78F6339F93CACD8D9E6AC421F2 -:100E4000818A46EE26417272DF25D7B7F017304A05 -:100E500039059E5638B505460E4C0021013500F087 -:100E6000E5FBA4F8F051B4F8F00100F0C7FB78B14D -:100E7000B4F8F00100F0D2FB014648B9B4F8F00133 -:100E800000F0D4FBB4F8F0310133A4F8F031EAE714 -:100E900038BD00BF7C2100202DE9F04F8DB000AFA0 -:100EA00004460D4601F0A4F9002846D12B7E022B02 -:100EB0001AD1EB8A012B17D100F0F8FE0646FFF796 -:100EC0000FFE4FF4C873B0FBF3F202FB1303DFF81D -:100ED00078829BB206F516763344C8F80030EB7E74 -:100EE00033B90022994B1A703437BD46BDE8F08FF4 -:100EF000284607F11C0100F0EFFC0028F4D107F1AF -:100F00000C00FFF705FEBD7F07F10C012A4607F133 -:100F10001F0002F0F5FE0028E3D10F2D08D88B4BFF -:100F20001D70D8F80030A3F51673C8F80030DBE761 -:100F30002046397F01F054F9D6E7EB8A282B6BD095 -:100F400010D8012B63D0052BCED1BFF34F8F804932 -:100F5000804BCA6802F4E0621343CB60BFF34F8F4B -:100F600000BFFDE7302BBFD17B4CEA7E237A9A424B -:100F7000BAD194F8DC206B7E9A42B5D1284604F1B0 -:100F8000EA0100F07FFD06460028ADD1012384F878 -:100F9000E83000F08BFED4F8E030C01A192840F693 -:100FA000B83338BF1920984228BF1846FFF742FAD5 -:100FB0006A49FFF7D5F805462068FFF73BFA68490C -:100FC000FFF7CEF801462846FFF784F9FFF78AFAC3 -:100FD00020604FF48A7194F8D9307B607A68636836 -:100FE00001FB02F5621992F8E80050B1D2F8E40072 -:100FF000E946834215D0002382F8E830C2F8E03099 -:10100000CD466368574A9B0A013313816CE7294632 -:101010002046FFF78DFD67E729462046FFF7F0FDE4 -:1010200062E7B2F8EC803B6008F1030A4FEA9A0AE3 -:101030004FEA8A02D11DC908A9EBC1039D46EB46C0 -:101040000021584600F02EFB05F1EE0142465846BD -:10105000214400F015FB3B6813B9012000F0C4FAED -:1010600094F8D20000F0CAFA054630B9207200F0B8 -:10107000E5FA284600F0B8FAC2E7D4F8D4303BB914 -:1010800094F8D200B4F8F031834201D8FFF7E2FEC1 -:10109000D4F8D43043449D4208D294F8D200B4F836 -:1010A000F0310130834201D8FFF7D4FE5946606821 -:1010B0005FFA8AF200F0FEFA08B9CD4689E7636864 -:1010C00094F8D20043446360D4F8D43008EB030AA8 -:1010D000C4F8D4A000F092FA824509D394F8D23033 -:1010E000D4F8D4000133401B84F8D230C4F8D400C3 -:1010F000B8F1FF0F0FD80025257200F09FFA28469F -:1011000000F072FA00F03EFD164B188108B9FFF7A7 -:1011100095FCCD46E8E64FF48A727B6894F8D900D6 -:1011200002FB0343D3F8E42083F8E86002F5807201 -:10113000C3F8E060C3F8E420FFF7B4FDFFF702FE58 -:1011400084F8D960B9E700BF48210020452100207C -:1011500000ED00E00400FA057C210020CDCCCC3D60 -:101160006666663F34110020014B1870704700BF5F -:101170004011002030B54FF00054254B226885B057 -:101180009A4207D002F020FB0446C0B90024204652 -:1011900005B030BD0025627D1E4B1F481A70237DAF -:1011A000C92203721D49C0F8E450093000F068FA02 -:1011B0002046E022294600F075FA0124E7E7184AA4 -:1011C000184DD36943F00073D361AA6D164B9A4250 -:1011D000DCD12B6E013B7E2BD8D8144A01AB07CA59 -:1011E00083E807001846032100F09CFC6B6D8342E6 -:1011F0004FF00003CAD12A6D8A4203BFAB652A6E45 -:10120000044B1C4601BF1A70EA6D094B1A60BEE719 -:101210009AAD44C5401100207C210020160000201A -:1012200000100240006600405041A0B058660040E7 -:10123000181100202DE9F04385B000F0A3FC022333 -:10124000494C637100230293484B2081D3F800C0BE -:10125000BCF57A7F12D3464F464BB7FBFCF59C4555 -:101260008CBF0A231123B5FBF3F603FB1652591E5C -:10127000C8B2002A3ED002290B46F4D89DF80B30A4 -:101280003D495A1E9DF80A303C48013B1B0443EA85 -:101290000253BDF80820013A13434B6001F0F4FEFD -:1012A00000230193364B374900934FF48052364B5D -:1012B000364800F06BFF364B197811B1334800F017 -:1012C0008FFF00F0F3FC0546FFF70AFC4FF4C873EC -:1012D000B0FBF3F202FB130305F516709BB2184442 -:1012E0002C4B186002F066FA08B10F23238105B079 -:1012F000BDE8F083731EB3F5806FBFD24FF47A75EB -:10130000C0EBC00E0EF103034FEAE30909FB0555DC -:10131000C3F3C703C11AC9B209F101088844B5FB78 -:10132000F8F5B5F5617F08D90EF1FF33C3F3C703B4 -:10133000C11A581E0F28C9B214D84A1E072A8CBFDA -:1013400000220122581800FB0660B7FBF0F7BC45ED -:1013500094D1002A92D0ADF808608DF80A308DF84B -:101360000B108BE71346EDE7341100201811002015 -:10137000005125023F420F0010110020A823002039 -:10138000CD0D000844110020990E00084C210020CA -:1013900040110020482100202DE9F04F80A7D7E917 -:1013A00000670FF20429D9E90089734D93B00DF15C -:1013B000300AFFF7C7FC18220021504600F072F9EE -:1013C000DFF8B8B16E4C002352461946584601F07A -:1013D00093FE014650BB102208A800F063F9E368B1 -:1013E00083F01003E36000F063FC0DF1240C0B4666 -:1013F00012A9024611E903008CE803009DF834109D -:10140000C1F30300890649BF0E99BDF83810C1F336 -:101410001C0141F0004158BFC1F30A018DF82C00B6 -:101420000891284608A901F097F9CCE7284600F072 -:10143000DFFE0446002847D100F038FCDFF844B155 -:10144000DBF8003098423FD300F030FC0790FFF704 -:1014500047FB4FF4C873B0FBF3F101FB1300079A8D -:1014600083B202F516701844CBF80000DFF818B10B -:101470008DF820409BF8001011B901238DF8203021 -:1014800050460791FFF744FB07990DF12100C1F188 -:101490001004E4B2062C28BF06245144224600F072 -:1014A000EFF808AB039318230293384B01340193F0 -:1014B0000123E4B2009332463B462846049400F0F0 -:1014C000DDFE00238BF8003000F0F0FB304A314C99 -:1014D0001368C31AB3F57A7F30D3106000F0E8FBCD -:1014E00002460B46284600F061FF284600F080FEC9 -:1014F00020B3237ADFF8A0B0002B14BF032302230C -:101500008BF8053000F0D2FB4FF47A73B0FBF3F0A8 -:101510000122CBF800005146584600F0B5F91823D7 -:1015200002931E4B80B2019340F25513CDE903A004 -:10153000009342464B46284600F0A0FE237ABBB1FA -:1015400000F0B4FB94F8E83073B9D4F8E03043B15C -:10155000C01A2368FA2B38BFFA230533B0EB430FC8 -:1015600002D30020FFF79EFB237A002B7FF41FAFEE -:1015700013B0BDE8F08F00BF4C210020A82300204D -:10158000000801404821002045210020442100207E -:10159000702300207C2100203411002074230020BF -:1015A000401DA12026812A0BF1C6A7C1D068080FD3 -:1015B0007047000070B501F095FF0024084E094DFA -:1015C000308028683388834208D901F087FF2B6870 -:1015D00004440133B4F5C84F2B60F2D370BD00BF93 -:1015E000A42300207823002002F00AB800F1006054 -:1015F000920000F5C84001F0AFBF0000054B1A682B -:10160000054B1B889B1A834202D9104401F066BF28 -:101610000020704778230020A4230020024B1B6881 -:10162000184401F061BF00BF78230020024B1B6803 -:10163000184401F06BBF00BF78230020064991F8E1 -:10164000243033B100230822086A81F82430FFF7E0 -:10165000CDBF0120704700BF7C230020022802BFBD -:101660001022014B1A61704700080140022802BF96 -:101670004FF48012014B1A61704700BF000801400F -:10168000002310B5934203D0CC5CC4540133F9E776 -:1016900010BD000003460246D01A12F9011B0029B2 -:1016A000FAD1704703460244934202D003F8011B6B -:1016B000FAE770472DE9F8431F4D144695F82420AA -:1016C0000746884652BBDFF870909CB395F82430EB -:1016D0002BB92022FF2148462F62FFF7E3FF95F840 -:1016E00024004146C0F10802A24228BF224605EB71 -:1016F0008000D6B29200FFF7C3FF95F82430A41BF8 -:101700001E44F6B2082E17449044E4B285F82460D3 -:10171000DBD1FFF793FF0028D7D108E02B6A03EB5A -:1017200082038342CFD0FFF789FF0028CBD100206E -:10173000BDE8F8830120FBE77C2300202DE9F0477A -:101740000D46044600219046284640F27912FFF7E4 -:10175000A9FF234620220021284600F09FFF0222F5 -:1017600020212846231D00F099FF0322222128462C -:10177000631D00F093FF032225212846A31D00F0DE -:101780008DFF10222821284604F1080300F086FF6F -:1017900008223821284604F1100300F07FFF0822B8 -:1017A0004021284604F1110300F078FF0822482167 -:1017B000284604F1120300F071FF20225021284630 -:1017C00004F1140300F06AFF40227021284604F15E -:1017D000180300F063FF0822B021284604F120031B -:1017E00000F05CFF0822B821284604F1210300F034 -:1017F00055FFC02604F122073B4631460822284601 -:10180000083600F04BFFB6F5A07F07F10107F3D1D2 -:1018100008223146284604F1320300F03FFF00273A -:1018200004F1330A94F832304FEAC7099F4209F5B0 -:10183000A47615D3B8F1000F08D131460722284607 -:1018400004F5997300F02AFF09F24F16274694F821 -:1018500032213B1B93420CD3F01DC008BDE8F0873A -:101860000AEB070308223146284600F017FF01372C -:10187000D8E7314607F233130822284600F00EFF5E -:1018800008360137E3E7000038B50C46002105466D -:1018900021600346C4F803102046202200F0FEFE1B -:1018A00020462B1D0222202100F0F8FE20466B1D51 -:1018B0000322222100F0F2FE2046AB1D0322252147 -:1018C00000F0ECFE20461022282105F1080300F06C -:1018D000E5FE072038BD00000023F7B50E4605469B -:1018E000047F07220091194600F09AFD731C0093B3 -:1018F000012200230721284600F092FDC4B9B31C41 -:101900000093052223460821284600F089FD0D2476 -:101910003746B278BB1B934211D32B7FE01DC00822 -:10192000AC8ABBB9A04294BF0020012003B0F0BD37 -:10193000AB8A0824DB00083BDB08B370E8E7FB1C3C -:101940002146009308220023284600F069FD083450 -:101950000137DEE7001B18BF0120E7E70023F7B5DA -:101960000E46047F082200911946054600F058FDF6 -:10197000731CC4B90822009311462346284600F080 -:101980004FFD1024012372785F1C013B934211D359 -:101990002B7FE01DC008AC8ABBB9A04294BF0020D9 -:1019A000012003B0F0BDAB8A0824DB00083BDB0854 -:1019B0007370E7E7F31921460093082200232846B5 -:1019C00000F02EFD08343B46DDE7001B18BF012068 -:1019D000E7E70000F8B50E460546144600218122CF -:1019E0003046FFF75FFE2B4608220021304600F00C -:1019F00055FE7CB90722082130466B1C00F04EFED4 -:101A00000F2401236A785F1C013B934204D3E01D3D -:101A1000C008F8BD0824F4E72146EB190822304637 -:101A200000F03CFE08343B46ECE70000F8B50E46FB -:101A3000054614460021CE223046FFF733FE2B46E2 -:101A400028220021304600F029FE7CB908222821F6 -:101A5000304605F1080300F021FE30242F462A7A93 -:101A60007B1B934204D3E01DC008F8BD2824F5E792 -:101A7000214607F109030822304600F00FFE083422 -:101A80000137ECE7F7B5047F0E46009101231022E1 -:101A90000021054600F0C4FCC4B9B31C0093092220 -:101AA00023461021284600F0BBFC192437467288D3 -:101AB000BB1B9A4211D82B7FE01DC008AC8ABBB972 -:101AC000A04294BF0020012003B0F0BDAB8A1024D7 -:101AD000DB00103BDB087380E8E73B1D21460093E9 -:101AE00008220023284600F09BFC08340137DEE77B -:101AF000001B18BF0120E7E730B5094D0A449142A9 -:101B00000DD011F8013B5840082340F30004013B7D -:101B10002C4013F0FF0384EA5000F6D1EFE730BD0C -:101B20002083B8ED4FF0FF33F7B500EB810619467F -:101B3000DFF848C0DFF848E0B0421BD050F8042B73 -:101B400001AF0192042217F8014B81EA04610824D5 -:101B50000D46DB184941013C002DBCBF83EA0C0354 -:101B600081EA0E0114F0FF04F2D1013A12F0FF02F3 -:101B7000E9D1E1E7D843C94303B0F0BD9336EAA900 -:101B8000EBE1F042F7B56B46354A106851686A469A -:101B900003C308233349344802F0C2F8044690BB1B -:101BA0000A256B46314A106851686A4603C3082308 -:101BB0002F492D4802F0B4F80446002847D00369A5 -:101BC000B3F5CE3F43D8B0F86620B2F57A7F3ED168 -:101BD000284A024402F15C018B4238D35C3B224923 -:101BE00000209E1AFFF788FF07463246002004F1C6 -:101BF0006401FFF781FFA3689F4228D1E368984200 -:101C000008BF002523E00369B3F5CE3F26D8428BF9 -:101C1000B2F57A7F20D1174A024402F110018B42BB -:101C200018D3103B104900209D1AFFF765FF0646A8 -:101C30002A46002004F11801FFF75EFFA3689E42C8 -:101C400002D1E368984201D00D25AAE70025284675 -:101C500003B0F0BD1025A4E70C25A2E70B25A0E7F3 -:101C60008C3D0008DC9B010000640008953D0008E5 -:101C7000909B0100089CFFF7EFF30983EFF30583C6 -:101C8000014B9B6BFEE700BF00ED00E008B5FFF7DE -:101C9000F3FF0000EFF30983EFF30583014B5B6B68 -:101CA000FEE700BF00ED00E0FEE7000001F0E2BC4F -:101CB00001F0BABC2DE9F041456A15B94162BDE8B1 -:101CC000F0814B68AC4623F06047C3F38A4616EABE -:101CD000230638BF3E464FEAD37EC3F380782B46B7 -:101CE0005A68BEEBD27F22F060440AD0002A18DA8C -:101CF000A40CB44217D19D420FD10D60DEE713460C -:101D0000EEE7A74207D102F08044C2F38072424559 -:101D10000BD054B1EFE708D2EDE7CCF800100B6020 -:101D2000CDE7B44201D0B442E5D81A689C46002AF7 -:101D3000E5D11960C3E700002DE9F0474FF47F4972 -:101D4000089D01F007044FEAD508224405F0070575 -:101D500000EBD100944201D1BDE8F08704F0070701 -:101D600005F0070A57453E4638BF5646111BC6F1D7 -:101D700008068E4228BF0E46E108415C08EBD50EEE -:101D800013F80EC0B94029FA06F721FA0AF1FFB29A -:101D90008CEA010147FA0AF739408CEA010C03F892 -:101DA0000EC034443544D5E7082341F2210280EACD -:101DB000012001B24000002980B203F1FF33B8BF17 -:101DC000504013F0FF03F4D17047000038B50C46C3 -:101DD0008D18A54200D138BD14F8011BFFF7E4FFB0 -:101DE000F7E700000346406848B1026899895A60E5 -:101DF0005A89013292B291425A8138BF9A81704712 -:101E000070B504460D4688B0202200216846FFF7D1 -:101E100049FC20460495FFF7E5FF024658B16B46A2 -:101E2000054608AE1C4603CCB442286069602346D0 -:101E300005F10805F6D1104608B070BD082817D97D -:101E400009280CD00A280CD00B280CD00C280CD058 -:101E50000D280CD00E2814BF4020302070470C20D5 -:101E600070471020704714207047182070472020BA -:101E700070470000082817D90C280CD910280CD955 -:101E800014280CD918280CD920280CD930288CBF3C -:101E90000F200E207047092070470A2070470B2042 -:101EA00070470C2070470D20704700002DE9F84363 -:101EB000078C0446072F1ED9D0E9029800254FF65B -:101EC000FF73C5F12006A5F1200029FA05F108FAF3 -:101ED00006F628FA00F031430143C9B21846FFF76D -:101EE00063FF0835402D0346EBD13A46E169BDE872 -:101EF000F843FFF76BBF4FF6FF70BDE8F8830000B3 -:101F000010B54B6823B9CA8A63F30902CA8210BDAF -:101F100004691A681C600361C38A013BC3824A607A -:101F2000EFE700002DE9F84F1D46CB8A0F46C3F3BB -:101F300009010529814692460B4630D00020AAB2FD -:101F400007F11A049EB2042E1FFA80F80FD89045AC -:101F500003F1010306D3FB8A0A4462F3090301205B -:101F6000FB821AE01AF800600130E654EAE7904577 -:101F7000F1D21C23A1F1050BBBFBF3F203FB12BB57 -:101F80007C681FFA8BF6002C45D14846FFF72AFFE4 -:101F9000044638B978606FF00200BDE8F88F4FF062 -:101FA0000008E6E70026066078604FF0000BADB24F -:101FB000454510D90AEB0803221D13F8011B08F14F -:101FC00001089155B1B21B291FFA88F82BD045455D -:101FD00006F10106F1D8FB8AC3F30902154465F343 -:101FE0000903BCE71C46013292B22368002BF9D1E9 -:101FF0006B1F0B441C21B3FBF1F301339BB29A42DC -:10200000D3D2BBF1000FD0D14846FFF7EBFE20B989 -:10201000C4F800B0BFE70122E7E7C0F800B05E46B1 -:1020200020600446C1E74545D5D94846FFF7DAFEAA -:1020300008B92060AFE7C0F800B000262060044671 -:10204000B6E700002DE9F74F1C465B690746884656 -:102050000092002B00F09780238C2BB1E269002ABC -:1020600000F09180072B33D807F10C00FFF7BAFE80 -:10207000054628B96FF00205284603B0BDE8F08F89 -:1020800014220021FFF70EFB228CE16905F1080004 -:10209000FFF7F6FA208C48F00041013080B2FFF7DC -:1020A000E9FEFFF7CBFE013880B2208401302874AE -:1020B0006369228C1B782A4403F01F0363F03F03FB -:1020C0001372384669602946FFF7F4FD0125D3E70E -:1020D0004FF000094FF0800A4E464D4600F10C03C8 -:1020E00001930198FFF77EFE83460028C2D0142298 -:1020F0000021FFF7D7FA002E3BD10222009BABF85C -:1021000008300BF1080E1FFA82FC0CF10100BCF143 -:10211000060F218C80B201D88E422CD3FFF7AAFE85 -:10212000FFF78CFE8E4208BF4FF0400A626901380B -:10213000127880B202F01F0242EA49120BEB000152 -:102140004AEA020A013048F0004281F808A08BF800 -:10215000100059463846CBF80420FFF7ABFD238C1E -:102160000135B3424FF0000A2DB289F00109B8D110 -:1021700082E70022C5E7E169895D01360EF80210A9 -:10218000B6B20132BFE76FF0010575E7F8B5044656 -:1021900015460E46302200211F46FFF783FA069BA4 -:1021A000B5F5001F6360079B28BF4FF6FF72A3625F -:1021B0004FF0000338BF6A09A760E66197B204F1E7 -:1021C00010009A4206D800230360A782E38223838B -:1021D000E360F8BD0660013330462036F1E70000C9 -:1021E00003781BB94BB2002BC8BF017070470000C9 -:1021F00000787047F8B50C46C969074611B9238CB9 -:10220000002B37D1257E1F2D34D8387828BB228C5F -:10221000072A2CD8268A36F003032BD14FF6FF70FD -:10222000FFF7D4FD4FF6FF7220F0010036024004A4 -:1022300046EA0565400C45EA4025234629463846CE -:10224000FFF700FF002807DD626913780133DBB276 -:102250001F2B88BF00231370F8BD218A2D0645EA85 -:10226000012505432046FFF721FE0246E5E76FF012 -:102270000300F1E76FF00100EEE7000070B50446DF -:102280001D4616468AB0282200216846FFF70AFA42 -:10229000BDF838306946ADF810300F9B20460593E5 -:1022A0009DF84030CDE902658DF81830119B0793F9 -:1022B000BDF84830ADF82030FFF79CFF0AB070BD84 -:1022C0002DE9F041D36905460C4616460BB9138C2F -:1022D0005BBB377E1F2F28D895F80080B8F1000F20 -:1022E00026D03046FFF7E2FD3378210241EAC331C0 -:1022F00041EA0801338A41EA076141EA03410246A3 -:102300003346284641F08001FFF79CFE00280ADD95 -:102310003378012B07D1726913780133DBB21F2B9D -:1023200088BF00231370BDE8F0816FF00100FAE769 -:102330006FF00300F7E70000F0B504460D461E46B7 -:1023400017468BB0282200216846FFF7ABF99DF8AD -:102350004C3029465A1E534253418DF800309DF8A7 -:1023600040306A46ADF81030119B204605939DF829 -:102370004830CDE902768DF81830149B0793BDF8EC -:102380005430ADF82030FFF79BFF0BB0F0BD0000DC -:10239000406A00B104307047436A1A6842620269B9 -:1023A0001A600361C38A013BC38270472DE9F04183 -:1023B000D0F8208014461D4641460027174E09B923 -:1023C000BDE8F081D1E90223A21A65EB030396422E -:1023D00077EB03031ED2036A8B420DD1FFF790FD0A -:1023E000036A1B68036203690B60C38A0161016AA7 -:1023F000013B8846C382E2E7FFF782FD0B68C8F81D -:10240000003003690B60C38A0161013BC382D8F8C5 -:102410000010D4E788460968D1E700BF80841E0019 -:102420002DE9F04F8BB00D4614469B468046DDF8F3 -:102430005090002800F01A81B9F1000F00F01681C9 -:10244000531E3F2B00F21281012A03D1BBF1000F72 -:1024500040F00C810023CDE90833B8F81430B5EB17 -:10246000C30F4FEAC30703D300200BB0BDE8F08FC2 -:102470002B199F42D8F80C3036BF7F1B2746FFB27E -:102480001BB9D8F81030002B7BD0272D4ED8C5F1C2 -:102490002806B7424FF0000334BF3E46F6B2009321 -:1024A00029463246D8F8080008ABFFF745FCA7EBF1 -:1024B000060A35445FFA8AFA2821B8F8143003F185 -:1024C0000053053BDB000493D8F80C300393039BC7 -:1024D00013B1BAF1000F2CD1D8F8100040B1BAF105 -:1024E000000F05D05246009608AB691AFFF724FC8E -:1024F00038B2002FB8D066070AD00AAB03EBD4017C -:1025000011F8083C624202F00702134101F8083C4E -:10251000082C3DD9102C40F2B680202C40F2B88017 -:10252000BBF1000F00F09D80082335E0BA4600267D -:10253000C2E7049BE02B28BFE02306930B44AB4289 -:10254000059315D95A1B924538BF5246039828BFA8 -:10255000D2B20096691A08AB04300792FFF7ECFB81 -:10256000079A1644AAEB020A1544F6B25FFA8AFAF1 -:10257000049B069A05999B1A0493039B1B6803937B -:10258000A5E700933A462946D8F8080008ABADE71E -:10259000BBF1000F13D00123B4EBC30F6CD0082C98 -:1025A00012D89DF82030621E23FA02F2D50706D514 -:1025B0004FF0FF3202FA04F423438DF820309DF8E7 -:1025C000203089F8003050E7102C12D8BDF82030A8 -:1025D000621E23FA02F2D10706D54FF0FF3202FA4B -:1025E00004F42343ADF82030BDF82030A9F80030C2 -:1025F0003BE7202C0FD80899631E21FA03F3DA0772 -:1026000005D54FF0FF3202FA04F40C430894089BFE -:10261000C9F8003029E7402C2BD0DDE90865611EA0 -:10262000C4F12102A4F1210326FA01F105FA02F214 -:1026300025FA03F311431943CB0712D50122A4F164 -:102640002003C4F1200102FA03F322FA01F1A240AF -:10265000524243EA010363EB430332432B43CDE988 -:102660000823DDE90823C9E90023FEE66FF0010035 -:10267000FBE66FF00800F8E6082CA0D9102CB3D9BF -:10268000202CEED8C3E7BBF1000FADD0022383E7C7 -:10269000BBF1000FBBD004237EE70000012A30B558 -:1026A000144638BF01220025402A28BF402285B0A9 -:1026B000012CCDE9025517D81B788DF80830530747 -:1026C0000AD004AB03EBD20515F8083C544204F0E1 -:1026D0000704A34005F8083C0346009102A8002126 -:1026E000FFF72AFB05B030BD082CE5D9102C03D824 -:1026F0001B88ADF80830E2E7202C02D81B68029353 -:10270000DDE7D3E90045CDE90245D8E710B5CB6850 -:102710001BB98B600B618B8210BD04691A681C6049 -:102720000361C38A013BC382CA60F0E703064CBF62 -:10273000C0F3C0300220704708B50246FFF7F6FF2D -:10274000022806D15306C2F30F2001D100F0030086 -:1027500008BDC2F30740FBE72DE9F04F93B0CDE988 -:1027600003230A6804461046FFF7E0FF02280CBF67 -:102770000026C2F30626002A0D46824680F2F98121 -:1027800012F0C04940F0F581097B002900F0F18189 -:10279000022803D02378B34240F0EE81C2F30463F1 -:1027A0001046069302F07F030593FFF7C5FF059BD4 -:1027B00000224FEA8348002348EA0A48294448EAAD -:1027C0004668CE78CDE90823F309834648EA000835 -:1027D000029367D0059B02460093204653466768E4 -:1027E00008A9B847002800F0CA81276A4FB94146B6 -:1027F00004F10C00FFF704FB074690B96FF00200EC -:1028000054E03B6998450DD03F68002FF9D141460F -:1028100004F10C00FFF7F4FA07460028EED0236A13 -:102820003B60276297F817C006F01F08CCF3840CB2 -:10283000ACEB08001FFA80FE0028B8BF0EF12000A4 -:10284000A8EB0C031FFA83FEB8BF00B2002B07935E -:10285000BEBF0EF120031BB20793D7E9022152EA53 -:10286000010338D04FF0000C039BDFF8F8E19A1A0F -:10287000049B63EB010196457CEB01032BD36B7B3F -:1028800097F81AE0734519D1029B002B78D00128E4 -:1028900021DC7868F8B9DFF8D0C1944570EB01030A -:1028A00016D337E0276A27B96FF00C0013B0BDE8E4 -:1028B000F08F3B699845B5D03F68F4E76A4890428D -:1028C0007CEB010301D30020F0E7029B002BFAD040 -:1028D000079B0F2B17DCFA7DB30002F0030203F015 -:1028E0007C031343FB7539462046FFF709FB6B7BDE -:1028F000BB76029B3BB9FB7DC3F38402013262F3DA -:102900008603FB75D0E76A7BBB7E9A42DBD1029BD4 -:10291000002B35D0B309022B32D0039B1422BB60AD -:10292000049B0021FB600DA8FEF7BCFE039B204624 -:102930000A93049BADF83EB00B932B1D0C932B7B9D -:102940008DF840A0013BDBB2ADF83C30069B8DF822 -:1029500041808DF84230059B0AA98DF8433094F8E8 -:102960002C3083F001038DF84430A3689847FB7D39 -:10297000C3F38403013303F01F039B02FB82A2E72E -:10298000FB7DC6F34012B2EBD31F40F0FB80C3F3D4 -:102990008403434540F0F980029A2B7BB609002A54 -:1029A0004DD0F20762D4032B40F2F280039BAE1DA0 -:1029B000BB60049B3246FB602B7B3946033BDBB29A -:1029C00004F10C00FFF7AEFA00280CDA3946204675 -:1029D000FFF796FAFB7DC3F38403013303F01F0373 -:1029E0009B02FB820AE7AB88DDE908843B834FF654 -:1029F000FF73C9F12000A9F1200228FA09F104FAB5 -:102A000000F0014324FA02F211431846C9B2FFF75D -:102A1000CBF909F10809B9F1400F0346E9D1314674 -:102A2000B8822A7B033AD2B2FFF7D0F9FB7DB88295 -:102A3000DA43C2F3C01262F3C713FB7543E7AEB9C2 -:102A40002E1D013B32463946DBB204F10C00FFF784 -:102A500069FA0028BADB2A7B3146013AB88AD2B239 -:102A6000E2E700BF80841E0040420F00F98A013B6C -:102A7000C1F309010429DAB25DD80023281D07F14A -:102A80001B069A4208D910F801CB013306F801C0A1 -:102A900001310529DBB2F4D1934228BF0023039909 -:102AA00038BF04330A91049938BFDBB20B9107F1A8 -:102AB0001B010C91796838BF5B190D910E93FB8A4D -:102AC000ADF83EB0C3F309031A44069BADF83C20B1 -:102AD0008DF84230059B8DF840A08DF8433094F876 -:102AE0002C308DF8418083F001038DF844300023B1 -:102AF0007B602A7BB88A013A291DFFF767F93B8B77 -:102B0000B882834203D12046A3680AA99847204689 -:102B10000AA9FFF7FBFDFB7DBA8AC3F384030133E7 -:102B200003F01F039B02FB823B8B9A420CBF0020E9 -:102B30006FF01000BAE67B68002BADD0052001E0F5 -:102B400033461C301E68002EFAD1091A081D2E1DAE -:102B5000184401EB090CBCF11B0F5FFA89F39BD8F9 -:102B60009A4299D916F8013B09F1010900F8013B95 -:102B7000EFE76FF0090099E66FF00A0096E66FF054 -:102B80000B0093E66FF00D0090E66FF00E008DE6FF -:102B90006FF00F008AE600BFF0B53F4D3F4FEB6985 -:102BA00043F00073EB61EB693D4B9B6AD3F8006225 -:102BB0003E4046F00106C3F80062D3F800423C40B4 -:102BC00044EA002444F00104C3F80042002955D02F -:102BD00000200646C3F81C02C3F80402C3F80C0226 -:102BE000C3F8140203EBC00401300E28C4F840629D -:102BF000C4F84462F6D100274FF0010C967814888F -:102C000016F0010F18BFD3F804E20CFA04F01CBF51 -:102C100040EA0E0EC3F804E216F0020F18BFD3F814 -:102C20000CE203EBC4041CBF40EA0E0EC3F80CE236 -:102C3000760748BFD3F8146207F1010744BF064383 -:102C4000C3F814625668B942C4F84062966802F14B -:102C50000C02C4F84462D3F81C4240EA0400C3F8F2 -:102C60001C02CBD1D3F8002222F00102C3F80022CB -:102C7000EB6923F00073EB61EB69F0BD0122C3F84F -:102C80004012C3F84412C3F80412C3F81412C3F874 -:102C90000C22C3F81C22E5E7001002400000FFFFF1 -:102CA000A8230020184A08B5916A8B688B6013F03E -:102CB000010104D013F00C0F18BF4FF48031D80578 -:102CC00006D513F4406F14BF41F4003141F0020106 -:102CD000D80306D513F4402F14BF41F4802141F0EE -:102CE0000401D3690BB108489847302383F3118856 -:102CF0000021064800F048FB002383F31188BDE85B -:102D0000084000F099BD00BFA8230020B023002098 -:102D100038B5124CA36ADD68AA0712D05A6922F0AE -:102D200002025A61A36913B101212046984730235A -:102D300083F3118800210A4800F026FB002383F367 -:102D40001188EB0606D51021A36AD960236A0BB15E -:102D500002489847BDE8384000F06EBDA823002027 -:102D6000B823002038B5124CA36A1D69AA0712D0F7 -:102D70005A6922F010025A61A36913B10221204658 -:102D80009847302383F3118800210A4800F0FCFAA9 -:102D9000002383F31188EB0606D51021A36A19617D -:102DA000236A0BB102489847BDE8384000F044BDA3 -:102DB000A8230020B823002038B50F4CA36A5D6813 -:102DC0002A075D600AD5042222701A6822F00202E6 -:102DD0001A60636A13B10021204698476B0706D535 -:102DE000A36A9969236A13B1034809049847BDE8A7 -:102DF000384000F021BD00BFA823002010B50E4CC4 -:102E0000204600F02FF90D4B0B211320A36200F098 -:102E100009F90B21142000F005F90B21152000F011 -:102E200001F90B21162000F0FDF8BDE8104000224A -:102E30000E201146FFF7B0BEA8230020006400401A -:102E40000F4B10B59842044605D10E4BDA6942F09B -:102E50000072DA61DB690122A36A1A60A36A5A6808 -:102E6000D20707D5626851681268D9611A60064AAC -:102E70005A6110BD0121082000F0B0F9EEE700BF53 -:102E8000A8230020001002405B87010003291AD804 -:102E9000DFE801F0020A0F14836A9B6813F0E05F19 -:102EA00014BF012000207047836A9868C0F38060D7 -:102EB0007047836A9868C0F3C0607047836A9868F7 -:102EC000C0F30070704700207047000010B5032960 -:102ED00027D8DFE801F002272B2F836A9968C1F316 -:102EE0000161183103EB01131078840648BF546860 -:102EF000C0F3001158BF94884FEA410148BF41EA2E -:102F0000C40100F00F00586048BF41F00401906810 -:102F100058BF41EA4451D26841F001019860DA603B -:102F2000196010BD836A03F5C073DDE7836A03F59A -:102F3000C873D9E7836A03F5D073D5E701290AD0AE -:102F400002290FD081B9836ADA68920701D1186922 -:102F500003E001207047836AD86810F0030018BFAF -:102F600001207047836AF2E70020704710B539B935 -:102F7000836AD96889071BD11B699C0704D110BDDE -:102F8000012915D00229FAD1816AD1F8C031D1F8CE -:102F9000C441D1F8C8011061D1F8CC0150612020A2 -:102FA00008610869800717D1486940F0100012E0F5 -:102FB000816AD1F8B031D1F8B441D1F8B8011061CB -:102FC000D1F8BC0150612020C860C868800703D1D7 -:102FD000486940F002004861C3F34000C3F3800138 -:102FE000000140EA4111107920F0300001431171D5 -:102FF00089064BBF91681189DB085B0D4CBF63F3F9 -:103000001C0163F30A01137948BF916064F3030361 -:1030100013714FEA14234FEA144458BF11811370FF -:103020005480ACE70122090100F1604303F56143DC -:10303000C9B283F8001300F01F039A4043099B00B4 -:1030400003F1604303F56143C3F880211A607047C0 -:10305000090100F16040C9B200F56D40017670478A -:10306000FFF7CCBE01230370002300F10802C0E982 -:10307000022200F11002C0E90422C0E90633C0E9CF -:10308000083343607047000010B53023044683F3D3 -:103090001188022341600370FFF7D2FE0423002051 -:1030A000237080F3118810BD2DE9F0411F460446BE -:1030B0000D461646302383F3118800F10808237863 -:1030C000052B0DD029462046FFF7E0FE40B12046F3 -:1030D00032462946FFF7FAFE002080F3118808E007 -:1030E0003946404600F040F90028E8D0002383F339 -:1030F0001188BDE8F08100002DE9F0411F4604462B -:103100000D461646302383F3118800F1100823780A -:10311000052B0DD029462046FFF710FF40B1204671 -:1031200032462946FFF722FF002080F3118808E08D -:103130003946404600F018F90028E8D0002383F310 -:103140001188BDE8F08100000023826803750369DF -:103150001B6899689142FBD25A6803604260106014 -:103160005860704700238268037503691B6899687B -:103170009142FBD85A680360426010605860704703 -:1031800008B50846302383F311880B7D032B05D047 -:10319000042B0DD02BB983F3118808BD00228B6955 -:1031A0001A604FF0FF338361FFF7CEFF0023F2E791 -:1031B000D1E9003213605A60F3E70000FFF7C4BFA3 -:1031C000054BD96808751868026853601A600122B7 -:1031D0000275D860FDF79ABBD823002030B50C4BA0 -:1031E0000446DD684B1C87B00FD02B466846094A61 -:1031F00000F0F0F82046FFF7E3FF009B13B16846AC -:1032000000F0F0F8A86907B030BDFFF7D9FFF9E783 -:10321000D823002081310008044B1A68DB689068CD -:103220009B68984294BF002001207047D82300205B -:10323000084B10B51C68D868226853601A600122D8 -:103240002275DC60FFF78EFF01462046BDE8104086 -:10325000FDF75CBBD8230020044B1A68DB6892683A -:103260009B689A4201D9FFF7E3BF7047D82300203B -:1032700038B501230025064C0649074823706560D0 -:1032800000F020FB0223237085F3118838BD00BFB6 -:1032900030250020A43D0008D823002000F0B4B859 -:1032A000EFF3118020B9EFF30583302282F3118808 -:1032B0007047000010B530B9EFF30584C4F308047B -:1032C00014B180F3118810BDFFF7C6FF84F3118895 -:1032D000F9E700008B60022308618B820846704783 -:1032E0008368A3F1440243F8142C026943F8442C88 -:1032F000426943F8402C094A43F8242CC268A3F1E0 -:10330000200043F8182C022203F80C2C002203F8AA -:103310000B2C034A43F8102C704700BF1D0900080E -:10332000D823002008B5FFF7DBFFBDE80840FFF712 -:1033300045BF0000024BDB6898610F20FFF740BFDC -:10334000D8230020302383F31188FFF7F3BF000058 -:1033500008B50146302383F311880820FFF73EFFAC -:10336000002383F3118808BD064BDB6839B142683E -:1033700018605A60136043600420FFF72FBF4FF0BE -:10338000FF307047D823002038B504460D4620682A -:10339000844200D138BD036823605C608561FFF71B -:1033A0000DFFF4E710B50A4C23699A6891420CD8D6 -:1033B0005A6881600360426010609A685860511AD0 -:1033C00099604FF0FF33A36110BD1B68891AECE7C9 -:1033D000D8230020C0E90323002310B410BC4361AC -:1033E000FFF7E0BF036881689A680A449A60426800 -:1033F00013605A6000234FF0FF320360014B9A6163 -:10340000704700BFD823002070B5124D2A46EB69E3 -:103410000133EB6152F8103F934206D030269A6890 -:10342000013A9A602C69A36803B170BDD4E9002108 -:103430000A605160236083F311882046D4E9033188 -:10344000984786F3118861690029EBD02046FFF781 -:10345000A9FFE7E7D823002000207047FEE700001F -:10346000704700004FF0FF3070470000BFF34F8FF0 -:10347000024AD368DB07FCD4704700BF002002403B -:1034800008B5074B1B7853B9FFF7F0FF054B1A69D6 -:10349000120641BF044A5A6002F188325A6008BDE0 -:1034A00048250020002002402301674508B5054B50 -:1034B0001B7833B9FFF7DAFF034A136943F080033F -:1034C000136108BD48250020002002407F289ABFD4 -:1034D00000F5003080020020704700004FF480604B -:1034E00070470000802070477F2808B50BD8FFF791 -:1034F000EDFF00F580630268013204D1043083429D -:10350000F9D1012008BD0020FCE700007F2810B59C -:1035100004461CD8FFF7AAFFFFF7B2FFF3220D4BBA -:103520004FF48061DA6002221A61FFF7CFFF586121 -:103530001A6942F040021A61FFF798FF00F004F99F -:10354000FFF7B4FF2046BDE81040FFF7CDBF0020D5 -:1035500010BD00BF002002402DE9F843054612F0DF -:103560000100144606D040F2F32200201E4B1A60E0 -:10357000BDE8F8831D4BAA189A4204D94FF43E7255 -:10358000194B1A60F4E7FFF77BFF4FF00109FFF7D3 -:103590006DFFDFF85C806D1A012C0F4605EB01060C -:1035A00003D8FFF783FF0120E2E73B88C8F81090BB -:1035B00033800020FFF75AFFC8F81000338831F835 -:1035C000022B9BB29A420CD040F20F32064B1A608B -:1035D000084B1E60084B1C60084B1F60FFF766FF1E -:1035E000C6E7023CD8E700BF4425002000000208DF -:1035F0000020024038250020402500203C250020E6 -:10360000084908B50B7828B11BB9FFF739FF01232A -:103610000B7008BD002BFCD0BDE808400870FFF718 -:1036200045BF00BF4825002070B5FFF739FE4FF4B5 -:103630007A710D4B0D4EDB69326801FB03F3934247 -:1036400037BF0B4A0A495168156836BF4C1CD1E98F -:10365000005454605D1944F100043360FFF72AFE02 -:103660002846214670BD00BFD82300204C250020ED -:103670005025002070B5FFF713FE4FF47A710F4B01 -:103680000F4EDB69326801FB03F3934237BF0D4AEB -:103690000C49516815683ABF4C1C5460D1E900547C -:1036A0005D1944F100043360FFF704FE4FF47A72B1 -:1036B000002328462146FCF735FF70BDD8230020A3 -:1036C0004C2500205025002010B5094C013AD2B2FB -:1036D000FF2A00D110BD500854F82030013054F8B2 -:1036E00020009BB243EA004341F8043BEEE700BFF1 -:1036F000046C004010B50748013AD2B2FF2A00D14D -:1037000010BD0C88530840F823404C88013340F822 -:103710002340F1E7046C004007B50122002001A915 -:10372000FFF7D2FF019803B05DF804FB13B5044620 -:10373000FFF7F2FFA04205D00122002001A9019469 -:10374000FFF7D8FF02B010BD7047000045F2555298 -:10375000064B1A6002225A6040F6FF729A604CF6DD -:10376000CC421A600122024B1A70704700300040B0 -:103770005C250020034B1B781BB14AF6AA22024BA2 -:103780001A6070475C25002000300040044B1A6826 -:103790002AB902F1804202F50432526A1A60704777 -:1037A000582500204FF08072014B5A62704700BFCD -:1037B0000010024008B5FFF7E9FF024B1868C0F39C -:1037C000407008BD5825002008B5FFF7DFFF024B09 -:1037D0001868C0F3007008BD58250020EFF3098376 -:1037E000203383F30988002383F311887047000096 -:1037F000302080F3118862B60C4B0D4AD96821F451 -:10380000E0610904090C0A43DA60D3F8FC20094995 -:1038100042F08072C3F8FC200A6842F001020A609C -:103820002022DA7783F82200704700BF00ED00E025 -:103830000003FA05001000E0302310B583F311886F -:103840000B4B5B6813F400630FD0EFF309844FF068 -:103850008073203CE36184F30988FFF7DDFC10B13D -:10386000044BA36110BD044BFBE783F31188F9E718 -:1038700000ED00E02F090008320900087047000041 -:10388000FEE700000A4B0B480B4A90420BD30B4B50 -:10389000C11EDA1C121A22F003028B4238BF00222A -:1038A0000021FDF7FFBE53F8041B40F8041BECE7B2 -:1038B000243E0008E0250020E0250020E02500202F -:1038C000FEE7000070B5002504461A4B86B058602C -:1038D000856201630E46FFF78BFF04F11003C4E914 -:1038E00004334FF0FF33A361134BE561D9692B46D5 -:1038F0000A462046C4E9082304F134018023C4E9C0 -:1039000000440E4AA560E5622565FFF7E3FC01234C -:103910000B4AE06003750092726868460192B268D3 -:10392000CDE90223074BCDE90435FFF7FBFC06B0D8 -:1039300070BD00BF30250020D8230020B03D000816 -:10394000B53D0008C138000800F030B808B500F0F7 -:1039500063F9FFF78DFCBDE80840FFF717BF0000D3 -:10396000704700004FF0FF310E4B1A6919611A6958 -:1039700000221A611869D868D960D968DA60DA68F3 -:10398000DA6942F08052DA61DA69DA6942F000629B -:10399000DA61054ADB69136843F48073136000F051 -:1039A0001BB900BF0010024000700040194B1A689C -:1039B00042F001021A601A689007FCD51A6802F0FA -:1039C000F9021A6000225A605A6812F00C0FFBD1FB -:1039D0001A6842F480321A601A689103FCD55A685A -:1039E00042F4E8125A601A6842F080721A601A684B -:1039F0009201FCD51221084A5A60084A11605A689F -:103A000042F002025A605A6802F00C02082AFAD107 -:103A1000704700BF0010024000641D0000200240FB -:103A2000084A08B5516913680B4003F0010353615C -:103A300023B1054A13680BB150689847BDE80840A8 -:103A4000FFF7FABE0004014060250020084A08B5CF -:103A5000516913680B4003F00203536123B1054A17 -:103A600093680BB1D0689847BDE80840FFF7E4BE03 -:103A70000004014060250020084A08B55169136818 -:103A80000B4003F00403536123B1054A13690BB1E2 -:103A900050699847BDE80840FFF7CEBE00040140DA -:103AA00060250020084A08B5516913680B4003F0EF -:103AB0000803536123B1054A93690BB1D069984754 -:103AC000BDE80840FFF7B8BE0004014060250020B3 -:103AD000084A08B5516913680B4003F0100353619D -:103AE00023B1054A136A0BB1506A9847BDE80840F4 -:103AF000FFF7A2BE0004014060250020174B10B55F -:103B00005A691C68144004F478725A61A30604D5FB -:103B1000134A936A0BB1D06A9847600604D5104ADD -:103B2000136B0BB1506B9847210604D50C4A936B6D -:103B30000BB1D06B9847E20504D5094A136C0BB161 -:103B4000506C9847A30504D5054A936C0BB1D06C13 -:103B50009847BDE81040FFF76FBE00BF000401406A -:103B6000602500201A4B10B55A691C68144004F4F3 -:103B70007C425A61620504D5164A136D0BB1506D33 -:103B80009847230504D5134A936D0BB1D06D984720 -:103B9000E00404D50F4A136E0BB1506E9847A10490 -:103BA00004D50C4A936E0BB1D06E9847620404D5CD -:103BB000084A136F0BB1506F9847230404D5054A88 -:103BC000936F0BB1D06F9847BDE81040FFF734BE3C -:103BD0000004014060250020062108B50846FFF7D3 -:103BE00021FA06210720FFF71DFA06210820FFF71A -:103BF00019FA06210920FFF715FA06210A20FFF716 -:103C000011FA06211720FFF70DFABDE8084006213A -:103C10002820FFF707BA000008B5FFF7A3FE054804 -:103C200000F00CF8FFF71CFAFFF79AFEBDE8084019 -:103C300000F002B8BC3D000800F042B8002319466D -:103C40001C4A0133102BC2E9001102F10802F8D11D -:103C5000194B9A6942F07D029A619B690268174B81 -:103C6000DA6082685A6042681A60C26803F580634D -:103C7000DA6042695A6002691A608269C3F80C24EA -:103C8000026AC3F80424C269C3F80024426AC3F874 -:103C90000C28C26AC3F80428826AC3F80028026BA1 -:103CA000C3F80C2C826BC3F8042C426BC3F8002CB5 -:103CB000704700BF6025002000100240000801404E -:103CC0004FF0E023044A08215A6100229A6107223A -:103CD0000B201A61FFF7BCB93F19010008B530236A -:103CE00083F31188FFF7DAFA002383F3118808BD04 -:103CF00008B5FFF7F3FFBDE80840FFF79DBD0000E2 -:103D000010B501390244904201D1002005E003784A -:103D100011F8014FA34201D0181B10BD0130F2E78A -:103D20002DE9F0419BB10446C91A1778014403F10B -:103D3000FF3C8C42204601D9002008E00578013480 -:103D4000BD42F6D10CEB0405D618A54201D1BDE861 -:103D5000F08115F8018D16F801EDF045F5D0E8E792 -:103D6000034611F8012B03F8012B002AF9D1704703 -:103D70006F72672E6172647570696C6F742E663134 -:103D800030332D48574553430000000040A2E4F172 -:103D9000646891060041A3E5F2656992070000009E -:103DA00063300000A03D00083024002030250020B2 -:103DB0006D61696E0069646C6500000000180000A8 -:103DC00044444144445449440100000042444444B2 -:103DD00044444444000000004444444444444444B3 -:103DE00000000000444444444444444400000000B3 -:103DF00044444444444444445CC7FF7F0100000001 -:103E0000E803000000000000009C0100000000002A -:103E1000640000000000000040420F00FE2A010084 -:043E2000D2040000C8 +:10052000704700BF02E000F000F8FEE772B6264810 +:1005300080F30888254880F3098825482549086004 +:10054000022080F31488BFF36F8F03F021F803F0CB +:1005500085F84FF0553020491B4A91423CBF41F885 +:10056000040BFAE71D49194A91423CBF41F8040BBC +:10057000FAE71B491B4A1C4B9A423EBF51F8040B39 +:1005800042F8040BF8E700201849194A91423CBF91 +:1005900041F8040BFAE702F0FFFF03F061F8154C95 +:1005A000154DAC4203DA54F8041B8847F9E700F014 +:1005B0003FF8124C124DAC4203DA54F8041B884742 +:1005C000F9E702F0E7BF0000000900200011002059 +:1005D0000000000808ED00E00001002000090020F4 +:1005E000103B0008001100202411002028110020D9 +:1005F000D4250020600100086001000860010008A7 +:10060000600100082DE9F04FC1F80CD0C3689D4689 +:10061000BDE8F08F002383F311882846A04700200F +:1006200002F0E2FCFEE702F07BFC00DFFEE70000E8 +:10063000F8B500F037FE02F0F9FE074602F044FF7D +:10064000064600283ED12B4B9F423BD001339F42B0 +:100650003BD0294B27F0FF029A4239D1F8B200F083 +:10066000FDFB354642F2107400F0FEFB08B1002499 +:10067000254601F0FFF878B30024032000F042F88B +:10068000254636B11D4B9F4203D0002402F014FFD3 +:100690002546002002F0D4FE194B9B6813F040035E +:1006A0001FD00DB100F044F800F03EFC01F076F9E7 +:1006B0000546C4B101F072F9401BA04213D900F005 +:1006C00037F8F3E735460024CEE704460125CBE7AB +:1006D00005464FF47A74C7E7B4F57A7F08BF012561 +:1006E000CFE71C46E0E700F0D1FC012002F082FCDD +:1006F000DFE700BF010007B0000008B0263A09B0EC +:10070000000C0140084B187003280CD8DFE800F0FB +:1007100008050208022000F021BE022000F016BEEB +:100720000022024B5A607047281100202C11002033 +:1007300038B501F09FF830B103221F4B1A70002228 +:100740001E4B5A6038BD1E4B1E4A19680131F9D044 +:1007500004339342F9D11C4C194DD4F80424AA4215 +:10076000F0D31A4B9B6803F1006303F5C8439A4228 +:10077000E8D202F075FE02F087FE002000F0ACFD2A +:100780000220FFF7BFFF124BDA690022DA61D96954 +:1007900099699A619B6972B64FF0E023C3F8085DCE +:1007A0003021D4F80034D4F8042481F311889D4614 +:1007B00083F308881047C5E7281100202C1100207A +:1007C0000064000820640008006000080011002098 +:1007D0000010024049F26900084A136899B21B0CE4 +:1007E00000FB013344F250611360054B186882B27C +:1007F000000C01FB0200186080B27047201100203D +:100800001C11002010B504460021102200F0C2FD8A +:10081000034B03CB206061601868A06010BD00BF6F +:10082000E8F7FF1F2DE9F0410026ADF54E7D6CACD9 +:1008300040F2751207460D460EA831460D9600F09F +:10084000A9FD31464FF4C472204600F0A3FD01F02B +:10085000A5F84FF47A72B0FBF2F0244B0DF1340896 +:10086000186093E80700022384E807000DF5E9709B +:100870002382FFF7C7FF4EF603031D4906A8238412 +:1008800003F0F8F818230DF2E32684F832310DF165 +:10089000300C6B441A4603CA6245306071601346DF +:1008A00006F10806F6D141460122204600F0BEFDC1 +:1008B00000230393AB7E80B2029305F119030193E9 +:1008C0000123CDE904800093384606A3D3E9002331 +:1008D000E97E01F0A9FB0DF54E7DBDE8F08100BF7A +:1008E000AFF300809E6AC421818A46EE3411002055 +:1008F000843A00082DE9F041264D80462B7A0C46BB +:10090000DAB0FBB9204627A900F0A0FE0746002870 +:1009100036D19DF89D60C82E32D801464FF4FA7248 +:10092000284600F037FD32460DF19E0105F1090021 +:1009300000F01EFD9DF89C302E4477722B720BB98F +:10094000E37E2B728122002106AD27A800F022FD54 +:100950000122294627A800F0B5FE00230393A37EB9 +:1009600080B2029304F1190301932823CDE90450C6 +:100970000093404605A3D3E90023E17E01F054FB38 +:100980005AB0BDE8F08100BFAFF30080264172721B +:10099000DF25D7B77C210020F0B54FF48A750024FD +:1009A000234EF1B005FB006596F8D830D8222146D9 +:1009B00085F8DC3085F8E8403AA800F0EBFC06F159 +:1009C000090000F0DFFCD5F8E430C2B206AF8DF8C4 +:1009D000F00006F109010DF1F100CDE93A3400F023 +:1009E000C7FC394601223AA800F098FE80B2CDE952 +:1009F000047008230127CDE9023706F1D8030193DB +:100A00003023317A00930B4807A3D3E9002301F088 +:100A10000BFBA04206DD00F0C1FFC5F8E000384640 +:100A200071B0F0BD2046FBE778F6339F93CACD8DB9 +:100A30007C2100204C210020F0B51E4E1E4F1F4D82 +:100A400085B0304601F01CFB044660B31022002143 +:100A5000684600F09FFC4FF00003227B6068A168AD +:100A600062F303038DF8003002AB03C3019B2268DD +:100A7000384662F31C0301939DF800306A4643F048 +:100A800020038DF800300023194602F085F9044652 +:100A900020B9304601F0F8FA2C70D2E72B78072BFA +:100AA00003D801332B7005B0F0BD024801F0ECFA19 +:100AB000F9E700BF4C210020A82300207523002067 +:100AC00070B50D4614461E4601F00AFA50B9022EC2 +:100AD00010D1012C0ED112A3D3E900230120C5E9C6 +:100AE000002307E0282C10D005D8012C09D0052CB4 +:100AF0000FD0002070BD302CFBD10BA3D3E9002315 +:100B0000ECE70BA3D3E90023E8E70BA3D3E9002329 +:100B1000E4E70BA3D3E90023E0E700BFAFF30080D5 +:100B2000401DA12026812A0B78F6339F93CACD8DD4 +:100B30009E6AC421818A46EE26417272DF25D7B7AC +:100B4000F017304A39059E5638B505460E4C00213F +:100B5000013500F0E3FBA4F8F051B4F8F00100F027 +:100B6000C5FB78B1B4F8F00100F0D0FB014648B9FC +:100B7000B4F8F00100F0D2FBB4F8F0310133A4F87E +:100B8000F031EAE738BD00BF7C2100202DE9F04FAD +:100B90008DB000AF04460D4601F0A2F9002846D101 +:100BA0002B7E022B1AD1EB8A012B17D100F0F6FE17 +:100BB0000646FFF70FFE4FF4C873B0FBF3F202FBDB +:100BC0001303DFF878829BB206F516763344C8F833 +:100BD0000030EB7E33B90022994B1A703437BD4692 +:100BE000BDE8F08F284607F11C0100F0EDFC00285D +:100BF000F4D107F10C00FFF705FEBD7F07F10C01F2 +:100C00002A4607F11F0002F005FF0028E3D10F2D4F +:100C100008D88B4B1D70D8F80030A3F51673C8F8B0 +:100C20000030DBE72046397F01F052F9D6E7EB8A46 +:100C3000282B6BD010D8012B63D0052BCED1BFF35E +:100C40004F8F8049804BCA6802F4E0621343CB6047 +:100C5000BFF34F8F00BFFDE7302BBFD17B4CEA7E47 +:100C6000237A9A42BAD194F8DC206B7E9A42B5D1AD +:100C7000284604F1EA0100F07DFD06460028ADD1CA +:100C8000012384F8E83000F089FED4F8E030C01A7F +:100C9000192840F6B83338BF1920984228BF1846A3 +:100CA000FFF7C8FB6A49FFF75BFA05462068FFF7C4 +:100CB000C1FB6849FFF754FA01462846FFF70AFBD3 +:100CC000FFF710FC20604FF48A7194F8D9307B60F4 +:100CD0007A68636801FB02F5621992F8E80050B186 +:100CE000D2F8E400E946834215D0002382F8E830C8 +:100CF000C2F8E030CD466368574A9B0A013313813E +:100D00006CE729462046FFF78DFD67E72946204618 +:100D1000FFF7F0FD62E7B2F8EC803B6008F1030AF0 +:100D20004FEA9A0A4FEA8A02D11DC908A9EBC1030A +:100D30009D46EB460021584600F02CFB05F1EE01E4 +:100D400042465846214400F013FB3B6813B901208A +:100D500000F0C2FA94F8D20000F0C8FA054630B9A3 +:100D6000207200F0E3FA284600F0B6FAC2E7D4F8A1 +:100D7000D4303BB994F8D200B4F8F031834201D8B2 +:100D8000FFF7E2FED4F8D43043449D4208D294F8F1 +:100D9000D200B4F8F0310130834201D8FFF7D4FE1D +:100DA000594660685FFA8AF200F0FCFA08B9CD464D +:100DB00089E7636894F8D20043446360D4F8D43080 +:100DC00008EB030AC4F8D4A000F090FA824509D3D6 +:100DD00094F8D230D4F8D4000133401B84F8D230D8 +:100DE000C4F8D400B8F1FF0F0FD80025257200F029 +:100DF0009DFA284600F070FA00F03CFD164B188171 +:100E000008B9FFF795FCCD46E8E64FF48A727B6897 +:100E100094F8D90002FB0343D3F8E42083F8E86098 +:100E200002F58072C3F8E060C3F8E420FFF7B4FD78 +:100E3000FFF702FE84F8D960B9E700BF482100201F +:100E40004521002000ED00E00400FA057C2100208F +:100E5000CDCCCC3D6666663F34110020014B187046 +:100E6000704700BF4011002030B54FF00054254BB3 +:100E7000226885B09A4207D002F030FB0446C0B920 +:100E80000024204605B030BD0025627D1E4B1F4862 +:100E90001A70237DC92203721D49C0F8E45009303D +:100EA00000F066FA2046E022294600F073FA012499 +:100EB000E7E7184A184DD36943F00073D361AA6D70 +:100EC000164B9A42DCD12B6E013B7E2BD8D8144AAC +:100ED00001AB07CA83E807001846032100F09AFC1B +:100EE0006B6D83424FF00003CAD12A6D8A4203BF63 +:100EF000AB652A6E044B1C4601BF1A70EA6D094BA4 +:100F00001A60BEE79AAD44C5401100207C21002044 +:100F10001600002000100240006600405041A0B0C2 +:100F200058660040181100202DE9F04385B000F00C +:100F3000A1FC0223494C637100230293484B20819A +:100F4000D3F800C0BCF57A7F12D3464F464BB7FBAF +:100F5000FCF59C458CBF0A231123B5FBF3F603FB7C +:100F60001652591EC8B2002A3ED002290B46F4D8A8 +:100F70009DF80B303D495A1E9DF80A303C48013B14 +:100F80001B0443EA0253BDF80820013A13434B60A7 +:100F900001F0F2FE00230193364B374900934FF4E2 +:100FA0008052364B364800F069FF364B197811B144 +:100FB000334800F08DFF00F0F1FC0546FFF70AFC16 +:100FC0004FF4C873B0FBF3F202FB130305F5167080 +:100FD0009BB218442C4B186002F076FA08B10F232C +:100FE000238105B0BDE8F083731EB3F5806FBFD2D7 +:100FF0004FF47A75C0EBC00E0EF103034FEAE3091C +:1010000009FB0555C3F3C703C11AC9B209F10108A9 +:101010008844B5FBF8F5B5F5617F08D90EF1FF33CB +:10102000C3F3C703C11A581E0F28C9B214D84A1EE9 +:10103000072A8CBF00220122581800FB0660B7FB6C +:10104000F0F7BC4594D1002A92D0ADF808608DF835 +:101050000A308DF80B108BE71346EDE734110020B2 +:1010600018110020005125023F420F0010110020EE +:10107000A8230020C10A0008441100208D0B00089D +:101080004C21002040110020482100202DE9F04F84 +:1010900080A7D7E900670FF20429D9E90089734DC9 +:1010A00093B00DF1300AFFF7C7FC1822002150461B +:1010B00000F070F9DFF8B8B16E4C002352461946C3 +:1010C000584601F091FE014650BB102208A800F0DE +:1010D00061F9E36883F01003E36000F061FC0DF157 +:1010E000240C0B4612A9024611E903008CE8030008 +:1010F0009DF83410C1F30300890649BF0E99BDF86D +:101100003810C1F31C0141F0004158BFC1F30A017E +:101110008DF82C000891284608A901F095F9CCE734 +:10112000284600F0DDFE0446002847D100F036FCDA +:10113000DFF844B1DBF8003098423FD300F02EFCDA +:101140000790FFF747FB4FF4C873B0FBF3F101FBC7 +:101150001300079A83B202F516701844CBF800000A +:10116000DFF818B18DF820409BF8001011B9012369 +:101170008DF8203050460791FFF744FB07990DF199 +:101180002100C1F11004E4B2062C28BF062451440A +:10119000224600F0EDF808AB039318230293384B76 +:1011A000013401930123E4B2009332463B462846C2 +:1011B000049400F0DBFE00238BF8003000F0EEFB1F +:1011C000304A314C1368C31AB3F57A7F30D31060BC +:1011D00000F0E6FB02460B46284600F05FFF28467B +:1011E00000F07EFE20B3237ADFF8A0B0002B14BFFE +:1011F000032302238BF8053000F0D0FB4FF47A7301 +:10120000B0FBF3F00122CBF800005146584600F045 +:10121000B3F9182302931E4B80B2019340F2551389 +:10122000CDE903A0009342464B46284600F09EFEBF +:10123000237ABBB100F0B2FB94F8E83073B9D4F86C +:10124000E03043B1C01A2368FA2B38BFFA230533C4 +:10125000B0EB430F02D30020FFF79EFB237A002B55 +:101260007FF41FAF13B0BDE8F08F00BF4C2100200A +:10127000A82300200008014048210020452100202B +:1012800044210020702300207C2100203411002004 +:1012900074230020401DA12026812A0BF1C6A7C17E +:1012A000D068080F70B501F07DFF0024084E094D8D +:1012B000308028683388834208D901F06FFF2B689B +:1012C00004440133B4F5C84F2B60F2D370BD00BFA6 +:1012D000A42300207823002001F0F2BF00F1006079 +:1012E000920000F5C84001F097BF0000054B1A6856 +:1012F000054B1B889B1A834202D9104401F04EBF54 +:101300000020704778230020A4230020024B1B6894 +:10131000184401F049BF00BF78230020024B1B682E +:10132000184401F053BF00BF78230020064991F80C +:10133000243033B100230822086A81F82430FFF7F3 +:10134000CDBF0120704700BF7C230020022802BFD0 +:101350001022014B1A61704700080140022802BFA9 +:101360004FF48012014B1A61704700BF0008014022 +:10137000002310B5934203D0CC5CC4540133F9E789 +:1013800010BD000003460246D01A12F9011B0029C5 +:10139000FAD1704703460244934202D003F8011B7E +:1013A000FAE770472DE9F8431F4D144695F82420BD +:1013B0000746884652BBDFF870909CB395F82430FE +:1013C0002BB92022FF2148462F62FFF7E3FF95F853 +:1013D00024004146C0F10802A24228BF224605EB84 +:1013E0008000D6B29200FFF7C3FF95F82430A41B0B +:1013F0001E44F6B2082E17449044E4B285F82460E7 +:10140000DBD1FFF793FF0028D7D108E02B6A03EB6D +:1014100082038342CFD0FFF789FF0028CBD1002081 +:10142000BDE8F8830120FBE77C2300202DE9F0478D +:101430000D46044600219046284640F27912FFF7F7 +:10144000A9FF234620220021284600F09FFF022208 +:1014500020212846231D00F099FF0322222128463F +:10146000631D00F093FF032225212846A31D00F0F1 +:101470008DFF10222821284604F1080300F086FF82 +:1014800008223821284604F1100300F07FFF0822CB +:101490004021284604F1110300F078FF082248217A +:1014A000284604F1120300F071FF20225021284643 +:1014B00004F1140300F06AFF40227021284604F171 +:1014C000180300F063FF0822B021284604F120032E +:1014D00000F05CFF0822B821284604F1210300F047 +:1014E00055FFC02604F122073B4631460822284614 +:1014F000083600F04BFFB6F5A07F07F10107F3D1E6 +:1015000008223146284604F1320300F03FFF00274D +:1015100004F1330A94F832304FEAC7099F4209F5C3 +:10152000A47615D3B8F1000F08D13146072228461A +:1015300004F5997300F02AFF09F24F16274694F834 +:1015400032213B1B93420CD3F01DC008BDE8F0874D +:101550000AEB070308223146284600F017FF01373F +:10156000D8E7314607F233130822284600F00EFF71 +:1015700008360137E3E7000038B50C460021054680 +:1015800021600346C4F803102046202200F0FEFE2E +:1015900020462B1D0222202100F0F8FE20466B1D64 +:1015A0000322222100F0F2FE2046AB1D032225215A +:1015B00000F0ECFE20461022282105F1080300F07F +:1015C000E5FE072038BD00000023F7B50E460546AE +:1015D000047F07220091194600F09AFD731C0093C6 +:1015E000012200230721284600F092FDC4B9B31C54 +:1015F0000093052223460821284600F089FD0D248A +:101600003746B278BB1B934211D32B7FE01DC00835 +:10161000AC8ABBB9A04294BF0020012003B0F0BD4A +:10162000AB8A0824DB00083BDB08B370E8E7FB1C4F +:101630002146009308220023284600F069FD083463 +:101640000137DEE7001B18BF0120E7E70023F7B5ED +:101650000E46047F082200911946054600F058FD09 +:10166000731CC4B90822009311462346284600F093 +:101670004FFD1024012372785F1C013B934211D36C +:101680002B7FE01DC008AC8ABBB9A04294BF0020EC +:10169000012003B0F0BDAB8A0824DB00083BDB0867 +:1016A0007370E7E7F31921460093082200232846C8 +:1016B00000F02EFD08343B46DDE7001B18BF01207B +:1016C000E7E70000F8B50E460546144600218122E2 +:1016D0003046FFF75FFE2B4608220021304600F01F +:1016E00055FE7CB90722082130466B1C00F04EFEE7 +:1016F0000F2401236A785F1C013B934204D3E01D51 +:10170000C008F8BD0824F4E72146EB19082230464A +:1017100000F03CFE08343B46ECE70000F8B50E460E +:10172000054614460021CE223046FFF733FE2B46F5 +:1017300028220021304600F029FE7CB90822282109 +:10174000304605F1080300F021FE30242F462A7AA6 +:101750007B1B934204D3E01DC008F8BD2824F5E7A5 +:10176000214607F109030822304600F00FFE083435 +:101770000137ECE7F7B5047F0E46009101231022F4 +:101780000021054600F0C4FCC4B9B31C0093092233 +:1017900023461021284600F0BBFC192437467288E6 +:1017A000BB1B9A4211D82B7FE01DC008AC8ABBB985 +:1017B000A04294BF0020012003B0F0BDAB8A1024EA +:1017C000DB00103BDB087380E8E73B1D21460093FC +:1017D00008220023284600F09BFC08340137DEE78E +:1017E000001B18BF0120E7E730B5094D0A449142BC +:1017F0000DD011F8013B5840082340F30004013B91 +:101800002C4013F0FF0384EA5000F6D1EFE730BD1F +:101810002083B8ED4FF0FF33F7B500EB8106194692 +:10182000DFF848C0DFF848E0B0421BD050F8042B86 +:1018300001AF0192042217F8014B81EA04610824E8 +:101840000D46DB184941013C002DBCBF83EA0C0367 +:1018500081EA0E0114F0FF04F2D1013A12F0FF0206 +:10186000E9D1E1E7D843C94303B0F0BD9336EAA913 +:10187000EBE1F042F7B56B46354A106851686A46AD +:1018800003C308233349344802F0D4F8044690BB1C +:101890000A256B46314A106851686A4603C308231B +:1018A0002F492D4802F0C6F80446002847D00369A6 +:1018B000B3F5CE3F43D8B0F86620B2F57A7F3ED17B +:1018C000284A024402F15C018B4238D35C3B224936 +:1018D00000209E1AFFF788FF07463246002004F1D9 +:1018E0006401FFF781FFA3689F4228D1E368984213 +:1018F00008BF002523E00369B3F5CE3F26D8428B0D +:10190000B2F57A7F20D1174A024402F110018B42CE +:1019100018D3103B104900209D1AFFF765FF0646BB +:101920002A46002004F11801FFF75EFFA3689E42DB +:1019300002D1E368984201D00D25AAE70025284688 +:1019400003B0F0BD1025A4E70C25A2E70B25A0E706 +:10195000A03A0008DC9B010000640008A93A0008D6 +:10196000909B0100089CFFF7EFF30983EFF30583D9 +:10197000014B9B6BFEE700BF00ED00E008B5FFF7F1 +:10198000F3FF0000EFF30983EFF30583014B5B6B7B +:10199000FEE700BF00ED00E0FEE7000001F0F6BC4E +:1019A00001F0A2BC2DE9F041456A15B94162BDE8DC +:1019B000F0814B68AC4623F06047C3F38A4616EAD1 +:1019C000230638BF3E464FEAD37EC3F380782B46CA +:1019D0005A68BEEBD27F22F060440AD0002A18DA9F +:1019E000A40CB44217D19D420FD10D60DEE713461F +:1019F000EEE7A74207D102F08044C2F3807242456D +:101A00000BD054B1EFE708D2EDE7CCF800100B6033 +:101A1000CDE7B44201D0B442E5D81A689C46002A0A +:101A2000E5D11960C3E700002DE9F0474FF47F4985 +:101A3000089D01F007044FEAD508224405F0070588 +:101A400000EBD100944201D1BDE8F08704F0070714 +:101A500005F0070A57453E4638BF5646111BC6F1EA +:101A600008068E4228BF0E46E108415C08EBD50E01 +:101A700013F80EC0B94029FA06F721FA0AF1FFB2AD +:101A80008CEA010147FA0AF739408CEA010C03F8A5 +:101A90000EC034443544D5E7082341F2210280EAE0 +:101AA000012001B24000002980B203F1FF33B8BF2A +:101AB000504013F0FF03F4D17047000038B50C46D6 +:101AC0008D18A54200D138BD14F8011BFFF7E4FFC3 +:101AD000F7E700000346406848B1026899895A60F8 +:101AE0005A89013292B291425A8138BF9A81704725 +:101AF00070B504460D4688B0202200216846FFF7E5 +:101B000049FC20460495FFF7E5FF024658B16B46B5 +:101B1000054608AE1C4603CCB442286069602346E3 +:101B200005F10805F6D1104608B070BD082817D990 +:101B300009280CD00A280CD00B280CD00C280CD06B +:101B40000D280CD00E2814BF4020302070470C20E8 +:101B500070471020704714207047182070472020CD +:101B600070470000082817D90C280CD910280CD968 +:101B700014280CD918280CD920280CD930288CBF4F +:101B80000F200E207047092070470A2070470B2055 +:101B900070470C2070470D20704700002DE9F84376 +:101BA000078C0446072F1ED9D0E9029800254FF66E +:101BB000FF73C5F12006A5F1200029FA05F108FA06 +:101BC00006F628FA00F031430143C9B21846FFF780 +:101BD00063FF0835402D0346EBD13A46E169BDE885 +:101BE000F843FFF76BBF4FF6FF70BDE8F8830000C6 +:101BF00010B54B6823B9CA8A63F30902CA8210BDC3 +:101C000004691A681C600361C38A013BC3824A608D +:101C1000EFE700002DE9F84F1D46CB8A0F46C3F3CE +:101C200009010529814692460B4630D00020AAB210 +:101C300007F11A049EB2042E1FFA80F80FD89045BF +:101C400003F1010306D3FB8A0A4462F3090301206E +:101C5000FB821AE01AF800600130E654EAE790458A +:101C6000F1D21C23A1F1050BBBFBF3F203FB12BB6A +:101C70007C681FFA8BF6002C45D14846FFF72AFFF7 +:101C8000044638B978606FF00200BDE8F88F4FF075 +:101C90000008E6E70026066078604FF0000BADB262 +:101CA000454510D90AEB0803221D13F8011B08F162 +:101CB00001089155B1B21B291FFA88F82BD0454570 +:101CC00006F10106F1D8FB8AC3F30902154465F356 +:101CD0000903BCE71C46013292B22368002BF9D1FC +:101CE0006B1F0B441C21B3FBF1F301339BB29A42EF +:101CF000D3D2BBF1000FD0D14846FFF7EBFE20B99D +:101D0000C4F800B0BFE70122E7E7C0F800B05E46C4 +:101D100020600446C1E74545D5D94846FFF7DAFEBD +:101D200008B92060AFE7C0F800B000262060044684 +:101D3000B6E700002DE9F74F1C465B690746884669 +:101D40000092002B00F09780238C2BB1E269002ACF +:101D500000F09180072B33D807F10C00FFF7BAFE93 +:101D6000054628B96FF00205284603B0BDE8F08F9C +:101D700014220021FFF70EFB228CE16905F1080017 +:101D8000FFF7F6FA208C48F00041013080B2FFF7EF +:101D9000E9FEFFF7CBFE013880B2208401302874C1 +:101DA0006369228C1B782A4403F01F0363F03F030E +:101DB0001372384669602946FFF7F4FD0125D3E721 +:101DC0004FF000094FF0800A4E464D4600F10C03DB +:101DD00001930198FFF77EFE83460028C2D01422AB +:101DE0000021FFF7D7FA002E3BD10222009BABF86F +:101DF00008300BF1080E1FFA82FC0CF10100BCF157 +:101E0000060F218C80B201D88E422CD3FFF7AAFE98 +:101E1000FFF78CFE8E4208BF4FF0400A626901381E +:101E2000127880B202F01F0242EA49120BEB000165 +:101E30004AEA020A013048F0004281F808A08BF813 +:101E4000100059463846CBF80420FFF7ABFD238C31 +:101E50000135B3424FF0000A2DB289F00109B8D123 +:101E600082E70022C5E7E169895D01360EF80210BC +:101E7000B6B20132BFE76FF0010575E7F8B5044669 +:101E800015460E46302200211F46FFF783FA069BB7 +:101E9000B5F5001F6360079B28BF4FF6FF72A36272 +:101EA0004FF0000338BF6A09A760E66197B204F1FA +:101EB00010009A4206D800230360A782E38223839E +:101EC000E360F8BD0660013330462036F1E70000DC +:101ED00003781BB94BB2002BC8BF017070470000DC +:101EE00000787047F8B50C46C969074611B9238CCC +:101EF000002B37D1257E1F2D34D8387828BB228C73 +:101F0000072A2CD8268A36F003032BD14FF6FF7010 +:101F1000FFF7D4FD4FF6FF7220F0010036024004B7 +:101F200046EA0565400C45EA4025234629463846E1 +:101F3000FFF700FF002807DD626913780133DBB289 +:101F40001F2B88BF00231370F8BD218A2D0645EA98 +:101F5000012505432046FFF721FE0246E5E76FF025 +:101F60000300F1E76FF00100EEE7000070B50446F2 +:101F70001D4616468AB0282200216846FFF70AFA55 +:101F8000BDF838306946ADF810300F9B20460593F8 +:101F90009DF84030CDE902658DF81830119B07930C +:101FA000BDF84830ADF82030FFF79CFF0AB070BD97 +:101FB0002DE9F041D36905460C4616460BB9138C42 +:101FC0005BBB377E1F2F28D895F80080B8F1000F33 +:101FD00026D03046FFF7E2FD3378210241EAC331D3 +:101FE00041EA0801338A41EA076141EA03410246B6 +:101FF0003346284641F08001FFF79CFE00280ADDA9 +:102000003378012B07D1726913780133DBB21F2BB0 +:1020100088BF00231370BDE8F0816FF00100FAE77C +:102020006FF00300F7E70000F0B504460D461E46CA +:1020300017468BB0282200216846FFF7ABF99DF8C0 +:102040004C3029465A1E534253418DF800309DF8BA +:1020500040306A46ADF81030119B204605939DF83C +:102060004830CDE902768DF81830149B0793BDF8FF +:102070005430ADF82030FFF79BFF0BB0F0BD0000EF +:10208000406A00B104307047436A1A6842620269CC +:102090001A600361C38A013BC38270472DE9F04196 +:1020A000D0F8208014461D4641460027174E09B936 +:1020B000BDE8F081D1E90223A21A65EB0303964241 +:1020C00077EB03031ED2036A8B420DD1FFF790FD1D +:1020D000036A1B68036203690B60C38A0161016ABA +:1020E000013B8846C382E2E7FFF782FD0B68C8F830 +:1020F000003003690B60C38A0161013BC382D8F8D9 +:102100000010D4E788460968D1E700BF80841E002C +:102110002DE9F04F8BB00D4614469B468046DDF806 +:102120005090002800F01A81B9F1000F00F01681DC +:10213000531E3F2B00F21281012A03D1BBF1000F85 +:1021400040F00C810023CDE90833B8F81430B5EB2A +:10215000C30F4FEAC30703D300200BB0BDE8F08FD5 +:102160002B199F42D8F80C3036BF7F1B2746FFB291 +:102170001BB9D8F81030002B7BD0272D4ED8C5F1D5 +:102180002806B7424FF0000334BF3E46F6B2009334 +:1021900029463246D8F8080008ABFFF745FCA7EB04 +:1021A000060A35445FFA8AFA2821B8F8143003F198 +:1021B0000053053BDB000493D8F80C300393039BDA +:1021C00013B1BAF1000F2CD1D8F8100040B1BAF118 +:1021D000000F05D05246009608AB691AFFF724FCA1 +:1021E00038B2002FB8D066070AD00AAB03EBD4018F +:1021F00011F8083C624202F00702134101F8083C62 +:10220000082C3DD9102C40F2B680202C40F2B8802A +:10221000BBF1000F00F09D80082335E0BA46002690 +:10222000C2E7049BE02B28BFE02306930B44AB429C +:10223000059315D95A1B924538BF5246039828BFBB +:10224000D2B20096691A08AB04300792FFF7ECFB94 +:10225000079A1644AAEB020A1544F6B25FFA8AFA04 +:10226000049B069A05999B1A0493039B1B6803938E +:10227000A5E700933A462946D8F8080008ABADE731 +:10228000BBF1000F13D00123B4EBC30F6CD0082CAB +:1022900012D89DF82030621E23FA02F2D50706D527 +:1022A0004FF0FF3202FA04F423438DF820309DF8FA +:1022B000203089F8003050E7102C12D8BDF82030BB +:1022C000621E23FA02F2D10706D54FF0FF3202FA5E +:1022D00004F42343ADF82030BDF82030A9F80030D5 +:1022E0003BE7202C0FD80899631E21FA03F3DA0785 +:1022F00005D54FF0FF3202FA04F40C430894089B12 +:10230000C9F8003029E7402C2BD0DDE90865611EB3 +:10231000C4F12102A4F1210326FA01F105FA02F227 +:1023200025FA03F311431943CB0712D50122A4F177 +:102330002003C4F1200102FA03F322FA01F1A240C2 +:10234000524243EA010363EB430332432B43CDE99B +:102350000823DDE90823C9E90023FEE66FF0010048 +:10236000FBE66FF00800F8E6082CA0D9102CB3D9D2 +:10237000202CEED8C3E7BBF1000FADD0022383E7DA +:10238000BBF1000FBBD004237EE70000012A30B56B +:10239000144638BF01220025402A28BF402285B0BC +:1023A000012CCDE9025517D81B788DF8083053075A +:1023B0000AD004AB03EBD20515F8083C544204F0F4 +:1023C0000704A34005F8083C0346009102A8002139 +:1023D000FFF72AFB05B030BD082CE5D9102C03D837 +:1023E0001B88ADF80830E2E7202C02D81B68029366 +:1023F000DDE7D3E90045CDE90245D8E710B5CB6864 +:102400001BB98B600B618B8210BD04691A681C605C +:102410000361C38A013BC382CA60F0E703064CBF75 +:10242000C0F3C0300220704708B50246FFF7F6FF40 +:10243000022806D15306C2F30F2001D100F0030099 +:1024400008BDC2F30740FBE72DE9F04F93B0CDE99B +:1024500003230A6804461046FFF7E0FF02280CBF7A +:102460000026C2F30626002A0D46824680F2F98134 +:1024700012F0C04940F0F581097B002900F0F1819C +:10248000022803D02378B34240F0EE81C2F3046304 +:102490001046069302F07F030593FFF7C5FF059BE7 +:1024A00000224FEA8348002348EA0A48294448EAC0 +:1024B0004668CE78CDE90823F309834648EA000848 +:1024C000029367D0059B02460093204653466768F7 +:1024D00008A9B847002800F0CA81276A4FB94146C9 +:1024E00004F10C00FFF704FB074690B96FF00200FF +:1024F00054E03B6998450DD03F68002FF9D1414623 +:1025000004F10C00FFF7F4FA07460028EED0236A26 +:102510003B60276297F817C006F01F08CCF3840CC5 +:10252000ACEB08001FFA80FE0028B8BF0EF12000B7 +:10253000A8EB0C031FFA83FEB8BF00B2002B079371 +:10254000BEBF0EF120031BB20793D7E9022152EA66 +:10255000010338D04FF0000C039BDFF8F8E19A1A22 +:10256000049B63EB010196457CEB01032BD36B7B52 +:1025700097F81AE0734519D1029B002B78D00128F7 +:1025800021DC7868F8B9DFF8D0C1944570EB01031D +:1025900016D337E0276A27B96FF00C0013B0BDE8F7 +:1025A000F08F3B699845B5D03F68F4E76A489042A0 +:1025B0007CEB010301D30020F0E7029B002BFAD053 +:1025C000079B0F2B17DCFA7DB30002F0030203F028 +:1025D0007C031343FB7539462046FFF709FB6B7BF1 +:1025E000BB76029B3BB9FB7DC3F38402013262F3ED +:1025F0008603FB75D0E76A7BBB7E9A42DBD1029BE8 +:10260000002B35D0B309022B32D0039B1422BB60C0 +:10261000049B0021FB600DA8FEF7BCFE039B204637 +:102620000A93049BADF83EB00B932B1D0C932B7BB0 +:102630008DF840A0013BDBB2ADF83C30069B8DF835 +:1026400041808DF84230059B0AA98DF8433094F8FB +:102650002C3083F001038DF84430A3689847FB7D4C +:10266000C3F38403013303F01F039B02FB82A2E741 +:10267000FB7DC6F34012B2EBD31F40F0FB80C3F3E7 +:102680008403434540F0F980029A2B7BB609002A67 +:102690004DD0F20762D4032B40F2F280039BAE1DB3 +:1026A000BB60049B3246FB602B7B3946033BDBB2AD +:1026B00004F10C00FFF7AEFA00280CDA3946204688 +:1026C000FFF796FAFB7DC3F38403013303F01F0386 +:1026D0009B02FB820AE7AB88DDE908843B834FF667 +:1026E000FF73C9F12000A9F1200228FA09F104FAC8 +:1026F00000F0014324FA02F211431846C9B2FFF771 +:10270000CBF909F10809B9F1400F0346E9D1314687 +:10271000B8822A7B033AD2B2FFF7D0F9FB7DB882A8 +:10272000DA43C2F3C01262F3C713FB7543E7AEB9D5 +:102730002E1D013B32463946DBB204F10C00FFF797 +:1027400069FA0028BADB2A7B3146013AB88AD2B24C +:10275000E2E700BF80841E0040420F00F98A013B7F +:10276000C1F309010429DAB25DD80023281D07F15D +:102770001B069A4208D910F801CB013306F801C0B4 +:1027800001310529DBB2F4D1934228BF002303991C +:1027900038BF04330A91049938BFDBB20B9107F1BB +:1027A0001B010C91796838BF5B190D910E93FB8A60 +:1027B000ADF83EB0C3F309031A44069BADF83C20C4 +:1027C0008DF84230059B8DF840A08DF8433094F889 +:1027D0002C308DF8418083F001038DF844300023C4 +:1027E0007B602A7BB88A013A291DFFF767F93B8B8A +:1027F000B882834203D12046A3680AA9984720469D +:102800000AA9FFF7FBFDFB7DBA8AC3F384030133FA +:1028100003F01F039B02FB823B8B9A420CBF0020FC +:102820006FF01000BAE67B68002BADD0052001E008 +:1028300033461C301E68002EFAD1091A081D2E1DC1 +:10284000184401EB090CBCF11B0F5FFA89F39BD80C +:102850009A4299D916F8013B09F1010900F8013BA8 +:10286000EFE76FF0090099E66FF00A0096E66FF067 +:102870000B0093E66FF00D0090E66FF00E008DE612 +:102880006FF00F008AE600BFF0B53F4D3F4FEB6998 +:1028900043F00073EB61EB693D4B9B6AD3F8006238 +:1028A0003E4046F00106C3F80062D3F800423C40C7 +:1028B00044EA002444F00104C3F80042002955D042 +:1028C00000200646C3F81C02C3F80402C3F80C0239 +:1028D000C3F8140203EBC00401300E28C4F84062B0 +:1028E000C4F84462F6D100274FF0010C96781488A2 +:1028F00016F0010F18BFD3F804E20CFA04F01CBF65 +:1029000040EA0E0EC3F804E216F0020F18BFD3F827 +:102910000CE203EBC4041CBF40EA0E0EC3F80CE249 +:10292000760748BFD3F8146207F1010744BF064396 +:10293000C3F814625668B942C4F84062966802F15E +:102940000C02C4F84462D3F81C4240EA0400C3F805 +:102950001C02CBD1D3F8002222F00102C3F80022DE +:10296000EB6923F00073EB61EB69F0BD0122C3F862 +:102970004012C3F84412C3F80412C3F81412C3F887 +:102980000C22C3F81C22E5E7001002400000FFFF04 +:10299000A8230020184A08B5916A8B688B6013F051 +:1029A000010104D013F00C0F18BF4FF48031D8058B +:1029B00006D513F4406F14BF41F4003141F0020119 +:1029C000D80306D513F4402F14BF41F4802141F001 +:1029D0000401D3690BB108489847302383F3118869 +:1029E0000021064800F022FB002383F31188BDE894 +:1029F000084000F0ABBD00BFA8230020B02300209A +:102A000038B5124CA36ADD68AA0712D05A6922F0C1 +:102A100002025A61A36913B101212046984730236D +:102A200083F3118800210A4800F000FB002383F3A0 +:102A30001188EB0606D51021A36AD960236A0BB171 +:102A400002489847BDE8384000F080BDA823002028 +:102A5000B823002038B5124CA36A1D69AA0712D00A +:102A60005A6922F010025A61A36913B1022120466B +:102A70009847302383F3118800210A4800F0D6FAE2 +:102A8000002383F31188EB0606D51021A36A196190 +:102A9000236A0BB102489847BDE8384000F056BDA4 +:102AA000A8230020B823002038B50F4CA36A5D6826 +:102AB0002A075D600AD5042222701A6822F00202F9 +:102AC0001A60636A13B10021204698476B0706D548 +:102AD000A36A9969236A13B1034809049847BDE8BA +:102AE000384000F033BD00BFA823002010B50E4CC5 +:102AF000204600F02FF90D4B0B211320A36200F0AC +:102B000009F90B21142000F005F90B21152000F024 +:102B100001F90B21162000F0FDF8BDE8104000225D +:102B20000E201146FFF7B0BEA8230020006400402D +:102B30000F4B10B59842044605D10E4BDA6942F0AE +:102B40000072DA61DB690122A36A1A60A36A5A681B +:102B5000D20707D5626851681268D9611A60064ABF +:102B60005A6110BD0121082000F0B0F9EEE700BF66 +:102B7000A8230020001002405B87010003291AD817 +:102B8000DFE801F0020A0F14836A9B6813F0E05F2C +:102B900014BF012000207047836A9868C0F38060EA +:102BA0007047836A9868C0F3C0607047836A98680A +:102BB000C0F30070704700207047000010B5032973 +:102BC00027D8DFE801F002272B2F836A9968C1F329 +:102BD0000161183103EB01131078840648BF546873 +:102BE000C0F3001158BF94884FEA410148BF41EA41 +:102BF000C40100F00F00586048BF41F00401906824 +:102C000058BF41EA4451D26841F001019860DA604E +:102C1000196010BD836A03F5C073DDE7836A03F5AD +:102C2000C873D9E7836A03F5D073D5E701290AD0C1 +:102C300002290FD081B9836ADA68920701D1186935 +:102C400003E001207047836AD86810F0030018BFC2 +:102C500001207047836AF2E70020704710B539B948 +:102C6000836AD96889071BD11B699C0704D110BDF1 +:102C7000012915D00229FAD1816AD1F8C031D1F8E1 +:102C8000C441D1F8C8011061D1F8CC0150612020B5 +:102C900008610869800717D1486940F0100012E008 +:102CA000816AD1F8B031D1F8B441D1F8B8011061DE +:102CB000D1F8BC0150612020C860C868800703D1EA +:102CC000486940F002004861C3F34000C3F380014B +:102CD000000140EA4111107920F0300001431171E8 +:102CE00089064BBF91681189DB085B0D4CBF63F30C +:102CF0001C0163F30A01137948BF916064F3030375 +:102D000013714FEA14234FEA144458BF1181137012 +:102D10005480ACE70122090100F1604303F56143EF +:102D2000C9B283F8001300F01F039A4043099B00C7 +:102D300003F1604303F56143C3F880211A607047D3 +:102D4000090100F16040C9B200F56D40017670479D +:102D5000FFF7CCBE01230370002300F10802C0E995 +:102D6000022200F11002C0E90422C0E90633C0E9E2 +:102D7000083343607047000010B53023044683F3E6 +:102D80001188022341600370FFF7D2FE0423002064 +:102D9000237080F3118810BD2DE9F0411F460446D1 +:102DA0000D461646302383F3118800F10808237876 +:102DB000052B0DD029462046FFF7E0FE40B1204606 +:102DC00032462946FFF7FAFE002080F3118808E01A +:102DD0003946404600F01AF90028E8D0002383F372 +:102DE0001188BDE8F08100002DE9F0411F4604463E +:102DF0000D461646302383F3118800F1100823781E +:102E0000052B0DD029462046FFF710FF40B1204684 +:102E100032462946FFF722FF002080F3118808E0A0 +:102E20003946404600F0F2F80028E8D0002383F34A +:102E30001188BDE8F08100000023826803750369F2 +:102E40001B6899689142FBD25A6803604260106027 +:102E50005860704700238268037503691B6899688E +:102E60009142FBD85A680360426010605860704716 +:102E700008B50846302383F311880B7D032B05D05A +:102E8000042B0DD02BB983F3118808BD00228B6968 +:102E90001A604FF0FF338361FFF7CEFF0023F2E7A4 +:102EA000D1E9003213605A60F3E70000FFF7C4BFB6 +:102EB000054BD96808751868026853601A600122CA +:102EC0000275D860FDF79EBBD823002030B50C4BAF +:102ED0000446DD684B1C87B00FD02B466846094A74 +:102EE00000F0CAF82046FFF7E3FF009B13B16846E5 +:102EF00000F0CAF8A86907B030BDFFF7D9FFF9E7BD +:102F0000D8230020712E0008044B1A68DB689068F3 +:102F10009B68984294BF002001207047D82300206E +:102F2000084B10B51C68D868226853601A600122EB +:102F30002275DC60FFF78EFF01462046BDE8104099 +:102F4000FDF760BBD823002038B501230025064CCF +:102F5000064907482370656000F03EFB022323709A +:102F600085F3118838BD00BF30250020B83A00082D +:102F7000D823002000F09AB88B60022308618B826E +:102F8000084670478368A3F1440243F8142C026991 +:102F900043F8442C426943F8402C094A43F8242C56 +:102FA000C268A3F1200043F8182C022203F80C2C6D +:102FB000002203F80B2C034A43F8102C704700BF83 +:102FC00015060008D823002008B5FFF7DBFFBDE891 +:102FD0000840FFF76BBF0000024BDB6898610F20D1 +:102FE000FFF766BFD8230020302383F31188FFF753 +:102FF000F3BF000008B50146302383F31188082091 +:10300000FFF764FF002383F3118808BD064BDB68DC +:1030100039B1426818605A60136043600420FFF7BA +:1030200055BF4FF0FF307047D823002038B5044615 +:103030000D462068844200D138BD036823605C607F +:103040008561FFF733FFF4E710B50A4C23699A68EE +:1030500091420CD85A6881600360426010609A689F +:103060005860511A99604FF0FF33A36110BD1B687F +:10307000891AECE7D8230020C0E90323002310B409 +:1030800010BC4361FFF7E0BF036881689A680A4497 +:103090009A60426813605A6000234FF0FF32036069 +:1030A000014B9A61704700BFD823002070B5124DC4 +:1030B0002A46EB690133EB6152F8103F934206D088 +:1030C00030269A68013A9A602C69A36803B170BDF2 +:1030D000D4E900210A605160236083F311882046FF +:1030E000D4E90331984786F3118861690029EBD050 +:1030F0002046FFF7A9FFE7E7D8230020054A30B5AF +:10310000D369D2E908451B1B181945F10001C2E932 +:10311000080130BDD823002000207047FEE70000E2 +:10312000704700004FF0FF3070470000BFF34F8F33 +:10313000024AD368DB07FCD4704700BF002002407E +:1031400008B5074B1B7853B9FFF7F0FF054B1A6919 +:10315000120641BF044A5A6002F188325A6008BD23 +:1031600048250020002002402301674508B5054B93 +:103170001B7833B9FFF7DAFF034A136943F0800382 +:10318000136108BD48250020002002407F289ABF17 +:1031900000F5003080020020704700004FF480608E +:1031A00070470000802070477F2808B50BD8FFF7D4 +:1031B000EDFF00F580630268013204D104308342E0 +:1031C000F9D1012008BD0020FCE700007F2810B5E0 +:1031D00004461CD8FFF7AAFFFFF7B2FFF3220D4BFE +:1031E0004FF48061DA6002221A61FFF7CFFF586165 +:1031F0001A6942F040021A61FFF798FF00F02EF9B9 +:10320000FFF7B4FF2046BDE81040FFF7CDBF002018 +:1032100010BD00BF002002402DE9F843054612F022 +:103220000100144606D040F2033200201E4B1A6003 +:10323000BDE8F8831D4BAA189A4204D94FF4427294 +:10324000194B1A60F4E7FFF77BFF4FF00109FFF716 +:103250006DFFDFF85C806D1A012C0F4605EB01064F +:1032600003D8FFF783FF0120E2E73B88C8F81090FE +:1032700033800020FFF75AFFC8F81000338831F878 +:10328000022B9BB29A420CD040F21F32064B1A60BE +:10329000084B1E60084B1C60084B1F60FFF766FF61 +:1032A000C6E7023CD8E700BF442500200000020822 +:1032B0000020024038250020402500203C25002029 +:1032C000084908B50B7828B11BB9FFF739FF01236E +:1032D0000B7008BD002BFCD0BDE808400870FFF75C +:1032E00045BF00BF4825002038B5EFF31185BDBBB1 +:1032F000EFF30584C4F308043023C4B183F31188C9 +:10330000FFF7FCFE44014B01241A43EAD06363EB50 +:103310000103A2009B00121843EA947341EB0301DE +:10332000C900D00041EA527185F3118838BD83F39A +:103330001188FFF7E3FE45014B012D1A43EAD063E4 +:1033400063EB0103AA009B00121843EA957341EB5B +:103350000301C900D00041EA527184F3118838BDDD +:10336000FFF7CCFE44014B01241A43EAD06363EB20 +:103370000103A2009B00121843EA947341EB03017E +:10338000C900D00041EA527138BD00BF38B5FFF71F +:10339000ABFF00230F4A104CC00840EA4170A0FB6D +:1033A000025EC908A0FB040CA1FB0440A1FB0212B1 +:1033B0001CEB050C5B411CEB040C43EB000011EB18 +:1033C0000E0142F10002411842F10000090941EAF0 +:1033D000007038BDA59BC420CFF753E310B5094C4E +:1033E000013AD2B2FF2A00D110BD500854F8203063 +:1033F000013054F820009BB243EA004341F8043BFB +:10340000EEE700BF046C004010B50748013AD2B2A5 +:10341000FF2A00D110BD0C88530840F823404C8887 +:10342000013340F82340F1E7046C004007B5012266 +:10343000002001A9FFF7D2FF019803B05DF804FB5B +:1034400013B50446FFF7F2FFA04205D00122002089 +:1034500001A90194FFF7D8FF02B010BD704700002A +:1034600045F25552064B1A6002225A6040F6FF722E +:103470009A604CF6CC421A600122024B1A707047D7 +:103480000030004050250020034B1B781BB14AF64A +:10349000AA22024B1A6070475025002000300040DD +:1034A000044B1A682AB902F1804202F50432526ACA +:1034B0001A6070474C2500204FF08072014B5A6211 +:1034C000704700BF0010024008B5FFF7E9FF024B4C +:1034D0001868C0F3407008BD4C25002008B5FFF700 +:1034E000DFFF024B1868C0F3007008BD4C250020B8 +:1034F000EFF30983203383F30988002383F31188D2 +:1035000070470000302080F3118862B60C4B0D4AE2 +:10351000D96821F4E0610904090C0A43DA60D3F8A0 +:10352000FC20094942F08072C3F8FC200A6842F08E +:1035300001020A602022DA7783F82200704700BF78 +:1035400000ED00E00003FA05001000E0302310B5A4 +:1035500083F311880B4B5B6813F400630FD0EFF318 +:1035600009844FF08073203CE36184F30988FFF7FE +:10357000CBFC10B1044BA36110BD044BFBE783F3FC +:103580001188F9E700ED00E0270600082A06000888 +:1035900070470000FEE700000A4B0B480B4A9042C0 +:1035A0000BD30B4BC11EDA1C121A22F003028B4202 +:1035B00038BF00220021FDF7EDBE53F8041B40F890 +:1035C000041BECE7343B0008D4250020D425002060 +:1035D000D4250020FEE7000070B5002504461A4BF4 +:1035E00086B05860856201630E46FFF78BFF04F1D9 +:1035F0001003C4E904334FF0FF33A361134BE561BB +:10360000D9692B460A462046C4E9082304F134014F +:103610008023C4E900440E4AA560E5622565FFF7F2 +:10362000ABFC01230B4AE0600375009272686846A8 +:103630000192B268CDE90223074BCDE90435FFF7CB +:10364000C3FC06B070BD00BF30250020D823002089 +:10365000C43A0008C93A0008D535000800F030B86F +:1036600008B500F063F9FFF76FFCBDE80840FFF70D +:1036700017BF0000704700004FF0FF310E4B1A6972 +:1036800019611A6900221A611869D868D960D96865 +:10369000DA60DA68DA6942F08052DA61DA69DA69A6 +:1036A00042F00062DA61054ADB69136843F4807313 +:1036B000136000F01BB900BF001002400070004012 +:1036C000194B1A6842F001021A601A689007FCD57B +:1036D0001A6802F0F9021A6000225A605A6812F061 +:1036E0000C0FFBD11A6842F480321A601A689103F9 +:1036F000FCD55A6842F4E8125A601A6842F08072A7 +:103700001A601A689201FCD51221084A5A60084AC8 +:1037100011605A6842F002025A605A6802F00C02C4 +:10372000082AFAD1704700BF0010024000641D0053 +:1037300000200240084A08B5516913680B4003F0A5 +:103740000103536123B1054A13680BB150689847D0 +:10375000BDE80840FFF7FABE0004014054250020F0 +:10376000084A08B5516913680B4003F0020353611E +:1037700023B1054A93680BB1D0689847BDE808406B +:10378000FFF7E4BE0004014054250020084A08B5B4 +:10379000516913680B4003F00403536123B1054AD8 +:1037A00013690BB150699847BDE80840FFF7CEBEDA +:1037B0000004014054250020084A08B551691368E7 +:1037C0000B4003F00803536123B1054A93690BB121 +:1037D000D0699847BDE80840FFF7B8BE0004014033 +:1037E00054250020084A08B5516913680B4003F0BE +:1037F0001003536123B1054A136A0BB1506A98470D +:10380000BDE80840FFF7A2BE000401405425002097 +:10381000174B10B55A691C68144004F478725A6149 +:10382000A30604D5134A936A0BB1D06A9847600681 +:1038300004D5104A136B0BB1506B9847210604D581 +:103840000C4A936B0BB1D06B9847E20504D5094A3B +:10385000136C0BB1506C9847A30504D5054A936CC3 +:103860000BB1D06C9847BDE81040FFF76FBE00BFAA +:1038700000040140542500201A4B10B55A691C68F9 +:10388000144004F47C425A61620504D5164A136D53 +:103890000BB1506D9847230504D5134A936D0BB1B6 +:1038A000D06D9847E00404D50F4A136E0BB1506EEB +:1038B0009847A10404D50C4A936E0BB1D06E98477B +:1038C000620404D5084A136F0BB1506F9847230464 +:1038D00004D5054A936F0BB1D06F9847BDE81040EF +:1038E000FFF734BE0004014054250020062108B52E +:1038F0000846FFF70FFA06210720FFF70BFA06210B +:103900000820FFF707FA06210920FFF703FA06212E +:103910000A20FFF7FFF906211720FFF7FBF9BDE8A2 +:10392000084006212820FFF7F5B9000008B5FFF789 +:10393000A3FE054800F00CF8FFF70AFAFFF79AFE1D +:10394000BDE8084000F002B8D03A000800F042B8E4 +:10395000002319461C4A0133102BC2E9001102F161 +:103960000802F8D1194B9A6942F07D029A619B696D +:103970000268174BDA6082685A6042681A60C2684F +:1039800003F58063DA6042695A6002691A608269ED +:10399000C3F80C24026AC3F80424C269C3F80024E3 +:1039A000426AC3F80C28C26AC3F80428826AC3F8C2 +:1039B0000028026BC3F80C2C826BC3F8042C426BFA +:1039C000C3F8002C704700BF5425002000100240AF +:1039D000000801404FF0E023044A08215A61002208 +:1039E0009A6107220B201A61FFF7AAB93F1901005B +:1039F00008B5302383F31188FFF7BCFA002383F363 +:103A0000118808BD08B5FFF7F3FFBDE80840FFF7D0 +:103A10009DBD000010B501390244904201D1002043 +:103A200005E0037811F8014FA34201D0181B10BD27 +:103A30000130F2E72DE9F0419BB10446C91A17782D +:103A4000014403F1FF3C8C42204601D9002008E0EC +:103A500005780134BD42F6D10CEB0405D618A54219 +:103A600001D1BDE8F08115F8018D16F801EDF045A2 +:103A7000F5D0E8E7034611F8012B03F8012B002AE3 +:103A8000F9D170476F72672E6172647570696C6FDF +:103A9000742E663130332D485745534300000000E3 +:103AA00040A2E4F1646891060041A3E5F2656992E1 +:103AB0000700000063300000B43A00083024002002 +:103AC000302500206D61696E0069646C650000003E +:103AD000001800004444414444544944010000009B +:103AE00042444444444444440000000044444444A8 +:103AF0004444444400000000444444444444444496 +:103B00000000000044444444444444440000000095 +:103B1000E803000000000000009C0100000000001D +:103B2000640000000000000040420F00FE2A010077 +:043B3000D2040000BB :00000001FF diff --git a/Tools/bootloaders/f103-QiotekPeriph_bl.bin b/Tools/bootloaders/f103-QiotekPeriph_bl.bin index ffde9e119ef8ff..4faa840de53728 100755 Binary files a/Tools/bootloaders/f103-QiotekPeriph_bl.bin and b/Tools/bootloaders/f103-QiotekPeriph_bl.bin differ diff --git a/Tools/bootloaders/f103-QiotekPeriph_bl.hex b/Tools/bootloaders/f103-QiotekPeriph_bl.hex index 072f1569b8776f..dce4580e2f9f5c 100644 --- a/Tools/bootloaders/f103-QiotekPeriph_bl.hex +++ b/Tools/bootloaders/f103-QiotekPeriph_bl.hex @@ -1,26 +1,26 @@ :020000040800F2 -:10000000000900202D080008B11C0008811C000810 -:100010009D1C0008811C0008951C00082F08000882 -:100020002F0800082F0800082F080008E5370008EF -:100030002F0800082F0800082F080008F93C0008C6 -:100040002F0800082F0800082F0800082F080008B4 -:100050002F0800082F080008293A0008553A000820 -:10006000813A0008AD3A0008D93A00082F08000884 -:100070002F0800082F0800082F0800082F08000884 -:100080002F0800082F0800082F080008AD2C0008D2 -:10009000192D00086D2D0008C12D0008053B000832 -:1000A0002F0800082F0800082F0800082F08000854 -:1000B0002F0800082F0800082F0800082F08000844 -:1000C0002F0800082F0800082F0800082F08000834 -:1000D0002F0800082F0800082F0800082F08000824 -:1000E0006D3B00082F0800082F0800082F080008A3 -:1000F0002F0800082F0800082F0800082F08000804 -:100100002F0800082F0800082F0800082F080008F3 -:100110002F0800082F0800082F0800082F080008E3 -:100120002F0800082F0800082F0800082F080008D3 -:100130002F0800082F0800082F0800082F080008C3 -:100140002F0800082F0800082F0800082F080008B3 -:100150002F0800082F0800082F0800082F080008A3 +:100000000009002025050008A11900087119000841 +:100010008D190008711900088519000827050008C6 +:10002000270500082705000827050008F9340008FF +:100030002705000827050008270500080D3A0008D5 +:1000400027050008270500082705000827050008E0 +:1000500027050008270500083D3700086937000814 +:1000600095370008C1370008ED370008270500085C +:1000700027050008270500082705000827050008B0 +:100080002705000827050008270500089D29000806 +:10009000092A00085D2A0008B12A0008193800085A +:1000A0002705000827050008270500082705000880 +:1000B0002705000827050008270500082705000870 +:1000C0002705000827050008270500082705000860 +:1000D0002705000827050008270500082705000850 +:1000E00081380008270500082705000827050008B3 +:1000F0002705000827050008270500082705000830 +:10010000270500082705000827050008270500081F +:10011000270500082705000827050008270500080F +:1001200027050008270500082705000827050008FF +:1001300027050008270500082705000827050008EF +:1001400027050008270500082705000827050008DF +:1001500027050008270500082705000827050008CF :100160004FF0FF0C1CEAD0521EBF1CEAD15392EA9A :100170000C0F93EA0C0F6FD01A4480EA010C400276 :1001800018BF5FEA41211ED04FF0006343EA5010D0 @@ -81,918 +81,870 @@ :1004F0009E03B3EB126209D44FEA002343F000439A :1005000023FA02F070474FF00000704712F1610FBC :1005100001D1420202D14FF0FF3070474FF000008E -:10052000704700BF53B94AB9002908BF00281CBF53 -:100530004FF0FF314FF0FF3000F076B9ADF1080C0D -:100540006DE904CE00F006F8DDF804E0DDE90223F1 -:1005500004B070472DE9F047089E0D4604468846D2 -:10056000002B4DD18A42944668D9B2FA82F252B138 -:1005700001FA02F3C2F1200120FA01F10CFA02FCA7 -:1005800041EA030894404FEA1C41B8FBF1F71FFA17 -:100590008CFE01FB178807FB0EF0230C43EA08438F -:1005A00098420AD91CEB030307F1FF3580F01E8146 -:1005B000984240F21B81023F63441B1AB3FBF1F0E7 -:1005C00001FB103300FB0EFEA4B244EA0344A6452F -:1005D0000AD91CEB040400F1FF3380F00981A64521 -:1005E00040F20681644402380021A4EB0E0440EA84 -:1005F00007401EB10023D440C6E90043BDE8F087A0 -:100600008B4208D9002E00F0EE800021C6E90005DB -:100610000846BDE8F087B3FA83F100294AD1AB421E -:1006200002D3824200F2FC80841A65EB03030120AE -:100630009846002EE2D0C6E90048DFE702B9FFDEA7 -:10064000B2FA82F2002A40F09180A1EB0C00012165 -:100650004FEA1C471FFA8CFEB0FBF7F307FB1300B1 -:10066000250C45EA00450EFB03F0A84208D91CEB17 -:10067000050503F1FF3802D2A84200F2CE804346BE -:100680002D1AB5FBF7F007FB10550EFB00FEA4B2C8 -:1006900044EA0544A64508D91CEB040400F1FF35E3 -:1006A00002D2A64500F2B6802846A4EB0E0440EA2A -:1006B00003409EE7C1F120078B4022FA07FC4CEA79 -:1006C000030C25FA07FA4FEA1C49BAFBF9F820FA9D -:1006D00007F309FB18AA8D401FFA8CFE1D4300FA90 -:1006E00001F308FB0EF02C0C44EA0A44A04202FA83 -:1006F00001F20BD91CEB040408F1FF3A80F088806A -:10070000A04240F28580A8F102086444241AB4FB98 -:10071000F9F009FB104400FB0EFEADB245EA0444BB -:10072000A64508D91CEB040400F1FF356CD2A645A0 -:100730006AD90238644440EA0840A0FB0295A4EB61 -:100740000E04AC42C846AE4656D353D0002E69D0F4 -:10075000B3EB080264EB0E0422FA01F304FA07F784 -:100760001F43CC40C6E90074002147E70CFA02FCA5 -:10077000C2F1200125FA01F34FEA1C4720FA01F1EA -:1007800095400D43B3FBF7F107FB11331FFA8CFEC5 -:10079000280C40EA034001FB0EF3834204FA02F402 -:1007A00008D91CEB000001F1FF382FD283422DD96C -:1007B00002396044C01AB0FBF7F307FB1300ADB277 -:1007C00045EA004503FB0EF0A84208D91CEB0505DD -:1007D00003F1FF3816D2A84214D9023B6544281A07 -:1007E00043EA014138E73146304607E72F46E4E661 -:1007F0001846F9E64B45A9D2B9EB020865EB0C0E99 -:100800000138A3E74346EAE7284694E74146D1E7A3 -:10081000D0467BE76444023847E7023B65442FE754 -:10082000084606E73146E9E6704700BF02E000F0FF -:1008300000F8FEE772B6264880F30888254880F362 -:100840000988254825490860022080F31488BFF3F1 -:100850006F8F03F017F803F07BF84FF05530204905 -:100860001B4A91423CBF41F8040BFAE71D49194A63 -:1008700091423CBF41F8040BFAE71B491B4A1C4B51 -:100880009A423EBF51F8040B42F8040BF8E70020EF -:100890001849194A91423CBF41F8040BFAE702F0AB -:1008A000F5FF03F057F8154C154DAC4203DA54F838 -:1008B000041B8847F9E700F03FF8124C124DAC4298 -:1008C00003DA54F8041B8847F9E702F0DDBF0000A3 -:1008D00000090020001100200000000808ED00E0E1 -:1008E0000001002000090020103E00080011002037 -:1008F0002411002028110020E025002060010008BC -:100900006001000860010008600100082DE9F04F57 -:10091000C1F80CD0C3689D46BDE8F08F002383F377 -:1009200011882846A047002002F010FDFEE702F0E3 -:1009300083FC00DFFEE70000F8B500F03DFE02F0AA -:10094000EFFE074602F03AFF0546002840D12C4B47 -:100950009F423DD001339F423DD02A4B27F0FF02FA -:100960009A423BD1F8B200F003FC2E4642F21074DA -:1009700000F004FC08B10024264601F007F988B312 -:100980000024032000F044F8264635B11E4B9F4258 -:1009900003D0002402F00AFF2646002002F0CAFE1F -:1009A0001A4B9B6813F0400322D00EB100F046F8BA -:1009B00000F044FC00F002FE01F07CF90546CCB1E9 -:1009C00001F078F9401BA04214D900F037F8F3E7A2 -:1009D0002E460024CCE704460126C9E706464FF41C -:1009E0007A74C5E7002CD0D04FF47A740126CCE796 -:1009F0001C46DDE700F0D4FC012002F0ADFCDEE790 -:100A0000010007B0000008B0263A09B0000C014010 -:100A1000084B187003280CD8DFE800F0080502081E -:100A2000022000F027BE022000F01CBE0022024B74 -:100A30005A607047281100202C11002038B501F0B1 -:100A4000A5F830B103221F4B1A7000221E4B5A60CA -:100A500038BD1E4B1E4A19680131F9D00433934248 -:100A6000F9D11C4C194DD4F80424AA42F0D31A4BE6 -:100A70009B6803F1006303F5C8439A42E8D202F091 -:100A800069FE02F07BFE002000F0B2FD0220FFF7BD -:100A9000BFFF124BDA690022DA61D96999699A615C -:100AA0009B6972B64FF0E023C3F8085D3021D4F89B -:100AB0000034D4F8042481F311889D4683F3088818 -:100AC0001047C5E7281100202C1100200064000801 -:100AD000206400080060000800110020001002409F -:100AE00049F26900084A136899B21B0C00FB0133F4 -:100AF00044F250611360054B186882B2000C01FB90 -:100B00000200186080B27047201100201C110020E4 -:100B100010B504460021102200F0C8FD034B03CBA2 -:100B2000206061601868A06010BD00BFE8F7FF1F7B -:100B30002DE9F0410026ADF5507D6EAC40F2751206 -:100B400007460D4610A831460F9600F0AFFD4FF452 -:100B5000C4723146204600F0A9FD01F0ABF84FF415 -:100B60007A72B0FBF2F0264B0DF13C08186093E866 -:100B70000700022384E807000DF5ED702382FFF7DC -:100B8000C7FF4EF603031F4907A8238403F0ECF8C0 -:100B90001F230DF2EB2284F832310DF1340C07AB38 -:100BA0001E4603CE664510605160334602F10802CE -:100BB000F6D130681060B188B37920469180937186 -:100BC0004146012200F0BEFD00230393AB7E80B2BC -:100BD000029305F1190301930123CDE904800093E9 -:100BE000384605A3D3E90023E97E01F0A9FB0DF502 -:100BF000507DBDE8F08100BF9E6AC421818A46EE27 -:100C000034110020783D00082DE9F041264D804642 -:100C10002B7A0C46DAB0FBB9204627A900F0A2FED9 -:100C20000746002836D19DF89D60C82E32D801466F -:100C30004FF4FA72284600F039FD32460DF19E015C -:100C400005F1090000F020FD9DF89C302E447772DC -:100C50002B720BB9E37E2B728122002106AD27A8EF -:100C600000F024FD0122294627A800F0B7FE00234A -:100C70000393A37E80B2029304F119030193282306 -:100C8000CDE904500093404605A3D3E90023E17E5B -:100C900001F056FB5AB0BDE8F08100BFAFF3008011 -:100CA00026417272DF25D7B77C210020F0B54FF4C2 -:100CB0008A750024234EF1B005FB006596F8D83004 -:100CC000D822214685F8DC3085F8E8403AA800F0C3 -:100CD000EDFC06F1090000F0E1FCD5F8E430C2B209 -:100CE00006AF8DF8F00006F109010DF1F100CDE934 -:100CF0003A3400F0C9FC394601223AA800F09AFEC5 -:100D000080B2CDE9047008230127CDE9023706F14E -:100D1000D80301933023317A00930B4807A3D3E91A -:100D2000002301F00DFBA04206DD00F0C3FFC5F873 -:100D3000E000384671B0F0BD2046FBE778F6339FFF -:100D400093CACD8D7C2100204C210020F0B51E4E91 -:100D50001E4F1F4D85B0304601F01EFB044660B3A8 -:100D600010220021684600F0A1FC4FF00003227B16 -:100D70006068A16862F303038DF8003002AB03C31F -:100D8000019B2268384662F31C0301939DF80030F2 -:100D90006A4643F020038DF800300023194602F024 -:100DA00087F9044620B9304601F0FAFA2C70D2E7F0 -:100DB0002B78072B03D801332B7005B0F0BD024808 -:100DC00001F0EEFAF9E700BF4C210020A823002033 -:100DD0007523002070B50D4614461E4601F00CFA2E -:100DE00050B9022E10D1012C0ED112A3D3E9002349 -:100DF0000120C5E9002307E0282C10D005D8012CDC -:100E000009D0052C0FD0002070BD302CFBD10BA3D6 -:100E1000D3E90023ECE70BA3D3E90023E8E70BA316 -:100E2000D3E90023E4E70BA3D3E90023E0E700BF05 -:100E3000AFF30080401DA12026812A0B78F6339F56 -:100E400093CACD8D9E6AC421818A46EE2641727274 -:100E5000DF25D7B7F017304A39059E5638B5054615 -:100E60000E4C0021013500F0E5FBA4F8F051B4F878 -:100E7000F00100F0C7FB78B1B4F8F00100F0D2FB4C -:100E8000014648B9B4F8F00100F0D4FBB4F8F031F1 -:100E90000133A4F8F031EAE738BD00BF7C2100201F -:100EA0002DE9F04F8DB000AF04460D4601F0A4F9D6 -:100EB000002846D12B7E022B1AD1EB8A012B17D1A9 -:100EC00000F0F8FE0646FFF70BFE4FF4C873B0FBC8 -:100ED000F3F202FB1303DFF878829BB206F5167675 -:100EE0003344C8F80030EB7E33B90022994B1A70B6 -:100EF0003437BD46BDE8F08F284607F11C0100F0ED -:100F0000EFFC0028F4D107F10C00FFF701FEBD7FD4 -:100F100007F10C012A4607F11F0002F0F5FE002838 -:100F2000E3D10F2D08D88B4B1D70D8F80030A3F5F6 -:100F30001673C8F80030DBE72046397F01F054F91A -:100F4000D6E7EB8A282B6BD010D8012B63D0052B6A -:100F5000CED1BFF34F8F8049804BCA6802F4E06264 -:100F60001343CB60BFF34F8F00BFFDE7302BBFD1E2 -:100F70007B4CEA7E237A9A42BAD194F8DC206B7ECD -:100F80009A42B5D1284604F1EA0100F07FFD0646F9 -:100F90000028ADD1012384F8E83000F08BFED4F8AE -:100FA000E030C01A192840F6B83338BF19209842EB -:100FB00028BF1846FFF73EFA6A49FFF7D1F8054601 -:100FC0002068FFF737FA6849FFF7CAF80146284654 -:100FD000FFF780F9FFF786FA20604FF48A7194F8E2 -:100FE000D9307B607A68636801FB02F5621992F878 -:100FF000E80050B1D2F8E400E946834215D000235E -:1010000082F8E830C2F8E030CD466368574A9B0A60 -:10101000013313816CE729462046FFF789FD67E716 -:1010200029462046FFF7F0FD62E7B2F8EC803B600E -:1010300008F1030A4FEA9A0A4FEA8A02D11DC90849 -:10104000A9EBC1039D46EB460021584600F02EFB5C -:1010500005F1EE0142465846214400F015FB3B687D -:1010600013B9012000F0C4FA94F8D20000F0CAFAD3 -:10107000054630B9207200F0E5FA284600F0B8FACB -:10108000C2E7D4F8D4303BB994F8D200B4F8F031C8 -:10109000834201D8FFF7E2FED4F8D43043449D42A6 -:1010A00008D294F8D200B4F8F0310130834201D86C -:1010B000FFF7D4FE594660685FFA8AF200F0FEFA44 -:1010C00008B9CD4689E7636894F8D2004344636069 -:1010D000D4F8D43008EB030AC4F8D4A000F092FA94 -:1010E000824509D394F8D230D4F8D4000133401BA0 -:1010F00084F8D230C4F8D400B8F1FF0F0FD800251F -:10110000257200F09FFA284600F072FA00F03EFDCA -:10111000164B188108B9FFF791FCCD46E8E64FF46D -:101120008A727B6894F8D90002FB0343D3F8E42069 -:1011300083F8E86002F58072C3F8E060C3F8E42049 -:10114000FFF7B4FDFFF702FE84F8D960B9E700BFEE -:10115000482100204521002000ED00E00400FA05B0 -:101160007C210020CDCCCC3D6666663F341100204A -:10117000014B1870704700BF4011002030B54FF090 -:101180000054254B226885B09A4207D002F020FB1C -:101190000446C0B90024204605B030BD0025627D5C -:1011A0001E4B1F481A70237DC92203721D49C0F8C7 -:1011B000E450093000F068FA2046E022294600F0A9 -:1011C00075FA0124E7E7184A184DD36943F0007314 -:1011D000D361AA6D164B9A42DCD12B6E013B7E2B5C -:1011E000D8D8144A01AB07CA83E807001846032180 -:1011F00000F09CFC6B6D83424FF00003CAD12A6D56 -:101200008A4203BFAB652A6E044B1C4601BF1A70AD -:10121000EA6D094B1A60BEE79AAD44C54011002043 -:101220007C210020160000200010024000660040D3 -:101230005041A0B058660040181100202DE9F0433D -:1012400085B000F0A3FC0223494C63710023029394 -:10125000484B2081D3F800C0BCF57A7F12D3464FAB -:10126000464BB7FBFCF59C458CBF0A231123B5FB0D -:10127000F3F603FB1652591EC8B2002A3ED00229CB -:101280000B46F4D89DF80B303D495A1E9DF80A30A4 -:101290003C48013B1B0443EA0253BDF80820013AD5 -:1012A00013434B6001F0F4FE00230193364B3749A2 -:1012B00000934FF48052364B364800F06BFF364BAC -:1012C000197811B1334800F08FFF00F0F3FC0546A8 -:1012D000FFF706FC4FF4C873B0FBF3F202FB1303F5 -:1012E00005F516709BB218442C4B186002F066FA94 -:1012F00008B10F23238105B0BDE8F083731EB3F559 -:10130000806FBFD24FF47A75C0EBC00E0EF10303AD -:101310004FEAE30909FB0555C3F3C703C11AC9B274 -:1013200009F101088844B5FBF8F5B5F5617F08D9E6 -:101330000EF1FF33C3F3C703C11A581E0F28C9B2F9 -:1013400014D84A1E072A8CBF00220122581800FB1D -:101350000660B7FBF0F7BC4594D1002A92D0ADF8F7 -:1013600008608DF80A308DF80B108BE71346EDE717 -:101370003411002018110020005125023F420F00B7 -:1013800010110020A8230020D50D000844110020D2 -:10139000A10E00084C21002040110020482100200F -:1013A0002DE9F04F80A7D7E900670FF20429D9E9AA -:1013B0000089734D93B00DF1300AFFF7C7FC182276 -:1013C0000021504600F072F9DFF8B8B16E4C0023EE -:1013D00052461946584601F093FE014650BB102272 -:1013E00008A800F063F9E36883F01003E36000F0FD -:1013F00063FC0DF1240C0B4612A9024611E903000F -:101400008CE803009DF83410C1F30300890649BF3E -:101410000E99BDF83810C1F31C0141F0004158BFCE -:10142000C1F30A018DF82C000891284608A901F0A3 -:1014300097F9CCE7284600F0DFFE0446002847D1A4 -:1014400000F038FCDFF844B1DBF8003098423FD3BD -:1014500000F030FC0790FFF743FB4FF4C873B0FB7C -:10146000F3F101FB1300079A83B202F516701844DA -:10147000CBF80000DFF818B18DF820409BF8001081 -:1014800011B901238DF8203050460791FFF740FB3A -:1014900007990DF12100C1F11004E4B2062C28BF18 -:1014A00006245144224600F0EFF808AB03931823BA -:1014B0000293384B013401930123E4B20093324686 -:1014C0003B462846049400F0DDFE00238BF80030F4 -:1014D00000F0F0FB304A314C1368C31AB3F57A7F41 -:1014E00030D3106000F0E8FB02460B46284600F0BF -:1014F00061FF284600F080FE20B3237ADFF8A0B019 -:10150000002B14BF032302238BF8053000F0D2FB1D -:101510004FF47A73B0FBF3F00122CBF80000514690 -:10152000584600F0B5F9182302931E4B80B2019380 -:1015300040F25513CDE903A0009342464B4628469E -:1015400000F0A0FE237ABBB100F0B4FB94F8E830C1 -:1015500073B9D4F8E03043B1C01A2368FA2B38BF0E -:10156000FA230533B0EB430F02D30020FFF79EFBB5 -:10157000237A002B7FF41FAF13B0BDE8F08F00BFBC -:101580004C210020A8230020000801404821002011 -:101590004521002044210020702300207C210020D0 -:1015A0003411002074230020401DA12026812A0B25 -:1015B000F1C6A7C1D068080F7047000070B501F0F0 -:1015C00095FF0024084E094D3080286833888342F7 -:1015D00008D901F087FF2B6804440133B4F5C84FE4 -:1015E0002B60F2D370BD00BFA4230020782300201D -:1015F00002F00AB800F10060920000F5C84001F066 -:10160000AFBF0000054B1A68054B1B889B1A83422D -:1016100002D9104401F066BF0020704778230020F3 -:10162000A4230020024B1B68184401F061BF00BFD7 -:1016300078230020024B1B68184401F06BBF00BFE9 -:1016400078230020064991F8243033B10023082282 -:10165000086A81F82430FFF7CDBF0120704700BF32 -:101660007C230020022802BF1022014B1A61704720 -:1016700000080140022802BF4FF48012014B1A619A -:10168000704700BF00080140002310B5934203D00B -:10169000CC5CC4540133F9E710BD00000346024698 -:1016A000D01A12F9011B0029FAD1704703460244EF -:1016B000934202D003F8011BFAE770472DE9F84383 -:1016C0001F4D144695F824200746884652BBDFF884 -:1016D00070909CB395F824302BB92022FF21484606 -:1016E0002F62FFF7E3FF95F824004146C0F108029E -:1016F000A24228BF224605EB8000D6B29200FFF737 -:10170000C3FF95F82430A41B1E44F6B2082E1744DC -:101710009044E4B285F82460DBD1FFF793FF002802 -:10172000D7D108E02B6A03EB82038342CFD0FFF7C7 -:1017300089FF0028CBD10020BDE8F8830120FBE71A -:101740007C2300202DE9F0470D46044600219046F9 -:10175000284640F27912FFF7A9FF234620220021F4 -:10176000284600F09FFF022220212846231D00F07A -:1017700099FF032222212846631D00F093FF0322D4 -:1017800025212846A31D00F08DFF10222821284680 -:1017900004F1080300F086FF08223821284604F1EE -:1017A000100300F07FFF08224021284604F11103B6 -:1017B00000F078FF08224821284604F1120300F0C7 -:1017C00071FF20225021284604F1140300F06AFF23 -:1017D00040227021284604F1180300F063FF08221C -:1017E000B021284604F1200300F05CFF0822B82154 -:1017F000284604F1210300F055FFC02604F122071A -:101800003B46314608222846083600F04BFFB6F525 -:10181000A07F07F10107F3D108223146284604F1E1 -:10182000320300F03FFF002704F1330A94F832300E -:101830004FEAC7099F4209F5A47615D3B8F1000F06 -:1018400008D131460722284604F5997300F02AFF93 -:1018500009F24F16274694F832213B1B93420CD3D2 -:10186000F01DC008BDE8F0870AEB070308223146E7 -:10187000284600F017FF0137D8E7314607F2331347 -:101880000822284600F00EFF08360137E3E7000083 -:1018900038B50C460021054621600346C4F8031004 -:1018A0002046202200F0FEFE20462B1D0222202191 -:1018B00000F0F8FE20466B1D0322222100F0F2FE0C -:1018C0002046AB1D0322252100F0ECFE204610220D -:1018D000282105F1080300F0E5FE072038BD0000CF -:1018E0000023F7B50E460546047F072200911946EE -:1018F00000F09AFD731C0093012200230721284663 -:1019000000F092FDC4B9B31C0093052223460821C0 -:10191000284600F089FD0D243746B278BB1B934260 -:1019200011D32B7FE01DC008AC8ABBB9A04294BF85 -:101930000020012003B0F0BDAB8A0824DB00083B87 -:10194000DB08B370E8E7FB1C214600930822002364 -:10195000284600F069FD08340137DEE7001B18BF98 -:101960000120E7E70023F7B50E46047F0822009127 -:101970001946054600F058FD731CC4B908220093AF -:1019800011462346284600F04FFD102401237278AB -:101990005F1C013B934211D32B7FE01DC008AC8A32 -:1019A000BBB9A04294BF0020012003B0F0BDAB8AB8 -:1019B0000824DB00083BDB087370E7E7F3192146D6 -:1019C000009308220023284600F02EFD08343B46F1 -:1019D000DDE7001B18BF0120E7E70000F8B50E4661 -:1019E00005461446002181223046FFF75FFE2B4654 -:1019F00008220021304600F055FE7CB9072208215C -:101A000030466B1C00F04EFE0F2401236A785F1CE9 -:101A1000013B934204D3E01DC008F8BD0824F4E75D -:101A20002146EB190822304600F03CFE08343B46C4 -:101A3000ECE70000F8B50E46054614460021CE221C -:101A40003046FFF733FE2B4628220021304600F0B7 -:101A500029FE7CB908222821304605F1080300F050 -:101A600021FE30242F462A7A7B1B934204D3E01DAB -:101A7000C008F8BD2824F5E7214607F1090308222C -:101A8000304600F00FFE08340137ECE7F7B5047F6D -:101A90000E460091012310220021054600F0C4FCEF -:101AA000C4B9B31C0093092223461021284600F034 -:101AB000BBFC192437467288BB1B9A4211D82B7F76 -:101AC000E01DC008AC8ABBB9A04294BF0020012031 -:101AD00003B0F0BDAB8A1024DB00103BDB08738041 -:101AE000E8E73B1D2146009308220023284600F02A -:101AF0009BFC08340137DEE7001B18BF0120E7E735 -:101B000030B5094D0A4491420DD011F8013B5840BF -:101B1000082340F30004013B2C4013F0FF0384EA48 -:101B20005000F6D1EFE730BD2083B8ED4FF0FF3322 -:101B3000F7B500EB81061946DFF848C0DFF848E04A -:101B4000B0421BD050F8042B01AF0192042217F8C9 -:101B5000014B81EA046108240D46DB184941013C30 -:101B6000002DBCBF83EA0C0381EA0E0114F0FF04D0 -:101B7000F2D1013A12F0FF02E9D1E1E7D843C943BB -:101B800003B0F0BD9336EAA9EBE1F042F7B56B463E -:101B9000354A106851686A4603C3082333493448FC -:101BA00002F0C2F8044690BB0A256B46314A106821 -:101BB00051686A4603C308232F492D4802F0B4F840 -:101BC0000446002847D00369B3F5CE3F43D8B0F8A8 -:101BD0006620B2F57A7F3ED1284A024402F15C01C8 -:101BE0008B4238D35C3B224900209E1AFFF788FFC6 -:101BF00007463246002004F16401FFF781FFA36825 -:101C00009F4228D1E368984208BF002523E003697A -:101C1000B3F5CE3F26D8428BB2F57A7F20D1174A52 -:101C2000024402F110018B4218D3103B10490020EE -:101C30009D1AFFF765FF06462A46002004F11801A9 -:101C4000FFF75EFFA3689E4202D1E368984201D08D -:101C50000D25AAE70025284603B0F0BD1025A4E70E -:101C60000C25A2E70B25A0E7983D0008DC9B0100AE -:101C700000640008A13D0008909B0100089CFFF74C -:101C8000EFF30983EFF30583014B9B6BFEE700BF86 -:101C900000ED00E008B5FFF7F3FF0000EFF3098364 -:101CA000EFF30583014B5B6BFEE700BF00ED00E047 -:101CB000FEE7000001F0E2BC01F0BABC2DE9F04102 -:101CC000456A15B94162BDE8F0814B68AC4623F026 -:101CD0006047C3F38A4616EA230638BF3E464FEAFA -:101CE000D37EC3F380782B465A68BEEBD27F22F0B6 -:101CF00060440AD0002A18DAA40CB44217D19D42DD -:101D00000FD10D60DEE71346EEE7A74207D102F0E0 -:101D10008044C2F3807242450BD054B1EFE708D241 -:101D2000EDE7CCF800100B60CDE7B44201D0B4422F -:101D3000E5D81A689C46002AE5D11960C3E700007F -:101D40002DE9F0474FF47F49089D01F007044FEA61 -:101D5000D508224405F0070500EBD100944201D1DB -:101D6000BDE8F08704F0070705F0070A57453E462F -:101D700038BF5646111BC6F108068E4228BF0E46D4 -:101D8000E108415C08EBD50E13F80EC0B94029FA02 -:101D900006F721FA0AF1FFB28CEA010147FA0AF7C5 -:101DA00039408CEA010C03F80EC034443544D5E7C1 -:101DB000082341F2210280EA012001B240000029FB -:101DC00080B203F1FF33B8BF504013F0FF03F4D1EA -:101DD0007047000038B50C468D18A54200D138BDBB -:101DE00014F8011BFFF7E4FFF7E700000346406823 -:101DF00048B1026899895A605A89013292B2914277 -:101E00005A8138BF9A81704770B504460D4688B034 -:101E1000202200216846FFF749FC20460495FFF781 -:101E2000E5FF024658B16B46054608AE1C4603CC9A -:101E3000B44228606960234605F10805F6D11046D2 -:101E400008B070BD082817D909280CD00A280CD072 -:101E50000B280CD00C280CD00D280CD00E2814BF49 -:101E60004020302070470C2070471020704714200D -:101E7000704718207047202070470000082817D9A5 -:101E80000C280CD910280CD914280CD918280CD9D6 -:101E900020280CD930288CBF0F200E207047092035 -:101EA00070470A2070470B2070470C2070470D20A8 -:101EB000704700002DE9F843078C0446072F1ED910 -:101EC000D0E9029800254FF6FF73C5F12006A5F171 -:101ED000200029FA05F108FA06F628FA00F0314345 -:101EE0000143C9B21846FFF763FF0835402D03468A -:101EF000EBD13A46E169BDE8F843FFF76BBF4FF617 -:101F0000FF70BDE8F883000010B54B6823B9CA8A9A -:101F100063F30902CA8210BD04691A681C60036178 -:101F2000C38A013BC3824A60EFE700002DE9F84F06 -:101F30001D46CB8A0F46C3F3090105298146924607 -:101F40000B4630D00020AAB207F11A049EB2042E2C -:101F50001FFA80F80FD8904503F1010306D3FB8ADE -:101F60000A4462F309030120FB821AE01AF80060B8 -:101F70000130E654EAE79045F1D21C23A1F1050BAC -:101F8000BBFBF3F203FB12BB7C681FFA8BF6002C41 -:101F900045D14846FFF72AFF044638B978606FF00C -:101FA0000200BDE8F88F4FF00008E6E70026066063 -:101FB00078604FF0000BADB2454510D90AEB08032D -:101FC000221D13F8011B08F101089155B1B21B291C -:101FD0001FFA88F82BD0454506F10106F1D8FB8A97 -:101FE000C3F30902154465F30903BCE71C4601323B -:101FF00092B22368002BF9D16B1F0B441C21B3FB59 -:10200000F1F301339BB29A42D3D2BBF1000FD0D18E -:102010004846FFF7EBFE20B9C4F800B0BFE7012245 -:10202000E7E7C0F800B05E4620600446C1E74545DA -:10203000D5D94846FFF7DAFE08B92060AFE7C0F807 -:1020400000B0002620600446B6E700002DE9F74FF7 -:102050001C465B69074688460092002B00F097807B -:10206000238C2BB1E269002A00F09180072B33D832 -:1020700007F10C00FFF7BAFE054628B96FF002051C -:10208000284603B0BDE8F08F14220021FFF70EFBB5 -:10209000228CE16905F10800FFF7F6FA208C48F080 -:1020A0000041013080B2FFF7E9FEFFF7CBFE0138B7 -:1020B00080B22084013028746369228C1B782A4402 -:1020C00003F01F0363F03F0313723846696029462B -:1020D000FFF7F4FD0125D3E74FF000094FF0800A28 -:1020E0004E464D4600F10C0301930198FFF77EFE2A -:1020F00083460028C2D014220021FFF7D7FA002E11 -:102100003BD10222009BABF808300BF1080E1FFAFE -:1021100082FC0CF10100BCF1060F218C80B201D8C9 -:102120008E422CD3FFF7AAFEFFF78CFE8E4208BF2B -:102130004FF0400A62690138127880B202F01F0243 -:1021400042EA49120BEB00014AEA020A013048F068 -:10215000004281F808A08BF8100059463846CBF8A9 -:102160000420FFF7ABFD238C0135B3424FF0000A8A -:102170002DB289F00109B8D182E70022C5E7E169F3 -:10218000895D01360EF80210B6B20132BFE76FF07A -:10219000010575E7F8B5044615460E4630220021C4 -:1021A0001F46FFF783FA069BB5F5001F6360079B88 -:1021B00028BF4FF6FF72A3624FF0000338BF6A09D1 -:1021C000A760E66197B204F110009A4206D8002396 -:1021D0000360A782E3822383E360F8BD06600133D6 -:1021E00030462036F1E7000003781BB94BB2002BD4 -:1021F000C8BF01707047000000787047F8B50C4602 -:10220000C969074611B9238C002B37D1257E1F2DB4 -:1022100034D8387828BB228C072A2CD8268A36F066 -:1022200003032BD14FF6FF70FFF7D4FD4FF6FF727B -:1022300020F001003602400446EA0565400C45EAFC -:102240004025234629463846FFF700FF002807DDD2 -:10225000626913780133DBB21F2B88BF0023137030 -:10226000F8BD218A2D0645EA012505432046FFF7E2 -:1022700021FE0246E5E76FF00300F1E76FF0010091 -:10228000EEE7000070B504461D4616468AB02822C7 -:1022900000216846FFF70AFABDF838306946ADF804 -:1022A00010300F9B204605939DF84030CDE9026524 -:1022B0008DF81830119B0793BDF84830ADF82030E9 -:1022C000FFF79CFF0AB070BD2DE9F041D3690546C8 -:1022D0000C4616460BB9138C5BBB377E1F2F28D8D4 -:1022E00095F80080B8F1000F26D03046FFF7E2FDE8 -:1022F0003378210241EAC33141EA0801338A41EAD5 -:10230000076141EA034102463346284641F0800115 -:10231000FFF79CFE00280ADD3378012B07D1726994 -:1023200013780133DBB21F2B88BF00231370BDE885 -:10233000F0816FF00100FAE76FF00300F7E70000AB -:10234000F0B504460D461E4617468BB028220021E4 -:102350006846FFF7ABF99DF84C3029465A1E5342A8 -:1023600053418DF800309DF840306A46ADF810308A -:10237000119B204605939DF84830CDE902768DF8F3 -:102380001830149B0793BDF85430ADF82030FFF798 -:102390009BFF0BB0F0BD0000406A00B104307047F5 -:1023A000436A1A68426202691A600361C38A013B88 -:1023B000C38270472DE9F041D0F8208014461D46B5 -:1023C00041460027174E09B9BDE8F081D1E9022343 -:1023D000A21A65EB0303964277EB03031ED2036A4E -:1023E0008B420DD1FFF790FD036A1B6803620369FE -:1023F0000B60C38A0161016A013B8846C382E2E740 -:10240000FFF782FD0B68C8F8003003690B60C38AD0 -:102410000161013BC382D8F80010D4E788460968FF -:10242000D1E700BF80841E002DE9F04F8BB00D4630 -:1024300014469B468046DDF85090002800F01A8133 -:10244000B9F1000F00F01681531E3F2B00F21281EC -:10245000012A03D1BBF1000F40F00C810023CDE92C -:102460000833B8F81430B5EBC30F4FEAC30703D3F2 -:1024700000200BB0BDE8F08F2B199F42D8F80C302C -:1024800036BF7F1B2746FFB21BB9D8F81030002B90 -:102490007BD0272D4ED8C5F12806B7424FF0000358 -:1024A00034BF3E46F6B2009329463246D8F80800BB -:1024B00008ABFFF745FCA7EB060A35445FFA8AFA3A -:1024C0002821B8F8143003F10053053BDB000493D6 -:1024D000D8F80C300393039B13B1BAF1000F2CD141 -:1024E000D8F8100040B1BAF1000F05D0524600965E -:1024F00008AB691AFFF724FC38B2002FB8D0660782 -:102500000AD00AAB03EBD40111F8083C624202F096 -:102510000702134101F8083C082C3DD9102C40F269 -:10252000B680202C40F2B880BBF1000F00F09D80F7 -:10253000082335E0BA460026C2E7049BE02B28BFFB -:10254000E02306930B44AB42059315D95A1B9245E1 -:1025500038BF5246039828BFD2B20096691A08AB1A -:1025600004300792FFF7ECFB079A1644AAEB020A25 -:102570001544F6B25FFA8AFA049B069A05999B1AEB -:102580000493039B1B680393A5E700933A462946EF -:10259000D8F8080008ABADE7BBF1000F13D001235A -:1025A000B4EBC30F6CD0082C12D89DF82030621EFB -:1025B00023FA02F2D50706D54FF0FF3202FA04F4EF -:1025C00023438DF820309DF8203089F8003050E703 -:1025D000102C12D8BDF82030621E23FA02F2D10767 -:1025E00006D54FF0FF3202FA04F42343ADF8203051 -:1025F000BDF82030A9F800303BE7202C0FD808990F -:10260000631E21FA03F3DA0705D54FF0FF3202FA11 -:1026100004F40C430894089BC9F8003029E7402CC7 -:102620002BD0DDE90865611EC4F12102A4F121036C -:1026300026FA01F105FA02F225FA03F311431943D0 -:10264000CB0712D50122A4F12003C4F1200102FA24 -:1026500003F322FA01F1A240524243EA010363EB81 -:10266000430332432B43CDE90823DDE90823C9E9BD -:102670000023FEE66FF00100FBE66FF00800F8E6CD -:10268000082CA0D9102CB3D9202CEED8C3E7BBF16D -:10269000000FADD0022383E7BBF1000FBBD00423B2 -:1026A0007EE70000012A30B5144638BF012200251C -:1026B000402A28BF402285B0012CCDE9025517D809 -:1026C0001B788DF8083053070AD004AB03EBD20512 -:1026D00015F8083C544204F00704A34005F8083CF0 -:1026E0000346009102A80021FFF72AFB05B030BD88 -:1026F000082CE5D9102C03D81B88ADF80830E2E788 -:10270000202C02D81B680293DDE7D3E90045CDE910 -:102710000245D8E710B5CB681BB98B600B618B8283 -:1027200010BD04691A681C600361C38A013BC3823F -:10273000CA60F0E703064CBFC0F3C0300220704708 -:1027400008B50246FFF7F6FF022806D15306C2F38A -:102750000F2001D100F0030008BDC2F30740FBE7E2 -:102760002DE9F04F93B0CDE903230A6804461046E3 -:10277000FFF7E0FF02280CBF0026C2F30626002A5E -:102780000D46824680F2F98112F0C04940F0F58191 -:10279000097B002900F0F181022803D02378B3429D -:1027A00040F0EE81C2F304631046069302F07F030B -:1027B0000593FFF7C5FF059B00224FEA83480023DE -:1027C00048EA0A48294448EA4668CE78CDE9082311 -:1027D000F309834648EA0008029367D0059B024646 -:1027E000009320465346676808A9B847002800F0C0 -:1027F000CA81276A4FB9414604F10C00FFF704FB78 -:10280000074690B96FF0020054E03B6998450DD03F -:102810003F68002FF9D1414604F10C00FFF7F4FAAC -:1028200007460028EED0236A3B60276297F817C05E -:1028300006F01F08CCF3840CACEB08001FFA80FEF6 -:102840000028B8BF0EF12000A8EB0C031FFA83FE8E -:10285000B8BF00B2002B0793BEBF0EF120031BB21E -:102860000793D7E9022152EA010338D04FF0000C58 -:10287000039BDFF8F8E19A1A049B63EB010196458C -:102880007CEB01032BD36B7B97F81AE0734519D1CE -:10289000029B002B78D0012821DC7868F8B9DFF89A -:1028A000D0C1944570EB010316D337E0276A27B9EE -:1028B0006FF00C0013B0BDE8F08F3B699845B5D0C0 -:1028C0003F68F4E76A4890427CEB010301D30020A3 -:1028D000F0E7029B002BFAD0079B0F2B17DCFA7D49 -:1028E000B30002F0030203F07C031343FB75394687 -:1028F0002046FFF709FB6B7BBB76029B3BB9FB7D58 -:10290000C3F38402013262F38603FB75D0E76A7B6E -:10291000BB7E9A42DBD1029B002B35D0B309022B40 -:1029200032D0039B1422BB60049B0021FB600DA8E6 -:10293000FEF7BCFE039B20460A93049BADF83EB015 -:102940000B932B1D0C932B7B8DF840A0013BDBB22E -:10295000ADF83C30069B8DF841808DF84230059BE8 -:102960000AA98DF8433094F82C3083F001038DF8D8 -:102970004430A3689847FB7DC3F38403013303F01D -:102980001F039B02FB82A2E7FB7DC6F34012B2EB62 -:10299000D31F40F0FB80C3F38403434540F0F9802C -:1029A000029A2B7BB609002A4DD0F20762D4032B82 -:1029B00040F2F280039BAE1DBB60049B3246FB607D -:1029C0002B7B3946033BDBB204F10C00FFF7AEFA78 -:1029D00000280CDA39462046FFF796FAFB7DC3F350 -:1029E0008403013303F01F039B02FB820AE7AB88D9 -:1029F000DDE908843B834FF6FF73C9F12000A9F19C -:102A0000200228FA09F104FA00F0014324FA02F244 -:102A100011431846C9B2FFF7CBF909F10809B9F11A -:102A2000400F0346E9D13146B8822A7B033AD2B23D -:102A3000FFF7D0F9FB7DB882DA43C2F3C01262F32C -:102A4000C713FB7543E7AEB92E1D013B324639462D -:102A5000DBB204F10C00FFF769FA0028BADB2A7B2D -:102A60003146013AB88AD2B2E2E700BF80841E0044 -:102A700040420F00F98A013BC1F309010429DAB28F -:102A80005DD80023281D07F11B069A4208D910F8CB -:102A900001CB013306F801C001310529DBB2F4D1C5 -:102AA000934228BF0023039938BF04330A91049945 -:102AB00038BFDBB20B9107F11B010C91796838BF6D -:102AC0005B190D910E93FB8AADF83EB0C3F3090379 -:102AD0001A44069BADF83C208DF84230059B8DF8DA -:102AE00040A08DF8433094F82C308DF8418083F06D -:102AF00001038DF8443000237B602A7BB88A013AB9 -:102B0000291DFFF767F93B8BB882834203D120462A -:102B1000A3680AA9984720460AA9FFF7FBFDFB7D99 -:102B2000BA8AC3F38403013303F01F039B02FB82C1 -:102B30003B8B9A420CBF00206FF01000BAE67B6816 -:102B4000002BADD0052001E033461C301E68002E5E -:102B5000FAD1091A081D2E1D184401EB090CBCF10D -:102B60001B0F5FFA89F39BD89A4299D916F8013B5B -:102B700009F1010900F8013BEFE76FF0090099E660 -:102B80006FF00A0096E66FF00B0093E66FF00D0011 -:102B900090E66FF00E008DE66FF00F008AE600BF42 -:102BA000F0B53F4D3F4FEB6943F00073EB61EB69CC -:102BB0003D4B9B6AD3F800623E4046F00106C3F8E5 -:102BC0000062D3F800423C4044EA002444F001048F -:102BD000C3F80042002955D000200646C3F81C0265 -:102BE000C3F80402C3F80C02C3F8140203EBC004D8 -:102BF00001300E28C4F84062C4F84462F6D10027C0 -:102C00004FF0010C9678148816F0010F18BFD3F816 -:102C100004E20CFA04F01CBF40EA0E0EC3F804E212 -:102C200016F0020F18BFD3F80CE203EBC4041CBF6C -:102C300040EA0E0EC3F80CE2760748BFD3F81462E0 -:102C400007F1010744BF0643C3F814625668B9424E -:102C5000C4F84062966802F10C02C4F84462D3F8EA -:102C60001C4240EA0400C3F81C02CBD1D3F8002276 -:102C700022F00102C3F80022EB6923F00073EB613C -:102C8000EB69F0BD0122C3F84012C3F84412C3F847 -:102C90000412C3F81412C3F80C22C3F81C22E5E78F -:102CA000001002400000FFFFA8230020184A08B5CA -:102CB000916A8B688B6013F0010104D013F00C0F44 -:102CC00018BF4FF48031D80506D513F4406F14BFF8 -:102CD00041F4003141F00201D80306D513F4402F2E -:102CE00014BF41F4802141F00401D3690BB10848BD -:102CF0009847302383F311880021064800F048FBF1 -:102D0000002383F31188BDE8084000F099BD00BF9F -:102D1000A8230020B023002038B5124CA36ADD6838 -:102D2000AA0712D05A6922F002025A61A36913B1AC -:102D3000012120469847302383F3118800210A4857 -:102D400000F026FB002383F31188EB0606D5102143 -:102D5000A36AD960236A0BB102489847BDE838409E -:102D600000F06EBDA8230020B823002038B5124C17 -:102D7000A36A1D69AA0712D05A6922F010025A618B -:102D8000A36913B1022120469847302383F31188A9 -:102D900000210A4800F0FCFA002383F31188EB06B7 -:102DA00006D51021A36A1961236A0BB1024898471E -:102DB000BDE8384000F044BDA8230020B82300201F -:102DC00038B50F4CA36A5D682A075D600AD50422F6 -:102DD00022701A6822F002021A60636A13B100219D -:102DE000204698476B0706D5A36A9969236A13B1F1 -:102DF000034809049847BDE8384000F021BD00BFF2 -:102E0000A823002010B50E4C204600F02FF90D4BE2 -:102E10000B211320A36200F009F90B21142000F00C -:102E200005F90B21152000F001F90B21162000F007 -:102E3000FDF8BDE8104000220E201146FFF7B0BE9D -:102E4000A8230020006400400F4B10B598420446B0 -:102E500005D10E4BDA6942F00072DA61DB690122BA -:102E6000A36A1A60A36A5A68D20707D562685168D4 -:102E70001268D9611A60064A5A6110BD0121082002 -:102E800000F0B0F9EEE700BFA823002000100240D8 -:102E90005B87010003291AD8DFE801F0020A0F144A -:102EA000836A9B6813F0E05F14BF01200020704725 -:102EB000836A9868C0F380607047836A9868C0F33B -:102EC000C0607047836A9868C0F300707047002044 -:102ED0007047000010B5032927D8DFE801F002276A -:102EE0002B2F836A9968C1F30161183103EB011339 -:102EF0001078840648BF5468C0F3001158BF948806 -:102F00004FEA410148BF41EAC40100F00F00586098 -:102F100048BF41F00401906858BF41EA4451D2686B -:102F200041F001019860DA60196010BD836A03F511 -:102F3000C073DDE7836A03F5C873D9E7836A03F5D5 -:102F4000D073D5E701290AD002290FD081B9836A4D -:102F5000DA68920701D1186903E001207047836A9B -:102F6000D86810F0030018BF01207047836AF2E7A9 -:102F70000020704710B539B9836AD96889071BD119 -:102F80001B699C0704D110BD012915D00229FAD173 -:102F9000816AD1F8C031D1F8C441D1F8C8011061BB -:102FA000D1F8CC015061202008610869800717D151 -:102FB000486940F0100012E0816AD1F8B031D1F8D0 -:102FC000B441D1F8B8011061D1F8BC0150612020A2 -:102FD000C860C868800703D1486940F002004861B2 -:102FE000C3F34000C3F38001000140EA41111079AE -:102FF00020F030000143117189064BBF916811899F -:10300000DB085B0D4CBF63F31C0163F30A0113790A -:1030100048BF916064F3030313714FEA14234FEA2E -:10302000144458BF118113705480ACE70122090188 -:1030300000F1604303F56143C9B283F8001300F067 -:103040001F039A4043099B0003F1604303F561436A -:10305000C3F880211A607047090100F16040C9B2CD -:1030600000F56D4001767047FFF7CCBE0123037079 -:10307000002300F10802C0E9022200F11002C0E9B9 -:103080000422C0E90633C0E90833436070470000FA -:1030900010B53023044683F3118802234160037086 -:1030A000FFF7D2FE04230020237080F3118810BDA7 -:1030B0002DE9F0411F4604460D461646302383F3A2 -:1030C000118800F108082378052B0DD029462046E9 -:1030D000FFF7E0FE40B1204632462946FFF7FAFEF0 -:1030E000002080F3118808E03946404600F040F99E -:1030F0000028E8D0002383F31188BDE8F0810000A8 -:103100002DE9F0411F4604460D461646302383F351 -:10311000118800F110082378052B0DD02946204690 -:10312000FFF710FF40B1204632462946FFF722FF45 -:10313000002080F3118808E03946404600F018F975 -:103140000028E8D0002383F31188BDE8F081000057 -:1031500000238268037503691B6899689142FBD25A -:103160005A680360426010605860704700238268AC -:10317000037503691B6899689142FBD85A6803601C -:10318000426010605860704708B50846302383F3EA -:1031900011880B7D032B05D0042B0DD02BB983F3A5 -:1031A000118808BD00228B691A604FF0FF338361DC -:1031B000FFF7CEFF0023F2E7D1E9003213605A6037 -:1031C000F3E70000FFF7C4BF054BD968087518681E -:1031D000026853601A6001220275D860FDF796BB41 -:1031E000D823002030B50C4B0446DD684B1C87B05B -:1031F0000FD02B466846094A00F0F0F82046FFF74A -:10320000E3FF009B13B1684600F0F0F8A86907B02F -:1032100030BDFFF7D9FFF9E7D82300208931000836 -:10322000044B1A68DB6890689B68984294BF002042 -:1032300001207047D8230020084B10B51C68D868BF -:10324000226853601A6001222275DC60FFF78EFF4E -:1032500001462046BDE81040FDF758BBD8230020AA -:10326000044B1A68DB6892689B689A4201D9FFF7A1 -:10327000E3BF7047D823002038B501230025064C52 -:10328000064907482370656000F020FB0223237085 -:1032900085F3118838BD00BF30250020B03D0008FF -:1032A000D823002000F0B4B8EFF3118020B9EFF379 -:1032B0000583302282F311887047000010B530B9C1 -:1032C000EFF30584C4F3080414B180F3118810BD32 -:1032D000FFF7C6FF84F31188F9E700008B60022333 -:1032E00008618B82084670478368A3F1440243F863 -:1032F000142C026943F8442C426943F8402C094AD3 -:1033000043F8242CC268A3F1200043F8182C0222B1 -:1033100003F80C2C002203F80B2C034A43F8102C62 -:10332000704700BF1D090008D823002008B5FFF72B -:10333000DBFFBDE80840FFF745BF0000024BDB683C -:1033400098610F20FFF740BFD8230020302383F37C -:103350001188FFF7F3BF000008B50146302383F35F -:1033600011880820FFF73EFF002383F3118808BD72 -:10337000064BDB6839B1426818605A6013604360DD -:103380000420FFF72FBF4FF0FF307047D8230020F5 -:1033900038B504460D462068844200D138BD036824 -:1033A00023605C608561FFF70DFFF4E710B50A4C00 -:1033B00023699A6891420CD85A6881600360426020 -:1033C00010609A685860511A99604FF0FF33A361FA -:1033D00010BD1B68891AECE7D8230020C0E903233D -:1033E000002310B410BC4361FFF7E0BF036881689D -:1033F0009A680A449A60426813605A6000234FF04A -:10340000FF320360014B9A61704700BFD823002050 -:1034100070B5124D2A46EB690133EB6152F8103F4B -:10342000934206D030269A68013A9A602C69A368C4 -:1034300003B170BDD4E900210A605160236083F3B9 -:1034400011882046D4E90331984786F311886169D1 -:103450000029EBD02046FFF7A9FFE7E7D82300209B -:1034600000207047FEE70000704700004FF0FF307B -:1034700070470000BFF34F8F024AD368DB07FCD4CC -:10348000704700BF0020024008B5074B1B7853B9B6 -:10349000FFF7F0FF054B1A69120641BF044A5A6054 -:1034A00002F188325A6008BD482500200020024001 -:1034B0002301674508B5054B1B7833B9FFF7DAFFE1 -:1034C000034A136943F08003136108BD48250020B7 -:1034D000002002407F289ABF00F5003080020020C3 -:1034E000704700004FF480607047000080207047F4 -:1034F0007F2808B50BD8FFF7EDFF00F58063026861 -:10350000013204D104308342F9D1012008BD0020EA -:10351000FCE700007F2810B504461CD8FFF7AAFF7F -:10352000FFF7B2FFF3220D4B4FF48061DA60022205 -:103530001A61FFF7CFFF58611A6942F040021A6121 -:10354000FFF798FF00F004F9FFF7B4FF2046BDE84D -:103550001040FFF7CDBF002010BD00BF002002408B -:103560002DE9F843054612F00100144606D040F25A -:10357000F32200201E4B1A60BDE8F8831D4BAA18E9 -:103580009A4204D94FF43E72194B1A60F4E7FFF7E0 -:103590007BFF4FF00109FFF76DFFDFF85C806D1ACC -:1035A000012C0F4605EB010603D8FFF783FF01202E -:1035B000E2E73B88C8F8109033800020FFF75AFFFD -:1035C000C8F81000338831F8022B9BB29A420CD015 -:1035D00040F20F32064B1A60084B1E60084B1C600D -:1035E000084B1F60FFF766FFC6E7023CD8E700BF45 -:1035F0004425002000000208002002403825002059 -:10360000402500203C250020084908B50B7828B14A -:103610001BB9FFF739FF01230B7008BD002BFCD04D -:10362000BDE808400870FFF745BF00BF48250020EF -:1036300070B5FFF739FE4FF47A710D4B0D4EDB6913 -:10364000326801FB03F3934237BF0B4A0A495168C2 -:10365000156836BF4C1CD1E9005454605D1944F123 -:1036600000043360FFF72AFE2846214670BD00BFE4 -:10367000D82300204C2500205025002070B5FFF7EE -:1036800013FE4FF47A710F4B0F4EDB69326801FB6A -:1036900003F3934237BF0D4A0C49516815683ABF8E -:1036A0004C1C5460D1E900545D1944F100043360AE -:1036B000FFF704FE4FF47A72002328462146FCF7F8 -:1036C00031FF70BDD82300204C250020502500205C -:1036D00010B5094C013AD2B2FF2A00D110BD5008F2 -:1036E00054F82030013054F820009BB243EA0043E4 -:1036F00041F8043BEEE700BF046C004010B50748FA -:10370000013AD2B2FF2A00D110BD0C88530840F80C -:1037100023404C88013340F82340F1E7046C00401B -:1037200007B50122002001A9FFF7D2FF019803B0DD -:103730005DF804FB13B50446FFF7F2FFA04205D085 -:103740000122002001A90194FFF7D8FF02B010BDAB -:103750007047000045F25552064B1A6002225A602B -:1037600040F6FF729A604CF6CC421A600122024B7E -:103770001A707047003000405C250020034B1B7816 -:103780001BB14AF6AA22024B1A6070475C25002042 -:1037900000300040044B1A682AB902F1804202F559 -:1037A0000432526A1A607047582500204FF0807228 -:1037B000014B5A62704700BF0010024008B5FFF786 -:1037C000E9FF024B1868C0F3407008BD582500207F -:1037D00008B5FFF7DFFF024B1868C0F3007008BDA3 -:1037E00058250020EFF30983203383F30988002351 -:1037F00083F3118870470000302080F3118862B68F -:103800000C4B0D4AD96821F4E0610904090C0A4304 -:10381000DA60D3F8FC20094942F08072C3F8FC203A -:103820000A6842F001020A602022DA7783F8220057 -:10383000704700BF00ED00E00003FA05001000E053 -:10384000302310B583F311880B4B5B6813F40063CE -:103850000FD0EFF309844FF08073203CE36184F3D1 -:103860000988FFF7DDFC10B1044BA36110BD044BC8 -:10387000FBE783F31188F9E700ED00E02F0900086A -:103880003209000870470000FEE700000A4B0B48B1 -:103890000B4A90420BD30B4BC11EDA1C121A22F0BA -:1038A00003028B4238BF00220021FDF7FFBE53F810 -:1038B000041B40F8041BECE7343E0008E025002020 -:1038C000E0250020E0250020FEE7000070B500257F -:1038D00004461A4B86B05860856201630E46FFF7B6 -:1038E0008BFF04F11003C4E904334FF0FF33A361ED -:1038F000134BE561D9692B460A462046C4E90823E3 -:1039000004F134018023C4E900440E4AA560E56255 -:103910002565FFF7E3FC01230B4AE0600375009285 -:10392000726868460192B268CDE90223074BCDE97F -:103930000435FFF7FBFC06B070BD00BF302500204A -:10394000D8230020BC3D0008C13D0008C93800084C -:1039500000F030B808B500F063F9FFF78DFCBDE862 -:103960000840FFF717BF0000704700004FF0FF311D -:103970000E4B1A6919611A6900221A611869D86810 -:10398000D960D968DA60DA68DA6942F08052DA61BF -:10399000DA69DA6942F00062DA61054ADB691368C4 -:1039A00043F48073136000F01BB900BF00100240A5 -:1039B00000700040194B1A6842F001021A601A6840 -:1039C0009007FCD51A6802F0F9021A6000225A60CA -:1039D0005A6812F00C0FFBD11A6842F480321A6058 -:1039E0001A689103FCD55A6842F4E8125A601A68C2 -:1039F00042F080721A601A689201FCD51221084ABE -:103A00005A60084A11605A6842F002025A605A68C5 -:103A100002F00C02082AFAD1704700BF00100240E1 -:103A200000641D0000200240084A08B5516913686F -:103A30000B4003F00103536123B1054A13680BB136 -:103A400050689847BDE80840FFF7FABE00040140FF -:103A500060250020084A08B5516913680B4003F03F -:103A60000203536123B1054A93680BB1D0689847AC -:103A7000BDE80840FFF7E4BE0004014060250020D7 -:103A8000084A08B5516913680B4003F004035361F9 -:103A900023B1054A13690BB150699847BDE8084046 -:103AA000FFF7CEBE0004014060250020084A08B59B -:103AB000516913680B4003F00803536123B1054AB1 -:103AC00093690BB1D0699847BDE80840FFF7B8BECD -:103AD0000004014060250020084A08B551691368B8 -:103AE0000B4003F01003536123B1054A136A0BB175 -:103AF000506A9847BDE80840FFF7A2BE00040140A5 -:103B000060250020174B10B55A691C68144004F456 -:103B100078725A61A30604D5134A936A0BB1D06A2E -:103B20009847600604D5104A136B0BB1506B984749 -:103B3000210604D50C4A936B0BB1D06B9847E20574 -:103B400004D5094A136C0BB1506C9847A30504D5F2 -:103B5000054A936C0BB1D06C9847BDE81040FFF755 -:103B60006FBE00BF00040140602500201A4B10B555 -:103B70005A691C68144004F47C425A61620504D5F9 -:103B8000164A136D0BB1506D9847230504D5134A9F -:103B9000936D0BB1D06D9847E00404D50F4A136EB6 -:103BA0000BB1506E9847A10404D50C4A936E0BB12B -:103BB000D06E9847620404D5084A136F0BB1506F5A -:103BC0009847230404D5054A936F0BB1D06F9847EB -:103BD000BDE81040FFF734BE00040140602500201E -:103BE000062108B50846FFF721FA06210720FFF74E -:103BF0001DFA06210820FFF719FA06210920FFF710 -:103C000015FA06210A20FFF711FA06211720FFF7FF -:103C10000DFABDE8084006212820FFF707BA00008A -:103C200008B5FFF7A3FE054800F00CF8FFF71CFAF3 -:103C3000FFF79AFEBDE8084000F002B8C83D000852 -:103C400000F042B8002319461C4A0133102BC2E988 -:103C5000001102F10802F8D1194B9A6942F07D0275 -:103C60009A619B690268174BDA6082685A60426801 -:103C70001A60C26803F58063DA6042695A600269BB -:103C80001A608269C3F80C24026AC3F80424C2696A -:103C9000C3F80024426AC3F80C28C26AC3F8042897 -:103CA000826AC3F80028026BC3F80C2C826BC3F83D -:103CB000042C426BC3F8002C704700BF6025002025 -:103CC00000100240000801404FF0E023044A0821A0 -:103CD0005A6100229A6107220B201A61FFF7BCB9D2 -:103CE0003F19010008B5302383F31188FFF7DAFA92 -:103CF000002383F3118808BD08B5FFF7F3FFBDE883 -:103D00000840FFF79DBD000010B501390244904204 -:103D100001D1002005E0037811F8014FA34201D042 -:103D2000181B10BD0130F2E72DE9F0419BB10446AC -:103D3000C91A1778014403F1FF3C8C42204601D98F -:103D4000002008E005780134BD42F6D10CEB0405F3 -:103D5000D618A54201D1BDE8F08115F8018D16F8FD -:103D600001EDF045F5D0E8E7034611F8012B03F823 -:103D7000012B002AF9D170476F72672E617264754A -:103D800070696C6F742E663130332D51696F7465B4 -:103D90006B5065726970680040A2E4F16468910636 -:103DA0000041A3E5F265699207000000633000005E -:103DB000AC3D000830240020302500206D61696E84 -:103DC0000069646C65000000001800004444414430 -:103DD000445449440100000042444444444444449F -:103DE00000000000444444444444444400000000B3 -:103DF0004444444444444444000000004444444493 -:103E00004444444450C7FF7F01000000000000000C -:103E1000E803000000000000009C0100000000001A -:103E2000640000000000000040420F00FE2A010074 -:043E3000D2040000B8 +:10052000704700BF02E000F000F8FEE772B6264810 +:1005300080F30888254880F3098825482549086004 +:10054000022080F31488BFF36F8F03F025F803F0C7 +:1005500089F84FF0553020491B4A91423CBF41F881 +:10056000040BFAE71D49194A91423CBF41F8040BBC +:10057000FAE71B491B4A1C4B9A423EBF51F8040B39 +:1005800042F8040BF8E700201849194A91423CBF91 +:1005900041F8040BFAE703F003F803F065F8154C93 +:1005A000154DAC4203DA54F8041B8847F9E700F014 +:1005B0003FF8124C124DAC4203DA54F8041B884742 +:1005C000F9E702F0EBBF0000000900200011002055 +:1005D0000000000808ED00E00001002000090020F4 +:1005E000183B0008001100202411002028110020D1 +:1005F000D4250020600100086001000860010008A7 +:10060000600100082DE9F04FC1F80CD0C3689D4689 +:10061000BDE8F08F002383F311882846A04700200F +:1006200002F0E6FCFEE702F07FFC00DFFEE70000E0 +:10063000F8B500F03BFE02F0FDFE074602F048FF71 +:10064000064600283ED12B4B9F423BD001339F42B0 +:100650003BD0294B27F0FF029A4239D1F8B200F083 +:1006600001FC354642F2107400F002FC08B100248F +:10067000254601F003F978B30024032000F042F886 +:10068000254636B11D4B9F4203D0002402F018FFCF +:100690002546002002F0D8FE194B9B6813F040035A +:1006A0001FD00DB100F044F800F042FC01F07AF9DF +:1006B0000546C4B101F076F9401BA04213D900F001 +:1006C00037F8F3E735460024CEE704460125CBE7AB +:1006D00005464FF47A74C7E7B4F57A7F08BF012561 +:1006E000CFE71C46E0E700F0D5FC012002F086FCD5 +:1006F000DFE700BF010007B0000008B0263A09B0EC +:10070000000C0140084B187003280CD8DFE800F0FB +:1007100008050208022000F025BE022000F01ABEE3 +:100720000022024B5A607047281100202C11002033 +:1007300038B501F0A3F830B103221F4B1A70002224 +:100740001E4B5A6038BD1E4B1E4A19680131F9D044 +:1007500004339342F9D11C4C194DD4F80424AA4215 +:10076000F0D31A4B9B6803F1006303F5C8439A4228 +:10077000E8D202F079FE02F08BFE002000F0B0FD1E +:100780000220FFF7BFFF124BDA690022DA61D96954 +:1007900099699A619B6972B64FF0E023C3F8085DCE +:1007A0003021D4F80034D4F8042481F311889D4614 +:1007B00083F308881047C5E7281100202C1100207A +:1007C0000064000820640008006000080011002098 +:1007D0000010024049F26900084A136899B21B0CE4 +:1007E00000FB013344F250611360054B186882B27C +:1007F000000C01FB0200186080B27047201100203D +:100800001C11002010B504460021102200F0C6FD86 +:10081000034B03CB206061601868A06010BD00BF6F +:10082000E8F7FF1F2DE9F0410026ADF5507D6EACD5 +:1008300040F2751207460D4610A831460F9600F09B +:10084000ADFD4FF4C4723146204600F0A7FD01F023 +:10085000A9F84FF47A72B0FBF2F0264B0DF13C0888 +:10086000186093E80700022384E807000DF5ED7097 +:100870002382FFF7C7FF4EF603031F4907A823840F +:1008800003F0FCF81F230DF2EB2284F832310DF156 +:10089000340C07AB1E4603CE6645106051603346EC +:1008A00002F10802F6D130681060B188B3792046B1 +:1008B000918093714146012200F0BCFD0023039317 +:1008C000AB7E80B2029305F1190301930123CDE9B8 +:1008D00004800093384605A3D3E90023E97E01F0A4 +:1008E000A7FB0DF5507DBDE8F08100BF9E6AC421D5 +:1008F000818A46EE341100208C3A00082DE9F0413F +:10090000264D80462B7A0C46DAB0FBB9204627A943 +:1009100000F0A0FE0746002836D19DF89D60C82E45 +:1009200032D801464FF4FA72284600F037FD3246BD +:100930000DF19E0105F1090000F01EFD9DF89C30AF +:100940002E4477722B720BB9E37E2B728122002129 +:1009500006AD27A800F022FD0122294627A800F0B5 +:10096000B5FE00230393A37E80B2029304F1190322 +:1009700001932823CDE904500093404605A3D3E911 +:100980000023E17E01F054FB5AB0BDE8F08100BFC6 +:10099000AFF3008026417272DF25D7B77C2100209B +:1009A000F0B54FF48A750024234EF1B005FB0065C5 +:1009B00096F8D830D822214685F8DC3085F8E84012 +:1009C0003AA800F0EBFC06F1090000F0DFFCD5F8D6 +:1009D000E430C2B206AF8DF8F00006F109010DF166 +:1009E000F100CDE93A3400F0C7FC394601223AA8BB +:1009F00000F098FE80B2CDE9047008230127CDE90C +:100A0000023706F1D80301933023317A00930B4863 +:100A100007A3D3E9002301F00BFBA04206DD00F0A1 +:100A2000C1FFC5F8E000384671B0F0BD2046FBE7D5 +:100A300078F6339F93CACD8D7C2100204C21002075 +:100A4000F0B51E4E1E4F1F4D85B0304601F01CFB09 +:100A5000044660B310220021684600F09FFC4FF06E +:100A60000003227B6068A16862F303038DF8003005 +:100A700002AB03C3019B2268384662F31C03019357 +:100A80009DF800306A4643F020038DF800300023C3 +:100A9000194602F085F9044620B9304601F0F8FA0B +:100AA0002C70D2E72B78072B03D801332B7005B0BD +:100AB000F0BD024801F0ECFAF9E700BF4C2100203C +:100AC000A82300207523002070B50D4614461E464D +:100AD00001F00AFA50B9022E10D1012C0ED112A346 +:100AE000D3E900230120C5E9002307E0282C10D01A +:100AF00005D8012C09D0052C0FD0002070BD302C5A +:100B0000FBD10BA3D3E90023ECE70BA3D3E900232C +:100B1000E8E70BA3D3E90023E4E70BA3D3E9002321 +:100B2000E0E700BFAFF30080401DA12026812A0B23 +:100B300078F6339F93CACD8D9E6AC421818A46EE92 +:100B400026417272DF25D7B7F017304A39059E5615 +:100B500038B505460E4C0021013500F0E3FBA4F842 +:100B6000F051B4F8F00100F0C5FB78B1B4F8F00131 +:100B700000F0D0FB014648B9B4F8F00100F0D2FB18 +:100B8000B4F8F0310133A4F8F031EAE738BD00BF22 +:100B90007C2100202DE9F04F8DB000AF04460D46BA +:100BA00001F0A2F9002846D12B7E022B1AD1EB8A44 +:100BB000012B17D100F0F6FE0646FFF70BFE4FF4AF +:100BC000C873B0FBF3F202FB1303DFF878829BB229 +:100BD00006F516763344C8F80030EB7E33B90022B0 +:100BE000994B1A703437BD46BDE8F08F284607F19F +:100BF0001C0100F0EDFC0028F4D107F10C00FFF718 +:100C000001FEBD7F07F10C012A4607F11F0002F02B +:100C100005FF0028E3D10F2D08D88B4B1D70D8F8A5 +:100C20000030A3F51673C8F80030DBE72046397FA3 +:100C300001F052F9D6E7EB8A282B6BD010D8012BA4 +:100C400063D0052BCED1BFF34F8F8049804BCA684C +:100C500002F4E0621343CB60BFF34F8F00BFFDE7A8 +:100C6000302BBFD17B4CEA7E237A9A42BAD194F8DA +:100C7000DC206B7E9A42B5D1284604F1EA0100F0EF +:100C80007DFD06460028ADD1012384F8E83000F050 +:100C900089FED4F8E030C01A192840F6B83338BFBE +:100CA0001920984228BF1846FFF7C4FB6A49FFF78E +:100CB00057FA05462068FFF7BDFB6849FFF750FA71 +:100CC00001462846FFF706FBFFF70CFC20604FF4B7 +:100CD0008A7194F8D9307B607A68636801FB02F509 +:100CE000621992F8E80050B1D2F8E400E946834274 +:100CF00015D0002382F8E830C2F8E030CD466368B2 +:100D0000574A9B0A013313816CE729462046FFF7B7 +:100D100089FD67E729462046FFF7F0FD62E7B2F854 +:100D2000EC803B6008F1030A4FEA9A0A4FEA8A0214 +:100D3000D11DC908A9EBC1039D46EB4600215846C9 +:100D400000F02CFB05F1EE0142465846214400F02C +:100D500013FB3B6813B9012000F0C2FA94F8D200EB +:100D600000F0C8FA054630B9207200F0E3FA2846D0 +:100D700000F0B6FAC2E7D4F8D4303BB994F8D20008 +:100D8000B4F8F031834201D8FFF7E2FED4F8D43052 +:100D900043449D4208D294F8D200B4F8F0310130B7 +:100DA000834201D8FFF7D4FE594660685FFA8AF2A1 +:100DB00000F0FCFA08B9CD4689E7636894F8D200E0 +:100DC00043446360D4F8D43008EB030AC4F8D4A0D9 +:100DD00000F090FA824509D394F8D230D4F8D400C8 +:100DE0000133401B84F8D230C4F8D400B8F1FF0FAF +:100DF0000FD80025257200F09DFA284600F070FA01 +:100E000000F03CFD164B188108B9FFF791FCCD4668 +:100E1000E8E64FF48A727B6894F8D90002FB03433A +:100E2000D3F8E42083F8E86002F58072C3F8E0604C +:100E3000C3F8E420FFF7B4FDFFF702FE84F8D960A1 +:100E4000B9E700BF482100204521002000ED00E067 +:100E50000400FA057C210020CDCCCC3D6666663FBF +:100E600034110020014B1870704700BF4011002062 +:100E700030B54FF00054254B226885B09A4207D018 +:100E800002F030FB0446C0B90024204605B030BD56 +:100E90000025627D1E4B1F481A70237DC9220372F4 +:100EA0001D49C0F8E450093000F066FA2046E022FF +:100EB000294600F073FA0124E7E7184A184DD36970 +:100EC00043F00073D361AA6D164B9A42DCD12B6EAE +:100ED000013B7E2BD8D8144A01AB07CA83E8070030 +:100EE0001846032100F09AFC6B6D83424FF000031B +:100EF000CAD12A6D8A4203BFAB652A6E044B1C46D9 +:100F000001BF1A70EA6D094B1A60BEE79AAD44C57D +:100F1000401100207C21002016000020001002401B +:100F2000006600405041A0B05866004018110020F3 +:100F30002DE9F04385B000F0A1FC0223494C637118 +:100F400000230293484B2081D3F800C0BCF57A7F80 +:100F500012D3464F464BB7FBFCF59C458CBF0A238A +:100F60001123B5FBF3F603FB1652591EC8B2002A33 +:100F70003ED002290B46F4D89DF80B303D495A1E4D +:100F80009DF80A303C48013B1B0443EA0253BDF87C +:100F90000820013A13434B6001F0F2FE0023019355 +:100FA000364B374900934FF48052364B364800F0A9 +:100FB00069FF364B197811B1334800F08DFF00F00E +:100FC000F1FC0546FFF706FC4FF4C873B0FBF3F2E3 +:100FD00002FB130305F516709BB218442C4B1860E6 +:100FE00002F076FA08B10F23238105B0BDE8F08343 +:100FF000731EB3F5806FBFD24FF47A75C0EBC00E8D +:101000000EF103034FEAE30909FB0555C3F3C703D8 +:10101000C11AC9B209F101088844B5FBF8F5B5F564 +:10102000617F08D90EF1FF33C3F3C703C11A581EFD +:101030000F28C9B214D84A1E072A8CBF00220122E9 +:10104000581800FB0660B7FBF0F7BC4594D1002AA6 +:1010500092D0ADF808608DF80A308DF80B108BE750 +:101060001346EDE73411002018110020005125022D +:101070003F420F0010110020A8230020C90A0008D9 +:1010800044110020950B00084C2100204011002045 +:10109000482100202DE9F04F80A7D7E900670FF223 +:1010A0000429D9E90089734D93B00DF1300AFFF797 +:1010B000C7FC18220021504600F070F9DFF8B8B1E3 +:1010C0006E4C002352461946584601F091FE0146E7 +:1010D00050BB102208A800F061F9E36883F0100308 +:1010E000E36000F061FC0DF1240C0B4612A90246EE +:1010F00011E903008CE803009DF83410C1F30300EC +:10110000890649BF0E99BDF83810C1F31C0141F0A2 +:10111000004158BFC1F30A018DF82C000891284600 +:1011200008A901F095F9CCE7284600F0DDFE044659 +:10113000002847D100F036FCDFF844B1DBF800307E +:1011400098423FD300F02EFC0790FFF743FB4FF48B +:10115000C873B0FBF3F101FB1300079A83B202F5E9 +:1011600016701844CBF80000DFF818B18DF8204055 +:101170009BF8001011B901238DF8203050460791DB +:10118000FFF740FB07990DF12100C1F11004E4B213 +:10119000062C28BF06245144224600F0EDF808AB87 +:1011A000039318230293384B013401930123E4B2D3 +:1011B000009332463B462846049400F0DBFE0023B1 +:1011C0008BF8003000F0EEFB304A314C1368C31A44 +:1011D000B3F57A7F30D3106000F0E6FB02460B4691 +:1011E000284600F05FFF284600F07EFE20B3237AF9 +:1011F000DFF8A0B0002B14BF032302238BF80530C7 +:1012000000F0D0FB4FF47A73B0FBF3F00122CBF87F +:1012100000005146584600F0B3F9182302931E4BC4 +:1012200080B2019340F25513CDE903A000934246EA +:101230004B46284600F09EFE237ABBB100F0B2FB7D +:1012400094F8E83073B9D4F8E03043B1C01A236899 +:10125000FA2B38BFFA230533B0EB430F02D300203B +:10126000FFF79EFB237A002B7FF41FAF13B0BDE87E +:10127000F08F00BF4C210020A8230020000801406F +:101280004821002045210020442100207023002017 +:101290007C2100203411002074230020401DA12057 +:1012A00026812A0BF1C6A7C1D068080F70B501F0DE +:1012B0007DFF0024084E094D308028683388834222 +:1012C00008D901F06FFF2B6804440133B4F5C84F0F +:1012D0002B60F2D370BD00BFA42300207823002030 +:1012E00001F0F2BF00F10060920000F5C84001F08B +:1012F00097BF0000054B1A68054B1B889B1A834259 +:1013000002D9104401F04EBF00207047782300201E +:10131000A4230020024B1B68184401F049BF00BF02 +:1013200078230020024B1B68184401F053BF00BF14 +:1013300078230020064991F8243033B10023082295 +:10134000086A81F82430FFF7CDBF0120704700BF45 +:101350007C230020022802BF1022014B1A61704733 +:1013600000080140022802BF4FF48012014B1A61AD +:10137000704700BF00080140002310B5934203D01E +:10138000CC5CC4540133F9E710BD000003460246AB +:10139000D01A12F9011B0029FAD170470346024402 +:1013A000934202D003F8011BFAE770472DE9F84396 +:1013B0001F4D144695F824200746884652BBDFF897 +:1013C00070909CB395F824302BB92022FF21484619 +:1013D0002F62FFF7E3FF95F824004146C0F10802B1 +:1013E000A24228BF224605EB8000D6B29200FFF74A +:1013F000C3FF95F82430A41B1E44F6B2082E1744F0 +:101400009044E4B285F82460DBD1FFF793FF002815 +:10141000D7D108E02B6A03EB82038342CFD0FFF7DA +:1014200089FF0028CBD10020BDE8F8830120FBE72D +:101430007C2300202DE9F0470D460446002190460C +:10144000284640F27912FFF7A9FF23462022002107 +:10145000284600F09FFF022220212846231D00F08D +:1014600099FF032222212846631D00F093FF0322E7 +:1014700025212846A31D00F08DFF10222821284693 +:1014800004F1080300F086FF08223821284604F101 +:10149000100300F07FFF08224021284604F11103C9 +:1014A00000F078FF08224821284604F1120300F0DA +:1014B00071FF20225021284604F1140300F06AFF36 +:1014C00040227021284604F1180300F063FF08222F +:1014D000B021284604F1200300F05CFF0822B82167 +:1014E000284604F1210300F055FFC02604F122072D +:1014F0003B46314608222846083600F04BFFB6F539 +:10150000A07F07F10107F3D108223146284604F1F4 +:10151000320300F03FFF002704F1330A94F8323021 +:101520004FEAC7099F4209F5A47615D3B8F1000F19 +:1015300008D131460722284604F5997300F02AFFA6 +:1015400009F24F16274694F832213B1B93420CD3E5 +:10155000F01DC008BDE8F0870AEB070308223146FA +:10156000284600F017FF0137D8E7314607F233135A +:101570000822284600F00EFF08360137E3E7000096 +:1015800038B50C460021054621600346C4F8031017 +:101590002046202200F0FEFE20462B1D02222021A4 +:1015A00000F0F8FE20466B1D0322222100F0F2FE1F +:1015B0002046AB1D0322252100F0ECFE2046102220 +:1015C000282105F1080300F0E5FE072038BD0000E2 +:1015D0000023F7B50E460546047F07220091194601 +:1015E00000F09AFD731C0093012200230721284676 +:1015F00000F092FDC4B9B31C0093052223460821D4 +:10160000284600F089FD0D243746B278BB1B934273 +:1016100011D32B7FE01DC008AC8ABBB9A04294BF98 +:101620000020012003B0F0BDAB8A0824DB00083B9A +:10163000DB08B370E8E7FB1C214600930822002377 +:10164000284600F069FD08340137DEE7001B18BFAB +:101650000120E7E70023F7B50E46047F082200913A +:101660001946054600F058FD731CC4B908220093C2 +:1016700011462346284600F04FFD102401237278BE +:101680005F1C013B934211D32B7FE01DC008AC8A45 +:10169000BBB9A04294BF0020012003B0F0BDAB8ACB +:1016A0000824DB00083BDB087370E7E7F3192146E9 +:1016B000009308220023284600F02EFD08343B4604 +:1016C000DDE7001B18BF0120E7E70000F8B50E4674 +:1016D00005461446002181223046FFF75FFE2B4667 +:1016E00008220021304600F055FE7CB9072208216F +:1016F00030466B1C00F04EFE0F2401236A785F1CFD +:10170000013B934204D3E01DC008F8BD0824F4E770 +:101710002146EB190822304600F03CFE08343B46D7 +:10172000ECE70000F8B50E46054614460021CE222F +:101730003046FFF733FE2B4628220021304600F0CA +:1017400029FE7CB908222821304605F1080300F063 +:1017500021FE30242F462A7A7B1B934204D3E01DBE +:10176000C008F8BD2824F5E7214607F1090308223F +:10177000304600F00FFE08340137ECE7F7B5047F80 +:101780000E460091012310220021054600F0C4FC02 +:10179000C4B9B31C0093092223461021284600F047 +:1017A000BBFC192437467288BB1B9A4211D82B7F89 +:1017B000E01DC008AC8ABBB9A04294BF0020012044 +:1017C00003B0F0BDAB8A1024DB00103BDB08738054 +:1017D000E8E73B1D2146009308220023284600F03D +:1017E0009BFC08340137DEE7001B18BF0120E7E748 +:1017F00030B5094D0A4491420DD011F8013B5840D3 +:10180000082340F30004013B2C4013F0FF0384EA5B +:101810005000F6D1EFE730BD2083B8ED4FF0FF3335 +:10182000F7B500EB81061946DFF848C0DFF848E05D +:10183000B0421BD050F8042B01AF0192042217F8DC +:10184000014B81EA046108240D46DB184941013C43 +:10185000002DBCBF83EA0C0381EA0E0114F0FF04E3 +:10186000F2D1013A12F0FF02E9D1E1E7D843C943CE +:1018700003B0F0BD9336EAA9EBE1F042F7B56B4651 +:10188000354A106851686A4603C30823334934480F +:1018900002F0D4F8044690BB0A256B46314A106822 +:1018A00051686A4603C308232F492D4802F0C6F841 +:1018B0000446002847D00369B3F5CE3F43D8B0F8BB +:1018C0006620B2F57A7F3ED1284A024402F15C01DB +:1018D0008B4238D35C3B224900209E1AFFF788FFD9 +:1018E00007463246002004F16401FFF781FFA36838 +:1018F0009F4228D1E368984208BF002523E003698E +:10190000B3F5CE3F26D8428BB2F57A7F20D1174A65 +:10191000024402F110018B4218D3103B1049002001 +:101920009D1AFFF765FF06462A46002004F11801BC +:10193000FFF75EFFA3689E4202D1E368984201D0A0 +:101940000D25AAE70025284603B0F0BD1025A4E721 +:101950000C25A2E70B25A0E7AC3A0008DC9B0100B0 +:1019600000640008B53A0008909B0100089CFFF74E +:10197000EFF30983EFF30583014B9B6BFEE700BF99 +:1019800000ED00E008B5FFF7F3FF0000EFF3098377 +:10199000EFF30583014B5B6BFEE700BF00ED00E05A +:1019A000FEE7000001F0F6BC01F0A2BC2DE9F04119 +:1019B000456A15B94162BDE8F0814B68AC4623F039 +:1019C0006047C3F38A4616EA230638BF3E464FEA0D +:1019D000D37EC3F380782B465A68BEEBD27F22F0C9 +:1019E00060440AD0002A18DAA40CB44217D19D42F0 +:1019F0000FD10D60DEE71346EEE7A74207D102F0F4 +:101A00008044C2F3807242450BD054B1EFE708D254 +:101A1000EDE7CCF800100B60CDE7B44201D0B44242 +:101A2000E5D81A689C46002AE5D11960C3E7000092 +:101A30002DE9F0474FF47F49089D01F007044FEA74 +:101A4000D508224405F0070500EBD100944201D1EE +:101A5000BDE8F08704F0070705F0070A57453E4642 +:101A600038BF5646111BC6F108068E4228BF0E46E7 +:101A7000E108415C08EBD50E13F80EC0B94029FA15 +:101A800006F721FA0AF1FFB28CEA010147FA0AF7D8 +:101A900039408CEA010C03F80EC034443544D5E7D4 +:101AA000082341F2210280EA012001B2400000290E +:101AB00080B203F1FF33B8BF504013F0FF03F4D1FD +:101AC0007047000038B50C468D18A54200D138BDCE +:101AD00014F8011BFFF7E4FFF7E700000346406836 +:101AE00048B1026899895A605A89013292B291428A +:101AF0005A8138BF9A81704770B504460D4688B048 +:101B0000202200216846FFF749FC20460495FFF794 +:101B1000E5FF024658B16B46054608AE1C4603CCAD +:101B2000B44228606960234605F10805F6D11046E5 +:101B300008B070BD082817D909280CD00A280CD085 +:101B40000B280CD00C280CD00D280CD00E2814BF5C +:101B50004020302070470C20704710207047142020 +:101B6000704718207047202070470000082817D9B8 +:101B70000C280CD910280CD914280CD918280CD9E9 +:101B800020280CD930288CBF0F200E207047092048 +:101B900070470A2070470B2070470C2070470D20BB +:101BA000704700002DE9F843078C0446072F1ED923 +:101BB000D0E9029800254FF6FF73C5F12006A5F184 +:101BC000200029FA05F108FA06F628FA00F0314358 +:101BD0000143C9B21846FFF763FF0835402D03469D +:101BE000EBD13A46E169BDE8F843FFF76BBF4FF62A +:101BF000FF70BDE8F883000010B54B6823B9CA8AAE +:101C000063F30902CA8210BD04691A681C6003618B +:101C1000C38A013BC3824A60EFE700002DE9F84F19 +:101C20001D46CB8A0F46C3F309010529814692461A +:101C30000B4630D00020AAB207F11A049EB2042E3F +:101C40001FFA80F80FD8904503F1010306D3FB8AF1 +:101C50000A4462F309030120FB821AE01AF80060CB +:101C60000130E654EAE79045F1D21C23A1F1050BBF +:101C7000BBFBF3F203FB12BB7C681FFA8BF6002C54 +:101C800045D14846FFF72AFF044638B978606FF01F +:101C90000200BDE8F88F4FF00008E6E70026066076 +:101CA00078604FF0000BADB2454510D90AEB080340 +:101CB000221D13F8011B08F101089155B1B21B292F +:101CC0001FFA88F82BD0454506F10106F1D8FB8AAA +:101CD000C3F30902154465F30903BCE71C4601324E +:101CE00092B22368002BF9D16B1F0B441C21B3FB6C +:101CF000F1F301339BB29A42D3D2BBF1000FD0D1A2 +:101D00004846FFF7EBFE20B9C4F800B0BFE7012258 +:101D1000E7E7C0F800B05E4620600446C1E74545ED +:101D2000D5D94846FFF7DAFE08B92060AFE7C0F81A +:101D300000B0002620600446B6E700002DE9F74F0A +:101D40001C465B69074688460092002B00F097808E +:101D5000238C2BB1E269002A00F09180072B33D845 +:101D600007F10C00FFF7BAFE054628B96FF002052F +:101D7000284603B0BDE8F08F14220021FFF70EFBC8 +:101D8000228CE16905F10800FFF7F6FA208C48F093 +:101D90000041013080B2FFF7E9FEFFF7CBFE0138CA +:101DA00080B22084013028746369228C1B782A4415 +:101DB00003F01F0363F03F0313723846696029463E +:101DC000FFF7F4FD0125D3E74FF000094FF0800A3B +:101DD0004E464D4600F10C0301930198FFF77EFE3D +:101DE00083460028C2D014220021FFF7D7FA002E24 +:101DF0003BD10222009BABF808300BF1080E1FFA12 +:101E000082FC0CF10100BCF1060F218C80B201D8DC +:101E10008E422CD3FFF7AAFEFFF78CFE8E4208BF3E +:101E20004FF0400A62690138127880B202F01F0256 +:101E300042EA49120BEB00014AEA020A013048F07B +:101E4000004281F808A08BF8100059463846CBF8BC +:101E50000420FFF7ABFD238C0135B3424FF0000A9D +:101E60002DB289F00109B8D182E70022C5E7E16906 +:101E7000895D01360EF80210B6B20132BFE76FF08D +:101E8000010575E7F8B5044615460E4630220021D7 +:101E90001F46FFF783FA069BB5F5001F6360079B9B +:101EA00028BF4FF6FF72A3624FF0000338BF6A09E4 +:101EB000A760E66197B204F110009A4206D80023A9 +:101EC0000360A782E3822383E360F8BD06600133E9 +:101ED00030462036F1E7000003781BB94BB2002BE7 +:101EE000C8BF01707047000000787047F8B50C4615 +:101EF000C969074611B9238C002B37D1257E1F2DC8 +:101F000034D8387828BB228C072A2CD8268A36F079 +:101F100003032BD14FF6FF70FFF7D4FD4FF6FF728E +:101F200020F001003602400446EA0565400C45EA0F +:101F30004025234629463846FFF700FF002807DDE5 +:101F4000626913780133DBB21F2B88BF0023137043 +:101F5000F8BD218A2D0645EA012505432046FFF7F5 +:101F600021FE0246E5E76FF00300F1E76FF00100A4 +:101F7000EEE7000070B504461D4616468AB02822DA +:101F800000216846FFF70AFABDF838306946ADF817 +:101F900010300F9B204605939DF84030CDE9026537 +:101FA0008DF81830119B0793BDF84830ADF82030FC +:101FB000FFF79CFF0AB070BD2DE9F041D3690546DB +:101FC0000C4616460BB9138C5BBB377E1F2F28D8E7 +:101FD00095F80080B8F1000F26D03046FFF7E2FDFB +:101FE0003378210241EAC33141EA0801338A41EAE8 +:101FF000076141EA034102463346284641F0800129 +:10200000FFF79CFE00280ADD3378012B07D17269A7 +:1020100013780133DBB21F2B88BF00231370BDE898 +:10202000F0816FF00100FAE76FF00300F7E70000BE +:10203000F0B504460D461E4617468BB028220021F7 +:102040006846FFF7ABF99DF84C3029465A1E5342BB +:1020500053418DF800309DF840306A46ADF810309D +:10206000119B204605939DF84830CDE902768DF806 +:102070001830149B0793BDF85430ADF82030FFF7AB +:102080009BFF0BB0F0BD0000406A00B10430704708 +:10209000436A1A68426202691A600361C38A013B9B +:1020A000C38270472DE9F041D0F8208014461D46C8 +:1020B00041460027174E09B9BDE8F081D1E9022356 +:1020C000A21A65EB0303964277EB03031ED2036A61 +:1020D0008B420DD1FFF790FD036A1B680362036911 +:1020E0000B60C38A0161016A013B8846C382E2E753 +:1020F000FFF782FD0B68C8F8003003690B60C38AE4 +:102100000161013BC382D8F80010D4E78846096812 +:10211000D1E700BF80841E002DE9F04F8BB00D4643 +:1021200014469B468046DDF85090002800F01A8146 +:10213000B9F1000F00F01681531E3F2B00F21281FF +:10214000012A03D1BBF1000F40F00C810023CDE93F +:102150000833B8F81430B5EBC30F4FEAC30703D305 +:1021600000200BB0BDE8F08F2B199F42D8F80C303F +:1021700036BF7F1B2746FFB21BB9D8F81030002BA3 +:102180007BD0272D4ED8C5F12806B7424FF000036B +:1021900034BF3E46F6B2009329463246D8F80800CE +:1021A00008ABFFF745FCA7EB060A35445FFA8AFA4D +:1021B0002821B8F8143003F10053053BDB000493E9 +:1021C000D8F80C300393039B13B1BAF1000F2CD154 +:1021D000D8F8100040B1BAF1000F05D05246009671 +:1021E00008AB691AFFF724FC38B2002FB8D0660795 +:1021F0000AD00AAB03EBD40111F8083C624202F0AA +:102200000702134101F8083C082C3DD9102C40F27C +:10221000B680202C40F2B880BBF1000F00F09D800A +:10222000082335E0BA460026C2E7049BE02B28BF0E +:10223000E02306930B44AB42059315D95A1B9245F4 +:1022400038BF5246039828BFD2B20096691A08AB2D +:1022500004300792FFF7ECFB079A1644AAEB020A38 +:102260001544F6B25FFA8AFA049B069A05999B1AFE +:102270000493039B1B680393A5E700933A46294602 +:10228000D8F8080008ABADE7BBF1000F13D001236D +:10229000B4EBC30F6CD0082C12D89DF82030621E0E +:1022A00023FA02F2D50706D54FF0FF3202FA04F402 +:1022B00023438DF820309DF8203089F8003050E716 +:1022C000102C12D8BDF82030621E23FA02F2D1077A +:1022D00006D54FF0FF3202FA04F42343ADF8203064 +:1022E000BDF82030A9F800303BE7202C0FD8089922 +:1022F000631E21FA03F3DA0705D54FF0FF3202FA25 +:1023000004F40C430894089BC9F8003029E7402CDA +:102310002BD0DDE90865611EC4F12102A4F121037F +:1023200026FA01F105FA02F225FA03F311431943E3 +:10233000CB0712D50122A4F12003C4F1200102FA37 +:1023400003F322FA01F1A240524243EA010363EB94 +:10235000430332432B43CDE90823DDE90823C9E9D0 +:102360000023FEE66FF00100FBE66FF00800F8E6E0 +:10237000082CA0D9102CB3D9202CEED8C3E7BBF180 +:10238000000FADD0022383E7BBF1000FBBD00423C5 +:102390007EE70000012A30B5144638BF012200252F +:1023A000402A28BF402285B0012CCDE9025517D81C +:1023B0001B788DF8083053070AD004AB03EBD20525 +:1023C00015F8083C544204F00704A34005F8083C03 +:1023D0000346009102A80021FFF72AFB05B030BD9B +:1023E000082CE5D9102C03D81B88ADF80830E2E79B +:1023F000202C02D81B680293DDE7D3E90045CDE924 +:102400000245D8E710B5CB681BB98B600B618B8296 +:1024100010BD04691A681C600361C38A013BC38252 +:10242000CA60F0E703064CBFC0F3C030022070471B +:1024300008B50246FFF7F6FF022806D15306C2F39D +:102440000F2001D100F0030008BDC2F30740FBE7F5 +:102450002DE9F04F93B0CDE903230A6804461046F6 +:10246000FFF7E0FF02280CBF0026C2F30626002A71 +:102470000D46824680F2F98112F0C04940F0F581A4 +:10248000097B002900F0F181022803D02378B342B0 +:1024900040F0EE81C2F304631046069302F07F031E +:1024A0000593FFF7C5FF059B00224FEA83480023F1 +:1024B00048EA0A48294448EA4668CE78CDE9082324 +:1024C000F309834648EA0008029367D0059B024659 +:1024D000009320465346676808A9B847002800F0D3 +:1024E000CA81276A4FB9414604F10C00FFF704FB8B +:1024F000074690B96FF0020054E03B6998450DD053 +:102500003F68002FF9D1414604F10C00FFF7F4FABF +:1025100007460028EED0236A3B60276297F817C071 +:1025200006F01F08CCF3840CACEB08001FFA80FE09 +:102530000028B8BF0EF12000A8EB0C031FFA83FEA1 +:10254000B8BF00B2002B0793BEBF0EF120031BB231 +:102550000793D7E9022152EA010338D04FF0000C6B +:10256000039BDFF8F8E19A1A049B63EB010196459F +:102570007CEB01032BD36B7B97F81AE0734519D1E1 +:10258000029B002B78D0012821DC7868F8B9DFF8AD +:10259000D0C1944570EB010316D337E0276A27B901 +:1025A0006FF00C0013B0BDE8F08F3B699845B5D0D3 +:1025B0003F68F4E76A4890427CEB010301D30020B6 +:1025C000F0E7029B002BFAD0079B0F2B17DCFA7D5C +:1025D000B30002F0030203F07C031343FB7539469A +:1025E0002046FFF709FB6B7BBB76029B3BB9FB7D6B +:1025F000C3F38402013262F38603FB75D0E76A7B82 +:10260000BB7E9A42DBD1029B002B35D0B309022B53 +:1026100032D0039B1422BB60049B0021FB600DA8F9 +:10262000FEF7BCFE039B20460A93049BADF83EB028 +:102630000B932B1D0C932B7B8DF840A0013BDBB241 +:10264000ADF83C30069B8DF841808DF84230059BFB +:102650000AA98DF8433094F82C3083F001038DF8EB +:102660004430A3689847FB7DC3F38403013303F030 +:102670001F039B02FB82A2E7FB7DC6F34012B2EB75 +:10268000D31F40F0FB80C3F38403434540F0F9803F +:10269000029A2B7BB609002A4DD0F20762D4032B95 +:1026A00040F2F280039BAE1DBB60049B3246FB6090 +:1026B0002B7B3946033BDBB204F10C00FFF7AEFA8B +:1026C00000280CDA39462046FFF796FAFB7DC3F363 +:1026D0008403013303F01F039B02FB820AE7AB88EC +:1026E000DDE908843B834FF6FF73C9F12000A9F1AF +:1026F000200228FA09F104FA00F0014324FA02F258 +:1027000011431846C9B2FFF7CBF909F10809B9F12D +:10271000400F0346E9D13146B8822A7B033AD2B250 +:10272000FFF7D0F9FB7DB882DA43C2F3C01262F33F +:10273000C713FB7543E7AEB92E1D013B3246394640 +:10274000DBB204F10C00FFF769FA0028BADB2A7B40 +:102750003146013AB88AD2B2E2E700BF80841E0057 +:1027600040420F00F98A013BC1F309010429DAB2A2 +:102770005DD80023281D07F11B069A4208D910F8DE +:1027800001CB013306F801C001310529DBB2F4D1D8 +:10279000934228BF0023039938BF04330A91049958 +:1027A00038BFDBB20B9107F11B010C91796838BF80 +:1027B0005B190D910E93FB8AADF83EB0C3F309038C +:1027C0001A44069BADF83C208DF84230059B8DF8ED +:1027D00040A08DF8433094F82C308DF8418083F080 +:1027E00001038DF8443000237B602A7BB88A013ACC +:1027F000291DFFF767F93B8BB882834203D120463E +:10280000A3680AA9984720460AA9FFF7FBFDFB7DAC +:10281000BA8AC3F38403013303F01F039B02FB82D4 +:102820003B8B9A420CBF00206FF01000BAE67B6829 +:10283000002BADD0052001E033461C301E68002E71 +:10284000FAD1091A081D2E1D184401EB090CBCF120 +:102850001B0F5FFA89F39BD89A4299D916F8013B6E +:1028600009F1010900F8013BEFE76FF0090099E673 +:102870006FF00A0096E66FF00B0093E66FF00D0024 +:1028800090E66FF00E008DE66FF00F008AE600BF55 +:10289000F0B53F4D3F4FEB6943F00073EB61EB69DF +:1028A0003D4B9B6AD3F800623E4046F00106C3F8F8 +:1028B0000062D3F800423C4044EA002444F00104A2 +:1028C000C3F80042002955D000200646C3F81C0278 +:1028D000C3F80402C3F80C02C3F8140203EBC004EB +:1028E00001300E28C4F84062C4F84462F6D10027D3 +:1028F0004FF0010C9678148816F0010F18BFD3F82A +:1029000004E20CFA04F01CBF40EA0E0EC3F804E225 +:1029100016F0020F18BFD3F80CE203EBC4041CBF7F +:1029200040EA0E0EC3F80CE2760748BFD3F81462F3 +:1029300007F1010744BF0643C3F814625668B94261 +:10294000C4F84062966802F10C02C4F84462D3F8FD +:102950001C4240EA0400C3F81C02CBD1D3F8002289 +:1029600022F00102C3F80022EB6923F00073EB614F +:10297000EB69F0BD0122C3F84012C3F84412C3F85A +:102980000412C3F81412C3F80C22C3F81C22E5E7A2 +:10299000001002400000FFFFA8230020184A08B5DD +:1029A000916A8B688B6013F0010104D013F00C0F57 +:1029B00018BF4FF48031D80506D513F4406F14BF0B +:1029C00041F4003141F00201D80306D513F4402F41 +:1029D00014BF41F4802141F00401D3690BB10848D0 +:1029E0009847302383F311880021064800F022FB2A +:1029F000002383F31188BDE8084000F0ABBD00BFA1 +:102A0000A8230020B023002038B5124CA36ADD684B +:102A1000AA0712D05A6922F002025A61A36913B1BF +:102A2000012120469847302383F3118800210A486A +:102A300000F000FB002383F31188EB0606D510217C +:102A4000A36AD960236A0BB102489847BDE83840B1 +:102A500000F080BDA8230020B823002038B5124C18 +:102A6000A36A1D69AA0712D05A6922F010025A619E +:102A7000A36913B1022120469847302383F31188BC +:102A800000210A4800F0D6FA002383F31188EB06F0 +:102A900006D51021A36A1961236A0BB10248984731 +:102AA000BDE8384000F056BDA8230020B823002020 +:102AB00038B50F4CA36A5D682A075D600AD5042209 +:102AC00022701A6822F002021A60636A13B10021B0 +:102AD000204698476B0706D5A36A9969236A13B104 +:102AE000034809049847BDE8384000F033BD00BFF3 +:102AF000A823002010B50E4C204600F02FF90D4BF6 +:102B00000B211320A36200F009F90B21142000F01F +:102B100005F90B21152000F001F90B21162000F01A +:102B2000FDF8BDE8104000220E201146FFF7B0BEB0 +:102B3000A8230020006400400F4B10B598420446C3 +:102B400005D10E4BDA6942F00072DA61DB690122CD +:102B5000A36A1A60A36A5A68D20707D562685168E7 +:102B60001268D9611A60064A5A6110BD0121082015 +:102B700000F0B0F9EEE700BFA823002000100240EB +:102B80005B87010003291AD8DFE801F0020A0F145D +:102B9000836A9B6813F0E05F14BF01200020704738 +:102BA000836A9868C0F380607047836A9868C0F34E +:102BB000C0607047836A9868C0F300707047002057 +:102BC0007047000010B5032927D8DFE801F002277D +:102BD0002B2F836A9968C1F30161183103EB01134C +:102BE0001078840648BF5468C0F3001158BF948819 +:102BF0004FEA410148BF41EAC40100F00F005860AC +:102C000048BF41F00401906858BF41EA4451D2687E +:102C100041F001019860DA60196010BD836A03F524 +:102C2000C073DDE7836A03F5C873D9E7836A03F5E8 +:102C3000D073D5E701290AD002290FD081B9836A60 +:102C4000DA68920701D1186903E001207047836AAE +:102C5000D86810F0030018BF01207047836AF2E7BC +:102C60000020704710B539B9836AD96889071BD12C +:102C70001B699C0704D110BD012915D00229FAD186 +:102C8000816AD1F8C031D1F8C441D1F8C8011061CE +:102C9000D1F8CC015061202008610869800717D164 +:102CA000486940F0100012E0816AD1F8B031D1F8E3 +:102CB000B441D1F8B8011061D1F8BC0150612020B5 +:102CC000C860C868800703D1486940F002004861C5 +:102CD000C3F34000C3F38001000140EA41111079C1 +:102CE00020F030000143117189064BBF91681189B2 +:102CF000DB085B0D4CBF63F31C0163F30A0113791E +:102D000048BF916064F3030313714FEA14234FEA41 +:102D1000144458BF118113705480ACE7012209019B +:102D200000F1604303F56143C9B283F8001300F07A +:102D30001F039A4043099B0003F1604303F561437D +:102D4000C3F880211A607047090100F16040C9B2E0 +:102D500000F56D4001767047FFF7CCBE012303708C +:102D6000002300F10802C0E9022200F11002C0E9CC +:102D70000422C0E90633C0E908334360704700000D +:102D800010B53023044683F3118802234160037099 +:102D9000FFF7D2FE04230020237080F3118810BDBA +:102DA0002DE9F0411F4604460D461646302383F3B5 +:102DB000118800F108082378052B0DD029462046FC +:102DC000FFF7E0FE40B1204632462946FFF7FAFE03 +:102DD000002080F3118808E03946404600F01AF9D7 +:102DE0000028E8D0002383F31188BDE8F0810000BB +:102DF0002DE9F0411F4604460D461646302383F365 +:102E0000118800F110082378052B0DD029462046A3 +:102E1000FFF710FF40B1204632462946FFF722FF58 +:102E2000002080F3118808E03946404600F0F2F8AF +:102E30000028E8D0002383F31188BDE8F08100006A +:102E400000238268037503691B6899689142FBD26D +:102E50005A680360426010605860704700238268BF +:102E6000037503691B6899689142FBD85A6803602F +:102E7000426010605860704708B50846302383F3FD +:102E800011880B7D032B05D0042B0DD02BB983F3B8 +:102E9000118808BD00228B691A604FF0FF338361EF +:102EA000FFF7CEFF0023F2E7D1E9003213605A604A +:102EB000F3E70000FFF7C4BF054BD9680875186831 +:102EC000026853601A6001220275D860FDF79ABB50 +:102ED000D823002030B50C4B0446DD684B1C87B06E +:102EE0000FD02B466846094A00F0CAF82046FFF783 +:102EF000E3FF009B13B1684600F0CAF8A86907B069 +:102F000030BDFFF7D9FFF9E7D8230020792E00085C +:102F1000044B1A68DB6890689B68984294BF002055 +:102F200001207047D8230020084B10B51C68D868D2 +:102F3000226853601A6001222275DC60FFF78EFF61 +:102F400001462046BDE81040FDF75CBBD8230020B9 +:102F500038B501230025064C0649074823706560F3 +:102F600000F03EFB0223237085F3118838BD00BFBB +:102F700030250020C43A0008D823002000F09AB879 +:102F80008B60022308618B82084670478368A3F137 +:102F9000440243F8142C026943F8442C426943F874 +:102FA000402C094A43F8242CC268A3F1200043F8BE +:102FB000182C022203F80C2C002203F80B2C034AD5 +:102FC00043F8102C704700BF15060008D8230020D6 +:102FD00008B5FFF7DBFFBDE80840FFF76BBF000057 +:102FE000024BDB6898610F20FFF766BFD8230020F3 +:102FF000302383F31188FFF7F3BF000008B50146C3 +:10300000302383F311880820FFF764FF002383F344 +:10301000118808BD064BDB6839B1426818605A60F8 +:10302000136043600420FFF755BF4FF0FF30704737 +:10303000D823002038B504460D462068844200D1CC +:1030400038BD036823605C608561FFF733FFF4E7F8 +:1030500010B50A4C23699A6891420CD85A6881606D +:103060000360426010609A685860511A99604FF08E +:10307000FF33A36110BD1B68891AECE7D823002039 +:10308000C0E90323002310B410BC4361FFF7E0BF85 +:10309000036881689A680A449A60426813605A60BB +:1030A00000234FF0FF320360014B9A61704700BF6D +:1030B000D823002070B5124D2A46EB690133EB612D +:1030C00052F8103F934206D030269A68013A9A602F +:1030D0002C69A36803B170BDD4E900210A60516076 +:1030E000236083F311882046D4E90331984786F39F +:1030F000118861690029EBD02046FFF7A9FFE7E7B7 +:10310000D8230020054A30B5D369D2E908451B1BF6 +:10311000181945F10001C2E9080130BDD82300208B +:1031200000207047FEE70000704700004FF0FF30BE +:1031300070470000BFF34F8F024AD368DB07FCD40F +:10314000704700BF0020024008B5074B1B7853B9F9 +:10315000FFF7F0FF054B1A69120641BF044A5A6097 +:1031600002F188325A6008BD482500200020024044 +:103170002301674508B5054B1B7833B9FFF7DAFF24 +:10318000034A136943F08003136108BD48250020FA +:10319000002002407F289ABF00F500308002002006 +:1031A000704700004FF48060704700008020704737 +:1031B0007F2808B50BD8FFF7EDFF00F580630268A4 +:1031C000013204D104308342F9D1012008BD00202E +:1031D000FCE700007F2810B504461CD8FFF7AAFFC3 +:1031E000FFF7B2FFF3220D4B4FF48061DA60022249 +:1031F0001A61FFF7CFFF58611A6942F040021A6165 +:10320000FFF798FF00F02EF9FFF7B4FF2046BDE866 +:103210001040FFF7CDBF002010BD00BF00200240CE +:103220002DE9F843054612F00100144606D040F29D +:10323000033200201E4B1A60BDE8F8831D4BAA180C +:103240009A4204D94FF44272194B1A60F4E7FFF71F +:103250007BFF4FF00109FFF76DFFDFF85C806D1A0F +:10326000012C0F4605EB010603D8FFF783FF012071 +:10327000E2E73B88C8F8109033800020FFF75AFF40 +:10328000C8F81000338831F8022B9BB29A420CD058 +:1032900040F21F32064B1A60084B1E60084B1C6040 +:1032A000084B1F60FFF766FFC6E7023CD8E700BF88 +:1032B000442500200000020800200240382500209C +:1032C000402500203C250020084908B50B7828B18E +:1032D0001BB9FFF739FF01230B7008BD002BFCD091 +:1032E000BDE808400870FFF745BF00BF4825002033 +:1032F00038B5EFF31185BDBBEFF30584C4F30804C3 +:103300003023C4B183F31188FFF7FCFE44014B0165 +:10331000241A43EAD06363EB0103A2009B00121856 +:1033200043EA947341EB0301C900D00041EA5271B2 +:1033300085F3118838BD83F31188FFF7E3FE45015B +:103340004B012D1A43EAD06363EB0103AA009B00F3 +:10335000121843EA957341EB0301C900D00041EA1A +:10336000527184F3118838BDFFF7CCFE44014B0144 +:10337000241A43EAD06363EB0103A2009B001218F6 +:1033800043EA947341EB0301C900D00041EA527152 +:1033900038BD00BF38B5FFF7ABFF00230F4A104C14 +:1033A000C00840EA4170A0FB025EC908A0FB040C03 +:1033B000A1FB0440A1FB02121CEB050C5B411CEBC2 +:1033C000040C43EB000011EB0E0142F10002411826 +:1033D00042F10000090941EA007038BDA59BC420F4 +:1033E000CFF753E310B5094C013AD2B2FF2A00D10E +:1033F00010BD500854F82030013054F820009BB222 +:1034000043EA004341F8043BEEE700BF046C004090 +:1034100010B50748013AD2B2FF2A00D110BD0C887E +:10342000530840F823404C88013340F82340F1E72B +:10343000046C004007B50122002001A9FFF7D2FF6C +:10344000019803B05DF804FB13B50446FFF7F2FFE3 +:10345000A04205D00122002001A90194FFF7D8FF66 +:1034600002B010BD7047000045F25552064B1A607D +:1034700002225A6040F6FF729A604CF6CC421A6003 +:103480000122024B1A707047003000405025002086 +:10349000034B1B781BB14AF6AA22024B1A607047F5 +:1034A0005025002000300040044B1A682AB902F170 +:1034B000804202F50432526A1A6070474C2500209F +:1034C0004FF08072014B5A62704700BF00100240FB +:1034D00008B5FFF7E9FF024B1868C0F3407008BD5C +:1034E0004C25002008B5FFF7DFFF024B1868C0F33A +:1034F000007008BD4C250020EFF30983203383F3CF +:103500000988002383F3118870470000302080F37E +:10351000118862B60C4B0D4AD96821F4E0610904A8 +:10352000090C0A43DA60D3F8FC20094942F08072A2 +:10353000C3F8FC200A6842F001020A602022DA7710 +:1035400083F82200704700BF00ED00E00003FA0599 +:10355000001000E0302310B583F311880B4B5B683B +:1035600013F400630FD0EFF309844FF08073203C15 +:10357000E36184F30988FFF7CBFC10B1044BA3612E +:1035800010BD044BFBE783F31188F9E700ED00E081 +:10359000270600082A06000870470000FEE7000022 +:1035A0000A4B0B480B4A90420BD30B4BC11EDA1C43 +:1035B000121A22F003028B4238BF00220021FDF7CD +:1035C000EDBE53F8041B40F8041BECE73C3B00083D +:1035D000D4250020D4250020D4250020FEE70000BB +:1035E00070B5002504461A4B86B0586085620163A9 +:1035F0000E46FFF78BFF04F11003C4E904334FF0CC +:10360000FF33A361134BE561D9692B460A46204677 +:10361000C4E9082304F134018023C4E900440E4ABC +:10362000A560E5622565FFF7ABFC01230B4AE0606E +:1036300003750092726868460192B268CDE9022370 +:10364000074BCDE90435FFF7C3FC06B070BD00BFE2 +:1036500030250020D8230020D03A0008D53A0008B1 +:10366000DD35000800F030B808B500F063F9FFF769 +:103670006FFCBDE80840FFF717BF0000704700006F +:103680004FF0FF310E4B1A6919611A6900221A6155 +:103690001869D868D960D968DA60DA68DA6942F0FE +:1036A0008052DA61DA69DA6942F00062DA61054A69 +:1036B000DB69136843F48073136000F01BB900BF2B +:1036C0000010024000700040194B1A6842F00102DD +:1036D0001A601A689007FCD51A6802F0F9021A609D +:1036E00000225A605A6812F00C0FFBD11A6842F49B +:1036F00080321A601A689103FCD55A6842F4E812C5 +:103700005A601A6842F080721A601A689201FCD5F9 +:103710001221084A5A60084A11605A6842F00202AF +:103720005A605A6802F00C02082AFAD1704700BFAA +:103730000010024000641D0000200240084A08B545 +:10374000516913680B4003F00103536123B1054A2B +:1037500013680BB150689847BDE80840FFF7FABE00 +:103760000004014054250020084A08B55169136837 +:103770000B4003F00203536123B1054A93680BB178 +:10378000D0689847BDE80840FFF7E4BE0004014058 +:1037900054250020084A08B5516913680B4003F00E +:1037A0000403536123B1054A13690BB1506998476B +:1037B000BDE80840FFF7CEBE0004014054250020BC +:1037C000084A08B5516913680B4003F008035361B8 +:1037D00023B1054A93690BB1D0699847BDE8084009 +:1037E000FFF7B8BE0004014054250020084A08B580 +:1037F000516913680B4003F01003536123B1054A6C +:10380000136A0BB1506A9847BDE80840FFF7A2BEA3 +:103810000004014054250020174B10B55A691C685C +:10382000144004F478725A61A30604D5134A936ACB +:103830000BB1D06A9847600604D5104A136B0BB1E0 +:10384000506B9847210604D50C4A936B0BB1D06B93 +:103850009847E20504D5094A136C0BB1506C9847A0 +:10386000A30504D5054A936C0BB1D06C9847BDE80D +:103870001040FFF76FBE00BF000401405425002038 +:103880001A4B10B55A691C68144004F47C425A6102 +:10389000620504D5164A136D0BB1506D9847230588 +:1038A00004D5134A936D0BB1D06D9847E00404D54D +:1038B0000F4A136E0BB1506E9847A10404D50C4A01 +:1038C000936E0BB1D06E9847620404D5084A136F0B +:1038D0000BB1506F9847230404D5054A936F0BB181 +:1038E000D06F9847BDE81040FFF734BE0004014098 +:1038F00054250020062108B50846FFF70FFA0621D7 +:103900000720FFF70BFA06210820FFF707FA062128 +:103910000920FFF703FA06210A20FFF7FFF9062125 +:103920001720FFF7FBF9BDE8084006212820FFF724 +:10393000F5B9000008B5FFF7A3FE054800F00CF844 +:10394000FFF70AFAFFF79AFEBDE8084000F002B858 +:10395000DC3A000800F042B8002319461C4A013343 +:10396000102BC2E9001102F10802F8D1194B9A6933 +:1039700042F07D029A619B690268174BDA608268A7 +:103980005A6042681A60C26803F58063DA6042696F +:103990005A6002691A608269C3F80C24026AC3F88B +:1039A0000424C269C3F80024426AC3F80C28C26A1E +:1039B000C3F80428826AC3F80028026BC3F80C2CF1 +:1039C000826BC3F8042C426BC3F8002C704700BF15 +:1039D0005425002000100240000801404FF0E02371 +:1039E000044A08215A6100229A6107220B201A61B9 +:1039F000FFF7AAB93F19010008B5302383F31188F6 +:103A0000FFF7BCFA002383F3118808BD08B5FFF760 +:103A1000F3FFBDE80840FFF79DBD000010B5013978 +:103A20000244904201D1002005E0037811F8014FD3 +:103A3000A34201D0181B10BD0130F2E72DE9F0417F +:103A40009BB10446C91A1778014403F1FF3C8C422C +:103A5000204601D9002008E005780134BD42F6D1A6 +:103A60000CEB0405D618A54201D1BDE8F08115F88C +:103A7000018D16F801EDF045F5D0E8E7034611F8A1 +:103A8000012B03F8012B002AF9D170476F72672EC2 +:103A90006172647570696C6F742E663130332D51AC +:103AA000696F74656B5065726970680040A2E4F1DB +:103AB000646891060041A3E5F26569920700000081 +:103AC00063300000C03A0008302400203025002078 +:103AD0006D61696E0069646C65000000001800008B +:103AE0004444414444544944010000004244444495 +:103AF0004444444400000000444444444444444496 +:103B00000000000044444444444444440000000095 +:103B10004444444444444444E8030000000000009A +:103B2000009C010000000000640000000000000094 +:0C3B300040420F00FE2A0100D2040000F9 :00000001FF diff --git a/Tools/bootloaders/f103-RangeFinder_bl.bin b/Tools/bootloaders/f103-RangeFinder_bl.bin index bc59ee7adab86c..3e4607027cd1b1 100755 Binary files a/Tools/bootloaders/f103-RangeFinder_bl.bin and b/Tools/bootloaders/f103-RangeFinder_bl.bin differ diff --git a/Tools/bootloaders/f103-RangeFinder_bl.elf b/Tools/bootloaders/f103-RangeFinder_bl.elf index 4f85de7a629ca5..ea56a0cb072fb7 100755 Binary files a/Tools/bootloaders/f103-RangeFinder_bl.elf and b/Tools/bootloaders/f103-RangeFinder_bl.elf differ diff --git a/Tools/bootloaders/f103-RangeFinder_bl.hex b/Tools/bootloaders/f103-RangeFinder_bl.hex index d9010ef8e65a7a..941d652c2c0a31 100644 --- a/Tools/bootloaders/f103-RangeFinder_bl.hex +++ b/Tools/bootloaders/f103-RangeFinder_bl.hex @@ -1,26 +1,26 @@ :020000040800F2 -:10000000000900202D080008B11C0008811C000810 -:100010009D1C0008811C0008951C00082F08000882 -:100020002F0800082F0800082F080008E5370008EF -:100030002F0800082F0800082F080008F93C0008C6 -:100040002F0800082F0800082F0800082F080008B4 -:100050002F0800082F080008293A0008553A000820 -:10006000813A0008AD3A0008D93A00082F08000884 -:100070002F0800082F0800082F0800082F08000884 -:100080002F0800082F0800082F080008AD2C0008D2 -:10009000192D00086D2D0008C12D0008053B000832 -:1000A0002F0800082F0800082F0800082F08000854 -:1000B0002F0800082F0800082F0800082F08000844 -:1000C0002F0800082F0800082F0800082F08000834 -:1000D0002F0800082F0800082F0800082F08000824 -:1000E0006D3B00082F0800082F0800082F080008A3 -:1000F0002F0800082F0800082F0800082F08000804 -:100100002F0800082F0800082F0800082F080008F3 -:100110002F0800082F0800082F0800082F080008E3 -:100120002F0800082F0800082F0800082F080008D3 -:100130002F0800082F0800082F0800082F080008C3 -:100140002F0800082F0800082F0800082F080008B3 -:100150002F0800082F0800082F0800082F080008A3 +:100000000009002025050008A11900087119000841 +:100010008D190008711900088519000827050008C6 +:10002000270500082705000827050008F9340008FF +:100030002705000827050008270500080D3A0008D5 +:1000400027050008270500082705000827050008E0 +:1000500027050008270500083D3700086937000814 +:1000600095370008C1370008ED370008270500085C +:1000700027050008270500082705000827050008B0 +:100080002705000827050008270500089D29000806 +:10009000092A00085D2A0008B12A0008193800085A +:1000A0002705000827050008270500082705000880 +:1000B0002705000827050008270500082705000870 +:1000C0002705000827050008270500082705000860 +:1000D0002705000827050008270500082705000850 +:1000E00081380008270500082705000827050008B3 +:1000F0002705000827050008270500082705000830 +:10010000270500082705000827050008270500081F +:10011000270500082705000827050008270500080F +:1001200027050008270500082705000827050008FF +:1001300027050008270500082705000827050008EF +:1001400027050008270500082705000827050008DF +:1001500027050008270500082705000827050008CF :100160004FF0FF0C1CEAD0521EBF1CEAD15392EA9A :100170000C0F93EA0C0F6FD01A4480EA010C400276 :1001800018BF5FEA41211ED04FF0006343EA5010D0 @@ -81,918 +81,870 @@ :1004F0009E03B3EB126209D44FEA002343F000439A :1005000023FA02F070474FF00000704712F1610FBC :1005100001D1420202D14FF0FF3070474FF000008E -:10052000704700BF53B94AB9002908BF00281CBF53 -:100530004FF0FF314FF0FF3000F076B9ADF1080C0D -:100540006DE904CE00F006F8DDF804E0DDE90223F1 -:1005500004B070472DE9F047089E0D4604468846D2 -:10056000002B4DD18A42944668D9B2FA82F252B138 -:1005700001FA02F3C2F1200120FA01F10CFA02FCA7 -:1005800041EA030894404FEA1C41B8FBF1F71FFA17 -:100590008CFE01FB178807FB0EF0230C43EA08438F -:1005A00098420AD91CEB030307F1FF3580F01E8146 -:1005B000984240F21B81023F63441B1AB3FBF1F0E7 -:1005C00001FB103300FB0EFEA4B244EA0344A6452F -:1005D0000AD91CEB040400F1FF3380F00981A64521 -:1005E00040F20681644402380021A4EB0E0440EA84 -:1005F00007401EB10023D440C6E90043BDE8F087A0 -:100600008B4208D9002E00F0EE800021C6E90005DB -:100610000846BDE8F087B3FA83F100294AD1AB421E -:1006200002D3824200F2FC80841A65EB03030120AE -:100630009846002EE2D0C6E90048DFE702B9FFDEA7 -:10064000B2FA82F2002A40F09180A1EB0C00012165 -:100650004FEA1C471FFA8CFEB0FBF7F307FB1300B1 -:10066000250C45EA00450EFB03F0A84208D91CEB17 -:10067000050503F1FF3802D2A84200F2CE804346BE -:100680002D1AB5FBF7F007FB10550EFB00FEA4B2C8 -:1006900044EA0544A64508D91CEB040400F1FF35E3 -:1006A00002D2A64500F2B6802846A4EB0E0440EA2A -:1006B00003409EE7C1F120078B4022FA07FC4CEA79 -:1006C000030C25FA07FA4FEA1C49BAFBF9F820FA9D -:1006D00007F309FB18AA8D401FFA8CFE1D4300FA90 -:1006E00001F308FB0EF02C0C44EA0A44A04202FA83 -:1006F00001F20BD91CEB040408F1FF3A80F088806A -:10070000A04240F28580A8F102086444241AB4FB98 -:10071000F9F009FB104400FB0EFEADB245EA0444BB -:10072000A64508D91CEB040400F1FF356CD2A645A0 -:100730006AD90238644440EA0840A0FB0295A4EB61 -:100740000E04AC42C846AE4656D353D0002E69D0F4 -:10075000B3EB080264EB0E0422FA01F304FA07F784 -:100760001F43CC40C6E90074002147E70CFA02FCA5 -:10077000C2F1200125FA01F34FEA1C4720FA01F1EA -:1007800095400D43B3FBF7F107FB11331FFA8CFEC5 -:10079000280C40EA034001FB0EF3834204FA02F402 -:1007A00008D91CEB000001F1FF382FD283422DD96C -:1007B00002396044C01AB0FBF7F307FB1300ADB277 -:1007C00045EA004503FB0EF0A84208D91CEB0505DD -:1007D00003F1FF3816D2A84214D9023B6544281A07 -:1007E00043EA014138E73146304607E72F46E4E661 -:1007F0001846F9E64B45A9D2B9EB020865EB0C0E99 -:100800000138A3E74346EAE7284694E74146D1E7A3 -:10081000D0467BE76444023847E7023B65442FE754 -:10082000084606E73146E9E6704700BF02E000F0FF -:1008300000F8FEE772B6264880F30888254880F362 -:100840000988254825490860022080F31488BFF3F1 -:100850006F8F03F017F803F07BF84FF05530204905 -:100860001B4A91423CBF41F8040BFAE71D49194A63 -:1008700091423CBF41F8040BFAE71B491B4A1C4B51 -:100880009A423EBF51F8040B42F8040BF8E70020EF -:100890001849194A91423CBF41F8040BFAE702F0AB -:1008A000F5FF03F057F8154C154DAC4203DA54F838 -:1008B000041B8847F9E700F03FF8124C124DAC4298 -:1008C00003DA54F8041B8847F9E702F0DDBF0000A3 -:1008D00000090020001100200000000808ED00E0E1 -:1008E0000001002000090020103E00080011002037 -:1008F0002411002028110020E025002060010008BC -:100900006001000860010008600100082DE9F04F57 -:10091000C1F80CD0C3689D46BDE8F08F002383F377 -:1009200011882846A047002002F010FDFEE702F0E3 -:1009300083FC00DFFEE70000F8B500F03DFE02F0AA -:10094000EFFE074602F03AFF0546002840D12C4B47 -:100950009F423DD001339F423DD02A4B27F0FF02FA -:100960009A423BD1F8B200F003FC2E4642F21074DA -:1009700000F004FC08B10024264601F007F988B312 -:100980000024032000F044F8264635B11E4B9F4258 -:1009900003D0002402F00AFF2646002002F0CAFE1F -:1009A0001A4B9B6813F0400322D00EB100F046F8BA -:1009B00000F044FC00F002FE01F07CF90546CCB1E9 -:1009C00001F078F9401BA04214D900F037F8F3E7A2 -:1009D0002E460024CCE704460126C9E706464FF41C -:1009E0007A74C5E7002CD0D04FF47A740126CCE796 -:1009F0001C46DDE700F0D4FC012002F0ADFCDEE790 -:100A0000010007B0000008B0263A09B0000C014010 -:100A1000084B187003280CD8DFE800F0080502081E -:100A2000022000F027BE022000F01CBE0022024B74 -:100A30005A607047281100202C11002038B501F0B1 -:100A4000A5F830B103221F4B1A7000221E4B5A60CA -:100A500038BD1E4B1E4A19680131F9D00433934248 -:100A6000F9D11C4C194DD4F80424AA42F0D31A4BE6 -:100A70009B6803F1006303F5C8439A42E8D202F091 -:100A800069FE02F07BFE002000F0B2FD0220FFF7BD -:100A9000BFFF124BDA690022DA61D96999699A615C -:100AA0009B6972B64FF0E023C3F8085D3021D4F89B -:100AB0000034D4F8042481F311889D4683F3088818 -:100AC0001047C5E7281100202C1100200064000801 -:100AD000206400080060000800110020001002409F -:100AE00049F26900084A136899B21B0C00FB0133F4 -:100AF00044F250611360054B186882B2000C01FB90 -:100B00000200186080B27047201100201C110020E4 -:100B100010B504460021102200F0C8FD034B03CBA2 -:100B2000206061601868A06010BD00BFE8F7FF1F7B -:100B30002DE9F0410026ADF5507D6EAC40F2751206 -:100B400007460D4610A831460F9600F0AFFD4FF452 -:100B5000C4723146204600F0A9FD01F0ABF84FF415 -:100B60007A72B0FBF2F0264B0DF13C08186093E866 -:100B70000700022384E807000DF5ED702382FFF7DC -:100B8000C7FF4EF603031F4907A8238403F0ECF8C0 -:100B90001E230DF2EB2284F832310DF1340C07AB39 -:100BA0001E4603CE664510605160334602F10802CE -:100BB000F6D1306841461060B38820469380012208 -:100BC00000F0C0FD00230393AB7E80B2029305F1D9 -:100BD000190301930123CDE904800093384606A34D -:100BE000D3E90023E97E01F0ABFB0DF5507DBDE8B4 -:100BF000F08100BFAFF300809E6AC421818A46EE77 -:100C000034110020783D00082DE9F041264D804642 -:100C10002B7A0C46DAB0FBB9204627A900F0A2FED9 -:100C20000746002836D19DF89D60C82E32D801466F -:100C30004FF4FA72284600F039FD32460DF19E015C -:100C400005F1090000F020FD9DF89C302E447772DC -:100C50002B720BB9E37E2B728122002106AD27A8EF -:100C600000F024FD0122294627A800F0B7FE00234A -:100C70000393A37E80B2029304F119030193282306 -:100C8000CDE904500093404605A3D3E90023E17E5B -:100C900001F056FB5AB0BDE8F08100BFAFF3008011 -:100CA00026417272DF25D7B77C210020F0B54FF4C2 -:100CB0008A750024234EF1B005FB006596F8D83004 -:100CC000D822214685F8DC3085F8E8403AA800F0C3 -:100CD000EDFC06F1090000F0E1FCD5F8E430C2B209 -:100CE00006AF8DF8F00006F109010DF1F100CDE934 -:100CF0003A3400F0C9FC394601223AA800F09AFEC5 -:100D000080B2CDE9047008230127CDE9023706F14E -:100D1000D80301933023317A00930B4807A3D3E91A -:100D2000002301F00DFBA04206DD00F0C3FFC5F873 -:100D3000E000384671B0F0BD2046FBE778F6339FFF -:100D400093CACD8D7C2100204C210020F0B51E4E91 -:100D50001E4F1F4D85B0304601F01EFB044660B3A8 -:100D600010220021684600F0A1FC4FF00003227B16 -:100D70006068A16862F303038DF8003002AB03C31F -:100D8000019B2268384662F31C0301939DF80030F2 -:100D90006A4643F020038DF800300023194602F024 -:100DA00087F9044620B9304601F0FAFA2C70D2E7F0 -:100DB0002B78072B03D801332B7005B0F0BD024808 -:100DC00001F0EEFAF9E700BF4C210020A823002033 -:100DD0007523002070B50D4614461E4601F00CFA2E -:100DE00050B9022E10D1012C0ED112A3D3E9002349 -:100DF0000120C5E9002307E0282C10D005D8012CDC -:100E000009D0052C0FD0002070BD302CFBD10BA3D6 -:100E1000D3E90023ECE70BA3D3E90023E8E70BA316 -:100E2000D3E90023E4E70BA3D3E90023E0E700BF05 -:100E3000AFF30080401DA12026812A0B78F6339F56 -:100E400093CACD8D9E6AC421818A46EE2641727274 -:100E5000DF25D7B7F017304A39059E5638B5054615 -:100E60000E4C0021013500F0E5FBA4F8F051B4F878 -:100E7000F00100F0C7FB78B1B4F8F00100F0D2FB4C -:100E8000014648B9B4F8F00100F0D4FBB4F8F031F1 -:100E90000133A4F8F031EAE738BD00BF7C2100201F -:100EA0002DE9F04F8DB000AF04460D4601F0A4F9D6 -:100EB000002846D12B7E022B1AD1EB8A012B17D1A9 -:100EC00000F0F8FE0646FFF70BFE4FF4C873B0FBC8 -:100ED000F3F202FB1303DFF878829BB206F5167675 -:100EE0003344C8F80030EB7E33B90022994B1A70B6 -:100EF0003437BD46BDE8F08F284607F11C0100F0ED -:100F0000EFFC0028F4D107F10C00FFF701FEBD7FD4 -:100F100007F10C012A4607F11F0002F0F5FE002838 -:100F2000E3D10F2D08D88B4B1D70D8F80030A3F5F6 -:100F30001673C8F80030DBE72046397F01F054F91A -:100F4000D6E7EB8A282B6BD010D8012B63D0052B6A -:100F5000CED1BFF34F8F8049804BCA6802F4E06264 -:100F60001343CB60BFF34F8F00BFFDE7302BBFD1E2 -:100F70007B4CEA7E237A9A42BAD194F8DC206B7ECD -:100F80009A42B5D1284604F1EA0100F07FFD0646F9 -:100F90000028ADD1012384F8E83000F08BFED4F8AE -:100FA000E030C01A192840F6B83338BF19209842EB -:100FB00028BF1846FFF73EFA6A49FFF7D1F8054601 -:100FC0002068FFF737FA6849FFF7CAF80146284654 -:100FD000FFF780F9FFF786FA20604FF48A7194F8E2 -:100FE000D9307B607A68636801FB02F5621992F878 -:100FF000E80050B1D2F8E400E946834215D000235E -:1010000082F8E830C2F8E030CD466368574A9B0A60 -:10101000013313816CE729462046FFF789FD67E716 -:1010200029462046FFF7F0FD62E7B2F8EC803B600E -:1010300008F1030A4FEA9A0A4FEA8A02D11DC90849 -:10104000A9EBC1039D46EB460021584600F02EFB5C -:1010500005F1EE0142465846214400F015FB3B687D -:1010600013B9012000F0C4FA94F8D20000F0CAFAD3 -:10107000054630B9207200F0E5FA284600F0B8FACB -:10108000C2E7D4F8D4303BB994F8D200B4F8F031C8 -:10109000834201D8FFF7E2FED4F8D43043449D42A6 -:1010A00008D294F8D200B4F8F0310130834201D86C -:1010B000FFF7D4FE594660685FFA8AF200F0FEFA44 -:1010C00008B9CD4689E7636894F8D2004344636069 -:1010D000D4F8D43008EB030AC4F8D4A000F092FA94 -:1010E000824509D394F8D230D4F8D4000133401BA0 -:1010F00084F8D230C4F8D400B8F1FF0F0FD800251F -:10110000257200F09FFA284600F072FA00F03EFDCA -:10111000164B188108B9FFF791FCCD46E8E64FF46D -:101120008A727B6894F8D90002FB0343D3F8E42069 -:1011300083F8E86002F58072C3F8E060C3F8E42049 -:10114000FFF7B4FDFFF702FE84F8D960B9E700BFEE -:10115000482100204521002000ED00E00400FA05B0 -:101160007C210020CDCCCC3D6666663F341100204A -:10117000014B1870704700BF4011002030B54FF090 -:101180000054254B226885B09A4207D002F020FB1C -:101190000446C0B90024204605B030BD0025627D5C -:1011A0001E4B1F481A70237DC92203721D49C0F8C7 -:1011B000E450093000F068FA2046E022294600F0A9 -:1011C00075FA0124E7E7184A184DD36943F0007314 -:1011D000D361AA6D164B9A42DCD12B6E013B7E2B5C -:1011E000D8D8144A01AB07CA83E807001846032180 -:1011F00000F09CFC6B6D83424FF00003CAD12A6D56 -:101200008A4203BFAB652A6E044B1C4601BF1A70AD -:10121000EA6D094B1A60BEE79AAD44C54011002043 -:101220007C210020160000200010024000660040D3 -:101230005041A0B058660040181100202DE9F0433D -:1012400085B000F0A3FC0223494C63710023029394 -:10125000484B2081D3F800C0BCF57A7F12D3464FAB -:10126000464BB7FBFCF59C458CBF0A231123B5FB0D -:10127000F3F603FB1652591EC8B2002A3ED00229CB -:101280000B46F4D89DF80B303D495A1E9DF80A30A4 -:101290003C48013B1B0443EA0253BDF80820013AD5 -:1012A00013434B6001F0F4FE00230193364B3749A2 -:1012B00000934FF48052364B364800F06BFF364BAC -:1012C000197811B1334800F08FFF00F0F3FC0546A8 -:1012D000FFF706FC4FF4C873B0FBF3F202FB1303F5 -:1012E00005F516709BB218442C4B186002F066FA94 -:1012F00008B10F23238105B0BDE8F083731EB3F559 -:10130000806FBFD24FF47A75C0EBC00E0EF10303AD -:101310004FEAE30909FB0555C3F3C703C11AC9B274 -:1013200009F101088844B5FBF8F5B5F5617F08D9E6 -:101330000EF1FF33C3F3C703C11A581E0F28C9B2F9 -:1013400014D84A1E072A8CBF00220122581800FB1D -:101350000660B7FBF0F7BC4594D1002A92D0ADF8F7 -:1013600008608DF80A308DF80B108BE71346EDE717 -:101370003411002018110020005125023F420F00B7 -:1013800010110020A8230020D50D000844110020D2 -:10139000A10E00084C21002040110020482100200F -:1013A0002DE9F04F80A7D7E900670FF20429D9E9AA -:1013B0000089734D93B00DF1300AFFF7C7FC182276 -:1013C0000021504600F072F9DFF8B8B16E4C0023EE -:1013D00052461946584601F093FE014650BB102272 -:1013E00008A800F063F9E36883F01003E36000F0FD -:1013F00063FC0DF1240C0B4612A9024611E903000F -:101400008CE803009DF83410C1F30300890649BF3E -:101410000E99BDF83810C1F31C0141F0004158BFCE -:10142000C1F30A018DF82C000891284608A901F0A3 -:1014300097F9CCE7284600F0DFFE0446002847D1A4 -:1014400000F038FCDFF844B1DBF8003098423FD3BD -:1014500000F030FC0790FFF743FB4FF4C873B0FB7C -:10146000F3F101FB1300079A83B202F516701844DA -:10147000CBF80000DFF818B18DF820409BF8001081 -:1014800011B901238DF8203050460791FFF740FB3A -:1014900007990DF12100C1F11004E4B2062C28BF18 -:1014A00006245144224600F0EFF808AB03931823BA -:1014B0000293384B013401930123E4B20093324686 -:1014C0003B462846049400F0DDFE00238BF80030F4 -:1014D00000F0F0FB304A314C1368C31AB3F57A7F41 -:1014E00030D3106000F0E8FB02460B46284600F0BF -:1014F00061FF284600F080FE20B3237ADFF8A0B019 -:10150000002B14BF032302238BF8053000F0D2FB1D -:101510004FF47A73B0FBF3F00122CBF80000514690 -:10152000584600F0B5F9182302931E4B80B2019380 -:1015300040F25513CDE903A0009342464B4628469E -:1015400000F0A0FE237ABBB100F0B4FB94F8E830C1 -:1015500073B9D4F8E03043B1C01A2368FA2B38BF0E -:10156000FA230533B0EB430F02D30020FFF79EFBB5 -:10157000237A002B7FF41FAF13B0BDE8F08F00BFBC -:101580004C210020A8230020000801404821002011 -:101590004521002044210020702300207C210020D0 -:1015A0003411002074230020401DA12026812A0B25 -:1015B000F1C6A7C1D068080F7047000070B501F0F0 -:1015C00095FF0024084E094D3080286833888342F7 -:1015D00008D901F087FF2B6804440133B4F5C84FE4 -:1015E0002B60F2D370BD00BFA4230020782300201D -:1015F00002F00AB800F10060920000F5C84001F066 -:10160000AFBF0000054B1A68054B1B889B1A83422D -:1016100002D9104401F066BF0020704778230020F3 -:10162000A4230020024B1B68184401F061BF00BFD7 -:1016300078230020024B1B68184401F06BBF00BFE9 -:1016400078230020064991F8243033B10023082282 -:10165000086A81F82430FFF7CDBF0120704700BF32 -:101660007C230020022802BF1022014B1A61704720 -:1016700000080140022802BF4FF48012014B1A619A -:10168000704700BF00080140002310B5934203D00B -:10169000CC5CC4540133F9E710BD00000346024698 -:1016A000D01A12F9011B0029FAD1704703460244EF -:1016B000934202D003F8011BFAE770472DE9F84383 -:1016C0001F4D144695F824200746884652BBDFF884 -:1016D00070909CB395F824302BB92022FF21484606 -:1016E0002F62FFF7E3FF95F824004146C0F108029E -:1016F000A24228BF224605EB8000D6B29200FFF737 -:10170000C3FF95F82430A41B1E44F6B2082E1744DC -:101710009044E4B285F82460DBD1FFF793FF002802 -:10172000D7D108E02B6A03EB82038342CFD0FFF7C7 -:1017300089FF0028CBD10020BDE8F8830120FBE71A -:101740007C2300202DE9F0470D46044600219046F9 -:10175000284640F27912FFF7A9FF234620220021F4 -:10176000284600F09FFF022220212846231D00F07A -:1017700099FF032222212846631D00F093FF0322D4 -:1017800025212846A31D00F08DFF10222821284680 -:1017900004F1080300F086FF08223821284604F1EE -:1017A000100300F07FFF08224021284604F11103B6 -:1017B00000F078FF08224821284604F1120300F0C7 -:1017C00071FF20225021284604F1140300F06AFF23 -:1017D00040227021284604F1180300F063FF08221C -:1017E000B021284604F1200300F05CFF0822B82154 -:1017F000284604F1210300F055FFC02604F122071A -:101800003B46314608222846083600F04BFFB6F525 -:10181000A07F07F10107F3D108223146284604F1E1 -:10182000320300F03FFF002704F1330A94F832300E -:101830004FEAC7099F4209F5A47615D3B8F1000F06 -:1018400008D131460722284604F5997300F02AFF93 -:1018500009F24F16274694F832213B1B93420CD3D2 -:10186000F01DC008BDE8F0870AEB070308223146E7 -:10187000284600F017FF0137D8E7314607F2331347 -:101880000822284600F00EFF08360137E3E7000083 -:1018900038B50C460021054621600346C4F8031004 -:1018A0002046202200F0FEFE20462B1D0222202191 -:1018B00000F0F8FE20466B1D0322222100F0F2FE0C -:1018C0002046AB1D0322252100F0ECFE204610220D -:1018D000282105F1080300F0E5FE072038BD0000CF -:1018E0000023F7B50E460546047F072200911946EE -:1018F00000F09AFD731C0093012200230721284663 -:1019000000F092FDC4B9B31C0093052223460821C0 -:10191000284600F089FD0D243746B278BB1B934260 -:1019200011D32B7FE01DC008AC8ABBB9A04294BF85 -:101930000020012003B0F0BDAB8A0824DB00083B87 -:10194000DB08B370E8E7FB1C214600930822002364 -:10195000284600F069FD08340137DEE7001B18BF98 -:101960000120E7E70023F7B50E46047F0822009127 -:101970001946054600F058FD731CC4B908220093AF -:1019800011462346284600F04FFD102401237278AB -:101990005F1C013B934211D32B7FE01DC008AC8A32 -:1019A000BBB9A04294BF0020012003B0F0BDAB8AB8 -:1019B0000824DB00083BDB087370E7E7F3192146D6 -:1019C000009308220023284600F02EFD08343B46F1 -:1019D000DDE7001B18BF0120E7E70000F8B50E4661 -:1019E00005461446002181223046FFF75FFE2B4654 -:1019F00008220021304600F055FE7CB9072208215C -:101A000030466B1C00F04EFE0F2401236A785F1CE9 -:101A1000013B934204D3E01DC008F8BD0824F4E75D -:101A20002146EB190822304600F03CFE08343B46C4 -:101A3000ECE70000F8B50E46054614460021CE221C -:101A40003046FFF733FE2B4628220021304600F0B7 -:101A500029FE7CB908222821304605F1080300F050 -:101A600021FE30242F462A7A7B1B934204D3E01DAB -:101A7000C008F8BD2824F5E7214607F1090308222C -:101A8000304600F00FFE08340137ECE7F7B5047F6D -:101A90000E460091012310220021054600F0C4FCEF -:101AA000C4B9B31C0093092223461021284600F034 -:101AB000BBFC192437467288BB1B9A4211D82B7F76 -:101AC000E01DC008AC8ABBB9A04294BF0020012031 -:101AD00003B0F0BDAB8A1024DB00103BDB08738041 -:101AE000E8E73B1D2146009308220023284600F02A -:101AF0009BFC08340137DEE7001B18BF0120E7E735 -:101B000030B5094D0A4491420DD011F8013B5840BF -:101B1000082340F30004013B2C4013F0FF0384EA48 -:101B20005000F6D1EFE730BD2083B8ED4FF0FF3322 -:101B3000F7B500EB81061946DFF848C0DFF848E04A -:101B4000B0421BD050F8042B01AF0192042217F8C9 -:101B5000014B81EA046108240D46DB184941013C30 -:101B6000002DBCBF83EA0C0381EA0E0114F0FF04D0 -:101B7000F2D1013A12F0FF02E9D1E1E7D843C943BB -:101B800003B0F0BD9336EAA9EBE1F042F7B56B463E -:101B9000354A106851686A4603C3082333493448FC -:101BA00002F0C2F8044690BB0A256B46314A106821 -:101BB00051686A4603C308232F492D4802F0B4F840 -:101BC0000446002847D00369B3F5CE3F43D8B0F8A8 -:101BD0006620B2F57A7F3ED1284A024402F15C01C8 -:101BE0008B4238D35C3B224900209E1AFFF788FFC6 -:101BF00007463246002004F16401FFF781FFA36825 -:101C00009F4228D1E368984208BF002523E003697A -:101C1000B3F5CE3F26D8428BB2F57A7F20D1174A52 -:101C2000024402F110018B4218D3103B10490020EE -:101C30009D1AFFF765FF06462A46002004F11801A9 -:101C4000FFF75EFFA3689E4202D1E368984201D08D -:101C50000D25AAE70025284603B0F0BD1025A4E70E -:101C60000C25A2E70B25A0E7983D0008DC9B0100AE -:101C700000640008A13D0008909B0100089CFFF74C -:101C8000EFF30983EFF30583014B9B6BFEE700BF86 -:101C900000ED00E008B5FFF7F3FF0000EFF3098364 -:101CA000EFF30583014B5B6BFEE700BF00ED00E047 -:101CB000FEE7000001F0E2BC01F0BABC2DE9F04102 -:101CC000456A15B94162BDE8F0814B68AC4623F026 -:101CD0006047C3F38A4616EA230638BF3E464FEAFA -:101CE000D37EC3F380782B465A68BEEBD27F22F0B6 -:101CF00060440AD0002A18DAA40CB44217D19D42DD -:101D00000FD10D60DEE71346EEE7A74207D102F0E0 -:101D10008044C2F3807242450BD054B1EFE708D241 -:101D2000EDE7CCF800100B60CDE7B44201D0B4422F -:101D3000E5D81A689C46002AE5D11960C3E700007F -:101D40002DE9F0474FF47F49089D01F007044FEA61 -:101D5000D508224405F0070500EBD100944201D1DB -:101D6000BDE8F08704F0070705F0070A57453E462F -:101D700038BF5646111BC6F108068E4228BF0E46D4 -:101D8000E108415C08EBD50E13F80EC0B94029FA02 -:101D900006F721FA0AF1FFB28CEA010147FA0AF7C5 -:101DA00039408CEA010C03F80EC034443544D5E7C1 -:101DB000082341F2210280EA012001B240000029FB -:101DC00080B203F1FF33B8BF504013F0FF03F4D1EA -:101DD0007047000038B50C468D18A54200D138BDBB -:101DE00014F8011BFFF7E4FFF7E700000346406823 -:101DF00048B1026899895A605A89013292B2914277 -:101E00005A8138BF9A81704770B504460D4688B034 -:101E1000202200216846FFF749FC20460495FFF781 -:101E2000E5FF024658B16B46054608AE1C4603CC9A -:101E3000B44228606960234605F10805F6D11046D2 -:101E400008B070BD082817D909280CD00A280CD072 -:101E50000B280CD00C280CD00D280CD00E2814BF49 -:101E60004020302070470C2070471020704714200D -:101E7000704718207047202070470000082817D9A5 -:101E80000C280CD910280CD914280CD918280CD9D6 -:101E900020280CD930288CBF0F200E207047092035 -:101EA00070470A2070470B2070470C2070470D20A8 -:101EB000704700002DE9F843078C0446072F1ED910 -:101EC000D0E9029800254FF6FF73C5F12006A5F171 -:101ED000200029FA05F108FA06F628FA00F0314345 -:101EE0000143C9B21846FFF763FF0835402D03468A -:101EF000EBD13A46E169BDE8F843FFF76BBF4FF617 -:101F0000FF70BDE8F883000010B54B6823B9CA8A9A -:101F100063F30902CA8210BD04691A681C60036178 -:101F2000C38A013BC3824A60EFE700002DE9F84F06 -:101F30001D46CB8A0F46C3F3090105298146924607 -:101F40000B4630D00020AAB207F11A049EB2042E2C -:101F50001FFA80F80FD8904503F1010306D3FB8ADE -:101F60000A4462F309030120FB821AE01AF80060B8 -:101F70000130E654EAE79045F1D21C23A1F1050BAC -:101F8000BBFBF3F203FB12BB7C681FFA8BF6002C41 -:101F900045D14846FFF72AFF044638B978606FF00C -:101FA0000200BDE8F88F4FF00008E6E70026066063 -:101FB00078604FF0000BADB2454510D90AEB08032D -:101FC000221D13F8011B08F101089155B1B21B291C -:101FD0001FFA88F82BD0454506F10106F1D8FB8A97 -:101FE000C3F30902154465F30903BCE71C4601323B -:101FF00092B22368002BF9D16B1F0B441C21B3FB59 -:10200000F1F301339BB29A42D3D2BBF1000FD0D18E -:102010004846FFF7EBFE20B9C4F800B0BFE7012245 -:10202000E7E7C0F800B05E4620600446C1E74545DA -:10203000D5D94846FFF7DAFE08B92060AFE7C0F807 -:1020400000B0002620600446B6E700002DE9F74FF7 -:102050001C465B69074688460092002B00F097807B -:10206000238C2BB1E269002A00F09180072B33D832 -:1020700007F10C00FFF7BAFE054628B96FF002051C -:10208000284603B0BDE8F08F14220021FFF70EFBB5 -:10209000228CE16905F10800FFF7F6FA208C48F080 -:1020A0000041013080B2FFF7E9FEFFF7CBFE0138B7 -:1020B00080B22084013028746369228C1B782A4402 -:1020C00003F01F0363F03F0313723846696029462B -:1020D000FFF7F4FD0125D3E74FF000094FF0800A28 -:1020E0004E464D4600F10C0301930198FFF77EFE2A -:1020F00083460028C2D014220021FFF7D7FA002E11 -:102100003BD10222009BABF808300BF1080E1FFAFE -:1021100082FC0CF10100BCF1060F218C80B201D8C9 -:102120008E422CD3FFF7AAFEFFF78CFE8E4208BF2B -:102130004FF0400A62690138127880B202F01F0243 -:1021400042EA49120BEB00014AEA020A013048F068 -:10215000004281F808A08BF8100059463846CBF8A9 -:102160000420FFF7ABFD238C0135B3424FF0000A8A -:102170002DB289F00109B8D182E70022C5E7E169F3 -:10218000895D01360EF80210B6B20132BFE76FF07A -:10219000010575E7F8B5044615460E4630220021C4 -:1021A0001F46FFF783FA069BB5F5001F6360079B88 -:1021B00028BF4FF6FF72A3624FF0000338BF6A09D1 -:1021C000A760E66197B204F110009A4206D8002396 -:1021D0000360A782E3822383E360F8BD06600133D6 -:1021E00030462036F1E7000003781BB94BB2002BD4 -:1021F000C8BF01707047000000787047F8B50C4602 -:10220000C969074611B9238C002B37D1257E1F2DB4 -:1022100034D8387828BB228C072A2CD8268A36F066 -:1022200003032BD14FF6FF70FFF7D4FD4FF6FF727B -:1022300020F001003602400446EA0565400C45EAFC -:102240004025234629463846FFF700FF002807DDD2 -:10225000626913780133DBB21F2B88BF0023137030 -:10226000F8BD218A2D0645EA012505432046FFF7E2 -:1022700021FE0246E5E76FF00300F1E76FF0010091 -:10228000EEE7000070B504461D4616468AB02822C7 -:1022900000216846FFF70AFABDF838306946ADF804 -:1022A00010300F9B204605939DF84030CDE9026524 -:1022B0008DF81830119B0793BDF84830ADF82030E9 -:1022C000FFF79CFF0AB070BD2DE9F041D3690546C8 -:1022D0000C4616460BB9138C5BBB377E1F2F28D8D4 -:1022E00095F80080B8F1000F26D03046FFF7E2FDE8 -:1022F0003378210241EAC33141EA0801338A41EAD5 -:10230000076141EA034102463346284641F0800115 -:10231000FFF79CFE00280ADD3378012B07D1726994 -:1023200013780133DBB21F2B88BF00231370BDE885 -:10233000F0816FF00100FAE76FF00300F7E70000AB -:10234000F0B504460D461E4617468BB028220021E4 -:102350006846FFF7ABF99DF84C3029465A1E5342A8 -:1023600053418DF800309DF840306A46ADF810308A -:10237000119B204605939DF84830CDE902768DF8F3 -:102380001830149B0793BDF85430ADF82030FFF798 -:102390009BFF0BB0F0BD0000406A00B104307047F5 -:1023A000436A1A68426202691A600361C38A013B88 -:1023B000C38270472DE9F041D0F8208014461D46B5 -:1023C00041460027174E09B9BDE8F081D1E9022343 -:1023D000A21A65EB0303964277EB03031ED2036A4E -:1023E0008B420DD1FFF790FD036A1B6803620369FE -:1023F0000B60C38A0161016A013B8846C382E2E740 -:10240000FFF782FD0B68C8F8003003690B60C38AD0 -:102410000161013BC382D8F80010D4E788460968FF -:10242000D1E700BF80841E002DE9F04F8BB00D4630 -:1024300014469B468046DDF85090002800F01A8133 -:10244000B9F1000F00F01681531E3F2B00F21281EC -:10245000012A03D1BBF1000F40F00C810023CDE92C -:102460000833B8F81430B5EBC30F4FEAC30703D3F2 -:1024700000200BB0BDE8F08F2B199F42D8F80C302C -:1024800036BF7F1B2746FFB21BB9D8F81030002B90 -:102490007BD0272D4ED8C5F12806B7424FF0000358 -:1024A00034BF3E46F6B2009329463246D8F80800BB -:1024B00008ABFFF745FCA7EB060A35445FFA8AFA3A -:1024C0002821B8F8143003F10053053BDB000493D6 -:1024D000D8F80C300393039B13B1BAF1000F2CD141 -:1024E000D8F8100040B1BAF1000F05D0524600965E -:1024F00008AB691AFFF724FC38B2002FB8D0660782 -:102500000AD00AAB03EBD40111F8083C624202F096 -:102510000702134101F8083C082C3DD9102C40F269 -:10252000B680202C40F2B880BBF1000F00F09D80F7 -:10253000082335E0BA460026C2E7049BE02B28BFFB -:10254000E02306930B44AB42059315D95A1B9245E1 -:1025500038BF5246039828BFD2B20096691A08AB1A -:1025600004300792FFF7ECFB079A1644AAEB020A25 -:102570001544F6B25FFA8AFA049B069A05999B1AEB -:102580000493039B1B680393A5E700933A462946EF -:10259000D8F8080008ABADE7BBF1000F13D001235A -:1025A000B4EBC30F6CD0082C12D89DF82030621EFB -:1025B00023FA02F2D50706D54FF0FF3202FA04F4EF -:1025C00023438DF820309DF8203089F8003050E703 -:1025D000102C12D8BDF82030621E23FA02F2D10767 -:1025E00006D54FF0FF3202FA04F42343ADF8203051 -:1025F000BDF82030A9F800303BE7202C0FD808990F -:10260000631E21FA03F3DA0705D54FF0FF3202FA11 -:1026100004F40C430894089BC9F8003029E7402CC7 -:102620002BD0DDE90865611EC4F12102A4F121036C -:1026300026FA01F105FA02F225FA03F311431943D0 -:10264000CB0712D50122A4F12003C4F1200102FA24 -:1026500003F322FA01F1A240524243EA010363EB81 -:10266000430332432B43CDE90823DDE90823C9E9BD -:102670000023FEE66FF00100FBE66FF00800F8E6CD -:10268000082CA0D9102CB3D9202CEED8C3E7BBF16D -:10269000000FADD0022383E7BBF1000FBBD00423B2 -:1026A0007EE70000012A30B5144638BF012200251C -:1026B000402A28BF402285B0012CCDE9025517D809 -:1026C0001B788DF8083053070AD004AB03EBD20512 -:1026D00015F8083C544204F00704A34005F8083CF0 -:1026E0000346009102A80021FFF72AFB05B030BD88 -:1026F000082CE5D9102C03D81B88ADF80830E2E788 -:10270000202C02D81B680293DDE7D3E90045CDE910 -:102710000245D8E710B5CB681BB98B600B618B8283 -:1027200010BD04691A681C600361C38A013BC3823F -:10273000CA60F0E703064CBFC0F3C0300220704708 -:1027400008B50246FFF7F6FF022806D15306C2F38A -:102750000F2001D100F0030008BDC2F30740FBE7E2 -:102760002DE9F04F93B0CDE903230A6804461046E3 -:10277000FFF7E0FF02280CBF0026C2F30626002A5E -:102780000D46824680F2F98112F0C04940F0F58191 -:10279000097B002900F0F181022803D02378B3429D -:1027A00040F0EE81C2F304631046069302F07F030B -:1027B0000593FFF7C5FF059B00224FEA83480023DE -:1027C00048EA0A48294448EA4668CE78CDE9082311 -:1027D000F309834648EA0008029367D0059B024646 -:1027E000009320465346676808A9B847002800F0C0 -:1027F000CA81276A4FB9414604F10C00FFF704FB78 -:10280000074690B96FF0020054E03B6998450DD03F -:102810003F68002FF9D1414604F10C00FFF7F4FAAC -:1028200007460028EED0236A3B60276297F817C05E -:1028300006F01F08CCF3840CACEB08001FFA80FEF6 -:102840000028B8BF0EF12000A8EB0C031FFA83FE8E -:10285000B8BF00B2002B0793BEBF0EF120031BB21E -:102860000793D7E9022152EA010338D04FF0000C58 -:10287000039BDFF8F8E19A1A049B63EB010196458C -:102880007CEB01032BD36B7B97F81AE0734519D1CE -:10289000029B002B78D0012821DC7868F8B9DFF89A -:1028A000D0C1944570EB010316D337E0276A27B9EE -:1028B0006FF00C0013B0BDE8F08F3B699845B5D0C0 -:1028C0003F68F4E76A4890427CEB010301D30020A3 -:1028D000F0E7029B002BFAD0079B0F2B17DCFA7D49 -:1028E000B30002F0030203F07C031343FB75394687 -:1028F0002046FFF709FB6B7BBB76029B3BB9FB7D58 -:10290000C3F38402013262F38603FB75D0E76A7B6E -:10291000BB7E9A42DBD1029B002B35D0B309022B40 -:1029200032D0039B1422BB60049B0021FB600DA8E6 -:10293000FEF7BCFE039B20460A93049BADF83EB015 -:102940000B932B1D0C932B7B8DF840A0013BDBB22E -:10295000ADF83C30069B8DF841808DF84230059BE8 -:102960000AA98DF8433094F82C3083F001038DF8D8 -:102970004430A3689847FB7DC3F38403013303F01D -:102980001F039B02FB82A2E7FB7DC6F34012B2EB62 -:10299000D31F40F0FB80C3F38403434540F0F9802C -:1029A000029A2B7BB609002A4DD0F20762D4032B82 -:1029B00040F2F280039BAE1DBB60049B3246FB607D -:1029C0002B7B3946033BDBB204F10C00FFF7AEFA78 -:1029D00000280CDA39462046FFF796FAFB7DC3F350 -:1029E0008403013303F01F039B02FB820AE7AB88D9 -:1029F000DDE908843B834FF6FF73C9F12000A9F19C -:102A0000200228FA09F104FA00F0014324FA02F244 -:102A100011431846C9B2FFF7CBF909F10809B9F11A -:102A2000400F0346E9D13146B8822A7B033AD2B23D -:102A3000FFF7D0F9FB7DB882DA43C2F3C01262F32C -:102A4000C713FB7543E7AEB92E1D013B324639462D -:102A5000DBB204F10C00FFF769FA0028BADB2A7B2D -:102A60003146013AB88AD2B2E2E700BF80841E0044 -:102A700040420F00F98A013BC1F309010429DAB28F -:102A80005DD80023281D07F11B069A4208D910F8CB -:102A900001CB013306F801C001310529DBB2F4D1C5 -:102AA000934228BF0023039938BF04330A91049945 -:102AB00038BFDBB20B9107F11B010C91796838BF6D -:102AC0005B190D910E93FB8AADF83EB0C3F3090379 -:102AD0001A44069BADF83C208DF84230059B8DF8DA -:102AE00040A08DF8433094F82C308DF8418083F06D -:102AF00001038DF8443000237B602A7BB88A013AB9 -:102B0000291DFFF767F93B8BB882834203D120462A -:102B1000A3680AA9984720460AA9FFF7FBFDFB7D99 -:102B2000BA8AC3F38403013303F01F039B02FB82C1 -:102B30003B8B9A420CBF00206FF01000BAE67B6816 -:102B4000002BADD0052001E033461C301E68002E5E -:102B5000FAD1091A081D2E1D184401EB090CBCF10D -:102B60001B0F5FFA89F39BD89A4299D916F8013B5B -:102B700009F1010900F8013BEFE76FF0090099E660 -:102B80006FF00A0096E66FF00B0093E66FF00D0011 -:102B900090E66FF00E008DE66FF00F008AE600BF42 -:102BA000F0B53F4D3F4FEB6943F00073EB61EB69CC -:102BB0003D4B9B6AD3F800623E4046F00106C3F8E5 -:102BC0000062D3F800423C4044EA002444F001048F -:102BD000C3F80042002955D000200646C3F81C0265 -:102BE000C3F80402C3F80C02C3F8140203EBC004D8 -:102BF00001300E28C4F84062C4F84462F6D10027C0 -:102C00004FF0010C9678148816F0010F18BFD3F816 -:102C100004E20CFA04F01CBF40EA0E0EC3F804E212 -:102C200016F0020F18BFD3F80CE203EBC4041CBF6C -:102C300040EA0E0EC3F80CE2760748BFD3F81462E0 -:102C400007F1010744BF0643C3F814625668B9424E -:102C5000C4F84062966802F10C02C4F84462D3F8EA -:102C60001C4240EA0400C3F81C02CBD1D3F8002276 -:102C700022F00102C3F80022EB6923F00073EB613C -:102C8000EB69F0BD0122C3F84012C3F84412C3F847 -:102C90000412C3F81412C3F80C22C3F81C22E5E78F -:102CA000001002400000FFFFA8230020184A08B5CA -:102CB000916A8B688B6013F0010104D013F00C0F44 -:102CC00018BF4FF48031D80506D513F4406F14BFF8 -:102CD00041F4003141F00201D80306D513F4402F2E -:102CE00014BF41F4802141F00401D3690BB10848BD -:102CF0009847302383F311880021064800F048FBF1 -:102D0000002383F31188BDE8084000F099BD00BF9F -:102D1000A8230020B023002038B5124CA36ADD6838 -:102D2000AA0712D05A6922F002025A61A36913B1AC -:102D3000012120469847302383F3118800210A4857 -:102D400000F026FB002383F31188EB0606D5102143 -:102D5000A36AD960236A0BB102489847BDE838409E -:102D600000F06EBDA8230020B823002038B5124C17 -:102D7000A36A1D69AA0712D05A6922F010025A618B -:102D8000A36913B1022120469847302383F31188A9 -:102D900000210A4800F0FCFA002383F31188EB06B7 -:102DA00006D51021A36A1961236A0BB1024898471E -:102DB000BDE8384000F044BDA8230020B82300201F -:102DC00038B50F4CA36A5D682A075D600AD50422F6 -:102DD00022701A6822F002021A60636A13B100219D -:102DE000204698476B0706D5A36A9969236A13B1F1 -:102DF000034809049847BDE8384000F021BD00BFF2 -:102E0000A823002010B50E4C204600F02FF90D4BE2 -:102E10000B211320A36200F009F90B21142000F00C -:102E200005F90B21152000F001F90B21162000F007 -:102E3000FDF8BDE8104000220E201146FFF7B0BE9D -:102E4000A8230020006400400F4B10B598420446B0 -:102E500005D10E4BDA6942F00072DA61DB690122BA -:102E6000A36A1A60A36A5A68D20707D562685168D4 -:102E70001268D9611A60064A5A6110BD0121082002 -:102E800000F0B0F9EEE700BFA823002000100240D8 -:102E90005B87010003291AD8DFE801F0020A0F144A -:102EA000836A9B6813F0E05F14BF01200020704725 -:102EB000836A9868C0F380607047836A9868C0F33B -:102EC000C0607047836A9868C0F300707047002044 -:102ED0007047000010B5032927D8DFE801F002276A -:102EE0002B2F836A9968C1F30161183103EB011339 -:102EF0001078840648BF5468C0F3001158BF948806 -:102F00004FEA410148BF41EAC40100F00F00586098 -:102F100048BF41F00401906858BF41EA4451D2686B -:102F200041F001019860DA60196010BD836A03F511 -:102F3000C073DDE7836A03F5C873D9E7836A03F5D5 -:102F4000D073D5E701290AD002290FD081B9836A4D -:102F5000DA68920701D1186903E001207047836A9B -:102F6000D86810F0030018BF01207047836AF2E7A9 -:102F70000020704710B539B9836AD96889071BD119 -:102F80001B699C0704D110BD012915D00229FAD173 -:102F9000816AD1F8C031D1F8C441D1F8C8011061BB -:102FA000D1F8CC015061202008610869800717D151 -:102FB000486940F0100012E0816AD1F8B031D1F8D0 -:102FC000B441D1F8B8011061D1F8BC0150612020A2 -:102FD000C860C868800703D1486940F002004861B2 -:102FE000C3F34000C3F38001000140EA41111079AE -:102FF00020F030000143117189064BBF916811899F -:10300000DB085B0D4CBF63F31C0163F30A0113790A -:1030100048BF916064F3030313714FEA14234FEA2E -:10302000144458BF118113705480ACE70122090188 -:1030300000F1604303F56143C9B283F8001300F067 -:103040001F039A4043099B0003F1604303F561436A -:10305000C3F880211A607047090100F16040C9B2CD -:1030600000F56D4001767047FFF7CCBE0123037079 -:10307000002300F10802C0E9022200F11002C0E9B9 -:103080000422C0E90633C0E90833436070470000FA -:1030900010B53023044683F3118802234160037086 -:1030A000FFF7D2FE04230020237080F3118810BDA7 -:1030B0002DE9F0411F4604460D461646302383F3A2 -:1030C000118800F108082378052B0DD029462046E9 -:1030D000FFF7E0FE40B1204632462946FFF7FAFEF0 -:1030E000002080F3118808E03946404600F040F99E -:1030F0000028E8D0002383F31188BDE8F0810000A8 -:103100002DE9F0411F4604460D461646302383F351 -:10311000118800F110082378052B0DD02946204690 -:10312000FFF710FF40B1204632462946FFF722FF45 -:10313000002080F3118808E03946404600F018F975 -:103140000028E8D0002383F31188BDE8F081000057 -:1031500000238268037503691B6899689142FBD25A -:103160005A680360426010605860704700238268AC -:10317000037503691B6899689142FBD85A6803601C -:10318000426010605860704708B50846302383F3EA -:1031900011880B7D032B05D0042B0DD02BB983F3A5 -:1031A000118808BD00228B691A604FF0FF338361DC -:1031B000FFF7CEFF0023F2E7D1E9003213605A6037 -:1031C000F3E70000FFF7C4BF054BD968087518681E -:1031D000026853601A6001220275D860FDF796BB41 -:1031E000D823002030B50C4B0446DD684B1C87B05B -:1031F0000FD02B466846094A00F0F0F82046FFF74A -:10320000E3FF009B13B1684600F0F0F8A86907B02F -:1032100030BDFFF7D9FFF9E7D82300208931000836 -:10322000044B1A68DB6890689B68984294BF002042 -:1032300001207047D8230020084B10B51C68D868BF -:10324000226853601A6001222275DC60FFF78EFF4E -:1032500001462046BDE81040FDF758BBD8230020AA -:10326000044B1A68DB6892689B689A4201D9FFF7A1 -:10327000E3BF7047D823002038B501230025064C52 -:10328000064907482370656000F020FB0223237085 -:1032900085F3118838BD00BF30250020B03D0008FF -:1032A000D823002000F0B4B8EFF3118020B9EFF379 -:1032B0000583302282F311887047000010B530B9C1 -:1032C000EFF30584C4F3080414B180F3118810BD32 -:1032D000FFF7C6FF84F31188F9E700008B60022333 -:1032E00008618B82084670478368A3F1440243F863 -:1032F000142C026943F8442C426943F8402C094AD3 -:1033000043F8242CC268A3F1200043F8182C0222B1 -:1033100003F80C2C002203F80B2C034A43F8102C62 -:10332000704700BF1D090008D823002008B5FFF72B -:10333000DBFFBDE80840FFF745BF0000024BDB683C -:1033400098610F20FFF740BFD8230020302383F37C -:103350001188FFF7F3BF000008B50146302383F35F -:1033600011880820FFF73EFF002383F3118808BD72 -:10337000064BDB6839B1426818605A6013604360DD -:103380000420FFF72FBF4FF0FF307047D8230020F5 -:1033900038B504460D462068844200D138BD036824 -:1033A00023605C608561FFF70DFFF4E710B50A4C00 -:1033B00023699A6891420CD85A6881600360426020 -:1033C00010609A685860511A99604FF0FF33A361FA -:1033D00010BD1B68891AECE7D8230020C0E903233D -:1033E000002310B410BC4361FFF7E0BF036881689D -:1033F0009A680A449A60426813605A6000234FF04A -:10340000FF320360014B9A61704700BFD823002050 -:1034100070B5124D2A46EB690133EB6152F8103F4B -:10342000934206D030269A68013A9A602C69A368C4 -:1034300003B170BDD4E900210A605160236083F3B9 -:1034400011882046D4E90331984786F311886169D1 -:103450000029EBD02046FFF7A9FFE7E7D82300209B -:1034600000207047FEE70000704700004FF0FF307B -:1034700070470000BFF34F8F024AD368DB07FCD4CC -:10348000704700BF0020024008B5074B1B7853B9B6 -:10349000FFF7F0FF054B1A69120641BF044A5A6054 -:1034A00002F188325A6008BD482500200020024001 -:1034B0002301674508B5054B1B7833B9FFF7DAFFE1 -:1034C000034A136943F08003136108BD48250020B7 -:1034D000002002407F289ABF00F5003080020020C3 -:1034E000704700004FF480607047000080207047F4 -:1034F0007F2808B50BD8FFF7EDFF00F58063026861 -:10350000013204D104308342F9D1012008BD0020EA -:10351000FCE700007F2810B504461CD8FFF7AAFF7F -:10352000FFF7B2FFF3220D4B4FF48061DA60022205 -:103530001A61FFF7CFFF58611A6942F040021A6121 -:10354000FFF798FF00F004F9FFF7B4FF2046BDE84D -:103550001040FFF7CDBF002010BD00BF002002408B -:103560002DE9F843054612F00100144606D040F25A -:10357000F32200201E4B1A60BDE8F8831D4BAA18E9 -:103580009A4204D94FF43E72194B1A60F4E7FFF7E0 -:103590007BFF4FF00109FFF76DFFDFF85C806D1ACC -:1035A000012C0F4605EB010603D8FFF783FF01202E -:1035B000E2E73B88C8F8109033800020FFF75AFFFD -:1035C000C8F81000338831F8022B9BB29A420CD015 -:1035D00040F20F32064B1A60084B1E60084B1C600D -:1035E000084B1F60FFF766FFC6E7023CD8E700BF45 -:1035F0004425002000000208002002403825002059 -:10360000402500203C250020084908B50B7828B14A -:103610001BB9FFF739FF01230B7008BD002BFCD04D -:10362000BDE808400870FFF745BF00BF48250020EF -:1036300070B5FFF739FE4FF47A710D4B0D4EDB6913 -:10364000326801FB03F3934237BF0B4A0A495168C2 -:10365000156836BF4C1CD1E9005454605D1944F123 -:1036600000043360FFF72AFE2846214670BD00BFE4 -:10367000D82300204C2500205025002070B5FFF7EE -:1036800013FE4FF47A710F4B0F4EDB69326801FB6A -:1036900003F3934237BF0D4A0C49516815683ABF8E -:1036A0004C1C5460D1E900545D1944F100043360AE -:1036B000FFF704FE4FF47A72002328462146FCF7F8 -:1036C00031FF70BDD82300204C250020502500205C -:1036D00010B5094C013AD2B2FF2A00D110BD5008F2 -:1036E00054F82030013054F820009BB243EA0043E4 -:1036F00041F8043BEEE700BF046C004010B50748FA -:10370000013AD2B2FF2A00D110BD0C88530840F80C -:1037100023404C88013340F82340F1E7046C00401B -:1037200007B50122002001A9FFF7D2FF019803B0DD -:103730005DF804FB13B50446FFF7F2FFA04205D085 -:103740000122002001A90194FFF7D8FF02B010BDAB -:103750007047000045F25552064B1A6002225A602B -:1037600040F6FF729A604CF6CC421A600122024B7E -:103770001A707047003000405C250020034B1B7816 -:103780001BB14AF6AA22024B1A6070475C25002042 -:1037900000300040044B1A682AB902F1804202F559 -:1037A0000432526A1A607047582500204FF0807228 -:1037B000014B5A62704700BF0010024008B5FFF786 -:1037C000E9FF024B1868C0F3407008BD582500207F -:1037D00008B5FFF7DFFF024B1868C0F3007008BDA3 -:1037E00058250020EFF30983203383F30988002351 -:1037F00083F3118870470000302080F3118862B68F -:103800000C4B0D4AD96821F4E0610904090C0A4304 -:10381000DA60D3F8FC20094942F08072C3F8FC203A -:103820000A6842F001020A602022DA7783F8220057 -:10383000704700BF00ED00E00003FA05001000E053 -:10384000302310B583F311880B4B5B6813F40063CE -:103850000FD0EFF309844FF08073203CE36184F3D1 -:103860000988FFF7DDFC10B1044BA36110BD044BC8 -:10387000FBE783F31188F9E700ED00E02F0900086A -:103880003209000870470000FEE700000A4B0B48B1 -:103890000B4A90420BD30B4BC11EDA1C121A22F0BA -:1038A00003028B4238BF00220021FDF7FFBE53F810 -:1038B000041B40F8041BECE7343E0008E025002020 -:1038C000E0250020E0250020FEE7000070B500257F -:1038D00004461A4B86B05860856201630E46FFF7B6 -:1038E0008BFF04F11003C4E904334FF0FF33A361ED -:1038F000134BE561D9692B460A462046C4E90823E3 -:1039000004F134018023C4E900440E4AA560E56255 -:103910002565FFF7E3FC01230B4AE0600375009285 -:10392000726868460192B268CDE90223074BCDE97F -:103930000435FFF7FBFC06B070BD00BF302500204A -:10394000D8230020BC3D0008C13D0008C93800084C -:1039500000F030B808B500F063F9FFF78DFCBDE862 -:103960000840FFF717BF0000704700004FF0FF311D -:103970000E4B1A6919611A6900221A611869D86810 -:10398000D960D968DA60DA68DA6942F08052DA61BF -:10399000DA69DA6942F00062DA61054ADB691368C4 -:1039A00043F48073136000F01BB900BF00100240A5 -:1039B00000700040194B1A6842F001021A601A6840 -:1039C0009007FCD51A6802F0F9021A6000225A60CA -:1039D0005A6812F00C0FFBD11A6842F480321A6058 -:1039E0001A689103FCD55A6842F4E8125A601A68C2 -:1039F00042F080721A601A689201FCD51221084ABE -:103A00005A60084A11605A6842F002025A605A68C5 -:103A100002F00C02082AFAD1704700BF00100240E1 -:103A200000641D0000200240084A08B5516913686F -:103A30000B4003F00103536123B1054A13680BB136 -:103A400050689847BDE80840FFF7FABE00040140FF -:103A500060250020084A08B5516913680B4003F03F -:103A60000203536123B1054A93680BB1D0689847AC -:103A7000BDE80840FFF7E4BE0004014060250020D7 -:103A8000084A08B5516913680B4003F004035361F9 -:103A900023B1054A13690BB150699847BDE8084046 -:103AA000FFF7CEBE0004014060250020084A08B59B -:103AB000516913680B4003F00803536123B1054AB1 -:103AC00093690BB1D0699847BDE80840FFF7B8BECD -:103AD0000004014060250020084A08B551691368B8 -:103AE0000B4003F01003536123B1054A136A0BB175 -:103AF000506A9847BDE80840FFF7A2BE00040140A5 -:103B000060250020174B10B55A691C68144004F456 -:103B100078725A61A30604D5134A936A0BB1D06A2E -:103B20009847600604D5104A136B0BB1506B984749 -:103B3000210604D50C4A936B0BB1D06B9847E20574 -:103B400004D5094A136C0BB1506C9847A30504D5F2 -:103B5000054A936C0BB1D06C9847BDE81040FFF755 -:103B60006FBE00BF00040140602500201A4B10B555 -:103B70005A691C68144004F47C425A61620504D5F9 -:103B8000164A136D0BB1506D9847230504D5134A9F -:103B9000936D0BB1D06D9847E00404D50F4A136EB6 -:103BA0000BB1506E9847A10404D50C4A936E0BB12B -:103BB000D06E9847620404D5084A136F0BB1506F5A -:103BC0009847230404D5054A936F0BB1D06F9847EB -:103BD000BDE81040FFF734BE00040140602500201E -:103BE000062108B50846FFF721FA06210720FFF74E -:103BF0001DFA06210820FFF719FA06210920FFF710 -:103C000015FA06210A20FFF711FA06211720FFF7FF -:103C10000DFABDE8084006212820FFF707BA00008A -:103C200008B5FFF7A3FE054800F00CF8FFF71CFAF3 -:103C3000FFF79AFEBDE8084000F002B8C83D000852 -:103C400000F042B8002319461C4A0133102BC2E988 -:103C5000001102F10802F8D1194B9A6942F07D0275 -:103C60009A619B690268174BDA6082685A60426801 -:103C70001A60C26803F58063DA6042695A600269BB -:103C80001A608269C3F80C24026AC3F80424C2696A -:103C9000C3F80024426AC3F80C28C26AC3F8042897 -:103CA000826AC3F80028026BC3F80C2C826BC3F83D -:103CB000042C426BC3F8002C704700BF6025002025 -:103CC00000100240000801404FF0E023044A0821A0 -:103CD0005A6100229A6107220B201A61FFF7BCB9D2 -:103CE0003F19010008B5302383F31188FFF7DAFA92 -:103CF000002383F3118808BD08B5FFF7F3FFBDE883 -:103D00000840FFF79DBD000010B501390244904204 -:103D100001D1002005E0037811F8014FA34201D042 -:103D2000181B10BD0130F2E72DE9F0419BB10446AC -:103D3000C91A1778014403F1FF3C8C42204601D98F -:103D4000002008E005780134BD42F6D10CEB0405F3 -:103D5000D618A54201D1BDE8F08115F8018D16F8FD -:103D600001EDF045F5D0E8E7034611F8012B03F823 -:103D7000012B002AF9D170476F72672E617264754A -:103D800070696C6F742E663130332D52616E6765C9 -:103D900046696E646572000040A2E4F164689106B1 -:103DA0000041A3E5F265699207000000633000005E -:103DB000AC3D000830240020302500206D61696E84 -:103DC0000069646C65000000001800004444414430 -:103DD000445449440100000042444444444444449F -:103DE00000000000444444444444444400000000B3 -:103DF0004444444444444444000000004444444493 -:103E00004444444450C7FF7F01000000000000000C -:103E1000E803000000000000009C0100000000001A -:103E2000640000000000000040420F00FE2A010074 -:043E3000D2040000B8 +:10052000704700BF02E000F000F8FEE772B6264810 +:1005300080F30888254880F3098825482549086004 +:10054000022080F31488BFF36F8F03F025F803F0C7 +:1005500089F84FF0553020491B4A91423CBF41F881 +:10056000040BFAE71D49194A91423CBF41F8040BBC +:10057000FAE71B491B4A1C4B9A423EBF51F8040B39 +:1005800042F8040BF8E700201849194A91423CBF91 +:1005900041F8040BFAE703F003F803F065F8154C93 +:1005A000154DAC4203DA54F8041B8847F9E700F014 +:1005B0003FF8124C124DAC4203DA54F8041B884742 +:1005C000F9E702F0EBBF0000000900200011002055 +:1005D0000000000808ED00E00001002000090020F4 +:1005E000183B0008001100202411002028110020D1 +:1005F000D4250020600100086001000860010008A7 +:10060000600100082DE9F04FC1F80CD0C3689D4689 +:10061000BDE8F08F002383F311882846A04700200F +:1006200002F0E6FCFEE702F07FFC00DFFEE70000E0 +:10063000F8B500F03BFE02F0FDFE074602F048FF71 +:10064000064600283ED12B4B9F423BD001339F42B0 +:100650003BD0294B27F0FF029A4239D1F8B200F083 +:1006600001FC354642F2107400F002FC08B100248F +:10067000254601F003F978B30024032000F042F886 +:10068000254636B11D4B9F4203D0002402F018FFCF +:100690002546002002F0D8FE194B9B6813F040035A +:1006A0001FD00DB100F044F800F042FC01F07AF9DF +:1006B0000546C4B101F076F9401BA04213D900F001 +:1006C00037F8F3E735460024CEE704460125CBE7AB +:1006D00005464FF47A74C7E7B4F57A7F08BF012561 +:1006E000CFE71C46E0E700F0D5FC012002F086FCD5 +:1006F000DFE700BF010007B0000008B0263A09B0EC +:10070000000C0140084B187003280CD8DFE800F0FB +:1007100008050208022000F025BE022000F01ABEE3 +:100720000022024B5A607047281100202C11002033 +:1007300038B501F0A3F830B103221F4B1A70002224 +:100740001E4B5A6038BD1E4B1E4A19680131F9D044 +:1007500004339342F9D11C4C194DD4F80424AA4215 +:10076000F0D31A4B9B6803F1006303F5C8439A4228 +:10077000E8D202F079FE02F08BFE002000F0B0FD1E +:100780000220FFF7BFFF124BDA690022DA61D96954 +:1007900099699A619B6972B64FF0E023C3F8085DCE +:1007A0003021D4F80034D4F8042481F311889D4614 +:1007B00083F308881047C5E7281100202C1100207A +:1007C0000064000820640008006000080011002098 +:1007D0000010024049F26900084A136899B21B0CE4 +:1007E00000FB013344F250611360054B186882B27C +:1007F000000C01FB0200186080B27047201100203D +:100800001C11002010B504460021102200F0C6FD86 +:10081000034B03CB206061601868A06010BD00BF6F +:10082000E8F7FF1F2DE9F0410026ADF5507D6EACD5 +:1008300040F2751207460D4610A831460F9600F09B +:10084000ADFD4FF4C4723146204600F0A7FD01F023 +:10085000A9F84FF47A72B0FBF2F0264B0DF13C0888 +:10086000186093E80700022384E807000DF5ED7097 +:100870002382FFF7C7FF4EF603031F4907A823840F +:1008800003F0FCF81E230DF2EB2284F832310DF157 +:10089000340C07AB1E4603CE6645106051603346EC +:1008A00002F10802F6D1306841461060B388204654 +:1008B0009380012200F0BEFD00230393AB7E80B243 +:1008C000029305F1190301930123CDE904800093FC +:1008D000384606A3D3E90023E97E01F0A9FB0DF514 +:1008E000507DBDE8F08100BFAFF300809E6AC42157 +:1008F000818A46EE341100208C3A00082DE9F0413F +:10090000264D80462B7A0C46DAB0FBB9204627A943 +:1009100000F0A0FE0746002836D19DF89D60C82E45 +:1009200032D801464FF4FA72284600F037FD3246BD +:100930000DF19E0105F1090000F01EFD9DF89C30AF +:100940002E4477722B720BB9E37E2B728122002129 +:1009500006AD27A800F022FD0122294627A800F0B5 +:10096000B5FE00230393A37E80B2029304F1190322 +:1009700001932823CDE904500093404605A3D3E911 +:100980000023E17E01F054FB5AB0BDE8F08100BFC6 +:10099000AFF3008026417272DF25D7B77C2100209B +:1009A000F0B54FF48A750024234EF1B005FB0065C5 +:1009B00096F8D830D822214685F8DC3085F8E84012 +:1009C0003AA800F0EBFC06F1090000F0DFFCD5F8D6 +:1009D000E430C2B206AF8DF8F00006F109010DF166 +:1009E000F100CDE93A3400F0C7FC394601223AA8BB +:1009F00000F098FE80B2CDE9047008230127CDE90C +:100A0000023706F1D80301933023317A00930B4863 +:100A100007A3D3E9002301F00BFBA04206DD00F0A1 +:100A2000C1FFC5F8E000384671B0F0BD2046FBE7D5 +:100A300078F6339F93CACD8D7C2100204C21002075 +:100A4000F0B51E4E1E4F1F4D85B0304601F01CFB09 +:100A5000044660B310220021684600F09FFC4FF06E +:100A60000003227B6068A16862F303038DF8003005 +:100A700002AB03C3019B2268384662F31C03019357 +:100A80009DF800306A4643F020038DF800300023C3 +:100A9000194602F085F9044620B9304601F0F8FA0B +:100AA0002C70D2E72B78072B03D801332B7005B0BD +:100AB000F0BD024801F0ECFAF9E700BF4C2100203C +:100AC000A82300207523002070B50D4614461E464D +:100AD00001F00AFA50B9022E10D1012C0ED112A346 +:100AE000D3E900230120C5E9002307E0282C10D01A +:100AF00005D8012C09D0052C0FD0002070BD302C5A +:100B0000FBD10BA3D3E90023ECE70BA3D3E900232C +:100B1000E8E70BA3D3E90023E4E70BA3D3E9002321 +:100B2000E0E700BFAFF30080401DA12026812A0B23 +:100B300078F6339F93CACD8D9E6AC421818A46EE92 +:100B400026417272DF25D7B7F017304A39059E5615 +:100B500038B505460E4C0021013500F0E3FBA4F842 +:100B6000F051B4F8F00100F0C5FB78B1B4F8F00131 +:100B700000F0D0FB014648B9B4F8F00100F0D2FB18 +:100B8000B4F8F0310133A4F8F031EAE738BD00BF22 +:100B90007C2100202DE9F04F8DB000AF04460D46BA +:100BA00001F0A2F9002846D12B7E022B1AD1EB8A44 +:100BB000012B17D100F0F6FE0646FFF70BFE4FF4AF +:100BC000C873B0FBF3F202FB1303DFF878829BB229 +:100BD00006F516763344C8F80030EB7E33B90022B0 +:100BE000994B1A703437BD46BDE8F08F284607F19F +:100BF0001C0100F0EDFC0028F4D107F10C00FFF718 +:100C000001FEBD7F07F10C012A4607F11F0002F02B +:100C100005FF0028E3D10F2D08D88B4B1D70D8F8A5 +:100C20000030A3F51673C8F80030DBE72046397FA3 +:100C300001F052F9D6E7EB8A282B6BD010D8012BA4 +:100C400063D0052BCED1BFF34F8F8049804BCA684C +:100C500002F4E0621343CB60BFF34F8F00BFFDE7A8 +:100C6000302BBFD17B4CEA7E237A9A42BAD194F8DA +:100C7000DC206B7E9A42B5D1284604F1EA0100F0EF +:100C80007DFD06460028ADD1012384F8E83000F050 +:100C900089FED4F8E030C01A192840F6B83338BFBE +:100CA0001920984228BF1846FFF7C4FB6A49FFF78E +:100CB00057FA05462068FFF7BDFB6849FFF750FA71 +:100CC00001462846FFF706FBFFF70CFC20604FF4B7 +:100CD0008A7194F8D9307B607A68636801FB02F509 +:100CE000621992F8E80050B1D2F8E400E946834274 +:100CF00015D0002382F8E830C2F8E030CD466368B2 +:100D0000574A9B0A013313816CE729462046FFF7B7 +:100D100089FD67E729462046FFF7F0FD62E7B2F854 +:100D2000EC803B6008F1030A4FEA9A0A4FEA8A0214 +:100D3000D11DC908A9EBC1039D46EB4600215846C9 +:100D400000F02CFB05F1EE0142465846214400F02C +:100D500013FB3B6813B9012000F0C2FA94F8D200EB +:100D600000F0C8FA054630B9207200F0E3FA2846D0 +:100D700000F0B6FAC2E7D4F8D4303BB994F8D20008 +:100D8000B4F8F031834201D8FFF7E2FED4F8D43052 +:100D900043449D4208D294F8D200B4F8F0310130B7 +:100DA000834201D8FFF7D4FE594660685FFA8AF2A1 +:100DB00000F0FCFA08B9CD4689E7636894F8D200E0 +:100DC00043446360D4F8D43008EB030AC4F8D4A0D9 +:100DD00000F090FA824509D394F8D230D4F8D400C8 +:100DE0000133401B84F8D230C4F8D400B8F1FF0FAF +:100DF0000FD80025257200F09DFA284600F070FA01 +:100E000000F03CFD164B188108B9FFF791FCCD4668 +:100E1000E8E64FF48A727B6894F8D90002FB03433A +:100E2000D3F8E42083F8E86002F58072C3F8E0604C +:100E3000C3F8E420FFF7B4FDFFF702FE84F8D960A1 +:100E4000B9E700BF482100204521002000ED00E067 +:100E50000400FA057C210020CDCCCC3D6666663FBF +:100E600034110020014B1870704700BF4011002062 +:100E700030B54FF00054254B226885B09A4207D018 +:100E800002F030FB0446C0B90024204605B030BD56 +:100E90000025627D1E4B1F481A70237DC9220372F4 +:100EA0001D49C0F8E450093000F066FA2046E022FF +:100EB000294600F073FA0124E7E7184A184DD36970 +:100EC00043F00073D361AA6D164B9A42DCD12B6EAE +:100ED000013B7E2BD8D8144A01AB07CA83E8070030 +:100EE0001846032100F09AFC6B6D83424FF000031B +:100EF000CAD12A6D8A4203BFAB652A6E044B1C46D9 +:100F000001BF1A70EA6D094B1A60BEE79AAD44C57D +:100F1000401100207C21002016000020001002401B +:100F2000006600405041A0B05866004018110020F3 +:100F30002DE9F04385B000F0A1FC0223494C637118 +:100F400000230293484B2081D3F800C0BCF57A7F80 +:100F500012D3464F464BB7FBFCF59C458CBF0A238A +:100F60001123B5FBF3F603FB1652591EC8B2002A33 +:100F70003ED002290B46F4D89DF80B303D495A1E4D +:100F80009DF80A303C48013B1B0443EA0253BDF87C +:100F90000820013A13434B6001F0F2FE0023019355 +:100FA000364B374900934FF48052364B364800F0A9 +:100FB00069FF364B197811B1334800F08DFF00F00E +:100FC000F1FC0546FFF706FC4FF4C873B0FBF3F2E3 +:100FD00002FB130305F516709BB218442C4B1860E6 +:100FE00002F076FA08B10F23238105B0BDE8F08343 +:100FF000731EB3F5806FBFD24FF47A75C0EBC00E8D +:101000000EF103034FEAE30909FB0555C3F3C703D8 +:10101000C11AC9B209F101088844B5FBF8F5B5F564 +:10102000617F08D90EF1FF33C3F3C703C11A581EFD +:101030000F28C9B214D84A1E072A8CBF00220122E9 +:10104000581800FB0660B7FBF0F7BC4594D1002AA6 +:1010500092D0ADF808608DF80A308DF80B108BE750 +:101060001346EDE73411002018110020005125022D +:101070003F420F0010110020A8230020C90A0008D9 +:1010800044110020950B00084C2100204011002045 +:10109000482100202DE9F04F80A7D7E900670FF223 +:1010A0000429D9E90089734D93B00DF1300AFFF797 +:1010B000C7FC18220021504600F070F9DFF8B8B1E3 +:1010C0006E4C002352461946584601F091FE0146E7 +:1010D00050BB102208A800F061F9E36883F0100308 +:1010E000E36000F061FC0DF1240C0B4612A90246EE +:1010F00011E903008CE803009DF83410C1F30300EC +:10110000890649BF0E99BDF83810C1F31C0141F0A2 +:10111000004158BFC1F30A018DF82C000891284600 +:1011200008A901F095F9CCE7284600F0DDFE044659 +:10113000002847D100F036FCDFF844B1DBF800307E +:1011400098423FD300F02EFC0790FFF743FB4FF48B +:10115000C873B0FBF3F101FB1300079A83B202F5E9 +:1011600016701844CBF80000DFF818B18DF8204055 +:101170009BF8001011B901238DF8203050460791DB +:10118000FFF740FB07990DF12100C1F11004E4B213 +:10119000062C28BF06245144224600F0EDF808AB87 +:1011A000039318230293384B013401930123E4B2D3 +:1011B000009332463B462846049400F0DBFE0023B1 +:1011C0008BF8003000F0EEFB304A314C1368C31A44 +:1011D000B3F57A7F30D3106000F0E6FB02460B4691 +:1011E000284600F05FFF284600F07EFE20B3237AF9 +:1011F000DFF8A0B0002B14BF032302238BF80530C7 +:1012000000F0D0FB4FF47A73B0FBF3F00122CBF87F +:1012100000005146584600F0B3F9182302931E4BC4 +:1012200080B2019340F25513CDE903A000934246EA +:101230004B46284600F09EFE237ABBB100F0B2FB7D +:1012400094F8E83073B9D4F8E03043B1C01A236899 +:10125000FA2B38BFFA230533B0EB430F02D300203B +:10126000FFF79EFB237A002B7FF41FAF13B0BDE87E +:10127000F08F00BF4C210020A8230020000801406F +:101280004821002045210020442100207023002017 +:101290007C2100203411002074230020401DA12057 +:1012A00026812A0BF1C6A7C1D068080F70B501F0DE +:1012B0007DFF0024084E094D308028683388834222 +:1012C00008D901F06FFF2B6804440133B4F5C84F0F +:1012D0002B60F2D370BD00BFA42300207823002030 +:1012E00001F0F2BF00F10060920000F5C84001F08B +:1012F00097BF0000054B1A68054B1B889B1A834259 +:1013000002D9104401F04EBF00207047782300201E +:10131000A4230020024B1B68184401F049BF00BF02 +:1013200078230020024B1B68184401F053BF00BF14 +:1013300078230020064991F8243033B10023082295 +:10134000086A81F82430FFF7CDBF0120704700BF45 +:101350007C230020022802BF1022014B1A61704733 +:1013600000080140022802BF4FF48012014B1A61AD +:10137000704700BF00080140002310B5934203D01E +:10138000CC5CC4540133F9E710BD000003460246AB +:10139000D01A12F9011B0029FAD170470346024402 +:1013A000934202D003F8011BFAE770472DE9F84396 +:1013B0001F4D144695F824200746884652BBDFF897 +:1013C00070909CB395F824302BB92022FF21484619 +:1013D0002F62FFF7E3FF95F824004146C0F10802B1 +:1013E000A24228BF224605EB8000D6B29200FFF74A +:1013F000C3FF95F82430A41B1E44F6B2082E1744F0 +:101400009044E4B285F82460DBD1FFF793FF002815 +:10141000D7D108E02B6A03EB82038342CFD0FFF7DA +:1014200089FF0028CBD10020BDE8F8830120FBE72D +:101430007C2300202DE9F0470D460446002190460C +:10144000284640F27912FFF7A9FF23462022002107 +:10145000284600F09FFF022220212846231D00F08D +:1014600099FF032222212846631D00F093FF0322E7 +:1014700025212846A31D00F08DFF10222821284693 +:1014800004F1080300F086FF08223821284604F101 +:10149000100300F07FFF08224021284604F11103C9 +:1014A00000F078FF08224821284604F1120300F0DA +:1014B00071FF20225021284604F1140300F06AFF36 +:1014C00040227021284604F1180300F063FF08222F +:1014D000B021284604F1200300F05CFF0822B82167 +:1014E000284604F1210300F055FFC02604F122072D +:1014F0003B46314608222846083600F04BFFB6F539 +:10150000A07F07F10107F3D108223146284604F1F4 +:10151000320300F03FFF002704F1330A94F8323021 +:101520004FEAC7099F4209F5A47615D3B8F1000F19 +:1015300008D131460722284604F5997300F02AFFA6 +:1015400009F24F16274694F832213B1B93420CD3E5 +:10155000F01DC008BDE8F0870AEB070308223146FA +:10156000284600F017FF0137D8E7314607F233135A +:101570000822284600F00EFF08360137E3E7000096 +:1015800038B50C460021054621600346C4F8031017 +:101590002046202200F0FEFE20462B1D02222021A4 +:1015A00000F0F8FE20466B1D0322222100F0F2FE1F +:1015B0002046AB1D0322252100F0ECFE2046102220 +:1015C000282105F1080300F0E5FE072038BD0000E2 +:1015D0000023F7B50E460546047F07220091194601 +:1015E00000F09AFD731C0093012200230721284676 +:1015F00000F092FDC4B9B31C0093052223460821D4 +:10160000284600F089FD0D243746B278BB1B934273 +:1016100011D32B7FE01DC008AC8ABBB9A04294BF98 +:101620000020012003B0F0BDAB8A0824DB00083B9A +:10163000DB08B370E8E7FB1C214600930822002377 +:10164000284600F069FD08340137DEE7001B18BFAB +:101650000120E7E70023F7B50E46047F082200913A +:101660001946054600F058FD731CC4B908220093C2 +:1016700011462346284600F04FFD102401237278BE +:101680005F1C013B934211D32B7FE01DC008AC8A45 +:10169000BBB9A04294BF0020012003B0F0BDAB8ACB +:1016A0000824DB00083BDB087370E7E7F3192146E9 +:1016B000009308220023284600F02EFD08343B4604 +:1016C000DDE7001B18BF0120E7E70000F8B50E4674 +:1016D00005461446002181223046FFF75FFE2B4667 +:1016E00008220021304600F055FE7CB9072208216F +:1016F00030466B1C00F04EFE0F2401236A785F1CFD +:10170000013B934204D3E01DC008F8BD0824F4E770 +:101710002146EB190822304600F03CFE08343B46D7 +:10172000ECE70000F8B50E46054614460021CE222F +:101730003046FFF733FE2B4628220021304600F0CA +:1017400029FE7CB908222821304605F1080300F063 +:1017500021FE30242F462A7A7B1B934204D3E01DBE +:10176000C008F8BD2824F5E7214607F1090308223F +:10177000304600F00FFE08340137ECE7F7B5047F80 +:101780000E460091012310220021054600F0C4FC02 +:10179000C4B9B31C0093092223461021284600F047 +:1017A000BBFC192437467288BB1B9A4211D82B7F89 +:1017B000E01DC008AC8ABBB9A04294BF0020012044 +:1017C00003B0F0BDAB8A1024DB00103BDB08738054 +:1017D000E8E73B1D2146009308220023284600F03D +:1017E0009BFC08340137DEE7001B18BF0120E7E748 +:1017F00030B5094D0A4491420DD011F8013B5840D3 +:10180000082340F30004013B2C4013F0FF0384EA5B +:101810005000F6D1EFE730BD2083B8ED4FF0FF3335 +:10182000F7B500EB81061946DFF848C0DFF848E05D +:10183000B0421BD050F8042B01AF0192042217F8DC +:10184000014B81EA046108240D46DB184941013C43 +:10185000002DBCBF83EA0C0381EA0E0114F0FF04E3 +:10186000F2D1013A12F0FF02E9D1E1E7D843C943CE +:1018700003B0F0BD9336EAA9EBE1F042F7B56B4651 +:10188000354A106851686A4603C30823334934480F +:1018900002F0D4F8044690BB0A256B46314A106822 +:1018A00051686A4603C308232F492D4802F0C6F841 +:1018B0000446002847D00369B3F5CE3F43D8B0F8BB +:1018C0006620B2F57A7F3ED1284A024402F15C01DB +:1018D0008B4238D35C3B224900209E1AFFF788FFD9 +:1018E00007463246002004F16401FFF781FFA36838 +:1018F0009F4228D1E368984208BF002523E003698E +:10190000B3F5CE3F26D8428BB2F57A7F20D1174A65 +:10191000024402F110018B4218D3103B1049002001 +:101920009D1AFFF765FF06462A46002004F11801BC +:10193000FFF75EFFA3689E4202D1E368984201D0A0 +:101940000D25AAE70025284603B0F0BD1025A4E721 +:101950000C25A2E70B25A0E7AC3A0008DC9B0100B0 +:1019600000640008B53A0008909B0100089CFFF74E +:10197000EFF30983EFF30583014B9B6BFEE700BF99 +:1019800000ED00E008B5FFF7F3FF0000EFF3098377 +:10199000EFF30583014B5B6BFEE700BF00ED00E05A +:1019A000FEE7000001F0F6BC01F0A2BC2DE9F04119 +:1019B000456A15B94162BDE8F0814B68AC4623F039 +:1019C0006047C3F38A4616EA230638BF3E464FEA0D +:1019D000D37EC3F380782B465A68BEEBD27F22F0C9 +:1019E00060440AD0002A18DAA40CB44217D19D42F0 +:1019F0000FD10D60DEE71346EEE7A74207D102F0F4 +:101A00008044C2F3807242450BD054B1EFE708D254 +:101A1000EDE7CCF800100B60CDE7B44201D0B44242 +:101A2000E5D81A689C46002AE5D11960C3E7000092 +:101A30002DE9F0474FF47F49089D01F007044FEA74 +:101A4000D508224405F0070500EBD100944201D1EE +:101A5000BDE8F08704F0070705F0070A57453E4642 +:101A600038BF5646111BC6F108068E4228BF0E46E7 +:101A7000E108415C08EBD50E13F80EC0B94029FA15 +:101A800006F721FA0AF1FFB28CEA010147FA0AF7D8 +:101A900039408CEA010C03F80EC034443544D5E7D4 +:101AA000082341F2210280EA012001B2400000290E +:101AB00080B203F1FF33B8BF504013F0FF03F4D1FD +:101AC0007047000038B50C468D18A54200D138BDCE +:101AD00014F8011BFFF7E4FFF7E700000346406836 +:101AE00048B1026899895A605A89013292B291428A +:101AF0005A8138BF9A81704770B504460D4688B048 +:101B0000202200216846FFF749FC20460495FFF794 +:101B1000E5FF024658B16B46054608AE1C4603CCAD +:101B2000B44228606960234605F10805F6D11046E5 +:101B300008B070BD082817D909280CD00A280CD085 +:101B40000B280CD00C280CD00D280CD00E2814BF5C +:101B50004020302070470C20704710207047142020 +:101B6000704718207047202070470000082817D9B8 +:101B70000C280CD910280CD914280CD918280CD9E9 +:101B800020280CD930288CBF0F200E207047092048 +:101B900070470A2070470B2070470C2070470D20BB +:101BA000704700002DE9F843078C0446072F1ED923 +:101BB000D0E9029800254FF6FF73C5F12006A5F184 +:101BC000200029FA05F108FA06F628FA00F0314358 +:101BD0000143C9B21846FFF763FF0835402D03469D +:101BE000EBD13A46E169BDE8F843FFF76BBF4FF62A +:101BF000FF70BDE8F883000010B54B6823B9CA8AAE +:101C000063F30902CA8210BD04691A681C6003618B +:101C1000C38A013BC3824A60EFE700002DE9F84F19 +:101C20001D46CB8A0F46C3F309010529814692461A +:101C30000B4630D00020AAB207F11A049EB2042E3F +:101C40001FFA80F80FD8904503F1010306D3FB8AF1 +:101C50000A4462F309030120FB821AE01AF80060CB +:101C60000130E654EAE79045F1D21C23A1F1050BBF +:101C7000BBFBF3F203FB12BB7C681FFA8BF6002C54 +:101C800045D14846FFF72AFF044638B978606FF01F +:101C90000200BDE8F88F4FF00008E6E70026066076 +:101CA00078604FF0000BADB2454510D90AEB080340 +:101CB000221D13F8011B08F101089155B1B21B292F +:101CC0001FFA88F82BD0454506F10106F1D8FB8AAA +:101CD000C3F30902154465F30903BCE71C4601324E +:101CE00092B22368002BF9D16B1F0B441C21B3FB6C +:101CF000F1F301339BB29A42D3D2BBF1000FD0D1A2 +:101D00004846FFF7EBFE20B9C4F800B0BFE7012258 +:101D1000E7E7C0F800B05E4620600446C1E74545ED +:101D2000D5D94846FFF7DAFE08B92060AFE7C0F81A +:101D300000B0002620600446B6E700002DE9F74F0A +:101D40001C465B69074688460092002B00F097808E +:101D5000238C2BB1E269002A00F09180072B33D845 +:101D600007F10C00FFF7BAFE054628B96FF002052F +:101D7000284603B0BDE8F08F14220021FFF70EFBC8 +:101D8000228CE16905F10800FFF7F6FA208C48F093 +:101D90000041013080B2FFF7E9FEFFF7CBFE0138CA +:101DA00080B22084013028746369228C1B782A4415 +:101DB00003F01F0363F03F0313723846696029463E +:101DC000FFF7F4FD0125D3E74FF000094FF0800A3B +:101DD0004E464D4600F10C0301930198FFF77EFE3D +:101DE00083460028C2D014220021FFF7D7FA002E24 +:101DF0003BD10222009BABF808300BF1080E1FFA12 +:101E000082FC0CF10100BCF1060F218C80B201D8DC +:101E10008E422CD3FFF7AAFEFFF78CFE8E4208BF3E +:101E20004FF0400A62690138127880B202F01F0256 +:101E300042EA49120BEB00014AEA020A013048F07B +:101E4000004281F808A08BF8100059463846CBF8BC +:101E50000420FFF7ABFD238C0135B3424FF0000A9D +:101E60002DB289F00109B8D182E70022C5E7E16906 +:101E7000895D01360EF80210B6B20132BFE76FF08D +:101E8000010575E7F8B5044615460E4630220021D7 +:101E90001F46FFF783FA069BB5F5001F6360079B9B +:101EA00028BF4FF6FF72A3624FF0000338BF6A09E4 +:101EB000A760E66197B204F110009A4206D80023A9 +:101EC0000360A782E3822383E360F8BD06600133E9 +:101ED00030462036F1E7000003781BB94BB2002BE7 +:101EE000C8BF01707047000000787047F8B50C4615 +:101EF000C969074611B9238C002B37D1257E1F2DC8 +:101F000034D8387828BB228C072A2CD8268A36F079 +:101F100003032BD14FF6FF70FFF7D4FD4FF6FF728E +:101F200020F001003602400446EA0565400C45EA0F +:101F30004025234629463846FFF700FF002807DDE5 +:101F4000626913780133DBB21F2B88BF0023137043 +:101F5000F8BD218A2D0645EA012505432046FFF7F5 +:101F600021FE0246E5E76FF00300F1E76FF00100A4 +:101F7000EEE7000070B504461D4616468AB02822DA +:101F800000216846FFF70AFABDF838306946ADF817 +:101F900010300F9B204605939DF84030CDE9026537 +:101FA0008DF81830119B0793BDF84830ADF82030FC +:101FB000FFF79CFF0AB070BD2DE9F041D3690546DB +:101FC0000C4616460BB9138C5BBB377E1F2F28D8E7 +:101FD00095F80080B8F1000F26D03046FFF7E2FDFB +:101FE0003378210241EAC33141EA0801338A41EAE8 +:101FF000076141EA034102463346284641F0800129 +:10200000FFF79CFE00280ADD3378012B07D17269A7 +:1020100013780133DBB21F2B88BF00231370BDE898 +:10202000F0816FF00100FAE76FF00300F7E70000BE +:10203000F0B504460D461E4617468BB028220021F7 +:102040006846FFF7ABF99DF84C3029465A1E5342BB +:1020500053418DF800309DF840306A46ADF810309D +:10206000119B204605939DF84830CDE902768DF806 +:102070001830149B0793BDF85430ADF82030FFF7AB +:102080009BFF0BB0F0BD0000406A00B10430704708 +:10209000436A1A68426202691A600361C38A013B9B +:1020A000C38270472DE9F041D0F8208014461D46C8 +:1020B00041460027174E09B9BDE8F081D1E9022356 +:1020C000A21A65EB0303964277EB03031ED2036A61 +:1020D0008B420DD1FFF790FD036A1B680362036911 +:1020E0000B60C38A0161016A013B8846C382E2E753 +:1020F000FFF782FD0B68C8F8003003690B60C38AE4 +:102100000161013BC382D8F80010D4E78846096812 +:10211000D1E700BF80841E002DE9F04F8BB00D4643 +:1021200014469B468046DDF85090002800F01A8146 +:10213000B9F1000F00F01681531E3F2B00F21281FF +:10214000012A03D1BBF1000F40F00C810023CDE93F +:102150000833B8F81430B5EBC30F4FEAC30703D305 +:1021600000200BB0BDE8F08F2B199F42D8F80C303F +:1021700036BF7F1B2746FFB21BB9D8F81030002BA3 +:102180007BD0272D4ED8C5F12806B7424FF000036B +:1021900034BF3E46F6B2009329463246D8F80800CE +:1021A00008ABFFF745FCA7EB060A35445FFA8AFA4D +:1021B0002821B8F8143003F10053053BDB000493E9 +:1021C000D8F80C300393039B13B1BAF1000F2CD154 +:1021D000D8F8100040B1BAF1000F05D05246009671 +:1021E00008AB691AFFF724FC38B2002FB8D0660795 +:1021F0000AD00AAB03EBD40111F8083C624202F0AA +:102200000702134101F8083C082C3DD9102C40F27C +:10221000B680202C40F2B880BBF1000F00F09D800A +:10222000082335E0BA460026C2E7049BE02B28BF0E +:10223000E02306930B44AB42059315D95A1B9245F4 +:1022400038BF5246039828BFD2B20096691A08AB2D +:1022500004300792FFF7ECFB079A1644AAEB020A38 +:102260001544F6B25FFA8AFA049B069A05999B1AFE +:102270000493039B1B680393A5E700933A46294602 +:10228000D8F8080008ABADE7BBF1000F13D001236D +:10229000B4EBC30F6CD0082C12D89DF82030621E0E +:1022A00023FA02F2D50706D54FF0FF3202FA04F402 +:1022B00023438DF820309DF8203089F8003050E716 +:1022C000102C12D8BDF82030621E23FA02F2D1077A +:1022D00006D54FF0FF3202FA04F42343ADF8203064 +:1022E000BDF82030A9F800303BE7202C0FD8089922 +:1022F000631E21FA03F3DA0705D54FF0FF3202FA25 +:1023000004F40C430894089BC9F8003029E7402CDA +:102310002BD0DDE90865611EC4F12102A4F121037F +:1023200026FA01F105FA02F225FA03F311431943E3 +:10233000CB0712D50122A4F12003C4F1200102FA37 +:1023400003F322FA01F1A240524243EA010363EB94 +:10235000430332432B43CDE90823DDE90823C9E9D0 +:102360000023FEE66FF00100FBE66FF00800F8E6E0 +:10237000082CA0D9102CB3D9202CEED8C3E7BBF180 +:10238000000FADD0022383E7BBF1000FBBD00423C5 +:102390007EE70000012A30B5144638BF012200252F +:1023A000402A28BF402285B0012CCDE9025517D81C +:1023B0001B788DF8083053070AD004AB03EBD20525 +:1023C00015F8083C544204F00704A34005F8083C03 +:1023D0000346009102A80021FFF72AFB05B030BD9B +:1023E000082CE5D9102C03D81B88ADF80830E2E79B +:1023F000202C02D81B680293DDE7D3E90045CDE924 +:102400000245D8E710B5CB681BB98B600B618B8296 +:1024100010BD04691A681C600361C38A013BC38252 +:10242000CA60F0E703064CBFC0F3C030022070471B +:1024300008B50246FFF7F6FF022806D15306C2F39D +:102440000F2001D100F0030008BDC2F30740FBE7F5 +:102450002DE9F04F93B0CDE903230A6804461046F6 +:10246000FFF7E0FF02280CBF0026C2F30626002A71 +:102470000D46824680F2F98112F0C04940F0F581A4 +:10248000097B002900F0F181022803D02378B342B0 +:1024900040F0EE81C2F304631046069302F07F031E +:1024A0000593FFF7C5FF059B00224FEA83480023F1 +:1024B00048EA0A48294448EA4668CE78CDE9082324 +:1024C000F309834648EA0008029367D0059B024659 +:1024D000009320465346676808A9B847002800F0D3 +:1024E000CA81276A4FB9414604F10C00FFF704FB8B +:1024F000074690B96FF0020054E03B6998450DD053 +:102500003F68002FF9D1414604F10C00FFF7F4FABF +:1025100007460028EED0236A3B60276297F817C071 +:1025200006F01F08CCF3840CACEB08001FFA80FE09 +:102530000028B8BF0EF12000A8EB0C031FFA83FEA1 +:10254000B8BF00B2002B0793BEBF0EF120031BB231 +:102550000793D7E9022152EA010338D04FF0000C6B +:10256000039BDFF8F8E19A1A049B63EB010196459F +:102570007CEB01032BD36B7B97F81AE0734519D1E1 +:10258000029B002B78D0012821DC7868F8B9DFF8AD +:10259000D0C1944570EB010316D337E0276A27B901 +:1025A0006FF00C0013B0BDE8F08F3B699845B5D0D3 +:1025B0003F68F4E76A4890427CEB010301D30020B6 +:1025C000F0E7029B002BFAD0079B0F2B17DCFA7D5C +:1025D000B30002F0030203F07C031343FB7539469A +:1025E0002046FFF709FB6B7BBB76029B3BB9FB7D6B +:1025F000C3F38402013262F38603FB75D0E76A7B82 +:10260000BB7E9A42DBD1029B002B35D0B309022B53 +:1026100032D0039B1422BB60049B0021FB600DA8F9 +:10262000FEF7BCFE039B20460A93049BADF83EB028 +:102630000B932B1D0C932B7B8DF840A0013BDBB241 +:10264000ADF83C30069B8DF841808DF84230059BFB +:102650000AA98DF8433094F82C3083F001038DF8EB +:102660004430A3689847FB7DC3F38403013303F030 +:102670001F039B02FB82A2E7FB7DC6F34012B2EB75 +:10268000D31F40F0FB80C3F38403434540F0F9803F +:10269000029A2B7BB609002A4DD0F20762D4032B95 +:1026A00040F2F280039BAE1DBB60049B3246FB6090 +:1026B0002B7B3946033BDBB204F10C00FFF7AEFA8B +:1026C00000280CDA39462046FFF796FAFB7DC3F363 +:1026D0008403013303F01F039B02FB820AE7AB88EC +:1026E000DDE908843B834FF6FF73C9F12000A9F1AF +:1026F000200228FA09F104FA00F0014324FA02F258 +:1027000011431846C9B2FFF7CBF909F10809B9F12D +:10271000400F0346E9D13146B8822A7B033AD2B250 +:10272000FFF7D0F9FB7DB882DA43C2F3C01262F33F +:10273000C713FB7543E7AEB92E1D013B3246394640 +:10274000DBB204F10C00FFF769FA0028BADB2A7B40 +:102750003146013AB88AD2B2E2E700BF80841E0057 +:1027600040420F00F98A013BC1F309010429DAB2A2 +:102770005DD80023281D07F11B069A4208D910F8DE +:1027800001CB013306F801C001310529DBB2F4D1D8 +:10279000934228BF0023039938BF04330A91049958 +:1027A00038BFDBB20B9107F11B010C91796838BF80 +:1027B0005B190D910E93FB8AADF83EB0C3F309038C +:1027C0001A44069BADF83C208DF84230059B8DF8ED +:1027D00040A08DF8433094F82C308DF8418083F080 +:1027E00001038DF8443000237B602A7BB88A013ACC +:1027F000291DFFF767F93B8BB882834203D120463E +:10280000A3680AA9984720460AA9FFF7FBFDFB7DAC +:10281000BA8AC3F38403013303F01F039B02FB82D4 +:102820003B8B9A420CBF00206FF01000BAE67B6829 +:10283000002BADD0052001E033461C301E68002E71 +:10284000FAD1091A081D2E1D184401EB090CBCF120 +:102850001B0F5FFA89F39BD89A4299D916F8013B6E +:1028600009F1010900F8013BEFE76FF0090099E673 +:102870006FF00A0096E66FF00B0093E66FF00D0024 +:1028800090E66FF00E008DE66FF00F008AE600BF55 +:10289000F0B53F4D3F4FEB6943F00073EB61EB69DF +:1028A0003D4B9B6AD3F800623E4046F00106C3F8F8 +:1028B0000062D3F800423C4044EA002444F00104A2 +:1028C000C3F80042002955D000200646C3F81C0278 +:1028D000C3F80402C3F80C02C3F8140203EBC004EB +:1028E00001300E28C4F84062C4F84462F6D10027D3 +:1028F0004FF0010C9678148816F0010F18BFD3F82A +:1029000004E20CFA04F01CBF40EA0E0EC3F804E225 +:1029100016F0020F18BFD3F80CE203EBC4041CBF7F +:1029200040EA0E0EC3F80CE2760748BFD3F81462F3 +:1029300007F1010744BF0643C3F814625668B94261 +:10294000C4F84062966802F10C02C4F84462D3F8FD +:102950001C4240EA0400C3F81C02CBD1D3F8002289 +:1029600022F00102C3F80022EB6923F00073EB614F +:10297000EB69F0BD0122C3F84012C3F84412C3F85A +:102980000412C3F81412C3F80C22C3F81C22E5E7A2 +:10299000001002400000FFFFA8230020184A08B5DD +:1029A000916A8B688B6013F0010104D013F00C0F57 +:1029B00018BF4FF48031D80506D513F4406F14BF0B +:1029C00041F4003141F00201D80306D513F4402F41 +:1029D00014BF41F4802141F00401D3690BB10848D0 +:1029E0009847302383F311880021064800F022FB2A +:1029F000002383F31188BDE8084000F0ABBD00BFA1 +:102A0000A8230020B023002038B5124CA36ADD684B +:102A1000AA0712D05A6922F002025A61A36913B1BF +:102A2000012120469847302383F3118800210A486A +:102A300000F000FB002383F31188EB0606D510217C +:102A4000A36AD960236A0BB102489847BDE83840B1 +:102A500000F080BDA8230020B823002038B5124C18 +:102A6000A36A1D69AA0712D05A6922F010025A619E +:102A7000A36913B1022120469847302383F31188BC +:102A800000210A4800F0D6FA002383F31188EB06F0 +:102A900006D51021A36A1961236A0BB10248984731 +:102AA000BDE8384000F056BDA8230020B823002020 +:102AB00038B50F4CA36A5D682A075D600AD5042209 +:102AC00022701A6822F002021A60636A13B10021B0 +:102AD000204698476B0706D5A36A9969236A13B104 +:102AE000034809049847BDE8384000F033BD00BFF3 +:102AF000A823002010B50E4C204600F02FF90D4BF6 +:102B00000B211320A36200F009F90B21142000F01F +:102B100005F90B21152000F001F90B21162000F01A +:102B2000FDF8BDE8104000220E201146FFF7B0BEB0 +:102B3000A8230020006400400F4B10B598420446C3 +:102B400005D10E4BDA6942F00072DA61DB690122CD +:102B5000A36A1A60A36A5A68D20707D562685168E7 +:102B60001268D9611A60064A5A6110BD0121082015 +:102B700000F0B0F9EEE700BFA823002000100240EB +:102B80005B87010003291AD8DFE801F0020A0F145D +:102B9000836A9B6813F0E05F14BF01200020704738 +:102BA000836A9868C0F380607047836A9868C0F34E +:102BB000C0607047836A9868C0F300707047002057 +:102BC0007047000010B5032927D8DFE801F002277D +:102BD0002B2F836A9968C1F30161183103EB01134C +:102BE0001078840648BF5468C0F3001158BF948819 +:102BF0004FEA410148BF41EAC40100F00F005860AC +:102C000048BF41F00401906858BF41EA4451D2687E +:102C100041F001019860DA60196010BD836A03F524 +:102C2000C073DDE7836A03F5C873D9E7836A03F5E8 +:102C3000D073D5E701290AD002290FD081B9836A60 +:102C4000DA68920701D1186903E001207047836AAE +:102C5000D86810F0030018BF01207047836AF2E7BC +:102C60000020704710B539B9836AD96889071BD12C +:102C70001B699C0704D110BD012915D00229FAD186 +:102C8000816AD1F8C031D1F8C441D1F8C8011061CE +:102C9000D1F8CC015061202008610869800717D164 +:102CA000486940F0100012E0816AD1F8B031D1F8E3 +:102CB000B441D1F8B8011061D1F8BC0150612020B5 +:102CC000C860C868800703D1486940F002004861C5 +:102CD000C3F34000C3F38001000140EA41111079C1 +:102CE00020F030000143117189064BBF91681189B2 +:102CF000DB085B0D4CBF63F31C0163F30A0113791E +:102D000048BF916064F3030313714FEA14234FEA41 +:102D1000144458BF118113705480ACE7012209019B +:102D200000F1604303F56143C9B283F8001300F07A +:102D30001F039A4043099B0003F1604303F561437D +:102D4000C3F880211A607047090100F16040C9B2E0 +:102D500000F56D4001767047FFF7CCBE012303708C +:102D6000002300F10802C0E9022200F11002C0E9CC +:102D70000422C0E90633C0E908334360704700000D +:102D800010B53023044683F3118802234160037099 +:102D9000FFF7D2FE04230020237080F3118810BDBA +:102DA0002DE9F0411F4604460D461646302383F3B5 +:102DB000118800F108082378052B0DD029462046FC +:102DC000FFF7E0FE40B1204632462946FFF7FAFE03 +:102DD000002080F3118808E03946404600F01AF9D7 +:102DE0000028E8D0002383F31188BDE8F0810000BB +:102DF0002DE9F0411F4604460D461646302383F365 +:102E0000118800F110082378052B0DD029462046A3 +:102E1000FFF710FF40B1204632462946FFF722FF58 +:102E2000002080F3118808E03946404600F0F2F8AF +:102E30000028E8D0002383F31188BDE8F08100006A +:102E400000238268037503691B6899689142FBD26D +:102E50005A680360426010605860704700238268BF +:102E6000037503691B6899689142FBD85A6803602F +:102E7000426010605860704708B50846302383F3FD +:102E800011880B7D032B05D0042B0DD02BB983F3B8 +:102E9000118808BD00228B691A604FF0FF338361EF +:102EA000FFF7CEFF0023F2E7D1E9003213605A604A +:102EB000F3E70000FFF7C4BF054BD9680875186831 +:102EC000026853601A6001220275D860FDF79ABB50 +:102ED000D823002030B50C4B0446DD684B1C87B06E +:102EE0000FD02B466846094A00F0CAF82046FFF783 +:102EF000E3FF009B13B1684600F0CAF8A86907B069 +:102F000030BDFFF7D9FFF9E7D8230020792E00085C +:102F1000044B1A68DB6890689B68984294BF002055 +:102F200001207047D8230020084B10B51C68D868D2 +:102F3000226853601A6001222275DC60FFF78EFF61 +:102F400001462046BDE81040FDF75CBBD8230020B9 +:102F500038B501230025064C0649074823706560F3 +:102F600000F03EFB0223237085F3118838BD00BFBB +:102F700030250020C43A0008D823002000F09AB879 +:102F80008B60022308618B82084670478368A3F137 +:102F9000440243F8142C026943F8442C426943F874 +:102FA000402C094A43F8242CC268A3F1200043F8BE +:102FB000182C022203F80C2C002203F80B2C034AD5 +:102FC00043F8102C704700BF15060008D8230020D6 +:102FD00008B5FFF7DBFFBDE80840FFF76BBF000057 +:102FE000024BDB6898610F20FFF766BFD8230020F3 +:102FF000302383F31188FFF7F3BF000008B50146C3 +:10300000302383F311880820FFF764FF002383F344 +:10301000118808BD064BDB6839B1426818605A60F8 +:10302000136043600420FFF755BF4FF0FF30704737 +:10303000D823002038B504460D462068844200D1CC +:1030400038BD036823605C608561FFF733FFF4E7F8 +:1030500010B50A4C23699A6891420CD85A6881606D +:103060000360426010609A685860511A99604FF08E +:10307000FF33A36110BD1B68891AECE7D823002039 +:10308000C0E90323002310B410BC4361FFF7E0BF85 +:10309000036881689A680A449A60426813605A60BB +:1030A00000234FF0FF320360014B9A61704700BF6D +:1030B000D823002070B5124D2A46EB690133EB612D +:1030C00052F8103F934206D030269A68013A9A602F +:1030D0002C69A36803B170BDD4E900210A60516076 +:1030E000236083F311882046D4E90331984786F39F +:1030F000118861690029EBD02046FFF7A9FFE7E7B7 +:10310000D8230020054A30B5D369D2E908451B1BF6 +:10311000181945F10001C2E9080130BDD82300208B +:1031200000207047FEE70000704700004FF0FF30BE +:1031300070470000BFF34F8F024AD368DB07FCD40F +:10314000704700BF0020024008B5074B1B7853B9F9 +:10315000FFF7F0FF054B1A69120641BF044A5A6097 +:1031600002F188325A6008BD482500200020024044 +:103170002301674508B5054B1B7833B9FFF7DAFF24 +:10318000034A136943F08003136108BD48250020FA +:10319000002002407F289ABF00F500308002002006 +:1031A000704700004FF48060704700008020704737 +:1031B0007F2808B50BD8FFF7EDFF00F580630268A4 +:1031C000013204D104308342F9D1012008BD00202E +:1031D000FCE700007F2810B504461CD8FFF7AAFFC3 +:1031E000FFF7B2FFF3220D4B4FF48061DA60022249 +:1031F0001A61FFF7CFFF58611A6942F040021A6165 +:10320000FFF798FF00F02EF9FFF7B4FF2046BDE866 +:103210001040FFF7CDBF002010BD00BF00200240CE +:103220002DE9F843054612F00100144606D040F29D +:10323000033200201E4B1A60BDE8F8831D4BAA180C +:103240009A4204D94FF44272194B1A60F4E7FFF71F +:103250007BFF4FF00109FFF76DFFDFF85C806D1A0F +:10326000012C0F4605EB010603D8FFF783FF012071 +:10327000E2E73B88C8F8109033800020FFF75AFF40 +:10328000C8F81000338831F8022B9BB29A420CD058 +:1032900040F21F32064B1A60084B1E60084B1C6040 +:1032A000084B1F60FFF766FFC6E7023CD8E700BF88 +:1032B000442500200000020800200240382500209C +:1032C000402500203C250020084908B50B7828B18E +:1032D0001BB9FFF739FF01230B7008BD002BFCD091 +:1032E000BDE808400870FFF745BF00BF4825002033 +:1032F00038B5EFF31185BDBBEFF30584C4F30804C3 +:103300003023C4B183F31188FFF7FCFE44014B0165 +:10331000241A43EAD06363EB0103A2009B00121856 +:1033200043EA947341EB0301C900D00041EA5271B2 +:1033300085F3118838BD83F31188FFF7E3FE45015B +:103340004B012D1A43EAD06363EB0103AA009B00F3 +:10335000121843EA957341EB0301C900D00041EA1A +:10336000527184F3118838BDFFF7CCFE44014B0144 +:10337000241A43EAD06363EB0103A2009B001218F6 +:1033800043EA947341EB0301C900D00041EA527152 +:1033900038BD00BF38B5FFF7ABFF00230F4A104C14 +:1033A000C00840EA4170A0FB025EC908A0FB040C03 +:1033B000A1FB0440A1FB02121CEB050C5B411CEBC2 +:1033C000040C43EB000011EB0E0142F10002411826 +:1033D00042F10000090941EA007038BDA59BC420F4 +:1033E000CFF753E310B5094C013AD2B2FF2A00D10E +:1033F00010BD500854F82030013054F820009BB222 +:1034000043EA004341F8043BEEE700BF046C004090 +:1034100010B50748013AD2B2FF2A00D110BD0C887E +:10342000530840F823404C88013340F82340F1E72B +:10343000046C004007B50122002001A9FFF7D2FF6C +:10344000019803B05DF804FB13B50446FFF7F2FFE3 +:10345000A04205D00122002001A90194FFF7D8FF66 +:1034600002B010BD7047000045F25552064B1A607D +:1034700002225A6040F6FF729A604CF6CC421A6003 +:103480000122024B1A707047003000405025002086 +:10349000034B1B781BB14AF6AA22024B1A607047F5 +:1034A0005025002000300040044B1A682AB902F170 +:1034B000804202F50432526A1A6070474C2500209F +:1034C0004FF08072014B5A62704700BF00100240FB +:1034D00008B5FFF7E9FF024B1868C0F3407008BD5C +:1034E0004C25002008B5FFF7DFFF024B1868C0F33A +:1034F000007008BD4C250020EFF30983203383F3CF +:103500000988002383F3118870470000302080F37E +:10351000118862B60C4B0D4AD96821F4E0610904A8 +:10352000090C0A43DA60D3F8FC20094942F08072A2 +:10353000C3F8FC200A6842F001020A602022DA7710 +:1035400083F82200704700BF00ED00E00003FA0599 +:10355000001000E0302310B583F311880B4B5B683B +:1035600013F400630FD0EFF309844FF08073203C15 +:10357000E36184F30988FFF7CBFC10B1044BA3612E +:1035800010BD044BFBE783F31188F9E700ED00E081 +:10359000270600082A06000870470000FEE7000022 +:1035A0000A4B0B480B4A90420BD30B4BC11EDA1C43 +:1035B000121A22F003028B4238BF00220021FDF7CD +:1035C000EDBE53F8041B40F8041BECE73C3B00083D +:1035D000D4250020D4250020D4250020FEE70000BB +:1035E00070B5002504461A4B86B0586085620163A9 +:1035F0000E46FFF78BFF04F11003C4E904334FF0CC +:10360000FF33A361134BE561D9692B460A46204677 +:10361000C4E9082304F134018023C4E900440E4ABC +:10362000A560E5622565FFF7ABFC01230B4AE0606E +:1036300003750092726868460192B268CDE9022370 +:10364000074BCDE90435FFF7C3FC06B070BD00BFE2 +:1036500030250020D8230020D03A0008D53A0008B1 +:10366000DD35000800F030B808B500F063F9FFF769 +:103670006FFCBDE80840FFF717BF0000704700006F +:103680004FF0FF310E4B1A6919611A6900221A6155 +:103690001869D868D960D968DA60DA68DA6942F0FE +:1036A0008052DA61DA69DA6942F00062DA61054A69 +:1036B000DB69136843F48073136000F01BB900BF2B +:1036C0000010024000700040194B1A6842F00102DD +:1036D0001A601A689007FCD51A6802F0F9021A609D +:1036E00000225A605A6812F00C0FFBD11A6842F49B +:1036F00080321A601A689103FCD55A6842F4E812C5 +:103700005A601A6842F080721A601A689201FCD5F9 +:103710001221084A5A60084A11605A6842F00202AF +:103720005A605A6802F00C02082AFAD1704700BFAA +:103730000010024000641D0000200240084A08B545 +:10374000516913680B4003F00103536123B1054A2B +:1037500013680BB150689847BDE80840FFF7FABE00 +:103760000004014054250020084A08B55169136837 +:103770000B4003F00203536123B1054A93680BB178 +:10378000D0689847BDE80840FFF7E4BE0004014058 +:1037900054250020084A08B5516913680B4003F00E +:1037A0000403536123B1054A13690BB1506998476B +:1037B000BDE80840FFF7CEBE0004014054250020BC +:1037C000084A08B5516913680B4003F008035361B8 +:1037D00023B1054A93690BB1D0699847BDE8084009 +:1037E000FFF7B8BE0004014054250020084A08B580 +:1037F000516913680B4003F01003536123B1054A6C +:10380000136A0BB1506A9847BDE80840FFF7A2BEA3 +:103810000004014054250020174B10B55A691C685C +:10382000144004F478725A61A30604D5134A936ACB +:103830000BB1D06A9847600604D5104A136B0BB1E0 +:10384000506B9847210604D50C4A936B0BB1D06B93 +:103850009847E20504D5094A136C0BB1506C9847A0 +:10386000A30504D5054A936C0BB1D06C9847BDE80D +:103870001040FFF76FBE00BF000401405425002038 +:103880001A4B10B55A691C68144004F47C425A6102 +:10389000620504D5164A136D0BB1506D9847230588 +:1038A00004D5134A936D0BB1D06D9847E00404D54D +:1038B0000F4A136E0BB1506E9847A10404D50C4A01 +:1038C000936E0BB1D06E9847620404D5084A136F0B +:1038D0000BB1506F9847230404D5054A936F0BB181 +:1038E000D06F9847BDE81040FFF734BE0004014098 +:1038F00054250020062108B50846FFF70FFA0621D7 +:103900000720FFF70BFA06210820FFF707FA062128 +:103910000920FFF703FA06210A20FFF7FFF9062125 +:103920001720FFF7FBF9BDE8084006212820FFF724 +:10393000F5B9000008B5FFF7A3FE054800F00CF844 +:10394000FFF70AFAFFF79AFEBDE8084000F002B858 +:10395000DC3A000800F042B8002319461C4A013343 +:10396000102BC2E9001102F10802F8D1194B9A6933 +:1039700042F07D029A619B690268174BDA608268A7 +:103980005A6042681A60C26803F58063DA6042696F +:103990005A6002691A608269C3F80C24026AC3F88B +:1039A0000424C269C3F80024426AC3F80C28C26A1E +:1039B000C3F80428826AC3F80028026BC3F80C2CF1 +:1039C000826BC3F8042C426BC3F8002C704700BF15 +:1039D0005425002000100240000801404FF0E02371 +:1039E000044A08215A6100229A6107220B201A61B9 +:1039F000FFF7AAB93F19010008B5302383F31188F6 +:103A0000FFF7BCFA002383F3118808BD08B5FFF760 +:103A1000F3FFBDE80840FFF79DBD000010B5013978 +:103A20000244904201D1002005E0037811F8014FD3 +:103A3000A34201D0181B10BD0130F2E72DE9F0417F +:103A40009BB10446C91A1778014403F1FF3C8C422C +:103A5000204601D9002008E005780134BD42F6D1A6 +:103A60000CEB0405D618A54201D1BDE8F08115F88C +:103A7000018D16F801EDF045F5D0E8E7034611F8A1 +:103A8000012B03F8012B002AF9D170476F72672EC2 +:103A90006172647570696C6F742E663130332D52AB +:103AA000616E676546696E646572000040A2E4F16C +:103AB000646891060041A3E5F26569920700000081 +:103AC00063300000C03A0008302400203025002078 +:103AD0006D61696E0069646C65000000001800008B +:103AE0004444414444544944010000004244444495 +:103AF0004444444400000000444444444444444496 +:103B00000000000044444444444444440000000095 +:103B10004444444444444444E8030000000000009A +:103B2000009C010000000000640000000000000094 +:0C3B300040420F00FE2A0100D2040000F9 :00000001FF diff --git a/Tools/bootloaders/f103-Trigger_bl.bin b/Tools/bootloaders/f103-Trigger_bl.bin index a2de5dfcab8091..faf1f07fa405f9 100755 Binary files a/Tools/bootloaders/f103-Trigger_bl.bin and b/Tools/bootloaders/f103-Trigger_bl.bin differ diff --git a/Tools/bootloaders/f103-Trigger_bl.elf b/Tools/bootloaders/f103-Trigger_bl.elf index dc9a90b5ba556f..55bc626ca38524 100755 Binary files a/Tools/bootloaders/f103-Trigger_bl.elf and b/Tools/bootloaders/f103-Trigger_bl.elf differ diff --git a/Tools/bootloaders/f103-Trigger_bl.hex b/Tools/bootloaders/f103-Trigger_bl.hex index fe677d32dd3236..e61b87f2ef1892 100644 --- a/Tools/bootloaders/f103-Trigger_bl.hex +++ b/Tools/bootloaders/f103-Trigger_bl.hex @@ -1,26 +1,26 @@ :020000040800F2 -:10000000000900202D080008A91C0008791C000820 -:10001000951C0008791C00088D1C00082F0800089A -:100020002F0800082F0800082F080008DD370008F7 -:100030002F0800082F0800082F080008F13C0008CE -:100040002F0800082F0800082F0800082F080008B4 -:100050002F0800082F080008213A00084D3A000830 -:10006000793A0008A53A0008D13A00082F0800089C -:100070002F0800082F0800082F0800082F08000884 -:100080002F0800082F0800082F080008A52C0008DA -:10009000112D0008652D0008B92D0008FD3A000853 -:1000A0002F0800082F0800082F0800082F08000854 -:1000B0002F0800082F0800082F0800082F08000844 -:1000C0002F0800082F0800082F0800082F08000834 -:1000D0002F0800082F0800082F0800082F08000824 -:1000E000653B00082F0800082F0800082F080008AB -:1000F0002F0800082F0800082F0800082F08000804 -:100100002F0800082F0800082F0800082F080008F3 -:100110002F0800082F0800082F0800082F080008E3 -:100120002F0800082F0800082F0800082F080008D3 -:100130002F0800082F0800082F0800082F080008C3 -:100140002F0800082F0800082F0800082F080008B3 -:100150002F0800082F0800082F0800082F080008A3 +:100000000009002025050008991900086919000851 +:1000100085190008691900087D19000827050008DE +:10002000270500082705000827050008F134000807 +:10003000270500082705000827050008053A0008DD +:1000400027050008270500082705000827050008E0 +:100050002705000827050008353700086137000824 +:100060008D370008B9370008E53700082705000874 +:1000700027050008270500082705000827050008B0 +:10008000270500082705000827050008952900080E +:10009000012A0008552A0008A92A0008113800087A +:1000A0002705000827050008270500082705000880 +:1000B0002705000827050008270500082705000870 +:1000C0002705000827050008270500082705000860 +:1000D0002705000827050008270500082705000850 +:1000E00079380008270500082705000827050008BB +:1000F0002705000827050008270500082705000830 +:10010000270500082705000827050008270500081F +:10011000270500082705000827050008270500080F +:1001200027050008270500082705000827050008FF +:1001300027050008270500082705000827050008EF +:1001400027050008270500082705000827050008DF +:1001500027050008270500082705000827050008CF :100160004FF0FF0C1CEAD0521EBF1CEAD15392EA9A :100170000C0F93EA0C0F6FD01A4480EA010C400276 :1001800018BF5FEA41211ED04FF0006343EA5010D0 @@ -81,917 +81,870 @@ :1004F0009E03B3EB126209D44FEA002343F000439A :1005000023FA02F070474FF00000704712F1610FBC :1005100001D1420202D14FF0FF3070474FF000008E -:10052000704700BF53B94AB9002908BF00281CBF53 -:100530004FF0FF314FF0FF3000F076B9ADF1080C0D -:100540006DE904CE00F006F8DDF804E0DDE90223F1 -:1005500004B070472DE9F047089E0D4604468846D2 -:10056000002B4DD18A42944668D9B2FA82F252B138 -:1005700001FA02F3C2F1200120FA01F10CFA02FCA7 -:1005800041EA030894404FEA1C41B8FBF1F71FFA17 -:100590008CFE01FB178807FB0EF0230C43EA08438F -:1005A00098420AD91CEB030307F1FF3580F01E8146 -:1005B000984240F21B81023F63441B1AB3FBF1F0E7 -:1005C00001FB103300FB0EFEA4B244EA0344A6452F -:1005D0000AD91CEB040400F1FF3380F00981A64521 -:1005E00040F20681644402380021A4EB0E0440EA84 -:1005F00007401EB10023D440C6E90043BDE8F087A0 -:100600008B4208D9002E00F0EE800021C6E90005DB -:100610000846BDE8F087B3FA83F100294AD1AB421E -:1006200002D3824200F2FC80841A65EB03030120AE -:100630009846002EE2D0C6E90048DFE702B9FFDEA7 -:10064000B2FA82F2002A40F09180A1EB0C00012165 -:100650004FEA1C471FFA8CFEB0FBF7F307FB1300B1 -:10066000250C45EA00450EFB03F0A84208D91CEB17 -:10067000050503F1FF3802D2A84200F2CE804346BE -:100680002D1AB5FBF7F007FB10550EFB00FEA4B2C8 -:1006900044EA0544A64508D91CEB040400F1FF35E3 -:1006A00002D2A64500F2B6802846A4EB0E0440EA2A -:1006B00003409EE7C1F120078B4022FA07FC4CEA79 -:1006C000030C25FA07FA4FEA1C49BAFBF9F820FA9D -:1006D00007F309FB18AA8D401FFA8CFE1D4300FA90 -:1006E00001F308FB0EF02C0C44EA0A44A04202FA83 -:1006F00001F20BD91CEB040408F1FF3A80F088806A -:10070000A04240F28580A8F102086444241AB4FB98 -:10071000F9F009FB104400FB0EFEADB245EA0444BB -:10072000A64508D91CEB040400F1FF356CD2A645A0 -:100730006AD90238644440EA0840A0FB0295A4EB61 -:100740000E04AC42C846AE4656D353D0002E69D0F4 -:10075000B3EB080264EB0E0422FA01F304FA07F784 -:100760001F43CC40C6E90074002147E70CFA02FCA5 -:10077000C2F1200125FA01F34FEA1C4720FA01F1EA -:1007800095400D43B3FBF7F107FB11331FFA8CFEC5 -:10079000280C40EA034001FB0EF3834204FA02F402 -:1007A00008D91CEB000001F1FF382FD283422DD96C -:1007B00002396044C01AB0FBF7F307FB1300ADB277 -:1007C00045EA004503FB0EF0A84208D91CEB0505DD -:1007D00003F1FF3816D2A84214D9023B6544281A07 -:1007E00043EA014138E73146304607E72F46E4E661 -:1007F0001846F9E64B45A9D2B9EB020865EB0C0E99 -:100800000138A3E74346EAE7284694E74146D1E7A3 -:10081000D0467BE76444023847E7023B65442FE754 -:10082000084606E73146E9E6704700BF02E000F0FF -:1008300000F8FEE772B6264880F30888254880F362 -:100840000988254825490860022080F31488BFF3F1 -:100850006F8F03F013F803F077F84FF0553020490D -:100860001B4A91423CBF41F8040BFAE71D49194A63 -:1008700091423CBF41F8040BFAE71B491B4A1C4B51 -:100880009A423EBF51F8040B42F8040BF8E70020EF -:100890001849194A91423CBF41F8040BFAE702F0AB -:1008A000F1FF03F053F8154C154DAC4203DA54F840 -:1008B000041B8847F9E700F03FF8124C124DAC4298 -:1008C00003DA54F8041B8847F9E702F0D9BF0000A7 -:1008D00000090020001100200000000808ED00E0E1 -:1008E0000001002000090020003E00080011002047 -:1008F0002411002028110020E025002060010008BC -:100900006001000860010008600100082DE9F04F57 -:10091000C1F80CD0C3689D46BDE8F08F002383F377 -:1009200011882846A047002002F00CFDFEE702F0E7 -:100930007FFC00DFFEE70000F8B500F039FE02F0B2 -:10094000EBFE074602F036FF0546002840D12C4B4F -:100950009F423DD001339F423DD02A4B27F0FF02FA -:100960009A423BD1F8B200F0FFFB2E4642F21074DF -:1009700000F000FC08B10024264601F003F988B31A -:100980000024032000F044F8264635B11E4B9F4258 -:1009900003D0002402F006FF2646002002F0C6FE27 -:1009A0001A4B9B6813F0400322D00EB100F046F8BA -:1009B00000F040FC00F0FEFD01F078F90546CCB1F6 -:1009C00001F074F9401BA04214D900F037F8F3E7A6 -:1009D0002E460024CCE704460126C9E706464FF41C -:1009E0007A74C5E7002CD0D04FF47A740126CCE796 -:1009F0001C46DDE700F0D0FC012002F0A9FCDEE798 -:100A0000010007B0000008B0263A09B0000C014010 -:100A1000084B187003280CD8DFE800F0080502081E -:100A2000022000F023BE022000F018BE0022024B7C -:100A30005A607047281100202C11002038B501F0B1 -:100A4000A1F830B103221F4B1A7000221E4B5A60CE -:100A500038BD1E4B1E4A19680131F9D00433934248 -:100A6000F9D11C4C194DD4F80424AA42F0D31A4BE6 -:100A70009B6803F1006303F5C8439A42E8D202F091 -:100A800065FE02F077FE002000F0AEFD0220FFF7C9 -:100A9000BFFF124BDA690022DA61D96999699A615C -:100AA0009B6972B64FF0E023C3F8085D3021D4F89B -:100AB0000034D4F8042481F311889D4683F3088818 -:100AC0001047C5E7281100202C1100200064000801 -:100AD000206400080060000800110020001002409F -:100AE00049F26900084A136899B21B0C00FB0133F4 -:100AF00044F250611360054B186882B2000C01FB90 -:100B00000200186080B27047201100201C110020E4 -:100B100010B504460021102200F0C4FD034B03CBA6 -:100B2000206061601868A06010BD00BFE8F7FF1F7B -:100B30002DE9F0410026ADF54E7D6CAC40F275120A -:100B400007460D460EA831460D9600F0ABFD4FF45A -:100B5000C4723146204600F0A5FD01F0A7F84FF41D -:100B60007A72B0FBF2F0244B0DF13408186093E870 -:100B70000700022384E807000DF5E9702382FFF7E0 -:100B8000C7FF4EF603031D4906A8238403F0E8F8C7 -:100B90001A230DF2E32284F832310DF1300C06AB4A -:100BA0001E4603CE664510605160334602F10802CE -:100BB000F6D13388414613802046012200F0BEFD65 -:100BC00000230393AB7E80B2029305F119030193D6 -:100BD0000123CDE904800093384605A3D3E900231F -:100BE000E97E01F0A9FB0DF54E7DBDE8F08100BF67 -:100BF0009E6AC421818A46EE34110020703D0008AF -:100C00002DE9F041264D80462B7A0C46DAB0FBB92F -:100C1000204627A900F0A2FE0746002836D19DF8FD -:100C20009D60C82E32D801464FF4FA72284600F073 -:100C300039FD32460DF19E0105F1090000F020FD5D -:100C40009DF89C302E4477722B720BB9E37E2B7289 -:100C50008122002106AD27A800F024FD01222946AB -:100C600027A800F0B7FE00230393A37E80B202936F -:100C700004F1190301932823CDE904500093404661 -:100C800005A3D3E90023E17E01F056FB5AB0BDE88D -:100C9000F08100BFAFF3008026417272DF25D7B725 -:100CA0007C210020F0B54FF48A750024234EF1B06A -:100CB00005FB006596F8D830D822214685F8DC304F -:100CC00085F8E8403AA800F0EDFC06F1090000F0D4 -:100CD000E1FCD5F8E430C2B206AF8DF8F00006F1C1 -:100CE00009010DF1F100CDE93A3400F0C9FC3946B3 -:100CF00001223AA800F09AFE80B2CDE904700823E0 -:100D00000127CDE9023706F1D80301933023317A68 -:100D100000930B4807A3D3E9002301F00DFBA04289 -:100D200006DD00F0C3FFC5F8E000384671B0F0BD45 -:100D30002046FBE778F6339F93CACD8D7C210020B7 -:100D40004C210020F0B51E4E1E4F1F4D85B0304681 -:100D500001F01EFB044660B310220021684600F03B -:100D6000A1FC4FF00003227B6068A16862F30303DB -:100D70008DF8003002AB03C3019B2268384662F352 -:100D80001C0301939DF800306A4643F020038DF860 -:100D900000300023194602F087F9044620B9304696 -:100DA00001F0FAFA2C70D2E72B78072B03D8013325 -:100DB0002B7005B0F0BD024801F0EEFAF9E700BF74 -:100DC0004C210020A82300207523002070B50D467B -:100DD00014461E4601F00CFA50B9022E10D1012C17 -:100DE0000ED112A3D3E900230120C5E9002307E0B7 -:100DF000282C10D005D8012C09D0052C0FD00020AC -:100E000070BD302CFBD10BA3D3E90023ECE70BA37F -:100E1000D3E90023E8E70BA3D3E90023E4E70BA31E -:100E2000D3E90023E0E700BFAFF30080401DA1201D -:100E300026812A0B78F6339F93CACD8D9E6AC421F2 -:100E4000818A46EE26417272DF25D7B7F017304A05 -:100E500039059E5638B505460E4C0021013500F087 -:100E6000E5FBA4F8F051B4F8F00100F0C7FB78B14D -:100E7000B4F8F00100F0D2FB014648B9B4F8F00133 -:100E800000F0D4FBB4F8F0310133A4F8F031EAE714 -:100E900038BD00BF7C2100202DE9F04F8DB000AFA0 -:100EA00004460D4601F0A4F9002846D12B7E022B02 -:100EB0001AD1EB8A012B17D100F0F8FE0646FFF796 -:100EC0000FFE4FF4C873B0FBF3F202FB1303DFF81D -:100ED00078829BB206F516763344C8F80030EB7E74 -:100EE00033B90022994B1A703437BD46BDE8F08FF4 -:100EF000284607F11C0100F0EFFC0028F4D107F1AF -:100F00000C00FFF705FEBD7F07F10C012A4607F133 -:100F10001F0002F0F5FE0028E3D10F2D08D88B4BFF -:100F20001D70D8F80030A3F51673C8F80030DBE761 -:100F30002046397F01F054F9D6E7EB8A282B6BD095 -:100F400010D8012B63D0052BCED1BFF34F8F804932 -:100F5000804BCA6802F4E0621343CB60BFF34F8F4B -:100F600000BFFDE7302BBFD17B4CEA7E237A9A424B -:100F7000BAD194F8DC206B7E9A42B5D1284604F1B0 -:100F8000EA0100F07FFD06460028ADD1012384F878 -:100F9000E83000F08BFED4F8E030C01A192840F693 -:100FA000B83338BF1920984228BF1846FFF742FAD5 -:100FB0006A49FFF7D5F805462068FFF73BFA68490C -:100FC000FFF7CEF801462846FFF784F9FFF78AFAC3 -:100FD00020604FF48A7194F8D9307B607A68636836 -:100FE00001FB02F5621992F8E80050B1D2F8E40072 -:100FF000E946834215D0002382F8E830C2F8E03099 -:10100000CD466368574A9B0A013313816CE7294632 -:101010002046FFF78DFD67E729462046FFF7F0FDE4 -:1010200062E7B2F8EC803B6008F1030A4FEA9A0AE3 -:101030004FEA8A02D11DC908A9EBC1039D46EB46C0 -:101040000021584600F02EFB05F1EE0142465846BD -:10105000214400F015FB3B6813B9012000F0C4FAED -:1010600094F8D20000F0CAFA054630B9207200F0B8 -:10107000E5FA284600F0B8FAC2E7D4F8D4303BB914 -:1010800094F8D200B4F8F031834201D8FFF7E2FEC1 -:10109000D4F8D43043449D4208D294F8D200B4F836 -:1010A000F0310130834201D8FFF7D4FE5946606821 -:1010B0005FFA8AF200F0FEFA08B9CD4689E7636864 -:1010C00094F8D20043446360D4F8D43008EB030AA8 -:1010D000C4F8D4A000F092FA824509D394F8D23033 -:1010E000D4F8D4000133401B84F8D230C4F8D400C3 -:1010F000B8F1FF0F0FD80025257200F09FFA28469F -:1011000000F072FA00F03EFD164B188108B9FFF7A7 -:1011100095FCCD46E8E64FF48A727B6894F8D900D6 -:1011200002FB0343D3F8E42083F8E86002F5807201 -:10113000C3F8E060C3F8E420FFF7B4FDFFF702FE58 -:1011400084F8D960B9E700BF48210020452100207C -:1011500000ED00E00400FA057C210020CDCCCC3D60 -:101160006666663F34110020014B1870704700BF5F -:101170004011002030B54FF00054254B226885B057 -:101180009A4207D002F020FB0446C0B90024204652 -:1011900005B030BD0025627D1E4B1F481A70237DAF -:1011A000C92203721D49C0F8E450093000F068FA02 -:1011B0002046E022294600F075FA0124E7E7184AA4 -:1011C000184DD36943F00073D361AA6D164B9A4250 -:1011D000DCD12B6E013B7E2BD8D8144A01AB07CA59 -:1011E00083E807001846032100F09CFC6B6D8342E6 -:1011F0004FF00003CAD12A6D8A4203BFAB652A6E45 -:10120000044B1C4601BF1A70EA6D094B1A60BEE719 -:101210009AAD44C5401100207C210020160000201A -:1012200000100240006600405041A0B058660040E7 -:10123000181100202DE9F04385B000F0A3FC022333 -:10124000494C637100230293484B2081D3F800C0BE -:10125000BCF57A7F12D3464F464BB7FBFCF59C4555 -:101260008CBF0A231123B5FBF3F603FB1652591E5C -:10127000C8B2002A3ED002290B46F4D89DF80B30A4 -:101280003D495A1E9DF80A303C48013B1B0443EA85 -:101290000253BDF80820013A13434B6001F0F4FEFD -:1012A00000230193364B374900934FF48052364B5D -:1012B000364800F06BFF364B197811B1334800F017 -:1012C0008FFF00F0F3FC0546FFF70AFC4FF4C873EC -:1012D000B0FBF3F202FB130305F516709BB2184442 -:1012E0002C4B186002F066FA08B10F23238105B079 -:1012F000BDE8F083731EB3F5806FBFD24FF47A75EB -:10130000C0EBC00E0EF103034FEAE30909FB0555DC -:10131000C3F3C703C11AC9B209F101088844B5FB78 -:10132000F8F5B5F5617F08D90EF1FF33C3F3C703B4 -:10133000C11A581E0F28C9B214D84A1E072A8CBFDA -:1013400000220122581800FB0660B7FBF0F7BC45ED -:1013500094D1002A92D0ADF808608DF80A308DF84B -:101360000B108BE71346EDE7341100201811002015 -:10137000005125023F420F0010110020A823002039 -:10138000CD0D000844110020990E00084C210020CA -:1013900040110020482100202DE9F04F80A7D7E917 -:1013A00000670FF20429D9E90089734D93B00DF15C -:1013B000300AFFF7C7FC18220021504600F072F9EE -:1013C000DFF8B8B16E4C002352461946584601F07A -:1013D00093FE014650BB102208A800F063F9E368B1 -:1013E00083F01003E36000F063FC0DF1240C0B4666 -:1013F00012A9024611E903008CE803009DF834109D -:10140000C1F30300890649BF0E99BDF83810C1F336 -:101410001C0141F0004158BFC1F30A018DF82C00B6 -:101420000891284608A901F097F9CCE7284600F072 -:10143000DFFE0446002847D100F038FCDFF844B155 -:10144000DBF8003098423FD300F030FC0790FFF704 -:1014500047FB4FF4C873B0FBF3F101FB1300079A8D -:1014600083B202F516701844CBF80000DFF818B10B -:101470008DF820409BF8001011B901238DF8203021 -:1014800050460791FFF744FB07990DF12100C1F188 -:101490001004E4B2062C28BF06245144224600F072 -:1014A000EFF808AB039318230293384B01340193F0 -:1014B0000123E4B2009332463B462846049400F0F0 -:1014C000DDFE00238BF8003000F0F0FB304A314C99 -:1014D0001368C31AB3F57A7F30D3106000F0E8FBCD -:1014E00002460B46284600F061FF284600F080FEC9 -:1014F00020B3237ADFF8A0B0002B14BF032302230C -:101500008BF8053000F0D2FB4FF47A73B0FBF3F0A8 -:101510000122CBF800005146584600F0B5F91823D7 -:1015200002931E4B80B2019340F25513CDE903A004 -:10153000009342464B46284600F0A0FE237ABBB1FA -:1015400000F0B4FB94F8E83073B9D4F8E03043B15C -:10155000C01A2368FA2B38BFFA230533B0EB430FC8 -:1015600002D30020FFF79EFB237A002B7FF41FAFEE -:1015700013B0BDE8F08F00BF4C210020A82300204D -:10158000000801404821002045210020442100207E -:10159000702300207C2100203411002074230020BF -:1015A000401DA12026812A0BF1C6A7C1D068080FD3 -:1015B0007047000070B501F095FF0024084E094DFA -:1015C000308028683388834208D901F087FF2B6870 -:1015D00004440133B4F5C84F2B60F2D370BD00BF93 -:1015E000A42300207823002002F00AB800F1006054 -:1015F000920000F5C84001F0AFBF0000054B1A682B -:10160000054B1B889B1A834202D9104401F066BF28 -:101610000020704778230020A4230020024B1B6881 -:10162000184401F061BF00BF78230020024B1B6803 -:10163000184401F06BBF00BF78230020064991F8E1 -:10164000243033B100230822086A81F82430FFF7E0 -:10165000CDBF0120704700BF7C230020022802BFBD -:101660001022014B1A61704700080140022802BF96 -:101670004FF48012014B1A61704700BF000801400F -:10168000002310B5934203D0CC5CC4540133F9E776 -:1016900010BD000003460246D01A12F9011B0029B2 -:1016A000FAD1704703460244934202D003F8011B6B -:1016B000FAE770472DE9F8431F4D144695F82420AA -:1016C0000746884652BBDFF870909CB395F82430EB -:1016D0002BB92022FF2148462F62FFF7E3FF95F840 -:1016E00024004146C0F10802A24228BF224605EB71 -:1016F0008000D6B29200FFF7C3FF95F82430A41BF8 -:101700001E44F6B2082E17449044E4B285F82460D3 -:10171000DBD1FFF793FF0028D7D108E02B6A03EB5A -:1017200082038342CFD0FFF789FF0028CBD100206E -:10173000BDE8F8830120FBE77C2300202DE9F0477A -:101740000D46044600219046284640F27912FFF7E4 -:10175000A9FF234620220021284600F09FFF0222F5 -:1017600020212846231D00F099FF0322222128462C -:10177000631D00F093FF032225212846A31D00F0DE -:101780008DFF10222821284604F1080300F086FF6F -:1017900008223821284604F1100300F07FFF0822B8 -:1017A0004021284604F1110300F078FF0822482167 -:1017B000284604F1120300F071FF20225021284630 -:1017C00004F1140300F06AFF40227021284604F15E -:1017D000180300F063FF0822B021284604F120031B -:1017E00000F05CFF0822B821284604F1210300F034 -:1017F00055FFC02604F122073B4631460822284601 -:10180000083600F04BFFB6F5A07F07F10107F3D1D2 -:1018100008223146284604F1320300F03FFF00273A -:1018200004F1330A94F832304FEAC7099F4209F5B0 -:10183000A47615D3B8F1000F08D131460722284607 -:1018400004F5997300F02AFF09F24F16274694F821 -:1018500032213B1B93420CD3F01DC008BDE8F0873A -:101860000AEB070308223146284600F017FF01372C -:10187000D8E7314607F233130822284600F00EFF5E -:1018800008360137E3E7000038B50C46002105466D -:1018900021600346C4F803102046202200F0FEFE1B -:1018A00020462B1D0222202100F0F8FE20466B1D51 -:1018B0000322222100F0F2FE2046AB1D0322252147 -:1018C00000F0ECFE20461022282105F1080300F06C -:1018D000E5FE072038BD00000023F7B50E4605469B -:1018E000047F07220091194600F09AFD731C0093B3 -:1018F000012200230721284600F092FDC4B9B31C41 -:101900000093052223460821284600F089FD0D2476 -:101910003746B278BB1B934211D32B7FE01DC00822 -:10192000AC8ABBB9A04294BF0020012003B0F0BD37 -:10193000AB8A0824DB00083BDB08B370E8E7FB1C3C -:101940002146009308220023284600F069FD083450 -:101950000137DEE7001B18BF0120E7E70023F7B5DA -:101960000E46047F082200911946054600F058FDF6 -:10197000731CC4B90822009311462346284600F080 -:101980004FFD1024012372785F1C013B934211D359 -:101990002B7FE01DC008AC8ABBB9A04294BF0020D9 -:1019A000012003B0F0BDAB8A0824DB00083BDB0854 -:1019B0007370E7E7F31921460093082200232846B5 -:1019C00000F02EFD08343B46DDE7001B18BF012068 -:1019D000E7E70000F8B50E460546144600218122CF -:1019E0003046FFF75FFE2B4608220021304600F00C -:1019F00055FE7CB90722082130466B1C00F04EFED4 -:101A00000F2401236A785F1C013B934204D3E01D3D -:101A1000C008F8BD0824F4E72146EB190822304637 -:101A200000F03CFE08343B46ECE70000F8B50E46FB -:101A3000054614460021CE223046FFF733FE2B46E2 -:101A400028220021304600F029FE7CB908222821F6 -:101A5000304605F1080300F021FE30242F462A7A93 -:101A60007B1B934204D3E01DC008F8BD2824F5E792 -:101A7000214607F109030822304600F00FFE083422 -:101A80000137ECE7F7B5047F0E46009101231022E1 -:101A90000021054600F0C4FCC4B9B31C0093092220 -:101AA00023461021284600F0BBFC192437467288D3 -:101AB000BB1B9A4211D82B7FE01DC008AC8ABBB972 -:101AC000A04294BF0020012003B0F0BDAB8A1024D7 -:101AD000DB00103BDB087380E8E73B1D21460093E9 -:101AE00008220023284600F09BFC08340137DEE77B -:101AF000001B18BF0120E7E730B5094D0A449142A9 -:101B00000DD011F8013B5840082340F30004013B7D -:101B10002C4013F0FF0384EA5000F6D1EFE730BD0C -:101B20002083B8ED4FF0FF33F7B500EB810619467F -:101B3000DFF848C0DFF848E0B0421BD050F8042B73 -:101B400001AF0192042217F8014B81EA04610824D5 -:101B50000D46DB184941013C002DBCBF83EA0C0354 -:101B600081EA0E0114F0FF04F2D1013A12F0FF02F3 -:101B7000E9D1E1E7D843C94303B0F0BD9336EAA900 -:101B8000EBE1F042F7B56B46354A106851686A469A -:101B900003C308233349344802F0C2F8044690BB1B -:101BA0000A256B46314A106851686A4603C3082308 -:101BB0002F492D4802F0B4F80446002847D00369A5 -:101BC000B3F5CE3F43D8B0F86620B2F57A7F3ED168 -:101BD000284A024402F15C018B4238D35C3B224923 -:101BE00000209E1AFFF788FF07463246002004F1C6 -:101BF0006401FFF781FFA3689F4228D1E368984200 -:101C000008BF002523E00369B3F5CE3F26D8428BF9 -:101C1000B2F57A7F20D1174A024402F110018B42BB -:101C200018D3103B104900209D1AFFF765FF0646A8 -:101C30002A46002004F11801FFF75EFFA3689E42C8 -:101C400002D1E368984201D00D25AAE70025284675 -:101C500003B0F0BD1025A4E70C25A2E70B25A0E7F3 -:101C60008C3D0008DC9B010000640008953D0008E5 -:101C7000909B0100089CFFF7EFF30983EFF30583C6 -:101C8000014B9B6BFEE700BF00ED00E008B5FFF7DE -:101C9000F3FF0000EFF30983EFF30583014B5B6B68 -:101CA000FEE700BF00ED00E0FEE7000001F0E2BC4F -:101CB00001F0BABC2DE9F041456A15B94162BDE8B1 -:101CC000F0814B68AC4623F06047C3F38A4616EABE -:101CD000230638BF3E464FEAD37EC3F380782B46B7 -:101CE0005A68BEEBD27F22F060440AD0002A18DA8C -:101CF000A40CB44217D19D420FD10D60DEE713460C -:101D0000EEE7A74207D102F08044C2F38072424559 -:101D10000BD054B1EFE708D2EDE7CCF800100B6020 -:101D2000CDE7B44201D0B442E5D81A689C46002AF7 -:101D3000E5D11960C3E700002DE9F0474FF47F4972 -:101D4000089D01F007044FEAD508224405F0070575 -:101D500000EBD100944201D1BDE8F08704F0070701 -:101D600005F0070A57453E4638BF5646111BC6F1D7 -:101D700008068E4228BF0E46E108415C08EBD50EEE -:101D800013F80EC0B94029FA06F721FA0AF1FFB29A -:101D90008CEA010147FA0AF739408CEA010C03F892 -:101DA0000EC034443544D5E7082341F2210280EACD -:101DB000012001B24000002980B203F1FF33B8BF17 -:101DC000504013F0FF03F4D17047000038B50C46C3 -:101DD0008D18A54200D138BD14F8011BFFF7E4FFB0 -:101DE000F7E700000346406848B1026899895A60E5 -:101DF0005A89013292B291425A8138BF9A81704712 -:101E000070B504460D4688B0202200216846FFF7D1 -:101E100049FC20460495FFF7E5FF024658B16B46A2 -:101E2000054608AE1C4603CCB442286069602346D0 -:101E300005F10805F6D1104608B070BD082817D97D -:101E400009280CD00A280CD00B280CD00C280CD058 -:101E50000D280CD00E2814BF4020302070470C20D5 -:101E600070471020704714207047182070472020BA -:101E700070470000082817D90C280CD910280CD955 -:101E800014280CD918280CD920280CD930288CBF3C -:101E90000F200E207047092070470A2070470B2042 -:101EA00070470C2070470D20704700002DE9F84363 -:101EB000078C0446072F1ED9D0E9029800254FF65B -:101EC000FF73C5F12006A5F1200029FA05F108FAF3 -:101ED00006F628FA00F031430143C9B21846FFF76D -:101EE00063FF0835402D0346EBD13A46E169BDE872 -:101EF000F843FFF76BBF4FF6FF70BDE8F8830000B3 -:101F000010B54B6823B9CA8A63F30902CA8210BDAF -:101F100004691A681C600361C38A013BC3824A607A -:101F2000EFE700002DE9F84F1D46CB8A0F46C3F3BB -:101F300009010529814692460B4630D00020AAB2FD -:101F400007F11A049EB2042E1FFA80F80FD89045AC -:101F500003F1010306D3FB8A0A4462F3090301205B -:101F6000FB821AE01AF800600130E654EAE7904577 -:101F7000F1D21C23A1F1050BBBFBF3F203FB12BB57 -:101F80007C681FFA8BF6002C45D14846FFF72AFFE4 -:101F9000044638B978606FF00200BDE8F88F4FF062 -:101FA0000008E6E70026066078604FF0000BADB24F -:101FB000454510D90AEB0803221D13F8011B08F14F -:101FC00001089155B1B21B291FFA88F82BD045455D -:101FD00006F10106F1D8FB8AC3F30902154465F343 -:101FE0000903BCE71C46013292B22368002BF9D1E9 -:101FF0006B1F0B441C21B3FBF1F301339BB29A42DC -:10200000D3D2BBF1000FD0D14846FFF7EBFE20B989 -:10201000C4F800B0BFE70122E7E7C0F800B05E46B1 -:1020200020600446C1E74545D5D94846FFF7DAFEAA -:1020300008B92060AFE7C0F800B000262060044671 -:10204000B6E700002DE9F74F1C465B690746884656 -:102050000092002B00F09780238C2BB1E269002ABC -:1020600000F09180072B33D807F10C00FFF7BAFE80 -:10207000054628B96FF00205284603B0BDE8F08F89 -:1020800014220021FFF70EFB228CE16905F1080004 -:10209000FFF7F6FA208C48F00041013080B2FFF7DC -:1020A000E9FEFFF7CBFE013880B2208401302874AE -:1020B0006369228C1B782A4403F01F0363F03F03FB -:1020C0001372384669602946FFF7F4FD0125D3E70E -:1020D0004FF000094FF0800A4E464D4600F10C03C8 -:1020E00001930198FFF77EFE83460028C2D0142298 -:1020F0000021FFF7D7FA002E3BD10222009BABF85C -:1021000008300BF1080E1FFA82FC0CF10100BCF143 -:10211000060F218C80B201D88E422CD3FFF7AAFE85 -:10212000FFF78CFE8E4208BF4FF0400A626901380B -:10213000127880B202F01F0242EA49120BEB000152 -:102140004AEA020A013048F0004281F808A08BF800 -:10215000100059463846CBF80420FFF7ABFD238C1E -:102160000135B3424FF0000A2DB289F00109B8D110 -:1021700082E70022C5E7E169895D01360EF80210A9 -:10218000B6B20132BFE76FF0010575E7F8B5044656 -:1021900015460E46302200211F46FFF783FA069BA4 -:1021A000B5F5001F6360079B28BF4FF6FF72A3625F -:1021B0004FF0000338BF6A09A760E66197B204F1E7 -:1021C00010009A4206D800230360A782E38223838B -:1021D000E360F8BD0660013330462036F1E70000C9 -:1021E00003781BB94BB2002BC8BF017070470000C9 -:1021F00000787047F8B50C46C969074611B9238CB9 -:10220000002B37D1257E1F2D34D8387828BB228C5F -:10221000072A2CD8268A36F003032BD14FF6FF70FD -:10222000FFF7D4FD4FF6FF7220F0010036024004A4 -:1022300046EA0565400C45EA4025234629463846CE -:10224000FFF700FF002807DD626913780133DBB276 -:102250001F2B88BF00231370F8BD218A2D0645EA85 -:10226000012505432046FFF721FE0246E5E76FF012 -:102270000300F1E76FF00100EEE7000070B50446DF -:102280001D4616468AB0282200216846FFF70AFA42 -:10229000BDF838306946ADF810300F9B20460593E5 -:1022A0009DF84030CDE902658DF81830119B0793F9 -:1022B000BDF84830ADF82030FFF79CFF0AB070BD84 -:1022C0002DE9F041D36905460C4616460BB9138C2F -:1022D0005BBB377E1F2F28D895F80080B8F1000F20 -:1022E00026D03046FFF7E2FD3378210241EAC331C0 -:1022F00041EA0801338A41EA076141EA03410246A3 -:102300003346284641F08001FFF79CFE00280ADD95 -:102310003378012B07D1726913780133DBB21F2B9D -:1023200088BF00231370BDE8F0816FF00100FAE769 -:102330006FF00300F7E70000F0B504460D461E46B7 -:1023400017468BB0282200216846FFF7ABF99DF8AD -:102350004C3029465A1E534253418DF800309DF8A7 -:1023600040306A46ADF81030119B204605939DF829 -:102370004830CDE902768DF81830149B0793BDF8EC -:102380005430ADF82030FFF79BFF0BB0F0BD0000DC -:10239000406A00B104307047436A1A6842620269B9 -:1023A0001A600361C38A013BC38270472DE9F04183 -:1023B000D0F8208014461D4641460027174E09B923 -:1023C000BDE8F081D1E90223A21A65EB030396422E -:1023D00077EB03031ED2036A8B420DD1FFF790FD0A -:1023E000036A1B68036203690B60C38A0161016AA7 -:1023F000013B8846C382E2E7FFF782FD0B68C8F81D -:10240000003003690B60C38A0161013BC382D8F8C5 -:102410000010D4E788460968D1E700BF80841E0019 -:102420002DE9F04F8BB00D4614469B468046DDF8F3 -:102430005090002800F01A81B9F1000F00F01681C9 -:10244000531E3F2B00F21281012A03D1BBF1000F72 -:1024500040F00C810023CDE90833B8F81430B5EB17 -:10246000C30F4FEAC30703D300200BB0BDE8F08FC2 -:102470002B199F42D8F80C3036BF7F1B2746FFB27E -:102480001BB9D8F81030002B7BD0272D4ED8C5F1C2 -:102490002806B7424FF0000334BF3E46F6B2009321 -:1024A00029463246D8F8080008ABFFF745FCA7EBF1 -:1024B000060A35445FFA8AFA2821B8F8143003F185 -:1024C0000053053BDB000493D8F80C300393039BC7 -:1024D00013B1BAF1000F2CD1D8F8100040B1BAF105 -:1024E000000F05D05246009608AB691AFFF724FC8E -:1024F00038B2002FB8D066070AD00AAB03EBD4017C -:1025000011F8083C624202F00702134101F8083C4E -:10251000082C3DD9102C40F2B680202C40F2B88017 -:10252000BBF1000F00F09D80082335E0BA4600267D -:10253000C2E7049BE02B28BFE02306930B44AB4289 -:10254000059315D95A1B924538BF5246039828BFA8 -:10255000D2B20096691A08AB04300792FFF7ECFB81 -:10256000079A1644AAEB020A1544F6B25FFA8AFAF1 -:10257000049B069A05999B1A0493039B1B6803937B -:10258000A5E700933A462946D8F8080008ABADE71E -:10259000BBF1000F13D00123B4EBC30F6CD0082C98 -:1025A00012D89DF82030621E23FA02F2D50706D514 -:1025B0004FF0FF3202FA04F423438DF820309DF8E7 -:1025C000203089F8003050E7102C12D8BDF82030A8 -:1025D000621E23FA02F2D10706D54FF0FF3202FA4B -:1025E00004F42343ADF82030BDF82030A9F80030C2 -:1025F0003BE7202C0FD80899631E21FA03F3DA0772 -:1026000005D54FF0FF3202FA04F40C430894089BFE -:10261000C9F8003029E7402C2BD0DDE90865611EA0 -:10262000C4F12102A4F1210326FA01F105FA02F214 -:1026300025FA03F311431943CB0712D50122A4F164 -:102640002003C4F1200102FA03F322FA01F1A240AF -:10265000524243EA010363EB430332432B43CDE988 -:102660000823DDE90823C9E90023FEE66FF0010035 -:10267000FBE66FF00800F8E6082CA0D9102CB3D9BF -:10268000202CEED8C3E7BBF1000FADD0022383E7C7 -:10269000BBF1000FBBD004237EE70000012A30B558 -:1026A000144638BF01220025402A28BF402285B0A9 -:1026B000012CCDE9025517D81B788DF80830530747 -:1026C0000AD004AB03EBD20515F8083C544204F0E1 -:1026D0000704A34005F8083C0346009102A8002126 -:1026E000FFF72AFB05B030BD082CE5D9102C03D824 -:1026F0001B88ADF80830E2E7202C02D81B68029353 -:10270000DDE7D3E90045CDE90245D8E710B5CB6850 -:102710001BB98B600B618B8210BD04691A681C6049 -:102720000361C38A013BC382CA60F0E703064CBF62 -:10273000C0F3C0300220704708B50246FFF7F6FF2D -:10274000022806D15306C2F30F2001D100F0030086 -:1027500008BDC2F30740FBE72DE9F04F93B0CDE988 -:1027600003230A6804461046FFF7E0FF02280CBF67 -:102770000026C2F30626002A0D46824680F2F98121 -:1027800012F0C04940F0F581097B002900F0F18189 -:10279000022803D02378B34240F0EE81C2F30463F1 -:1027A0001046069302F07F030593FFF7C5FF059BD4 -:1027B00000224FEA8348002348EA0A48294448EAAD -:1027C0004668CE78CDE90823F309834648EA000835 -:1027D000029367D0059B02460093204653466768E4 -:1027E00008A9B847002800F0CA81276A4FB94146B6 -:1027F00004F10C00FFF704FB074690B96FF00200EC -:1028000054E03B6998450DD03F68002FF9D141460F -:1028100004F10C00FFF7F4FA07460028EED0236A13 -:102820003B60276297F817C006F01F08CCF3840CB2 -:10283000ACEB08001FFA80FE0028B8BF0EF12000A4 -:10284000A8EB0C031FFA83FEB8BF00B2002B07935E -:10285000BEBF0EF120031BB20793D7E9022152EA53 -:10286000010338D04FF0000C039BDFF8F8E19A1A0F -:10287000049B63EB010196457CEB01032BD36B7B3F -:1028800097F81AE0734519D1029B002B78D00128E4 -:1028900021DC7868F8B9DFF8D0C1944570EB01030A -:1028A00016D337E0276A27B96FF00C0013B0BDE8E4 -:1028B000F08F3B699845B5D03F68F4E76A4890428D -:1028C0007CEB010301D30020F0E7029B002BFAD040 -:1028D000079B0F2B17DCFA7DB30002F0030203F015 -:1028E0007C031343FB7539462046FFF709FB6B7BDE -:1028F000BB76029B3BB9FB7DC3F38402013262F3DA -:102900008603FB75D0E76A7BBB7E9A42DBD1029BD4 -:10291000002B35D0B309022B32D0039B1422BB60AD -:10292000049B0021FB600DA8FEF7BCFE039B204624 -:102930000A93049BADF83EB00B932B1D0C932B7B9D -:102940008DF840A0013BDBB2ADF83C30069B8DF822 -:1029500041808DF84230059B0AA98DF8433094F8E8 -:102960002C3083F001038DF84430A3689847FB7D39 -:10297000C3F38403013303F01F039B02FB82A2E72E -:10298000FB7DC6F34012B2EBD31F40F0FB80C3F3D4 -:102990008403434540F0F980029A2B7BB609002A54 -:1029A0004DD0F20762D4032B40F2F280039BAE1DA0 -:1029B000BB60049B3246FB602B7B3946033BDBB29A -:1029C00004F10C00FFF7AEFA00280CDA3946204675 -:1029D000FFF796FAFB7DC3F38403013303F01F0373 -:1029E0009B02FB820AE7AB88DDE908843B834FF654 -:1029F000FF73C9F12000A9F1200228FA09F104FAB5 -:102A000000F0014324FA02F211431846C9B2FFF75D -:102A1000CBF909F10809B9F1400F0346E9D1314674 -:102A2000B8822A7B033AD2B2FFF7D0F9FB7DB88295 -:102A3000DA43C2F3C01262F3C713FB7543E7AEB9C2 -:102A40002E1D013B32463946DBB204F10C00FFF784 -:102A500069FA0028BADB2A7B3146013AB88AD2B239 -:102A6000E2E700BF80841E0040420F00F98A013B6C -:102A7000C1F309010429DAB25DD80023281D07F14A -:102A80001B069A4208D910F801CB013306F801C0A1 -:102A900001310529DBB2F4D1934228BF0023039909 -:102AA00038BF04330A91049938BFDBB20B9107F1A8 -:102AB0001B010C91796838BF5B190D910E93FB8A4D -:102AC000ADF83EB0C3F309031A44069BADF83C20B1 -:102AD0008DF84230059B8DF840A08DF8433094F876 -:102AE0002C308DF8418083F001038DF844300023B1 -:102AF0007B602A7BB88A013A291DFFF767F93B8B77 -:102B0000B882834203D12046A3680AA99847204689 -:102B10000AA9FFF7FBFDFB7DBA8AC3F384030133E7 -:102B200003F01F039B02FB823B8B9A420CBF0020E9 -:102B30006FF01000BAE67B68002BADD0052001E0F5 -:102B400033461C301E68002EFAD1091A081D2E1DAE -:102B5000184401EB090CBCF11B0F5FFA89F39BD8F9 -:102B60009A4299D916F8013B09F1010900F8013B95 -:102B7000EFE76FF0090099E66FF00A0096E66FF054 -:102B80000B0093E66FF00D0090E66FF00E008DE6FF -:102B90006FF00F008AE600BFF0B53F4D3F4FEB6985 -:102BA00043F00073EB61EB693D4B9B6AD3F8006225 -:102BB0003E4046F00106C3F80062D3F800423C40B4 -:102BC00044EA002444F00104C3F80042002955D02F -:102BD00000200646C3F81C02C3F80402C3F80C0226 -:102BE000C3F8140203EBC00401300E28C4F840629D -:102BF000C4F84462F6D100274FF0010C967814888F -:102C000016F0010F18BFD3F804E20CFA04F01CBF51 -:102C100040EA0E0EC3F804E216F0020F18BFD3F814 -:102C20000CE203EBC4041CBF40EA0E0EC3F80CE236 -:102C3000760748BFD3F8146207F1010744BF064383 -:102C4000C3F814625668B942C4F84062966802F14B -:102C50000C02C4F84462D3F81C4240EA0400C3F8F2 -:102C60001C02CBD1D3F8002222F00102C3F80022CB -:102C7000EB6923F00073EB61EB69F0BD0122C3F84F -:102C80004012C3F84412C3F80412C3F81412C3F874 -:102C90000C22C3F81C22E5E7001002400000FFFFF1 -:102CA000A8230020184A08B5916A8B688B6013F03E -:102CB000010104D013F00C0F18BF4FF48031D80578 -:102CC00006D513F4406F14BF41F4003141F0020106 -:102CD000D80306D513F4402F14BF41F4802141F0EE -:102CE0000401D3690BB108489847302383F3118856 -:102CF0000021064800F048FB002383F31188BDE85B -:102D0000084000F099BD00BFA8230020B023002098 -:102D100038B5124CA36ADD68AA0712D05A6922F0AE -:102D200002025A61A36913B101212046984730235A -:102D300083F3118800210A4800F026FB002383F367 -:102D40001188EB0606D51021A36AD960236A0BB15E -:102D500002489847BDE8384000F06EBDA823002027 -:102D6000B823002038B5124CA36A1D69AA0712D0F7 -:102D70005A6922F010025A61A36913B10221204658 -:102D80009847302383F3118800210A4800F0FCFAA9 -:102D9000002383F31188EB0606D51021A36A19617D -:102DA000236A0BB102489847BDE8384000F044BDA3 -:102DB000A8230020B823002038B50F4CA36A5D6813 -:102DC0002A075D600AD5042222701A6822F00202E6 -:102DD0001A60636A13B10021204698476B0706D535 -:102DE000A36A9969236A13B1034809049847BDE8A7 -:102DF000384000F021BD00BFA823002010B50E4CC4 -:102E0000204600F02FF90D4B0B211320A36200F098 -:102E100009F90B21142000F005F90B21152000F011 -:102E200001F90B21162000F0FDF8BDE8104000224A -:102E30000E201146FFF7B0BEA8230020006400401A -:102E40000F4B10B59842044605D10E4BDA6942F09B -:102E50000072DA61DB690122A36A1A60A36A5A6808 -:102E6000D20707D5626851681268D9611A60064AAC -:102E70005A6110BD0121082000F0B0F9EEE700BF53 -:102E8000A8230020001002405B87010003291AD804 -:102E9000DFE801F0020A0F14836A9B6813F0E05F19 -:102EA00014BF012000207047836A9868C0F38060D7 -:102EB0007047836A9868C0F3C0607047836A9868F7 -:102EC000C0F30070704700207047000010B5032960 -:102ED00027D8DFE801F002272B2F836A9968C1F316 -:102EE0000161183103EB01131078840648BF546860 -:102EF000C0F3001158BF94884FEA410148BF41EA2E -:102F0000C40100F00F00586048BF41F00401906810 -:102F100058BF41EA4451D26841F001019860DA603B -:102F2000196010BD836A03F5C073DDE7836A03F59A -:102F3000C873D9E7836A03F5D073D5E701290AD0AE -:102F400002290FD081B9836ADA68920701D1186922 -:102F500003E001207047836AD86810F0030018BFAF -:102F600001207047836AF2E70020704710B539B935 -:102F7000836AD96889071BD11B699C0704D110BDDE -:102F8000012915D00229FAD1816AD1F8C031D1F8CE -:102F9000C441D1F8C8011061D1F8CC0150612020A2 -:102FA00008610869800717D1486940F0100012E0F5 -:102FB000816AD1F8B031D1F8B441D1F8B8011061CB -:102FC000D1F8BC0150612020C860C868800703D1D7 -:102FD000486940F002004861C3F34000C3F3800138 -:102FE000000140EA4111107920F0300001431171D5 -:102FF00089064BBF91681189DB085B0D4CBF63F3F9 -:103000001C0163F30A01137948BF916064F3030361 -:1030100013714FEA14234FEA144458BF11811370FF -:103020005480ACE70122090100F1604303F56143DC -:10303000C9B283F8001300F01F039A4043099B00B4 -:1030400003F1604303F56143C3F880211A607047C0 -:10305000090100F16040C9B200F56D40017670478A -:10306000FFF7CCBE01230370002300F10802C0E982 -:10307000022200F11002C0E90422C0E90633C0E9CF -:10308000083343607047000010B53023044683F3D3 -:103090001188022341600370FFF7D2FE0423002051 -:1030A000237080F3118810BD2DE9F0411F460446BE -:1030B0000D461646302383F3118800F10808237863 -:1030C000052B0DD029462046FFF7E0FE40B12046F3 -:1030D00032462946FFF7FAFE002080F3118808E007 -:1030E0003946404600F040F90028E8D0002383F339 -:1030F0001188BDE8F08100002DE9F0411F4604462B -:103100000D461646302383F3118800F1100823780A -:10311000052B0DD029462046FFF710FF40B1204671 -:1031200032462946FFF722FF002080F3118808E08D -:103130003946404600F018F90028E8D0002383F310 -:103140001188BDE8F08100000023826803750369DF -:103150001B6899689142FBD25A6803604260106014 -:103160005860704700238268037503691B6899687B -:103170009142FBD85A680360426010605860704703 -:1031800008B50846302383F311880B7D032B05D047 -:10319000042B0DD02BB983F3118808BD00228B6955 -:1031A0001A604FF0FF338361FFF7CEFF0023F2E791 -:1031B000D1E9003213605A60F3E70000FFF7C4BFA3 -:1031C000054BD96808751868026853601A600122B7 -:1031D0000275D860FDF79ABBD823002030B50C4BA0 -:1031E0000446DD684B1C87B00FD02B466846094A61 -:1031F00000F0F0F82046FFF7E3FF009B13B16846AC -:1032000000F0F0F8A86907B030BDFFF7D9FFF9E783 -:10321000D823002081310008044B1A68DB689068CD -:103220009B68984294BF002001207047D82300205B -:10323000084B10B51C68D868226853601A600122D8 -:103240002275DC60FFF78EFF01462046BDE8104086 -:10325000FDF75CBBD8230020044B1A68DB6892683A -:103260009B689A4201D9FFF7E3BF7047D82300203B -:1032700038B501230025064C0649074823706560D0 -:1032800000F020FB0223237085F3118838BD00BFB6 -:1032900030250020A43D0008D823002000F0B4B859 -:1032A000EFF3118020B9EFF30583302282F3118808 -:1032B0007047000010B530B9EFF30584C4F308047B -:1032C00014B180F3118810BDFFF7C6FF84F3118895 -:1032D000F9E700008B60022308618B820846704783 -:1032E0008368A3F1440243F8142C026943F8442C88 -:1032F000426943F8402C094A43F8242CC268A3F1E0 -:10330000200043F8182C022203F80C2C002203F8AA -:103310000B2C034A43F8102C704700BF1D0900080E -:10332000D823002008B5FFF7DBFFBDE80840FFF712 -:1033300045BF0000024BDB6898610F20FFF740BFDC -:10334000D8230020302383F31188FFF7F3BF000058 -:1033500008B50146302383F311880820FFF73EFFAC -:10336000002383F3118808BD064BDB6839B142683E -:1033700018605A60136043600420FFF72FBF4FF0BE -:10338000FF307047D823002038B504460D4620682A -:10339000844200D138BD036823605C608561FFF71B -:1033A0000DFFF4E710B50A4C23699A6891420CD8D6 -:1033B0005A6881600360426010609A685860511AD0 -:1033C00099604FF0FF33A36110BD1B68891AECE7C9 -:1033D000D8230020C0E90323002310B410BC4361AC -:1033E000FFF7E0BF036881689A680A449A60426800 -:1033F00013605A6000234FF0FF320360014B9A6163 -:10340000704700BFD823002070B5124D2A46EB69E3 -:103410000133EB6152F8103F934206D030269A6890 -:10342000013A9A602C69A36803B170BDD4E9002108 -:103430000A605160236083F311882046D4E9033188 -:10344000984786F3118861690029EBD02046FFF781 -:10345000A9FFE7E7D823002000207047FEE700001F -:10346000704700004FF0FF3070470000BFF34F8FF0 -:10347000024AD368DB07FCD4704700BF002002403B -:1034800008B5074B1B7853B9FFF7F0FF054B1A69D6 -:10349000120641BF044A5A6002F188325A6008BDE0 -:1034A00048250020002002402301674508B5054B50 -:1034B0001B7833B9FFF7DAFF034A136943F080033F -:1034C000136108BD48250020002002407F289ABFD4 -:1034D00000F5003080020020704700004FF480604B -:1034E00070470000802070477F2808B50BD8FFF791 -:1034F000EDFF00F580630268013204D1043083429D -:10350000F9D1012008BD0020FCE700007F2810B59C -:1035100004461CD8FFF7AAFFFFF7B2FFF3220D4BBA -:103520004FF48061DA6002221A61FFF7CFFF586121 -:103530001A6942F040021A61FFF798FF00F004F99F -:10354000FFF7B4FF2046BDE81040FFF7CDBF0020D5 -:1035500010BD00BF002002402DE9F843054612F0DF -:103560000100144606D040F2F32200201E4B1A60E0 -:10357000BDE8F8831D4BAA189A4204D94FF43E7255 -:10358000194B1A60F4E7FFF77BFF4FF00109FFF7D3 -:103590006DFFDFF85C806D1A012C0F4605EB01060C -:1035A00003D8FFF783FF0120E2E73B88C8F81090BB -:1035B00033800020FFF75AFFC8F81000338831F835 -:1035C000022B9BB29A420CD040F20F32064B1A608B -:1035D000084B1E60084B1C60084B1F60FFF766FF1E -:1035E000C6E7023CD8E700BF4425002000000208DF -:1035F0000020024038250020402500203C250020E6 -:10360000084908B50B7828B11BB9FFF739FF01232A -:103610000B7008BD002BFCD0BDE808400870FFF718 -:1036200045BF00BF4825002070B5FFF739FE4FF4B5 -:103630007A710D4B0D4EDB69326801FB03F3934247 -:1036400037BF0B4A0A495168156836BF4C1CD1E98F -:10365000005454605D1944F100043360FFF72AFE02 -:103660002846214670BD00BFD82300204C250020ED -:103670005025002070B5FFF713FE4FF47A710F4B01 -:103680000F4EDB69326801FB03F3934237BF0D4AEB -:103690000C49516815683ABF4C1C5460D1E900547C -:1036A0005D1944F100043360FFF704FE4FF47A72B1 -:1036B000002328462146FCF735FF70BDD8230020A3 -:1036C0004C2500205025002010B5094C013AD2B2FB -:1036D000FF2A00D110BD500854F82030013054F8B2 -:1036E00020009BB243EA004341F8043BEEE700BFF1 -:1036F000046C004010B50748013AD2B2FF2A00D14D -:1037000010BD0C88530840F823404C88013340F822 -:103710002340F1E7046C004007B50122002001A915 -:10372000FFF7D2FF019803B05DF804FB13B5044620 -:10373000FFF7F2FFA04205D00122002001A9019469 -:10374000FFF7D8FF02B010BD7047000045F2555298 -:10375000064B1A6002225A6040F6FF729A604CF6DD -:10376000CC421A600122024B1A70704700300040B0 -:103770005C250020034B1B781BB14AF6AA22024BA2 -:103780001A6070475C25002000300040044B1A6826 -:103790002AB902F1804202F50432526A1A60704777 -:1037A000582500204FF08072014B5A62704700BFCD -:1037B0000010024008B5FFF7E9FF024B1868C0F39C -:1037C000407008BD5825002008B5FFF7DFFF024B09 -:1037D0001868C0F3007008BD58250020EFF3098376 -:1037E000203383F30988002383F311887047000096 -:1037F000302080F3118862B60C4B0D4AD96821F451 -:10380000E0610904090C0A43DA60D3F8FC20094995 -:1038100042F08072C3F8FC200A6842F001020A609C -:103820002022DA7783F82200704700BF00ED00E025 -:103830000003FA05001000E0302310B583F311886F -:103840000B4B5B6813F400630FD0EFF309844FF068 -:103850008073203CE36184F30988FFF7DDFC10B13D -:10386000044BA36110BD044BFBE783F31188F9E718 -:1038700000ED00E02F090008320900087047000041 -:10388000FEE700000A4B0B480B4A90420BD30B4B50 -:10389000C11EDA1C121A22F003028B4238BF00222A -:1038A0000021FDF7FFBE53F8041B40F8041BECE7B2 -:1038B000243E0008E0250020E0250020E02500202F -:1038C000FEE7000070B5002504461A4B86B058602C -:1038D000856201630E46FFF78BFF04F11003C4E914 -:1038E00004334FF0FF33A361134BE561D9692B46D5 -:1038F0000A462046C4E9082304F134018023C4E9C0 -:1039000000440E4AA560E5622565FFF7E3FC01234C -:103910000B4AE06003750092726868460192B268D3 -:10392000CDE90223074BCDE90435FFF7FBFC06B0D8 -:1039300070BD00BF30250020D8230020B03D000816 -:10394000B53D0008C138000800F030B808B500F0F7 -:1039500063F9FFF78DFCBDE80840FFF717BF0000D3 -:10396000704700004FF0FF310E4B1A6919611A6958 -:1039700000221A611869D868D960D968DA60DA68F3 -:10398000DA6942F08052DA61DA69DA6942F000629B -:10399000DA61054ADB69136843F48073136000F051 -:1039A0001BB900BF0010024000700040194B1A689C -:1039B00042F001021A601A689007FCD51A6802F0FA -:1039C000F9021A6000225A605A6812F00C0FFBD1FB -:1039D0001A6842F480321A601A689103FCD55A685A -:1039E00042F4E8125A601A6842F080721A601A684B -:1039F0009201FCD51221084A5A60084A11605A689F -:103A000042F002025A605A6802F00C02082AFAD107 -:103A1000704700BF0010024000641D0000200240FB -:103A2000084A08B5516913680B4003F0010353615C -:103A300023B1054A13680BB150689847BDE80840A8 -:103A4000FFF7FABE0004014060250020084A08B5CF -:103A5000516913680B4003F00203536123B1054A17 -:103A600093680BB1D0689847BDE80840FFF7E4BE03 -:103A70000004014060250020084A08B55169136818 -:103A80000B4003F00403536123B1054A13690BB1E2 -:103A900050699847BDE80840FFF7CEBE00040140DA -:103AA00060250020084A08B5516913680B4003F0EF -:103AB0000803536123B1054A93690BB1D069984754 -:103AC000BDE80840FFF7B8BE0004014060250020B3 -:103AD000084A08B5516913680B4003F0100353619D -:103AE00023B1054A136A0BB1506A9847BDE80840F4 -:103AF000FFF7A2BE0004014060250020174B10B55F -:103B00005A691C68144004F478725A61A30604D5FB -:103B1000134A936A0BB1D06A9847600604D5104ADD -:103B2000136B0BB1506B9847210604D50C4A936B6D -:103B30000BB1D06B9847E20504D5094A136C0BB161 -:103B4000506C9847A30504D5054A936C0BB1D06C13 -:103B50009847BDE81040FFF76FBE00BF000401406A -:103B6000602500201A4B10B55A691C68144004F4F3 -:103B70007C425A61620504D5164A136D0BB1506D33 -:103B80009847230504D5134A936D0BB1D06D984720 -:103B9000E00404D50F4A136E0BB1506E9847A10490 -:103BA00004D50C4A936E0BB1D06E9847620404D5CD -:103BB000084A136F0BB1506F9847230404D5054A88 -:103BC000936F0BB1D06F9847BDE81040FFF734BE3C -:103BD0000004014060250020062108B50846FFF7D3 -:103BE00021FA06210720FFF71DFA06210820FFF71A -:103BF00019FA06210920FFF715FA06210A20FFF716 -:103C000011FA06211720FFF70DFABDE8084006213A -:103C10002820FFF707BA000008B5FFF7A3FE054804 -:103C200000F00CF8FFF71CFAFFF79AFEBDE8084019 -:103C300000F002B8BC3D000800F042B8002319466D -:103C40001C4A0133102BC2E9001102F10802F8D11D -:103C5000194B9A6942F07D029A619B690268174B81 -:103C6000DA6082685A6042681A60C26803F580634D -:103C7000DA6042695A6002691A608269C3F80C24EA -:103C8000026AC3F80424C269C3F80024426AC3F874 -:103C90000C28C26AC3F80428826AC3F80028026BA1 -:103CA000C3F80C2C826BC3F8042C426BC3F8002CB5 -:103CB000704700BF6025002000100240000801404E -:103CC0004FF0E023044A08215A6100229A6107223A -:103CD0000B201A61FFF7BCB93F19010008B530236A -:103CE00083F31188FFF7DAFA002383F3118808BD04 -:103CF00008B5FFF7F3FFBDE80840FFF79DBD0000E2 -:103D000010B501390244904201D1002005E003784A -:103D100011F8014FA34201D0181B10BD0130F2E78A -:103D20002DE9F0419BB10446C91A1778014403F10B -:103D3000FF3C8C42204601D9002008E00578013480 -:103D4000BD42F6D10CEB0405D618A54201D1BDE861 -:103D5000F08115F8018D16F801EDF045F5D0E8E792 -:103D6000034611F8012B03F8012B002AF9D1704703 -:103D70006F72672E6172647570696C6F742E663134 -:103D800030332D54726967676572000040A2E4F118 -:103D9000646891060041A3E5F2656992070000009E -:103DA00063300000A03D00083024002030250020B2 -:103DB0006D61696E0069646C6500000000180000A8 -:103DC00044444144445449440100000042444444B2 -:103DD00044444444000000004444444444444444B3 -:103DE00000000000444444444444444400000000B3 -:103DF00044444444444444445CC7FF7F0100000001 -:103E0000E803000000000000009C0100000000002A -:103E1000640000000000000040420F00FE2A010084 -:043E2000D2040000C8 +:10052000704700BF02E000F000F8FEE772B6264810 +:1005300080F30888254880F3098825482549086004 +:10054000022080F31488BFF36F8F03F021F803F0CB +:1005500085F84FF0553020491B4A91423CBF41F885 +:10056000040BFAE71D49194A91423CBF41F8040BBC +:10057000FAE71B491B4A1C4B9A423EBF51F8040B39 +:1005800042F8040BF8E700201849194A91423CBF91 +:1005900041F8040BFAE702F0FFFF03F061F8154C95 +:1005A000154DAC4203DA54F8041B8847F9E700F014 +:1005B0003FF8124C124DAC4203DA54F8041B884742 +:1005C000F9E702F0E7BF0000000900200011002059 +:1005D0000000000808ED00E00001002000090020F4 +:1005E000103B0008001100202411002028110020D9 +:1005F000D4250020600100086001000860010008A7 +:10060000600100082DE9F04FC1F80CD0C3689D4689 +:10061000BDE8F08F002383F311882846A04700200F +:1006200002F0E2FCFEE702F07BFC00DFFEE70000E8 +:10063000F8B500F037FE02F0F9FE074602F044FF7D +:10064000064600283ED12B4B9F423BD001339F42B0 +:100650003BD0294B27F0FF029A4239D1F8B200F083 +:10066000FDFB354642F2107400F0FEFB08B1002499 +:10067000254601F0FFF878B30024032000F042F88B +:10068000254636B11D4B9F4203D0002402F014FFD3 +:100690002546002002F0D4FE194B9B6813F040035E +:1006A0001FD00DB100F044F800F03EFC01F076F9E7 +:1006B0000546C4B101F072F9401BA04213D900F005 +:1006C00037F8F3E735460024CEE704460125CBE7AB +:1006D00005464FF47A74C7E7B4F57A7F08BF012561 +:1006E000CFE71C46E0E700F0D1FC012002F082FCDD +:1006F000DFE700BF010007B0000008B0263A09B0EC +:10070000000C0140084B187003280CD8DFE800F0FB +:1007100008050208022000F021BE022000F016BEEB +:100720000022024B5A607047281100202C11002033 +:1007300038B501F09FF830B103221F4B1A70002228 +:100740001E4B5A6038BD1E4B1E4A19680131F9D044 +:1007500004339342F9D11C4C194DD4F80424AA4215 +:10076000F0D31A4B9B6803F1006303F5C8439A4228 +:10077000E8D202F075FE02F087FE002000F0ACFD2A +:100780000220FFF7BFFF124BDA690022DA61D96954 +:1007900099699A619B6972B64FF0E023C3F8085DCE +:1007A0003021D4F80034D4F8042481F311889D4614 +:1007B00083F308881047C5E7281100202C1100207A +:1007C0000064000820640008006000080011002098 +:1007D0000010024049F26900084A136899B21B0CE4 +:1007E00000FB013344F250611360054B186882B27C +:1007F000000C01FB0200186080B27047201100203D +:100800001C11002010B504460021102200F0C2FD8A +:10081000034B03CB206061601868A06010BD00BF6F +:10082000E8F7FF1F2DE9F0410026ADF54E7D6CACD9 +:1008300040F2751207460D460EA831460D9600F09F +:10084000A9FD4FF4C4723146204600F0A3FD01F02B +:10085000A5F84FF47A72B0FBF2F0244B0DF1340896 +:10086000186093E80700022384E807000DF5E9709B +:100870002382FFF7C7FF4EF603031D4906A8238412 +:1008800003F0F8F81A230DF2E32284F832310DF167 +:10089000300C06AB1E4603CE6645106051603346F1 +:1008A00002F10802F6D13388414613802046012226 +:1008B00000F0BCFD00230393AB7E80B2029305F1F0 +:1008C000190301930123CDE904800093384605A361 +:1008D000D3E90023E97E01F0A7FB0DF54E7DBDE8CD +:1008E000F08100BF9E6AC421818A46EE3411002047 +:1008F000843A00082DE9F041264D80462B7A0C46BB +:10090000DAB0FBB9204627A900F0A0FE0746002870 +:1009100036D19DF89D60C82E32D801464FF4FA7248 +:10092000284600F037FD32460DF19E0105F1090021 +:1009300000F01EFD9DF89C302E4477722B720BB98F +:10094000E37E2B728122002106AD27A800F022FD54 +:100950000122294627A800F0B5FE00230393A37EB9 +:1009600080B2029304F1190301932823CDE90450C6 +:100970000093404605A3D3E90023E17E01F054FB38 +:100980005AB0BDE8F08100BFAFF30080264172721B +:10099000DF25D7B77C210020F0B54FF48A750024FD +:1009A000234EF1B005FB006596F8D830D8222146D9 +:1009B00085F8DC3085F8E8403AA800F0EBFC06F159 +:1009C000090000F0DFFCD5F8E430C2B206AF8DF8C4 +:1009D000F00006F109010DF1F100CDE93A3400F023 +:1009E000C7FC394601223AA800F098FE80B2CDE952 +:1009F000047008230127CDE9023706F1D8030193DB +:100A00003023317A00930B4807A3D3E9002301F088 +:100A10000BFBA04206DD00F0C1FFC5F8E000384640 +:100A200071B0F0BD2046FBE778F6339F93CACD8DB9 +:100A30007C2100204C210020F0B51E4E1E4F1F4D82 +:100A400085B0304601F01CFB044660B31022002143 +:100A5000684600F09FFC4FF00003227B6068A168AD +:100A600062F303038DF8003002AB03C3019B2268DD +:100A7000384662F31C0301939DF800306A4643F048 +:100A800020038DF800300023194602F085F9044652 +:100A900020B9304601F0F8FA2C70D2E72B78072BFA +:100AA00003D801332B7005B0F0BD024801F0ECFA19 +:100AB000F9E700BF4C210020A82300207523002067 +:100AC00070B50D4614461E4601F00AFA50B9022EC2 +:100AD00010D1012C0ED112A3D3E900230120C5E9C6 +:100AE000002307E0282C10D005D8012C09D0052CB4 +:100AF0000FD0002070BD302CFBD10BA3D3E9002315 +:100B0000ECE70BA3D3E90023E8E70BA3D3E9002329 +:100B1000E4E70BA3D3E90023E0E700BFAFF30080D5 +:100B2000401DA12026812A0B78F6339F93CACD8DD4 +:100B30009E6AC421818A46EE26417272DF25D7B7AC +:100B4000F017304A39059E5638B505460E4C00213F +:100B5000013500F0E3FBA4F8F051B4F8F00100F027 +:100B6000C5FB78B1B4F8F00100F0D0FB014648B9FC +:100B7000B4F8F00100F0D2FBB4F8F0310133A4F87E +:100B8000F031EAE738BD00BF7C2100202DE9F04FAD +:100B90008DB000AF04460D4601F0A2F9002846D101 +:100BA0002B7E022B1AD1EB8A012B17D100F0F6FE17 +:100BB0000646FFF70FFE4FF4C873B0FBF3F202FBDB +:100BC0001303DFF878829BB206F516763344C8F833 +:100BD0000030EB7E33B90022994B1A703437BD4692 +:100BE000BDE8F08F284607F11C0100F0EDFC00285D +:100BF000F4D107F10C00FFF705FEBD7F07F10C01F2 +:100C00002A4607F11F0002F005FF0028E3D10F2D4F +:100C100008D88B4B1D70D8F80030A3F51673C8F8B0 +:100C20000030DBE72046397F01F052F9D6E7EB8A46 +:100C3000282B6BD010D8012B63D0052BCED1BFF35E +:100C40004F8F8049804BCA6802F4E0621343CB6047 +:100C5000BFF34F8F00BFFDE7302BBFD17B4CEA7E47 +:100C6000237A9A42BAD194F8DC206B7E9A42B5D1AD +:100C7000284604F1EA0100F07DFD06460028ADD1CA +:100C8000012384F8E83000F089FED4F8E030C01A7F +:100C9000192840F6B83338BF1920984228BF1846A3 +:100CA000FFF7C8FB6A49FFF75BFA05462068FFF7C4 +:100CB000C1FB6849FFF754FA01462846FFF70AFBD3 +:100CC000FFF710FC20604FF48A7194F8D9307B60F4 +:100CD0007A68636801FB02F5621992F8E80050B186 +:100CE000D2F8E400E946834215D0002382F8E830C8 +:100CF000C2F8E030CD466368574A9B0A013313813E +:100D00006CE729462046FFF78DFD67E72946204618 +:100D1000FFF7F0FD62E7B2F8EC803B6008F1030AF0 +:100D20004FEA9A0A4FEA8A02D11DC908A9EBC1030A +:100D30009D46EB460021584600F02CFB05F1EE01E4 +:100D400042465846214400F013FB3B6813B901208A +:100D500000F0C2FA94F8D20000F0C8FA054630B9A3 +:100D6000207200F0E3FA284600F0B6FAC2E7D4F8A1 +:100D7000D4303BB994F8D200B4F8F031834201D8B2 +:100D8000FFF7E2FED4F8D43043449D4208D294F8F1 +:100D9000D200B4F8F0310130834201D8FFF7D4FE1D +:100DA000594660685FFA8AF200F0FCFA08B9CD464D +:100DB00089E7636894F8D20043446360D4F8D43080 +:100DC00008EB030AC4F8D4A000F090FA824509D3D6 +:100DD00094F8D230D4F8D4000133401B84F8D230D8 +:100DE000C4F8D400B8F1FF0F0FD80025257200F029 +:100DF0009DFA284600F070FA00F03CFD164B188171 +:100E000008B9FFF795FCCD46E8E64FF48A727B6897 +:100E100094F8D90002FB0343D3F8E42083F8E86098 +:100E200002F58072C3F8E060C3F8E420FFF7B4FD78 +:100E3000FFF702FE84F8D960B9E700BF482100201F +:100E40004521002000ED00E00400FA057C2100208F +:100E5000CDCCCC3D6666663F34110020014B187046 +:100E6000704700BF4011002030B54FF00054254BB3 +:100E7000226885B09A4207D002F030FB0446C0B920 +:100E80000024204605B030BD0025627D1E4B1F4862 +:100E90001A70237DC92203721D49C0F8E45009303D +:100EA00000F066FA2046E022294600F073FA012499 +:100EB000E7E7184A184DD36943F00073D361AA6D70 +:100EC000164B9A42DCD12B6E013B7E2BD8D8144AAC +:100ED00001AB07CA83E807001846032100F09AFC1B +:100EE0006B6D83424FF00003CAD12A6D8A4203BF63 +:100EF000AB652A6E044B1C4601BF1A70EA6D094BA4 +:100F00001A60BEE79AAD44C5401100207C21002044 +:100F10001600002000100240006600405041A0B0C2 +:100F200058660040181100202DE9F04385B000F00C +:100F3000A1FC0223494C637100230293484B20819A +:100F4000D3F800C0BCF57A7F12D3464F464BB7FBAF +:100F5000FCF59C458CBF0A231123B5FBF3F603FB7C +:100F60001652591EC8B2002A3ED002290B46F4D8A8 +:100F70009DF80B303D495A1E9DF80A303C48013B14 +:100F80001B0443EA0253BDF80820013A13434B60A7 +:100F900001F0F2FE00230193364B374900934FF4E2 +:100FA0008052364B364800F069FF364B197811B144 +:100FB000334800F08DFF00F0F1FC0546FFF70AFC16 +:100FC0004FF4C873B0FBF3F202FB130305F5167080 +:100FD0009BB218442C4B186002F076FA08B10F232C +:100FE000238105B0BDE8F083731EB3F5806FBFD2D7 +:100FF0004FF47A75C0EBC00E0EF103034FEAE3091C +:1010000009FB0555C3F3C703C11AC9B209F10108A9 +:101010008844B5FBF8F5B5F5617F08D90EF1FF33CB +:10102000C3F3C703C11A581E0F28C9B214D84A1EE9 +:10103000072A8CBF00220122581800FB0660B7FB6C +:10104000F0F7BC4594D1002A92D0ADF808608DF835 +:101050000A308DF80B108BE71346EDE734110020B2 +:1010600018110020005125023F420F0010110020EE +:10107000A8230020C10A0008441100208D0B00089D +:101080004C21002040110020482100202DE9F04F84 +:1010900080A7D7E900670FF20429D9E90089734DC9 +:1010A00093B00DF1300AFFF7C7FC1822002150461B +:1010B00000F070F9DFF8B8B16E4C002352461946C3 +:1010C000584601F091FE014650BB102208A800F0DE +:1010D00061F9E36883F01003E36000F061FC0DF157 +:1010E000240C0B4612A9024611E903008CE8030008 +:1010F0009DF83410C1F30300890649BF0E99BDF86D +:101100003810C1F31C0141F0004158BFC1F30A017E +:101110008DF82C000891284608A901F095F9CCE734 +:10112000284600F0DDFE0446002847D100F036FCDA +:10113000DFF844B1DBF8003098423FD300F02EFCDA +:101140000790FFF747FB4FF4C873B0FBF3F101FBC7 +:101150001300079A83B202F516701844CBF800000A +:10116000DFF818B18DF820409BF8001011B9012369 +:101170008DF8203050460791FFF744FB07990DF199 +:101180002100C1F11004E4B2062C28BF062451440A +:10119000224600F0EDF808AB039318230293384B76 +:1011A000013401930123E4B2009332463B462846C2 +:1011B000049400F0DBFE00238BF8003000F0EEFB1F +:1011C000304A314C1368C31AB3F57A7F30D31060BC +:1011D00000F0E6FB02460B46284600F05FFF28467B +:1011E00000F07EFE20B3237ADFF8A0B0002B14BFFE +:1011F000032302238BF8053000F0D0FB4FF47A7301 +:10120000B0FBF3F00122CBF800005146584600F045 +:10121000B3F9182302931E4B80B2019340F2551389 +:10122000CDE903A0009342464B46284600F09EFEBF +:10123000237ABBB100F0B2FB94F8E83073B9D4F86C +:10124000E03043B1C01A2368FA2B38BFFA230533C4 +:10125000B0EB430F02D30020FFF79EFB237A002B55 +:101260007FF41FAF13B0BDE8F08F00BF4C2100200A +:10127000A82300200008014048210020452100202B +:1012800044210020702300207C2100203411002004 +:1012900074230020401DA12026812A0BF1C6A7C17E +:1012A000D068080F70B501F07DFF0024084E094D8D +:1012B000308028683388834208D901F06FFF2B689B +:1012C00004440133B4F5C84F2B60F2D370BD00BFA6 +:1012D000A42300207823002001F0F2BF00F1006079 +:1012E000920000F5C84001F097BF0000054B1A6856 +:1012F000054B1B889B1A834202D9104401F04EBF54 +:101300000020704778230020A4230020024B1B6894 +:10131000184401F049BF00BF78230020024B1B682E +:10132000184401F053BF00BF78230020064991F80C +:10133000243033B100230822086A81F82430FFF7F3 +:10134000CDBF0120704700BF7C230020022802BFD0 +:101350001022014B1A61704700080140022802BFA9 +:101360004FF48012014B1A61704700BF0008014022 +:10137000002310B5934203D0CC5CC4540133F9E789 +:1013800010BD000003460246D01A12F9011B0029C5 +:10139000FAD1704703460244934202D003F8011B7E +:1013A000FAE770472DE9F8431F4D144695F82420BD +:1013B0000746884652BBDFF870909CB395F82430FE +:1013C0002BB92022FF2148462F62FFF7E3FF95F853 +:1013D00024004146C0F10802A24228BF224605EB84 +:1013E0008000D6B29200FFF7C3FF95F82430A41B0B +:1013F0001E44F6B2082E17449044E4B285F82460E7 +:10140000DBD1FFF793FF0028D7D108E02B6A03EB6D +:1014100082038342CFD0FFF789FF0028CBD1002081 +:10142000BDE8F8830120FBE77C2300202DE9F0478D +:101430000D46044600219046284640F27912FFF7F7 +:10144000A9FF234620220021284600F09FFF022208 +:1014500020212846231D00F099FF0322222128463F +:10146000631D00F093FF032225212846A31D00F0F1 +:101470008DFF10222821284604F1080300F086FF82 +:1014800008223821284604F1100300F07FFF0822CB +:101490004021284604F1110300F078FF082248217A +:1014A000284604F1120300F071FF20225021284643 +:1014B00004F1140300F06AFF40227021284604F171 +:1014C000180300F063FF0822B021284604F120032E +:1014D00000F05CFF0822B821284604F1210300F047 +:1014E00055FFC02604F122073B4631460822284614 +:1014F000083600F04BFFB6F5A07F07F10107F3D1E6 +:1015000008223146284604F1320300F03FFF00274D +:1015100004F1330A94F832304FEAC7099F4209F5C3 +:10152000A47615D3B8F1000F08D13146072228461A +:1015300004F5997300F02AFF09F24F16274694F834 +:1015400032213B1B93420CD3F01DC008BDE8F0874D +:101550000AEB070308223146284600F017FF01373F +:10156000D8E7314607F233130822284600F00EFF71 +:1015700008360137E3E7000038B50C460021054680 +:1015800021600346C4F803102046202200F0FEFE2E +:1015900020462B1D0222202100F0F8FE20466B1D64 +:1015A0000322222100F0F2FE2046AB1D032225215A +:1015B00000F0ECFE20461022282105F1080300F07F +:1015C000E5FE072038BD00000023F7B50E460546AE +:1015D000047F07220091194600F09AFD731C0093C6 +:1015E000012200230721284600F092FDC4B9B31C54 +:1015F0000093052223460821284600F089FD0D248A +:101600003746B278BB1B934211D32B7FE01DC00835 +:10161000AC8ABBB9A04294BF0020012003B0F0BD4A +:10162000AB8A0824DB00083BDB08B370E8E7FB1C4F +:101630002146009308220023284600F069FD083463 +:101640000137DEE7001B18BF0120E7E70023F7B5ED +:101650000E46047F082200911946054600F058FD09 +:10166000731CC4B90822009311462346284600F093 +:101670004FFD1024012372785F1C013B934211D36C +:101680002B7FE01DC008AC8ABBB9A04294BF0020EC +:10169000012003B0F0BDAB8A0824DB00083BDB0867 +:1016A0007370E7E7F31921460093082200232846C8 +:1016B00000F02EFD08343B46DDE7001B18BF01207B +:1016C000E7E70000F8B50E460546144600218122E2 +:1016D0003046FFF75FFE2B4608220021304600F01F +:1016E00055FE7CB90722082130466B1C00F04EFEE7 +:1016F0000F2401236A785F1C013B934204D3E01D51 +:10170000C008F8BD0824F4E72146EB19082230464A +:1017100000F03CFE08343B46ECE70000F8B50E460E +:10172000054614460021CE223046FFF733FE2B46F5 +:1017300028220021304600F029FE7CB90822282109 +:10174000304605F1080300F021FE30242F462A7AA6 +:101750007B1B934204D3E01DC008F8BD2824F5E7A5 +:10176000214607F109030822304600F00FFE083435 +:101770000137ECE7F7B5047F0E46009101231022F4 +:101780000021054600F0C4FCC4B9B31C0093092233 +:1017900023461021284600F0BBFC192437467288E6 +:1017A000BB1B9A4211D82B7FE01DC008AC8ABBB985 +:1017B000A04294BF0020012003B0F0BDAB8A1024EA +:1017C000DB00103BDB087380E8E73B1D21460093FC +:1017D00008220023284600F09BFC08340137DEE78E +:1017E000001B18BF0120E7E730B5094D0A449142BC +:1017F0000DD011F8013B5840082340F30004013B91 +:101800002C4013F0FF0384EA5000F6D1EFE730BD1F +:101810002083B8ED4FF0FF33F7B500EB8106194692 +:10182000DFF848C0DFF848E0B0421BD050F8042B86 +:1018300001AF0192042217F8014B81EA04610824E8 +:101840000D46DB184941013C002DBCBF83EA0C0367 +:1018500081EA0E0114F0FF04F2D1013A12F0FF0206 +:10186000E9D1E1E7D843C94303B0F0BD9336EAA913 +:10187000EBE1F042F7B56B46354A106851686A46AD +:1018800003C308233349344802F0D4F8044690BB1C +:101890000A256B46314A106851686A4603C308231B +:1018A0002F492D4802F0C6F80446002847D00369A6 +:1018B000B3F5CE3F43D8B0F86620B2F57A7F3ED17B +:1018C000284A024402F15C018B4238D35C3B224936 +:1018D00000209E1AFFF788FF07463246002004F1D9 +:1018E0006401FFF781FFA3689F4228D1E368984213 +:1018F00008BF002523E00369B3F5CE3F26D8428B0D +:10190000B2F57A7F20D1174A024402F110018B42CE +:1019100018D3103B104900209D1AFFF765FF0646BB +:101920002A46002004F11801FFF75EFFA3689E42DB +:1019300002D1E368984201D00D25AAE70025284688 +:1019400003B0F0BD1025A4E70C25A2E70B25A0E706 +:10195000A03A0008DC9B010000640008A93A0008D6 +:10196000909B0100089CFFF7EFF30983EFF30583D9 +:10197000014B9B6BFEE700BF00ED00E008B5FFF7F1 +:10198000F3FF0000EFF30983EFF30583014B5B6B7B +:10199000FEE700BF00ED00E0FEE7000001F0F6BC4E +:1019A00001F0A2BC2DE9F041456A15B94162BDE8DC +:1019B000F0814B68AC4623F06047C3F38A4616EAD1 +:1019C000230638BF3E464FEAD37EC3F380782B46CA +:1019D0005A68BEEBD27F22F060440AD0002A18DA9F +:1019E000A40CB44217D19D420FD10D60DEE713461F +:1019F000EEE7A74207D102F08044C2F3807242456D +:101A00000BD054B1EFE708D2EDE7CCF800100B6033 +:101A1000CDE7B44201D0B442E5D81A689C46002A0A +:101A2000E5D11960C3E700002DE9F0474FF47F4985 +:101A3000089D01F007044FEAD508224405F0070588 +:101A400000EBD100944201D1BDE8F08704F0070714 +:101A500005F0070A57453E4638BF5646111BC6F1EA +:101A600008068E4228BF0E46E108415C08EBD50E01 +:101A700013F80EC0B94029FA06F721FA0AF1FFB2AD +:101A80008CEA010147FA0AF739408CEA010C03F8A5 +:101A90000EC034443544D5E7082341F2210280EAE0 +:101AA000012001B24000002980B203F1FF33B8BF2A +:101AB000504013F0FF03F4D17047000038B50C46D6 +:101AC0008D18A54200D138BD14F8011BFFF7E4FFC3 +:101AD000F7E700000346406848B1026899895A60F8 +:101AE0005A89013292B291425A8138BF9A81704725 +:101AF00070B504460D4688B0202200216846FFF7E5 +:101B000049FC20460495FFF7E5FF024658B16B46B5 +:101B1000054608AE1C4603CCB442286069602346E3 +:101B200005F10805F6D1104608B070BD082817D990 +:101B300009280CD00A280CD00B280CD00C280CD06B +:101B40000D280CD00E2814BF4020302070470C20E8 +:101B500070471020704714207047182070472020CD +:101B600070470000082817D90C280CD910280CD968 +:101B700014280CD918280CD920280CD930288CBF4F +:101B80000F200E207047092070470A2070470B2055 +:101B900070470C2070470D20704700002DE9F84376 +:101BA000078C0446072F1ED9D0E9029800254FF66E +:101BB000FF73C5F12006A5F1200029FA05F108FA06 +:101BC00006F628FA00F031430143C9B21846FFF780 +:101BD00063FF0835402D0346EBD13A46E169BDE885 +:101BE000F843FFF76BBF4FF6FF70BDE8F8830000C6 +:101BF00010B54B6823B9CA8A63F30902CA8210BDC3 +:101C000004691A681C600361C38A013BC3824A608D +:101C1000EFE700002DE9F84F1D46CB8A0F46C3F3CE +:101C200009010529814692460B4630D00020AAB210 +:101C300007F11A049EB2042E1FFA80F80FD89045BF +:101C400003F1010306D3FB8A0A4462F3090301206E +:101C5000FB821AE01AF800600130E654EAE790458A +:101C6000F1D21C23A1F1050BBBFBF3F203FB12BB6A +:101C70007C681FFA8BF6002C45D14846FFF72AFFF7 +:101C8000044638B978606FF00200BDE8F88F4FF075 +:101C90000008E6E70026066078604FF0000BADB262 +:101CA000454510D90AEB0803221D13F8011B08F162 +:101CB00001089155B1B21B291FFA88F82BD0454570 +:101CC00006F10106F1D8FB8AC3F30902154465F356 +:101CD0000903BCE71C46013292B22368002BF9D1FC +:101CE0006B1F0B441C21B3FBF1F301339BB29A42EF +:101CF000D3D2BBF1000FD0D14846FFF7EBFE20B99D +:101D0000C4F800B0BFE70122E7E7C0F800B05E46C4 +:101D100020600446C1E74545D5D94846FFF7DAFEBD +:101D200008B92060AFE7C0F800B000262060044684 +:101D3000B6E700002DE9F74F1C465B690746884669 +:101D40000092002B00F09780238C2BB1E269002ACF +:101D500000F09180072B33D807F10C00FFF7BAFE93 +:101D6000054628B96FF00205284603B0BDE8F08F9C +:101D700014220021FFF70EFB228CE16905F1080017 +:101D8000FFF7F6FA208C48F00041013080B2FFF7EF +:101D9000E9FEFFF7CBFE013880B2208401302874C1 +:101DA0006369228C1B782A4403F01F0363F03F030E +:101DB0001372384669602946FFF7F4FD0125D3E721 +:101DC0004FF000094FF0800A4E464D4600F10C03DB +:101DD00001930198FFF77EFE83460028C2D01422AB +:101DE0000021FFF7D7FA002E3BD10222009BABF86F +:101DF00008300BF1080E1FFA82FC0CF10100BCF157 +:101E0000060F218C80B201D88E422CD3FFF7AAFE98 +:101E1000FFF78CFE8E4208BF4FF0400A626901381E +:101E2000127880B202F01F0242EA49120BEB000165 +:101E30004AEA020A013048F0004281F808A08BF813 +:101E4000100059463846CBF80420FFF7ABFD238C31 +:101E50000135B3424FF0000A2DB289F00109B8D123 +:101E600082E70022C5E7E169895D01360EF80210BC +:101E7000B6B20132BFE76FF0010575E7F8B5044669 +:101E800015460E46302200211F46FFF783FA069BB7 +:101E9000B5F5001F6360079B28BF4FF6FF72A36272 +:101EA0004FF0000338BF6A09A760E66197B204F1FA +:101EB00010009A4206D800230360A782E38223839E +:101EC000E360F8BD0660013330462036F1E70000DC +:101ED00003781BB94BB2002BC8BF017070470000DC +:101EE00000787047F8B50C46C969074611B9238CCC +:101EF000002B37D1257E1F2D34D8387828BB228C73 +:101F0000072A2CD8268A36F003032BD14FF6FF7010 +:101F1000FFF7D4FD4FF6FF7220F0010036024004B7 +:101F200046EA0565400C45EA4025234629463846E1 +:101F3000FFF700FF002807DD626913780133DBB289 +:101F40001F2B88BF00231370F8BD218A2D0645EA98 +:101F5000012505432046FFF721FE0246E5E76FF025 +:101F60000300F1E76FF00100EEE7000070B50446F2 +:101F70001D4616468AB0282200216846FFF70AFA55 +:101F8000BDF838306946ADF810300F9B20460593F8 +:101F90009DF84030CDE902658DF81830119B07930C +:101FA000BDF84830ADF82030FFF79CFF0AB070BD97 +:101FB0002DE9F041D36905460C4616460BB9138C42 +:101FC0005BBB377E1F2F28D895F80080B8F1000F33 +:101FD00026D03046FFF7E2FD3378210241EAC331D3 +:101FE00041EA0801338A41EA076141EA03410246B6 +:101FF0003346284641F08001FFF79CFE00280ADDA9 +:102000003378012B07D1726913780133DBB21F2BB0 +:1020100088BF00231370BDE8F0816FF00100FAE77C +:102020006FF00300F7E70000F0B504460D461E46CA +:1020300017468BB0282200216846FFF7ABF99DF8C0 +:102040004C3029465A1E534253418DF800309DF8BA +:1020500040306A46ADF81030119B204605939DF83C +:102060004830CDE902768DF81830149B0793BDF8FF +:102070005430ADF82030FFF79BFF0BB0F0BD0000EF +:10208000406A00B104307047436A1A6842620269CC +:102090001A600361C38A013BC38270472DE9F04196 +:1020A000D0F8208014461D4641460027174E09B936 +:1020B000BDE8F081D1E90223A21A65EB0303964241 +:1020C00077EB03031ED2036A8B420DD1FFF790FD1D +:1020D000036A1B68036203690B60C38A0161016ABA +:1020E000013B8846C382E2E7FFF782FD0B68C8F830 +:1020F000003003690B60C38A0161013BC382D8F8D9 +:102100000010D4E788460968D1E700BF80841E002C +:102110002DE9F04F8BB00D4614469B468046DDF806 +:102120005090002800F01A81B9F1000F00F01681DC +:10213000531E3F2B00F21281012A03D1BBF1000F85 +:1021400040F00C810023CDE90833B8F81430B5EB2A +:10215000C30F4FEAC30703D300200BB0BDE8F08FD5 +:102160002B199F42D8F80C3036BF7F1B2746FFB291 +:102170001BB9D8F81030002B7BD0272D4ED8C5F1D5 +:102180002806B7424FF0000334BF3E46F6B2009334 +:1021900029463246D8F8080008ABFFF745FCA7EB04 +:1021A000060A35445FFA8AFA2821B8F8143003F198 +:1021B0000053053BDB000493D8F80C300393039BDA +:1021C00013B1BAF1000F2CD1D8F8100040B1BAF118 +:1021D000000F05D05246009608AB691AFFF724FCA1 +:1021E00038B2002FB8D066070AD00AAB03EBD4018F +:1021F00011F8083C624202F00702134101F8083C62 +:10220000082C3DD9102C40F2B680202C40F2B8802A +:10221000BBF1000F00F09D80082335E0BA46002690 +:10222000C2E7049BE02B28BFE02306930B44AB429C +:10223000059315D95A1B924538BF5246039828BFBB +:10224000D2B20096691A08AB04300792FFF7ECFB94 +:10225000079A1644AAEB020A1544F6B25FFA8AFA04 +:10226000049B069A05999B1A0493039B1B6803938E +:10227000A5E700933A462946D8F8080008ABADE731 +:10228000BBF1000F13D00123B4EBC30F6CD0082CAB +:1022900012D89DF82030621E23FA02F2D50706D527 +:1022A0004FF0FF3202FA04F423438DF820309DF8FA +:1022B000203089F8003050E7102C12D8BDF82030BB +:1022C000621E23FA02F2D10706D54FF0FF3202FA5E +:1022D00004F42343ADF82030BDF82030A9F80030D5 +:1022E0003BE7202C0FD80899631E21FA03F3DA0785 +:1022F00005D54FF0FF3202FA04F40C430894089B12 +:10230000C9F8003029E7402C2BD0DDE90865611EB3 +:10231000C4F12102A4F1210326FA01F105FA02F227 +:1023200025FA03F311431943CB0712D50122A4F177 +:102330002003C4F1200102FA03F322FA01F1A240C2 +:10234000524243EA010363EB430332432B43CDE99B +:102350000823DDE90823C9E90023FEE66FF0010048 +:10236000FBE66FF00800F8E6082CA0D9102CB3D9D2 +:10237000202CEED8C3E7BBF1000FADD0022383E7DA +:10238000BBF1000FBBD004237EE70000012A30B56B +:10239000144638BF01220025402A28BF402285B0BC +:1023A000012CCDE9025517D81B788DF8083053075A +:1023B0000AD004AB03EBD20515F8083C544204F0F4 +:1023C0000704A34005F8083C0346009102A8002139 +:1023D000FFF72AFB05B030BD082CE5D9102C03D837 +:1023E0001B88ADF80830E2E7202C02D81B68029366 +:1023F000DDE7D3E90045CDE90245D8E710B5CB6864 +:102400001BB98B600B618B8210BD04691A681C605C +:102410000361C38A013BC382CA60F0E703064CBF75 +:10242000C0F3C0300220704708B50246FFF7F6FF40 +:10243000022806D15306C2F30F2001D100F0030099 +:1024400008BDC2F30740FBE72DE9F04F93B0CDE99B +:1024500003230A6804461046FFF7E0FF02280CBF7A +:102460000026C2F30626002A0D46824680F2F98134 +:1024700012F0C04940F0F581097B002900F0F1819C +:10248000022803D02378B34240F0EE81C2F3046304 +:102490001046069302F07F030593FFF7C5FF059BE7 +:1024A00000224FEA8348002348EA0A48294448EAC0 +:1024B0004668CE78CDE90823F309834648EA000848 +:1024C000029367D0059B02460093204653466768F7 +:1024D00008A9B847002800F0CA81276A4FB94146C9 +:1024E00004F10C00FFF704FB074690B96FF00200FF +:1024F00054E03B6998450DD03F68002FF9D1414623 +:1025000004F10C00FFF7F4FA07460028EED0236A26 +:102510003B60276297F817C006F01F08CCF3840CC5 +:10252000ACEB08001FFA80FE0028B8BF0EF12000B7 +:10253000A8EB0C031FFA83FEB8BF00B2002B079371 +:10254000BEBF0EF120031BB20793D7E9022152EA66 +:10255000010338D04FF0000C039BDFF8F8E19A1A22 +:10256000049B63EB010196457CEB01032BD36B7B52 +:1025700097F81AE0734519D1029B002B78D00128F7 +:1025800021DC7868F8B9DFF8D0C1944570EB01031D +:1025900016D337E0276A27B96FF00C0013B0BDE8F7 +:1025A000F08F3B699845B5D03F68F4E76A489042A0 +:1025B0007CEB010301D30020F0E7029B002BFAD053 +:1025C000079B0F2B17DCFA7DB30002F0030203F028 +:1025D0007C031343FB7539462046FFF709FB6B7BF1 +:1025E000BB76029B3BB9FB7DC3F38402013262F3ED +:1025F0008603FB75D0E76A7BBB7E9A42DBD1029BE8 +:10260000002B35D0B309022B32D0039B1422BB60C0 +:10261000049B0021FB600DA8FEF7BCFE039B204637 +:102620000A93049BADF83EB00B932B1D0C932B7BB0 +:102630008DF840A0013BDBB2ADF83C30069B8DF835 +:1026400041808DF84230059B0AA98DF8433094F8FB +:102650002C3083F001038DF84430A3689847FB7D4C +:10266000C3F38403013303F01F039B02FB82A2E741 +:10267000FB7DC6F34012B2EBD31F40F0FB80C3F3E7 +:102680008403434540F0F980029A2B7BB609002A67 +:102690004DD0F20762D4032B40F2F280039BAE1DB3 +:1026A000BB60049B3246FB602B7B3946033BDBB2AD +:1026B00004F10C00FFF7AEFA00280CDA3946204688 +:1026C000FFF796FAFB7DC3F38403013303F01F0386 +:1026D0009B02FB820AE7AB88DDE908843B834FF667 +:1026E000FF73C9F12000A9F1200228FA09F104FAC8 +:1026F00000F0014324FA02F211431846C9B2FFF771 +:10270000CBF909F10809B9F1400F0346E9D1314687 +:10271000B8822A7B033AD2B2FFF7D0F9FB7DB882A8 +:10272000DA43C2F3C01262F3C713FB7543E7AEB9D5 +:102730002E1D013B32463946DBB204F10C00FFF797 +:1027400069FA0028BADB2A7B3146013AB88AD2B24C +:10275000E2E700BF80841E0040420F00F98A013B7F +:10276000C1F309010429DAB25DD80023281D07F15D +:102770001B069A4208D910F801CB013306F801C0B4 +:1027800001310529DBB2F4D1934228BF002303991C +:1027900038BF04330A91049938BFDBB20B9107F1BB +:1027A0001B010C91796838BF5B190D910E93FB8A60 +:1027B000ADF83EB0C3F309031A44069BADF83C20C4 +:1027C0008DF84230059B8DF840A08DF8433094F889 +:1027D0002C308DF8418083F001038DF844300023C4 +:1027E0007B602A7BB88A013A291DFFF767F93B8B8A +:1027F000B882834203D12046A3680AA9984720469D +:102800000AA9FFF7FBFDFB7DBA8AC3F384030133FA +:1028100003F01F039B02FB823B8B9A420CBF0020FC +:102820006FF01000BAE67B68002BADD0052001E008 +:1028300033461C301E68002EFAD1091A081D2E1DC1 +:10284000184401EB090CBCF11B0F5FFA89F39BD80C +:102850009A4299D916F8013B09F1010900F8013BA8 +:10286000EFE76FF0090099E66FF00A0096E66FF067 +:102870000B0093E66FF00D0090E66FF00E008DE612 +:102880006FF00F008AE600BFF0B53F4D3F4FEB6998 +:1028900043F00073EB61EB693D4B9B6AD3F8006238 +:1028A0003E4046F00106C3F80062D3F800423C40C7 +:1028B00044EA002444F00104C3F80042002955D042 +:1028C00000200646C3F81C02C3F80402C3F80C0239 +:1028D000C3F8140203EBC00401300E28C4F84062B0 +:1028E000C4F84462F6D100274FF0010C96781488A2 +:1028F00016F0010F18BFD3F804E20CFA04F01CBF65 +:1029000040EA0E0EC3F804E216F0020F18BFD3F827 +:102910000CE203EBC4041CBF40EA0E0EC3F80CE249 +:10292000760748BFD3F8146207F1010744BF064396 +:10293000C3F814625668B942C4F84062966802F15E +:102940000C02C4F84462D3F81C4240EA0400C3F805 +:102950001C02CBD1D3F8002222F00102C3F80022DE +:10296000EB6923F00073EB61EB69F0BD0122C3F862 +:102970004012C3F84412C3F80412C3F81412C3F887 +:102980000C22C3F81C22E5E7001002400000FFFF04 +:10299000A8230020184A08B5916A8B688B6013F051 +:1029A000010104D013F00C0F18BF4FF48031D8058B +:1029B00006D513F4406F14BF41F4003141F0020119 +:1029C000D80306D513F4402F14BF41F4802141F001 +:1029D0000401D3690BB108489847302383F3118869 +:1029E0000021064800F022FB002383F31188BDE894 +:1029F000084000F0ABBD00BFA8230020B02300209A +:102A000038B5124CA36ADD68AA0712D05A6922F0C1 +:102A100002025A61A36913B101212046984730236D +:102A200083F3118800210A4800F000FB002383F3A0 +:102A30001188EB0606D51021A36AD960236A0BB171 +:102A400002489847BDE8384000F080BDA823002028 +:102A5000B823002038B5124CA36A1D69AA0712D00A +:102A60005A6922F010025A61A36913B1022120466B +:102A70009847302383F3118800210A4800F0D6FAE2 +:102A8000002383F31188EB0606D51021A36A196190 +:102A9000236A0BB102489847BDE8384000F056BDA4 +:102AA000A8230020B823002038B50F4CA36A5D6826 +:102AB0002A075D600AD5042222701A6822F00202F9 +:102AC0001A60636A13B10021204698476B0706D548 +:102AD000A36A9969236A13B1034809049847BDE8BA +:102AE000384000F033BD00BFA823002010B50E4CC5 +:102AF000204600F02FF90D4B0B211320A36200F0AC +:102B000009F90B21142000F005F90B21152000F024 +:102B100001F90B21162000F0FDF8BDE8104000225D +:102B20000E201146FFF7B0BEA8230020006400402D +:102B30000F4B10B59842044605D10E4BDA6942F0AE +:102B40000072DA61DB690122A36A1A60A36A5A681B +:102B5000D20707D5626851681268D9611A60064ABF +:102B60005A6110BD0121082000F0B0F9EEE700BF66 +:102B7000A8230020001002405B87010003291AD817 +:102B8000DFE801F0020A0F14836A9B6813F0E05F2C +:102B900014BF012000207047836A9868C0F38060EA +:102BA0007047836A9868C0F3C0607047836A98680A +:102BB000C0F30070704700207047000010B5032973 +:102BC00027D8DFE801F002272B2F836A9968C1F329 +:102BD0000161183103EB01131078840648BF546873 +:102BE000C0F3001158BF94884FEA410148BF41EA41 +:102BF000C40100F00F00586048BF41F00401906824 +:102C000058BF41EA4451D26841F001019860DA604E +:102C1000196010BD836A03F5C073DDE7836A03F5AD +:102C2000C873D9E7836A03F5D073D5E701290AD0C1 +:102C300002290FD081B9836ADA68920701D1186935 +:102C400003E001207047836AD86810F0030018BFC2 +:102C500001207047836AF2E70020704710B539B948 +:102C6000836AD96889071BD11B699C0704D110BDF1 +:102C7000012915D00229FAD1816AD1F8C031D1F8E1 +:102C8000C441D1F8C8011061D1F8CC0150612020B5 +:102C900008610869800717D1486940F0100012E008 +:102CA000816AD1F8B031D1F8B441D1F8B8011061DE +:102CB000D1F8BC0150612020C860C868800703D1EA +:102CC000486940F002004861C3F34000C3F380014B +:102CD000000140EA4111107920F0300001431171E8 +:102CE00089064BBF91681189DB085B0D4CBF63F30C +:102CF0001C0163F30A01137948BF916064F3030375 +:102D000013714FEA14234FEA144458BF1181137012 +:102D10005480ACE70122090100F1604303F56143EF +:102D2000C9B283F8001300F01F039A4043099B00C7 +:102D300003F1604303F56143C3F880211A607047D3 +:102D4000090100F16040C9B200F56D40017670479D +:102D5000FFF7CCBE01230370002300F10802C0E995 +:102D6000022200F11002C0E90422C0E90633C0E9E2 +:102D7000083343607047000010B53023044683F3E6 +:102D80001188022341600370FFF7D2FE0423002064 +:102D9000237080F3118810BD2DE9F0411F460446D1 +:102DA0000D461646302383F3118800F10808237876 +:102DB000052B0DD029462046FFF7E0FE40B1204606 +:102DC00032462946FFF7FAFE002080F3118808E01A +:102DD0003946404600F01AF90028E8D0002383F372 +:102DE0001188BDE8F08100002DE9F0411F4604463E +:102DF0000D461646302383F3118800F1100823781E +:102E0000052B0DD029462046FFF710FF40B1204684 +:102E100032462946FFF722FF002080F3118808E0A0 +:102E20003946404600F0F2F80028E8D0002383F34A +:102E30001188BDE8F08100000023826803750369F2 +:102E40001B6899689142FBD25A6803604260106027 +:102E50005860704700238268037503691B6899688E +:102E60009142FBD85A680360426010605860704716 +:102E700008B50846302383F311880B7D032B05D05A +:102E8000042B0DD02BB983F3118808BD00228B6968 +:102E90001A604FF0FF338361FFF7CEFF0023F2E7A4 +:102EA000D1E9003213605A60F3E70000FFF7C4BFB6 +:102EB000054BD96808751868026853601A600122CA +:102EC0000275D860FDF79EBBD823002030B50C4BAF +:102ED0000446DD684B1C87B00FD02B466846094A74 +:102EE00000F0CAF82046FFF7E3FF009B13B16846E5 +:102EF00000F0CAF8A86907B030BDFFF7D9FFF9E7BD +:102F0000D8230020712E0008044B1A68DB689068F3 +:102F10009B68984294BF002001207047D82300206E +:102F2000084B10B51C68D868226853601A600122EB +:102F30002275DC60FFF78EFF01462046BDE8104099 +:102F4000FDF760BBD823002038B501230025064CCF +:102F5000064907482370656000F03EFB022323709A +:102F600085F3118838BD00BF30250020B83A00082D +:102F7000D823002000F09AB88B60022308618B826E +:102F8000084670478368A3F1440243F8142C026991 +:102F900043F8442C426943F8402C094A43F8242C56 +:102FA000C268A3F1200043F8182C022203F80C2C6D +:102FB000002203F80B2C034A43F8102C704700BF83 +:102FC00015060008D823002008B5FFF7DBFFBDE891 +:102FD0000840FFF76BBF0000024BDB6898610F20D1 +:102FE000FFF766BFD8230020302383F31188FFF753 +:102FF000F3BF000008B50146302383F31188082091 +:10300000FFF764FF002383F3118808BD064BDB68DC +:1030100039B1426818605A60136043600420FFF7BA +:1030200055BF4FF0FF307047D823002038B5044615 +:103030000D462068844200D138BD036823605C607F +:103040008561FFF733FFF4E710B50A4C23699A68EE +:1030500091420CD85A6881600360426010609A689F +:103060005860511A99604FF0FF33A36110BD1B687F +:10307000891AECE7D8230020C0E90323002310B409 +:1030800010BC4361FFF7E0BF036881689A680A4497 +:103090009A60426813605A6000234FF0FF32036069 +:1030A000014B9A61704700BFD823002070B5124DC4 +:1030B0002A46EB690133EB6152F8103F934206D088 +:1030C00030269A68013A9A602C69A36803B170BDF2 +:1030D000D4E900210A605160236083F311882046FF +:1030E000D4E90331984786F3118861690029EBD050 +:1030F0002046FFF7A9FFE7E7D8230020054A30B5AF +:10310000D369D2E908451B1B181945F10001C2E932 +:10311000080130BDD823002000207047FEE70000E2 +:10312000704700004FF0FF3070470000BFF34F8F33 +:10313000024AD368DB07FCD4704700BF002002407E +:1031400008B5074B1B7853B9FFF7F0FF054B1A6919 +:10315000120641BF044A5A6002F188325A6008BD23 +:1031600048250020002002402301674508B5054B93 +:103170001B7833B9FFF7DAFF034A136943F0800382 +:10318000136108BD48250020002002407F289ABF17 +:1031900000F5003080020020704700004FF480608E +:1031A00070470000802070477F2808B50BD8FFF7D4 +:1031B000EDFF00F580630268013204D104308342E0 +:1031C000F9D1012008BD0020FCE700007F2810B5E0 +:1031D00004461CD8FFF7AAFFFFF7B2FFF3220D4BFE +:1031E0004FF48061DA6002221A61FFF7CFFF586165 +:1031F0001A6942F040021A61FFF798FF00F02EF9B9 +:10320000FFF7B4FF2046BDE81040FFF7CDBF002018 +:1032100010BD00BF002002402DE9F843054612F022 +:103220000100144606D040F2033200201E4B1A6003 +:10323000BDE8F8831D4BAA189A4204D94FF4427294 +:10324000194B1A60F4E7FFF77BFF4FF00109FFF716 +:103250006DFFDFF85C806D1A012C0F4605EB01064F +:1032600003D8FFF783FF0120E2E73B88C8F81090FE +:1032700033800020FFF75AFFC8F81000338831F878 +:10328000022B9BB29A420CD040F21F32064B1A60BE +:10329000084B1E60084B1C60084B1F60FFF766FF61 +:1032A000C6E7023CD8E700BF442500200000020822 +:1032B0000020024038250020402500203C25002029 +:1032C000084908B50B7828B11BB9FFF739FF01236E +:1032D0000B7008BD002BFCD0BDE808400870FFF75C +:1032E00045BF00BF4825002038B5EFF31185BDBBB1 +:1032F000EFF30584C4F308043023C4B183F31188C9 +:10330000FFF7FCFE44014B01241A43EAD06363EB50 +:103310000103A2009B00121843EA947341EB0301DE +:10332000C900D00041EA527185F3118838BD83F39A +:103330001188FFF7E3FE45014B012D1A43EAD063E4 +:1033400063EB0103AA009B00121843EA957341EB5B +:103350000301C900D00041EA527184F3118838BDDD +:10336000FFF7CCFE44014B01241A43EAD06363EB20 +:103370000103A2009B00121843EA947341EB03017E +:10338000C900D00041EA527138BD00BF38B5FFF71F +:10339000ABFF00230F4A104CC00840EA4170A0FB6D +:1033A000025EC908A0FB040CA1FB0440A1FB0212B1 +:1033B0001CEB050C5B411CEB040C43EB000011EB18 +:1033C0000E0142F10002411842F10000090941EAF0 +:1033D000007038BDA59BC420CFF753E310B5094C4E +:1033E000013AD2B2FF2A00D110BD500854F8203063 +:1033F000013054F820009BB243EA004341F8043BFB +:10340000EEE700BF046C004010B50748013AD2B2A5 +:10341000FF2A00D110BD0C88530840F823404C8887 +:10342000013340F82340F1E7046C004007B5012266 +:10343000002001A9FFF7D2FF019803B05DF804FB5B +:1034400013B50446FFF7F2FFA04205D00122002089 +:1034500001A90194FFF7D8FF02B010BD704700002A +:1034600045F25552064B1A6002225A6040F6FF722E +:103470009A604CF6CC421A600122024B1A707047D7 +:103480000030004050250020034B1B781BB14AF64A +:10349000AA22024B1A6070475025002000300040DD +:1034A000044B1A682AB902F1804202F50432526ACA +:1034B0001A6070474C2500204FF08072014B5A6211 +:1034C000704700BF0010024008B5FFF7E9FF024B4C +:1034D0001868C0F3407008BD4C25002008B5FFF700 +:1034E000DFFF024B1868C0F3007008BD4C250020B8 +:1034F000EFF30983203383F30988002383F31188D2 +:1035000070470000302080F3118862B60C4B0D4AE2 +:10351000D96821F4E0610904090C0A43DA60D3F8A0 +:10352000FC20094942F08072C3F8FC200A6842F08E +:1035300001020A602022DA7783F82200704700BF78 +:1035400000ED00E00003FA05001000E0302310B5A4 +:1035500083F311880B4B5B6813F400630FD0EFF318 +:1035600009844FF08073203CE36184F30988FFF7FE +:10357000CBFC10B1044BA36110BD044BFBE783F3FC +:103580001188F9E700ED00E0270600082A06000888 +:1035900070470000FEE700000A4B0B480B4A9042C0 +:1035A0000BD30B4BC11EDA1C121A22F003028B4202 +:1035B00038BF00220021FDF7EDBE53F8041B40F890 +:1035C000041BECE7343B0008D4250020D425002060 +:1035D000D4250020FEE7000070B5002504461A4BF4 +:1035E00086B05860856201630E46FFF78BFF04F1D9 +:1035F0001003C4E904334FF0FF33A361134BE561BB +:10360000D9692B460A462046C4E9082304F134014F +:103610008023C4E900440E4AA560E5622565FFF7F2 +:10362000ABFC01230B4AE0600375009272686846A8 +:103630000192B268CDE90223074BCDE90435FFF7CB +:10364000C3FC06B070BD00BF30250020D823002089 +:10365000C43A0008C93A0008D535000800F030B86F +:1036600008B500F063F9FFF76FFCBDE80840FFF70D +:1036700017BF0000704700004FF0FF310E4B1A6972 +:1036800019611A6900221A611869D868D960D96865 +:10369000DA60DA68DA6942F08052DA61DA69DA69A6 +:1036A00042F00062DA61054ADB69136843F4807313 +:1036B000136000F01BB900BF001002400070004012 +:1036C000194B1A6842F001021A601A689007FCD57B +:1036D0001A6802F0F9021A6000225A605A6812F061 +:1036E0000C0FFBD11A6842F480321A601A689103F9 +:1036F000FCD55A6842F4E8125A601A6842F08072A7 +:103700001A601A689201FCD51221084A5A60084AC8 +:1037100011605A6842F002025A605A6802F00C02C4 +:10372000082AFAD1704700BF0010024000641D0053 +:1037300000200240084A08B5516913680B4003F0A5 +:103740000103536123B1054A13680BB150689847D0 +:10375000BDE80840FFF7FABE0004014054250020F0 +:10376000084A08B5516913680B4003F0020353611E +:1037700023B1054A93680BB1D0689847BDE808406B +:10378000FFF7E4BE0004014054250020084A08B5B4 +:10379000516913680B4003F00403536123B1054AD8 +:1037A00013690BB150699847BDE80840FFF7CEBEDA +:1037B0000004014054250020084A08B551691368E7 +:1037C0000B4003F00803536123B1054A93690BB121 +:1037D000D0699847BDE80840FFF7B8BE0004014033 +:1037E00054250020084A08B5516913680B4003F0BE +:1037F0001003536123B1054A136A0BB1506A98470D +:10380000BDE80840FFF7A2BE000401405425002097 +:10381000174B10B55A691C68144004F478725A6149 +:10382000A30604D5134A936A0BB1D06A9847600681 +:1038300004D5104A136B0BB1506B9847210604D581 +:103840000C4A936B0BB1D06B9847E20504D5094A3B +:10385000136C0BB1506C9847A30504D5054A936CC3 +:103860000BB1D06C9847BDE81040FFF76FBE00BFAA +:1038700000040140542500201A4B10B55A691C68F9 +:10388000144004F47C425A61620504D5164A136D53 +:103890000BB1506D9847230504D5134A936D0BB1B6 +:1038A000D06D9847E00404D50F4A136E0BB1506EEB +:1038B0009847A10404D50C4A936E0BB1D06E98477B +:1038C000620404D5084A136F0BB1506F9847230464 +:1038D00004D5054A936F0BB1D06F9847BDE81040EF +:1038E000FFF734BE0004014054250020062108B52E +:1038F0000846FFF70FFA06210720FFF70BFA06210B +:103900000820FFF707FA06210920FFF703FA06212E +:103910000A20FFF7FFF906211720FFF7FBF9BDE8A2 +:10392000084006212820FFF7F5B9000008B5FFF789 +:10393000A3FE054800F00CF8FFF70AFAFFF79AFE1D +:10394000BDE8084000F002B8D03A000800F042B8E4 +:10395000002319461C4A0133102BC2E9001102F161 +:103960000802F8D1194B9A6942F07D029A619B696D +:103970000268174BDA6082685A6042681A60C2684F +:1039800003F58063DA6042695A6002691A608269ED +:10399000C3F80C24026AC3F80424C269C3F80024E3 +:1039A000426AC3F80C28C26AC3F80428826AC3F8C2 +:1039B0000028026BC3F80C2C826BC3F8042C426BFA +:1039C000C3F8002C704700BF5425002000100240AF +:1039D000000801404FF0E023044A08215A61002208 +:1039E0009A6107220B201A61FFF7AAB93F1901005B +:1039F00008B5302383F31188FFF7BCFA002383F363 +:103A0000118808BD08B5FFF7F3FFBDE80840FFF7D0 +:103A10009DBD000010B501390244904201D1002043 +:103A200005E0037811F8014FA34201D0181B10BD27 +:103A30000130F2E72DE9F0419BB10446C91A17782D +:103A4000014403F1FF3C8C42204601D9002008E0EC +:103A500005780134BD42F6D10CEB0405D618A54219 +:103A600001D1BDE8F08115F8018D16F801EDF045A2 +:103A7000F5D0E8E7034611F8012B03F8012B002AE3 +:103A8000F9D170476F72672E6172647570696C6FDF +:103A9000742E663130332D54726967676572000089 +:103AA00040A2E4F1646891060041A3E5F2656992E1 +:103AB0000700000063300000B43A00083024002002 +:103AC000302500206D61696E0069646C650000003E +:103AD000001800004444414444544944010000009B +:103AE00042444444444444440000000044444444A8 +:103AF0004444444400000000444444444444444496 +:103B00000000000044444444444444440000000095 +:103B1000E803000000000000009C0100000000001D +:103B2000640000000000000040420F00FE2A010077 +:043B3000D2040000BB :00000001FF diff --git a/Tools/bootloaders/f303-GPS_bl.bin b/Tools/bootloaders/f303-GPS_bl.bin index 52d37cb46e4f8f..98a2afed0f6904 100755 Binary files a/Tools/bootloaders/f303-GPS_bl.bin and b/Tools/bootloaders/f303-GPS_bl.bin differ diff --git a/Tools/bootloaders/f303-GPS_bl.hex b/Tools/bootloaders/f303-GPS_bl.hex index 8411e72140b114..dba536f8458946 100644 --- a/Tools/bootloaders/f303-GPS_bl.hex +++ b/Tools/bootloaders/f303-GPS_bl.hex @@ -1,1217 +1,1172 @@ :020000040800F2 -:1000000000090020B5040008D52500088D2500084A -:10001000B52500088D250008AD250008B7040008A7 -:10002000B7040008B7040008B7040008C935000881 -:10003000B7040008B7040008B70400087D430008AF -:10004000B7040008B7040008B7040008B7040008A4 -:10005000B7040008B7040008614000088D4000089C -:10006000B9400008E540000811410008B704000845 -:10007000B7040008B7040008B7040008B704000874 -:10008000B7040008B7040008B704000841250008B9 -:100090006D2500087D250008B70400083D410008D3 -:1000A000B7040008B7040008B7040008B704000844 -:1000B000B7040008B7040008B7040008B704000834 -:1000C000B7040008B7040008B7040008B704000824 -:1000D000B70400086D45000881450008B704000812 -:1000E000A5410008B7040008B7040008B7040008D9 -:1000F000B7040008B7040008B7040008B7040008F4 -:10010000B7040008B7040008B7040008B7040008E3 -:10011000B7040008B7040008B7040008B7040008D3 -:10012000B7040008B7040008B7040008B7040008C3 -:10013000B7040008B7040008B7040008B7040008B3 -:10014000B7040008B7040008B7040008B7040008A3 -:10015000B7040008B7040008B7040008B704000893 -:10016000B7040008B7040008B7040008B704000883 -:10017000B7040008B7040008B7040008B704000873 -:10018000B7040008B7040008B7040008B704000863 -:10019000B7040008B7040008B7040008B704000853 -:1001A000291200080000000000000000000000000C -:1001B00053B94AB9002908BF00281CBF4FF0FF31CE -:1001C0004FF0FF3000F074B9ADF1080C6DE904CECA -:1001D00000F006F8DDF804E0DDE9022304B0704722 -:1001E0002DE9F047089D04468E46002B4DD18A42EA -:1001F000944669D9B2FA82F252B101FA02F3C2F11D -:10020000200120FA01F10CFA02FC41EA030E9440AD -:100210004FEA1C48210CBEFBF8F61FFA8CF708FBCE -:1002200016E341EA034306FB07F199420AD91CEBA6 -:10023000030306F1FF3080F01F81994240F21C81D8 -:10024000023E63445B1AA4B2B3FBF8F008FB103320 -:1002500044EA034400FB07F7A7420AD91CEB040455 -:1002600000F1FF3380F00A81A74240F20781644425 -:10027000023840EA0640E41B00261DB1D4400023AA -:10028000C5E900433146BDE8F0878B4209D9002D0E -:1002900000F0EF800026C5E9000130463146BDE898 -:1002A000F087B3FA83F6002E4AD18B4202D3824202 -:1002B00000F2F980841A61EB030301209E46002DB1 -:1002C000E0D0C5E9004EDDE702B9FFDEB2FA82F206 -:1002D000002A40F09280A1EB0C014FEA1C471FFA64 -:1002E0008CFE0126200CB1FBF7F307FB131140EA4B -:1002F00001410EFB03F0884208D91CEB010103F118 -:10030000FF3802D2884200F2CB804346091AA4B2D9 -:10031000B1FBF7F007FB101144EA01440EFB00FEAD -:10032000A64508D91CEB040400F1FF3102D2A64512 -:1003300000F2BB800846A4EB0E0440EA03409CE7B1 -:10034000C6F12007B34022FA07FC4CEA030C20FA5E -:1003500007F401FA06F31C43F9404FEA1C4900FA7E -:1003600006F3B1FBF9F8200C1FFA8CFE09FB1811FB -:1003700040EA014108FB0EF0884202FA06F20BD96E -:100380001CEB010108F1FF3A80F08880884240F2BE -:100390008580A8F102086144091AA4B2B1FBF9F002 -:1003A00009FB101144EA014100FB0EFE8E4508D9FD -:1003B0001CEB010100F1FF346CD28E456AD9023882 -:1003C000614440EA0840A0FB0294A1EB0E01A14267 -:1003D000C846A64656D353D05DB1B3EB080261EBD5 -:1003E0000E0101FA07F722FA06F3F1401F43C5E9AF -:1003F000007100263146BDE8F087C2F12003D840E5 -:100400000CFA02FC21FA03F3914001434FEA1C4726 -:100410001FFA8CFEB3FBF7F007FB10360B0C43EA18 -:10042000064300FB0EF69E4204FA02F408D91CEBC8 -:10043000030300F1FF382FD29E422DD902386344C6 -:100440009B1B89B2B3FBF7F607FB163341EA034166 -:1004500006FB0EF38B4208D91CEB010106F1FF38B5 -:1004600016D28B4214D9023E6144C91A46EA0046AC -:1004700038E72E46284605E70646E3E61846F8E63E -:100480004B45A9D2B9EB020864EB0C0E0138A3E787 -:100490004646EAE7204694E74046D1E7D0467BE768 -:1004A000023B614432E7304609E76444023842E7E0 -:1004B000704700BF02E000F000F8FEE772B6374870 -:1004C00080F30888364880F3098836483649086042 -:1004D00040F20000CCF200004EF63471CEF2000182 -:1004E0000860BFF34F8FBFF36F8F40F20000C0F280 -:1004F000F0004EF68851CEF200010860BFF34F8F36 -:10050000BFF36F8F4FF00000E1EE100A4EF63C7122 -:10051000CEF200010860062080F31488BFF36F8FCD -:1005200003F052FC03F0C6FC4FF055301F491B4A44 -:1005300091423CBF41F8040BFAE71D49184A914229 -:100540003CBF41F8040BFAE71A491B4A1B4B9A427D -:100550003EBF51F8040B42F8040BF8E7002018499D -:10056000184A91423CBF41F8040BFAE703F030FC13 -:1005700003F0DCFC144C154DAC4203DA54F8041BB8 -:100580008847F9E700F042F8114C124DAC4203DA0B -:1005900054F8041B8847F9E703F018BC0009002051 -:1005A000001100200000000808ED00E0000100201C -:1005B00000090020704B0008001100207C11002071 -:1005C00080110020583C0020A0010008A401000870 -:1005D000A4010008A40100082DE9F04F2DED108AB8 -:1005E000C1F80CD0C3689D46BDEC108ABDE8F08F01 -:1005F000002383F311882846A047002003F06EF9FA -:10060000FEE703F0D1F800DFFEE70000F8B500F0E8 -:100610001DFE03F07DFB074603F0CCFB05460028DA -:1006200040D12C4B9F423DD001339F423DD02A4BBD -:1006300027F0FF029A423BD1F8B200F043FC2E466D -:1006400042F2107400F044FC08B10024264601F088 -:10065000B5F888B3032000F045F80024264635B1EC -:100660001E4B9F4203D003F09DFB00242646002032 -:1006700003F058FB1A4B1B6913F0400322D00EB154 -:1006800000F046F800F056FC00F0E2FD01F0AAFF91 -:100690000546CCB101F0A6FF401BA04214D900F0E2 -:1006A00037F8F3E72E460024CCE704460126C9E7D5 -:1006B00006464FF47A74C5E7002CD0D04FF47A7414 -:1006C0000126CCE71C46DDE700F07CFC012003F0AE -:1006D0000BF9DEE7010007B0000008B0263A09B0C8 -:1006E00000040048084B187003280CD8DFE800F01D -:1006F00008050208022000F007BE022000F0FCBD41 -:10070000024B00225A6070478011002084110020A3 -:1007100038B501F053F830B11F4B03221A701F4B4C -:1007200000225A6038BD1E4B1E4A19680131F9D0AB -:1007300004339342F9D11C4C194DD4F80428AA4231 -:10074000F0D31A4B9B6803F1006303F5D0439A4240 -:10075000E8D203F0FBFA03F00DFB002000F092FD5D -:100760000220FFF7BFFF124BDA690022DA61D96974 -:1007700099699A619B6972B64FF0E0233021C3F802 -:10078000085DD4F80038D4F8042881F311889D4618 -:1007900083F308881047C5E78011002084110020EA -:1007A00000680008206800080060000800110020B0 -:1007B00000100240094A136849F2690099B21B0C03 -:1007C00000FB01331360064B186844F2506182B29B -:1007D000000C01FB0200186080B270471411002069 -:1007E0001011002010B500211022044600F0A6FDD3 -:1007F000034B03CB206061601868A06010BD00BF90 -:10080000ACF7FF1F2DE9F041ADF54E7D0DF1340839 -:100810006CAC40F2751207460D460EA80021C8F8D0 -:10082000001000F08BFD4FF4C4720021204600F050 -:1008300085FD01F0D7FE274B4FF47A72B0FBF2F042 -:10084000186093E80700022384E807000DF5E970BB -:100850002382FFF7C7FF4EF603431F49238407A8EF -:1008600004F0BAF8162384F832310DF2E32207AB14 -:100870000DF12C0C1E4603CE6645106051603346C8 -:1008800002F10802F6D130681060B38893804146C7 -:100890000122204600F09EFD00230393AB7E0293CD -:1008A00005F11903019380B20123CDE9048000937F -:1008B000E97E06A3D3E90023384602F05BFA0DF582 -:1008C0004E7DBDE8F08100BFAFF300809E6AC42179 -:1008D000818A46EE8C110020E84900082DE9F0419C -:1008E0002C4C237ADAB080460D465BBB27A92846FC -:1008F00000F080FE0746002842D19DF89D60C82E7A -:100900003ED801464FF4A662204600F017FD4FF492 -:100910008073C4F8F8314FF40073C4F80C334FF40B -:100920004073C4F8203432460DF19E0104F10900F1 -:1009300000F0F2FC26449DF89C30777223720BB9CC -:10094000EB7E23728122002106AC27A800F0F6FC82 -:100950000122214627A800F089FE00230393AB7EE5 -:10096000029305F1190380B201932823CDE90440D5 -:100970000093E97E05A3D3E90023404602F0FAF98B -:100980005AB0BDE8F08100BFAFF30080264172721B -:10099000DF25D7B7A8320020F0B5254E4FF48A7571 -:1009A00005FB0065F1B096F8D83085F8DC300024FE -:1009B000D822214685F8E8403AA800F0BFFC06F1AD -:1009C000090000F0B3FCD5F8E4308DF8F000C2B2B5 -:1009D00006AF06F109010DF1F100CDE93A3400F05E -:1009E0009BFC394601223AA800F06CFE80B2CDE9AA -:1009F000047008230127CDE9023706F1D8030193DB -:100A000030230093317A0B4807A3D3E9002302F087 -:100A1000B1F9A04206DD01F0E5FDC5F8E000384679 -:100A200071B0F0BD2046FBE778F6339F93CACD8DB9 -:100A3000A8320020A42100202DE9F0411D4D1E4EBA -:100A40001E4F86B0284602F0C1F9034658B3002471 -:100A5000CDE90344ADF81440027B8DF81420996869 -:100A60004068029403AA03C21B68DFF8548043F075 -:100A70000043029301F0B8FD821941F10003009494 -:100A800002A9384601F07CF8A04205DD284602F0B4 -:100A9000A1F988F80040D5E798F80030072B05D871 -:100AA000013388F8003006B0BDE8F081014802F05B -:100AB00091F9F8E7A421002040420F00D82100203E -:100AC000DD37002070B50D4614461E4602F0AEF824 -:100AD00050B9022E10D1012C0ED112A3D3E900235C -:100AE000C5E90023012007E0282C10D005D8012CEF -:100AF00009D0052C0FD0002070BD302CFBD10BA3EA -:100B0000D3E90023ECE70BA3D3E90023E8E70BA329 -:100B1000D3E90023E4E70BA3D3E90023E0E700BF18 -:100B2000AFF30080401DA12026812A0B78F6339F69 -:100B300093CACD8D9E6AC421818A46EE2641727287 -:100B4000DF25D7B7F017304A39059E5638B5054628 -:100B50000E4C0021013500F0B7FBA4F82C55B4F879 -:100B60002C0500F099FB78B1B4F82C0500F0A4FB3B -:100B7000014648B9B4F82C0500F0A6FBB4F82C35B2 -:100B80000133A4F82C35EAE738BD00BFA8320020B5 -:100B900010B50A4B0A4A1A6003F5805393F8602097 -:100BA0003AB9DC6D2CB1204600F082FE204603F0FD -:100BB00053FEBDE81040034800F07ABED821002063 -:100BC0003C4A0008203200202DE9F04F8FB000AFE2 -:100BD00005460C4602F02AF8002849D1237E022B54 -:100BE0001BD1E38A012B18D101F0FCFC0646FFF76C -:100BF000E1FD03464FF4C870DFF8C482B3FBF0F2A6 -:100C000006F5167602FB103316FA83F3C8F80030A7 -:100C1000E37E33B9A34B00221A703C37BD46BDE8D2 -:100C2000F08F07F12401204600F0A2FC0028F4D147 -:100C300007F11400FFF7D6FD97F8264007F11401DD -:100C4000224607F1270003F051FE0028E2D10F2CC5 -:100C500008D8944B1C70D8F80030A3F51673C8F868 -:100C60000030DAE797F82410284601F0D7FFD4E7E0 -:100C7000E38A282B2BD010D8012B23D0052BCCD1E5 -:100C8000BFF34F8F8849894BCA6802F4E06213436F -:100C9000CB60BFF34F8F00BFFDE7302BBDD1844E3B -:100CA000E17E327A9142B8D1607E3146002291F8DD -:100CB000DC50854200F0A5800132042A01F58A71DA -:100CC000F5D1AAE721462846FFF79CFDA5E7214676 -:100CD0002846FFF703FEA0E7B2F8EC507B6005F171 -:100CE00003094FEA99094FEA8902D11DC908A8EB07 -:100CF000C1039D46EB460021584600F01FFB04F15E -:100D0000EE012A463144584600F006FB7B6813B9D1 -:100D1000012000F0B7FA96F8D20000F0BDFA0446C0 -:100D200030B9307200F0D8FA204600F0ABFAB1E0EA -:100D3000D6F8D4203AB996F8D200B6F82C258242DB -:100D400001D8FFF703FFD6F8D4202A44944208D2F2 -:100D500096F8D200B6F82C250130824201D8FFF770 -:100D6000F5FE70685FFA89F2594600F0EFFA08B9AB -:100D7000C54679E0726896F8D2002A447260D6F8C7 -:100D8000D42005EB0209C6F8D49000F085FA81451D -:100D900009D396F8D220D6F8D4000132001B86F889 -:100DA000D220C6F8D400FF2D0FD80024347200F0F2 -:100DB00093FA204600F066FA00F000FD3D4B1881E2 -:100DC00008B9FFF7A5FCC54627E7BB6896F8D90028 -:100DD0000AFB0362FB68D2F8E41082F8E83001F500 -:100DE0008061C2F8E030C2F8E410FFF7D5FDFFF7EC -:100DF00023FE96F8D920013202F0030286F8D920AA -:100E0000B6E74FF48A7A0AFB02F505F1EA013144AC -:100E1000204600F083FCF86000287FF4FEAE3544E5 -:100E2000012285F8E82001F0DDFBD5F8E020D6EDC1 -:100E3000007ADFED216A801A192838BF192040F6A0 -:100E4000B832904228BF1046B8EE677A07EE900A93 -:100E5000F8EEE77A67EEA67ADFED186AE7EE267A13 -:100E6000FCEEE77AC6ED007A96F8D930BB60BA6836 -:100E700073680AFB02F4321992F8E81059B1D2F8FB -:100E8000E4108B42E8463FF427AF002182F8E810D7 -:100E9000C2F8E010C5467368064A9B0A0133138105 -:100EA000BBE600BF9D21002000ED00E00400FA0534 -:100EB000A83200208C110020CDCCCC3D6666663F68 -:100EC000A0210020014B1870704700BF981100202E -:100ED00038B54FF00054134B22689A4220D1124B80 -:100EE000627D12481A70237D03724FF48073C0F83C -:100EF000F8314FF40073C0F80C3300254FF4407301 -:100F0000C0F820340A49C0F8E450C922093000F082 -:100F100003FAE0222946204600F010FA012038BDED -:100F20000020FCE79AAD44C598110020A8320020AB -:100F30001600002037B500F041FC194D19492881F1 -:100F40000223012218486B7101F0EAF90023019392 -:100F5000164B174900931748174B4FF4805201F076 -:100F600035FE164B197811B1124801F057FE01F009 -:100F700039FB0446FFF71EFC4FF4C873B0FBF3F2D5 -:100F800002FB130304F5167010FA83F00C4B186083 -:100F900002F010FF08B10F232B8103B030BD00BF5A -:100FA0008C11002040420F00D8210020C50A000803 -:100FB0009C110020A4210020C90B000898110020DA -:100FC000A02100202DE9F04F2DED028B8EA7D7E94F -:100FD00000670FF23C29D9E90089864C95B00DAD28 -:100FE0009FED828BFFF728FDDFF82CB200230C93D6 -:100FF000ADF83C300D936B6000230DF125028DEDB3 -:10100000008B4FF0010A09A958468DF825308DF85C -:1010100024A001F035F99DF824200023002A40F097 -:10102000AB80204601F002FE0546002847D1DFF8DC -:10103000ECB101F0D7FADBF8003098423FD301F071 -:10104000D1FA0790FFF7B6FB079A4FF4C873B0FBCD -:10105000F3F101FB130302F5167010FA83F0CBF8DD -:101060000000DFF8BCB19BF800100791002914BF05 -:101070002B46534610A88DF83030FFF7B3FB079985 -:10108000C1F11002D2B2062A10AB28BF06221944C1 -:101090000DF13100079200F03FF9079A0CAB039372 -:1010A000182302930132544BD2B2CDE900A304922B -:1010B0003B463246204601F0FFFD8BF8005001F020 -:1010C00091FA4E4A4E4D1368C31AB3F57A7F32D364 -:1010D000106001F089FA02460B46204601F084FEBA -:1010E000204601F0A3FD30B32B7ADFF838A1002BA6 -:1010F00014BF032302238AF8053001F073FA0DF1BF -:10110000400B4FF47A730122B0FBF3F05946CAF852 -:101110000000504600F004FA18230293394B019363 -:1011200080B240F25513CDE903B0009342464B46DE -:10113000204601F0C1FD2B7ACBB101F053FA4FF0FC -:10114000000A83464FF48A7295F8D900504400F0A3 -:10115000030002FB005393F8E81089B30AF1010A77 -:10116000BAF1040FF0D12B7A002B7FF438AF15B011 -:10117000BDEC028BBDE8F08F4FF0904110A84A699A -:1011800082F010024A611946102200F0D7F80DF1E2 -:1011900026030AAA0CA9584600F0F0FD95E80300C2 -:1011A00011AB83E803009DF83C308DF84C300C9B6C -:1011B000109310A9DDE90A23204601F0E9FF1BE79F -:1011C000D3F8E01049B12B68FA2B38BFFA23ABEB08 -:1011D00001010533B1EB430FC0D3FFF7DDFB4FF443 -:1011E0008A720028BAD1BEE7AFF300800000000089 -:1011F00000000000A42100209C210020D8370020FE -:10120000A8320020DC370020401DA12026812A0BB7 -:10121000F1C6A7C1D068080FD8210020A021002066 -:101220009D2100208C11002008B5054800F040FEEB -:10123000BDE80840034A0449002003F007BB00BF93 -:10124000D821002018380020910B000870470000BA -:1012500070B502F013FC094E094D30800024286857 -:101260003388834208D902F005FC2B68044401331B -:10127000B4F5D04F2B60F2D370BD00BF0C38002006 -:10128000E037002002F086BC00F10060920000F51B -:10129000D04002F02DBC0000054B1A68054B1B889E -:1012A0009B1A834202D9104402F0E4BB002070472D -:1012B000E03700200C380020024B1B68184402F075 -:1012C000DFBB00BFE0370020024B1B68184402F070 -:1012D000E9BB00BFE0370020064991F8243033B164 -:1012E0000023086A81F824300822FFF7CDBF0120CF -:1012F000704700BFE4370020022802BF4FF0904340 -:1013000010229A6170470000022802BF4FF09043FC -:101310004FF480129A61704710B50023934203D0B6 -:10132000CC5CC4540133F9E710BD0000034602460B -:10133000D01A12F9011B0029FAD170470244034662 -:10134000934202D003F8011BFAE770472DE9F843F6 -:101350001F4D144695F824200746884652BBDFF8F7 -:1013600070909CB395F824302BB92022FF21484679 -:101370002F62FFF7E3FF95F82400C0F10802A242B4 -:1013800028BF2246D6B24146920005EB8000FFF707 -:10139000C3FF95F82430A41B1E44F6B2082E174450 -:1013A0009044E4B285F82460DBD1FFF795FF002874 -:1013B000D7D108E02B6A03EB82038342CFD0FFF73B -:1013C0008BFF0028CBD10020BDE8F8830120FBE78C -:1013D000E43700202DE9F0470D46044600219046F1 -:1013E000284640F27912FFF7A9FF23462022002168 -:1013F000284601F06FFE231D02222021284601F01D -:1014000069FE631D03222221284601F063FEA31D0D -:1014100003222521284601F05DFE04F10803102275 -:101420002821284601F056FE04F110030822382135 -:10143000284601F04FFE04F11103082240212846FE -:1014400001F048FE04F1120308224821284601F069 -:1014500041FE04F1140320225021284601F03AFEF7 -:1014600004F1180340227021284601F033FE04F1F4 -:1014700020030822B021284601F02CFE04F12103AC -:101480000822B821284601F025FE04F12207C026D3 -:101490003B46314608222846083601F01BFEB6F5C9 -:1014A000A07F07F10107F3D104F13203082231468E -:1014B000284601F00FFE002704F1330A94F8323079 -:1014C0004FEAC7099F4209F5A47615D3B8F1000F7A -:1014D00008D1314604F599730722284601F0FAFD38 -:1014E00009F24F16274694F832213B1B93420CD346 -:1014F000F01DC008BDE8F0870AEB0703082231465B -:10150000284601F0E7FD0137D8E707F233133146EB -:101510000822284601F0DEFD08360137E3E7000027 -:1015200013B504460846002101602346C0F80310A5 -:101530002022019001F0CEFD0198231D02222021DE -:1015400001F0C8FD0198631D0322222101F0C2FDB4 -:101550000198A31D0322252101F0BCFD019804F18F -:1015600008031022282101F0B5FD072002B010BDAC -:10157000F7B50023047F00910E4607221946054661 -:1015800001F06CFC731C0093012200230721284604 -:1015900001F064FCC4B9B31C009305222346082162 -:1015A000284601F05BFC0D243746B278BB1B934202 -:1015B00011D32B7FA88A0734E408BBB9844294BFB7 -:1015C0000020012003B0F0BDAB8ADB00083BDB0844 -:1015D000B3700824E8E7FB1C00932146002308228F -:1015E000284601F03BFC08340137DEE7201A18BF1B -:1015F0000120E7E7F7B50023047F00910E4608229B -:101600001946054601F02AFC731CC4B90822009350 -:1016100011462346284601F021FC1024012372784C -:101620005F1C013B934211D32B7FA88A0734E40847 -:10163000BBB9844294BF0020012003B0F0BDAB8A47 -:10164000DB00083BDB0873700824E7E7F31900931D -:10165000214600230822284601F000FC08343B46BE -:10166000DDE7201A18BF0120E7E70000F8B50E46B5 -:1016700005461446002181223046FFF75FFE2B46C7 -:1016800008220021304601F025FD7CB96B1C0722A1 -:101690000821304601F01EFD0F2401236A785F1CEB -:1016A000013B934204D3E01DC008F8BD0824F4E7D1 -:1016B000EB1921460822304601F00CFD08343B4668 -:1016C000ECE70000F8B50E46054614460021CE2290 -:1016D0003046FFF733FE2B4628220021304601F02A -:1016E000F9FC7CB905F1080308222821304601F0F5 -:1016F000F1FC30242F462A7A7B1B934204D3E01D51 -:10170000C008F8BD2824F5E707F10903214608229F -:10171000304601F0DFFC08340137ECE7F7B5047F11 -:1017200000910E46012310220021054601F096FB90 -:10173000C4B9B31C0093092223461021284601F0A6 -:101740008DFB192437467288BB1B9A4211D82B7F18 -:10175000A88A0734E408BBB9844294BF0020012062 -:1017600003B0F0BDAB8ADB00103BDB0873801024B4 -:10177000E8E73B1D0093214600230822284601F09C -:101780006DFB08340137DEE7201A18BF0120E7E7B8 -:1017900030B5094D0A4491420DD011F8013B584033 -:1017A000082340F30004013B2C4013F0FF0384EABC -:1017B0005000F6D1EFE730BD2083B8EDF7B5364ADB -:1017C000106851686B4603C36A463449344808239D -:1017D00003F09CF8044690BB0A25324A1068516811 -:1017E0006B4603C36A4630492D48082303F08EF840 -:1017F0000446002847D00369B3F5663F43D8B0F8E4 -:101800006620B2F57B7F3ED1284A024402F15C019A -:101810008B4238D35C3B224900209E1AFFF7B8FF69 -:101820003246074604F164010020FFF7B1FFA368C8 -:101830009F4228D1E368984208BF002523E003694E -:10184000B3F5663F26D8428BB2F57B7F20D1174A8D -:10185000024402F110018B4218D3103B10490020C2 -:101860009D1AFFF795FF2A46064604F1180100204D -:10187000FFF78EFFA3689E4202D1E368984201D031 -:101880000D25AAE70025284603B0F0BD1025A4E7E2 -:101890000C25A2E70B25A0E7004A0008DC9703000F -:1018A00000680008094A0008909703000898FFF7AD -:1018B00010B5037C044613B9006803F00FF8204606 -:1018C00010BD00000023BFF35B8FC360BFF35B8FCD -:1018D000BFF35B8F8360BFF35B8F7047BFF35B8F9A -:1018E0000068BFF35B8F704770B505460C30FFF79B -:1018F000F5FF05F1080604463046FFF7EFFFA0426A -:1019000006D930466D68FFF7E9FF2544281A70BDF7 -:101910003046FFF7E3FF201AF9E7000070B50546EF -:10192000406898B105F10800FFF7D8FF05F10C06F3 -:1019300004463046FFF7D2FF8442304694BF6D68BC -:101940000025FFF7CBFF013C2C44201A70BD00009E -:1019500038B50C460546FFF7C7FFA04210D305F186 -:101960000800FFF7BBFF04446868B4FBF0F100FB1C -:101970001144BFF35B8F0120AC60BFF35B8F38BDB8 -:101980000020FCE72DE9F041144607460D46FFF71D -:10199000C5FF844228BF0446D4B1B84658F80C6B42 -:1019A0004046FFF79BFF3044286040467E68FFF7C3 -:1019B00095FF331A9C4203D86C600120BDE8F0818A -:1019C0006B60A41B3B68AB602044E8600220F5E735 -:1019D0002046F3E738B50C460546FFF79FFFA042C7 -:1019E00010D305F10C00FFF779FF04446868B4FBDD -:1019F000F0F100FB1144BFF35B8F0120EC60BFF3FB -:101A00005B8F38BD0020FCE72DE9FF418846694621 -:101A10000746FFF7B7FF6C4606B204EBC606002583 -:101A2000B44209D06268206808EB0501FFF774FC36 -:101A3000636808341D44F3E729463846FFF7CAFFB8 -:101A4000284604B0BDE8F081F8B505460C300F46D5 -:101A5000FFF744FF05F1080604463046FFF73EFF56 -:101A6000A042304688BF6C68FFF738FF201A386004 -:101A700020B130462C68FFF731FF2044F8BD00004C -:101A800073B5144606460D46FFF72EFF844228BF65 -:101A900004460190DCB101A93046FFF7D5FF019B58 -:101AA00033B93268C5E90233C5E9002401200CE0EE -:101AB0009C4238BF01942860019868608442F5D93F -:101AC0003368AB60241AEC60022002B070BD20467F -:101AD000FBE700002DE9FF410F466946FFF7D0FF05 -:101AE0006C4600B204EBC0050026AC4209D0D4F825 -:101AF000048054F8081BB8194246FFF70DFC464411 -:101B0000F3E7304604B0BDE8F081000038B5054683 -:101B1000FFF7E0FF044601462846FFF719FF20467D -:101B200038BD0000302383F3118862B6704700008F -:101B3000002383F3118862B67047000010B4026876 -:101B400054681A4623465DF8044B18470120704735 -:101B50000020704700207047704700000020704749 -:101B60000E20704700F5805090F8C800C0F3400088 -:101B70007047000000F5805090F9C90070470000E0 -:101B8000F7B50C68BDF8207014F000541E466FD1F4 -:101B90000B7B082B6CD8FFF7C5FF4569AB685B0171 -:101BA0000CD4AB681B0108D4AC6814F080545DD130 -:101BB000FFF7BEFF204603B0F0BD01240B6804F11F -:101BC000180C002BB8BFDB004FEA0C1CB4BF43F06D -:101BD00004035B0545F80C300B680FFA84FC13F026 -:101BE000804F18BF05EB0C1E05EB0C1C1EBFDEF86A -:101BF000803143F00203CEF880310B7BCCF8843186 -:101C000005EB04158B68C5F88C314B68C5F8883135 -:101C1000DCF8803143F00103CCF8803100EB44154F -:101C200041F268031D4403EB44130344C5E9002655 -:101C300008330D4601F10C0C55F804EB43F804EBA6 -:101C40006545F9D184342D881D8000EB441407F0DC -:101C50000303257925F00B052B432371FFF768FF5C -:101C60000097334600F0E0FC0120A4E70224A5E73A -:101C70004FF0FF309FE7000013B500F5805401914D -:101C8000E06DFFF74BFE1F280AD90199E06D202275 -:101C9000FFF7BAFEA0F120035842584102B010BD30 -:101CA0000020FBE708B500F58050FFF73BFFC06D53 -:101CB000FFF708FEBDE80840FFF73ABF00220260C8 -:101CC000828142608260704710B500220023C0E923 -:101CD00000230023044603810C30FFF7EFFF20466A -:101CE00010BD0000F0B5054600F580500C4690F898 -:101CF000C83013F0040FC3F3800108BF114661F32D -:101D0000820304F1840680F8C83005EB461389B0DD -:101D10001B79D8072ED57AB319072DD46846FFF75B -:101D2000D3FF05EB441303F5835303F1180703AA0C -:101D3000103318685968144603C40833BB4222465E -:101D4000F7D1186820609B88A380DDE90E23CDE9D8 -:101D500000230123ADF808302B686946DB6B284669 -:101D6000984705EB46152B791A075CBF43F008032B -:101D70002B7101E0002AF4D109B0F0BD2DE9F04744 -:101D8000074688B007F5805468469A468846FFF7AC -:101D9000C9FE9146FFF798FFE06DFFF7A5FD1F28EC -:101DA00029D9E06D20226946FFF7B0FE202822D114 -:101DB00003AD444605AB2E4603CE9E4220606160D3 -:101DC000354604F10804F6D130682060B388A3805A -:101DD000DDE90023C9E90023BDF80830AAF8003086 -:101DE000FFF7A6FE4A4653464146384608B0BDE8CE -:101DF000F04700F007BCFFF79BFE002008B0BDE8ED -:101E0000F08700002DE9F84F0023C0E90133254B8E -:101E1000044640F8183B0F46FFF750FF04F1280036 -:101E2000FFF752FF04F1480804F58255464608358D -:101E300030462036FFF748FFAE42F9D104F5805511 -:101E40004FF480534FF00009C5E91339C5F84880B5 -:101E50000123EE6504F5875804F58456C5F85490BF -:101E600085F8583085F86030083608F108084FF0DA -:101E7000000A4FF0000B46E908ABA6F11800FFF787 -:101E80001DFF203646F8289C4645F4D185F8C970D8 -:101E900017B1054800F0A0FB044B63612046BDE884 -:101EA000F88F00BF3C4A0008144A00080064004054 -:101EB00010B5044B197804464A1C1A70FFF7A2FFAC -:101EC000204610BD143800202DE9F047002950D0DD -:101ED000294B2A4FB7FBF1F599428CBF0A231123F6 -:101EE000581EB5FBF3FC03FB1C53C4B22BB10228F4 -:101EF0000346F5D80020BDE8F0870CF1FF36B6F5B3 -:101F0000806FF7D2C4EBC40E0EF103034FEAE3096E -:101F1000C3F3C703A4EB030809F1010A4FF47A7570 -:101F20005FFA88F009FB05555AFA88F8B5FBF8F511 -:101F3000B5F5617FC1BF0EF1FF33C3F3C703E01AEC -:101F4000C0B25C1C50FA84F40CFB04F4B7FBF4F44C -:101F5000A142CFD1013BDBB20F2BCBD80138C0B2AD -:101F60000728C7D80021107116809170D370012006 -:101F7000C1E70846BFE700BF3F420F0000512502FE -:101F800070B505460E464FF47A746B695B6803F0D2 -:101F90000103B3424FF0010004D001F0A5FC013C65 -:101FA000F3D1204670BD000030B54269936913F04B -:101FB000700F16D000230B4C936103F1840200EBE9 -:101FC000421211794D0709D5890707D5416954F89F -:101FD00023508D60117941F0040111710133032BFD -:101FE000EBD130BD284A000873B51D46436916463B -:101FF0009A68D207044609D59A6801219960C2F30C -:102000004002CDE900650021FFF76CFE63699A6824 -:10201000D1050BD59A684FF480719960C2F34022C4 -:10202000CDE9006501212046FFF75CFE63699A68EF -:10203000D2030BD59A684FF480319960C2F34042C5 -:10204000CDE9006502212046FFF74CFE204602B094 -:10205000BDE87040FFF7A8BFF8B5044646690029FF -:102060006CD106F10C07386880076AD006EB0115C1 -:102070003868D5F8B00110F0040FD5F8B0011ABFD8 -:10208000C00840F00040400DA061D5F8B0C11CF080 -:10209000020F1CBF40F08040A061D5F8B40106EBF0 -:1020A000011100F00F0084F82400D1F8B801207766 -:1020B000D1F8B801000A6077D1F8B801000CA07718 -:1020C000D1F8B801000EE077D1F8BC0184F8200007 -:1020D000D1F8BC01000A84F82100D1F8BC01000C41 -:1020E00084F82200D1F8BC11090E84F8231038219D -:1020F000396004F1340004F1180104F1240551F8A9 -:10210000046B40F8046BA942F9D109880180C4E945 -:102110000A2321460023238651F8283B2046DB6B07 -:10212000984704F58052204692F8C83043F00403E3 -:1021300082F8C830BDE8F840FFF736BF06F1100757 -:1021400091E7F8BD10B5044600F04EFA02460B4682 -:1021500052EA030102D0013A63F10003044908681E -:1021600020B12146BDE81040FFF776BF10BD00BF8B -:1021700010380020F8B500F583511E46FFF7D2FC59 -:10218000DFF844C00831002404F1840500EB451554 -:102190002B795F070ED4DB060CD5D1E9007397428B -:1021A000B34107D243695CF824709F602B7943F0F8 -:1021B00004032B710134032C01F12001E4D1BDE8AB -:1021C000F840FFF7B5BC00BF284A000808B5FFF784 -:1021D000A9FCFFF7E9FEBDE80840FFF7A9BC000035 -:1021E000F8B543690546986800F0E050B0F1E05F4B -:1021F0000F461FD0E8B1FFF795FC05F58354103466 -:10220000002606F1840305EB43131B791A0706D554 -:102210000136032E04F12004F3D1012007E05B070F -:10222000F6D42146384600F039FA0028F0D1FFF7FD -:102230007FFCF8BD0120FCE700F5805008B5FFF7F2 -:1022400071FCC06DFFF750FBFFF772FC43090CBF38 -:102250000120002008BD0000F8B51D4600231370C2 -:102260000F4606461446FFF7E7FF80F0010038707E -:1022700025B129463046FFF7B3FF2070F8BD0000B6 -:102280002DE9B8410C4615461F46804600F0ACF9D2 -:102290000B462178024609B9287850B14046FFF72D -:1022A00069FFFFF793FF3B462A462146FFF7D4FF1D -:1022B0000120BDE8B881000010B5FFF733FC174BD3 -:1022C000DA6942F00072DA611A6942F000721A614A -:1022D0001A6900F5805422F000721A61FFF728FC99 -:1022E00094F8C830DB0718D4B9B103211320FFF7E5 -:1022F00019FC01F0C7F90321142001F0C3F90321EF -:10230000152001F0BFF994F8C83043F0010384F8B8 -:10231000C830BDE81040FFF70BBC10BD00100240F4 -:102320002DE9F04700F5805588B095F8C930012BAC -:102330000446884616467FD8804F57F823200AB9AE -:1023400047F82300D7F800A0C4F80C802674BAF12F -:10235000000F63D095F8C930012B6FD001212046C2 -:10236000FFF7AAFFFFF7DEFB6269136823F00203A1 -:1023700013606269136843F0010313606369002707 -:102380005F6101212046FFF7D3FBFFF7F9FD00282D -:1023900000F09580E86DFFF795FA04F58359BA4689 -:1023A00009F10809202200216846FEF7C7FF02A8AC -:1023B000FFF784FCCDF818A06A4609EB07030DF17E -:1023C000180E9446BCE80300F44518605960624654 -:1023D00003F10803F5D1DCF80000186020379CF801 -:1023E00004201A71602FDDD195F8C8306FF3820395 -:1023F000002785F8C8306A4641462046ADF800708F -:10240000ADF802708DF80470FFF75EFD636948BB9C -:102410004FF400421A6008B0BDE8F08741F2D000E6 -:1024200002F01CFA814610B15146FFF7EBFCC7F8E9 -:102430000090B9F1000F8DD10020ECE738680368F7 -:102440001B6B98470146002888D13868FFF734FF96 -:102450003868036832465B684146984700287FF435 -:102460007DAFE9E761221A609DF802309DF80320F4 -:102470001B06120402F4702203F040731343BDF8EC -:102480000020C2F3090213439DF804201205022E16 -:1024900002F4E0020CBF4FF00041002113436269D7 -:1024A0000B43D361636913225A616269136823F095 -:1024B0000103136039462046FFF762FD08B96369DE -:1024C000A6E795F8C93093BB6169D1F8002242F0C4 -:1024D0000102C1F800226169D1F8002222F47C5285 -:1024E00022F00E02C1F800226169D1F8002242F404 -:1024F0006062C1F800226269C2F814326269C2F8EF -:102500000432626941F6FF71C2F80C126269C2F8C6 -:1025100040326269C2F8443263690122C3F81C2266 -:102520006269D2F8003223F00103C2F8003295F854 -:10253000C83043F0020385F8C8306CE7103800203B -:1025400008B500F051F850EA0103024602D0421EDD -:1025500061F10001044B186810B10B46FFF744FD10 -:10256000BDE8084001F064B81038002008B500202C -:10257000FFF7E8FDBDE8084001F05AB808B50120B2 -:10258000FFF7E0FDBDE8084001F052B800B59BB090 -:10259000EFF3098168226846FEF7BEFEEFF305837C -:1025A000014B9B6BFEE700BF00ED00E008B5FFF7B5 -:1025B000EDFF000000B59BB0EFF30981682268468B -:1025C000FEF7AAFEEFF30583014B5B6BFEE700BF4E -:1025D00000ED00E0FEE700000FB408B5029801F03E -:1025E00019F9FEE701F02EBB01F004BB13B56C46F0 -:1025F00084E80600031D94E8030083E80500012039 -:1026000002B010BD73B58568019155B11B885B0799 -:1026100007D4D0E900369B6B9847019AC1B2304687 -:10262000A847012002B070BDF0B5866889B00546A4 -:102630000C465EB1BDF838305B070AD4D0E90037EC -:102640009B6B98472246C1B23846B047012009B07B -:10265000F0BD00220023CDE900230023ADF80830AF -:102660000A4603AB01F10806106851681C4603C412 -:102670000832B2422346F7D1106820609288A280C7 -:10268000FFF7B2FF0423ADF808302B68CDE9000155 -:10269000DB6B694628469847D8E7000030B50368E9 -:1026A0000968DD0FB5EBD17F23F0604421F0604273 -:1026B0004FEAD1700BD0002BB8BFA40C0029B8BFD3 -:1026C000920C944202D034BF0120002030BD9442CD -:1026D00005D1C1F38070C3F380738342F6D1944275 -:1026E0002CBF00200120F1E72DE9F041456A15B922 -:1026F0004162BDE8F0814B6823F06047C3F38A462E -:102700004FEAD37EC3F3807816EA230638BF3E46ED -:10271000AC462B465A68BEEBD27F22F060440AD00A -:10272000002A18DAA40CB44217D19D420FD10D60D3 -:10273000DEE71346EEE7A74207D102F08044C2F37A -:10274000807242450BD054B1EFE708D2EDE7CCF8E8 -:1027500000100B60CDE7B44201D0B442E5D81A684E -:102760009C46002AE5D11960C3E700002DE9F04737 -:10277000089D01F007044FEAD508224405F007053B -:1027800000EBD1004FF47F49944201D1BDE8F087BE -:1027900004F0070705F0070A57453E4638BF56467E -:1027A000C6F10806111B8E4228BF0E46E10808EB51 -:1027B000D50E415C13F80EC0B94029FA06F721FA8C -:1027C0000AF1FFB28CEA010147FA0AF739408CEAB4 -:1027D000010C03F80EC034443544D5E780EA0120EB -:1027E000082341F2210201B24000002980B203F126 -:1027F000FF33B8BF504013F0FF03F4D1704700001F -:1028000038B50C468D18A54200D138BD14F8011B0F -:10281000FFF7E4FFF7E7000042684AB1136843603E -:102820004389818901339BB29942438138BF8381B7 -:102830001046704770B588B0202204460D466846A1 -:102840000021FEF77BFD20460495FFF7E5FF0246D9 -:1028500058B16B46054608AE1C4603CCB44228600E -:102860006960234605F10805F6D1104608B070BD31 -:10287000082817D909280CD00A280CD00B280CD00E -:102880000C280CD00D280CD00E2814BF402030206E -:1028900070470C2070471020704714207047182094 -:1028A0007047202070470000082817D90C280CD941 -:1028B00010280CD914280CD918280CD920280CD988 -:1028C00030288CBF0F200E207047092070470A2047 -:1028D00070470B2070470C2070470D207047000098 -:1028E0002DE9F843078C072F04461ED9D0E902983A -:1028F00000254FF6FF73C5F12006A5F1200029FA47 -:1029000005F108FA06F628FA00F031430143C9B28E -:102910001846FFF763FF0835402D0346EBD1E16908 -:102920003A46BDE8F843FFF76BBF4FF6FF70BDE8CE -:10293000F883000010B54B6823B9CA8A63F3090213 -:10294000CA8210BD04691A681C600361C38A013B16 -:10295000C3824A60EFE700002DE9F84F1D46CB8A9D -:102960000F46C3F309010529814692460B4630D034 -:102970000020AAB207F11A049EB2042E1FFA80F8B2 -:102980000FD8904503F1010306D3FB8A0A4462F392 -:102990000903FB8201201AE01AF80060E6540130B6 -:1029A000EAE79045F1D2A1F1050B1C237C68BBFB43 -:1029B000F3F203FB12BB1FFA8BF6002C45D14846FD -:1029C000FFF72AFF044638B978606FF00200BDE8CF -:1029D000F88F4FF00008E6E7002606607860ADB299 -:1029E0004FF0000B454510D90AEB0803221D13F8E0 -:1029F000011B9155B1B208F101081B291FFA88F893 -:102A00002BD0454506F10106F1D8FB8AC3F3090234 -:102A1000154465F30903BCE7013292B21C462368F2 -:102A2000002BF9D16B1F0B441C21B3FBF1F30133D5 -:102A30009BB29A42D3D2BBF1000FD0D14846FFF7E8 -:102A4000EBFE20B9C4F800B0BFE70122E7E7C0F809 -:102A500000B05E4620600446C1E74545D5D94846EA -:102A6000FFF7DAFE08B92060AFE7C0F800B0002633 -:102A700020600446B6E700002DE9F04F2DED028BF3 -:102A80001C4683B05B69019207468846002B00F024 -:102A90009A80238C2BB1E269002A00F09480072BE6 -:102AA00035D807F10C00FFF7B7FE054638B96FF0CF -:102AB0000205284603B0BDEC028BBDE8F08F14225E -:102AC0000021FEF73BFC228CE16905F10800FEF7CE -:102AD00023FC208C013080B2FFF7E6FEFFF7C8FE32 -:102AE000013880B22084013028746369228C1B78FD -:102AF0002A4403F01F0363F03F0348F000411372C0 -:102B0000384669602946FFF7EFFD0125D1E700F15E -:102B10000C034FF0000908EE103A4FF0800A4E46C1 -:102B20004D4618EE100AFFF777FE83460028BED008 -:102B300014220021FEF702FC002E3AD1019BABF8D3 -:102B4000083002220BF1080E1FFA82FC0CF1010082 -:102B5000BCF1060F218C80B201D88E422BD3FFF737 -:102B6000A3FEFFF785FE62691278013802F01F02AA -:102B70008E4208BF4FF0400A42EA49121BFA80F128 -:102B80004AEA020A013048F0004281F808A08BF8B6 -:102B90001000CBF8042059463846FFF7A5FD238CDA -:102BA0000135B3422DB289F001094FF0000AB8D1C6 -:102BB0007FE70022C6E7E169895D0EF80210013661 -:102BC000B6B20132C0E76FF0010572E7F8B51546FD -:102BD0000E463022002104461F46FEF7AFFB069B3F -:102BE0006360B5F5001F079BA76034BF6A094FF605 -:102BF000FF72A36297B2E66104F1100000239A42CB -:102C000006D800230360A782E3822383E360F8BD34 -:102C10000660013330462036F1E7000003781BB927 -:102C20004BB2002BC8BF017070470000007870479E -:102C3000F8B50C46C969074611B9238C002B37D16A -:102C4000257E1F2D34D8387828BB228C072A2CD813 -:102C5000268A36F003032BD14FF6FF70FFF7D0FD25 -:102C600020F001003102400441EA0561400C41EAD4 -:102C700040254FF6FF72234629463846FFF7FCFEF3 -:102C8000002807DD626913780133DBB21F2B88BF90 -:102C900000231370F8BD218A2D0645EA012505435E -:102CA0002046FFF71DFE0246E5E76FF00300F1E75F -:102CB0006FF00100EEE7000070B58AB004461646DA -:102CC0000021282268461D46FEF738FBBDF8383043 -:102CD000ADF810300F9B05939DF840308DF81830FB -:102CE000119B07936946BDF84830ADF82030204667 -:102CF000CDE90265FFF79CFF0AB070BD2DE9F041F8 -:102D0000D36905460C4616460BB9138C5BBB377E60 -:102D10001F2F28D895F80080B8F1000F26D0304634 -:102D2000FFF7DEFD3378210241EAC33141EA0801B1 -:102D3000338A41EA076141EA03410246334641F0E2 -:102D400080012846FFF798FE00280ADD3378012B22 -:102D500007D1726913780133DBB21F2B88BF0023C0 -:102D60001370BDE8F0816FF00100FAE76FF0030027 -:102D7000F7E70000F0B58BB004460D46174600217A -:102D8000282268461E46FEF7D9FA9DF84C305A1E96 -:102D9000534253418DF800309DF84030ADF810306B -:102DA000119B05939DF848308DF81830149B0793BC -:102DB0006A46BDF85430ADF8203029462046CDE9AA -:102DC0000276FFF79BFF0BB0F0BD0000406A00B138 -:102DD00004307047436A1A68426202691A600361EC -:102DE000C38A013BC38270472DE9F041D0F82080AF -:102DF000194E14461D464146002709B9BDE8F08129 -:102E0000D1E90223A21A65EB0303964277EB030391 -:102E10001ED2036A8B420DD1FFF78CFD036A1B683B -:102E2000036203690B60C38A0161016A013BC382CB -:102E30008846E2E7FFF77EFD0B68C8F800300369BB -:102E40000B60C38A0161013BC382D8F80010D4E74C -:102E500088460968D1E700BF80841E002DE9F04F45 -:102E60008BB00D46DDF8509014469B4680460028F6 -:102E700000F01981B9F1000F00F01581531E3F2BAE -:102E800000F21181012A03D1BBF1000F40F00B8148 -:102E90000023CDE90833B8F81430B5EBC30F4FEA7F -:102EA000C30703D300200BB0BDE8F08F2B199F425E -:102EB000D8F80C303ABF7F1BFFB227461BB9D8F8B1 -:102EC0001030002B7AD0272D4ED8C5F12806B742F6 -:102ED0004FF000032CBFF6B23E4600932946D8F8C7 -:102EE000080008AB3246FFF741FCA7EB060A354461 -:102EF0005FFA8AFAB8F8143003F10053053BDB009F -:102F00000493D8F80C3003932821039B13B1BAF132 -:102F1000000F2CD1D8F8100040B1BAF1000F05D045 -:102F2000009608AB5246691AFFF720FC38B2002F12 -:102F3000B8D066070AD00AAB03EBD401624211F89D -:102F4000083C02F00702134101F8083C082C3CD968 -:102F5000102C40F2B580202C40F2B780BBF1000F5E -:102F600000F09C80082334E0BA460026C2E7049BA8 -:102F7000E02B28BFE02306930B44AB42059314D902 -:102F80005A1B03980096924534BF5246D2B2691A32 -:102F900008AB04300792FFF7E9FB079A1644AAEB47 -:102FA000020A1544F6B25FFA8AFA049B069A05995A -:102FB0009B1A0493039B1B680393A6E70093D8F81E -:102FC000080008AB3A462946AEE7BBF1000F13D024 -:102FD0000123B4EBC30F6CD0082C12D89DF820301D -:102FE000621E23FA02F2D50706D54FF0FF3202FA2D -:102FF00004F423438DF820309DF8203089F8003008 -:1030000051E7102C12D8BDF82030621E23FA02F2CC -:10301000D10706D54FF0FF3202FA04F42343ADF88E -:103020002030BDF82030A9F800303CE7202C0FD824 -:103030000899631E21FA03F3DA0705D54FF0FF3232 -:1030400002FA04F40C430894089BC9F800302AE7FC -:10305000402C2BD0DDE90865611EC4F12102A4F1EA -:10306000210326FA01F105FA02F225FA03F31143CE -:103070001943CB0712D50122A4F12003C4F120018A -:1030800002FA03F322FA01F1A240524243EA010399 -:1030900063EB430332432B43CDE90823DDE90823E7 -:1030A000C9E90023FFE66FF00100FCE66FF00800BD -:1030B000F9E6082CA0D9102CB3D9202CEED8C3E700 -:1030C000BBF1000FADD0022383E7BBF1000FBBD0F3 -:1030D00004237EE730B5012A144638BF0124402C72 -:1030E00085B028BF40240025012ACDE9025518D813 -:1030F0001B788DF8083063070AD004AB03EBD405C6 -:10310000624215F8083C02F00702934005F8083CBB -:10311000009103462246002102A8FFF727FB05B0D5 -:1031200030BD082AE4D9102A03D81B88ADF808302E -:10313000E1E7202A8DBFD3E900231B680293CDE984 -:103140000223D8E710B5CB681BB98B600B618B826B -:1031500010BD04691A681C600361C38A013BC38205 -:10316000CA60F0E703064CBFC0F3C03002207047CE -:1031700008B50246FFF7F6FF022806D15306C2F350 -:103180000F2001D100F0030008BDC2F30740FBE7A8 -:103190002DE9F04F93B0CDE903230A6804461046A9 -:1031A000FFF7E0FF022814BFC2F306260026002A1C -:1031B0000D46824680F2F28112F0C04940F0EE8165 -:1031C000097B002900F0EA81022803D02378B3426A -:1031D00040F0E781C2F304630693104602F07F03D8 -:1031E0000593FFF7C5FF059B29444FEA834848EA4A -:1031F0000A4848EA4668CE7800230022CDE9082331 -:10320000F309834648EA0008029367D0059B0093C0 -:1032100002466768534608A92046B847002800F0D0 -:10322000C381276A4FB9414604F10C00FFF702FB46 -:10323000074690B96FF0020054E03B6998450DD005 -:103240003F68002FF9D1414604F10C00FFF7F2FA74 -:1032500007460028EED0236A3B60276297F817C024 -:1032600006F01F08CCF3840CACEB08001FFA80FEBC -:103270000028B8BF0EF12000A8EB0C031FFA83FE54 -:10328000D7E90221B8BF00B2002B0793BEBF0EF1F1 -:1032900020031BB2079352EA010338D0039BDFF8E7 -:1032A00024E39A1A049B4FF0000C63EB010196454E -:1032B0007CEB01032BD36B7B97F81AE0734519D194 -:1032C000029B002B78D0012821DC7868F8B9DFF860 -:1032D000F0C2944570EB010316D337E0276A27B993 -:1032E0006FF00C0013B0BDE8F08F3B699845B5D086 -:1032F0003F68F4E7B24890427CEB010301D3002021 -:10330000F0E7029B002BFAD0079B0F2B17DCFA7D0E -:10331000B30002F0030203F07C031343FB7539464C -:103320002046FFF707FB6B7BBB76029B3BB9FB7D1F -:10333000C3F38402013262F38603FB75D0E76A7B34 -:10334000BB7E9A42DBD1029B002B35D0B309022B06 -:1033500032D0039BBB60049BFB60142200210DA8AC -:10336000FDF7ECFF039B0A93049B0B932B1D0C931F -:103370002B7BADF83EB0013BDBB2ADF83C30069B99 -:103380008DF84230059B8DF8433094F82C308DF841 -:1033900040A083F001038DF844308DF84180A3688C -:1033A0000AA920469847FB7DC3F38403013303F049 -:1033B0001F039B02FB82A2E7FB7DC6F34012B2EB28 -:1033C000D31F40F0F480C3F38403434540F0F28000 -:1033D000029A2B7BB609002A4DD0F2075DD4032B4D -:1033E00040F2EB80039BBB60049BFB602B7BAE1D1C -:1033F000033BDBB23246394604F10C00FFF7ACFA6E -:1034000000280CDA39462046FFF794FAFB7DC3F317 -:103410008403013303F01F039B02FB820AE7DDE90B -:103420000884AB883B834FF6FF73C9F12000A9F1F4 -:10343000200228FA09F104FA00F0014324FA02F20A -:1034400011431846C9B2FFF7C9F909F10809B9F1E2 -:10345000400F0346E9D1B8822A7B033AD2B2314603 -:10346000FFF7CEF9FB7DB882DA43C2F3C01262F3F4 -:10347000C713FB7543E786B92E1D013BDBB232460D -:10348000394604F10C00FFF767FA0028BADB2A7B03 -:10349000B88A013AD2B23146E2E7F98AC1F30901AA -:1034A000013B0429DAB25BD8281D002307F11B0673 -:1034B0009A4208D910F801CB06F801C00131013356 -:1034C0000529DBB2F4D103990A9104990B91934237 -:1034D00007F11B010C9138BF043379680D9134BF9B -:1034E00055FA83F300230E93FB8AADF83EB0C3F385 -:1034F00009031A44069B8DF84230059B8DF8433032 -:1035000094F82C30ADF83C2083F001038DF8443062 -:1035100000238DF840A08DF841807B602A7BB88A1B -:10352000013A291DFFF76CF93B8BB882834203D126 -:10353000A3680AA92046984720460AA9FFF702FE79 -:10354000FB7DBA8AC3F38403013303F01F039B029C -:10355000FB823B8B9A420CBF00206FF01000C1E64B -:103560007B68002BAFD0052001E01C3033461E687D -:10357000002EFAD1091A081D2E1D184401EB090C62 -:10358000BCF11B0F5FFA89F39DD89A429BD916F8BC -:10359000013B00F8013B09F10109EFE76FF0090079 -:1035A000A0E66FF00A009DE66FF00B009AE66FF060 -:1035B0000D0097E66FF00E0094E66FF00F0091E6B5 -:1035C00040420F0080841E00EFF3098305494A6BD7 -:1035D00022F001024A63683383F30988002383F3EE -:1035E0001188704700EF00E0302080F3118862B648 -:1035F0000C4B0D4AD96821F4E0610904090C0A4317 -:10360000DA60D3F8FC20094942F08072C3F8FC204C -:103610000A6842F001020A602022DA7783F8220069 -:10362000704700BF00ED00E00003FA05001000E065 -:1036300010B5302383F311880E4B5B6813F40063DD -:1036400014D0F1EE103AEFF30984683C4FF0807328 -:10365000E361094BDB6B236684F3098800F098F87B -:1036600010B1064BA36110BD054BFBE783F3118836 -:10367000F9E700BF00ED00E000EF00E003060008FE -:103680000606000800F1604303F561430901C9B271 -:1036900083F80013012200F01F039A4043099B00A6 -:1036A00003F1604303F56143C3F880211A6070475A -:1036B00000F16040090100F56D40C9B20176704724 -:1036C00000230375826803691B6899689142FBD2E5 -:1036D0005A680360426010605860704700230375A9 -:1036E000826803691B6899689142FBD85A68036035 -:1036F000426010605860704708B50846302383F375 -:1037000011880B7D032B05D0042B0DD02BB983F32F -:10371000118808BD8B6900221A604FF0FF33836166 -:10372000FFF7CEFF0023F2E7D1E9003213605A60C1 -:10373000F3E70000FFF7C4BF054BD96808751868A8 -:1037400002681A60536001220275D860FCF744BF1A -:103750002038002030B50C4BDD684B1C87B0044688 -:103760000FD02B46094A684600F0FEF82046FFF7C6 -:10377000E3FF009B13B1684600F000F9A86907B0A9 -:1037800030BDFFF7D9FFF9E720380020F9360008EF -:10379000044B1A68DB6890689B68984294BF0020CD -:1037A0000120704720380020084B10B51C68D868ED -:1037B00022681A60536001222275DC60FFF78EFFD9 -:1037C00001462046BDE81040FCF706BF2038002027 -:1037D000044B1A68DB6892689B689A4201D9FFF72C -:1037E000E3BF70472038002038B5074C0749084828 -:1037F000012300252370656000F00AFB022323707B -:1038000085F3118838BD00BF483A0020804A00087F -:103810002038002008B572B6044B186500F0CEF9C8 -:1038200000F092FA024B03221A70FEE720380020C3 -:10383000483A002000F0B4B8EFF3118020B9EFF35C -:103840000583302282F311887047000010B530B92B -:10385000EFF30584C4F3080414B180F3118810BD9C -:10386000FFF7B6FF84F31188F9E700008B600223AD -:1038700008618B82084670478368A3F1840243F88D -:10388000142C026943F8442C426943F8402C094A3D -:1038900043F8242CC26843F8182C022203F80C2C9D -:1038A000002203F80B2C044A43F8102CA3F120004B -:1038B000704700BFF10500082038002008B5FFF769 -:1038C000DBFFBDE80840FFF735BF0000024BDB68B7 -:1038D00098610F20FFF730BF20380020302383F39A -:1038E0001188FFF7F3BF000008B50146302383F3CA -:1038F00011880820FFF72EFF002383F3118808BDED -:10390000064BDB6839B1426818605A601360436047 -:103910000420FFF71FBF4FF0FF3070472038002012 -:103920000368984206D01A68026050609961184690 -:10393000FFF700BF7047000010B50A4C23699A6872 -:1039400091420CD85A6881600360426010609A68A6 -:103950005860511A99604FF0FF33A36110BD1B6886 -:10396000891AECE72038002010B4C0E903230023B3 -:103970005DF8044B4361FFF7DFBF00000368816817 -:103980009A680A449A60426813605A600023036090 -:10399000024B4FF0FF329A61704700BF2038002081 -:1039A00070B5124DEB692A460133EB6152F8103FB6 -:1039B000934206D09A68013A9A6030262C69A3682F -:1039C00003B170BDD4E900210A605160236083F324 -:1039D0001188D4E903312046984786F3118861693C -:1039E0000029EBD02046FFF7A7FFE7E720380020AB -:1039F00000207047FEE70000704700004FF0FF30E6 -:103A000070470000BFF34F8F024AD368DB07FCD436 -:103A1000704700BF0020024008B5074B1B7853B920 -:103A2000FFF7F0FF054B1A69120641BF044A5A60BE -:103A300002F188325A6008BD603A0020002002403E -:103A40002301674508B5054B1B7833B9FFF7DAFF4B -:103A5000034A136943F08003136108BD603A0020F4 -:103A6000002002407F289ABF00F58030C00200206D -:103A7000704700004FF400607047000080207047DE -:103A80007F2808B50BD8FFF7EDFF00F5006302684B -:103A9000013204D104308342F9D1012008BD002055 -:103AA000FCE700007F2810B504461CD8FFF7AAFFEA -:103AB000FFF7B2FF0D4BF322DA6002221A61FFF723 -:103AC000D1FF58611A6942F040021A614FF4006157 -:103AD000FFF798FF00F034F9FFF7B4FF2046BDE888 -:103AE0001040FFF7CDBF002010BD00BF00200240F6 -:103AF0002DE9F84312F00103144606D01F4B40F2A3 -:103B0000F3221A600020BDE8F88385181C4A95420C -:103B100004D91A4A4FF43E711160F3E7FFF77CFFB6 -:103B2000FFF770FFDFF86880451A4FF00109012C9C -:103B300005EB01060F4603D8FFF784FF0120E2E7FB -:103B40003B88C8F8109033800020FFF75BFFC8F86F -:103B50001000338831F8022B9BB29A420CD0074BED -:103B600040F20F321A60074B1E60074B1C60074B78 -:103B70001F60FFF767FFC6E7023CD8E75C3A00200A -:103B800000000408503A0020583A0020543A00201F -:103B900000200240084908B50B7828B11BB9FFF78F -:103BA0003BFF01230B7008BD002BFCD0BDE8084093 -:103BB0000870FFF747BF00BF603A002008B54FF418 -:103BC00020414FF0005000F0BDF8BDE808404FF430 -:103BD00000514FF0805000F0B5B800000846114683 -:103BE00000F05EBE012000F05BBE0000084600F061 -:103BF00075BE000030B583B0FFF71EFE0E4B0F4DB3 -:103C0000DB692A684FF47A7101FB03F3934237BFF3 -:103C10000B4A0B49516814682B602EBFD1E9004153 -:103C2000013151601C1941F100010191FFF70EFEB5 -:103C30000199204603B030BD20380020643A0020AE -:103C4000683A002030B583B0FFF7F6FD114B124DF6 -:103C5000DB692A684FF47A7101FB03F3934237BFA3 -:103C60000E4A0E49516814682B602EBFD1E90041FD -:103C7000013151601C1941F100010191FFF7E6FD8E -:103C800001994FF47A7200232046FCF791FA03B0B1 -:103C900030BD00BF20380020643A0020683A002080 -:103CA00010B50244064BD2B2904200D110BD441C64 -:103CB00000B253F8200041F8040BE0B2F4E700BF73 -:103CC000502800400F4B30B51C6A240407D41C6AEE -:103CD00044F440741C621C6A44F400441C620A4CA4 -:103CE000236843F4807323600244084BD2B29042AD -:103CF00000D130BD441C00B251F8045B43F82050A1 -:103D0000E0B2F4E70010024000700040502800408C -:103D100007B5012201A90020FFF7C2FF019803B0F7 -:103D20005DF804FB13B50446FFF7F2FFA04205D08F -:103D3000012201A900200194FFF7C4FF02B010BDC9 -:103D4000704700007047000070470000074B45F2C5 -:103D500055521A6002225A6040F6FF729A604CF681 -:103D6000CC421A60024B01221A70704700300040AA -:103D7000743A0020034B1B781BB1034B4AF6AA226E -:103D80001A607047743A002000300040044B1A68F3 -:103D90002AB902F1804202F50432526A1A60704771 -:103DA000703A0020024B4FF080725A62704700BF99 -:103DB0000010024008B5FFF7E9FF024B1868C0F396 -:103DC000407008BD703A002070470000FEE7000018 -:103DD0000A4B0B480B4A90420BD30B4BDA1C121ABE -:103DE000C11E22F003028B4238BF00220021FDF7E2 -:103DF000A5BA53F8041B40F8041BECE7EC4B000891 -:103E0000583C0020583C0020583C0020FEE70000B1 -:103E100070B51B4B01630025044686B0586085626F -:103E20000E46FFF7E1FB04F11003C4E904334FF041 -:103E3000FF33A361134BE561D969A5600A462B46A0 -:103E4000C4E9082304F13401C4E900440E4AE562E0 -:103E5000256580232046FFF709FD0123E0600B4A1A -:103E60000375009272680192B268CDE90223084B93 -:103E70006846CDE90435FFF721FD06B070BD00BFEF -:103E8000483A0020203800208C4A0008914A000857 -:103E90000D3E00084B6843608B688360CB68C3604D -:103EA0000B6943614B6903628B6943620B68036072 -:103EB0007047000008B51B4B9A6A42F4FC029A62F4 -:103EC0009A6A22F4FC029A629A6A5A6942F4FC02E3 -:103ED0005A61154A5B6911464FF09040FFF7DAFFCF -:103EE00002F11C0100F58060FFF7D4FF02F13801F8 -:103EF00000F58060FFF7CEFF02F1540100F580600D -:103F0000FFF7C8FF02F1700100F58060FFF7C2FF04 -:103F100002F18C0100F58060FFF7BCFFBDE80840AE -:103F200000F05AB800100240984A000808B500F0A6 -:103F300093F9FFF759FCBDE80840FFF727BF0000E1 -:103F40007047000010B5214CA36A63F4FC03A36220 -:103F5000A36A03F4FC03A3624FF0FF32A36A236950 -:103F600022612369002323612169E168E260E2683C -:103F7000E360E268E269164942F08052E261E26978 -:103F80000A6842F480720A60226A02F44072B2F552 -:103F9000407F1EBF4FF4803222622362236A1B04DB -:103FA00007D4236A43F440732362236A43F4004333 -:103FB000236200F031F9A369064A43F00103A361CB -:103FC000A369136843F02003136010BD0010024082 -:103FD00000700040000001401E4B1A6842F00102D0 -:103FE0001A601A689007FCD55A6822F003025A60DA -:103FF0005A6812F00C02FBD1196801F0F90119603E -:104000005A601A6842F480321A601A689103FCD52B -:10401000114A5A604FF40452DA6230221A631A6865 -:1040200042F080721A601A689201FCD50B49122284 -:104030000A600A6802F00702022AFAD15A6842F0BE -:1040400002025A605A6802F00C02082AFAD11A6B6E -:104050001A6370470010024000241D000020024037 -:10406000084A08B5516913680B4003F00103536116 -:1040700023B1054A13680BB150689847BDE8084062 -:10408000FFF7D6BA00040140783A0020084A08B584 -:10409000516913680B4003F00203536123B1054AD1 -:1040A00093680BB1D0689847BDE80840FFF7C0BAE5 -:1040B00000040140783A0020084A08B551691368A5 -:1040C0000B4003F00403536123B1054A13690BB19C -:1040D00050699847BDE80840FFF7AABA00040140BC -:1040E000783A0020084A08B5516913680B4003F07C -:1040F0000803536123B1054A93690BB1D06998470E -:10410000BDE80840FFF794BA00040140783A002067 -:10411000084A08B5516913680B4003F01003536156 -:1041200023B1054A136A0BB1506A9847BDE80840AD -:10413000FFF77EBA00040140783A0020174B10B513 -:104140005A691C68144004F478725A61A30604D5B5 -:10415000134A936A0BB1D06A9847600604D5104A97 -:10416000136B0BB1506B9847210604D50C4A936B27 -:104170000BB1D06B9847E20504D5094A136C0BB11B -:10418000506C9847A30504D5054A936C0BB1D06CCD -:104190009847BDE81040FFF74BBA00BF000401404C -:1041A000783A00201A4B10B55A691C68144004F480 -:1041B0007C425A61620504D5164A136D0BB1506DED -:1041C0009847230504D5134A936D0BB1D06D9847DA -:1041D000E00404D50F4A136E0BB1506E9847A1044A -:1041E00004D50C4A936E0BB1D06E9847620404D587 -:1041F000084A136F0BB1506F9847230404D5054A42 -:10420000936F0BB1D06F9847BDE81040FFF710BA1D -:1042100000040140783A0020062108B50846FFF75F -:1042200031FA06210720FFF72DFA06210820FFF7B3 -:1042300029FA06210920FFF725FA06210A20FFF7AF -:1042400021FA06211720FFF71DFABDE808400621D4 -:104250002820FFF717BA000008B5FFF773FE00F03B -:1042600067F800F03DF8FFF76BFEBDE8084000F08E -:104270005DB80000026843681143016003B118474C -:1042800070470000143000F02FBA00004FF0FF33E9 -:10429000143000F029BA0000383000F0A5BA000050 -:1042A0004FF0FF33383000F09FBA0000143000F0B8 -:1042B000F5B900004FF0FF31143000F0EFB9000005 -:1042C000383000F04FBA00004FF0FF32383000F0C5 -:1042D00049BA0000012914BF6FF013000020704795 -:1042E00000F06CB8044B03600023C0E90233436064 -:1042F00001230374704700BF404B000838B5C36901 -:1043000004460D461BB904210844FFF7B3FF2946B4 -:1043100004F1140000F0A6F9002806DA201D4FF47D -:104320000061BDE83840FFF7A5BF38BD00F00EB80A -:104330000023054A19460133102BC2E9001102F18E -:104340000802F8D1704700BF783A00204FF0E02310 -:10435000044A5A6100229A6107221A6108210B203F -:10436000FFF7A6B93F19010008B5302383F3118880 -:10437000FFF760FA002383F3118808BD08B5FFF743 -:10438000F3FFBDE80840FFF753B900000268436837 -:104390001143016003B1184770470000024A1368D7 -:1043A00043F0C0031360704700380140024A1368AD -:1043B00043F0C003136070470044004037B51D4C04 -:1043C0001D4D2046FFF78EFF009404F114001B4999 -:1043D0000023202200F038F92022009404F1380054 -:1043E000174B184900F0B2F9174BC4E91735174CB1 -:1043F0000C212520FFF746F92046FFF773FF04F153 -:104400001400134900940023202200F01DF904F148 -:104410003800104B10490094202200F097F90F4B00 -:104420000C212620C4E9173503B0BDE83040FFF762 -:1044300029B900BFF83A002000512502D03B0020E6 -:104440009D430008103C002000380140643B0020E0 -:10445000F03B0020AD430008303C00200044004009 -:104460002DE9F047C66D3768F469346221070546C7 -:1044700019D014F0080118BF4FF48071E20748BF4B -:1044800041F02001A30748BF41F04001600748BF49 -:1044900041F08001302383F31188281DFFF776FF58 -:1044A000002383F31188E2050AD5302383F31188B2 -:1044B0004FF48061281DFFF769FF002383F3118803 -:1044C0004FF030094FF0000A14F0200838D13B06B5 -:1044D00016D54FF0300905F1380A200610D589F3BA -:1044E0001188504600F066F9002836DA0821281DA8 -:1044F000FFF74CFF27F080033360002383F311881C -:10450000790614D5620612D5302383F31188D5E9D4 -:1045100013239A4208D12B6C33B11021281D27F0A8 -:104520004007FFF733FF3760002383F31188E3066A -:1045300019D5AA6E1369B3B1BDE8F04750691847A1 -:1045400089F31188B38C95F8641028461940FFF759 -:10455000D5FE8AF31188F469B6E780B2308588F316 -:104560001188F469B9E7BDE8F087000008B5034891 -:10457000FFF776FFBDE80840FFF75AB8F83A002089 -:1045800008B50348FFF76CFFBDE80840FFF750B8D7 -:10459000643B0020F8B5154682680669AA420B46BE -:1045A000816938BF8568761AB54204460BD2184631 -:1045B0002A46FCF7B1FEA3692B44A361A3685B1BE9 -:1045C000A3602846F8BD0CD918463246FCF7A4FE75 -:1045D000AF1BE1683A463044FCF79EFEE3683B447B -:1045E000EBE718462A46FCF797FEE368E5E700008C -:1045F00083689342F7B51546044638BF8568D0E90D -:104600000460361AB5420BD22A46FCF785FE636970 -:104610002B446361A36828465B1BA36003B0F0BD15 -:104620000DD932460191FCF777FE0199E068AF1B86 -:104630003A463144FCF770FEE3683B44E9E72A461A -:10464000FCF76AFEE368E4E710B50A440024C3619E -:10465000029B8460C0E90000C0E90511C1600261ED -:10466000036210BD08B5D0E90532934201D18268DA -:1046700082B98268013282605A1C42611970D0E9A5 -:1046800004329A4224BFC36843610021FFF748F90E -:10469000002008BD4FF0FF30FBE7000070B530236D -:1046A00004460E4683F31188A568A5B1A368A269E4 -:1046B000013BA360531CA36115782269934224BF78 -:1046C000E368A361E3690BB120469847002383F3B5 -:1046D0001188284607E031462046FFF711F90028E7 -:1046E000E2DA85F3118870BD2DE9F74F04460E46D6 -:1046F00017469846D0F81C904FF0300A8AF311887C -:104700004FF0000B154665B12A4631462046FFF7AB -:1047100041FF034660B941462046FFF7F1F8002803 -:10472000F1D0002383F31188781B03B0BDE8F08F2C -:10473000B9F1000F03D001902046C847019B8BF3CD -:104740001188ED1A1E448AF31188DCE7C0E90511CF -:10475000C160C3611144009B8260C0E90000016137 -:1047600003627047F8B504460D461646302383F3BE -:104770001188A768A7B1A368013BA36063695A1CAD -:1047800062611D70D4E904329A4224BFE368636118 -:10479000E3690BB120469847002080F3118807E0B9 -:1047A00031462046FFF7ACF80028E2DA87F311889B -:1047B000F8BD0000D0E905239A4210B501D1826806 -:1047C0007AB98268013282605A1C82611C7803695E -:1047D0009A4224BFC36883610021FFF7A1F82046F5 -:1047E00010BD4FF0FF30FBE72DE9F74F04460E46B2 -:1047F00017469846D0F81C904FF0300A8AF311887B -:104800004FF0000B154665B12A4631462046FFF7AA -:10481000EFFE034660B941462046FFF771F80028D5 -:10482000F1D0002383F31188781B03B0BDE8F08F2B -:10483000B9F1000F03D001902046C847019B8BF3CC -:104840001188ED1A1E448AF31188DCE70B460146F5 -:10485000184600F02DB8000000F040B8012838BF1D -:10486000012010B50446204600F030F830B900F0C1 -:1048700007F808B900F00CF88047F4E710BD000015 -:10488000024B1868BFF35B8F704700BF503C00209D -:1048900008B5062000F084F80120FFF7ABF800000F -:1048A000024B0A4601461868FFF798B91811002014 -:1048B00010B5054C13462CB10A4601460220AFF351 -:1048C000008010BD2046FCE700000000024B0146BE -:1048D0001868FFF787B900BF18110020024B014686 -:1048E0001868FFF783B900BF1811002010B501390F -:1048F0000244904201D1002005E0037811F8014FF5 -:10490000A34201D0181B10BD0130F2E72DE9F041A0 -:10491000A3B1C91A17780144044603F1FF3C8C4245 -:10492000204601D9002009E00578BD4204F10104C8 -:10493000F5D10CEB0405D618A54201D1BDE8F081F4 -:1049400015F8018D16F801EDF045F5D0E7E7000008 -:104950001F2938B504460D4604D9162303604FF0CD -:10496000FF3038BD426C12B152F821304BB92046AD -:1049700000F030F82A4601462046BDE8384000F0F5 -:1049800017B8012B0AD0591C03D11623036001204C -:10499000E7E7002442F82540284698470020E0E752 -:1049A000024B01461868FFF7D3BF00BF1811002063 -:1049B00038B5074D00230446084611462B60FFF723 -:1049C0001DF8431C02D12B6803B1236038BD00BF22 -:1049D000543C0020FFF70CB8034611F8012B03F8F4 -:1049E000012B002AF9D170476F72672E61726475CE -:1049F00070696C6F742E663330332D47505300004E -:104A000040A2E4F1646891060041A3E5F265699271 -:104A1000070000004261642043414E4966616365BE -:104A200020696E6465782E00800000000080000020 -:104A30000000800000000000000000003D1B000896 -:104A400021230008812200084D1B0008811B00085B -:104A50007D1D0008511B0008611B0008551B000844 -:104A60005D1B0008591B0008A51C0008651B0008F9 -:104A7000ED250008751B0008791C00086330000054 -:104A80007C4A000878380020483A00206D61696E41 -:104A90000069646C65000000A001A82A0000000005 -:104AA000FAAABEAA50001424EFFF0000007700000D -:104AB000709709000100000000000000AAAAAAAA3D -:104AC00001000000FFFF00000000000000000000E7 -:104AD0000000000000000000AAAAAAAA000000002E -:104AE000FFFF0000000000000000000000000000C8 -:104AF00000000000AAAAAAAA00000000FFFF000010 -:104B000000000000000000000000000000000000A5 -:104B1000AAAAAAAA00000000FFFF000000000000EF -:104B2000000000000000000000000000AAAAAAAADD -:104B300000000000FFFF0000000000000000000077 -:104B400000000000A14200088D420008C942000890 -:104B5000B5420008C1420008AD4200089942000871 -:104B600085420008D542000878B6FF7F01000000AA -:104B7000EC030000000000000098030000000000AB -:104B8000FE2A0100D20400001C11002000000000D9 -:104B90000000000000000000000000000000000015 -:104BA0000000000000000000000000000000000005 -:104BB00000000000000000000000000000000000F5 -:104BC00000000000000000000000000000000000E5 -:104BD00000000000000000000000000000000000D5 -:0C4BE000000000000000000000000000C9 +:1000000000090020B1010008ED220008A522000827 +:10001000CD220008A5220008C5220008B30100086F +:10002000B3010008B3010008B3010008E132000881 +:10003000B3010008B3010008B3010008B140000893 +:10004000B3010008B3010008B3010008B3010008C0 +:10005000B3010008B3010008953D0008C13D000848 +:10006000ED3D0008193E0008453E0008B3010008B8 +:10007000B3010008B3010008B3010008B301000890 +:10008000B3010008B3010008B301000859220008B9 +:100090008522000895220008B3010008713E00087F +:1000A000B3010008B3010008B3010008B301000860 +:1000B000B3010008B3010008B3010008B301000850 +:1000C000B3010008B3010008B3010008B301000840 +:1000D000B3010008A1420008B5420008B3010008BE +:1000E000D93E0008B3010008B3010008B3010008BD +:1000F000B3010008B3010008B3010008B301000810 +:10010000B3010008B3010008B3010008B3010008FF +:10011000B3010008B3010008B3010008B3010008EF +:10012000B3010008B3010008B3010008B3010008DF +:10013000B3010008B3010008B3010008B3010008CF +:10014000B3010008B3010008B3010008B3010008BF +:10015000B3010008B3010008B3010008B3010008AF +:10016000B3010008B3010008B3010008B30100089F +:10017000B3010008B3010008B3010008B30100088F +:10018000B3010008B3010008B3010008B30100087F +:10019000B3010008B3010008B3010008B30100086F +:1001A000210F000800000000000000000000000017 +:1001B00002E000F000F8FEE772B6374880F30888E6 +:1001C000364880F3098836483649086040F2000016 +:1001D000CCF200004EF63471CEF200010860BFF39D +:1001E0004F8FBFF36F8F40F20000C0F2F0004EF669 +:1001F0008851CEF200010860BFF34F8FBFF36F8FBD +:100200004FF00000E1EE100A4EF63C71CEF2000114 +:100210000860062080F31488BFF36F8F03F06EFC34 +:1002200003F0E2FC4FF055301F491B4A91423CBF9E +:1002300041F8040BFAE71D49184A91423CBF41F8C6 +:10024000040BFAE71A491B4A1B4B9A423EBF51F86E +:10025000040B42F8040BF8E700201849184A9142B1 +:100260003CBF41F8040BFAE703F04CFC03F0F8FC48 +:10027000144C154DAC4203DA54F8041B8847F9E7D7 +:1002800000F042F8114C124DAC4203DA54F8041B52 +:100290008847F9E703F034BC000900200011002072 +:1002A0000000000808ED00E0000100200009002027 +:1002B000A0480008001100207C11002080110020BF +:1002C000543C0020A0010008A4010008A40100087B +:1002D000A40100082DE9F04F2DED108AC1F80CD0D3 +:1002E000C3689D46BDEC108ABDE8F08F002383F300 +:1002F00011882846A047002003F056F9FEE703F0D6 +:10030000DFF800DFFEE70000F8B500F01BFE03F0A9 +:1003100099FB074603F0E8FB064600283ED12B4B2D +:100320009F423BD001339F423BD0294B27F0FF0235 +:100330009A4239D1F8B200F041FC354642F21074CD +:1003400000F042FC08B10024254601F0B1F878B372 +:10035000032000F043F80024254636B11D4B9F4290 +:1003600003D003F0B9FB00242546002003F074FB02 +:10037000194B1B6913F040031FD00DB100F044F876 +:1003800000F054FC01F0BAFF0546C4B101F0B6FF1D +:10039000401BA04213D900F037F8F3E7354600249C +:1003A000CEE704460125CBE705464FF47A74C7E74C +:1003B000B4F57A7F08BF0125CFE71C46E0E700F0DF +:1003C0007DFC012003F0F6F8DFE700BF010007B075 +:1003D000000008B0263A09B000040048084B187025 +:1003E00003280CD8DFE800F008050208022000F01E +:1003F00005BE022000F0FABD024B00225A60704791 +:10040000801100208411002038B501F051F830B17E +:100410001F4B03221A701F4B00225A6038BD1E4B1F +:100420001E4A19680131F9D004339342F9D11C4CAA +:10043000194DD4F80428AA42F0D31A4B9B6803F153 +:10044000006303F5D0439A42E8D203F019FB03F0AE +:100450002BFB002000F090FD0220FFF7BFFF124BA6 +:10046000DA690022DA61D96999699A619B6972B681 +:100470004FF0E0233021C3F8085DD4F80038D4F8F9 +:10048000042881F311889D4683F308881047C5E747 +:1004900080110020841100200068000820680008F6 +:1004A000006000080011002000100240094A136893 +:1004B00049F2690099B21B0C00FB01331360064B33 +:1004C000186844F2506182B2000C01FB020018600F +:1004D00080B27047141100201011002010B50021C7 +:1004E0001022044600F0A4FD034B03CB20606160A2 +:1004F0001868A06010BD00BFACF7FF1F2DE9F041E8 +:10050000ADF54E7D0DF134086CAC40F27512074626 +:100510000D460EA80021C8F8001000F089FD4FF428 +:10052000C4720021204600F083FD01F0E7FE274B56 +:100530004FF47A72B0FBF2F0186093E807000223E0 +:1005400084E807000DF5E9702382FFF7C7FF4EF638 +:1005500003431F49238407A804F0D8F8162384F81E +:1005600032310DF2E32207AB0DF12C0C1E4603CE07 +:10057000664510605160334602F10802F6D13068DA +:100580001060B388938041460122204600F09CFD14 +:1005900000230393AB7E029305F11903019380B20C +:1005A0000123CDE904800093E97E06A3D3E900236B +:1005B000384602F06BFA0DF54E7DBDE8F08100BFC4 +:1005C000AFF300809E6AC421818A46EE8C11002020 +:1005D0001C4700082DE9F0412C4C237ADAB0804604 +:1005E0000D465BBB27A9284600F07EFE0746002883 +:1005F00042D19DF89D60C82E3ED801464FF4A662B8 +:10060000204600F015FD4FF48073C4F8F8314FF424 +:100610000073C4F80C334FF44073C4F820343246EE +:100620000DF19E0104F1090000F0F0FC26449DF854 +:100630009C30777223720BB9EB7E237281220021EA +:1006400006AC27A800F0F4FC0122214627A800F000 +:1006500087FE00230393AB7E029305F1190380B25A +:1006600001932823CDE904400093E97E05A3D3E953 +:100670000023404602F00AFA5AB0BDE8F08100BFFC +:10068000AFF3008026417272DF25D7B7B032002069 +:10069000F0B5254E4FF48A7505FB0065F1B096F86C +:1006A000D83085F8DC300024D822214685F8E8408F +:1006B0003AA800F0BDFC06F1090000F0B1FCD5F845 +:1006C000E4308DF8F000C2B206AF06F109010DF179 +:1006D000F100CDE93A3400F099FC394601223AA8FC +:1006E00000F06AFE80B2CDE9047008230127CDE94D +:1006F000023706F1D803019330230093317A0B4877 +:1007000007A3D3E9002302F0C1F9A04206DD01F0FE +:10071000F5FDC5F8E000384671B0F0BD2046FBE7B6 +:1007200078F6339F93CACD8DB0320020A4210020EB +:100730002DE9F0411D4D1E4E1E4F86B0284602F099 +:10074000D1F9034658B30024CDE90344ADF8144071 +:10075000027B8DF8142099684068029403AA03C2B2 +:100760001B68DFF8548043F00043029301F0C8FD9A +:10077000821941F10003009402A9384601F072F891 +:10078000A04205DD284602F0B1F988F80040D5E71F +:1007900098F80030072B05D8013388F8003006B0F0 +:1007A000BDE8F081014802F0A1F9F8E7A42100209A +:1007B00040420F00D8210020E537002070B50D46DB +:1007C00014461E4602F0BEF850B9022E10D1012C7C +:1007D0000ED112A3D3E90023C5E90023012007E0CD +:1007E000282C10D005D8012C09D0052C0FD00020C2 +:1007F00070BD302CFBD10BA3D3E90023ECE70BA396 +:10080000D3E90023E8E70BA3D3E90023E4E70BA334 +:10081000D3E90023E0E700BFAFF30080401DA12033 +:1008200026812A0B78F6339F93CACD8D9E6AC42108 +:10083000818A46EE26417272DF25D7B7F017304A1B +:1008400039059E5638B505460E4C0021013500F09D +:10085000B5FBA4F82C55B4F82C0500F097FB78B143 +:10086000B4F82C0500F0A2FB014648B9B4F82C05F9 +:1008700000F0A4FBB4F82C350133A4F82C35EAE7DA +:1008800038BD00BFB032002010B50A4B0A4A1A60CA +:1008900003F5805393F860203AB9DC6D2CB1204603 +:1008A00000F080FE204603F071FEBDE810400348D2 +:1008B00000F078BED82100207047000820320020C8 +:1008C0002DE9F04F8FB000AF05460C4602F03AF824 +:1008D000002849D1237E022B1BD1E38A012B18D19A +:1008E00001F00CFD0646FFF7E1FD03464FF4C8702A +:1008F000DFF8C482B3FBF0F206F5167602FB103384 +:1009000016FA83F3C8F80030E37E33B9A34B002214 +:100910001A703C37BD46BDE8F08F07F12401204630 +:1009200000F0A0FC0028F4D107F11400FFF7D6FD79 +:1009300097F8264007F11401224607F1270003F03B +:100940006FFE0028E2D10F2C08D8944B1C70D8F809 +:100950000030A3F51673C8F80030DAE797F82410D2 +:10096000284601F0E7FFD4E7E38A282B2BD010D8E4 +:10097000012B23D0052BCCD1BFF34F8F8849894B56 +:10098000CA6802F4E0621343CB60BFF34F8F00BF2D +:10099000FDE7302BBDD1844EE17E327A9142B8D151 +:1009A000607E3146002291F8DC50854200F0A5803F +:1009B0000132042A01F58A71F5D1AAE721462846B9 +:1009C000FFF79CFDA5E721462846FFF703FEA0E7B9 +:1009D000B2F8EC507B6005F103094FEA99094FEA40 +:1009E0008902D11DC908A8EBC1039D46EB46002131 +:1009F000584600F01DFB04F1EE012A4631445846EA +:100A000000F004FB7B6813B9012000F0B5FA96F8FA +:100A1000D20000F0BBFA044630B9307200F0D6FACA +:100A2000204600F0A9FAB1E0D6F8D4203AB996F8F9 +:100A3000D200B6F82C25824201D8FFF703FFD6F882 +:100A4000D4202A44944208D296F8D200B6F82C2535 +:100A50000130824201D8FFF7F5FE70685FFA89F233 +:100A6000594600F0EDFA08B9C54679E0726896F883 +:100A7000D2002A447260D6F8D42005EB0209C6F8E9 +:100A8000D49000F083FA814509D396F8D220D6F8A5 +:100A9000D4000132001B86F8D220C6F8D400FF2D06 +:100AA0000FD80024347200F091FA204600F064FA66 +:100AB00000F0FEFC3D4B188108B9FFF7A5FCC546C8 +:100AC00027E7BB6896F8D9000AFB0362FB68D2F8F7 +:100AD000E41082F8E83001F58061C2F8E030C2F835 +:100AE000E410FFF7D5FDFFF723FE96F8D920013279 +:100AF00002F0030286F8D920B6E74FF48A7A0AFB9F +:100B000002F505F1EA013144204600F081FCF8606D +:100B100000287FF4FEAE3544012285F8E82001F07C +:100B2000EDFBD5F8E020D6ED007ADFED216A801AE2 +:100B3000192838BF192040F6B832904228BF104615 +:100B4000B8EE677A07EE900AF8EEE77A67EEA67AD3 +:100B5000DFED186AE7EE267AFCEEE77AC6ED007A5A +:100B600096F8D930BB60BA6873680AFB02F4321990 +:100B700092F8E81059B1D2F8E4108B42E8463FF4FD +:100B800027AF002182F8E810C2F8E010C54673686C +:100B9000064A9B0A01331381BBE600BF9D2100205A +:100BA00000ED00E00400FA05B03200208C110020B6 +:100BB000CDCCCC3D6666663FA0210020014B18706D +:100BC000704700BF9811002038B54FF00054134B08 +:100BD00022689A4220D1124B627D12481A70237DFE +:100BE00003724FF48073C0F8F8314FF40073C0F80B +:100BF0000C3300254FF44073C0F820340A49C0F884 +:100C0000E450C922093000F001FAE02229462046CA +:100C100000F00EFA012038BD0020FCE79AAD44C573 +:100C200098110020B03200201600002037B500F0E7 +:100C30003FFC194D194928810223012218486B7184 +:100C400001F0F8F900230193164B17490093174858 +:100C5000174B4FF4805201F045FE164B197811B135 +:100C6000124801F067FE01F049FB0446FFF71EFC45 +:100C70004FF4C873B0FBF3F202FB130304F51670D4 +:100C800010FA83F00C4B186002F02EFF08B10F230E +:100C90002B8103B030BD00BF8C11002040420F00FB +:100CA000D8210020BD0700089C110020A4210020AD +:100CB000C108000898110020A02100202DE9F04F64 +:100CC0002DED028B8EA7D7E900670FF23C29D9E9F9 +:100CD0000089864C95B00DAD9FED828BFFF728FD06 +:100CE000DFF82CB200230C93ADF83C300D936B6011 +:100CF00000230DF125028DED008B4FF0010A09A9AB +:100D000058468DF825308DF824A001F041F99DF862 +:100D100024200023002A40F0AB80204601F012FE80 +:100D20000546002847D1DFF8ECB101F0E7FADBF81F +:100D3000003098423FD301F0E1FA0790FFF7B6FB8D +:100D4000079A4FF4C873B0FBF3F101FB130302F5EC +:100D5000167010FA83F0CBF80000DFF8BCB19BF8F6 +:100D600000100791002914BF2B46534610A88DF898 +:100D70003030FFF7B3FB0799C1F11002D2B2062A57 +:100D800010AB28BF062219440DF13100079200F084 +:100D90003DF9079A0CAB0393182302930132544B8D +:100DA000D2B2CDE900A304923B463246204601F080 +:100DB0000FFE8BF8005001F0A1FA4E4A4E4D136819 +:100DC000C31AB3F57A7F32D3106001F099FA024664 +:100DD0000B46204601F094FE204601F0B3FD30B3EF +:100DE0002B7ADFF838A1002B14BF032302238AF8E3 +:100DF000053001F083FA0DF1400B4FF47A730122B4 +:100E0000B0FBF3F05946CAF80000504600F002FA71 +:100E100018230293394B019380B240F25513CDE968 +:100E200003B0009342464B46204601F0D1FD2B7A99 +:100E3000CBB101F063FA4FF0000A83464FF48A7297 +:100E400095F8D900504400F0030002FB005393F8DA +:100E5000E81089B30AF1010ABAF1040FF0D12B7A34 +:100E6000002B7FF438AF15B0BDEC028BBDE8F08FDE +:100E70004FF0904110A84A6982F010024A61194669 +:100E8000102200F0D5F80DF126030AAA0CA9584645 +:100E900000F0E8FD95E8030011AB83E803009DF83E +:100EA0003C308DF84C300C9B109310A9DDE90A23DF +:100EB000204601F0F9FF1BE7D3F8E01049B12B6899 +:100EC000FA2B38BFFA23ABEB01010533B1EB430F2B +:100ED000C0D3FFF7DDFB4FF48A720028BAD1BEE71A +:100EE000AFF300800000000000000000A4210020FB +:100EF0009C210020E0370020B0320020E4370020A1 +:100F0000401DA12026812A0BF1C6A7C1D068080F79 +:100F1000D8210020A02100209D2100208C1100203C +:100F200008B5054800F03AFEBDE80840034A044908 +:100F3000002003F025BB00BFD8210020203800206E +:100F40008908000870B502F00DFC094E094D30808B +:100F5000002428683388834208D902F0FFFB2B68FD +:100F600004440133B4F5D04F2B60F2D370BD00BF01 +:100F700014380020E837002002F080BC00F1006047 +:100F8000920000F5D04002F027BC0000054B1A6823 +:100F9000054B1B889B1A834202D9104402F0DEBB2A +:100FA00000207047E837002014380020024B1B68EF +:100FB000184402F0D9BB00BFE8370020024B1B6881 +:100FC000184402F0E3BB00BFE8370020064991F85F +:100FD000243033B10023086A81F824300822FFF757 +:100FE000CDBF0120704700BFEC370020022802BFB0 +:100FF0004FF0904310229A6170470000022802BF10 +:101000004FF090434FF480129A61704710B500235F +:10101000934203D0CC5CC4540133F9E710BD000007 +:1010200003460246D01A12F9011B0029FAD1704773 +:1010300002440346934202D003F8011BFAE77047CB +:101040002DE9F8431F4D144695F82420074688469D +:1010500052BBDFF870909CB395F824302BB9202256 +:10106000FF2148462F62FFF7E3FF95F82400C0F107 +:101070000802A24228BF2246D6B24146920005EBA2 +:101080008000FFF7C3FF95F82430A41B1E44F6B27E +:10109000082E17449044E4B285F82460DBD1FFF7B2 +:1010A00095FF0028D7D108E02B6A03EB8203834227 +:1010B000CFD0FFF78BFF0028CBD10020BDE8F8830D +:1010C0000120FBE7EC3700202DE9F0470D460446F0 +:1010D00000219046284640F27912FFF7A9FF2346E7 +:1010E00020220021284601F081FE231D022220211A +:1010F000284601F07BFE631D03222221284601F0D1 +:1011000075FEA31D03222521284601F06FFE04F180 +:10111000080310222821284601F068FE04F110037C +:1011200008223821284601F061FE04F1110308224B +:101130004021284601F05AFE04F1120308224821FA +:10114000284601F053FE04F11403202250212846C2 +:1011500001F04CFE04F1180340227021284601F0F2 +:1011600045FE04F120030822B021284601F03EFE8E +:1011700004F121030822B821284601F037FE04F1CA +:101180002207C0263B46314608222846083601F091 +:101190002DFEB6F5A07F07F10107F3D104F132036C +:1011A00008223146284601F021FE002704F1330AC7 +:1011B00094F832304FEAC7099F4209F5A47615D357 +:1011C000B8F1000F08D1314604F59973072228467B +:1011D00001F00CFE09F24F16274694F832213B1B12 +:1011E00093420CD3F01DC008BDE8F0870AEB07035B +:1011F00008223146284601F0F9FD0137D8E707F209 +:10120000331331460822284601F0F0FD0836013735 +:10121000E3E7000013B504460846002101602346B9 +:10122000C0F803102022019001F0E0FD0198231D79 +:101230000222202101F0DAFD0198631D0322222100 +:1012400001F0D4FD0198A31D0322252101F0CEFD5C +:10125000019804F108031022282101F0C7FD07209E +:1012600002B010BDF7B50023047F00910E4607229F +:101270001946054601F07EFC731C009301220023F1 +:101280000721284601F076FCC4B9B31C009305225F +:1012900023460821284601F06DFC0D243746B2781C +:1012A000BB1B934211D32B7FA88A0734E408BBB938 +:1012B000844294BF0020012003B0F0BDAB8ADB0064 +:1012C000083BDB08B3700824E8E7FB1C00932146C9 +:1012D00000230822284601F04DFC08340137DEE7E0 +:1012E000201A18BF0120E7E7F7B50023047F00911B +:1012F0000E4608221946054601F03CFC731CC4B991 +:101300000822009311462346284601F033FC10249E +:10131000012372785F1C013B934211D32B7FA88A73 +:101320000734E408BBB9844294BF0020012003B015 +:10133000F0BDAB8ADB00083BDB0873700824E7E7ED +:10134000F3190093214600230822284601F012FCDD +:1013500008343B46DDE7201A18BF0120E7E700000C +:10136000F8B50E4605461446002181223046FFF7A7 +:101370005FFE2B4608220021304601F037FD7CB984 +:101380006B1C07220821304601F030FD0F24012399 +:101390006A785F1C013B934204D3E01DC008F8BD8E +:1013A0000824F4E7EB1921460822304601F01EFD1F +:1013B00008343B46ECE70000F8B50E4605461446F7 +:1013C0000021CE223046FFF733FE2B462822002193 +:1013D000304601F00BFD7CB905F1080308222821F5 +:1013E000304601F003FD30242F462A7A7B1B9342BE +:1013F00004D3E01DC008F8BD2824F5E707F1090370 +:1014000021460822304601F0F1FC08340137ECE7B0 +:10141000F7B5047F00910E460123102200210546F6 +:1014200001F0A8FBC4B9B31C009309222346102184 +:10143000284601F09FFB192437467288BB1B9A424D +:1014400011D82B7FA88A0734E408BBB9844294BF23 +:101450000020012003B0F0BDAB8ADB00103BDB08AD +:1014600073801024E8E73B1D0093214600230822E7 +:10147000284601F07FFB08340137DEE7201A18BF49 +:101480000120E7E730B5094D0A4491420DD011F82B +:10149000013B5840082340F30004013B2C4013F06B +:1014A000FF0384EA5000F6D1EFE730BD2083B8EDAA +:1014B000F7B5364A106851686B4603C36A4634492B +:1014C0003448082303F0BCF8044690BB0A25324A8E +:1014D000106851686B4603C36A4630492D4808239B +:1014E00003F0AEF80446002847D00369B3F5663F21 +:1014F00043D8B0F86620B2F57B7F3ED1284A02443B +:1015000002F15C018B4238D35C3B224900209E1AD9 +:10151000FFF7B8FF3246074604F164010020FFF7E9 +:10152000B1FFA3689F4228D1E368984208BF002515 +:1015300023E00369B3F5663F26D8428BB2F57B7F83 +:1015400020D1174A024402F110018B4218D3103BFC +:10155000104900209D1AFFF795FF2A46064604F120 +:1015600018010020FFF78EFFA3689E4202D1E368B6 +:10157000984201D00D25AAE70025284603B0F0BD0A +:101580001025A4E70C25A2E70B25A0E734470008A7 +:10159000DC970300006800083D47000890970300AF +:1015A0000898FFF710B5037C044613B9006803F0F0 +:1015B0002FF8204610BD00000023BFF35B8FC360EF +:1015C000BFF35B8FBFF35B8F8360BFF35B8F7047AD +:1015D000BFF35B8F0068BFF35B8F704770B5054644 +:1015E0000C30FFF7F5FF05F1080604463046FFF71B +:1015F000EFFFA04206D930466D68FFF7E9FF2544AA +:10160000281A70BD3046FFF7E3FF201AF9E7000003 +:1016100070B50546406898B105F10800FFF7D8FF9E +:1016200005F10C0604463046FFF7D2FF84423046EF +:1016300094BF6D680025FFF7CBFF013C2C44201AB6 +:1016400070BD000038B50C460546FFF7C7FFA04245 +:1016500010D305F10800FFF7BBFF04446868B4FB32 +:10166000F0F100FB1144BFF35B8F0120AC60BFF3CE +:101670005B8F38BD0020FCE72DE9F041144607469A +:101680000D46FFF7C5FF844228BF0446D4B1B846D3 +:1016900058F80C6B4046FFF79BFF304428604046EB +:1016A0007E68FFF795FF331A9C4203D86C600120D7 +:1016B000BDE8F0816B60A41B3B68AB602044E86030 +:1016C0000220F5E72046F3E738B50C460546FFF75C +:1016D0009FFFA04210D305F10C00FFF779FF0444EF +:1016E0006868B4FBF0F100FB1144BFF35B8F01208D +:1016F000EC60BFF35B8F38BD0020FCE72DE9FF41B4 +:10170000884669460746FFF7B7FF6C4606B204EB0A +:10171000C6060025B44209D06268206808EB0501BE +:10172000FFF774FC636808341D44F3E72946384624 +:10173000FFF7CAFF284604B0BDE8F081F8B50546BA +:101740000C300F46FFF744FF05F10806044630460B +:10175000FFF73EFFA042304688BF6C68FFF738FFB6 +:10176000201A386020B130462C68FFF731FF204442 +:10177000F8BD000073B5144606460D46FFF72EFF70 +:10178000844228BF04460190DCB101A93046FFF72E +:10179000D5FF019B33B93268C5E90233C5E900249E +:1017A00001200CE09C4238BF0194286001986860D9 +:1017B0008442F5D93368AB60241AEC60022002B091 +:1017C00070BD2046FBE700002DE9FF410F4669464A +:1017D000FFF7D0FF6C4600B204EBC0050026AC4218 +:1017E00009D0D4F8048054F8081BB8194246FFF712 +:1017F0000DFC4644F3E7304604B0BDE8F08100003C +:1018000038B50546FFF7E0FF044601462846FFF7D6 +:1018100019FF204638BD000010B4026854681A460B +:1018200023465DF8044B184700207047002070479E +:1018300070470000002070470E20704700F5805070 +:1018400090F8C800C0F340007047000000F58050D9 +:1018500090F9D0007047000000F58050C0F8CC101F +:1018600001207047F7B50C68BDF8207014F00054E3 +:1018700070D10D7B082D6DD8302585F31188456911 +:10188000AE6876010CD4AC68240108D4AC6814F0BE +:1018900080545DD184F31188204603B0F0BD01244B +:1018A0000E6804F1180C002EB8BFF6004FEA0C1CAD +:1018B000B4BF46F00406760545F80C600E680FFAD2 +:1018C00084FC16F0804F18BF05EB0C1E05EB0C1CBA +:1018D0001EBFDEF8806146F00206CEF880610E7B06 +:1018E000CCF8846105EB04158E68C5F88C614E68F0 +:1018F000C5F88861DCF8805145F00105CCF88051CD +:1019000000EB441641F268052E4405EB44150544EE +:10191000C6E9002308350E4601F10C0C56F804EB1D +:1019200045F804EB6645F9D1843436882E8000EB07 +:10193000441407F00305267926F00B06354325717C +:10194000002484F31188009700F0FAFC0120A4E73A +:101950000224A5E74FF0FF309FE7000013B500F524 +:1019600080540191E06DFFF753FE1F280AD90199B9 +:10197000E06D2022FFF7C2FEA0F12003584258413B +:1019800002B010BD0020FBE708B5302383F31188B7 +:1019900000F58050C06DFFF70FFE002383F3118820 +:1019A00008BD0000002202608281426082607047B0 +:1019B00010B500220023C0E9002300230446038160 +:1019C0000C30FFF7EFFF204610BD0000F0B50546D4 +:1019D00000F580500C4690F8C83013F0040FC3F3A4 +:1019E000800108BF114661F3820304F1840680F888 +:1019F000C83005EB461389B01B79D8072ED57AB3CA +:101A000019072DD46846FFF7D3FF05EB441303F500 +:101A1000835303F1180703AA103318685968144652 +:101A200003C40833BB422246F7D1186820609B8864 +:101A3000A380DDE90E23CDE900230123ADF80830B2 +:101A40002B686946DB6B2846984705EB46152B79D2 +:101A50001A075CBF43F008032B7101E0002AF4D1A0 +:101A600009B0F0BD2DE9F0479A4688B00746884690 +:101A70009146302383F3118807F580546846FFF7B9 +:101A800097FFE06DFFF7AAFD1F282AD9E06D2022FD +:101A90006946FFF7B5FE202823D103AD444605ABC8 +:101AA0002E4603CE9E4220606160354604F1080454 +:101AB000F6D130682060B388A380DDE90023C9E94E +:101AC0000023BDF80830AAF80030002383F3118802 +:101AD00053464A464146384608B0BDE8F04700F054 +:101AE0001DBC002080F3118808B0BDE8F08700001D +:101AF0002DE9F84F0023C0E90133254B044640F897 +:101B0000183B0F46FFF74EFF04F12800FFF750FF88 +:101B100004F1480804F5825546460835304620361B +:101B2000FFF746FFAE42F9D104F580554FF48053DC +:101B30004FF00009C5E91339C5F848800123EE6567 +:101B400004F5875804F58456C5F8549085F8583044 +:101B500085F86030083608F108084FF0000A4FF0A9 +:101B6000000B46E908ABA6F11800FFF71BFF203673 +:101B700046F8289C4645F4D185F8D07017B1054841 +:101B800000F0B6FB044B63612046BDE8F88F00BF50 +:101B900070470008484700080064004010B5044B37 +:101BA000197804464A1C1A70FFF7A2FF204610BDA0 +:101BB0001C3800202DE9F047002950D0294B2A4F2E +:101BC000B7FBF1F599428CBF0A231123581EB5FBD0 +:101BD000F3FC03FB1C53C4B22BB102280346F5D817 +:101BE0000020BDE8F0870CF1FF36B6F5806FF7D224 +:101BF000C4EBC40E0EF103034FEAE309C3F3C703BA +:101C0000A4EB030809F1010A4FF47A755FFA88F032 +:101C100009FB05555AFA88F8B5FBF8F5B5F5617F6B +:101C2000C1BF0EF1FF33C3F3C703E01AC0B25C1C9F +:101C300050FA84F40CFB04F4B7FBF4F4A142CFD1C6 +:101C4000013BDBB20F2BCBD80138C0B20728C7D875 +:101C50000021107116809170D3700120C1E70846F1 +:101C6000BFE700BF3F420F000051250270B5054697 +:101C70000E464FF47A746B695B6803F00103B3425C +:101C80004FF0010004D001F095FC013CF3D1204657 +:101C900070BD000030B54269936913F0700F16D023 +:101CA00000230B4C936103F1840200EB4212117983 +:101CB0004D0709D5890707D5416954F823508D6030 +:101CC000117941F0040111710133032BEBD130BDC7 +:101CD0005C47000873B51D46436916469A68D207EB +:101CE000044609D59A6801219960C2F34002CDE902 +:101CF00000650021FFF76AFE63699A68D1050BD57C +:101D00009A684FF480719960C2F34022CDE9006572 +:101D100001212046FFF75AFE63699A68D2030BD56A +:101D20009A684FF480319960C2F34042CDE9006572 +:101D300002212046FFF74AFE04F58053D3F8CC0079 +:101D400010B103681B699847204602B0BDE8704097 +:101D5000FFF7A0BFF8B504464669002972D106F125 +:101D60000C073868800770D006EB01153868D5F885 +:101D7000B00110F0040FD5F8B0011ABFC00840F050 +:101D80000040400DA061D5F8B0C11CF0020F1CBF8F +:101D900040F08040A061D5F8B40106EB011100F0DD +:101DA0000F0084F82400D1F8B8012077D1F8B801E9 +:101DB000000A6077D1F8B801000CA077D1F8B8011B +:101DC000000EE077D1F8BC0184F82000D1F8BC0106 +:101DD000000A84F82100D1F8BC01000C84F822002C +:101DE000D1F8BC11090E84F823103821396004F1B0 +:101DF000340004F1180104F1240551F8046B40F893 +:101E0000046BA942F9D109880180C4E90A2321465B +:101E10000023238651F8283B2046DB6B984704F5C6 +:101E2000805393F8C820D3F8CC0042F0040283F822 +:101E3000C82010B103681B6998472046BDE8F840E8 +:101E4000FFF728BF06F110078BE7F8BD10B5044671 +:101E500000F056FA02460B4652EA030102D0013A5C +:101E600063F100030449086820B12146BDE8104031 +:101E7000FFF770BF10BD00BF18380020F0B530214B +:101E800081F31188DFF848C000F583510831002440 +:101E900004F1840500EB45152E7977070ED4F6067C +:101EA0000CD5D1E9007697429E4107D246695CF88D +:101EB0002470B7602E7946F004062E710134032C8D +:101EC00001F12001E4D1002383F31188F0BD00BFAC +:101ED0005C47000808B5302383F31188FFF7DAFE6A +:101EE000002383F3118808BDF8B543690546986857 +:101EF00000F0E050B0F1E05F0F4621D0F8B13023A0 +:101F000083F3118805F583541034002606F1840309 +:101F100005EB43131B791A0706D50136032E04F18E +:101F20002004F3D1012007E05B07F6D421463846B0 +:101F300000F040FA0028F0D1002383F31188F8BDA7 +:101F40000120FCE708B5302383F3118800F58050A9 +:101F5000C06DFFF743FB002383F3118843090CBFD7 +:101F60000120002008BD0000F8B51D4600231370B5 +:101F70000F4606461446FFF7E5FF80F00100387073 +:101F800025B129463046FFF7AFFF2070F8BD0000AD +:101F90002DE9B8410C4615461F46804600F0B0F9C1 +:101FA0000B462178024609B9287850B14046FFF720 +:101FB00065FFFFF78FFF3B462A462146FFF7D4FF18 +:101FC0000120BDE8B881000070B5302686F3118885 +:101FD000174BDA6942F00072DA611A6942F0007256 +:101FE0001A611A6922F000721A61002383F31188C2 +:101FF00000F5805494F8C83013F0010516D1A9B14A +:1020000086F311880321132001F0C8F9032114205D +:1020100001F0C4F90321152001F0C0F994F8C8308B +:1020200043F0010384F8C83085F3118870BD00BF08 +:10203000001002402DE9F04700F5805588B095F872 +:10204000D030012B04468846164600F28180814F2D +:1020500057F823200AB947F82300D7F800A0C4F89E +:102060000C802674BAF1000F64D095F8D030012BA3 +:1020700070D001212046FFF7A7FF302383F311889A +:102080006269136823F0020313606269136843F006 +:1020900001031360636900275F6187F311880121E1 +:1020A0002046FFF7E3FD002800F09580E86DFFF77C +:1020B00083FA04F58359BA4609F108092022002160 +:1020C0006846FEF7B5FF02A8FFF76CFCCDF818A034 +:1020D0006A4609EB07030DF1180E9446BCE80300AD +:1020E000F44518605960624603F10803F5D1DCF845 +:1020F0000000186020379CF804201A71602FDDD191 +:1021000095F8C8306FF38203002785F8C8306A4617 +:1021100041462046ADF80070ADF802708DF80470AD +:10212000FFF748FD636948BB4FF400421A6008B0EE +:10213000BDE8F08741F2D80002F02AFA814610B1DA +:102140005146FFF7D5FCC7F80090B9F1000F8CD1CC +:102150000020ECE7386803681B6B984701460028AD +:1021600087D13868FFF730FF3868036832465B680C +:102170004146984700287FF47CAFE9E761221A6066 +:102180009DF802309DF803201B06120402F4702211 +:1021900003F040731343BDF80020C2F30902134358 +:1021A0009DF804201205022E02F4E0020CBF4FF04D +:1021B00000410021134362690B43D3616369132219 +:1021C0005A616269136823F001031360394620469F +:1021D000FFF74CFD08B96369A6E795F8D03093BBCB +:1021E0006169D1F8002242F00102C1F80022616960 +:1021F000D1F8002222F47C5222F00E02C1F8002213 +:102200006169D1F8002242F46062C1F8002262697B +:10221000C2F814326269C2F80432626941F6FF7191 +:10222000C2F80C126269C2F840326269C2F84432E4 +:1022300063690122C3F81C226269D2F8003223F0DC +:102240000103C2F8003295F8C83043F0020385F864 +:10225000C8306CE71838002008B500F051F850EA93 +:102260000103024602D0421E61F10001044B1868CE +:1022700010B10B46FFF72EFDBDE8084001F064B831 +:102280001838002008B50020FFF7E0FDBDE8084041 +:1022900001F05AB808B50120FFF7D8FDBDE80840A5 +:1022A00001F052B800B59BB0EFF30981682268468F +:1022B000FEF7ACFEEFF30583014B9B6BFEE700BF1F +:1022C00000ED00E008B5FFF7EDFF000000B59BB0A2 +:1022D000EFF3098168226846FEF798FEEFF3058365 +:1022E000014B5B6BFEE700BF00ED00E0FEE7000086 +:1022F0000FB408B5029801F00DF9FEE701F040BBFC +:1023000001F0ECBA13B56C4684E80600031D94E8AE +:10231000030083E80500012002B010BD73B5856895 +:10232000019155B11B885B0707D4D0E900369B6B40 +:102330009847019AC1B23046A847012002B070BD4B +:10234000F0B5866889B005460C465EB1BDF83830F8 +:102350005B070AD4D0E900379B6B98472246C1B28D +:102360003846B047012009B0F0BD00220023CDE976 +:1023700000230023ADF808300A4603AB01F108063C +:10238000106851681C4603C40832B2422346F7D194 +:10239000106820609288A280FFF7B2FF0423ADF896 +:1023A00008302B68CDE90001DB6B69462846984769 +:1023B000D8E7000030B503680968DD0FB5EBD17FC1 +:1023C00023F0604421F060424FEAD1700BD0002B23 +:1023D000B8BFA40C0029B8BF920C944202D034BFFD +:1023E0000120002030BD944205D1C1F38070C3F3B9 +:1023F00080738342F6D194422CBF00200120F1E784 +:102400002DE9F041456A15B94162BDE8F0814B689C +:1024100023F06047C3F38A464FEAD37EC3F3807844 +:1024200016EA230638BF3E46AC462B465A68BEEB3A +:10243000D27F22F060440AD0002A18DAA40CB442F9 +:1024400017D19D420FD10D60DEE71346EEE7A7429C +:1024500007D102F08044C2F3807242450BD054B1E0 +:10246000EFE708D2EDE7CCF800100B60CDE7B442FF +:1024700001D0B442E5D81A689C46002AE5D119601B +:10248000C3E700002DE9F047089D01F007044FEA7B +:10249000D508224405F0070500EBD1004FF47F4931 +:1024A000944201D1BDE8F08704F0070705F0070A60 +:1024B00057453E4638BF5646C6F10806111B8E42A8 +:1024C00028BF0E46E10808EBD50E415C13F80EC09C +:1024D000B94029FA06F721FA0AF1FFB28CEA0101A4 +:1024E00047FA0AF739408CEA010C03F80EC034446D +:1024F0003544D5E780EA0120082341F2210201B2E8 +:102500004000002980B203F1FF33B8BF504013F000 +:10251000FF03F4D17047000038B50C468D18A54272 +:1025200000D138BD14F8011BFFF7E4FFF7E7000006 +:1025300042684AB1136843604389818901339BB281 +:102540009942438138BF83811046704770B588B087 +:10255000202204460D4668460021FEF769FD20460C +:102560000495FFF7E5FF024658B16B46054608AEF5 +:102570001C4603CCB44228606960234605F1080577 +:10258000F6D1104608B070BD082817D909280CD01C +:102590000A280CD00B280CD00C280CD00D280CD0FD +:1025A0000E2814BF4020302070470C2070471020A8 +:1025B0007047142070471820704720207047000093 +:1025C000082817D90C280CD910280CD914280CD994 +:1025D00018280CD920280CD930288CBF0F200E20A9 +:1025E0007047092070470A2070470B2070470C2065 +:1025F00070470D20704700002DE9F843078C072F26 +:1026000004461ED9D0E9029800254FF6FF73C5F1A4 +:102610002006A5F1200029FA05F108FA06F628FAA5 +:1026200000F031430143C9B21846FFF763FF083594 +:10263000402D0346EBD1E1693A46BDE8F843FFF788 +:102640006BBF4FF6FF70BDE8F883000010B54B6814 +:1026500023B9CA8A63F30902CA8210BD04691A68E1 +:102660001C600361C38A013BC3824A60EFE700003C +:102670002DE9F84F1D46CB8A0F46C3F30901052902 +:10268000814692460B4630D00020AAB207F11A04C8 +:102690009EB2042E1FFA80F80FD8904503F1010373 +:1026A00006D3FB8A0A4462F30903FB8201201AE085 +:1026B0001AF80060E6540130EAE79045F1D2A1F142 +:1026C000050B1C237C68BBFBF3F203FB12BB1FFA58 +:1026D0008BF6002C45D14846FFF72AFF044638B94F +:1026E00078606FF00200BDE8F88F4FF00008E6E771 +:1026F000002606607860ADB24FF0000B454510D95A +:102700000AEB0803221D13F8011B9155B1B208F121 +:1027100001081B291FFA88F82BD0454506F1010650 +:10272000F1D8FB8AC3F30902154465F30903BCE73A +:10273000013292B21C462368002BF9D16B1F0B4467 +:102740001C21B3FBF1F301339BB29A42D3D2BBF10C +:10275000000FD0D14846FFF7EBFE20B9C4F800B017 +:10276000BFE70122E7E7C0F800B05E4620600446FC +:10277000C1E74545D5D94846FFF7DAFE08B92060DC +:10278000AFE7C0F800B0002620600446B6E70000BE +:102790002DE9F04F2DED028B1C4683B05B69019251 +:1027A00007468846002B00F09A80238C2BB1E26903 +:1027B000002A00F09480072B35D807F10C00FFF7B2 +:1027C000B7FE054638B96FF00205284603B0BDECE8 +:1027D000028BBDE8F08F14220021FEF729FC228C29 +:1027E000E16905F10800FEF711FC208C013080B290 +:1027F000FFF7E6FEFFF7C8FE013880B22084013003 +:1028000028746369228C1B782A4403F01F0363F049 +:102810003F0348F000411372384669602946FFF7CC +:10282000EFFD0125D1E700F10C034FF0000908EEA0 +:10283000103A4FF0800A4E464D4618EE100AFFF748 +:1028400077FE83460028BED014220021FEF7F0FB5D +:10285000002E3AD1019BABF8083002220BF1080E92 +:102860001FFA82FC0CF10100BCF1060F218C80B232 +:1028700001D88E422BD3FFF7A3FEFFF785FE6269D6 +:102880001278013802F01F028E4208BF4FF0400A52 +:1028900042EA49121BFA80F14AEA020A013048F082 +:1028A000004281F808A08BF81000CBF804205946AC +:1028B0003846FFF7A5FD238C0135B3422DB289F0D0 +:1028C00001094FF0000AB8D17FE70022C6E7E169AD +:1028D000895D0EF802100136B6B20132C0E76FF022 +:1028E000010572E7F8B515460E4630220021044670 +:1028F0001F46FEF79DFB069B6360B5F5001F079B17 +:10290000A76034BF6A094FF6FF72A36297B2E6610F +:1029100004F1100000239A4206D800230360A78226 +:10292000E3822383E360F8BD06600133304620363E +:10293000F1E7000003781BB94BB2002BC8BF017050 +:102940007047000000787047F8B50C46C969074623 +:1029500011B9238C002B37D1257E1F2D34D8387820 +:1029600028BB228C072A2CD8268A36F003032BD1C9 +:102970004FF6FF70FFF7D0FD20F001003102400458 +:1029800041EA0561400C41EA40254FF6FF722346BB +:1029900029463846FFF7FCFE002807DD62691378F8 +:1029A0000133DBB21F2B88BF00231370F8BD218ACF +:1029B0002D0645EA012505432046FFF71DFE024688 +:1029C000E5E76FF00300F1E76FF00100EEE70000CC +:1029D00070B58AB0044616460021282268461D4676 +:1029E000FEF726FBBDF83830ADF810300F9B05938D +:1029F0009DF840308DF81830119B07936946BDF85B +:102A00004830ADF820302046CDE90265FFF79CFF45 +:102A10000AB070BD2DE9F041D36905460C46164653 +:102A20000BB9138C5BBB377E1F2F28D895F800801D +:102A3000B8F1000F26D03046FFF7DEFD33782102D3 +:102A400041EAC33141EA0801338A41EA076141EAB8 +:102A500003410246334641F080012846FFF798FEC5 +:102A600000280ADD3378012B07D17269137801330E +:102A7000DBB21F2B88BF00231370BDE8F0816FF01D +:102A80000100FAE76FF00300F7E70000F0B58BB044 +:102A900004460D4617460021282268461E46FEF7CA +:102AA000C7FA9DF84C305A1E534253418DF80030FE +:102AB0009DF84030ADF81030119B05939DF84830DB +:102AC0008DF81830149B07936A46BDF85430ADF862 +:102AD000203029462046CDE90276FFF79BFF0BB058 +:102AE000F0BD0000406A00B104307047436A1A68C4 +:102AF000426202691A600361C38A013BC382704764 +:102B00002DE9F041D0F82080194E14461D4641466B +:102B1000002709B9BDE8F081D1E90223A21A65EBCB +:102B20000303964277EB03031ED2036A8B420DD157 +:102B3000FFF78CFD036A1B68036203690B60C38A9D +:102B40000161016A013BC3828846E2E7FFF77EFD2F +:102B50000B68C8F8003003690B60C38A0161013B50 +:102B6000C382D8F80010D4E788460968D1E700BFCF +:102B700080841E002DE9F04F8BB00D46DDF850909B +:102B800014469B468046002800F01981B9F1000FD9 +:102B900000F01581531E3F2B00F21181012A03D151 +:102BA000BBF1000F40F00B810023CDE90833B8F8EA +:102BB0001430B5EBC30F4FEAC30703D300200BB0AB +:102BC000BDE8F08F2B199F42D8F80C303ABF7F1B1D +:102BD000FFB227461BB9D8F81030002B7AD0272D2A +:102BE0004ED8C5F12806B7424FF000032CBFF6B20D +:102BF0003E4600932946D8F8080008AB3246FFF756 +:102C000041FCA7EB060A35445FFA8AFAB8F814309B +:102C100003F10053053BDB000493D8F80C30039319 +:102C20002821039B13B1BAF1000F2CD1D8F8100062 +:102C300040B1BAF1000F05D0009608AB5246691AB0 +:102C4000FFF720FC38B2002FB8D066070AD00AABD5 +:102C500003EBD401624211F8083C02F00702134171 +:102C600001F8083C082C3CD9102C40F2B580202CEF +:102C700040F2B780BBF1000F00F09C80082334E0E5 +:102C8000BA460026C2E7049BE02B28BFE023069348 +:102C90000B44AB42059314D95A1B039800969245F6 +:102CA00034BF5246D2B2691A08AB04300792FFF71C +:102CB000E9FB079A1644AAEB020A1544F6B25FFA3A +:102CC0008AFA049B069A05999B1A0493039B1B6836 +:102CD0000393A6E70093D8F8080008AB3A462946C4 +:102CE000AEE7BBF1000F13D00123B4EBC30F6CD0E0 +:102CF000082C12D89DF82030621E23FA02F2D50764 +:102D000006D54FF0FF3202FA04F423438DF8203049 +:102D10009DF8203089F8003051E7102C12D8BDF80A +:102D20002030621E23FA02F2D10706D54FF0FF329F +:102D300002FA04F42343ADF82030BDF82030A9F89E +:102D400000303CE7202C0FD80899631E21FA03F3CA +:102D5000DA0705D54FF0FF3202FA04F40C43089469 +:102D6000089BC9F800302AE7402C2BD0DDE9086524 +:102D7000611EC4F12102A4F1210326FA01F105FA32 +:102D800002F225FA03F311431943CB0712D50122AE +:102D9000A4F12003C4F1200102FA03F322FA01F1A5 +:102DA000A240524243EA010363EB430332432B4305 +:102DB000CDE90823DDE90823C9E90023FFE66FF028 +:102DC0000100FCE66FF00800F9E6082CA0D9102CF1 +:102DD000B3D9202CEED8C3E7BBF1000FADD002234E +:102DE00083E7BBF1000FBBD004237EE730B5012A97 +:102DF000144638BF0124402C85B028BF402400254C +:102E0000012ACDE9025518D81B788DF808306307E0 +:102E10000AD004AB03EBD405624215F8083C02F07B +:102E20000702934005F8083C009103462246002122 +:102E300002A8FFF727FB05B030BD082AE4D9102A05 +:102E400003D81B88ADF80830E1E7202A8DBFD3E90D +:102E500000231B680293CDE90223D8E710B5CB68A5 +:102E60001BB98B600B618B8210BD04691A681C60F2 +:102E70000361C38A013BC382CA60F0E703064CBF0B +:102E8000C0F3C0300220704708B50246FFF7F6FFD6 +:102E9000022806D15306C2F30F2001D100F003002F +:102EA00008BDC2F30740FBE72DE9F04F93B0CDE931 +:102EB00003230A6804461046FFF7E0FF022814BF08 +:102EC000C2F306260026002A0D46824680F2F281D1 +:102ED00012F0C04940F0EE81097B002900F0EA8140 +:102EE000022803D02378B34240F0E781C2F30463A1 +:102EF0000693104602F07F030593FFF7C5FF059B7D +:102F000029444FEA834848EA0A4848EA4668CE78A6 +:102F100000230022CDE90823F309834648EA00088C +:102F2000029367D0059B009302466768534608A941 +:102F30002046B847002800F0C381276A4FB94146B0 +:102F400004F10C00FFF702FB074690B96FF0020096 +:102F500054E03B6998450DD03F68002FF9D14146B8 +:102F600004F10C00FFF7F2FA07460028EED0236ABE +:102F70003B60276297F817C006F01F08CCF3840C5B +:102F8000ACEB08001FFA80FE0028B8BF0EF120004D +:102F9000A8EB0C031FFA83FED7E90221B8BF00B2E9 +:102FA000002B0793BEBF0EF120031BB2079352EA1A +:102FB000010338D0039BDFF824E39A1A049B4FF0F7 +:102FC000000C63EB010196457CEB01032BD36B7B7B +:102FD00097F81AE0734519D1029B002B78D001288D +:102FE00021DC7868F8B9DFF8F0C2944570EB010392 +:102FF00016D337E0276A27B96FF00C0013B0BDE88D +:10300000F08F3B699845B5D03F68F4E7B2489042ED +:103010007CEB010301D30020F0E7029B002BFAD0E8 +:10302000079B0F2B17DCFA7DB30002F0030203F0BD +:103030007C031343FB7539462046FFF707FB6B7B88 +:10304000BB76029B3BB9FB7DC3F38402013262F382 +:103050008603FB75D0E76A7BBB7E9A42DBD1029B7D +:10306000002B35D0B309022B32D0039BBB60049BED +:10307000FB60142200210DA8FDF7DAFF039B0A93E1 +:10308000049B0B932B1D0C932B7BADF83EB0013BA7 +:10309000DBB2ADF83C30069B8DF84230059B8DF8D5 +:1030A000433094F82C308DF840A083F001038DF864 +:1030B00044308DF84180A3680AA920469847FB7DDB +:1030C000C3F38403013303F01F039B02FB82A2E7D7 +:1030D000FB7DC6F34012B2EBD31F40F0F480C3F384 +:1030E0008403434540F0F280029A2B7BB609002A04 +:1030F0004DD0F2075DD4032B40F2EB80039BBB6005 +:10310000049BFB602B7BAE1D033BDBB23246394692 +:1031100004F10C00FFF7ACFA00280CDA394620461F +:10312000FFF794FAFB7DC3F38403013303F01F031D +:103130009B02FB820AE7DDE90884AB883B834FF6FC +:10314000FF73C9F12000A9F1200228FA09F104FA5D +:1031500000F0014324FA02F211431846C9B2FFF706 +:10316000C9F909F10809B9F1400F0346E9D1B8825C +:103170002A7B033AD2B23146FFF7CEF9FB7DB88203 +:10318000DA43C2F3C01262F3C713FB7543E786B993 +:103190002E1D013BDBB23246394604F10C00FFF72D +:1031A00067FA0028BADB2A7BB88A013AD2B23146E4 +:1031B000E2E7F98AC1F30901013B0429DAB25BD8DD +:1031C000281D002307F11B069A4208D910F801CBED +:1031D00006F801C0013101330529DBB2F4D10399AE +:1031E0000A9104990B91934207F11B010C9138BF8E +:1031F000043379680D9134BF55FA83F300230E939D +:10320000FB8AADF83EB0C3F309031A44069B8DF860 +:103210004230059B8DF8433094F82C30ADF83C20BB +:1032200083F001038DF8443000238DF840A08DF821 +:1032300041807B602A7BB88A013A291DFFF76CF92F +:103240003B8BB882834203D1A3680AA920469847E2 +:1032500020460AA9FFF702FEFB7DBA8AC3F3840366 +:10326000013303F01F039B02FB823B8B9A420CBF8E +:1032700000206FF01000C1E67B68002BAFD0052066 +:1032800001E01C3033461E68002EFAD1091A081DD1 +:103290002E1D184401EB090CBCF11B0F5FFA89F3DA +:1032A0009DD89A429BD916F8013B00F8013B09F1E1 +:1032B0000109EFE76FF00900A0E66FF00A009DE654 +:1032C0006FF00B009AE66FF00D0097E66FF00E00BE +:1032D00094E66FF00F0091E640420F0080841E00DC +:1032E000EFF3098305494A6B22F001024A63683310 +:1032F00083F30988002383F31188704700EF00E00F +:10330000302080F3118862B60C4B0D4AD96821F445 +:10331000E0610904090C0A43DA60D3F8FC2009498A +:1033200042F08072C3F8FC200A6842F001020A6091 +:103330002022DA7783F82200704700BF00ED00E01A +:103340000003FA05001000E010B5302383F3118864 +:103350000E4B5B6813F4006314D0F1EE103AEFF3F8 +:103360000984683C4FF08073E361094BDB6B236693 +:1033700084F3098800F098F810B1064BA36110BDE2 +:10338000054BFBE783F31188F9E700BF00ED00E090 +:1033900000EF00E0FF0200080203000800F16043B4 +:1033A00003F561430901C9B283F80013012200F05B +:1033B0001F039A4043099B0003F1604303F56143F7 +:1033C000C3F880211A60704700F16040090100F5E0 +:1033D0006D40C9B2017670470023037582680369A6 +:1033E0001B6899689142FBD25A6803604260106082 +:1033F0005860704700230375826803691B689968E9 +:103400009142FBD85A680360426010605860704770 +:1034100008B50846302383F311880B7D032B05D0B4 +:10342000042B0DD02BB983F3118808BD8B690022C2 +:103430001A604FF0FF338361FFF7CEFF0023F2E7FE +:10344000D1E9003213605A60F3E70000FFF7C4BF10 +:10345000054BD9680875186802681A605360012224 +:103460000275D860FCF736BF2838002030B50C4B09 +:10347000DD684B1C87B004460FD02B46094A6846CE +:1034800000F0D8F82046FFF7E3FF009B13B1684631 +:1034900000F0DAF8A86907B030BDFFF7D9FFF9E707 +:1034A0002838002011340008044B1A68DB68906843 +:1034B0009B68984294BF0020012070472838002064 +:1034C000084B10B51C68D86822681A605360012246 +:1034D0002275DC60FFF78EFF01462046BDE81040F4 +:1034E000FCF7F8BE2838002038B5074C07490848D3 +:1034F000012300252370656000F024FB0223237064 +:1035000085F3118838BD00BF503A0020B447000849 +:103510002838002008B572B6044B186500F0C2F9CF +:1035200000F0ACFA024B03221A70FEE728380020A4 +:10353000503A002000F09AB88B60022308618B8219 +:10354000084670478368A3F1840243F8142C02698B +:1035500043F8442C426943F8402C094A43F8242C90 +:10356000C26843F8182C022203F80C2C002203F83E +:103570000B2C044A43F8102CA3F12000704700BF25 +:10358000ED0200082838002008B5FFF7DBFFBDE892 +:103590000840FFF75BBF0000024BDB6898610F201B +:1035A000FFF756BF28380020302383F31188FFF738 +:1035B000F3BF000008B50146302383F311880820CB +:1035C000FFF754FF002383F3118808BD064BDB6827 +:1035D00039B1426818605A60136043600420FFF7F5 +:1035E00045BF4FF0FF3070472838002003689842ED +:1035F00006D01A680260506099611846FFF726BF2E +:103600007047000010B50A4C23699A6891420CD8A3 +:103610005A6881600360426010609A685860511A6D +:1036200099604FF0FF33A36110BD1B68891AECE766 +:103630002838002010B4C0E9032300235DF8044BB0 +:103640004361FFF7DFBF0000036881689A680A449E +:103650009A60426813605A6000230360024B4FF087 +:10366000FF329A61704700BF2838002070B5124DB4 +:10367000EB692A460133EB6152F8103F934206D0C2 +:103680009A68013A9A6030262C69A36803B170BD2C +:10369000D4E900210A605160236083F31188D4E9E2 +:1036A00003312046984786F3118861690029EBD0E1 +:1036B0002046FFF7A7FFE7E728380020054A30B586 +:1036C000D369D2E908451B1B181945F10001C2E96D +:1036D000080130BD2838002000207047FEE70000B8 +:1036E000704700004FF0FF3070470000BFF34F8F6E +:1036F000024AD368DB07FCD4704700BF00200240B9 +:1037000008B5074B1B7853B9FFF7F0FF054B1A6953 +:10371000120641BF044A5A6002F188325A6008BD5D +:10372000683A0020002002402301674508B5054B98 +:103730001B7833B9FFF7DAFF034A136943F08003BC +:10374000136108BD683A0020002002407F289ABF1C +:1037500000F58030C0020020704700004FF4006088 +:1037600070470000802070477F2808B50BD8FFF70E +:10377000EDFF00F500630268013204D1043083429A +:10378000F9D1012008BD0020FCE700007F2810B51A +:1037900004461CD8FFF7AAFFFFF7B2FF0D4BF32238 +:1037A000DA6002221A61FFF7D1FF58611A6942F00C +:1037B00040021A614FF40061FFF798FF00F05AF9D8 +:1037C000FFF7B4FF2046BDE81040FFF7CDBF002053 +:1037D00010BD00BF002002402DE9F84312F00103A4 +:1037E000144606D01F4B40F203321A600020BDE899 +:1037F000F88385181C4A954204D91A4A4FF442713D +:103800001160F3E7FFF77CFFFFF770FFDFF86880D8 +:10381000451A4FF00109012C05EB01060F4603D8AC +:10382000FFF784FF0120E2E73B88C8F8109033805F +:103830000020FFF75BFFC8F81000338831F8022B37 +:103840009BB29A420CD0074B40F21F321A60074BD2 +:103850001E60074B1C60074B1F60FFF767FFC6E742 +:10386000023CD8E7643A002000000408583A0020DF +:10387000603A00205C3A002000200240084908B568 +:103880000B7828B11BB9FFF73BFF01230B7008BD74 +:10389000002BFCD0BDE808400870FFF747BF00BF11 +:1038A000683A002008B506484FF41F4100F0E4F8DC +:1038B000BDE808404FF400514FF0805000F0DCB8F4 +:1038C000000100200846114600F084BE012000F0EF +:1038D00081BE0000084600F09BBE000038B5EFF343 +:1038E0001185BDBBEFF30584C4F308043023C4B1D4 +:1038F00083F31188FFF7E2FE4C014201121A44EAF9 +:10390000D06464EB01049300A4001B1844EA927491 +:1039100041EB0401C900D80041EA537185F31188D5 +:1039200038BD83F31188FFF7C9FE4D014201121A19 +:1039300045EAD06565EB01059300AD001B1845EA2B +:10394000927541EB0501C900D80041EA537184F337 +:10395000118838BDFFF7B2FE4B014401241A43EA37 +:10396000D06363EB0103A2009B00121843EA947337 +:1039700041EB0301C900D00041EA527138BD00BFDC +:1039800038B5FFF7ABFF114C114AC00840EA41704F +:10399000A0FB025EC908A0FB040C1CEB050CA1FBFC +:1039A00004404FF000035B41A1FB02121CEB040C2E +:1039B00043EB000011EB0E0142F10002411842F10D +:1039C0000000090941EA007038BD00BFCFF753E39A +:1039D000A59BC42010B50244064BD2B2904200D140 +:1039E00010BD441C00B253F8200041F8040BE0B2B3 +:1039F000F4E700BF502800400F4B30B51C6A240488 +:103A000007D41C6A44F440741C621C6A44F40044E9 +:103A10001C620A4C236843F4807323600244084B01 +:103A2000D2B2904200D130BD441C00B251F8045BC8 +:103A300043F82050E0B2F4E700100240007000406C +:103A40005028004007B5012201A90020FFF7C2FF5E +:103A5000019803B05DF804FB13B50446FFF7F2FFCD +:103A6000A04205D0012201A900200194FFF7C4FF64 +:103A700002B010BD704700007047000070470000A2 +:103A8000074B45F255521A6002225A6040F6FF7207 +:103A90009A604CF6CC421A60024B01221A707047B1 +:103AA00000300040703A0020034B1B781BB1034BE1 +:103AB0004AF6AA221A607047703A0020003000408F +:103AC000044B1A682AB902F1804202F50432526AA4 +:103AD0001A6070476C3A0020024B4FF080725A62B5 +:103AE000704700BF0010024008B5FFF7E9FF024B26 +:103AF0001868C0F3407008BD6C3A002070470000A1 +:103B0000FEE700000A4B0B480B4A90420BD30B4BCD +:103B1000DA1C121AC11E22F003028B4238BF0022A7 +:103B20000021FDF785BA53F8041B40F8041BECE7AD +:103B30001C490008543C0020543C0020543C002008 +:103B4000FEE7000070B51B4B01630025044686B0FC +:103B5000586085620E46FFF7D3FB04F11003C4E9F9 +:103B600004334FF0FF33A361134BE561D969A560BE +:103B70000A462B46C4E9082304F13401C4E9004491 +:103B80000E4AE562256580232046FFF7D5FC012318 +:103B9000E0600B4A0375009272680192B268CDE949 +:103BA0000223084B6846CDE90435FFF7EDFC06B06B +:103BB00070BD00BF503A002028380020C0470008E0 +:103BC000C5470008413B00084B6843608B68836031 +:103BD000CB68C3600B6943614B6903628B694362C5 +:103BE0000B6803607047000008B51B4B9A6A42F4EB +:103BF000FC029A629A6A22F4FC029A629A6A5A69F0 +:103C000042F4FC025A61154A5B6911464FF090403C +:103C1000FFF7DAFF02F11C0100F58060FFF7D4FF27 +:103C200002F1380100F58060FFF7CEFF02F1540188 +:103C300000F58060FFF7C8FF02F1700100F58060B9 +:103C4000FFF7C2FF02F18C0100F58060FFF7BCFFB7 +:103C5000BDE8084000F05AB800100240CC47000808 +:103C600008B500F093F9FFF73FFCBDE80840FFF707 +:103C700027BF00007047000010B5214CA36A63F411 +:103C8000FC03A362A36A03F4FC03A3624FF0FF32B8 +:103C9000A36A236922612369002323612169E16802 +:103CA000E260E268E360E268E269164942F080524D +:103CB000E261E2690A6842F480720A60226A02F4F0 +:103CC0004072B2F5407F1EBF4FF480322262236201 +:103CD000236A1B0407D4236A43F440732362236AD4 +:103CE00043F40043236200F031F9A369064A43F02C +:103CF0000103A361A369136843F02003136010BD9F +:103D00000010024000700040000001401E4B1A6885 +:103D100042F001021A601A689007FCD55A6822F036 +:103D200003025A605A6812F00C02FBD1196801F0C4 +:103D3000F90119605A601A6842F480321A601A68F0 +:103D40009103FCD5114A5A604FF40452DA623022D2 +:103D50001A631A6842F080721A601A689201FCD5E0 +:103D60000B4912220A600A6802F00702022AFAD1FD +:103D70005A6842F002025A605A6802F00C02082A9D +:103D8000FAD11A6B1A6370470010024000241D001C +:103D900000200240084A08B5516913680B4003F03F +:103DA0000103536123B1054A13680BB1506898476A +:103DB000BDE80840FFF7C8BA00040140743A00208B +:103DC000084A08B5516913680B4003F002035361B8 +:103DD00023B1054A93680BB1D0689847BDE8084005 +:103DE000FFF7B2BA00040140743A0020084A08B54F +:103DF000516913680B4003F00403536123B1054A72 +:103E000013690BB150699847BDE80840FFF79CBAA9 +:103E100000040140743A0020084A08B5516913684B +:103E20000B4003F00803536123B1054A93690BB1BA +:103E3000D0699847BDE80840FFF786BA0004014002 +:103E4000743A0020084A08B5516913680B4003F022 +:103E50001003536123B1054A136A0BB1506A9847A6 +:103E6000BDE80840FFF770BA00040140743A002032 +:103E7000174B10B55A691C68144004F478725A61E3 +:103E8000A30604D5134A936A0BB1D06A984760061B +:103E900004D5104A136B0BB1506B9847210604D51B +:103EA0000C4A936B0BB1D06B9847E20504D5094AD5 +:103EB000136C0BB1506C9847A30504D5054A936C5D +:103EC0000BB1D06C9847BDE81040FFF73DBA00BF7A +:103ED00000040140743A00201A4B10B55A691C685E +:103EE000144004F47C425A61620504D5164A136DED +:103EF0000BB1506D9847230504D5134A936D0BB150 +:103F0000D06D9847E00404D50F4A136E0BB1506E84 +:103F10009847A10404D50C4A936E0BB1D06E984714 +:103F2000620404D5084A136F0BB1506F98472304FD +:103F300004D5054A936F0BB1D06F9847BDE8104088 +:103F4000FFF702BA00040140743A0020062108B5C8 +:103F50000846FFF723FA06210720FFF71FFA06217C +:103F60000820FFF71BFA06210920FFF717FA0621A0 +:103F70000A20FFF713FA06211720FFF70FFABDE812 +:103F8000084006212820FFF709BA000008B5FFF70E +:103F900073FE00F067F800F03DF8FFF76BFEBDE838 +:103FA000084000F05DB800000268436811430160FA +:103FB00003B1184770470000143000F02FBA00001A +:103FC0004FF0FF33143000F029BA0000383000F011 +:103FD000A5BA00004FF0FF33383000F09FBA000060 +:103FE000143000F0F5B900004FF0FF31143000F04C +:103FF000EFB90000383000F04FBA00004FF0FF3248 +:10400000383000F049BA0000012914BF6FF01300E6 +:104010000020704700F06CB8044B03600023C0E937 +:104020000233436001230374704700BF74480008E3 +:1040300038B5C36904460D461BB904210844FFF78F +:10404000B3FF294604F1140000F0A6F9002806DAAF +:10405000201D4FF40061BDE83840FFF7A5BF38BD13 +:1040600000F00EB80023054A19460133102BC2E9AF +:10407000001102F10802F8D1704700BF743A002025 +:104080004FF0E023044A5A6100229A6107221A6124 +:1040900008210B20FFF798B93F19010008B530231C +:1040A00083F31188FFF746FA002383F3118808BDD4 +:1040B00008B5FFF7F3FFBDE80840FFF745B900007A +:1040C000026843681143016003B11847704700005C +:1040D000024A136843F0C003136070470038014080 +:1040E000024A136843F0C003136070470044004065 +:1040F00037B51D4C1D4D2046FFF78EFF009404F18F +:1041000014001B490023202200F038F920220094DB +:1041100004F13800174B184900F0B2F9174BC4E905 +:104120001735174C0C212520FFF738F92046FFF7EB +:1041300073FF04F11400134900940023202200F0BF +:104140001DF904F13800104B10490094202200F0B2 +:1041500097F90F4B0C212620C4E9173503B0BDE8B1 +:104160003040FFF71BB900BFF43A00200051250290 +:10417000CC3B0020D14000080C3C0020003801401E +:10418000603B0020EC3B0020E14000082C3C00207C +:10419000004400402DE9F047C66D3768F469346289 +:1041A0002107054619D014F0080118BF4FF480719B +:1041B000E20748BF41F02001A30748BF41F040019A +:1041C000600748BF41F08001302383F31188281D28 +:1041D000FFF776FF002383F31188E2050AD5302329 +:1041E00083F311884FF48061281DFFF769FF0023D6 +:1041F00083F311884FF030094FF0000A14F02008C3 +:1042000038D13B0616D54FF0300905F1380A2006A3 +:1042100010D589F31188504600F066F9002836DA87 +:104220000821281DFFF74CFF27F08003336000238F +:1042300083F31188790614D5620612D5302383F3EF +:104240001188D5E913239A4208D12B6C33B1102180 +:10425000281D27F04007FFF733FF3760002383F363 +:104260001188E30619D5AA6E1369B3B1BDE8F0470A +:104270005069184789F31188B38C95F86410284663 +:104280001940FFF7D5FE8AF31188F469B6E780B2CA +:10429000308588F31188F469B9E7BDE8F08700003C +:1042A00008B50348FFF776FFBDE80840FFF74CB8B4 +:1042B000F43A002008B50348FFF76CFFBDE808405A +:1042C000FFF742B8603B0020F8B5154682680669E2 +:1042D000AA420B46816938BF8568761AB542044602 +:1042E0000BD218462A46FCF791FEA3692B44A36122 +:1042F000A3685B1BA3602846F8BD0CD9184632465C +:10430000FCF784FEAF1BE1683A463044FCF77EFEC2 +:10431000E3683B44EBE718462A46FCF777FEE36880 +:10432000E5E7000083689342F7B51546044638BFB9 +:104330008568D0E90460361AB5420BD22A46FCF7EC +:1043400065FE63692B446361A36828465B1BA36019 +:1043500003B0F0BD0DD932460191FCF757FE01992B +:10436000E068AF1B3A463144FCF750FEE3683B443B +:10437000E9E72A46FCF74AFEE368E4E710B50A4499 +:104380000024C361029B8460C0E90000C0E90511FC +:10439000C1600261036210BD08B5D0E905329342E5 +:1043A00001D1826882B98268013282605A1C4261FE +:1043B0001970D0E904329A4224BFC36843610021D6 +:1043C000FFF714F9002008BD4FF0FF30FBE70000B5 +:1043D00070B5302304460E4683F31188A568A5B155 +:1043E000A368A269013BA360531CA36115782269ED +:1043F000934224BFE368A361E3690BB12046984769 +:10440000002383F31188284607E031462046FFF752 +:10441000DDF80028E2DA85F3118870BD2DE9F74F49 +:1044200004460E4617469846D0F81C904FF0300AC6 +:104430008AF311884FF0000B154665B12A463146C4 +:104440002046FFF741FF034660B941462046FFF78B +:10445000BDF80028F1D0002383F31188781B03B046 +:10446000BDE8F08FB9F1000F03D001902046C84796 +:10447000019B8BF31188ED1A1E448AF31188DCE747 +:10448000C0E90511C160C3611144009B8260C0E9AD +:104490000000016103627047F8B504460D461646F8 +:1044A000302383F31188A768A7B1A368013BA360F9 +:1044B00063695A1C62611D70D4E904329A4224BFB8 +:1044C000E3686361E3690BB120469847002080F3FD +:1044D000118807E031462046FFF778F80028E2DA35 +:1044E00087F31188F8BD0000D0E905239A4210B582 +:1044F00001D182687AB98268013282605A1C826175 +:104500001C7803699A4224BFC36883610021FFF7C6 +:104510006DF8204610BD4FF0FF30FBE72DE9F74F57 +:1045200004460E4617469846D0F81C904FF0300AC5 +:104530008AF311884FF0000B154665B12A463146C3 +:104540002046FFF7EFFE034660B941462046FFF7DD +:104550003DF80028F1D0002383F31188781B03B0C5 +:10456000BDE8F08FB9F1000F03D001902046C84795 +:10457000019B8BF31188ED1A1E448AF31188DCE746 +:104580000B460146184600F02DB8000000F040B878 +:10459000012838BF012010B50446204600F030F84D +:1045A00030B900F007F808B900F00CF88047F4E7DC +:1045B00010BD0000024B1868BFF35B8F704700BF4F +:1045C0004C3C002008B5062000F084F80120FFF7DD +:1045D00085F80000024B0A4601461868FFF772B9D9 +:1045E0001811002010B5054C13462CB10A4601469F +:1045F0000220AFF3008010BD2046FCE70000000061 +:10460000024B01461868FFF761B900BF181100207E +:10461000024B01461868FFF75DB900BF1811002072 +:1046200010B501390244904201D1002005E0037821 +:1046300011F8014FA34201D0181B10BD0130F2E761 +:104640002DE9F041A3B1C91A17780144044603F1DA +:10465000FF3C8C42204601D9002009E00578BD428C +:1046600004F10104F5D10CEB0405D618A54201D1E3 +:10467000BDE8F08115F8018D16F801EDF045F5D093 +:10468000E7E700001F2938B504460D4604D9162374 +:1046900003604FF0FF3038BD426C12B152F8213048 +:1046A0004BB9204600F030F82A4601462046BDE8C6 +:1046B000384000F017B8012B0AD0591C03D116233B +:1046C00003600120E7E7002442F825402846984788 +:1046D0000020E0E7024B01461868FFF7D3BF00BF98 +:1046E0001811002038B5074D00230446084611462E +:1046F0002B60FEF7F7FF431C02D12B6803B1236048 +:1047000038BD00BF503C0020FEF7E6BF034611F85D +:10471000012B03F8012B002AF9D170476F72672E25 +:104720006172647570696C6F742E663330332D4717 +:104730005053000040A2E4F1646891060041A3E5F3 +:10474000F2656992070000004261642043414E49CE +:104750006661636520696E6465782E0080000000E4 +:104760000080000000008000000000000000000049 +:104770001918000835200008911F00085918000872 +:1047800065180008651A000829180008391800087B +:104790002D1800083518000831180008891900087C +:1047A0003D180008052300084D1800085D19000891 +:1047B00063300000B047000880380020503A0020E5 +:1047C0006D61696E0069646C65000000A001A82A33 +:1047D00000000000FAAABEAA50001424EFFF000057 +:1047E0000077000070970900010000000000000041 +:1047F000AAAAAAAA01000000FFFF00000000000012 +:10480000000000000000000000000000AAAAAAAA00 +:1048100000000000FFFF000000000000000000009A +:104820000000000000000000AAAAAAAA00000000E0 +:10483000FFFF00000000000000000000000000007A +:1048400000000000AAAAAAAA00000000FFFF0000C2 +:104850000000000000000000000000000000000058 +:10486000AAAAAAAA00000000FFFF000000000000A2 +:104870000000000000000000D53F0008C13F000814 +:10488000FD3F0008E93F0008F53F0008E13F000850 +:10489000CD3F0008B93F00080940000800000000B3 +:1048A000EC0300000000000000980300000000007E +:1048B000FE2A0100D20400001C11002000000000AC +:1048C00000000000000000000000000000000000E8 +:1048D00000000000000000000000000000000000D8 +:1048E00000000000000000000000000000000000C8 +:1048F00000000000000000000000000000000000B8 +:1049000000000000000000000000000000000000A7 +:0C4910000000000000000000000000009B :00000001FF diff --git a/Tools/bootloaders/f303-HWESC_bl.bin b/Tools/bootloaders/f303-HWESC_bl.bin index 39b8393e352121..9419312c08c2df 100755 Binary files a/Tools/bootloaders/f303-HWESC_bl.bin and b/Tools/bootloaders/f303-HWESC_bl.bin differ diff --git a/Tools/bootloaders/f303-HWESC_bl.hex b/Tools/bootloaders/f303-HWESC_bl.hex index e35db883a3e8dc..3d882502410125 100644 --- a/Tools/bootloaders/f303-HWESC_bl.hex +++ b/Tools/bootloaders/f303-HWESC_bl.hex @@ -1,1217 +1,1172 @@ :020000040800F2 -:1000000000090020B5040008CD250008852500085A -:10001000AD25000885250008A5250008B7040008BF -:10002000B7040008B7040008B7040008C135000889 -:10003000B7040008B7040008B704000875430008B7 -:10004000B7040008B7040008B7040008B7040008A4 -:10005000B7040008B70400085940000885400008AC -:10006000B1400008DD40000809410008B70400085D -:10007000B7040008B7040008B7040008B704000874 -:10008000B7040008B7040008B704000839250008C1 -:100090006525000875250008B704000835410008EB -:1000A000B7040008B7040008B7040008B704000844 -:1000B000B7040008B7040008B7040008B704000834 -:1000C000B7040008B7040008B7040008B704000824 -:1000D000B70400086545000879450008B704000822 -:1000E0009D410008B7040008B7040008B7040008E1 -:1000F000B7040008B7040008B7040008B7040008F4 -:10010000B7040008B7040008B7040008B7040008E3 -:10011000B7040008B7040008B7040008B7040008D3 -:10012000B7040008B7040008B7040008B7040008C3 -:10013000B7040008B7040008B7040008B7040008B3 -:10014000B7040008B7040008B7040008B7040008A3 -:10015000B7040008B7040008B7040008B704000893 -:10016000B7040008B7040008B7040008B704000883 -:10017000B7040008B7040008B7040008B704000873 -:10018000B7040008B7040008B7040008B704000863 -:10019000B7040008B7040008B7040008B704000853 -:1001A0002112000800000000000000000000000014 -:1001B00053B94AB9002908BF00281CBF4FF0FF31CE -:1001C0004FF0FF3000F074B9ADF1080C6DE904CECA -:1001D00000F006F8DDF804E0DDE9022304B0704722 -:1001E0002DE9F047089D04468E46002B4DD18A42EA -:1001F000944669D9B2FA82F252B101FA02F3C2F11D -:10020000200120FA01F10CFA02FC41EA030E9440AD -:100210004FEA1C48210CBEFBF8F61FFA8CF708FBCE -:1002200016E341EA034306FB07F199420AD91CEBA6 -:10023000030306F1FF3080F01F81994240F21C81D8 -:10024000023E63445B1AA4B2B3FBF8F008FB103320 -:1002500044EA034400FB07F7A7420AD91CEB040455 -:1002600000F1FF3380F00A81A74240F20781644425 -:10027000023840EA0640E41B00261DB1D4400023AA -:10028000C5E900433146BDE8F0878B4209D9002D0E -:1002900000F0EF800026C5E9000130463146BDE898 -:1002A000F087B3FA83F6002E4AD18B4202D3824202 -:1002B00000F2F980841A61EB030301209E46002DB1 -:1002C000E0D0C5E9004EDDE702B9FFDEB2FA82F206 -:1002D000002A40F09280A1EB0C014FEA1C471FFA64 -:1002E0008CFE0126200CB1FBF7F307FB131140EA4B -:1002F00001410EFB03F0884208D91CEB010103F118 -:10030000FF3802D2884200F2CB804346091AA4B2D9 -:10031000B1FBF7F007FB101144EA01440EFB00FEAD -:10032000A64508D91CEB040400F1FF3102D2A64512 -:1003300000F2BB800846A4EB0E0440EA03409CE7B1 -:10034000C6F12007B34022FA07FC4CEA030C20FA5E -:1003500007F401FA06F31C43F9404FEA1C4900FA7E -:1003600006F3B1FBF9F8200C1FFA8CFE09FB1811FB -:1003700040EA014108FB0EF0884202FA06F20BD96E -:100380001CEB010108F1FF3A80F08880884240F2BE -:100390008580A8F102086144091AA4B2B1FBF9F002 -:1003A00009FB101144EA014100FB0EFE8E4508D9FD -:1003B0001CEB010100F1FF346CD28E456AD9023882 -:1003C000614440EA0840A0FB0294A1EB0E01A14267 -:1003D000C846A64656D353D05DB1B3EB080261EBD5 -:1003E0000E0101FA07F722FA06F3F1401F43C5E9AF -:1003F000007100263146BDE8F087C2F12003D840E5 -:100400000CFA02FC21FA03F3914001434FEA1C4726 -:100410001FFA8CFEB3FBF7F007FB10360B0C43EA18 -:10042000064300FB0EF69E4204FA02F408D91CEBC8 -:10043000030300F1FF382FD29E422DD902386344C6 -:100440009B1B89B2B3FBF7F607FB163341EA034166 -:1004500006FB0EF38B4208D91CEB010106F1FF38B5 -:1004600016D28B4214D9023E6144C91A46EA0046AC -:1004700038E72E46284605E70646E3E61846F8E63E -:100480004B45A9D2B9EB020864EB0C0E0138A3E787 -:100490004646EAE7204694E74046D1E7D0467BE768 -:1004A000023B614432E7304609E76444023842E7E0 -:1004B000704700BF02E000F000F8FEE772B6374870 -:1004C00080F30888364880F3098836483649086042 -:1004D00040F20000CCF200004EF63471CEF2000182 -:1004E0000860BFF34F8FBFF36F8F40F20000C0F280 -:1004F000F0004EF68851CEF200010860BFF34F8F36 -:10050000BFF36F8F4FF00000E1EE100A4EF63C7122 -:10051000CEF200010860062080F31488BFF36F8FCD -:1005200003F04EFC03F0C2FC4FF055301F491B4A4C -:1005300091423CBF41F8040BFAE71D49184A914229 -:100540003CBF41F8040BFAE71A491B4A1B4B9A427D -:100550003EBF51F8040B42F8040BF8E7002018499D -:10056000184A91423CBF41F8040BFAE703F02CFC17 -:1005700003F0D8FC144C154DAC4203DA54F8041BBC -:100580008847F9E700F042F8114C124DAC4203DA0B -:1005900054F8041B8847F9E703F014BC0009002055 -:1005A000001100200000000808ED00E0000100201C -:1005B00000090020704B0008001100207C11002071 -:1005C00080110020583C0020A0010008A401000870 -:1005D000A4010008A40100082DE9F04F2DED108AB8 -:1005E000C1F80CD0C3689D46BDEC108ABDE8F08F01 -:1005F000002383F311882846A047002003F06AF9FE -:10060000FEE703F0CDF800DFFEE70000F8B500F0EC -:1006100019FE03F079FB074603F0C8FB05460028E6 -:1006200040D12C4B9F423DD001339F423DD02A4BBD -:1006300027F0FF029A423BD1F8B200F03FFC2E4671 -:1006400042F2107400F040FC08B10024264601F08C -:10065000B1F888B3032000F045F80024264635B1F0 -:100660001E4B9F4203D003F099FB00242646002036 -:1006700003F054FB1A4B1B6913F0400322D00EB158 -:1006800000F046F800F052FC00F0DEFD01F0A6FF9D -:100690000546CCB101F0A2FF401BA04214D900F0E6 -:1006A00037F8F3E72E460024CCE704460126C9E7D5 -:1006B00006464FF47A74C5E7002CD0D04FF47A7414 -:1006C0000126CCE71C46DDE700F078FC012003F0B2 -:1006D00007F9DEE7010007B0000008B0263A09B0CC -:1006E00000040048084B187003280CD8DFE800F01D -:1006F00008050208022000F003BE022000F0F8BD49 -:10070000024B00225A6070478011002084110020A3 -:1007100038B501F04FF830B11F4B03221A701F4B50 -:1007200000225A6038BD1E4B1E4A19680131F9D0AB -:1007300004339342F9D11C4C194DD4F80428AA4231 -:10074000F0D31A4B9B6803F1006303F5D0439A4240 -:10075000E8D203F0F7FA03F009FB002000F08EFD69 -:100760000220FFF7BFFF124BDA690022DA61D96974 -:1007700099699A619B6972B64FF0E0233021C3F802 -:10078000085DD4F80038D4F8042881F311889D4618 -:1007900083F308881047C5E78011002084110020EA -:1007A00000680008206800080060000800110020B0 -:1007B00000100240094A136849F2690099B21B0C03 -:1007C00000FB01331360064B186844F2506182B29B -:1007D000000C01FB0200186080B270471411002069 -:1007E0001011002010B500211022044600F0A2FDD7 -:1007F000034B03CB206061601868A06010BD00BF90 -:10080000ACF7FF1F2DE9F041ADF54E7D0DF1340839 -:100810006CAC40F2751207460D460EA80021C8F8D0 -:10082000001000F087FD4FF4C4720021204600F054 -:1008300081FD01F0D3FE254B4FF47A72B0FBF2F04C -:10084000186093E80700022384E807000DF5E970BB -:100850002382FFF7C7FF4EF603431D49238406A8F2 -:1008600004F0B6F8182384F832310DF2E3266B4415 -:100870000DF1300C1A4603CA6245306071601346B0 -:1008800006F10806F6D141460122204600F09EFD01 -:1008900000230393AB7E029305F11903019380B209 -:1008A0000123CDE904800093E97E06A3D3E9002368 -:1008B000384602F05BFA0DF54E7DBDE8F08100BFD1 -:1008C000AFF300809E6AC421818A46EE8C1100201D -:1008D000E04900082DE9F0412C4C237ADAB080463B -:1008E0000D465BBB27A9284600F080FE074600287E -:1008F00042D19DF89D60C82E3ED801464FF4A662B5 -:10090000204600F017FD4FF48073C4F8F8314FF41F -:100910000073C4F80C334FF44073C4F820343246EB -:100920000DF19E0104F1090000F0F2FC26449DF84F -:100930009C30777223720BB9EB7E237281220021E7 -:1009400006AC27A800F0F6FC0122214627A800F0FB -:1009500089FE00230393AB7E029305F1190380B255 -:1009600001932823CDE904400093E97E05A3D3E950 -:100970000023404602F0FAF95AB0BDE8F08100BF0A -:10098000AFF3008026417272DF25D7B7A83200206E -:10099000F0B5254E4FF48A7505FB0065F1B096F869 -:1009A000D83085F8DC300024D822214685F8E8408C -:1009B0003AA800F0BFFC06F1090000F0B3FCD5F83E -:1009C000E4308DF8F000C2B206AF06F109010DF176 -:1009D000F100CDE93A3400F09BFC394601223AA8F7 -:1009E00000F06CFE80B2CDE9047008230127CDE948 -:1009F000023706F1D803019330230093317A0B4874 -:100A000007A3D3E9002302F0B1F9A04206DD01F00B -:100A1000E5FDC5F8E000384671B0F0BD2046FBE7C3 -:100A200078F6339F93CACD8DA8320020A4210020F0 -:100A30002DE9F0411D4D1E4E1E4F86B0284602F096 -:100A4000C1F9034658B30024CDE90344ADF814407E -:100A5000027B8DF8142099684068029403AA03C2AF -:100A60001B68DFF8548043F00043029301F0B8FDA7 -:100A7000821941F10003009402A9384601F07CF884 -:100A8000A04205DD284602F0A1F988F80040D5E72C -:100A900098F80030072B05D8013388F8003006B0ED -:100AA000BDE8F081014802F091F9F8E7A4210020A7 -:100AB00040420F00D8210020DD37002070B50D46E0 -:100AC00014461E4602F0AEF850B9022E10D1012C89 -:100AD0000ED112A3D3E90023C5E90023012007E0CA -:100AE000282C10D005D8012C09D0052C0FD00020BF -:100AF00070BD302CFBD10BA3D3E90023ECE70BA393 -:100B0000D3E90023E8E70BA3D3E90023E4E70BA331 -:100B1000D3E90023E0E700BFAFF30080401DA12030 -:100B200026812A0B78F6339F93CACD8D9E6AC42105 -:100B3000818A46EE26417272DF25D7B7F017304A18 -:100B400039059E5638B505460E4C0021013500F09A -:100B5000B7FBA4F82C55B4F82C0500F099FB78B13C -:100B6000B4F82C0500F0A4FB014648B9B4F82C05F4 -:100B700000F0A6FBB4F82C350133A4F82C35EAE7D5 -:100B800038BD00BFA832002010B50A4B0A4A1A60CF -:100B900003F5805393F860203AB9DC6D2CB1204600 -:100BA00000F082FE204603F053FEBDE810400348EB -:100BB00000F07ABED8210020384A000820320020F8 -:100BC0002DE9F04F8FB000AF05460C4602F02AF831 -:100BD000002849D1237E022B1BD1E38A012B18D197 -:100BE00001F0FCFC0646FFF7E5FD03464FF4C87034 -:100BF000DFF8C482B3FBF0F206F5167602FB103381 -:100C000016FA83F3C8F80030E37E33B9A34B002211 -:100C10001A703C37BD46BDE8F08F07F1240120462D -:100C200000F0A2FC0028F4D107F11400FFF7DAFD70 -:100C300097F8264007F11401224607F1270003F038 -:100C400051FE0028E2D10F2C08D8944B1C70D8F824 -:100C50000030A3F51673C8F80030DAE797F82410CF -:100C6000284601F0D7FFD4E7E38A282B2BD010D8F1 -:100C7000012B23D0052BCCD1BFF34F8F8849894B53 -:100C8000CA6802F4E0621343CB60BFF34F8F00BF2A -:100C9000FDE7302BBDD1844EE17E327A9142B8D14E -:100CA000607E3146002291F8DC50854200F0A5803C -:100CB0000132042A01F58A71F5D1AAE721462846B6 -:100CC000FFF7A0FDA5E721462846FFF703FEA0E7B2 -:100CD000B2F8EC507B6005F103094FEA99094FEA3D -:100CE0008902D11DC908A8EBC1039D46EB4600212E -:100CF000584600F01FFB04F1EE012A4631445846E5 -:100D000000F006FB7B6813B9012000F0B7FA96F8F3 -:100D1000D20000F0BDFA044630B9307200F0D8FAC3 -:100D2000204600F0ABFAB1E0D6F8D4203AB996F8F4 -:100D3000D200B6F82C25824201D8FFF703FFD6F87F -:100D4000D4202A44944208D296F8D200B6F82C2532 -:100D50000130824201D8FFF7F5FE70685FFA89F230 -:100D6000594600F0EFFA08B9C54679E0726896F87E -:100D7000D2002A447260D6F8D42005EB0209C6F8E6 -:100D8000D49000F085FA814509D396F8D220D6F8A0 -:100D9000D4000132001B86F8D220C6F8D400FF2D03 -:100DA0000FD80024347200F093FA204600F066FA5F -:100DB00000F000FD3D4B188108B9FFF7A9FCC546BE -:100DC00027E7BB6896F8D9000AFB0362FB68D2F8F4 -:100DD000E41082F8E83001F58061C2F8E030C2F832 -:100DE000E410FFF7D5FDFFF723FE96F8D920013276 -:100DF00002F0030286F8D920B6E74FF48A7A0AFB9C -:100E000002F505F1EA013144204600F083FCF86068 -:100E100000287FF4FEAE3544012285F8E82001F079 -:100E2000DDFBD5F8E020D6ED007ADFED216A801AEF -:100E3000192838BF192040F6B832904228BF104612 -:100E4000B8EE677A07EE900AF8EEE77A67EEA67AD0 -:100E5000DFED186AE7EE267AFCEEE77AC6ED007A57 -:100E600096F8D930BB60BA6873680AFB02F432198D -:100E700092F8E81059B1D2F8E4108B42E8463FF4FA -:100E800027AF002182F8E810C2F8E010C546736869 -:100E9000064A9B0A01331381BBE600BF9D21002057 -:100EA00000ED00E00400FA05A83200208C110020BB -:100EB000CDCCCC3D6666663FA0210020014B18706A -:100EC000704700BF9811002038B54FF00054134B05 -:100ED00022689A4220D1124B627D12481A70237DFB -:100EE00003724FF48073C0F8F8314FF40073C0F808 -:100EF0000C3300254FF44073C0F820340A49C0F881 -:100F0000E450C922093000F003FAE02229462046C5 -:100F100000F010FA012038BD0020FCE79AAD44C56E -:100F200098110020A83200201600002037B500F0EC -:100F300041FC194D194928810223012218486B717F -:100F400001F0EAF900230193164B17490093174863 -:100F5000174B4FF4805201F035FE164B197811B142 -:100F6000124801F057FE01F039FB0446FFF722FC5E -:100F70004FF4C873B0FBF3F202FB130304F51670D1 -:100F800010FA83F00C4B186002F010FF08B10F2329 -:100F90002B8103B030BD00BF8C11002040420F00F8 -:100FA000D8210020BD0A00089C110020A4210020A7 -:100FB000C10B000898110020A02100202DE9F04F5E -:100FC0002DED028B8EA7D7E900670FF23C29D9E9F6 -:100FD0000089864C95B00DAD9FED828BFFF728FD03 -:100FE000DFF82CB200230C93ADF83C300D936B600E -:100FF00000230DF125028DED008B4FF0010A09A9A8 -:1010000058468DF825308DF824A001F035F99DF86B -:1010100024200023002A40F0AB80204601F002FE8D -:101020000546002847D1DFF8ECB101F0D7FADBF82C -:10103000003098423FD301F0D1FA0790FFF7BAFB96 -:10104000079A4FF4C873B0FBF3F101FB130302F5E9 -:10105000167010FA83F0CBF80000DFF8BCB19BF8F3 -:1010600000100791002914BF2B46534610A88DF895 -:101070003030FFF7B7FB0799C1F11002D2B2062A50 -:1010800010AB28BF062219440DF13100079200F081 -:101090003FF9079A0CAB0393182302930132544B88 -:1010A000D2B2CDE900A304923B463246204601F07D -:1010B000FFFD8BF8005001F091FA4E4A4E4D136837 -:1010C000C31AB3F57A7F32D3106001F089FA024671 -:1010D0000B46204601F084FE204601F0A3FD30B30C -:1010E0002B7ADFF838A1002B14BF032302238AF8E0 -:1010F000053001F073FA0DF1400B4FF47A730122C1 -:10110000B0FBF3F05946CAF80000504600F004FA6C -:1011100018230293394B019380B240F25513CDE965 -:1011200003B0009342464B46204601F0C1FD2B7AA6 -:10113000CBB101F053FA4FF0000A83464FF48A72A4 -:1011400095F8D900504400F0030002FB005393F8D7 -:10115000E81089B30AF1010ABAF1040FF0D12B7A31 -:10116000002B7FF438AF15B0BDEC028BBDE8F08FDB -:101170004FF0904110A84A6982F010024A61194666 -:10118000102200F0D7F80DF126030AAA0CA9584640 -:1011900000F0F0FD95E8030011AB83E803009DF833 -:1011A0003C308DF84C300C9B109310A9DDE90A23DC -:1011B000204601F0E9FF1BE7D3F8E01049B12B68A6 -:1011C000FA2B38BFFA23ABEB01010533B1EB430F28 -:1011D000C0D3FFF7DDFB4FF48A720028BAD1BEE717 -:1011E000AFF300800000000000000000A4210020F8 -:1011F0009C210020D8370020A8320020DC370020B6 -:10120000401DA12026812A0BF1C6A7C1D068080F76 -:10121000D8210020A02100209D2100208C11002039 -:1012200008B5054800F040FEBDE80840034A0449FF -:10123000002003F007BB00BFD82100201838002091 -:10124000890B00087047000070B502F013FC094ECE -:10125000094D3080002428683388834208D902F081 -:1012600005FC2B6804440133B4F5D04F2B60F2D356 -:1012700070BD00BF0C380020E037002002F086BCB3 -:1012800000F10060920000F5D04002F02DBC00009B -:10129000054B1A68054B1B889B1A834202D91044E0 -:1012A00002F0E4BB00207047E03700200C3800203B -:1012B000024B1B68184402F0DFBB00BFE037002080 -:1012C000024B1B68184402F0E9BB00BFE037002066 -:1012D000064991F8243033B10023086A81F824309C -:1012E0000822FFF7CDBF0120704700BFE437002080 -:1012F000022802BF4FF0904310229A61704700000D -:10130000022802BF4FF090434FF480129A61704759 -:1013100010B50023934203D0CC5CC4540133F9E7E9 -:1013200010BD000003460246D01A12F9011B002925 -:10133000FAD1704702440346934202D003F8011BDE -:10134000FAE770472DE9F8431F4D144695F824201D -:101350000746884652BBDFF870909CB395F824305E -:101360002BB92022FF2148462F62FFF7E3FF95F8B3 -:101370002400C0F10802A24228BF2246D6B241464C -:10138000920005EB8000FFF7C3FF95F82430A41B03 -:101390001E44F6B2082E17449044E4B285F8246047 -:1013A000DBD1FFF795FF0028D7D108E02B6A03EBCC -:1013B00082038342CFD0FFF78BFF0028CBD10020E0 -:1013C000BDE8F8830120FBE7E43700202DE9F04772 -:1013D0000D46044600219046284640F27912FFF758 -:1013E000A9FF234620220021284601F06FFE231D7D -:1013F00002222021284601F069FE631D03222221DA -:10140000284601F063FEA31D03222521284601F092 -:101410005DFE04F1080310222821284601F056FE43 -:1014200004F1100308223821284601F04FFE04F190 -:10143000110308224021284601F048FE04F112035E -:1014400008224821284601F041FE04F1140320221D -:101450005021284601F03AFE04F118034022702181 -:10146000284601F033FE04F120030822B02128466B -:1014700001F02CFE04F121030822B821284601F0D6 -:1014800025FE04F12207C0263B46314608222846A5 -:10149000083601F01BFEB6F5A07F07F10107F3D176 -:1014A00004F1320308223146284601F00FFE0027DE -:1014B00004F1330A94F832304FEAC7099F4209F524 -:1014C000A47615D3B8F1000F08D1314604F599730D -:1014D0000722284601F0FAFD09F24F16274694F834 -:1014E00032213B1B93420CD3F01DC008BDE8F087AE -:1014F0000AEB070308223146284601F0E7FD0137D1 -:10150000D8E707F2331331460822284601F0DEFD02 -:1015100008360137E3E7000013B50446084600210A -:1015200001602346C0F803102022019001F0CEFD97 -:101530000198231D0222202101F0C8FD0198631D9E -:101540000322222101F0C2FD0198A31D03222521BF -:1015500001F0BCFD019804F108031022282101F0DC -:10156000B5FD072002B010BDF7B50023047F009140 -:101570000E4607221946054601F06CFC731C0093C9 -:10158000012200230721284601F064FCC4B9B31CE2 -:101590000093052223460821284601F05BFC0D2418 -:1015A0003746B278BB1B934211D32B7FA88A0734EE -:1015B000E408BBB9844294BF0020012003B0F0BD11 -:1015C000AB8ADB00083BDB08B3700824E8E7FB1CB0 -:1015D0000093214600230822284601F03BFC0834F2 -:1015E0000137DEE7201A18BF0120E7E7F7B500232F -:1015F000047F00910E4608221946054601F02AFC98 -:10160000731CC4B90822009311462346284601F0F2 -:1016100021FC1024012372785F1C013B934211D3FB -:101620002B7FA88A0734E408BBB9844294BF00200A -:10163000012003B0F0BDAB8ADB00083BDB08737010 -:101640000824E7E7F31900932146002308222846DF -:1016500001F000FC08343B46DDE7201A18BF0120EA -:10166000E7E70000F8B50E46054614460021812242 -:101670003046FFF75FFE2B4608220021304601F07E -:1016800025FD7CB96B1C07220821304601F01EFDA8 -:101690000F2401236A785F1C013B934204D3E01DB1 -:1016A000C008F8BD0824F4E7EB19214608223046AB -:1016B00001F00CFD08343B46ECE70000F8B50E469F -:1016C000054614460021CE223046FFF733FE2B4656 -:1016D00028220021304601F0F9FC7CB905F108030D -:1016E00008222821304601F0F1FC30242F462A7AC6 -:1016F0007B1B934204D3E01DC008F8BD2824F5E706 -:1017000007F1090321460822304601F0DFFC0834C6 -:101710000137ECE7F7B5047F00910E460123102254 -:101720000021054601F096FBC4B9B31C00930922C1 -:1017300023461021284601F08DFB19243746728874 -:10174000BB1B9A4211D82B7FA88A0734E408BBB987 -:10175000844294BF0020012003B0F0BDAB8ADB00BF -:10176000103BDB0873801024E8E73B1D0093214603 -:1017700000230822284601F06DFB08340137DEE71C -:10178000201A18BF0120E7E730B5094D0A449142FD -:101790000DD011F8013B5840082340F30004013BF1 -:1017A0002C4013F0FF0384EA5000F6D1EFE730BD80 -:1017B0002083B8EDF7B5364A106851686B4603C30D -:1017C0006A4634493448082303F09CF8044690BB29 -:1017D0000A25324A106851686B4603C36A4630498D -:1017E0002D48082303F08EF80446002847D00369EB -:1017F000B3F5663F43D8B0F86620B2F57B7F3ED1A3 -:10180000284A024402F15C018B4238D35C3B2249F6 -:1018100000209E1AFFF7B8FF3246074604F1640124 -:101820000020FFF7B1FFA3689F4228D1E3689842E8 -:1018300008BF002523E00369B3F5663F26D8428B35 -:10184000B2F57B7F20D1174A024402F110018B428E -:1018500018D3103B104900209D1AFFF795FF2A4628 -:10186000064604F118010020FFF78EFFA3689E4290 -:1018700002D1E368984201D00D25AAE70025284649 -:1018800003B0F0BD1025A4E70C25A2E70B25A0E7C7 -:10189000FC490008DC97030000680008054A0008BE -:1018A000909703000898FFF710B5037C044613B91E -:1018B000006803F00FF8204610BD00000023BFF3BE -:1018C0005B8FC360BFF35B8FBFF35B8F8360BFF33E -:1018D0005B8F7047BFF35B8F0068BFF35B8F704710 -:1018E00070B505460C30FFF7F5FF05F10806044614 -:1018F0003046FFF7EFFFA04206D930466D68FFF78C -:10190000E9FF2544281A70BD3046FFF7E3FF201A8F -:10191000F9E7000070B50546406898B105F1080088 -:10192000FFF7D8FF05F10C0604463046FFF7D2FF5B -:101930008442304694BF6D680025FFF7CBFF013C21 -:101940002C44201A70BD000038B50C460546FFF740 -:10195000C7FFA04210D305F10800FFF7BBFF044406 -:101960006868B4FBF0F100FB1144BFF35B8F01200A -:10197000AC60BFF35B8F38BD0020FCE72DE9F04180 -:10198000144607460D46FFF7C5FF844228BF0446AC -:10199000D4B1B84658F80C6B4046FFF79BFF304473 -:1019A000286040467E68FFF795FF331A9C4203D8B3 -:1019B0006C600120BDE8F0816B60A41B3B68AB60EC -:1019C0002044E8600220F5E72046F3E738B50C46EE -:1019D0000546FFF79FFFA04210D305F10C00FFF76B -:1019E00079FF04446868B4FBF0F100FB1144BFF3D5 -:1019F0005B8F0120EC60BFF35B8F38BD0020FCE7FC -:101A00002DE9FF41884669460746FFF7B7FF6C4658 -:101A100006B204EBC6060025B44209D0626820680D -:101A200008EB0501FFF774FC636808341D44F3E715 -:101A300029463846FFF7CAFF284604B0BDE8F081C2 -:101A4000F8B505460C300F46FFF744FF05F10806D0 -:101A500004463046FFF73EFFA042304688BF6C6820 -:101A6000FFF738FF201A386020B130462C68FFF7A6 -:101A700031FF2044F8BD000073B5144606460D46FC -:101A8000FFF72EFF844228BF04460190DCB101A974 -:101A90003046FFF7D5FF019B33B93268C5E9023301 -:101AA000C5E9002401200CE09C4238BF0194286065 -:101AB000019868608442F5D93368AB60241AEC6001 -:101AC000022002B070BD2046FBE700002DE9FF4177 -:101AD0000F466946FFF7D0FF6C4600B204EBC00525 -:101AE0000026AC4209D0D4F8048054F8081BB81979 -:101AF0004246FFF70DFC4644F3E7304604B0BDE82C -:101B0000F081000038B50546FFF7E0FF04460146C6 -:101B10002846FFF719FF204638BD0000302383F325 -:101B2000118862B670470000002383F3118862B603 -:101B30007047000010B4026854681A4623465DF8E6 -:101B4000044B184701207047002070470020704761 -:101B500070470000002070470E20704700F580504D -:101B600090F8C800C0F340007047000000F58050B6 -:101B700090F9C90070470000F7B50C68BDF82070F7 -:101B800014F000541E466FD10B7B082B6CD8FFF766 -:101B9000C5FF4569AB685B010CD4AB681B0108D479 -:101BA000AC6814F080545DD1FFF7BEFF204603B04F -:101BB000F0BD01240B6804F1180C002BB8BFDB004A -:101BC0004FEA0C1CB4BF43F004035B0545F80C302E -:101BD0000B680FFA84FC13F0804F18BF05EB0C1E46 -:101BE00005EB0C1C1EBFDEF8803143F00203CEF87B -:101BF00080310B7BCCF8843105EB04158B68C5F87C -:101C00008C314B68C5F88831DCF8803143F0010332 -:101C1000CCF8803100EB441541F268031D4403EB1E -:101C200044130344C5E9002608330D4601F10C0CAA -:101C300055F804EB43F804EB6545F9D184342D885D -:101C40001D8000EB441407F00303257925F00B05F4 -:101C50002B432371FFF768FF0097334600F0E0FC49 -:101C60000120A4E70224A5E74FF0FF309FE7000022 -:101C700013B500F580540191E06DFFF74BFE1F286E -:101C80000AD90199E06D2022FFF7BAFEA0F12003E6 -:101C90005842584102B010BD0020FBE708B500F5DE -:101CA0008050FFF73BFFC06DFFF708FEBDE808401E -:101CB000FFF73ABF00220260828142608260704773 -:101CC00010B500220023C0E900230023044603814D -:101CD0000C30FFF7EFFF204610BD0000F0B50546C1 -:101CE00000F580500C4690F8C83013F0040FC3F391 -:101CF000800108BF114661F3820304F1840680F875 -:101D0000C83005EB461389B01B79D8072ED57AB3B6 -:101D100019072DD46846FFF7D3FF05EB441303F5ED -:101D2000835303F1180703AA10331868596814463F -:101D300003C40833BB422246F7D1186820609B8851 -:101D4000A380DDE90E23CDE900230123ADF808309F -:101D50002B686946DB6B2846984705EB46152B79BF -:101D60001A075CBF43F008032B7101E0002AF4D18D -:101D700009B0F0BD2DE9F047074688B007F580545B -:101D800068469A468846FFF7C9FE9146FFF798FFD6 -:101D9000E06DFFF7A5FD1F2829D9E06D20226946D7 -:101DA000FFF7B0FE202822D103AD444605AB2E46F6 -:101DB00003CE9E4220606160354604F10804F6D1EE -:101DC00030682060B388A380DDE90023C9E90023DF -:101DD000BDF80830AAF80030FFF7A6FE4A46534681 -:101DE0004146384608B0BDE8F04700F007BCFFF7B1 -:101DF0009BFE002008B0BDE8F08700002DE9F84FF9 -:101E00000023C0E90133254B044640F8183B0F4638 -:101E1000FFF750FF04F12800FFF752FF04F14808D4 -:101E200004F582554646083530462036FFF748FF10 -:101E3000AE42F9D104F580554FF480534FF00009BC -:101E4000C5E91339C5F848800123EE6504F58758C4 -:101E500004F58456C5F8549085F8583085F86030FC -:101E6000083608F108084FF0000A4FF0000B46E969 -:101E700008ABA6F11800FFF71DFF203646F8289C96 -:101E80004645F4D185F8C97017B1054800F0A0FBAC -:101E9000044B63612046BDE8F88F00BF384A000854 -:101EA000104A00080064004010B5044B197804463D -:101EB0004A1C1A70FFF7A2FF204610BD14380020FC -:101EC0002DE9F047002950D0294B2A4FB7FBF1F5F7 -:101ED00099428CBF0A231123581EB5FBF3FC03FB68 -:101EE0001C53C4B22BB102280346F5D80020BDE82C -:101EF000F0870CF1FF36B6F5806FF7D2C4EBC40E55 -:101F00000EF103034FEAE309C3F3C703A4EB03088D -:101F100009F1010A4FF47A755FFA88F009FB05555B -:101F20005AFA88F8B5FBF8F5B5F5617FC1BF0EF137 -:101F3000FF33C3F3C703E01AC0B25C1C50FA84F449 -:101F40000CFB04F4B7FBF4F4A142CFD1013BDBB2AC -:101F50000F2BCBD80138C0B20728C7D80021107189 -:101F600016809170D3700120C1E70846BFE700BF1B -:101F70003F420F000051250270B505460E464FF452 -:101F80007A746B695B6803F00103B3424FF00100A0 -:101F900004D001F0A5FC013CF3D1204670BD000047 -:101FA00030B54269936913F0700F16D000230B4CC3 -:101FB000936103F1840200EB421211794D0709D5B8 -:101FC000890707D5416954F823508D60117941F094 -:101FD000040111710133032BEBD130BD244A0008F9 -:101FE00073B51D46436916469A68D207044609D55B -:101FF0009A6801219960C2F34002CDE90065002191 -:10200000FFF76CFE63699A68D1050BD59A684FF4A7 -:1020100080719960C2F34022CDE90065012120461C -:10202000FFF75CFE63699A68D2030BD59A684FF498 -:1020300080319960C2F34042CDE90065022120461B -:10204000FFF74CFE204602B0BDE87040FFF7A8BF86 -:10205000F8B50446466900296CD106F10C073868CA -:1020600080076AD006EB01153868D5F8B00110F08A -:10207000040FD5F8B0011ABFC00840F00040400D71 -:10208000A061D5F8B0C11CF0020F1CBF40F0804029 -:10209000A061D5F8B40106EB011100F00F0084F83F -:1020A0002400D1F8B8012077D1F8B801000A607790 -:1020B000D1F8B801000CA077D1F8B801000EE07794 -:1020C000D1F8BC0184F82000D1F8BC01000A84F8E2 -:1020D0002100D1F8BC01000C84F82200D1F8BC1119 -:1020E000090E84F823103821396004F1340004F11A -:1020F000180104F1240551F8046B40F8046BA9425F -:10210000F9D109880180C4E90A23214600232386E6 -:1021100051F8283B2046DB6B984704F58052204657 -:1021200092F8C83043F0040382F8C830BDE8F840A4 -:10213000FFF736BF06F1100791E7F8BD10B504466A -:1021400000F04EFA02460B4652EA030102D0013A71 -:1021500063F100030449086820B12146BDE810403E -:10216000FFF776BF10BD00BF10380020F8B500F5AE -:1021700083511E46FFF7D2FCDFF844C0083100242B -:1021800004F1840500EB45152B795F070ED4DB06BF -:102190000CD5D1E900739742B34107D243695CF88B -:1021A00024709F602B7943F004032B710134032CBE -:1021B00001F12001E4D1BDE8F840FFF7B5BC00BF54 -:1021C000244A000808B5FFF7A9FCFFF7E9FEBDE8BF -:1021D0000840FFF7A9BC0000F8B5436905469868B8 -:1021E00000F0E050B0F1E05F0F461FD0E8B1FFF71C -:1021F00095FC05F583541034002606F1840305EBA5 -:1022000043131B791A0706D50136032E04F1200467 -:10221000F3D1012007E05B07F6D42146384600F0F1 -:1022200039FA0028F0D1FFF77FFCF8BD0120FCE768 -:1022300000F5805008B5FFF771FCC06DFFF750FB4B -:10224000FFF772FC43090CBF0120002008BD00000D -:10225000F8B51D46002313700F4606461446FFF7D7 -:10226000E7FF80F00100387025B129463046FFF7BE -:10227000B3FF2070F8BD00002DE9B8410C461546AB -:102280001F46804600F0ACF90B462178024609B99A -:10229000287850B14046FFF769FFFFF793FF3B46B0 -:1022A0002A462146FFF7D4FF0120BDE8B88100008F -:1022B00010B5FFF733FC174BDA6942F00072DA61B0 -:1022C0001A6942F000721A611A6900F5805422F00E -:1022D00000721A61FFF728FC94F8C830DB0718D4A5 -:1022E000B9B103211320FFF719FC01F0C7F903214D -:1022F000142001F0C3F90321152001F0BFF994F86F -:10230000C83043F0010384F8C830BDE81040FFF73F -:102310000BBC10BD001002402DE9F04700F58055C0 -:1023200088B095F8C930012B0446884616467FD8F8 -:10233000804F57F823200AB947F82300D7F800A0A8 -:10234000C4F80C802674BAF1000F63D095F8C93038 -:10235000012B6FD001212046FFF7AAFFFFF7DEFB1C -:102360006269136823F0020313606269136843F023 -:1023700001031360636900275F6101212046FFF7B5 -:10238000D3FBFFF7F9FD002800F09580E86DFFF71B -:1023900095FA04F58359BA4609F10809202200216B -:1023A0006846FEF7C7FF02A8FFF784FCCDF818A027 -:1023B0006A4609EB07030DF1180E9446BCE80300CA -:1023C000F44518605960624603F10803F5D1DCF862 -:1023D0000000186020379CF804201A71602FDDD1AE -:1023E00095F8C8306FF38203002785F8C8306A4635 -:1023F00041462046ADF80070ADF802708DF80470CB -:10240000FFF75EFD636948BB4FF400421A6008B0F5 -:10241000BDE8F08741F2D00002F01CFA814610B10D -:102420005146FFF7EBFCC7F80090B9F1000F8DD1D2 -:102430000020ECE7386803681B6B984701460028CA -:1024400088D13868FFF734FF3868036832465B6824 -:102450004146984700287FF47DAFE9E761221A6082 -:102460009DF802309DF803201B06120402F470222E -:1024700003F040731343BDF80020C2F30902134375 -:102480009DF804201205022E02F4E0020CBF4FF06A -:1024900000410021134362690B43D3616369132236 -:1024A0005A616269136823F00103136039462046BC -:1024B000FFF762FD08B96369A6E795F8C93093BBD9 -:1024C0006169D1F8002242F00102C1F8002261697D -:1024D000D1F8002222F47C5222F00E02C1F8002230 -:1024E0006169D1F8002242F46062C1F80022626999 -:1024F000C2F814326269C2F80432626941F6FF71AF -:10250000C2F80C126269C2F840326269C2F8443201 -:1025100063690122C3F81C226269D2F8003223F0F9 -:102520000103C2F8003295F8C83043F0020385F881 -:10253000C8306CE71038002008B500F051F850EAB8 -:102540000103024602D0421E61F10001044B1868EB -:1025500010B10B46FFF744FDBDE8084001F064B838 -:102560001038002008B50020FFF7E8FDBDE808405E -:1025700001F05AB808B50120FFF7E0FDBDE80840BA -:1025800001F052B800B59BB0EFF3098168226846AC -:10259000FEF7BEFEEFF30583014B9B6BFEE700BF2A -:1025A00000ED00E008B5FFF7EDFF000000B59BB0BF -:1025B000EFF3098168226846FEF7AAFEEFF3058370 -:1025C000014B5B6BFEE700BF00ED00E0FEE70000A3 -:1025D0000FB408B5029801F019F9FEE701F02EBB1F -:1025E00001F004BB13B56C4684E80600031D94E8B3 -:1025F000030083E80500012002B010BD73B58568B3 -:10260000019155B11B885B0707D4D0E900369B6B5D -:102610009847019AC1B23046A847012002B070BD68 -:10262000F0B5866889B005460C465EB1BDF8383015 -:102630005B070AD4D0E900379B6B98472246C1B2AA -:102640003846B047012009B0F0BD00220023CDE993 -:1026500000230023ADF808300A4603AB01F1080659 -:10266000106851681C4603C40832B2422346F7D1B1 -:10267000106820609288A280FFF7B2FF0423ADF8B3 -:1026800008302B68CDE90001DB6B69462846984786 -:10269000D8E7000030B503680968DD0FB5EBD17FDE -:1026A00023F0604421F060424FEAD1700BD0002B40 -:1026B000B8BFA40C0029B8BF920C944202D034BF1A -:1026C0000120002030BD944205D1C1F38070C3F3D6 -:1026D00080738342F6D194422CBF00200120F1E7A1 -:1026E0002DE9F041456A15B94162BDE8F0814B68BA -:1026F00023F06047C3F38A464FEAD37EC3F3807862 -:1027000016EA230638BF3E46AC462B465A68BEEB57 -:10271000D27F22F060440AD0002A18DAA40CB44216 -:1027200017D19D420FD10D60DEE71346EEE7A742B9 -:1027300007D102F08044C2F3807242450BD054B1FD -:10274000EFE708D2EDE7CCF800100B60CDE7B4421C -:1027500001D0B442E5D81A689C46002AE5D1196038 -:10276000C3E700002DE9F047089D01F007044FEA98 -:10277000D508224405F0070500EBD1004FF47F494E -:10278000944201D1BDE8F08704F0070705F0070A7D -:1027900057453E4638BF5646C6F10806111B8E42C5 -:1027A00028BF0E46E10808EBD50E415C13F80EC0B9 -:1027B000B94029FA06F721FA0AF1FFB28CEA0101C1 -:1027C00047FA0AF739408CEA010C03F80EC034448A -:1027D0003544D5E780EA0120082341F2210201B205 -:1027E0004000002980B203F1FF33B8BF504013F01E -:1027F000FF03F4D17047000038B50C468D18A54290 -:1028000000D138BD14F8011BFFF7E4FFF7E7000023 -:1028100042684AB1136843604389818901339BB29E -:102820009942438138BF83811046704770B588B0A4 -:10283000202204460D4668460021FEF77BFD204617 -:102840000495FFF7E5FF024658B16B46054608AE12 -:102850001C4603CCB44228606960234605F1080594 -:10286000F6D1104608B070BD082817D909280CD039 -:102870000A280CD00B280CD00C280CD00D280CD01A -:102880000E2814BF4020302070470C2070471020C5 -:1028900070471420704718207047202070470000B0 -:1028A000082817D90C280CD910280CD914280CD9B1 -:1028B00018280CD920280CD930288CBF0F200E20C6 -:1028C0007047092070470A2070470B2070470C2082 -:1028D00070470D20704700002DE9F843078C072F43 -:1028E00004461ED9D0E9029800254FF6FF73C5F1C2 -:1028F0002006A5F1200029FA05F108FA06F628FAC3 -:1029000000F031430143C9B21846FFF763FF0835B1 -:10291000402D0346EBD1E1693A46BDE8F843FFF7A5 -:102920006BBF4FF6FF70BDE8F883000010B54B6831 -:1029300023B9CA8A63F30902CA8210BD04691A68FE -:102940001C600361C38A013BC3824A60EFE7000059 -:102950002DE9F84F1D46CB8A0F46C3F3090105291F -:10296000814692460B4630D00020AAB207F11A04E5 -:102970009EB2042E1FFA80F80FD8904503F1010390 -:1029800006D3FB8A0A4462F30903FB8201201AE0A2 -:102990001AF80060E6540130EAE79045F1D2A1F15F -:1029A000050B1C237C68BBFBF3F203FB12BB1FFA75 -:1029B0008BF6002C45D14846FFF72AFF044638B96C -:1029C00078606FF00200BDE8F88F4FF00008E6E78E -:1029D000002606607860ADB24FF0000B454510D977 -:1029E0000AEB0803221D13F8011B9155B1B208F13F -:1029F00001081B291FFA88F82BD0454506F101066E -:102A0000F1D8FB8AC3F30902154465F30903BCE757 -:102A1000013292B21C462368002BF9D16B1F0B4484 -:102A20001C21B3FBF1F301339BB29A42D3D2BBF129 -:102A3000000FD0D14846FFF7EBFE20B9C4F800B034 -:102A4000BFE70122E7E7C0F800B05E462060044619 -:102A5000C1E74545D5D94846FFF7DAFE08B92060F9 -:102A6000AFE7C0F800B0002620600446B6E70000DB -:102A70002DE9F04F2DED028B1C4683B05B6901926E -:102A800007468846002B00F09A80238C2BB1E26920 -:102A9000002A00F09480072B35D807F10C00FFF7CF -:102AA000B7FE054638B96FF00205284603B0BDEC05 -:102AB000028BBDE8F08F14220021FEF73BFC228C34 -:102AC000E16905F10800FEF723FC208C013080B29B -:102AD000FFF7E6FEFFF7C8FE013880B22084013020 -:102AE00028746369228C1B782A4403F01F0363F067 -:102AF0003F0348F000411372384669602946FFF7EA -:102B0000EFFD0125D1E700F10C034FF0000908EEBD -:102B1000103A4FF0800A4E464D4618EE100AFFF765 -:102B200077FE83460028BED014220021FEF702FC67 -:102B3000002E3AD1019BABF8083002220BF1080EAF -:102B40001FFA82FC0CF10100BCF1060F218C80B24F -:102B500001D88E422BD3FFF7A3FEFFF785FE6269F3 -:102B60001278013802F01F028E4208BF4FF0400A6F -:102B700042EA49121BFA80F14AEA020A013048F09F -:102B8000004281F808A08BF81000CBF804205946C9 -:102B90003846FFF7A5FD238C0135B3422DB289F0ED -:102BA00001094FF0000AB8D17FE70022C6E7E169CA -:102BB000895D0EF802100136B6B20132C0E76FF03F -:102BC000010572E7F8B515460E463022002104468D -:102BD0001F46FEF7AFFB069B6360B5F5001F079B22 -:102BE000A76034BF6A094FF6FF72A36297B2E6612D -:102BF00004F1100000239A4206D800230360A78244 -:102C0000E3822383E360F8BD06600133304620365B -:102C1000F1E7000003781BB94BB2002BC8BF01706D -:102C20007047000000787047F8B50C46C969074640 -:102C300011B9238C002B37D1257E1F2D34D838783D -:102C400028BB228C072A2CD8268A36F003032BD1E6 -:102C50004FF6FF70FFF7D0FD20F001003102400475 -:102C600041EA0561400C41EA40254FF6FF722346D8 -:102C700029463846FFF7FCFE002807DD6269137815 -:102C80000133DBB21F2B88BF00231370F8BD218AEC -:102C90002D0645EA012505432046FFF71DFE0246A5 -:102CA000E5E76FF00300F1E76FF00100EEE70000E9 -:102CB00070B58AB0044616460021282268461D4693 -:102CC000FEF738FBBDF83830ADF810300F9B059398 -:102CD0009DF840308DF81830119B07936946BDF878 -:102CE0004830ADF820302046CDE90265FFF79CFF63 -:102CF0000AB070BD2DE9F041D36905460C46164671 -:102D00000BB9138C5BBB377E1F2F28D895F800803A -:102D1000B8F1000F26D03046FFF7DEFD33782102F0 -:102D200041EAC33141EA0801338A41EA076141EAD5 -:102D300003410246334641F080012846FFF798FEE2 -:102D400000280ADD3378012B07D17269137801332B -:102D5000DBB21F2B88BF00231370BDE8F0816FF03A -:102D60000100FAE76FF00300F7E70000F0B58BB061 -:102D700004460D4617460021282268461E46FEF7E7 -:102D8000D9FA9DF84C305A1E534253418DF8003009 -:102D90009DF84030ADF81030119B05939DF84830F8 -:102DA0008DF81830149B07936A46BDF85430ADF87F -:102DB000203029462046CDE90276FFF79BFF0BB075 -:102DC000F0BD0000406A00B104307047436A1A68E1 -:102DD000426202691A600361C38A013BC382704781 -:102DE0002DE9F041D0F82080194E14461D46414689 -:102DF000002709B9BDE8F081D1E90223A21A65EBE9 -:102E00000303964277EB03031ED2036A8B420DD174 -:102E1000FFF78CFD036A1B68036203690B60C38ABA -:102E20000161016A013BC3828846E2E7FFF77EFD4C -:102E30000B68C8F8003003690B60C38A0161013B6D -:102E4000C382D8F80010D4E788460968D1E700BFEC -:102E500080841E002DE9F04F8BB00D46DDF85090B8 -:102E600014469B468046002800F01981B9F1000FF6 -:102E700000F01581531E3F2B00F21181012A03D16E -:102E8000BBF1000F40F00B810023CDE90833B8F807 -:102E90001430B5EBC30F4FEAC30703D300200BB0C8 -:102EA000BDE8F08F2B199F42D8F80C303ABF7F1B3A -:102EB000FFB227461BB9D8F81030002B7AD0272D47 -:102EC0004ED8C5F12806B7424FF000032CBFF6B22A -:102ED0003E4600932946D8F8080008AB3246FFF773 -:102EE00041FCA7EB060A35445FFA8AFAB8F81430B9 -:102EF00003F10053053BDB000493D8F80C30039337 -:102F00002821039B13B1BAF1000F2CD1D8F810007F -:102F100040B1BAF1000F05D0009608AB5246691ACD -:102F2000FFF720FC38B2002FB8D066070AD00AABF2 -:102F300003EBD401624211F8083C02F0070213418E -:102F400001F8083C082C3CD9102C40F2B580202C0C -:102F500040F2B780BBF1000F00F09C80082334E002 -:102F6000BA460026C2E7049BE02B28BFE023069365 -:102F70000B44AB42059314D95A1B03980096924513 -:102F800034BF5246D2B2691A08AB04300792FFF739 -:102F9000E9FB079A1644AAEB020A1544F6B25FFA57 -:102FA0008AFA049B069A05999B1A0493039B1B6853 -:102FB0000393A6E70093D8F8080008AB3A462946E1 -:102FC000AEE7BBF1000F13D00123B4EBC30F6CD0FD -:102FD000082C12D89DF82030621E23FA02F2D50781 -:102FE00006D54FF0FF3202FA04F423438DF8203067 -:102FF0009DF8203089F8003051E7102C12D8BDF828 -:103000002030621E23FA02F2D10706D54FF0FF32BC -:1030100002FA04F42343ADF82030BDF82030A9F8BB -:1030200000303CE7202C0FD80899631E21FA03F3E7 -:10303000DA0705D54FF0FF3202FA04F40C43089486 -:10304000089BC9F800302AE7402C2BD0DDE9086541 -:10305000611EC4F12102A4F1210326FA01F105FA4F -:1030600002F225FA03F311431943CB0712D50122CB -:10307000A4F12003C4F1200102FA03F322FA01F1C2 -:10308000A240524243EA010363EB430332432B4322 -:10309000CDE90823DDE90823C9E90023FFE66FF045 -:1030A0000100FCE66FF00800F9E6082CA0D9102C0E -:1030B000B3D9202CEED8C3E7BBF1000FADD002236B -:1030C00083E7BBF1000FBBD004237EE730B5012AB4 -:1030D000144638BF0124402C85B028BF4024002569 -:1030E000012ACDE9025518D81B788DF808306307FE -:1030F0000AD004AB03EBD405624215F8083C02F099 -:103100000702934005F8083C00910346224600213F -:1031100002A8FFF727FB05B030BD082AE4D9102A22 -:1031200003D81B88ADF80830E1E7202A8DBFD3E92A -:1031300000231B680293CDE90223D8E710B5CB68C2 -:103140001BB98B600B618B8210BD04691A681C600F -:103150000361C38A013BC382CA60F0E703064CBF28 -:10316000C0F3C0300220704708B50246FFF7F6FFF3 -:10317000022806D15306C2F30F2001D100F003004C -:1031800008BDC2F30740FBE72DE9F04F93B0CDE94E -:1031900003230A6804461046FFF7E0FF022814BF25 -:1031A000C2F306260026002A0D46824680F2F281EE -:1031B00012F0C04940F0EE81097B002900F0EA815D -:1031C000022803D02378B34240F0E781C2F30463BE -:1031D0000693104602F07F030593FFF7C5FF059B9A -:1031E00029444FEA834848EA0A4848EA4668CE78C4 -:1031F00000230022CDE90823F309834648EA0008AA -:10320000029367D0059B009302466768534608A95E -:103210002046B847002800F0C381276A4FB94146CD -:1032200004F10C00FFF702FB074690B96FF00200B3 -:1032300054E03B6998450DD03F68002FF9D14146D5 -:1032400004F10C00FFF7F2FA07460028EED0236ADB -:103250003B60276297F817C006F01F08CCF3840C78 -:10326000ACEB08001FFA80FE0028B8BF0EF120006A -:10327000A8EB0C031FFA83FED7E90221B8BF00B206 -:10328000002B0793BEBF0EF120031BB2079352EA37 -:10329000010338D0039BDFF824E39A1A049B4FF014 -:1032A000000C63EB010196457CEB01032BD36B7B98 -:1032B00097F81AE0734519D1029B002B78D00128AA -:1032C00021DC7868F8B9DFF8F0C2944570EB0103AF -:1032D00016D337E0276A27B96FF00C0013B0BDE8AA -:1032E000F08F3B699845B5D03F68F4E7B24890420B -:1032F0007CEB010301D30020F0E7029B002BFAD006 -:10330000079B0F2B17DCFA7DB30002F0030203F0DA -:103310007C031343FB7539462046FFF707FB6B7BA5 -:10332000BB76029B3BB9FB7DC3F38402013262F39F -:103330008603FB75D0E76A7BBB7E9A42DBD1029B9A -:10334000002B35D0B309022B32D0039BBB60049B0A -:10335000FB60142200210DA8FDF7ECFF039B0A93EC -:10336000049B0B932B1D0C932B7BADF83EB0013BC4 -:10337000DBB2ADF83C30069B8DF84230059B8DF8F2 -:10338000433094F82C308DF840A083F001038DF881 -:1033900044308DF84180A3680AA920469847FB7DF8 -:1033A000C3F38403013303F01F039B02FB82A2E7F4 -:1033B000FB7DC6F34012B2EBD31F40F0F480C3F3A1 -:1033C0008403434540F0F280029A2B7BB609002A21 -:1033D0004DD0F2075DD4032B40F2EB80039BBB6022 -:1033E000049BFB602B7BAE1D033BDBB232463946B0 -:1033F00004F10C00FFF7ACFA00280CDA394620463D -:10340000FFF794FAFB7DC3F38403013303F01F033A -:103410009B02FB820AE7DDE90884AB883B834FF619 -:10342000FF73C9F12000A9F1200228FA09F104FA7A -:1034300000F0014324FA02F211431846C9B2FFF723 -:10344000C9F909F10809B9F1400F0346E9D1B88279 -:103450002A7B033AD2B23146FFF7CEF9FB7DB88220 -:10346000DA43C2F3C01262F3C713FB7543E786B9B0 -:103470002E1D013BDBB23246394604F10C00FFF74A -:1034800067FA0028BADB2A7BB88A013AD2B2314601 -:10349000E2E7F98AC1F30901013B0429DAB25BD8FA -:1034A000281D002307F11B069A4208D910F801CB0A -:1034B00006F801C0013101330529DBB2F4D10399CB -:1034C0000A9104990B91934207F11B010C9138BFAB -:1034D000043379680D9134BF55FA83F300230E93BA -:1034E000FB8AADF83EB0C3F309031A44069B8DF87E -:1034F0004230059B8DF8433094F82C30ADF83C20D9 -:1035000083F001038DF8443000238DF840A08DF83E -:1035100041807B602A7BB88A013A291DFFF76CF94C -:103520003B8BB882834203D1A3680AA920469847FF -:1035300020460AA9FFF702FEFB7DBA8AC3F3840383 -:10354000013303F01F039B02FB823B8B9A420CBFAB -:1035500000206FF01000C1E67B68002BAFD0052083 -:1035600001E01C3033461E68002EFAD1091A081DEE -:103570002E1D184401EB090CBCF11B0F5FFA89F3F7 -:103580009DD89A429BD916F8013B00F8013B09F1FE -:103590000109EFE76FF00900A0E66FF00A009DE671 -:1035A0006FF00B009AE66FF00D0097E66FF00E00DB -:1035B00094E66FF00F0091E640420F0080841E00F9 -:1035C000EFF3098305494A6B22F001024A6368332D -:1035D00083F30988002383F31188704700EF00E02C -:1035E000302080F3118862B60C4B0D4AD96821F463 -:1035F000E0610904090C0A43DA60D3F8FC200949A8 -:1036000042F08072C3F8FC200A6842F001020A60AE -:103610002022DA7783F82200704700BF00ED00E037 -:103620000003FA05001000E010B5302383F3118881 -:103630000E4B5B6813F4006314D0F1EE103AEFF315 -:103640000984683C4FF08073E361094BDB6B2366B0 -:1036500084F3098800F098F810B1064BA36110BDFF -:10366000054BFBE783F31188F9E700BF00ED00E0AD -:1036700000EF00E0030600080606000800F16043C2 -:1036800003F561430901C9B283F80013012200F078 -:103690001F039A4043099B0003F1604303F5614314 -:1036A000C3F880211A60704700F16040090100F5FD -:1036B0006D40C9B2017670470023037582680369C3 -:1036C0001B6899689142FBD25A680360426010609F -:1036D0005860704700230375826803691B68996806 -:1036E0009142FBD85A68036042601060586070478E -:1036F00008B50846302383F311880B7D032B05D0D2 -:10370000042B0DD02BB983F3118808BD8B690022DF -:103710001A604FF0FF338361FFF7CEFF0023F2E71B -:10372000D1E9003213605A60F3E70000FFF7C4BF2D -:10373000054BD9680875186802681A605360012241 -:103740000275D860FCF748BF2038002030B50C4B1C -:10375000DD684B1C87B004460FD02B46094A6846EB -:1037600000F0FEF82046FFF7E3FF009B13B1684628 -:1037700000F000F9A86907B030BDFFF7D9FFF9E7FD -:1037800020380020F1360008044B1A68DB68906886 -:103790009B68984294BF0020012070472038002089 -:1037A000084B10B51C68D86822681A605360012263 -:1037B0002275DC60FFF78EFF01462046BDE8104011 -:1037C000FCF70ABF20380020044B1A68DB689268B7 -:1037D0009B689A4201D9FFF7E3BF70472038002069 -:1037E00038B5074C07490848012300252370656058 -:1037F00000F00AFB0223237085F3118838BD00BF57 -:10380000483A00207C4A00082038002008B572B6EB -:10381000044B186500F0CEF900F092FA024B032237 -:103820001A70FEE720380020483A002000F0B4B8B3 -:10383000EFF3118020B9EFF30583302282F3118872 -:103840007047000010B530B9EFF30584C4F30804E5 -:1038500014B180F3118810BDFFF7B6FF84F311880F -:10386000F9E700008B60022308618B8208467047ED -:103870008368A3F1840243F8142C026943F8442CB2 -:10388000426943F8402C094A43F8242CC26843F8A3 -:10389000182C022203F80C2C002203F80B2C044AEB -:1038A00043F8102CA3F12000704700BFF105000879 -:1038B0002038002008B5FFF7DBFFBDE80840FFF720 -:1038C00035BF0000024BDB6898610F20FFF730BF67 -:1038D00020380020302383F31188FFF7F3BF000066 -:1038E00008B50146302383F311880820FFF72EFF27 -:1038F000002383F3118808BD064BDB6839B14268A9 -:1039000018605A60136043600420FFF71FBF4FF038 -:10391000FF307047203800200368984206D01A68AC -:103920000260506099611846FFF700BF70470000C1 -:1039300010B50A4C23699A6891420CD85A68816084 -:103940000360426010609A685860511A99604FF0A5 -:10395000FF33A36110BD1B68891AECE720380020F3 -:1039600010B4C0E9032300235DF8044B4361FFF763 -:10397000DFBF0000036881689A680A449A60426861 -:1039800013605A6000230360024B4FF0FF329A61CC -:10399000704700BF2038002070B5124DEB692A46F1 -:1039A0000133EB6152F8103F934206D09A68013A16 -:1039B0009A6030262C69A36803B170BDD4E9002158 -:1039C0000A605160236083F31188D4E903312046F3 -:1039D000984786F3118861690029EBD02046FFF7EC -:1039E000A7FFE7E72038002000207047FEE700002F -:1039F000704700004FF0FF3070470000BFF34F8F5B -:103A0000024AD368DB07FCD4704700BF00200240A5 -:103A100008B5074B1B7853B9FFF7F0FF054B1A6940 -:103A2000120641BF044A5A6002F188325A6008BD4A -:103A3000603A0020002002402301674508B5054B8D -:103A40001B7833B9FFF7DAFF034A136943F08003A9 -:103A5000136108BD603A0020002002407F289ABF11 -:103A600000F58030C0020020704700004FF4006075 -:103A700070470000802070477F2808B50BD8FFF7FB -:103A8000EDFF00F500630268013204D10430834287 -:103A9000F9D1012008BD0020FCE700007F2810B507 -:103AA00004461CD8FFF7AAFFFFF7B2FF0D4BF32225 -:103AB000DA6002221A61FFF7D1FF58611A6942F0F9 -:103AC00040021A614FF40061FFF798FF00F034F9EB -:103AD000FFF7B4FF2046BDE81040FFF7CDBF002040 -:103AE00010BD00BF002002402DE9F84312F0010391 -:103AF000144606D01F4B40F2F3221A600020BDE8A6 -:103B0000F88385181C4A954204D91A4A4FF43E712D -:103B10001160F3E7FFF77CFFFFF770FFDFF86880C5 -:103B2000451A4FF00109012C05EB01060F4603D899 -:103B3000FFF784FF0120E2E73B88C8F8109033804C -:103B40000020FFF75BFFC8F81000338831F8022B24 -:103B50009BB29A420CD0074B40F20F321A60074BCF -:103B60001E60074B1C60074B1F60FFF767FFC6E72F -:103B7000023CD8E75C3A002000000408503A0020DC -:103B8000583A0020543A002000200240084908B565 -:103B90000B7828B11BB9FFF73BFF01230B7008BD61 -:103BA000002BFCD0BDE808400870FFF747BF00BFFE -:103BB000603A002008B54FF420414FF0005000F06B -:103BC000BDF8BDE808404FF400514FF0805000F0C0 -:103BD000B5B800000846114600F05EBE012000F0B6 -:103BE0005BBE0000084600F075BE000030B583B033 -:103BF000FFF71EFE0E4B0F4DDB692A684FF47A71FA -:103C000001FB03F3934237BF0B4A0B495168146819 -:103C10002B602EBFD1E90041013151601C1941F1E7 -:103C200000010191FFF70EFE0199204603B030BD5F -:103C300020380020643A0020683A002030B583B074 -:103C4000FFF7F6FD114B124DDB692A684FF47A71CC -:103C500001FB03F3934237BF0E4A0E4951681468C3 -:103C60002B602EBFD1E90041013151601C1941F197 -:103C700000010191FFF7E6FD01994FF47A720023EC -:103C80002046FCF795FA03B030BD00BF2038002075 -:103C9000643A0020683A002010B50244064BD2B2C4 -:103CA000904200D110BD441C00B253F8200041F8EE -:103CB000040BE0B2F4E700BF502800400F4B30B5D2 -:103CC0001C6A240407D41C6A44F440741C621C6AF5 -:103CD00044F400441C620A4C236843F4807323605C -:103CE0000244084BD2B2904200D130BD441C00B215 -:103CF00051F8045B43F82050E0B2F4E700100240B2 -:103D0000007000405028004007B5012201A90020A2 -:103D1000FFF7C2FF019803B05DF804FB13B504463A -:103D2000FFF7F2FFA04205D0012201A90020019473 -:103D3000FFF7C4FF02B010BD7047000070470000DD -:103D400070470000074B45F255521A6002225A6034 -:103D500040F6FF729A604CF6CC421A60024B012288 -:103D60001A70704700300040743A0020034B1B78F3 -:103D70001BB1034B4AF6AA221A607047743A00201E -:103D800000300040044B1A682AB902F1804202F563 -:103D90000432526A1A607047703A0020024B4FF0AA -:103DA00080725A62704700BF0010024008B5FFF7EA -:103DB000E9FF024B1868C0F3407008BD703A00205C -:103DC00070470000FEE700000A4B0B480B4A904288 -:103DD0000BD30B4BDA1C121AC11E22F003028B42CA -:103DE00038BF00220021FDF7A5BA53F8041B40F8A4 -:103DF000041BECE7EC4B0008583C0020583C00202A -:103E0000583C0020FEE7000070B51B4B0163002505 -:103E1000044686B0586085620E46FFF7E1FB04F168 -:103E20001003C4E904334FF0FF33A361134BE56182 -:103E3000D969A5600A462B46C4E9082304F1340178 -:103E4000C4E900440E4AE562256580232046FFF759 -:103E500009FD0123E0600B4A03750092726801922C -:103E6000B268CDE90223084B6846CDE90435FFF777 -:103E700021FD06B070BD00BF483A00202038002068 -:103E8000884A00088D4A0008053E00084B684360D8 -:103E90008B688360CB68C3600B6943614B690362C5 -:103EA0008B6943620B6803607047000008B51B4BC9 -:103EB0009A6A42F4FC029A629A6A22F4FC029A62BA -:103EC0009A6A5A6942F4FC025A61154A5B691146C2 -:103ED0004FF09040FFF7DAFF02F11C0100F580601F -:103EE000FFF7D4FF02F1380100F58060FFF7CEFF45 -:103EF00002F1540100F58060FFF7C8FF02F1700184 -:103F000000F58060FFF7C2FF02F18C0100F58060D0 -:103F1000FFF7BCFFBDE8084000F05AB800100240AF -:103F2000944A000808B500F093F9FFF759FCBDE882 -:103F30000840FFF727BF00007047000010B5214C74 -:103F4000A36A63F4FC03A362A36A03F4FC03A36201 -:103F50004FF0FF32A36A23692261236900232361A2 -:103F60002169E168E260E268E360E268E2691649BB -:103F700042F08052E261E2690A6842F480720A60AB -:103F8000226A02F44072B2F5407F1EBF4FF48032C5 -:103F900022622362236A1B0407D4236A43F440731A -:103FA0002362236A43F40043236200F031F9A369DA -:103FB000064A43F00103A361A369136843F0200399 -:103FC000136010BD0010024000700040000001406E -:103FD0001E4B1A6842F001021A601A689007FCD55D -:103FE0005A6822F003025A605A6812F00C02FBD1A0 -:103FF000196801F0F90119605A601A6842F48032B8 -:104000001A601A689103FCD5114A5A604FF40452A1 -:10401000DA6230221A631A6842F080721A601A68F3 -:104020009201FCD50B4912220A600A6802F00702CD -:10403000022AFAD15A6842F002025A605A6802F023 -:104040000C02082AFAD11A6B1A637047001002405A -:1040500000241D0000200240084A08B55169136879 -:104060000B4003F00103536123B1054A13680BB100 -:1040700050689847BDE80840FFF7D6BA00040140F1 -:10408000783A0020084A08B5516913680B4003F0DC -:104090000203536123B1054A93680BB1D068984776 -:1040A000BDE80840FFF7C0BA00040140783A00209C -:1040B000084A08B5516913680B4003F004035361C3 -:1040C00023B1054A13690BB150699847BDE8084010 -:1040D000FFF7AABA00040140783A0020084A08B560 -:1040E000516913680B4003F00803536123B1054A7B -:1040F00093690BB1D0699847BDE80840FFF794BABF -:1041000000040140783A0020084A08B55169136854 -:104110000B4003F01003536123B1054A136A0BB13E -:10412000506A9847BDE80840FFF77EBA0004014096 -:10413000783A0020174B10B55A691C68144004F4F3 -:1041400078725A61A30604D5134A936A0BB1D06AF8 -:104150009847600604D5104A136B0BB1506B984713 -:10416000210604D50C4A936B0BB1D06B9847E2053E -:1041700004D5094A136C0BB1506C9847A30504D5BC -:10418000054A936C0BB1D06C9847BDE81040FFF71F -:104190004BBA00BF00040140783A00201A4B10B51A -:1041A0005A691C68144004F47C425A61620504D5C3 -:1041B000164A136D0BB1506D9847230504D5134A69 -:1041C000936D0BB1D06D9847E00404D50F4A136E80 -:1041D0000BB1506E9847A10404D50C4A936E0BB1F5 -:1041E000D06E9847620404D5084A136F0BB1506F24 -:1041F0009847230404D5054A936F0BB1D06F9847B5 -:10420000BDE81040FFF710BA00040140783A0020E2 -:10421000062108B50846FFF731FA06210720FFF707 -:104220002DFA06210820FFF729FA06210920FFF7B9 -:1042300025FA06210A20FFF721FA06211720FFF7A9 -:104240001DFABDE8084006212820FFF717BA000034 -:1042500008B5FFF773FE00F067F800F03DF8FFF7D0 -:104260006BFEBDE8084000F05DB8000002684368DE -:104270001143016003B1184770470000143000F08B -:104280002FBA00004FF0FF33143000F029BA0000BD -:10429000383000F0A5BA00004FF0FF33383000F09E -:1042A0009FBA0000143000F0F5B900004FF0FF3164 -:1042B000143000F0EFB90000383000F04FBA0000C1 -:1042C0004FF0FF32383000F049BA0000012914BF26 -:1042D0006FF013000020704700F06CB8044B0360CF -:1042E0000023C0E90233436001230374704700BF19 -:1042F0003C4B000838B5C36904460D461BB9042180 -:104300000844FFF7B3FF294604F1140000F0A6F9B2 -:10431000002806DA201D4FF40061BDE83840FFF7A1 -:10432000A5BF38BD00F00EB80023054A1946013379 -:10433000102BC2E9001102F10802F8D1704700BF4A -:10434000783A00204FF0E023044A5A6100229A6133 -:1043500007221A6108210B20FFF7A6B93F190100B7 -:1043600008B5302383F31188FFF760FA002383F345 -:10437000118808BD08B5FFF7F3FFBDE80840FFF757 -:1043800053B90000026843681143016003B1184744 -:1043900070470000024A136843F0C003136070477F -:1043A00000380140024A136843F0C00313607047AD -:1043B0000044004037B51D4C1D4D2046FFF78EFFD1 -:1043C000009404F114001B490023202200F038F966 -:1043D0002022009404F13800174B184900F0B2F97C -:1043E000174BC4E91735174C0C212520FFF746F968 -:1043F0002046FFF773FF04F11400134900940023D3 -:10440000202200F01DF904F13800104B10490094EF -:10441000202200F097F90F4B0C212620C4E9173514 -:1044200003B0BDE83040FFF729B900BFF83A0020DB -:1044300000512502D03B002095430008103C00208D -:1044400000380140643B0020F03B0020A5430008F9 -:10445000303C0020004400402DE9F047C66D37682D -:10446000F46934622107054619D014F0080118BF19 -:104470004FF48071E20748BF41F02001A30748BF15 -:1044800041F04001600748BF41F08001302383F3D1 -:104490001188281DFFF776FF002383F31188E205BA -:1044A0000AD5302383F311884FF48061281DFFF76C -:1044B00069FF002383F311884FF030094FF0000AA1 -:1044C00014F0200838D13B0616D54FF0300905F11D -:1044D000380A200610D589F31188504600F066F995 -:1044E000002836DA0821281DFFF74CFF27F080034B -:1044F0003360002383F31188790614D5620612D540 -:10450000302383F31188D5E913239A4208D12B6C09 -:1045100033B11021281D27F04007FFF733FF376024 -:10452000002383F31188E30619D5AA6E1369B3B18A -:10453000BDE8F0475069184789F31188B38C95F8A6 -:10454000641028461940FFF7D5FE8AF31188F469F4 -:10455000B6E780B2308588F31188F469B9E7BDE821 -:10456000F087000008B50348FFF776FFBDE8084074 -:10457000FFF75AB8F83A002008B50348FFF76CFF78 -:10458000BDE80840FFF750B8643B0020F8B5154679 -:1045900082680669AA420B46816938BF8568761A27 -:1045A000B54204460BD218462A46FCF7B1FEA36971 -:1045B0002B44A361A3685B1BA3602846F8BD0CD9FC -:1045C00018463246FCF7A4FEAF1BE1683A46304479 -:1045D000FCF79EFEE3683B44EBE718462A46FCF7EF -:1045E00097FEE368E5E7000083689342F7B5154658 -:1045F000044638BF8568D0E90460361AB5420BD24C -:104600002A46FCF785FE63692B446361A36828464C -:104610005B1BA36003B0F0BD0DD932460191FCF7DE -:1046200077FE0199E068AF1B3A463144FCF770FE13 -:10463000E3683B44E9E72A46FCF76AFEE368E4E7FF -:1046400010B50A440024C361029B8460C0E90000E5 -:10465000C0E90511C1600261036210BD08B5D0E96F -:104660000532934201D1826882B982680132826048 -:104670005A1C42611970D0E904329A4224BFC368BF -:1046800043610021FFF748F9002008BD4FF0FF30DB -:10469000FBE7000070B5302304460E4683F3118813 -:1046A000A568A5B1A368A269013BA360531CA361DF -:1046B00015782269934224BFE368A361E3690BB1D3 -:1046C00020469847002383F31188284607E03146A7 -:1046D0002046FFF711F90028E2DA85F3118870BD52 -:1046E0002DE9F74F04460E4617469846D0F81C9021 -:1046F0004FF0300A8AF311884FF0000B154665B170 -:104700002A4631462046FFF741FF034660B941463D -:104710002046FFF7F1F80028F1D0002383F3118839 -:10472000781B03B0BDE8F08FB9F1000F03D0019002 -:104730002046C847019B8BF31188ED1A1E448AF36B -:104740001188DCE7C0E90511C160C3611144009B19 -:104750008260C0E90000016103627047F8B5044659 -:104760000D461646302383F31188A768A7B1A368C6 -:10477000013BA36063695A1C62611D70D4E9043275 -:104780009A4224BFE3686361E3690BB1204698470E -:10479000002080F3118807E031462046FFF7ACF88F -:1047A0000028E2DA87F31188F8BD0000D0E905237C -:1047B0009A4210B501D182687AB98268013282606A -:1047C0005A1C82611C7803699A4224BFC3688361C2 -:1047D0000021FFF7A1F8204610BD4FF0FF30FBE7A6 -:1047E0002DE9F74F04460E4617469846D0F81C9020 -:1047F0004FF0300A8AF311884FF0000B154665B16F -:104800002A4631462046FFF7EFFE034660B941468F -:104810002046FFF771F80028F1D0002383F31188B8 -:10482000781B03B0BDE8F08FB9F1000F03D0019001 -:104830002046C847019B8BF31188ED1A1E448AF36A -:104840001188DCE70B460146184600F02DB8000041 -:1048500000F040B8012838BF012010B504462046BA -:1048600000F030F830B900F007F808B900F00CF8A3 -:104870008047F4E710BD0000024B1868BFF35B8F60 -:10488000704700BF503C002008B5062000F084F8B7 -:104890000120FFF7ABF80000024B0A4601461868FA -:1048A000FFF798B91811002010B5054C13462CB12C -:1048B0000A4601460220AFF3008010BD2046FCE707 -:1048C00000000000024B01461868FFF787B900BFDF -:1048D00018110020024B01461868FFF783B900BF8A -:1048E0001811002010B501390244904201D1002076 -:1048F00005E0037811F8014FA34201D0181B10BD49 -:104900000130F2E72DE9F041A3B1C91A177801444B -:10491000044603F1FF3C8C42204601D9002009E007 -:104920000578BD4204F10104F5D10CEB0405D6185D -:10493000A54201D1BDE8F08115F8018D16F801ED11 -:10494000F045F5D0E7E700001F2938B504460D46CD -:1049500004D9162303604FF0FF3038BD426C12B10A -:1049600052F821304BB9204600F030F82A46014673 -:104970002046BDE8384000F017B8012B0AD0591C7A -:1049800003D1162303600120E7E7002442F8254005 -:10499000284698470020E0E7024B01461868FFF7D9 -:1049A000D3BF00BF1811002038B5074D00230446BF -:1049B000084611462B60FFF71DF8431C02D12B68F7 -:1049C00003B1236038BD00BF543C0020FFF70CB892 -:1049D000034611F8012B03F8012B002AF9D1704787 -:1049E0006F72672E6172647570696C6F742E6633B6 -:1049F00030332D48574553430000000040A2E4F1F6 -:104A0000646891060041A3E5F26569920700000021 -:104A10004261642043414E496661636520696E646A -:104A200065782E00800000000080000000008000FB -:104A30000000000000000000351B000819230008DA -:104A400079220008451B0008791B0008751D000825 -:104A5000491B0008591B00084D1B0008551B000886 -:104A6000511B00089D1C00085D1B0008E52500087F -:104A70006D1B0008711C000863300000784A0008B4 -:104A800078380020483A00206D61696E0069646CD6 -:104A900065000000A001A82A00000000FAAABEAA32 -:104AA00050001424EFFF0000007700007097090009 -:104AB0000100000000000000AAAAAAAA010000004C -:104AC000FFFF0000000000000000000000000000E8 -:104AD00000000000AAAAAAAA00000000FFFF000030 -:104AE00000000000000000000000000000000000C6 -:104AF000AAAAAAAA00000000FFFF00000000000010 -:104B0000000000000000000000000000AAAAAAAAFD -:104B100000000000FFFF0000000000000000000097 -:104B20000000000000000000AAAAAAAA00000000DD -:104B3000FFFF000000000000000000000000000077 -:104B40009942000885420008C1420008AD420008B1 -:104B5000B9420008A5420008914200087D420008C1 -:104B6000CD4200087CB6FF7F01000000000000007D -:104B7000EC030000000000000098030000000000AB -:104B8000FE2A0100D20400001C11002000000000D9 -:104B90000000000000000000000000000000000015 -:104BA0000000000000000000000000000000000005 -:104BB00000000000000000000000000000000000F5 -:104BC00000000000000000000000000000000000E5 -:104BD00000000000000000000000000000000000D5 -:0C4BE000000000000000000000000000C9 +:1000000000090020B1010008E52200089D22000837 +:10001000C52200089D220008BD220008B301000887 +:10002000B3010008B3010008B3010008D932000889 +:10003000B3010008B3010008B3010008A94000089B +:10004000B3010008B3010008B3010008B3010008C0 +:10005000B3010008B30100088D3D0008B93D000858 +:10006000E53D0008113E00083D3E0008B3010008D0 +:10007000B3010008B3010008B3010008B301000890 +:10008000B3010008B3010008B301000851220008C1 +:100090007D2200088D220008B3010008693E000897 +:1000A000B3010008B3010008B3010008B301000860 +:1000B000B3010008B3010008B3010008B301000850 +:1000C000B3010008B3010008B3010008B301000840 +:1000D000B301000899420008AD420008B3010008CE +:1000E000D13E0008B3010008B3010008B3010008C5 +:1000F000B3010008B3010008B3010008B301000810 +:10010000B3010008B3010008B3010008B3010008FF +:10011000B3010008B3010008B3010008B3010008EF +:10012000B3010008B3010008B3010008B3010008DF +:10013000B3010008B3010008B3010008B3010008CF +:10014000B3010008B3010008B3010008B3010008BF +:10015000B3010008B3010008B3010008B3010008AF +:10016000B3010008B3010008B3010008B30100089F +:10017000B3010008B3010008B3010008B30100088F +:10018000B3010008B3010008B3010008B30100087F +:10019000B3010008B3010008B3010008B30100086F +:1001A000190F00080000000000000000000000001F +:1001B00002E000F000F8FEE772B6374880F30888E6 +:1001C000364880F3098836483649086040F2000016 +:1001D000CCF200004EF63471CEF200010860BFF39D +:1001E0004F8FBFF36F8F40F20000C0F2F0004EF669 +:1001F0008851CEF200010860BFF34F8FBFF36F8FBD +:100200004FF00000E1EE100A4EF63C71CEF2000114 +:100210000860062080F31488BFF36F8F03F06AFC38 +:1002200003F0DEFC4FF055301F491B4A91423CBFA2 +:1002300041F8040BFAE71D49184A91423CBF41F8C6 +:10024000040BFAE71A491B4A1B4B9A423EBF51F86E +:10025000040B42F8040BF8E700201849184A9142B1 +:100260003CBF41F8040BFAE703F048FC03F0F4FC50 +:10027000144C154DAC4203DA54F8041B8847F9E7D7 +:1002800000F042F8114C124DAC4203DA54F8041B52 +:100290008847F9E703F030BC000900200011002076 +:1002A0000000000808ED00E0000100200009002027 +:1002B00098480008001100207C11002080110020C7 +:1002C000543C0020A0010008A4010008A40100087B +:1002D000A40100082DE9F04F2DED108AC1F80CD0D3 +:1002E000C3689D46BDEC108ABDE8F08F002383F300 +:1002F00011882846A047002003F052F9FEE703F0DA +:10030000DBF800DFFEE70000F8B500F017FE03F0B1 +:1003100095FB074603F0E4FB064600283ED12B4B35 +:100320009F423BD001339F423BD0294B27F0FF0235 +:100330009A4239D1F8B200F03DFC354642F21074D1 +:1003400000F03EFC08B10024254601F0ADF878B37A +:10035000032000F043F80024254636B11D4B9F4290 +:1003600003D003F0B5FB00242546002003F070FB0A +:10037000194B1B6913F040031FD00DB100F044F876 +:1003800000F050FC01F0B6FF0546C4B101F0B2FF29 +:10039000401BA04213D900F037F8F3E7354600249C +:1003A000CEE704460125CBE705464FF47A74C7E74C +:1003B000B4F57A7F08BF0125CFE71C46E0E700F0DF +:1003C00079FC012003F0F2F8DFE700BF010007B07D +:1003D000000008B0263A09B000040048084B187025 +:1003E00003280CD8DFE800F008050208022000F01E +:1003F00001BE022000F0F6BD024B00225A60704799 +:10040000801100208411002038B501F04DF830B182 +:100410001F4B03221A701F4B00225A6038BD1E4B1F +:100420001E4A19680131F9D004339342F9D11C4CAA +:10043000194DD4F80428AA42F0D31A4B9B6803F153 +:10044000006303F5D0439A42E8D203F015FB03F0B2 +:1004500027FB002000F08CFD0220FFF7BFFF124BAE +:10046000DA690022DA61D96999699A619B6972B681 +:100470004FF0E0233021C3F8085DD4F80038D4F8F9 +:10048000042881F311889D4683F308881047C5E747 +:1004900080110020841100200068000820680008F6 +:1004A000006000080011002000100240094A136893 +:1004B00049F2690099B21B0C00FB01331360064B33 +:1004C000186844F2506182B2000C01FB020018600F +:1004D00080B27047141100201011002010B50021C7 +:1004E0001022044600F0A0FD034B03CB20606160A6 +:1004F0001868A06010BD00BFACF7FF1F2DE9F041E8 +:10050000ADF54E7D0DF134086CAC40F27512074626 +:100510000D460EA80021C8F8001000F085FD4FF42C +:10052000C4720021204600F07FFD01F0E3FE254B60 +:100530004FF47A72B0FBF2F0186093E807000223E0 +:1005400084E807000DF5E9702382FFF7C7FF4EF638 +:1005500003431D49238406A804F0D4F8182384F823 +:1005600032310DF2E3266B440DF1300C1A4603CA0A +:10057000624530607160134606F10806F6D14146C7 +:100580000122204600F09CFD00230393AB7E0293E2 +:1005900005F11903019380B20123CDE90480009392 +:1005A000E97E06A3D3E90023384602F06BFA0DF585 +:1005B0004E7DBDE8F08100BFAFF300809E6AC4218C +:1005C000818A46EE8C110020144700082DE9F04185 +:1005D0002C4C237ADAB080460D465BBB27A928460F +:1005E00000F07EFE0746002842D19DF89D60C82E8F +:1005F0003ED801464FF4A662204600F015FD4FF4A8 +:100600008073C4F8F8314FF40073C4F80C334FF41E +:100610004073C4F8203432460DF19E0104F1090004 +:1006200000F0F0FC26449DF89C30777223720BB9E1 +:10063000EB7E23728122002106AC27A800F0F4FC97 +:100640000122214627A800F087FE00230393AB7EFA +:10065000029305F1190380B201932823CDE90440E8 +:100660000093E97E05A3D3E90023404602F00AFA8D +:100670005AB0BDE8F08100BFAFF30080264172722E +:10068000DF25D7B7B0320020F0B5254E4FF48A757C +:1006900005FB0065F1B096F8D83085F8DC30002411 +:1006A000D822214685F8E8403AA800F0BDFC06F1C2 +:1006B000090000F0B1FCD5F8E4308DF8F000C2B2CA +:1006C00006AF06F109010DF1F100CDE93A3400F071 +:1006D00099FC394601223AA800F06AFE80B2CDE9C1 +:1006E000047008230127CDE9023706F1D8030193EE +:1006F00030230093317A0B4807A3D3E9002302F09B +:10070000C1F9A04206DD01F0F5FDC5F8E00038466C +:1007100071B0F0BD2046FBE778F6339F93CACD8DCC +:10072000B0320020A42100202DE9F0411D4D1E4EC5 +:100730001E4F86B0284602F0D1F9034658B3002474 +:10074000CDE90344ADF81440027B8DF8142099687C +:100750004068029403AA03C21B68DFF8548043F088 +:100760000043029301F0C8FD821941F10003009497 +:1007700002A9384601F072F8A04205DD284602F0D1 +:10078000B1F988F80040D5E798F80030072B05D874 +:10079000013388F8003006B0BDE8F081014802F06E +:1007A000A1F9F8E7A421002040420F00D821002041 +:1007B000E537002070B50D4614461E4602F0BEF81F +:1007C00050B9022E10D1012C0ED112A3D3E900236F +:1007D000C5E90023012007E0282C10D005D8012C02 +:1007E00009D0052C0FD0002070BD302CFBD10BA3FD +:1007F000D3E90023ECE70BA3D3E90023E8E70BA33D +:10080000D3E90023E4E70BA3D3E90023E0E700BF2B +:10081000AFF30080401DA12026812A0B78F6339F7C +:1008200093CACD8D9E6AC421818A46EE264172729A +:10083000DF25D7B7F017304A39059E5638B505463B +:100840000E4C0021013500F0B5FBA4F82C55B4F88E +:100850002C0500F097FB78B1B4F82C0500F0A2FB52 +:10086000014648B9B4F82C0500F0A4FBB4F82C35C7 +:100870000133A4F82C35EAE738BD00BFB0320020C0 +:1008800010B50A4B0A4A1A6003F5805393F86020AA +:100890003AB9DC6D2CB1204600F080FE204603F012 +:1008A00071FEBDE81040034800F078BED82100205A +:1008B0006C470008203200202DE9F04F8FB000AFC8 +:1008C00005460C4602F03AF8002849D1237E022B57 +:1008D0001BD1E38A012B18D101F00CFD0646FFF76E +:1008E000E5FD03464FF4C870DFF8C482B3FBF0F2B5 +:1008F00006F5167602FB103316FA83F3C8F80030BB +:10090000E37E33B9A34B00221A703C37BD46BDE8E5 +:10091000F08F07F12401204600F0A0FC0028F4D15C +:1009200007F11400FFF7DAFD97F8264007F11401EC +:10093000224607F1270003F06FFE0028E2D10F2CBA +:1009400008D8944B1C70D8F80030A3F51673C8F87B +:100950000030DAE797F82410284601F0E7FFD4E7E3 +:10096000E38A282B2BD010D8012B23D0052BCCD1F8 +:10097000BFF34F8F8849894BCA6802F4E062134382 +:10098000CB60BFF34F8F00BFFDE7302BBDD1844E4E +:10099000E17E327A9142B8D1607E3146002291F8F0 +:1009A000DC50854200F0A5800132042A01F58A71ED +:1009B000F5D1AAE721462846FFF7A0FDA5E7214685 +:1009C0002846FFF703FEA0E7B2F8EC507B6005F184 +:1009D00003094FEA99094FEA8902D11DC908A8EB1A +:1009E000C1039D46EB460021584600F01DFB04F173 +:1009F000EE012A463144584600F004FB7B6813B9E7 +:100A0000012000F0B5FA96F8D20000F0BBFA0446D7 +:100A100030B9307200F0D6FA204600F0A9FAB1E001 +:100A2000D6F8D4203AB996F8D200B6F82C258242EE +:100A300001D8FFF703FFD6F8D4202A44944208D205 +:100A400096F8D200B6F82C250130824201D8FFF783 +:100A5000F5FE70685FFA89F2594600F0EDFA08B9C0 +:100A6000C54679E0726896F8D2002A447260D6F8DA +:100A7000D42005EB0209C6F8D49000F083FA814532 +:100A800009D396F8D220D6F8D4000132001B86F89C +:100A9000D220C6F8D400FF2D0FD80024347200F005 +:100AA00091FA204600F064FA00F0FEFC3D4B1881FC +:100AB00008B9FFF7A9FCC54627E7BB6896F8D90037 +:100AC0000AFB0362FB68D2F8E41082F8E83001F513 +:100AD0008061C2F8E030C2F8E410FFF7D5FDFFF7FF +:100AE00023FE96F8D920013202F0030286F8D920BD +:100AF000B6E74FF48A7A0AFB02F505F1EA013144C0 +:100B0000204600F081FCF86000287FF4FEAE3544FA +:100B1000012285F8E82001F0EDFBD5F8E020D6EDC4 +:100B2000007ADFED216A801A192838BF192040F6B3 +:100B3000B832904228BF1046B8EE677A07EE900AA6 +:100B4000F8EEE77A67EEA67ADFED186AE7EE267A26 +:100B5000FCEEE77AC6ED007A96F8D930BB60BA6849 +:100B600073680AFB02F4321992F8E81059B1D2F80E +:100B7000E4108B42E8463FF427AF002182F8E810EA +:100B8000C2F8E010C5467368064A9B0A0133138118 +:100B9000BBE600BF9D21002000ED00E00400FA0547 +:100BA000B03200208C110020CDCCCC3D6666663F73 +:100BB000A0210020014B1870704700BF9811002041 +:100BC00038B54FF00054134B22689A4220D1124B93 +:100BD000627D12481A70237D03724FF48073C0F84F +:100BE000F8314FF40073C0F80C3300254FF4407314 +:100BF000C0F820340A49C0F8E450C922093000F096 +:100C000001FAE0222946204600F00EFA012038BD04 +:100C10000020FCE79AAD44C598110020B0320020B6 +:100C20001600002037B500F03FFC194D1949288106 +:100C30000223012218486B7101F0F8F90023019397 +:100C4000164B174900931748174B4FF4805201F089 +:100C500045FE164B197811B1124801F067FE01F0FC +:100C600049FB0446FFF722FC4FF4C873B0FBF3F2D4 +:100C700002FB130304F5167010FA83F00C4B186096 +:100C800002F02EFF08B10F232B8103B030BD00BF4F +:100C90008C11002040420F00D8210020B507000829 +:100CA0009C110020A4210020B90800089811002000 +:100CB000A02100202DE9F04F2DED028B8EA7D7E962 +:100CC00000670FF23C29D9E90089864C95B00DAD3B +:100CD0009FED828BFFF728FDDFF82CB200230C93E9 +:100CE000ADF83C300D936B6000230DF125028DEDC6 +:100CF000008B4FF0010A09A958468DF825308DF870 +:100D000024A001F041F99DF824200023002A40F09E +:100D1000AB80204601F012FE0546002847D1DFF8DF +:100D2000ECB101F0E7FADBF8003098423FD301F074 +:100D3000E1FA0790FFF7BAFB079A4FF4C873B0FBCC +:100D4000F3F101FB130302F5167010FA83F0CBF8F0 +:100D50000000DFF8BCB19BF800100791002914BF18 +:100D60002B46534610A88DF83030FFF7B7FB079994 +:100D7000C1F11002D2B2062A10AB28BF06221944D4 +:100D80000DF13100079200F03DF9079A0CAB039387 +:100D9000182302930132544BD2B2CDE900A304923E +:100DA0003B463246204601F00FFE8BF8005001F022 +:100DB000A1FA4E4A4E4D1368C31AB3F57A7F32D367 +:100DC000106001F099FA02460B46204601F094FEAD +:100DD000204601F0B3FD30B32B7ADFF838A1002BA9 +:100DE00014BF032302238AF8053001F083FA0DF1C2 +:100DF000400B4FF47A730122B0FBF3F05946CAF866 +:100E00000000504600F002FA18230293394B019378 +:100E100080B240F25513CDE903B0009342464B46F1 +:100E2000204601F0D1FD2B7ACBB101F063FA4FF0EF +:100E3000000A83464FF48A7295F8D900504400F0B6 +:100E4000030002FB005393F8E81089B30AF1010A8A +:100E5000BAF1040FF0D12B7A002B7FF438AF15B024 +:100E6000BDEC028BBDE8F08F4FF0904110A84A69AD +:100E700082F010024A611946102200F0D5F80DF1F7 +:100E800026030AAA0CA9584600F0E8FD95E80300DD +:100E900011AB83E803009DF83C308DF84C300C9B7F +:100EA000109310A9DDE90A23204601F0F9FF1BE7A2 +:100EB000D3F8E01049B12B68FA2B38BFFA23ABEB1B +:100EC00001010533B1EB430FC0D3FFF7DDFB4FF456 +:100ED0008A720028BAD1BEE7AFF30080000000009C +:100EE00000000000A42100209C210020E037002009 +:100EF000B0320020E4370020401DA12026812A0BBB +:100F0000F1C6A7C1D068080FD8210020A021002079 +:100F10009D2100208C11002008B5054800F03AFE04 +:100F2000BDE80840034A0449002003F025BB00BF88 +:100F3000D8210020203800208108000870B502F078 +:100F40000DFC094E094D3080002428683388834207 +:100F500008D902F0FFFB2B6804440133B4F5D04FED +:100F60002B60F2D370BD00BF14380020E83700209A +:100F700002F080BC00F10060920000F5D04002F069 +:100F800027BC0000054B1A68054B1B889B1A83423F +:100F900002D9104402F0DEBB00207047E837002081 +:100FA00014380020024B1B68184402F0D9BB00BF64 +:100FB000E8370020024B1B68184402F0E3BB00BF77 +:100FC000E8370020064991F8243033B10023086A3D +:100FD00081F824300822FFF7CDBF0120704700BF01 +:100FE000EC370020022802BF4FF0904310229A6194 +:100FF00070470000022802BF4FF090434FF4801268 +:101000009A61704710B50023934203D0CC5CC4545E +:101010000133F9E710BD000003460246D01A12F969 +:10102000011B0029FAD1704702440346934202D0C3 +:1010300003F8011BFAE770472DE9F8431F4D1446EA +:1010400095F824200746884652BBDFF870909CB381 +:1010500095F824302BB92022FF2148462F62FFF754 +:10106000E3FF95F82400C0F10802A24228BF2246FF +:10107000D6B24146920005EB8000FFF7C3FF95F81A +:101080002430A41B1E44F6B2082E17449044E4B248 +:1010900085F82460DBD1FFF795FF0028D7D108E061 +:1010A0002B6A03EB82038342CFD0FFF78BFF00282C +:1010B000CBD10020BDE8F8830120FBE7EC3700200E +:1010C0002DE9F0470D46044600219046284640F29F +:1010D0007912FFF7A9FF234620220021284601F0BC +:1010E00081FE231D02222021284601F07BFE631D84 +:1010F00003222221284601F075FEA31D032225218B +:10110000284601F06FFE04F108031022282128462A +:1011100001F068FE04F1100308223821284601F08E +:1011200061FE04F1110308224021284601F05AFE15 +:1011300004F1120308224821284601F053FE04F16D +:10114000140320225021284601F04CFE04F118031C +:1011500040227021284601F045FE04F120030822B8 +:10116000B021284601F03EFE04F121030822B821F7 +:10117000284601F037FE04F12207C0263B463146DF +:1011800008222846083601F02DFEB6F5A07F07F1AB +:101190000107F3D104F1320308223146284601F059 +:1011A00021FE002704F1330A94F832304FEAC709D0 +:1011B0009F4209F5A47615D3B8F1000F08D1314646 +:1011C00004F599730722284601F00CFE09F24F1628 +:1011D000274694F832213B1B93420CD3F01DC008E4 +:1011E000BDE8F0870AEB070308223146284601F0E4 +:1011F000F9FD0137D8E707F23313314608222846B4 +:1012000001F0F0FD08360137E3E7000013B50446AE +:101210000846002101602346C0F8031020220190F7 +:1012200001F0E0FD0198231D0222202101F0DAFDEA +:101230000198631D0322222101F0D4FD0198A31D12 +:101240000322252101F0CEFD019804F108031022AC +:10125000282101F0C7FD072002B010BDF7B500231B +:10126000047F00910E4607221946054601F07EFCD8 +:10127000731C0093012200230721284601F076FC0D +:10128000C4B9B31C0093052223460821284601F067 +:101290006DFC0D243746B278BB1B934211D32B7FD4 +:1012A000A88A0734E408BBB9844294BF0020012017 +:1012B00003B0F0BDAB8ADB00083BDB08B370082449 +:1012C000E8E7FB1C0093214600230822284601F092 +:1012D0004DFC08340137DEE7201A18BF0120E7E78C +:1012E000F7B50023047F00910E46082219460546F3 +:1012F00001F03CFC731CC4B908220093114623463C +:10130000284601F033FC1024012372785F1C013B56 +:10131000934211D32B7FA88A0734E408BBB98442D7 +:1013200094BF0020012003B0F0BDAB8ADB00083B76 +:10133000DB0873700824E7E7F319009321460023C4 +:101340000822284601F012FC08343B46DDE7201A4B +:1013500018BF0120E7E70000F8B50E460546144621 +:10136000002181223046FFF75FFE2B460822002134 +:10137000304601F037FD7CB96B1C0722082130464E +:1013800001F030FD0F2401236A785F1C013B93427A +:1013900004D3E01DC008F8BD0824F4E7EB1921468A +:1013A0000822304601F01EFD08343B46ECE7000001 +:1013B000F8B50E46054614460021CE223046FFF70A +:1013C00033FE2B4628220021304601F00BFD7CB96C +:1013D00005F1080308222821304601F003FD3024DE +:1013E0002F462A7A7B1B934204D3E01DC008F8BD28 +:1013F0002824F5E707F1090321460822304601F0C9 +:10140000F1FC08340137ECE7F7B5047F00910E4694 +:10141000012310220021054601F0A8FBC4B9B31C2A +:101420000093092223461021284601F09FFB19242E +:1014300037467288BB1B9A4211D82B7FA88A073483 +:10144000E408BBB9844294BF0020012003B0F0BD82 +:10145000AB8ADB00103BDB0873801024E8E73B1D00 +:101460000093214600230822284601F07FFB083420 +:101470000137DEE7201A18BF0120E7E730B5094D34 +:101480000A4491420DD011F8013B5840082340F323 +:101490000004013B2C4013F0FF0384EA5000F6D116 +:1014A000EFE730BD2083B8EDF7B5364A10685168D4 +:1014B0006B4603C36A4634493448082303F0BCF83A +:1014C000044690BB0A25324A106851686B4603C334 +:1014D0006A4630492D48082303F0AEF80446002838 +:1014E00047D00369B3F5663F43D8B0F86620B2F53C +:1014F0007B7F3ED1284A024402F15C018B4238D303 +:101500005C3B224900209E1AFFF7B8FF324607468F +:1015100004F164010020FFF7B1FFA3689F4228D1C6 +:10152000E368984208BF002523E00369B3F5663FEE +:1015300026D8428BB2F57B7F20D1174A024402F1B4 +:1015400010018B4218D3103B104900209D1AFFF761 +:1015500095FF2A46064604F118010020FFF78EFF8A +:10156000A3689E4202D1E368984201D00D25AAE704 +:101570000025284603B0F0BD1025A4E70C25A2E7FE +:101580000B25A0E730470008DC970300006800083F +:1015900039470008909703000898FFF710B5037CBF +:1015A000044613B9006803F02FF8204610BD000070 +:1015B0000023BFF35B8FC360BFF35B8FBFF35B8F11 +:1015C0008360BFF35B8F7047BFF35B8F0068BFF32F +:1015D0005B8F704770B505460C30FFF7F5FF05F1DE +:1015E000080604463046FFF7EFFFA04206D9304612 +:1015F0006D68FFF7E9FF2544281A70BD3046FFF7F4 +:10160000E3FF201AF9E7000070B50546406898B17D +:1016100005F10800FFF7D8FF05F10C060446304637 +:10162000FFF7D2FF8442304694BF6D680025FFF774 +:10163000CBFF013C2C44201A70BD000038B50C468D +:101640000546FFF7C7FFA04210D305F10800FFF7DA +:10165000BBFF04446868B4FBF0F100FB1144BFF326 +:101660005B8F0120AC60BFF35B8F38BD0020FCE7CF +:101670002DE9F041144607460D46FFF7C5FF8442A9 +:1016800028BF0446D4B1B84658F80C6B4046FFF763 +:101690009BFF3044286040467E68FFF795FF331A71 +:1016A0009C4203D86C600120BDE8F0816B60A41BF4 +:1016B0003B68AB602044E8600220F5E72046F3E792 +:1016C00038B50C460546FFF79FFFA04210D305F141 +:1016D0000C00FFF779FF04446868B4FBF0F100FBED +:1016E0001144BFF35B8F0120EC60BFF35B8F38BD0B +:1016F0000020FCE72DE9FF41884669460746FFF7D1 +:10170000B7FF6C4606B204EBC6060025B44209D00A +:101710006268206808EB0501FFF774FC6368083411 +:101720001D44F3E729463846FFF7CAFF284604B0B0 +:10173000BDE8F081F8B505460C300F46FFF744FFD1 +:1017400005F1080604463046FFF73EFFA04230464A +:1017500088BF6C68FFF738FF201A386020B1304628 +:101760002C68FFF731FF2044F8BD000073B5144624 +:1017700006460D46FFF72EFF844228BF044601901F +:10178000DCB101A93046FFF7D5FF019B33B93268C0 +:10179000C5E90233C5E9002401200CE09C4238BFB2 +:1017A00001942860019868608442F5D93368AB6081 +:1017B000241AEC60022002B070BD2046FBE7000056 +:1017C0002DE9FF410F466946FFF7D0FF6C4600B296 +:1017D00004EBC0050026AC4209D0D4F8048054F8CC +:1017E000081BB8194246FFF70DFC4644F3E73046A4 +:1017F00004B0BDE8F081000038B50546FFF7E0FF12 +:10180000044601462846FFF719FF204638BD000070 +:1018100010B4026854681A4623465DF8044B184712 +:10182000002070470020704770470000002070477C +:101830000E20704700F5805090F8C800C0F34000BB +:101840007047000000F5805090F9D000704700000C +:1018500000F58050C0F8CC1001207047F7B50C6837 +:10186000BDF8207014F0005470D10D7B082D6DD898 +:10187000302585F311884569AE6876010CD4AC68D3 +:10188000240108D4AC6814F080545DD184F311882D +:10189000204603B0F0BD01240E6804F1180C002EA0 +:1018A000B8BFF6004FEA0C1CB4BF46F0040676053C +:1018B00045F80C600E680FFA84FC16F0804F18BFD4 +:1018C00005EB0C1E05EB0C1C1EBFDEF8806146F01C +:1018D0000206CEF880610E7BCCF8846105EB04151E +:1018E0008E68C5F88C614E68C5F88861DCF8805157 +:1018F00045F00105CCF8805100EB441641F2680533 +:101900002E4405EB44150544C6E9002308350E4670 +:1019100001F10C0C56F804EB45F804EB6645F9D1DF +:10192000843436882E8000EB441407F003052679B2 +:1019300026F00B0635432571002484F311880097A7 +:1019400000F0FAFC0120A4E70224A5E74FF0FF30E5 +:101950009FE7000013B500F580540191E06DFFF79B +:1019600053FE1F280AD90199E06D2022FFF7C2FE1D +:10197000A0F120035842584102B010BD0020FBE7FF +:1019800008B5302383F3118800F58050C06DFFF750 +:101990000FFE002383F3118808BD000000220260BF +:1019A000828142608260704710B500220023C0E946 +:1019B00000230023044603810C30FFF7EFFF20468D +:1019C00010BD0000F0B5054600F580500C4690F8BB +:1019D000C83013F0040FC3F3800108BF114661F350 +:1019E000820304F1840680F8C83005EB461389B001 +:1019F0001B79D8072ED57AB319072DD46846FFF77F +:101A0000D3FF05EB441303F5835303F1180703AA2F +:101A1000103318685968144603C40833BB42224681 +:101A2000F7D1186820609B88A380DDE90E23CDE9FB +:101A300000230123ADF808302B686946DB6B28468C +:101A4000984705EB46152B791A075CBF43F008034E +:101A50002B7101E0002AF4D109B0F0BD2DE9F04767 +:101A60009A4688B0074688469146302383F311880A +:101A700007F580546846FFF797FFE06DFFF7AAFD72 +:101A80001F282AD9E06D20226946FFF7B5FE2028DD +:101A900023D103AD444605AB2E4603CE9E422060C3 +:101AA0006160354604F10804F6D130682060B388DF +:101AB000A380DDE90023C9E90023BDF80830AAF8B6 +:101AC0000030002383F3118853464A464146384686 +:101AD00008B0BDE8F04700F01DBC002080F311887D +:101AE00008B0BDE8F08700002DE9F84F0023C0E9F9 +:101AF0000133254B044640F8183B0F46FFF74EFFD5 +:101B000004F12800FFF750FF04F1480804F582555E +:101B10004646083530462036FFF746FFAE42F9D13B +:101B200004F580554FF480534FF00009C5E913398F +:101B3000C5F848800123EE6504F5875804F58456FE +:101B4000C5F8549085F8583085F86030083608F1AB +:101B500008084FF0000A4FF0000B46E908ABA6F169 +:101B60001800FFF71BFF203646F8289C4645F4D1A5 +:101B700085F8D07017B1054800F0B6FB044B6361DF +:101B80002046BDE8F88F00BF6C47000844470008B6 +:101B90000064004010B5044B197804464A1C1A70C2 +:101BA000FFF7A2FF204610BD1C3800202DE9F047AA +:101BB000002950D0294B2A4FB7FBF1F599428CBF31 +:101BC0000A231123581EB5FBF3FC03FB1C53C4B2BC +:101BD0002BB102280346F5D80020BDE8F0870CF1B0 +:101BE000FF36B6F5806FF7D2C4EBC40E0EF10303D7 +:101BF0004FEAE309C3F3C703A4EB030809F1010AA1 +:101C00004FF47A755FFA88F009FB05555AFA88F89F +:101C1000B5FBF8F5B5F5617FC1BF0EF1FF33C3F336 +:101C2000C703E01AC0B25C1C50FA84F40CFB04F445 +:101C3000B7FBF4F4A142CFD1013BDBB20F2BCBD8E1 +:101C40000138C0B20728C7D80021107116809170E2 +:101C5000D3700120C1E70846BFE700BF3F420F0035 +:101C60000051250270B505460E464FF47A746B6933 +:101C70005B6803F00103B3424FF0010004D001F0B0 +:101C800095FC013CF3D1204670BD000030B542699F +:101C9000936913F0700F16D000230B4C936103F17E +:101CA000840200EB421211794D0709D5890707D547 +:101CB000416954F823508D60117941F0040111718C +:101CC0000133032BEBD130BD5847000873B51D46D7 +:101CD000436916469A68D207044609D59A680121D5 +:101CE0009960C2F34002CDE900650021FFF76AFE6A +:101CF00063699A68D1050BD59A684FF48071996031 +:101D0000C2F34022CDE9006501212046FFF75AFECB +:101D100063699A68D2030BD59A684FF48031996051 +:101D2000C2F34042CDE9006502212046FFF74AFE9A +:101D300004F58053D3F8CC0010B103681B699847B1 +:101D4000204602B0BDE87040FFF7A0BFF8B50446DA +:101D50004669002972D106F10C073868800770D0F7 +:101D600006EB01153868D5F8B00110F0040FD5F86E +:101D7000B0011ABFC00840F00040400DA061D5F886 +:101D8000B0C11CF0020F1CBF40F08040A061D5F82C +:101D9000B40106EB011100F00F0084F82400D1F823 +:101DA000B8012077D1F8B801000A6077D1F8B801FE +:101DB000000CA077D1F8B801000EE077D1F8BC0193 +:101DC00084F82000D1F8BC01000A84F82100D1F881 +:101DD000BC01000C84F82200D1F8BC11090E84F873 +:101DE00023103821396004F1340004F1180104F1A2 +:101DF000240551F8046B40F8046BA942F9D1098815 +:101E00000180C4E90A2321460023238651F8283B98 +:101E10002046DB6B984704F5805393F8C820D3F82D +:101E2000CC0042F0040283F8C82010B103681B699B +:101E300098472046BDE8F840FFF728BF06F1100795 +:101E40008BE7F8BD10B5044600F056FA02460B4683 +:101E500052EA030102D0013A63F100030449086821 +:101E600020B12146BDE81040FFF770BF10BD00BF94 +:101E700018380020F0B5302181F31188DFF848C010 +:101E800000F583510831002404F1840500EB451569 +:101E90002E7977070ED4F6060CD5D1E90076974255 +:101EA0009E4107D246695CF82470B7602E7946F0EF +:101EB00004062E710134032C01F12001E4D100232A +:101EC00083F31188F0BD00BF5847000808B53023E0 +:101ED00083F31188FFF7DAFE002383F3118808BD2E +:101EE000F8B543690546986800F0E050B0F1E05F4E +:101EF0000F4621D0F8B1302383F3118805F58354C0 +:101F00001034002606F1840305EB43131B791A07EE +:101F100006D50136032E04F12004F3D1012007E099 +:101F20005B07F6D42146384600F040FA0028F0D18D +:101F3000002383F31188F8BD0120FCE708B53023A6 +:101F400083F3118800F58050C06DFFF743FB002339 +:101F500083F3118843090CBF0120002008BD000055 +:101F6000F8B51D46002313700F4606461446FFF7CA +:101F7000E5FF80F00100387025B129463046FFF7B3 +:101F8000AFFF2070F8BD00002DE9B8410C461546A2 +:101F90001F46804600F0B0F90B462178024609B989 +:101FA000287850B14046FFF765FFFFF78FFF3B46AB +:101FB0002A462146FFF7D4FF0120BDE8B881000082 +:101FC00070B5302686F31188174BDA6942F000723B +:101FD000DA611A6942F000721A611A6922F000721D +:101FE0001A61002383F3118800F5805494F8C830F7 +:101FF00013F0010516D1A9B186F31188032113202E +:1020000001F0C8F90321142001F0C4F903211520BF +:1020100001F0C0F994F8C83043F0010384F8C830E7 +:1020200085F3118870BD00BF001002402DE9F04714 +:1020300000F5805588B095F8D030012B04468846CD +:10204000164600F28180814F57F823200AB947F8DD +:102050002300D7F800A0C4F80C802674BAF1000F52 +:1020600064D095F8D030012B70D001212046FFF7C5 +:10207000A7FF302383F311886269136823F00203FA +:1020800013606269136843F00103136063690027FA +:102090005F6187F3118801212046FFF7E3FD0028E7 +:1020A00000F09580E86DFFF783FA04F58359BA468E +:1020B00009F10809202200216846FEF7B5FF02A8B1 +:1020C000FFF76CFCCDF818A06A4609EB07030DF189 +:1020D000180E9446BCE80300F44518605960624647 +:1020E00003F10803F5D1DCF80000186020379CF8F4 +:1020F00004201A71602FDDD195F8C8306FF3820388 +:10210000002785F8C8306A4641462046ADF8007081 +:10211000ADF802708DF80470FFF748FD636948BBA5 +:102120004FF400421A6008B0BDE8F08741F2D800D1 +:1021300002F02AFA814610B15146FFF7D5FCC7F8E4 +:102140000090B9F1000F8CD10020ECE738680368EB +:102150001B6B98470146002887D13868FFF730FF8E +:102160003868036832465B684146984700287FF428 +:102170007CAFE9E761221A609DF802309DF80320E8 +:102180001B06120402F4702203F040731343BDF8DF +:102190000020C2F3090213439DF804201205022E09 +:1021A00002F4E0020CBF4FF00041002113436269CA +:1021B0000B43D361636913225A616269136823F088 +:1021C0000103136039462046FFF74CFD08B96369E7 +:1021D000A6E795F8D03093BB6169D1F8002242F0B0 +:1021E0000102C1F800226169D1F8002222F47C5278 +:1021F00022F00E02C1F800226169D1F8002242F4F7 +:102200006062C1F800226269C2F814326269C2F8E1 +:102210000432626941F6FF71C2F80C126269C2F8B9 +:1022200040326269C2F8443263690122C3F81C2259 +:102230006269D2F8003223F00103C2F8003295F847 +:10224000C83043F0020385F8C8306CE71838002026 +:1022500008B500F051F850EA0103024602D0421ED0 +:1022600061F10001044B186810B10B46FFF72EFD19 +:10227000BDE8084001F064B81838002008B5002017 +:10228000FFF7E0FDBDE8084001F05AB808B50120AD +:10229000FFF7D8FDBDE8084001F052B800B59BB08B +:1022A000EFF3098168226846FEF7ACFEEFF3058381 +:1022B000014B9B6BFEE700BF00ED00E008B5FFF7A8 +:1022C000EDFF000000B59BB0EFF30981682268467E +:1022D000FEF798FEEFF30583014B5B6BFEE700BF53 +:1022E00000ED00E0FEE700000FB408B5029801F031 +:1022F0000DF9FEE701F040BB01F0ECBA13B56C46F6 +:1023000084E80600031D94E8030083E8050001202B +:1023100002B010BD73B58568019155B11B885B078C +:1023200007D4D0E900369B6B9847019AC1B230467A +:10233000A847012002B070BDF0B5866889B0054697 +:102340000C465EB1BDF838305B070AD4D0E90037DF +:102350009B6B98472246C1B23846B047012009B06E +:10236000F0BD00220023CDE900230023ADF80830A2 +:102370000A4603AB01F10806106851681C4603C405 +:102380000832B2422346F7D1106820609288A280BA +:10239000FFF7B2FF0423ADF808302B68CDE9000148 +:1023A000DB6B694628469847D8E7000030B50368DC +:1023B0000968DD0FB5EBD17F23F0604421F0604266 +:1023C0004FEAD1700BD0002BB8BFA40C0029B8BFC6 +:1023D000920C944202D034BF0120002030BD9442C0 +:1023E00005D1C1F38070C3F380738342F6D1944268 +:1023F0002CBF00200120F1E72DE9F041456A15B915 +:102400004162BDE8F0814B6823F06047C3F38A4620 +:102410004FEAD37EC3F3807816EA230638BF3E46E0 +:10242000AC462B465A68BEEBD27F22F060440AD0FD +:10243000002A18DAA40CB44217D19D420FD10D60C6 +:10244000DEE71346EEE7A74207D102F08044C2F36D +:10245000807242450BD054B1EFE708D2EDE7CCF8DB +:1024600000100B60CDE7B44201D0B442E5D81A6841 +:102470009C46002AE5D11960C3E700002DE9F0472A +:10248000089D01F007044FEAD508224405F007052E +:1024900000EBD1004FF47F49944201D1BDE8F087B1 +:1024A00004F0070705F0070A57453E4638BF564671 +:1024B000C6F10806111B8E4228BF0E46E10808EB44 +:1024C000D50E415C13F80EC0B94029FA06F721FA7F +:1024D0000AF1FFB28CEA010147FA0AF739408CEAA7 +:1024E000010C03F80EC034443544D5E780EA0120DE +:1024F000082341F2210201B24000002980B203F119 +:10250000FF33B8BF504013F0FF03F4D17047000011 +:1025100038B50C468D18A54200D138BD14F8011B02 +:10252000FFF7E4FFF7E7000042684AB11368436031 +:102530004389818901339BB29942438138BF8381AA +:102540001046704770B588B0202204460D46684694 +:102550000021FEF769FD20460495FFF7E5FF0246DE +:1025600058B16B46054608AE1C4603CCB442286001 +:102570006960234605F10805F6D1104608B070BD24 +:10258000082817D909280CD00A280CD00B280CD001 +:102590000C280CD00D280CD00E2814BF4020302061 +:1025A00070470C2070471020704714207047182087 +:1025B0007047202070470000082817D90C280CD934 +:1025C00010280CD914280CD918280CD920280CD97B +:1025D00030288CBF0F200E207047092070470A203A +:1025E00070470B2070470C2070470D20704700008B +:1025F0002DE9F843078C072F04461ED9D0E902982D +:1026000000254FF6FF73C5F12006A5F1200029FA39 +:1026100005F108FA06F628FA00F031430143C9B281 +:102620001846FFF763FF0835402D0346EBD1E169FB +:102630003A46BDE8F843FFF76BBF4FF6FF70BDE8C1 +:10264000F883000010B54B6823B9CA8A63F3090206 +:10265000CA8210BD04691A681C600361C38A013B09 +:10266000C3824A60EFE700002DE9F84F1D46CB8A90 +:102670000F46C3F309010529814692460B4630D027 +:102680000020AAB207F11A049EB2042E1FFA80F8A5 +:102690000FD8904503F1010306D3FB8A0A4462F385 +:1026A0000903FB8201201AE01AF80060E6540130A9 +:1026B000EAE79045F1D2A1F1050B1C237C68BBFB36 +:1026C000F3F203FB12BB1FFA8BF6002C45D14846F0 +:1026D000FFF72AFF044638B978606FF00200BDE8C2 +:1026E000F88F4FF00008E6E7002606607860ADB28C +:1026F0004FF0000B454510D90AEB0803221D13F8D3 +:10270000011B9155B1B208F101081B291FFA88F885 +:102710002BD0454506F10106F1D8FB8AC3F3090227 +:10272000154465F30903BCE7013292B21C462368E5 +:10273000002BF9D16B1F0B441C21B3FBF1F30133C8 +:102740009BB29A42D3D2BBF1000FD0D14846FFF7DB +:10275000EBFE20B9C4F800B0BFE70122E7E7C0F8FC +:1027600000B05E4620600446C1E74545D5D94846DD +:10277000FFF7DAFE08B92060AFE7C0F800B0002626 +:1027800020600446B6E700002DE9F04F2DED028BE6 +:102790001C4683B05B69019207468846002B00F017 +:1027A0009A80238C2BB1E269002A00F09480072BD9 +:1027B00035D807F10C00FFF7B7FE054638B96FF0C2 +:1027C0000205284603B0BDEC028BBDE8F08F142251 +:1027D0000021FEF729FC228CE16905F10800FEF7D3 +:1027E00011FC208C013080B2FFF7E6FEFFF7C8FE37 +:1027F000013880B22084013028746369228C1B78F0 +:102800002A4403F01F0363F03F0348F000411372B2 +:10281000384669602946FFF7EFFD0125D1E700F151 +:102820000C034FF0000908EE103A4FF0800A4E46B4 +:102830004D4618EE100AFFF777FE83460028BED0FB +:1028400014220021FEF7F0FB002E3AD1019BABF8D9 +:10285000083002220BF1080E1FFA82FC0CF1010075 +:10286000BCF1060F218C80B201D88E422BD3FFF72A +:10287000A3FEFFF785FE62691278013802F01F029D +:102880008E4208BF4FF0400A42EA49121BFA80F11B +:102890004AEA020A013048F0004281F808A08BF8A9 +:1028A0001000CBF8042059463846FFF7A5FD238CCD +:1028B0000135B3422DB289F001094FF0000AB8D1B9 +:1028C0007FE70022C6E7E169895D0EF80210013654 +:1028D000B6B20132C0E76FF0010572E7F8B51546F0 +:1028E0000E463022002104461F46FEF79DFB069B44 +:1028F0006360B5F5001F079BA76034BF6A094FF6F8 +:10290000FF72A36297B2E66104F1100000239A42BD +:1029100006D800230360A782E3822383E360F8BD27 +:102920000660013330462036F1E7000003781BB91A +:102930004BB2002BC8BF0170704700000078704791 +:10294000F8B50C46C969074611B9238C002B37D15D +:10295000257E1F2D34D8387828BB228C072A2CD806 +:10296000268A36F003032BD14FF6FF70FFF7D0FD18 +:1029700020F001003102400441EA0561400C41EAC7 +:1029800040254FF6FF72234629463846FFF7FCFEE6 +:10299000002807DD626913780133DBB21F2B88BF83 +:1029A00000231370F8BD218A2D0645EA0125054351 +:1029B0002046FFF71DFE0246E5E76FF00300F1E752 +:1029C0006FF00100EEE7000070B58AB004461646CD +:1029D0000021282268461D46FEF726FBBDF8383048 +:1029E000ADF810300F9B05939DF840308DF81830EE +:1029F000119B07936946BDF84830ADF8203020465A +:102A0000CDE90265FFF79CFF0AB070BD2DE9F041EA +:102A1000D36905460C4616460BB9138C5BBB377E53 +:102A20001F2F28D895F80080B8F1000F26D0304627 +:102A3000FFF7DEFD3378210241EAC33141EA0801A4 +:102A4000338A41EA076141EA03410246334641F0D5 +:102A500080012846FFF798FE00280ADD3378012B15 +:102A600007D1726913780133DBB21F2B88BF0023B3 +:102A70001370BDE8F0816FF00100FAE76FF003001A +:102A8000F7E70000F0B58BB004460D46174600216D +:102A9000282268461E46FEF7C7FA9DF84C305A1E9B +:102AA000534253418DF800309DF84030ADF810305E +:102AB000119B05939DF848308DF81830149B0793AF +:102AC0006A46BDF85430ADF8203029462046CDE99D +:102AD0000276FFF79BFF0BB0F0BD0000406A00B12B +:102AE00004307047436A1A68426202691A600361DF +:102AF000C38A013BC38270472DE9F041D0F82080A2 +:102B0000194E14461D464146002709B9BDE8F0811B +:102B1000D1E90223A21A65EB0303964277EB030384 +:102B20001ED2036A8B420DD1FFF78CFD036A1B682E +:102B3000036203690B60C38A0161016A013BC382BE +:102B40008846E2E7FFF77EFD0B68C8F800300369AE +:102B50000B60C38A0161013BC382D8F80010D4E73F +:102B600088460968D1E700BF80841E002DE9F04F38 +:102B70008BB00D46DDF8509014469B4680460028E9 +:102B800000F01981B9F1000F00F01581531E3F2BA1 +:102B900000F21181012A03D1BBF1000F40F00B813B +:102BA0000023CDE90833B8F81430B5EBC30F4FEA72 +:102BB000C30703D300200BB0BDE8F08F2B199F4251 +:102BC000D8F80C303ABF7F1BFFB227461BB9D8F8A4 +:102BD0001030002B7AD0272D4ED8C5F12806B742E9 +:102BE0004FF000032CBFF6B23E4600932946D8F8BA +:102BF000080008AB3246FFF741FCA7EB060A354454 +:102C00005FFA8AFAB8F8143003F10053053BDB0091 +:102C10000493D8F80C3003932821039B13B1BAF125 +:102C2000000F2CD1D8F8100040B1BAF1000F05D038 +:102C3000009608AB5246691AFFF720FC38B2002F05 +:102C4000B8D066070AD00AAB03EBD401624211F890 +:102C5000083C02F00702134101F8083C082C3CD95B +:102C6000102C40F2B580202C40F2B780BBF1000F51 +:102C700000F09C80082334E0BA460026C2E7049B9B +:102C8000E02B28BFE02306930B44AB42059314D9F5 +:102C90005A1B03980096924534BF5246D2B2691A25 +:102CA00008AB04300792FFF7E9FB079A1644AAEB3A +:102CB000020A1544F6B25FFA8AFA049B069A05994D +:102CC0009B1A0493039B1B680393A6E70093D8F811 +:102CD000080008AB3A462946AEE7BBF1000F13D017 +:102CE0000123B4EBC30F6CD0082C12D89DF8203010 +:102CF000621E23FA02F2D50706D54FF0FF3202FA20 +:102D000004F423438DF820309DF8203089F80030FA +:102D100051E7102C12D8BDF82030621E23FA02F2BF +:102D2000D10706D54FF0FF3202FA04F42343ADF881 +:102D30002030BDF82030A9F800303CE7202C0FD817 +:102D40000899631E21FA03F3DA0705D54FF0FF3225 +:102D500002FA04F40C430894089BC9F800302AE7EF +:102D6000402C2BD0DDE90865611EC4F12102A4F1DD +:102D7000210326FA01F105FA02F225FA03F31143C1 +:102D80001943CB0712D50122A4F12003C4F120017D +:102D900002FA03F322FA01F1A240524243EA01038C +:102DA00063EB430332432B43CDE90823DDE90823DA +:102DB000C9E90023FFE66FF00100FCE66FF00800B0 +:102DC000F9E6082CA0D9102CB3D9202CEED8C3E7F3 +:102DD000BBF1000FADD0022383E7BBF1000FBBD0E6 +:102DE00004237EE730B5012A144638BF0124402C65 +:102DF00085B028BF40240025012ACDE9025518D806 +:102E00001B788DF8083063070AD004AB03EBD405B8 +:102E1000624215F8083C02F00702934005F8083CAE +:102E2000009103462246002102A8FFF727FB05B0C8 +:102E300030BD082AE4D9102A03D81B88ADF8083021 +:102E4000E1E7202A8DBFD3E900231B680293CDE977 +:102E50000223D8E710B5CB681BB98B600B618B825E +:102E600010BD04691A681C600361C38A013BC382F8 +:102E7000CA60F0E703064CBFC0F3C03002207047C1 +:102E800008B50246FFF7F6FF022806D15306C2F343 +:102E90000F2001D100F0030008BDC2F30740FBE79B +:102EA0002DE9F04F93B0CDE903230A68044610469C +:102EB000FFF7E0FF022814BFC2F306260026002A0F +:102EC0000D46824680F2F28112F0C04940F0EE8158 +:102ED000097B002900F0EA81022803D02378B3425D +:102EE00040F0E781C2F304630693104602F07F03CB +:102EF0000593FFF7C5FF059B29444FEA834848EA3D +:102F00000A4848EA4668CE7800230022CDE9082323 +:102F1000F309834648EA0008029367D0059B0093B3 +:102F200002466768534608A92046B847002800F0C3 +:102F3000C381276A4FB9414604F10C00FFF702FB39 +:102F4000074690B96FF0020054E03B6998450DD0F8 +:102F50003F68002FF9D1414604F10C00FFF7F2FA67 +:102F600007460028EED0236A3B60276297F817C017 +:102F700006F01F08CCF3840CACEB08001FFA80FEAF +:102F80000028B8BF0EF12000A8EB0C031FFA83FE47 +:102F9000D7E90221B8BF00B2002B0793BEBF0EF1E4 +:102FA00020031BB2079352EA010338D0039BDFF8DA +:102FB00024E39A1A049B4FF0000C63EB0101964541 +:102FC0007CEB01032BD36B7B97F81AE0734519D187 +:102FD000029B002B78D0012821DC7868F8B9DFF853 +:102FE000F0C2944570EB010316D337E0276A27B986 +:102FF0006FF00C0013B0BDE8F08F3B699845B5D079 +:103000003F68F4E7B24890427CEB010301D3002013 +:10301000F0E7029B002BFAD0079B0F2B17DCFA7D01 +:10302000B30002F0030203F07C031343FB7539463F +:103030002046FFF707FB6B7BBB76029B3BB9FB7D12 +:10304000C3F38402013262F38603FB75D0E76A7B27 +:10305000BB7E9A42DBD1029B002B35D0B309022BF9 +:1030600032D0039BBB60049BFB60142200210DA89F +:10307000FDF7DAFF039B0A93049B0B932B1D0C9324 +:103080002B7BADF83EB0013BDBB2ADF83C30069B8C +:103090008DF84230059B8DF8433094F82C308DF834 +:1030A00040A083F001038DF844308DF84180A3687F +:1030B0000AA920469847FB7DC3F38403013303F03C +:1030C0001F039B02FB82A2E7FB7DC6F34012B2EB1B +:1030D000D31F40F0F480C3F38403434540F0F280F3 +:1030E000029A2B7BB609002A4DD0F2075DD4032B40 +:1030F00040F2EB80039BBB60049BFB602B7BAE1D0F +:10310000033BDBB23246394604F10C00FFF7ACFA60 +:1031100000280CDA39462046FFF794FAFB7DC3F30A +:103120008403013303F01F039B02FB820AE7DDE9FE +:103130000884AB883B834FF6FF73C9F12000A9F1E7 +:10314000200228FA09F104FA00F0014324FA02F2FD +:1031500011431846C9B2FFF7C9F909F10809B9F1D5 +:10316000400F0346E9D1B8822A7B033AD2B23146F6 +:10317000FFF7CEF9FB7DB882DA43C2F3C01262F3E7 +:10318000C713FB7543E786B92E1D013BDBB2324600 +:10319000394604F10C00FFF767FA0028BADB2A7BF6 +:1031A000B88A013AD2B23146E2E7F98AC1F309019D +:1031B000013B0429DAB25BD8281D002307F11B0666 +:1031C0009A4208D910F801CB06F801C00131013349 +:1031D0000529DBB2F4D103990A9104990B9193422A +:1031E00007F11B010C9138BF043379680D9134BF8E +:1031F00055FA83F300230E93FB8AADF83EB0C3F378 +:1032000009031A44069B8DF84230059B8DF8433024 +:1032100094F82C30ADF83C2083F001038DF8443055 +:1032200000238DF840A08DF841807B602A7BB88A0E +:10323000013A291DFFF76CF93B8BB882834203D119 +:10324000A3680AA92046984720460AA9FFF702FE6C +:10325000FB7DBA8AC3F38403013303F01F039B028F +:10326000FB823B8B9A420CBF00206FF01000C1E63E +:103270007B68002BAFD0052001E01C3033461E6870 +:10328000002EFAD1091A081D2E1D184401EB090C55 +:10329000BCF11B0F5FFA89F39DD89A429BD916F8AF +:1032A000013B00F8013B09F10109EFE76FF009006C +:1032B000A0E66FF00A009DE66FF00B009AE66FF053 +:1032C0000D0097E66FF00E0094E66FF00F0091E6A8 +:1032D00040420F0080841E00EFF3098305494A6BCA +:1032E00022F001024A63683383F30988002383F3E1 +:1032F0001188704700EF00E0302080F3118862B63B +:103300000C4B0D4AD96821F4E0610904090C0A4309 +:10331000DA60D3F8FC20094942F08072C3F8FC203F +:103320000A6842F001020A602022DA7783F822005C +:10333000704700BF00ED00E00003FA05001000E058 +:1033400010B5302383F311880E4B5B6813F40063D0 +:1033500014D0F1EE103AEFF30984683C4FF080731B +:10336000E361094BDB6B236684F3098800F098F86E +:1033700010B1064BA36110BD054BFBE783F3118829 +:10338000F9E700BF00ED00E000EF00E0FF020008F9 +:103390000203000800F1604303F561430901C9B26B +:1033A00083F80013012200F01F039A4043099B0099 +:1033B00003F1604303F56143C3F880211A6070474D +:1033C00000F16040090100F56D40C9B20176704717 +:1033D00000230375826803691B6899689142FBD2D8 +:1033E0005A6803604260106058607047002303759C +:1033F000826803691B6899689142FBD85A68036028 +:10340000426010605860704708B50846302383F367 +:1034100011880B7D032B05D0042B0DD02BB983F322 +:10342000118808BD8B6900221A604FF0FF33836159 +:10343000FFF7CEFF0023F2E7D1E9003213605A60B4 +:10344000F3E70000FFF7C4BF054BD968087518689B +:1034500002681A60536001220275D860FCF73ABF17 +:103460002838002030B50C4BDD684B1C87B0044673 +:103470000FD02B46094A684600F0D8F82046FFF7DF +:10348000E3FF009B13B1684600F0DAF8A86907B0C3 +:1034900030BDFFF7D9FFF9E72838002009340008CC +:1034A000044B1A68DB6890689B68984294BF0020C0 +:1034B0000120704728380020084B10B51C68D868D8 +:1034C00022681A60536001222275DC60FFF78EFFCC +:1034D00001462046BDE81040FCF7FCBE283800201D +:1034E00038B5074C0749084801230025237065605B +:1034F00000F024FB0223237085F3118838BD00BF40 +:10350000503A0020B04700082838002008B572B6AD +:10351000044B186500F0C2F900F0ACFA024B03222C +:103520001A70FEE728380020503A002000F09AB8C0 +:103530008B60022308618B82084670478368A3F181 +:10354000840243F8142C026943F8442C426943F87E +:10355000402C094A43F8242CC26843F8182C022254 +:1035600003F80C2C002203F80B2C044A43F8102C0F +:10357000A3F12000704700BFED02000828380020AA +:1035800008B5FFF7DBFFBDE80840FFF75BBF0000B1 +:10359000024BDB6898610F20FFF756BF28380020E8 +:1035A000302383F31188FFF7F3BF000008B501460D +:1035B000302383F311880820FFF754FF002383F39F +:1035C000118808BD064BDB6839B1426818605A6043 +:1035D000136043600420FFF745BF4FF0FF30704792 +:1035E000283800200368984206D01A6802605060AC +:1035F00099611846FFF726BF7047000010B50A4CC6 +:1036000023699A6891420CD85A68816003604260CD +:1036100010609A685860511A99604FF0FF33A361A7 +:1036200010BD1B68891AECE72838002010B4C0E9E7 +:10363000032300235DF8044B4361FFF7DFBF000065 +:10364000036881689A680A449A60426813605A6005 +:1036500000230360024B4FF0FF329A61704700BFB6 +:103660002838002070B5124DEB692A460133EB6112 +:1036700052F8103F934206D09A68013A9A60302679 +:103680002C69A36803B170BDD4E900210A605160C0 +:10369000236083F31188D4E903312046984786F3E9 +:1036A000118861690029EBD02046FFF7A7FFE7E703 +:1036B00028380020054A30B5D369D2E908451B1BDC +:1036C000181945F10001C2E9080130BD2838002071 +:1036D00000207047FEE70000704700004FF0FF3009 +:1036E00070470000BFF34F8F024AD368DB07FCD45A +:1036F000704700BF0020024008B5074B1B7853B944 +:10370000FFF7F0FF054B1A69120641BF044A5A60E1 +:1037100002F188325A6008BD683A00200020024059 +:103720002301674508B5054B1B7833B9FFF7DAFF6E +:10373000034A136943F08003136108BD683A00200F +:10374000002002407F289ABF00F58030C002002090 +:10375000704700004FF40060704700008020704701 +:103760007F2808B50BD8FFF7EDFF00F5006302686E +:10377000013204D104308342F9D1012008BD002078 +:10378000FCE700007F2810B504461CD8FFF7AAFF0D +:10379000FFF7B2FF0D4BF322DA6002221A61FFF746 +:1037A000D1FF58611A6942F040021A614FF400617A +:1037B000FFF798FF00F05AF9FFF7B4FF2046BDE885 +:1037C0001040FFF7CDBF002010BD00BF0020024019 +:1037D0002DE9F84312F00103144606D01F4B40F2C6 +:1037E00003321A600020BDE8F88385181C4A954210 +:1037F00004D91A4A4FF442711160F3E7FFF77CFFD6 +:10380000FFF770FFDFF86880451A4FF00109012CBF +:1038100005EB01060F4603D8FFF784FF0120E2E71E +:103820003B88C8F8109033800020FFF75BFFC8F892 +:103830001000338831F8022B9BB29A420CD0074B10 +:1038400040F21F321A60074B1E60074B1C60074B8B +:103850001F60FFF767FFC6E7023CD8E7643A002025 +:1038600000000408583A0020603A00205C3A00202A +:1038700000200240084908B50B7828B11BB9FFF7B2 +:103880003BFF01230B7008BD002BFCD0BDE80840B6 +:103890000870FFF747BF00BF683A002008B5064828 +:1038A0004FF41F4100F0E4F8BDE808404FF4005128 +:1038B0004FF0805000F0DCB80001002008461146AF +:1038C00000F084BE012000F081BE0000084600F038 +:1038D0009BBE000038B5EFF31185BDBBEFF3058447 +:1038E000C4F308043023C4B183F31188FFF7E2FE68 +:1038F0004C014201121A44EAD06464EB01049300C3 +:10390000A4001B1844EA927441EB0401C900D800DA +:1039100041EA537185F3118838BD83F31188FFF7AD +:10392000C9FE4D014201121A45EAD06565EB010559 +:103930009300AD001B1845EA927541EB0501C900E3 +:10394000D80041EA537184F3118838BDFFF7B2FE05 +:103950004B014401241A43EAD06363EB0103A20044 +:103960009B00121843EA947341EB0301C900D00095 +:1039700041EA527138BD00BF38B5FFF7ABFF114CBB +:10398000114AC00840EA4170A0FB025EC908A0FBD2 +:10399000040C1CEB050CA1FB04404FF000035B4141 +:1039A000A1FB02121CEB040C43EB000011EB0E0117 +:1039B00042F10002411842F10000090941EA007099 +:1039C00038BD00BFCFF753E3A59BC42010B5024418 +:1039D000064BD2B2904200D110BD441C00B253F845 +:1039E000200041F8040BE0B2F4E700BF502800408B +:1039F0000F4B30B51C6A240407D41C6A44F440748D +:103A00001C621C6A44F400441C620A4C236843F4A0 +:103A1000807323600244084BD2B2904200D130BD83 +:103A2000441C00B251F8045B43F82050E0B2F4E7C4 +:103A300000100240007000405028004007B50122ED +:103A400001A90020FFF7C2FF019803B05DF804FB55 +:103A500013B50446FFF7F2FFA04205D0012201A9E9 +:103A600000200194FFF7C4FF02B010BD70470000B2 +:103A70007047000070470000074B45F255521A602E +:103A800002225A6040F6FF729A604CF6CC421A60ED +:103A9000024B01221A70704700300040703A00203B +:103AA000034B1B781BB1034B4AF6AA221A607047DE +:103AB000703A002000300040044B1A682AB902F125 +:103AC000804202F50432526A1A6070476C3A002054 +:103AD000024B4FF080725A62704700BF00100240E4 +:103AE00008B5FFF7E9FF024B1868C0F3407008BD46 +:103AF0006C3A002070470000FEE700000A4B0B48BC +:103B00000B4A90420BD30B4BDA1C121AC11E22F047 +:103B100003028B4238BF00220021FDF785BA53F81B +:103B2000041B40F8041BECE714490008543C002037 +:103B3000543C0020543C0020FEE7000070B51B4BB5 +:103B400001630025044686B0586085620E46FFF783 +:103B5000D3FB04F11003C4E904334FF0FF33A36136 +:103B6000134BE561D969A5600A462B46C4E90823D1 +:103B700004F13401C4E900440E4AE562256580235E +:103B80002046FFF7D5FC0123E0600B4A0375009245 +:103B900072680192B268CDE90223084B6846CDE90C +:103BA0000435FFF7EDFC06B070BD00BF503A0020B1 +:103BB00028380020BC470008C1470008393B0008EE +:103BC0004B6843608B688360CB68C3600B6943615B +:103BD0004B6903628B6943620B68036070470000A6 +:103BE00008B51B4B9A6A42F4FC029A629A6A22F464 +:103BF000FC029A629A6A5A6942F4FC025A61154AB6 +:103C00005B6911464FF09040FFF7DAFF02F11C01AB +:103C100000F58060FFF7D4FF02F1380100F5806005 +:103C2000FFF7CEFF02F1540100F58060FFF7C8FFF7 +:103C300002F1700100F58060FFF7C2FF02F18C0114 +:103C400000F58060FFF7BCFFBDE8084000F05AB8FF +:103C500000100240C847000808B500F093F9FFF7CC +:103C60003FFCBDE80840FFF727BF00007047000099 +:103C700010B5214CA36A63F4FC03A362A36A03F4A6 +:103C8000FC03A3624FF0FF32A36A23692261236918 +:103C9000002323612169E168E260E268E360E26891 +:103CA000E269164942F08052E261E2690A6842F430 +:103CB00080720A60226A02F44072B2F5407F1EBF31 +:103CC0004FF4803222622362236A1B0407D4236AE2 +:103CD00043F440732362236A43F40043236200F0F9 +:103CE00031F9A369064A43F00103A361A36913688C +:103CF00043F02003136010BD00100240007000402C +:103D0000000001401E4B1A6842F001021A601A6856 +:103D10009007FCD55A6822F003025A605A6812F0E4 +:103D20000C02FBD1196801F0F90119605A601A6898 +:103D300042F480321A601A689103FCD5114A5A6025 +:103D40004FF40452DA6230221A631A6842F0807229 +:103D50001A601A689201FCD50B4912220A600A689F +:103D600002F00702022AFAD15A6842F002025A60AF +:103D70005A6802F00C02082AFAD11A6B1A637047CB +:103D80000010024000241D0000200240084A08B52F +:103D9000516913680B4003F00103536123B1054AD5 +:103DA00013680BB150689847BDE80840FFF7C8BAE0 +:103DB00000040140743A0020084A08B551691368AC +:103DC0000B4003F00203536123B1054A93680BB122 +:103DD000D0689847BDE80840FFF7B2BA0004014038 +:103DE000743A0020084A08B5516913680B4003F083 +:103DF0000403536123B1054A13690BB15069984715 +:103E0000BDE80840FFF79CBA00040140743A002066 +:103E1000084A08B5516913680B4003F00803536161 +:103E200023B1054A93690BB1D0699847BDE80840B2 +:103E3000FFF786BA00040140743A0020084A08B52A +:103E4000516913680B4003F01003536123B1054A15 +:103E5000136A0BB1506A9847BDE80840FFF770BA83 +:103E600000040140743A0020174B10B55A691C68D1 +:103E7000144004F478725A61A30604D5134A936A75 +:103E80000BB1D06A9847600604D5104A136B0BB18A +:103E9000506B9847210604D50C4A936B0BB1D06B3D +:103EA0009847E20504D5094A136C0BB1506C98474A +:103EB000A30504D5054A936C0BB1D06C9847BDE8B7 +:103EC0001040FFF73DBA00BF00040140743A0020E3 +:103ED0001A4B10B55A691C68144004F47C425A61AC +:103EE000620504D5164A136D0BB1506D9847230532 +:103EF00004D5134A936D0BB1D06D9847E00404D5F7 +:103F00000F4A136E0BB1506E9847A10404D50C4AAA +:103F1000936E0BB1D06E9847620404D5084A136FB4 +:103F20000BB1506F9847230404D5054A936F0BB12A +:103F3000D06F9847BDE81040FFF702BA0004014077 +:103F4000743A0020062108B50846FFF723FA062137 +:103F50000720FFF71FFA06210820FFF71BFA0621AA +:103F60000920FFF717FA06210A20FFF713FA0621A6 +:103F70001720FFF70FFABDE8084006212820FFF7B9 +:103F800009BA000008B5FFF773FE00F067F800F00B +:103F90003DF8FFF76BFEBDE8084000F05DB800009B +:103FA000026843681143016003B11847704700007D +:103FB000143000F02FBA00004FF0FF33143000F03F +:103FC00029BA0000383000F0A5BA00004FF0FF33E6 +:103FD000383000F09FBA0000143000F0F5B900004E +:103FE0004FF0FF31143000F0EFB90000383000F02E +:103FF0004FBA00004FF0FF32383000F049BA0000ED +:10400000012914BF6FF013000020704700F06CB856 +:10401000044B03600023C0E90233436001230374AF +:10402000704700BF7048000838B5C36904460D46A4 +:104030001BB904210844FFF7B3FF294604F114001B +:1040400000F0A6F9002806DA201D4FF40061BDE853 +:104050003840FFF7A5BF38BD00F00EB80023054A71 +:1040600019460133102BC2E9001102F10802F8D100 +:10407000704700BF743A00204FF0E023044A5A61B1 +:1040800000229A6107221A6108210B20FFF798B9D4 +:104090003F19010008B5302383F31188FFF746FA72 +:1040A000002383F3118808BD08B5FFF7F3FFBDE8CF +:1040B0000840FFF745B900000268436811430160FA +:1040C00003B1184770470000024A136843F0C00369 +:1040D0001360704700380140024A136843F0C00380 +:1040E000136070470044004037B51D4C1D4D2046FD +:1040F000FFF78EFF009404F114001B4900232022D7 +:1041000000F038F92022009404F13800174B1849C8 +:1041100000F0B2F9174BC4E91735174C0C212520D4 +:10412000FFF738F92046FFF773FF04F11400134935 +:1041300000940023202200F01DF904F13800104BF8 +:1041400010490094202200F097F90F4B0C212620F3 +:10415000C4E9173503B0BDE83040FFF71BB900BF15 +:10416000F43A002000512502CC3B0020C940000851 +:104170000C3C002000380140603B0020EC3B00205C +:10418000D94000082C3C0020004400402DE9F047B5 +:10419000C66D3768F46934622107054619D014F0FA +:1041A000080118BF4FF48071E20748BF41F02001B9 +:1041B000A30748BF41F04001600748BF41F08001BC +:1041C000302383F31188281DFFF776FF002383F344 +:1041D0001188E2050AD5302383F311884FF48061FA +:1041E000281DFFF769FF002383F311884FF0300982 +:1041F0004FF0000A14F0200838D13B0616D54FF0D6 +:10420000300905F1380A200610D589F31188504687 +:1042100000F066F9002836DA0821281DFFF74CFF68 +:1042200027F080033360002383F31188790614D5C7 +:10423000620612D5302383F31188D5E913239A42FD +:1042400008D12B6C33B11021281D27F04007FFF750 +:1042500033FF3760002383F31188E30619D5AA6E74 +:104260001369B3B1BDE8F0475069184789F3118865 +:10427000B38C95F8641028461940FFF7D5FE8AF3F1 +:104280001188F469B6E780B2308588F31188F46943 +:10429000B9E7BDE8F087000008B50348FFF776FFEF +:1042A000BDE80840FFF74CB8F43A002008B50348D1 +:1042B000FFF76CFFBDE80840FFF742B8603B002005 +:1042C000F8B5154682680669AA420B46816938BF6F +:1042D0008568761AB54204460BD218462A46FCF782 +:1042E00091FEA3692B44A361A3685B1BA3602846CE +:1042F000F8BD0CD918463246FCF784FEAF1BE168C6 +:104300003A463044FCF77EFEE3683B44EBE7184650 +:104310002A46FCF777FEE368E5E7000083689342EE +:10432000F7B51546044638BF8568D0E90460361AEB +:10433000B5420BD22A46FCF765FE63692B446361E4 +:10434000A36828465B1BA36003B0F0BD0DD93246BD +:104350000191FCF757FE0199E068AF1B3A463144E2 +:10436000FCF750FEE3683B44E9E72A46FCF74AFEC7 +:10437000E368E4E710B50A440024C361029B84604B +:10438000C0E90000C0E90511C1600261036210BD0F +:1043900008B5D0E90532934201D1826882B98268BA +:1043A000013282605A1C42611970D0E904329A428B +:1043B00024BFC36843610021FFF714F9002008BD42 +:1043C0004FF0FF30FBE7000070B5302304460E4687 +:1043D00083F31188A568A5B1A368A269013BA36016 +:1043E000531CA36115782269934224BFE368A3613B +:1043F000E3690BB120469847002383F311882846D0 +:1044000007E031462046FFF7DDF80028E2DA85F3C1 +:10441000118870BD2DE9F74F04460E4617469846A1 +:10442000D0F81C904FF0300A8AF311884FF0000B3F +:10443000154665B12A4631462046FFF741FF03463F +:1044400060B941462046FFF7BDF80028F1D00023AF +:1044500083F31188781B03B0BDE8F08FB9F1000F2A +:1044600003D001902046C847019B8BF31188ED1AB9 +:104470001E448AF31188DCE7C0E90511C160C361FD +:104480001144009B8260C0E9000001610362704733 +:10449000F8B504460D461646302383F31188A76805 +:1044A000A7B1A368013BA36063695A1C62611D70D8 +:1044B000D4E904329A4224BFE3686361E3690BB133 +:1044C00020469847002080F3118807E031462046B7 +:1044D000FFF778F80028E2DA87F31188F8BD0000CA +:1044E000D0E905239A4210B501D182687AB9826871 +:1044F000013282605A1C82611C7803699A4224BF8F +:10450000C36883610021FFF76DF8204610BD4FF0AE +:10451000FF30FBE72DE9F74F04460E461746984655 +:10452000D0F81C904FF0300A8AF311884FF0000B3E +:10453000154665B12A4631462046FFF7EFFE034691 +:1045400060B941462046FFF73DF80028F1D000232E +:1045500083F31188781B03B0BDE8F08FB9F1000F29 +:1045600003D001902046C847019B8BF31188ED1AB8 +:104570001E448AF31188DCE70B460146184600F01A +:104580002DB8000000F040B8012838BF012010B558 +:104590000446204600F030F830B900F007F808B9BA +:1045A00000F00CF88047F4E710BD0000024B1868DB +:1045B000BFF35B8F704700BF4C3C002008B506205E +:1045C00000F084F80120FFF785F80000024B0A464E +:1045D00001461868FFF772B91811002010B5054C94 +:1045E00013462CB10A4601460220AFF3008010BDED +:1045F0002046FCE700000000024B01461868FFF768 +:1046000061B900BF18110020024B01461868FFF77E +:104610005DB900BF1811002010B501390244904265 +:1046200001D1002005E0037811F8014FA34201D029 +:10463000181B10BD0130F2E72DE9F041A3B1C91AF2 +:1046400017780144044603F1FF3C8C42204601D90F +:10465000002009E00578BD4204F10104F5D10CEB1E +:104660000405D618A54201D1BDE8F08115F8018DE9 +:1046700016F801EDF045F5D0E7E700001F2938B541 +:1046800004460D4604D9162303604FF0FF3038BDB1 +:10469000426C12B152F821304BB9204600F030F88C +:1046A0002A4601462046BDE8384000F017B8012BE5 +:1046B0000AD0591C03D1162303600120E7E7002428 +:1046C00042F82540284698470020E0E7024B014683 +:1046D0001868FFF7D3BF00BF1811002038B5074D89 +:1046E00000230446084611462B60FEF7F7FF431CE3 +:1046F00002D12B6803B1236038BD00BF503C0020BD +:10470000FEF7E6BF034611F8012B03F8012B002A40 +:10471000F9D170476F72672E6172647570696C6F42 +:10472000742E663330332D48574553430000000044 +:1047300040A2E4F1646891060041A3E5F265699244 +:10474000070000004261642043414E496661636591 +:1047500020696E6465782E008000000000800000F3 +:104760000000800000000000000000001118000898 +:104770002D200008891F0008511800085D18000846 +:104780005D1A0008211800083118000825180008D3 +:104790002D1800082918000881190008351800088C +:1047A000FD22000845180008551900086330000074 +:1047B000AC47000880380020503A00206D61696ED7 +:1047C0000069646C65000000A001A82A00000000D8 +:1047D000FAAABEAA50001424EFFF000000770000E0 +:1047E000709709000100000000000000AAAAAAAA10 +:1047F00001000000FFFF00000000000000000000BA +:104800000000000000000000AAAAAAAA0000000000 +:10481000FFFF00000000000000000000000000009A +:1048200000000000AAAAAAAA00000000FFFF0000E2 +:104830000000000000000000000000000000000078 +:10484000AAAAAAAA00000000FFFF000000000000C2 +:10485000000000000000000000000000AAAAAAAAB0 +:1048600000000000FFFF000000000000000000004A +:1048700000000000CD3F0008B93F0008F53F0008E8 +:10488000E13F0008ED3F0008D93F0008C53F0008A0 +:10489000B13F000801400008EC03000000000000E8 +:1048A0000098030000000000FE2A0100D20400006E +:1048B0001C110020000000000000000000000000AB +:1048C00000000000000000000000000000000000E8 +:1048D00000000000000000000000000000000000D8 +:1048E00000000000000000000000000000000000C8 +:1048F00000000000000000000000000000000000B8 +:1049000000000000000000000000000000000000A7 +:0449100000000000A3 :00000001FF diff --git a/Tools/bootloaders/f303-M10025_bl.bin b/Tools/bootloaders/f303-M10025_bl.bin index a0a56a32285786..81f284ff04e3fd 100755 Binary files a/Tools/bootloaders/f303-M10025_bl.bin and b/Tools/bootloaders/f303-M10025_bl.bin differ diff --git a/Tools/bootloaders/f303-M10025_bl.hex b/Tools/bootloaders/f303-M10025_bl.hex index 7d09f547760507..703e54b675df3c 100644 --- a/Tools/bootloaders/f303-M10025_bl.hex +++ b/Tools/bootloaders/f303-M10025_bl.hex @@ -1,1217 +1,1172 @@ :020000040800F2 -:1000000000090020B5040008CD250008852500085A -:10001000AD25000885250008A5250008B7040008BF -:10002000B7040008B7040008B7040008C135000889 -:10003000B7040008B7040008B704000875430008B7 -:10004000B7040008B7040008B7040008B7040008A4 -:10005000B7040008B70400085940000885400008AC -:10006000B1400008DD40000809410008B70400085D -:10007000B7040008B7040008B7040008B704000874 -:10008000B7040008B7040008B704000839250008C1 -:100090006525000875250008B704000835410008EB -:1000A000B7040008B7040008B7040008B704000844 -:1000B000B7040008B7040008B7040008B704000834 -:1000C000B7040008B7040008B7040008B704000824 -:1000D000B70400086545000879450008B704000822 -:1000E0009D410008B7040008B7040008B7040008E1 -:1000F000B7040008B7040008B7040008B7040008F4 -:10010000B7040008B7040008B7040008B7040008E3 -:10011000B7040008B7040008B7040008B7040008D3 -:10012000B7040008B7040008B7040008B7040008C3 -:10013000B7040008B7040008B7040008B7040008B3 -:10014000B7040008B7040008B7040008B7040008A3 -:10015000B7040008B7040008B7040008B704000893 -:10016000B7040008B7040008B7040008B704000883 -:10017000B7040008B7040008B7040008B704000873 -:10018000B7040008B7040008B7040008B704000863 -:10019000B7040008B7040008B7040008B704000853 -:1001A0002112000800000000000000000000000014 -:1001B00053B94AB9002908BF00281CBF4FF0FF31CE -:1001C0004FF0FF3000F074B9ADF1080C6DE904CECA -:1001D00000F006F8DDF804E0DDE9022304B0704722 -:1001E0002DE9F047089D04468E46002B4DD18A42EA -:1001F000944669D9B2FA82F252B101FA02F3C2F11D -:10020000200120FA01F10CFA02FC41EA030E9440AD -:100210004FEA1C48210CBEFBF8F61FFA8CF708FBCE -:1002200016E341EA034306FB07F199420AD91CEBA6 -:10023000030306F1FF3080F01F81994240F21C81D8 -:10024000023E63445B1AA4B2B3FBF8F008FB103320 -:1002500044EA034400FB07F7A7420AD91CEB040455 -:1002600000F1FF3380F00A81A74240F20781644425 -:10027000023840EA0640E41B00261DB1D4400023AA -:10028000C5E900433146BDE8F0878B4209D9002D0E -:1002900000F0EF800026C5E9000130463146BDE898 -:1002A000F087B3FA83F6002E4AD18B4202D3824202 -:1002B00000F2F980841A61EB030301209E46002DB1 -:1002C000E0D0C5E9004EDDE702B9FFDEB2FA82F206 -:1002D000002A40F09280A1EB0C014FEA1C471FFA64 -:1002E0008CFE0126200CB1FBF7F307FB131140EA4B -:1002F00001410EFB03F0884208D91CEB010103F118 -:10030000FF3802D2884200F2CB804346091AA4B2D9 -:10031000B1FBF7F007FB101144EA01440EFB00FEAD -:10032000A64508D91CEB040400F1FF3102D2A64512 -:1003300000F2BB800846A4EB0E0440EA03409CE7B1 -:10034000C6F12007B34022FA07FC4CEA030C20FA5E -:1003500007F401FA06F31C43F9404FEA1C4900FA7E -:1003600006F3B1FBF9F8200C1FFA8CFE09FB1811FB -:1003700040EA014108FB0EF0884202FA06F20BD96E -:100380001CEB010108F1FF3A80F08880884240F2BE -:100390008580A8F102086144091AA4B2B1FBF9F002 -:1003A00009FB101144EA014100FB0EFE8E4508D9FD -:1003B0001CEB010100F1FF346CD28E456AD9023882 -:1003C000614440EA0840A0FB0294A1EB0E01A14267 -:1003D000C846A64656D353D05DB1B3EB080261EBD5 -:1003E0000E0101FA07F722FA06F3F1401F43C5E9AF -:1003F000007100263146BDE8F087C2F12003D840E5 -:100400000CFA02FC21FA03F3914001434FEA1C4726 -:100410001FFA8CFEB3FBF7F007FB10360B0C43EA18 -:10042000064300FB0EF69E4204FA02F408D91CEBC8 -:10043000030300F1FF382FD29E422DD902386344C6 -:100440009B1B89B2B3FBF7F607FB163341EA034166 -:1004500006FB0EF38B4208D91CEB010106F1FF38B5 -:1004600016D28B4214D9023E6144C91A46EA0046AC -:1004700038E72E46284605E70646E3E61846F8E63E -:100480004B45A9D2B9EB020864EB0C0E0138A3E787 -:100490004646EAE7204694E74046D1E7D0467BE768 -:1004A000023B614432E7304609E76444023842E7E0 -:1004B000704700BF02E000F000F8FEE772B6374870 -:1004C00080F30888364880F3098836483649086042 -:1004D00040F20000CCF200004EF63471CEF2000182 -:1004E0000860BFF34F8FBFF36F8F40F20000C0F280 -:1004F000F0004EF68851CEF200010860BFF34F8F36 -:10050000BFF36F8F4FF00000E1EE100A4EF63C7122 -:10051000CEF200010860062080F31488BFF36F8FCD -:1005200003F04EFC03F0C2FC4FF055301F491B4A4C -:1005300091423CBF41F8040BFAE71D49184A914229 -:100540003CBF41F8040BFAE71A491B4A1B4B9A427D -:100550003EBF51F8040B42F8040BF8E7002018499D -:10056000184A91423CBF41F8040BFAE703F02CFC17 -:1005700003F0D8FC144C154DAC4203DA54F8041BBC -:100580008847F9E700F042F8114C124DAC4203DA0B -:1005900054F8041B8847F9E703F014BC0009002055 -:1005A000001100200000000808ED00E0000100201C -:1005B00000090020704B0008001100207C11002071 -:1005C00080110020583C0020A0010008A401000870 -:1005D000A4010008A40100082DE9F04F2DED108AB8 -:1005E000C1F80CD0C3689D46BDEC108ABDE8F08F01 -:1005F000002383F311882846A047002003F06AF9FE -:10060000FEE703F0CDF800DFFEE70000F8B500F0EC -:1006100019FE03F079FB074603F0C8FB05460028E6 -:1006200040D12C4B9F423DD001339F423DD02A4BBD -:1006300027F0FF029A423BD1F8B200F03FFC2E4671 -:1006400042F2107400F040FC08B10024264601F08C -:10065000B1F888B3032000F045F80024264635B1F0 -:100660001E4B9F4203D003F099FB00242646002036 -:1006700003F054FB1A4B1B6913F0400322D00EB158 -:1006800000F046F800F052FC00F0DEFD01F0A6FF9D -:100690000546CCB101F0A2FF401BA04214D900F0E6 -:1006A00037F8F3E72E460024CCE704460126C9E7D5 -:1006B00006464FF47A74C5E7002CD0D04FF47A7414 -:1006C0000126CCE71C46DDE700F078FC012003F0B2 -:1006D00007F9DEE7010007B0000008B0263A09B0CC -:1006E00000040048084B187003280CD8DFE800F01D -:1006F00008050208022000F003BE022000F0F8BD49 -:10070000024B00225A6070478011002084110020A3 -:1007100038B501F04FF830B11F4B03221A701F4B50 -:1007200000225A6038BD1E4B1E4A19680131F9D0AB -:1007300004339342F9D11C4C194DD4F80428AA4231 -:10074000F0D31A4B9B6803F1006303F5D0439A4240 -:10075000E8D203F0F7FA03F009FB002000F08EFD69 -:100760000220FFF7BFFF124BDA690022DA61D96974 -:1007700099699A619B6972B64FF0E0233021C3F802 -:10078000085DD4F80038D4F8042881F311889D4618 -:1007900083F308881047C5E78011002084110020EA -:1007A00000680008206800080060000800110020B0 -:1007B00000100240094A136849F2690099B21B0C03 -:1007C00000FB01331360064B186844F2506182B29B -:1007D000000C01FB0200186080B270471411002069 -:1007E0001011002010B500211022044600F0A2FDD7 -:1007F000034B03CB206061601868A06010BD00BF90 -:10080000ACF7FF1F2DE9F041ADF54E7D0DF1340839 -:100810006CAC40F2751207460D460EA80021C8F8D0 -:10082000001000F087FD4FF4C4720021204600F054 -:1008300081FD01F0D3FE254B4FF47A72B0FBF2F04C -:10084000186093E80700022384E807000DF5E970BB -:100850002382FFF7C7FF4EF603431D49238406A8F2 -:1008600004F0B6F8192384F832310DF2E32206AB16 -:100870000DF1300C1E4603CE6645106051603346C4 -:1008800002F10802F6D13378137041460122204666 -:1008900000F09CFD00230393AB7E029305F1190346 -:1008A000019380B20123CDE904800093E97E05A382 -:1008B000D3E90023384602F059FA0DF54E7DBDE824 -:1008C000F08100BF9E6AC421818A46EE8C1100200F -:1008D000E04900082DE9F0412C4C237ADAB080463B -:1008E0000D465BBB27A9284600F080FE074600287E -:1008F00042D19DF89D60C82E3ED801464FF4A662B5 -:10090000204600F017FD4FF48073C4F8F8314FF41F -:100910000073C4F80C334FF44073C4F820343246EB -:100920000DF19E0104F1090000F0F2FC26449DF84F -:100930009C30777223720BB9EB7E237281220021E7 -:1009400006AC27A800F0F6FC0122214627A800F0FB -:1009500089FE00230393AB7E029305F1190380B255 -:1009600001932823CDE904400093E97E05A3D3E950 -:100970000023404602F0FAF95AB0BDE8F08100BF0A -:10098000AFF3008026417272DF25D7B7A83200206E -:10099000F0B5254E4FF48A7505FB0065F1B096F869 -:1009A000D83085F8DC300024D822214685F8E8408C -:1009B0003AA800F0BFFC06F1090000F0B3FCD5F83E -:1009C000E4308DF8F000C2B206AF06F109010DF176 -:1009D000F100CDE93A3400F09BFC394601223AA8F7 -:1009E00000F06CFE80B2CDE9047008230127CDE948 -:1009F000023706F1D803019330230093317A0B4874 -:100A000007A3D3E9002302F0B1F9A04206DD01F00B -:100A1000E5FDC5F8E000384671B0F0BD2046FBE7C3 -:100A200078F6339F93CACD8DA8320020A4210020F0 -:100A30002DE9F0411D4D1E4E1E4F86B0284602F096 -:100A4000C1F9034658B30024CDE90344ADF814407E -:100A5000027B8DF8142099684068029403AA03C2AF -:100A60001B68DFF8548043F00043029301F0B8FDA7 -:100A7000821941F10003009402A9384601F07CF884 -:100A8000A04205DD284602F0A1F988F80040D5E72C -:100A900098F80030072B05D8013388F8003006B0ED -:100AA000BDE8F081014802F091F9F8E7A4210020A7 -:100AB00040420F00D8210020DD37002070B50D46E0 -:100AC00014461E4602F0AEF850B9022E10D1012C89 -:100AD0000ED112A3D3E90023C5E90023012007E0CA -:100AE000282C10D005D8012C09D0052C0FD00020BF -:100AF00070BD302CFBD10BA3D3E90023ECE70BA393 -:100B0000D3E90023E8E70BA3D3E90023E4E70BA331 -:100B1000D3E90023E0E700BFAFF30080401DA12030 -:100B200026812A0B78F6339F93CACD8D9E6AC42105 -:100B3000818A46EE26417272DF25D7B7F017304A18 -:100B400039059E5638B505460E4C0021013500F09A -:100B5000B7FBA4F82C55B4F82C0500F099FB78B13C -:100B6000B4F82C0500F0A4FB014648B9B4F82C05F4 -:100B700000F0A6FBB4F82C350133A4F82C35EAE7D5 -:100B800038BD00BFA832002010B50A4B0A4A1A60CF -:100B900003F5805393F860203AB9DC6D2CB1204600 -:100BA00000F082FE204603F053FEBDE810400348EB -:100BB00000F07ABED8210020384A000820320020F8 -:100BC0002DE9F04F8FB000AF05460C4602F02AF831 -:100BD000002849D1237E022B1BD1E38A012B18D197 -:100BE00001F0FCFC0646FFF7E5FD03464FF4C87034 -:100BF000DFF8C482B3FBF0F206F5167602FB103381 -:100C000016FA83F3C8F80030E37E33B9A34B002211 -:100C10001A703C37BD46BDE8F08F07F1240120462D -:100C200000F0A2FC0028F4D107F11400FFF7DAFD70 -:100C300097F8264007F11401224607F1270003F038 -:100C400051FE0028E2D10F2C08D8944B1C70D8F824 -:100C50000030A3F51673C8F80030DAE797F82410CF -:100C6000284601F0D7FFD4E7E38A282B2BD010D8F1 -:100C7000012B23D0052BCCD1BFF34F8F8849894B53 -:100C8000CA6802F4E0621343CB60BFF34F8F00BF2A -:100C9000FDE7302BBDD1844EE17E327A9142B8D14E -:100CA000607E3146002291F8DC50854200F0A5803C -:100CB0000132042A01F58A71F5D1AAE721462846B6 -:100CC000FFF7A0FDA5E721462846FFF703FEA0E7B2 -:100CD000B2F8EC507B6005F103094FEA99094FEA3D -:100CE0008902D11DC908A8EBC1039D46EB4600212E -:100CF000584600F01FFB04F1EE012A4631445846E5 -:100D000000F006FB7B6813B9012000F0B7FA96F8F3 -:100D1000D20000F0BDFA044630B9307200F0D8FAC3 -:100D2000204600F0ABFAB1E0D6F8D4203AB996F8F4 -:100D3000D200B6F82C25824201D8FFF703FFD6F87F -:100D4000D4202A44944208D296F8D200B6F82C2532 -:100D50000130824201D8FFF7F5FE70685FFA89F230 -:100D6000594600F0EFFA08B9C54679E0726896F87E -:100D7000D2002A447260D6F8D42005EB0209C6F8E6 -:100D8000D49000F085FA814509D396F8D220D6F8A0 -:100D9000D4000132001B86F8D220C6F8D400FF2D03 -:100DA0000FD80024347200F093FA204600F066FA5F -:100DB00000F000FD3D4B188108B9FFF7A9FCC546BE -:100DC00027E7BB6896F8D9000AFB0362FB68D2F8F4 -:100DD000E41082F8E83001F58061C2F8E030C2F832 -:100DE000E410FFF7D5FDFFF723FE96F8D920013276 -:100DF00002F0030286F8D920B6E74FF48A7A0AFB9C -:100E000002F505F1EA013144204600F083FCF86068 -:100E100000287FF4FEAE3544012285F8E82001F079 -:100E2000DDFBD5F8E020D6ED007ADFED216A801AEF -:100E3000192838BF192040F6B832904228BF104612 -:100E4000B8EE677A07EE900AF8EEE77A67EEA67AD0 -:100E5000DFED186AE7EE267AFCEEE77AC6ED007A57 -:100E600096F8D930BB60BA6873680AFB02F432198D -:100E700092F8E81059B1D2F8E4108B42E8463FF4FA -:100E800027AF002182F8E810C2F8E010C546736869 -:100E9000064A9B0A01331381BBE600BF9D21002057 -:100EA00000ED00E00400FA05A83200208C110020BB -:100EB000CDCCCC3D6666663FA0210020014B18706A -:100EC000704700BF9811002038B54FF00054134B05 -:100ED00022689A4220D1124B627D12481A70237DFB -:100EE00003724FF48073C0F8F8314FF40073C0F808 -:100EF0000C3300254FF44073C0F820340A49C0F881 -:100F0000E450C922093000F003FAE02229462046C5 -:100F100000F010FA012038BD0020FCE79AAD44C56E -:100F200098110020A83200201600002037B500F0EC -:100F300041FC194D194928810223012218486B717F -:100F400001F0EAF900230193164B17490093174863 -:100F5000174B4FF4805201F035FE164B197811B142 -:100F6000124801F057FE01F039FB0446FFF722FC5E -:100F70004FF4C873B0FBF3F202FB130304F51670D1 -:100F800010FA83F00C4B186002F010FF08B10F2329 -:100F90002B8103B030BD00BF8C11002040420F00F8 -:100FA000D8210020BD0A00089C110020A4210020A7 -:100FB000C10B000898110020A02100202DE9F04F5E -:100FC0002DED028B8EA7D7E900670FF23C29D9E9F6 -:100FD0000089864C95B00DAD9FED828BFFF728FD03 -:100FE000DFF82CB200230C93ADF83C300D936B600E -:100FF00000230DF125028DED008B4FF0010A09A9A8 -:1010000058468DF825308DF824A001F035F99DF86B -:1010100024200023002A40F0AB80204601F002FE8D -:101020000546002847D1DFF8ECB101F0D7FADBF82C -:10103000003098423FD301F0D1FA0790FFF7BAFB96 -:10104000079A4FF4C873B0FBF3F101FB130302F5E9 -:10105000167010FA83F0CBF80000DFF8BCB19BF8F3 -:1010600000100791002914BF2B46534610A88DF895 -:101070003030FFF7B7FB0799C1F11002D2B2062A50 -:1010800010AB28BF062219440DF13100079200F081 -:101090003FF9079A0CAB0393182302930132544B88 -:1010A000D2B2CDE900A304923B463246204601F07D -:1010B000FFFD8BF8005001F091FA4E4A4E4D136837 -:1010C000C31AB3F57A7F32D3106001F089FA024671 -:1010D0000B46204601F084FE204601F0A3FD30B30C -:1010E0002B7ADFF838A1002B14BF032302238AF8E0 -:1010F000053001F073FA0DF1400B4FF47A730122C1 -:10110000B0FBF3F05946CAF80000504600F004FA6C -:1011100018230293394B019380B240F25513CDE965 -:1011200003B0009342464B46204601F0C1FD2B7AA6 -:10113000CBB101F053FA4FF0000A83464FF48A72A4 -:1011400095F8D900504400F0030002FB005393F8D7 -:10115000E81089B30AF1010ABAF1040FF0D12B7A31 -:10116000002B7FF438AF15B0BDEC028BBDE8F08FDB -:101170004FF0904110A84A6982F010024A61194666 -:10118000102200F0D7F80DF126030AAA0CA9584640 -:1011900000F0F0FD95E8030011AB83E803009DF833 -:1011A0003C308DF84C300C9B109310A9DDE90A23DC -:1011B000204601F0E9FF1BE7D3F8E01049B12B68A6 -:1011C000FA2B38BFFA23ABEB01010533B1EB430F28 -:1011D000C0D3FFF7DDFB4FF48A720028BAD1BEE717 -:1011E000AFF300800000000000000000A4210020F8 -:1011F0009C210020D8370020A8320020DC370020B6 -:10120000401DA12026812A0BF1C6A7C1D068080F76 -:10121000D8210020A02100209D2100208C11002039 -:1012200008B5054800F040FEBDE80840034A0449FF -:10123000002003F007BB00BFD82100201838002091 -:10124000890B00087047000070B502F013FC094ECE -:10125000094D3080002428683388834208D902F081 -:1012600005FC2B6804440133B4F5D04F2B60F2D356 -:1012700070BD00BF0C380020E037002002F086BCB3 -:1012800000F10060920000F5D04002F02DBC00009B -:10129000054B1A68054B1B889B1A834202D91044E0 -:1012A00002F0E4BB00207047E03700200C3800203B -:1012B000024B1B68184402F0DFBB00BFE037002080 -:1012C000024B1B68184402F0E9BB00BFE037002066 -:1012D000064991F8243033B10023086A81F824309C -:1012E0000822FFF7CDBF0120704700BFE437002080 -:1012F000022802BF4FF0904310229A61704700000D -:10130000022802BF4FF090434FF480129A61704759 -:1013100010B50023934203D0CC5CC4540133F9E7E9 -:1013200010BD000003460246D01A12F9011B002925 -:10133000FAD1704702440346934202D003F8011BDE -:10134000FAE770472DE9F8431F4D144695F824201D -:101350000746884652BBDFF870909CB395F824305E -:101360002BB92022FF2148462F62FFF7E3FF95F8B3 -:101370002400C0F10802A24228BF2246D6B241464C -:10138000920005EB8000FFF7C3FF95F82430A41B03 -:101390001E44F6B2082E17449044E4B285F8246047 -:1013A000DBD1FFF795FF0028D7D108E02B6A03EBCC -:1013B00082038342CFD0FFF78BFF0028CBD10020E0 -:1013C000BDE8F8830120FBE7E43700202DE9F04772 -:1013D0000D46044600219046284640F27912FFF758 -:1013E000A9FF234620220021284601F06FFE231D7D -:1013F00002222021284601F069FE631D03222221DA -:10140000284601F063FEA31D03222521284601F092 -:101410005DFE04F1080310222821284601F056FE43 -:1014200004F1100308223821284601F04FFE04F190 -:10143000110308224021284601F048FE04F112035E -:1014400008224821284601F041FE04F1140320221D -:101450005021284601F03AFE04F118034022702181 -:10146000284601F033FE04F120030822B02128466B -:1014700001F02CFE04F121030822B821284601F0D6 -:1014800025FE04F12207C0263B46314608222846A5 -:10149000083601F01BFEB6F5A07F07F10107F3D176 -:1014A00004F1320308223146284601F00FFE0027DE -:1014B00004F1330A94F832304FEAC7099F4209F524 -:1014C000A47615D3B8F1000F08D1314604F599730D -:1014D0000722284601F0FAFD09F24F16274694F834 -:1014E00032213B1B93420CD3F01DC008BDE8F087AE -:1014F0000AEB070308223146284601F0E7FD0137D1 -:10150000D8E707F2331331460822284601F0DEFD02 -:1015100008360137E3E7000013B50446084600210A -:1015200001602346C0F803102022019001F0CEFD97 -:101530000198231D0222202101F0C8FD0198631D9E -:101540000322222101F0C2FD0198A31D03222521BF -:1015500001F0BCFD019804F108031022282101F0DC -:10156000B5FD072002B010BDF7B50023047F009140 -:101570000E4607221946054601F06CFC731C0093C9 -:10158000012200230721284601F064FCC4B9B31CE2 -:101590000093052223460821284601F05BFC0D2418 -:1015A0003746B278BB1B934211D32B7FA88A0734EE -:1015B000E408BBB9844294BF0020012003B0F0BD11 -:1015C000AB8ADB00083BDB08B3700824E8E7FB1CB0 -:1015D0000093214600230822284601F03BFC0834F2 -:1015E0000137DEE7201A18BF0120E7E7F7B500232F -:1015F000047F00910E4608221946054601F02AFC98 -:10160000731CC4B90822009311462346284601F0F2 -:1016100021FC1024012372785F1C013B934211D3FB -:101620002B7FA88A0734E408BBB9844294BF00200A -:10163000012003B0F0BDAB8ADB00083BDB08737010 -:101640000824E7E7F31900932146002308222846DF -:1016500001F000FC08343B46DDE7201A18BF0120EA -:10166000E7E70000F8B50E46054614460021812242 -:101670003046FFF75FFE2B4608220021304601F07E -:1016800025FD7CB96B1C07220821304601F01EFDA8 -:101690000F2401236A785F1C013B934204D3E01DB1 -:1016A000C008F8BD0824F4E7EB19214608223046AB -:1016B00001F00CFD08343B46ECE70000F8B50E469F -:1016C000054614460021CE223046FFF733FE2B4656 -:1016D00028220021304601F0F9FC7CB905F108030D -:1016E00008222821304601F0F1FC30242F462A7AC6 -:1016F0007B1B934204D3E01DC008F8BD2824F5E706 -:1017000007F1090321460822304601F0DFFC0834C6 -:101710000137ECE7F7B5047F00910E460123102254 -:101720000021054601F096FBC4B9B31C00930922C1 -:1017300023461021284601F08DFB19243746728874 -:10174000BB1B9A4211D82B7FA88A0734E408BBB987 -:10175000844294BF0020012003B0F0BDAB8ADB00BF -:10176000103BDB0873801024E8E73B1D0093214603 -:1017700000230822284601F06DFB08340137DEE71C -:10178000201A18BF0120E7E730B5094D0A449142FD -:101790000DD011F8013B5840082340F30004013BF1 -:1017A0002C4013F0FF0384EA5000F6D1EFE730BD80 -:1017B0002083B8EDF7B5364A106851686B4603C30D -:1017C0006A4634493448082303F09CF8044690BB29 -:1017D0000A25324A106851686B4603C36A4630498D -:1017E0002D48082303F08EF80446002847D00369EB -:1017F000B3F5663F43D8B0F86620B2F57B7F3ED1A3 -:10180000284A024402F15C018B4238D35C3B2249F6 -:1018100000209E1AFFF7B8FF3246074604F1640124 -:101820000020FFF7B1FFA3689F4228D1E3689842E8 -:1018300008BF002523E00369B3F5663F26D8428B35 -:10184000B2F57B7F20D1174A024402F110018B428E -:1018500018D3103B104900209D1AFFF795FF2A4628 -:10186000064604F118010020FFF78EFFA3689E4290 -:1018700002D1E368984201D00D25AAE70025284649 -:1018800003B0F0BD1025A4E70C25A2E70B25A0E7C7 -:10189000FC490008DC97030000680008054A0008BE -:1018A000909703000898FFF710B5037C044613B91E -:1018B000006803F00FF8204610BD00000023BFF3BE -:1018C0005B8FC360BFF35B8FBFF35B8F8360BFF33E -:1018D0005B8F7047BFF35B8F0068BFF35B8F704710 -:1018E00070B505460C30FFF7F5FF05F10806044614 -:1018F0003046FFF7EFFFA04206D930466D68FFF78C -:10190000E9FF2544281A70BD3046FFF7E3FF201A8F -:10191000F9E7000070B50546406898B105F1080088 -:10192000FFF7D8FF05F10C0604463046FFF7D2FF5B -:101930008442304694BF6D680025FFF7CBFF013C21 -:101940002C44201A70BD000038B50C460546FFF740 -:10195000C7FFA04210D305F10800FFF7BBFF044406 -:101960006868B4FBF0F100FB1144BFF35B8F01200A -:10197000AC60BFF35B8F38BD0020FCE72DE9F04180 -:10198000144607460D46FFF7C5FF844228BF0446AC -:10199000D4B1B84658F80C6B4046FFF79BFF304473 -:1019A000286040467E68FFF795FF331A9C4203D8B3 -:1019B0006C600120BDE8F0816B60A41B3B68AB60EC -:1019C0002044E8600220F5E72046F3E738B50C46EE -:1019D0000546FFF79FFFA04210D305F10C00FFF76B -:1019E00079FF04446868B4FBF0F100FB1144BFF3D5 -:1019F0005B8F0120EC60BFF35B8F38BD0020FCE7FC -:101A00002DE9FF41884669460746FFF7B7FF6C4658 -:101A100006B204EBC6060025B44209D0626820680D -:101A200008EB0501FFF774FC636808341D44F3E715 -:101A300029463846FFF7CAFF284604B0BDE8F081C2 -:101A4000F8B505460C300F46FFF744FF05F10806D0 -:101A500004463046FFF73EFFA042304688BF6C6820 -:101A6000FFF738FF201A386020B130462C68FFF7A6 -:101A700031FF2044F8BD000073B5144606460D46FC -:101A8000FFF72EFF844228BF04460190DCB101A974 -:101A90003046FFF7D5FF019B33B93268C5E9023301 -:101AA000C5E9002401200CE09C4238BF0194286065 -:101AB000019868608442F5D93368AB60241AEC6001 -:101AC000022002B070BD2046FBE700002DE9FF4177 -:101AD0000F466946FFF7D0FF6C4600B204EBC00525 -:101AE0000026AC4209D0D4F8048054F8081BB81979 -:101AF0004246FFF70DFC4644F3E7304604B0BDE82C -:101B0000F081000038B50546FFF7E0FF04460146C6 -:101B10002846FFF719FF204638BD0000302383F325 -:101B2000118862B670470000002383F3118862B603 -:101B30007047000010B4026854681A4623465DF8E6 -:101B4000044B184701207047002070470020704761 -:101B500070470000002070470E20704700F580504D -:101B600090F8C800C0F340007047000000F58050B6 -:101B700090F9C90070470000F7B50C68BDF82070F7 -:101B800014F000541E466FD10B7B082B6CD8FFF766 -:101B9000C5FF4569AB685B010CD4AB681B0108D479 -:101BA000AC6814F080545DD1FFF7BEFF204603B04F -:101BB000F0BD01240B6804F1180C002BB8BFDB004A -:101BC0004FEA0C1CB4BF43F004035B0545F80C302E -:101BD0000B680FFA84FC13F0804F18BF05EB0C1E46 -:101BE00005EB0C1C1EBFDEF8803143F00203CEF87B -:101BF00080310B7BCCF8843105EB04158B68C5F87C -:101C00008C314B68C5F88831DCF8803143F0010332 -:101C1000CCF8803100EB441541F268031D4403EB1E -:101C200044130344C5E9002608330D4601F10C0CAA -:101C300055F804EB43F804EB6545F9D184342D885D -:101C40001D8000EB441407F00303257925F00B05F4 -:101C50002B432371FFF768FF0097334600F0E0FC49 -:101C60000120A4E70224A5E74FF0FF309FE7000022 -:101C700013B500F580540191E06DFFF74BFE1F286E -:101C80000AD90199E06D2022FFF7BAFEA0F12003E6 -:101C90005842584102B010BD0020FBE708B500F5DE -:101CA0008050FFF73BFFC06DFFF708FEBDE808401E -:101CB000FFF73ABF00220260828142608260704773 -:101CC00010B500220023C0E900230023044603814D -:101CD0000C30FFF7EFFF204610BD0000F0B50546C1 -:101CE00000F580500C4690F8C83013F0040FC3F391 -:101CF000800108BF114661F3820304F1840680F875 -:101D0000C83005EB461389B01B79D8072ED57AB3B6 -:101D100019072DD46846FFF7D3FF05EB441303F5ED -:101D2000835303F1180703AA10331868596814463F -:101D300003C40833BB422246F7D1186820609B8851 -:101D4000A380DDE90E23CDE900230123ADF808309F -:101D50002B686946DB6B2846984705EB46152B79BF -:101D60001A075CBF43F008032B7101E0002AF4D18D -:101D700009B0F0BD2DE9F047074688B007F580545B -:101D800068469A468846FFF7C9FE9146FFF798FFD6 -:101D9000E06DFFF7A5FD1F2829D9E06D20226946D7 -:101DA000FFF7B0FE202822D103AD444605AB2E46F6 -:101DB00003CE9E4220606160354604F10804F6D1EE -:101DC00030682060B388A380DDE90023C9E90023DF -:101DD000BDF80830AAF80030FFF7A6FE4A46534681 -:101DE0004146384608B0BDE8F04700F007BCFFF7B1 -:101DF0009BFE002008B0BDE8F08700002DE9F84FF9 -:101E00000023C0E90133254B044640F8183B0F4638 -:101E1000FFF750FF04F12800FFF752FF04F14808D4 -:101E200004F582554646083530462036FFF748FF10 -:101E3000AE42F9D104F580554FF480534FF00009BC -:101E4000C5E91339C5F848800123EE6504F58758C4 -:101E500004F58456C5F8549085F8583085F86030FC -:101E6000083608F108084FF0000A4FF0000B46E969 -:101E700008ABA6F11800FFF71DFF203646F8289C96 -:101E80004645F4D185F8C97017B1054800F0A0FBAC -:101E9000044B63612046BDE8F88F00BF384A000854 -:101EA000104A00080064004010B5044B197804463D -:101EB0004A1C1A70FFF7A2FF204610BD14380020FC -:101EC0002DE9F047002950D0294B2A4FB7FBF1F5F7 -:101ED00099428CBF0A231123581EB5FBF3FC03FB68 -:101EE0001C53C4B22BB102280346F5D80020BDE82C -:101EF000F0870CF1FF36B6F5806FF7D2C4EBC40E55 -:101F00000EF103034FEAE309C3F3C703A4EB03088D -:101F100009F1010A4FF47A755FFA88F009FB05555B -:101F20005AFA88F8B5FBF8F5B5F5617FC1BF0EF137 -:101F3000FF33C3F3C703E01AC0B25C1C50FA84F449 -:101F40000CFB04F4B7FBF4F4A142CFD1013BDBB2AC -:101F50000F2BCBD80138C0B20728C7D80021107189 -:101F600016809170D3700120C1E70846BFE700BF1B -:101F70003F420F000051250270B505460E464FF452 -:101F80007A746B695B6803F00103B3424FF00100A0 -:101F900004D001F0A5FC013CF3D1204670BD000047 -:101FA00030B54269936913F0700F16D000230B4CC3 -:101FB000936103F1840200EB421211794D0709D5B8 -:101FC000890707D5416954F823508D60117941F094 -:101FD000040111710133032BEBD130BD244A0008F9 -:101FE00073B51D46436916469A68D207044609D55B -:101FF0009A6801219960C2F34002CDE90065002191 -:10200000FFF76CFE63699A68D1050BD59A684FF4A7 -:1020100080719960C2F34022CDE90065012120461C -:10202000FFF75CFE63699A68D2030BD59A684FF498 -:1020300080319960C2F34042CDE90065022120461B -:10204000FFF74CFE204602B0BDE87040FFF7A8BF86 -:10205000F8B50446466900296CD106F10C073868CA -:1020600080076AD006EB01153868D5F8B00110F08A -:10207000040FD5F8B0011ABFC00840F00040400D71 -:10208000A061D5F8B0C11CF0020F1CBF40F0804029 -:10209000A061D5F8B40106EB011100F00F0084F83F -:1020A0002400D1F8B8012077D1F8B801000A607790 -:1020B000D1F8B801000CA077D1F8B801000EE07794 -:1020C000D1F8BC0184F82000D1F8BC01000A84F8E2 -:1020D0002100D1F8BC01000C84F82200D1F8BC1119 -:1020E000090E84F823103821396004F1340004F11A -:1020F000180104F1240551F8046B40F8046BA9425F -:10210000F9D109880180C4E90A23214600232386E6 -:1021100051F8283B2046DB6B984704F58052204657 -:1021200092F8C83043F0040382F8C830BDE8F840A4 -:10213000FFF736BF06F1100791E7F8BD10B504466A -:1021400000F04EFA02460B4652EA030102D0013A71 -:1021500063F100030449086820B12146BDE810403E -:10216000FFF776BF10BD00BF10380020F8B500F5AE -:1021700083511E46FFF7D2FCDFF844C0083100242B -:1021800004F1840500EB45152B795F070ED4DB06BF -:102190000CD5D1E900739742B34107D243695CF88B -:1021A00024709F602B7943F004032B710134032CBE -:1021B00001F12001E4D1BDE8F840FFF7B5BC00BF54 -:1021C000244A000808B5FFF7A9FCFFF7E9FEBDE8BF -:1021D0000840FFF7A9BC0000F8B5436905469868B8 -:1021E00000F0E050B0F1E05F0F461FD0E8B1FFF71C -:1021F00095FC05F583541034002606F1840305EBA5 -:1022000043131B791A0706D50136032E04F1200467 -:10221000F3D1012007E05B07F6D42146384600F0F1 -:1022200039FA0028F0D1FFF77FFCF8BD0120FCE768 -:1022300000F5805008B5FFF771FCC06DFFF750FB4B -:10224000FFF772FC43090CBF0120002008BD00000D -:10225000F8B51D46002313700F4606461446FFF7D7 -:10226000E7FF80F00100387025B129463046FFF7BE -:10227000B3FF2070F8BD00002DE9B8410C461546AB -:102280001F46804600F0ACF90B462178024609B99A -:10229000287850B14046FFF769FFFFF793FF3B46B0 -:1022A0002A462146FFF7D4FF0120BDE8B88100008F -:1022B00010B5FFF733FC174BDA6942F00072DA61B0 -:1022C0001A6942F000721A611A6900F5805422F00E -:1022D00000721A61FFF728FC94F8C830DB0718D4A5 -:1022E000B9B103211320FFF719FC01F0C7F903214D -:1022F000142001F0C3F90321152001F0BFF994F86F -:10230000C83043F0010384F8C830BDE81040FFF73F -:102310000BBC10BD001002402DE9F04700F58055C0 -:1023200088B095F8C930012B0446884616467FD8F8 -:10233000804F57F823200AB947F82300D7F800A0A8 -:10234000C4F80C802674BAF1000F63D095F8C93038 -:10235000012B6FD001212046FFF7AAFFFFF7DEFB1C -:102360006269136823F0020313606269136843F023 -:1023700001031360636900275F6101212046FFF7B5 -:10238000D3FBFFF7F9FD002800F09580E86DFFF71B -:1023900095FA04F58359BA4609F10809202200216B -:1023A0006846FEF7C7FF02A8FFF784FCCDF818A027 -:1023B0006A4609EB07030DF1180E9446BCE80300CA -:1023C000F44518605960624603F10803F5D1DCF862 -:1023D0000000186020379CF804201A71602FDDD1AE -:1023E00095F8C8306FF38203002785F8C8306A4635 -:1023F00041462046ADF80070ADF802708DF80470CB -:10240000FFF75EFD636948BB4FF400421A6008B0F5 -:10241000BDE8F08741F2D00002F01CFA814610B10D -:102420005146FFF7EBFCC7F80090B9F1000F8DD1D2 -:102430000020ECE7386803681B6B984701460028CA -:1024400088D13868FFF734FF3868036832465B6824 -:102450004146984700287FF47DAFE9E761221A6082 -:102460009DF802309DF803201B06120402F470222E -:1024700003F040731343BDF80020C2F30902134375 -:102480009DF804201205022E02F4E0020CBF4FF06A -:1024900000410021134362690B43D3616369132236 -:1024A0005A616269136823F00103136039462046BC -:1024B000FFF762FD08B96369A6E795F8C93093BBD9 -:1024C0006169D1F8002242F00102C1F8002261697D -:1024D000D1F8002222F47C5222F00E02C1F8002230 -:1024E0006169D1F8002242F46062C1F80022626999 -:1024F000C2F814326269C2F80432626941F6FF71AF -:10250000C2F80C126269C2F840326269C2F8443201 -:1025100063690122C3F81C226269D2F8003223F0F9 -:102520000103C2F8003295F8C83043F0020385F881 -:10253000C8306CE71038002008B500F051F850EAB8 -:102540000103024602D0421E61F10001044B1868EB -:1025500010B10B46FFF744FDBDE8084001F064B838 -:102560001038002008B50020FFF7E8FDBDE808405E -:1025700001F05AB808B50120FFF7E0FDBDE80840BA -:1025800001F052B800B59BB0EFF3098168226846AC -:10259000FEF7BEFEEFF30583014B9B6BFEE700BF2A -:1025A00000ED00E008B5FFF7EDFF000000B59BB0BF -:1025B000EFF3098168226846FEF7AAFEEFF3058370 -:1025C000014B5B6BFEE700BF00ED00E0FEE70000A3 -:1025D0000FB408B5029801F019F9FEE701F02EBB1F -:1025E00001F004BB13B56C4684E80600031D94E8B3 -:1025F000030083E80500012002B010BD73B58568B3 -:10260000019155B11B885B0707D4D0E900369B6B5D -:102610009847019AC1B23046A847012002B070BD68 -:10262000F0B5866889B005460C465EB1BDF8383015 -:102630005B070AD4D0E900379B6B98472246C1B2AA -:102640003846B047012009B0F0BD00220023CDE993 -:1026500000230023ADF808300A4603AB01F1080659 -:10266000106851681C4603C40832B2422346F7D1B1 -:10267000106820609288A280FFF7B2FF0423ADF8B3 -:1026800008302B68CDE90001DB6B69462846984786 -:10269000D8E7000030B503680968DD0FB5EBD17FDE -:1026A00023F0604421F060424FEAD1700BD0002B40 -:1026B000B8BFA40C0029B8BF920C944202D034BF1A -:1026C0000120002030BD944205D1C1F38070C3F3D6 -:1026D00080738342F6D194422CBF00200120F1E7A1 -:1026E0002DE9F041456A15B94162BDE8F0814B68BA -:1026F00023F06047C3F38A464FEAD37EC3F3807862 -:1027000016EA230638BF3E46AC462B465A68BEEB57 -:10271000D27F22F060440AD0002A18DAA40CB44216 -:1027200017D19D420FD10D60DEE71346EEE7A742B9 -:1027300007D102F08044C2F3807242450BD054B1FD -:10274000EFE708D2EDE7CCF800100B60CDE7B4421C -:1027500001D0B442E5D81A689C46002AE5D1196038 -:10276000C3E700002DE9F047089D01F007044FEA98 -:10277000D508224405F0070500EBD1004FF47F494E -:10278000944201D1BDE8F08704F0070705F0070A7D -:1027900057453E4638BF5646C6F10806111B8E42C5 -:1027A00028BF0E46E10808EBD50E415C13F80EC0B9 -:1027B000B94029FA06F721FA0AF1FFB28CEA0101C1 -:1027C00047FA0AF739408CEA010C03F80EC034448A -:1027D0003544D5E780EA0120082341F2210201B205 -:1027E0004000002980B203F1FF33B8BF504013F01E -:1027F000FF03F4D17047000038B50C468D18A54290 -:1028000000D138BD14F8011BFFF7E4FFF7E7000023 -:1028100042684AB1136843604389818901339BB29E -:102820009942438138BF83811046704770B588B0A4 -:10283000202204460D4668460021FEF77BFD204617 -:102840000495FFF7E5FF024658B16B46054608AE12 -:102850001C4603CCB44228606960234605F1080594 -:10286000F6D1104608B070BD082817D909280CD039 -:102870000A280CD00B280CD00C280CD00D280CD01A -:102880000E2814BF4020302070470C2070471020C5 -:1028900070471420704718207047202070470000B0 -:1028A000082817D90C280CD910280CD914280CD9B1 -:1028B00018280CD920280CD930288CBF0F200E20C6 -:1028C0007047092070470A2070470B2070470C2082 -:1028D00070470D20704700002DE9F843078C072F43 -:1028E00004461ED9D0E9029800254FF6FF73C5F1C2 -:1028F0002006A5F1200029FA05F108FA06F628FAC3 -:1029000000F031430143C9B21846FFF763FF0835B1 -:10291000402D0346EBD1E1693A46BDE8F843FFF7A5 -:102920006BBF4FF6FF70BDE8F883000010B54B6831 -:1029300023B9CA8A63F30902CA8210BD04691A68FE -:102940001C600361C38A013BC3824A60EFE7000059 -:102950002DE9F84F1D46CB8A0F46C3F3090105291F -:10296000814692460B4630D00020AAB207F11A04E5 -:102970009EB2042E1FFA80F80FD8904503F1010390 -:1029800006D3FB8A0A4462F30903FB8201201AE0A2 -:102990001AF80060E6540130EAE79045F1D2A1F15F -:1029A000050B1C237C68BBFBF3F203FB12BB1FFA75 -:1029B0008BF6002C45D14846FFF72AFF044638B96C -:1029C00078606FF00200BDE8F88F4FF00008E6E78E -:1029D000002606607860ADB24FF0000B454510D977 -:1029E0000AEB0803221D13F8011B9155B1B208F13F -:1029F00001081B291FFA88F82BD0454506F101066E -:102A0000F1D8FB8AC3F30902154465F30903BCE757 -:102A1000013292B21C462368002BF9D16B1F0B4484 -:102A20001C21B3FBF1F301339BB29A42D3D2BBF129 -:102A3000000FD0D14846FFF7EBFE20B9C4F800B034 -:102A4000BFE70122E7E7C0F800B05E462060044619 -:102A5000C1E74545D5D94846FFF7DAFE08B92060F9 -:102A6000AFE7C0F800B0002620600446B6E70000DB -:102A70002DE9F04F2DED028B1C4683B05B6901926E -:102A800007468846002B00F09A80238C2BB1E26920 -:102A9000002A00F09480072B35D807F10C00FFF7CF -:102AA000B7FE054638B96FF00205284603B0BDEC05 -:102AB000028BBDE8F08F14220021FEF73BFC228C34 -:102AC000E16905F10800FEF723FC208C013080B29B -:102AD000FFF7E6FEFFF7C8FE013880B22084013020 -:102AE00028746369228C1B782A4403F01F0363F067 -:102AF0003F0348F000411372384669602946FFF7EA -:102B0000EFFD0125D1E700F10C034FF0000908EEBD -:102B1000103A4FF0800A4E464D4618EE100AFFF765 -:102B200077FE83460028BED014220021FEF702FC67 -:102B3000002E3AD1019BABF8083002220BF1080EAF -:102B40001FFA82FC0CF10100BCF1060F218C80B24F -:102B500001D88E422BD3FFF7A3FEFFF785FE6269F3 -:102B60001278013802F01F028E4208BF4FF0400A6F -:102B700042EA49121BFA80F14AEA020A013048F09F -:102B8000004281F808A08BF81000CBF804205946C9 -:102B90003846FFF7A5FD238C0135B3422DB289F0ED -:102BA00001094FF0000AB8D17FE70022C6E7E169CA -:102BB000895D0EF802100136B6B20132C0E76FF03F -:102BC000010572E7F8B515460E463022002104468D -:102BD0001F46FEF7AFFB069B6360B5F5001F079B22 -:102BE000A76034BF6A094FF6FF72A36297B2E6612D -:102BF00004F1100000239A4206D800230360A78244 -:102C0000E3822383E360F8BD06600133304620365B -:102C1000F1E7000003781BB94BB2002BC8BF01706D -:102C20007047000000787047F8B50C46C969074640 -:102C300011B9238C002B37D1257E1F2D34D838783D -:102C400028BB228C072A2CD8268A36F003032BD1E6 -:102C50004FF6FF70FFF7D0FD20F001003102400475 -:102C600041EA0561400C41EA40254FF6FF722346D8 -:102C700029463846FFF7FCFE002807DD6269137815 -:102C80000133DBB21F2B88BF00231370F8BD218AEC -:102C90002D0645EA012505432046FFF71DFE0246A5 -:102CA000E5E76FF00300F1E76FF00100EEE70000E9 -:102CB00070B58AB0044616460021282268461D4693 -:102CC000FEF738FBBDF83830ADF810300F9B059398 -:102CD0009DF840308DF81830119B07936946BDF878 -:102CE0004830ADF820302046CDE90265FFF79CFF63 -:102CF0000AB070BD2DE9F041D36905460C46164671 -:102D00000BB9138C5BBB377E1F2F28D895F800803A -:102D1000B8F1000F26D03046FFF7DEFD33782102F0 -:102D200041EAC33141EA0801338A41EA076141EAD5 -:102D300003410246334641F080012846FFF798FEE2 -:102D400000280ADD3378012B07D17269137801332B -:102D5000DBB21F2B88BF00231370BDE8F0816FF03A -:102D60000100FAE76FF00300F7E70000F0B58BB061 -:102D700004460D4617460021282268461E46FEF7E7 -:102D8000D9FA9DF84C305A1E534253418DF8003009 -:102D90009DF84030ADF81030119B05939DF84830F8 -:102DA0008DF81830149B07936A46BDF85430ADF87F -:102DB000203029462046CDE90276FFF79BFF0BB075 -:102DC000F0BD0000406A00B104307047436A1A68E1 -:102DD000426202691A600361C38A013BC382704781 -:102DE0002DE9F041D0F82080194E14461D46414689 -:102DF000002709B9BDE8F081D1E90223A21A65EBE9 -:102E00000303964277EB03031ED2036A8B420DD174 -:102E1000FFF78CFD036A1B68036203690B60C38ABA -:102E20000161016A013BC3828846E2E7FFF77EFD4C -:102E30000B68C8F8003003690B60C38A0161013B6D -:102E4000C382D8F80010D4E788460968D1E700BFEC -:102E500080841E002DE9F04F8BB00D46DDF85090B8 -:102E600014469B468046002800F01981B9F1000FF6 -:102E700000F01581531E3F2B00F21181012A03D16E -:102E8000BBF1000F40F00B810023CDE90833B8F807 -:102E90001430B5EBC30F4FEAC30703D300200BB0C8 -:102EA000BDE8F08F2B199F42D8F80C303ABF7F1B3A -:102EB000FFB227461BB9D8F81030002B7AD0272D47 -:102EC0004ED8C5F12806B7424FF000032CBFF6B22A -:102ED0003E4600932946D8F8080008AB3246FFF773 -:102EE00041FCA7EB060A35445FFA8AFAB8F81430B9 -:102EF00003F10053053BDB000493D8F80C30039337 -:102F00002821039B13B1BAF1000F2CD1D8F810007F -:102F100040B1BAF1000F05D0009608AB5246691ACD -:102F2000FFF720FC38B2002FB8D066070AD00AABF2 -:102F300003EBD401624211F8083C02F0070213418E -:102F400001F8083C082C3CD9102C40F2B580202C0C -:102F500040F2B780BBF1000F00F09C80082334E002 -:102F6000BA460026C2E7049BE02B28BFE023069365 -:102F70000B44AB42059314D95A1B03980096924513 -:102F800034BF5246D2B2691A08AB04300792FFF739 -:102F9000E9FB079A1644AAEB020A1544F6B25FFA57 -:102FA0008AFA049B069A05999B1A0493039B1B6853 -:102FB0000393A6E70093D8F8080008AB3A462946E1 -:102FC000AEE7BBF1000F13D00123B4EBC30F6CD0FD -:102FD000082C12D89DF82030621E23FA02F2D50781 -:102FE00006D54FF0FF3202FA04F423438DF8203067 -:102FF0009DF8203089F8003051E7102C12D8BDF828 -:103000002030621E23FA02F2D10706D54FF0FF32BC -:1030100002FA04F42343ADF82030BDF82030A9F8BB -:1030200000303CE7202C0FD80899631E21FA03F3E7 -:10303000DA0705D54FF0FF3202FA04F40C43089486 -:10304000089BC9F800302AE7402C2BD0DDE9086541 -:10305000611EC4F12102A4F1210326FA01F105FA4F -:1030600002F225FA03F311431943CB0712D50122CB -:10307000A4F12003C4F1200102FA03F322FA01F1C2 -:10308000A240524243EA010363EB430332432B4322 -:10309000CDE90823DDE90823C9E90023FFE66FF045 -:1030A0000100FCE66FF00800F9E6082CA0D9102C0E -:1030B000B3D9202CEED8C3E7BBF1000FADD002236B -:1030C00083E7BBF1000FBBD004237EE730B5012AB4 -:1030D000144638BF0124402C85B028BF4024002569 -:1030E000012ACDE9025518D81B788DF808306307FE -:1030F0000AD004AB03EBD405624215F8083C02F099 -:103100000702934005F8083C00910346224600213F -:1031100002A8FFF727FB05B030BD082AE4D9102A22 -:1031200003D81B88ADF80830E1E7202A8DBFD3E92A -:1031300000231B680293CDE90223D8E710B5CB68C2 -:103140001BB98B600B618B8210BD04691A681C600F -:103150000361C38A013BC382CA60F0E703064CBF28 -:10316000C0F3C0300220704708B50246FFF7F6FFF3 -:10317000022806D15306C2F30F2001D100F003004C -:1031800008BDC2F30740FBE72DE9F04F93B0CDE94E -:1031900003230A6804461046FFF7E0FF022814BF25 -:1031A000C2F306260026002A0D46824680F2F281EE -:1031B00012F0C04940F0EE81097B002900F0EA815D -:1031C000022803D02378B34240F0E781C2F30463BE -:1031D0000693104602F07F030593FFF7C5FF059B9A -:1031E00029444FEA834848EA0A4848EA4668CE78C4 -:1031F00000230022CDE90823F309834648EA0008AA -:10320000029367D0059B009302466768534608A95E -:103210002046B847002800F0C381276A4FB94146CD -:1032200004F10C00FFF702FB074690B96FF00200B3 -:1032300054E03B6998450DD03F68002FF9D14146D5 -:1032400004F10C00FFF7F2FA07460028EED0236ADB -:103250003B60276297F817C006F01F08CCF3840C78 -:10326000ACEB08001FFA80FE0028B8BF0EF120006A -:10327000A8EB0C031FFA83FED7E90221B8BF00B206 -:10328000002B0793BEBF0EF120031BB2079352EA37 -:10329000010338D0039BDFF824E39A1A049B4FF014 -:1032A000000C63EB010196457CEB01032BD36B7B98 -:1032B00097F81AE0734519D1029B002B78D00128AA -:1032C00021DC7868F8B9DFF8F0C2944570EB0103AF -:1032D00016D337E0276A27B96FF00C0013B0BDE8AA -:1032E000F08F3B699845B5D03F68F4E7B24890420B -:1032F0007CEB010301D30020F0E7029B002BFAD006 -:10330000079B0F2B17DCFA7DB30002F0030203F0DA -:103310007C031343FB7539462046FFF707FB6B7BA5 -:10332000BB76029B3BB9FB7DC3F38402013262F39F -:103330008603FB75D0E76A7BBB7E9A42DBD1029B9A -:10334000002B35D0B309022B32D0039BBB60049B0A -:10335000FB60142200210DA8FDF7ECFF039B0A93EC -:10336000049B0B932B1D0C932B7BADF83EB0013BC4 -:10337000DBB2ADF83C30069B8DF84230059B8DF8F2 -:10338000433094F82C308DF840A083F001038DF881 -:1033900044308DF84180A3680AA920469847FB7DF8 -:1033A000C3F38403013303F01F039B02FB82A2E7F4 -:1033B000FB7DC6F34012B2EBD31F40F0F480C3F3A1 -:1033C0008403434540F0F280029A2B7BB609002A21 -:1033D0004DD0F2075DD4032B40F2EB80039BBB6022 -:1033E000049BFB602B7BAE1D033BDBB232463946B0 -:1033F00004F10C00FFF7ACFA00280CDA394620463D -:10340000FFF794FAFB7DC3F38403013303F01F033A -:103410009B02FB820AE7DDE90884AB883B834FF619 -:10342000FF73C9F12000A9F1200228FA09F104FA7A -:1034300000F0014324FA02F211431846C9B2FFF723 -:10344000C9F909F10809B9F1400F0346E9D1B88279 -:103450002A7B033AD2B23146FFF7CEF9FB7DB88220 -:10346000DA43C2F3C01262F3C713FB7543E786B9B0 -:103470002E1D013BDBB23246394604F10C00FFF74A -:1034800067FA0028BADB2A7BB88A013AD2B2314601 -:10349000E2E7F98AC1F30901013B0429DAB25BD8FA -:1034A000281D002307F11B069A4208D910F801CB0A -:1034B00006F801C0013101330529DBB2F4D10399CB -:1034C0000A9104990B91934207F11B010C9138BFAB -:1034D000043379680D9134BF55FA83F300230E93BA -:1034E000FB8AADF83EB0C3F309031A44069B8DF87E -:1034F0004230059B8DF8433094F82C30ADF83C20D9 -:1035000083F001038DF8443000238DF840A08DF83E -:1035100041807B602A7BB88A013A291DFFF76CF94C -:103520003B8BB882834203D1A3680AA920469847FF -:1035300020460AA9FFF702FEFB7DBA8AC3F3840383 -:10354000013303F01F039B02FB823B8B9A420CBFAB -:1035500000206FF01000C1E67B68002BAFD0052083 -:1035600001E01C3033461E68002EFAD1091A081DEE -:103570002E1D184401EB090CBCF11B0F5FFA89F3F7 -:103580009DD89A429BD916F8013B00F8013B09F1FE -:103590000109EFE76FF00900A0E66FF00A009DE671 -:1035A0006FF00B009AE66FF00D0097E66FF00E00DB -:1035B00094E66FF00F0091E640420F0080841E00F9 -:1035C000EFF3098305494A6B22F001024A6368332D -:1035D00083F30988002383F31188704700EF00E02C -:1035E000302080F3118862B60C4B0D4AD96821F463 -:1035F000E0610904090C0A43DA60D3F8FC200949A8 -:1036000042F08072C3F8FC200A6842F001020A60AE -:103610002022DA7783F82200704700BF00ED00E037 -:103620000003FA05001000E010B5302383F3118881 -:103630000E4B5B6813F4006314D0F1EE103AEFF315 -:103640000984683C4FF08073E361094BDB6B2366B0 -:1036500084F3098800F098F810B1064BA36110BDFF -:10366000054BFBE783F31188F9E700BF00ED00E0AD -:1036700000EF00E0030600080606000800F16043C2 -:1036800003F561430901C9B283F80013012200F078 -:103690001F039A4043099B0003F1604303F5614314 -:1036A000C3F880211A60704700F16040090100F5FD -:1036B0006D40C9B2017670470023037582680369C3 -:1036C0001B6899689142FBD25A680360426010609F -:1036D0005860704700230375826803691B68996806 -:1036E0009142FBD85A68036042601060586070478E -:1036F00008B50846302383F311880B7D032B05D0D2 -:10370000042B0DD02BB983F3118808BD8B690022DF -:103710001A604FF0FF338361FFF7CEFF0023F2E71B -:10372000D1E9003213605A60F3E70000FFF7C4BF2D -:10373000054BD9680875186802681A605360012241 -:103740000275D860FCF748BF2038002030B50C4B1C -:10375000DD684B1C87B004460FD02B46094A6846EB -:1037600000F0FEF82046FFF7E3FF009B13B1684628 -:1037700000F000F9A86907B030BDFFF7D9FFF9E7FD -:1037800020380020F1360008044B1A68DB68906886 -:103790009B68984294BF0020012070472038002089 -:1037A000084B10B51C68D86822681A605360012263 -:1037B0002275DC60FFF78EFF01462046BDE8104011 -:1037C000FCF70ABF20380020044B1A68DB689268B7 -:1037D0009B689A4201D9FFF7E3BF70472038002069 -:1037E00038B5074C07490848012300252370656058 -:1037F00000F00AFB0223237085F3118838BD00BF57 -:10380000483A00207C4A00082038002008B572B6EB -:10381000044B186500F0CEF900F092FA024B032237 -:103820001A70FEE720380020483A002000F0B4B8B3 -:10383000EFF3118020B9EFF30583302282F3118872 -:103840007047000010B530B9EFF30584C4F30804E5 -:1038500014B180F3118810BDFFF7B6FF84F311880F -:10386000F9E700008B60022308618B8208467047ED -:103870008368A3F1840243F8142C026943F8442CB2 -:10388000426943F8402C094A43F8242CC26843F8A3 -:10389000182C022203F80C2C002203F80B2C044AEB -:1038A00043F8102CA3F12000704700BFF105000879 -:1038B0002038002008B5FFF7DBFFBDE80840FFF720 -:1038C00035BF0000024BDB6898610F20FFF730BF67 -:1038D00020380020302383F31188FFF7F3BF000066 -:1038E00008B50146302383F311880820FFF72EFF27 -:1038F000002383F3118808BD064BDB6839B14268A9 -:1039000018605A60136043600420FFF71FBF4FF038 -:10391000FF307047203800200368984206D01A68AC -:103920000260506099611846FFF700BF70470000C1 -:1039300010B50A4C23699A6891420CD85A68816084 -:103940000360426010609A685860511A99604FF0A5 -:10395000FF33A36110BD1B68891AECE720380020F3 -:1039600010B4C0E9032300235DF8044B4361FFF763 -:10397000DFBF0000036881689A680A449A60426861 -:1039800013605A6000230360024B4FF0FF329A61CC -:10399000704700BF2038002070B5124DEB692A46F1 -:1039A0000133EB6152F8103F934206D09A68013A16 -:1039B0009A6030262C69A36803B170BDD4E9002158 -:1039C0000A605160236083F31188D4E903312046F3 -:1039D000984786F3118861690029EBD02046FFF7EC -:1039E000A7FFE7E72038002000207047FEE700002F -:1039F000704700004FF0FF3070470000BFF34F8F5B -:103A0000024AD368DB07FCD4704700BF00200240A5 -:103A100008B5074B1B7853B9FFF7F0FF054B1A6940 -:103A2000120641BF044A5A6002F188325A6008BD4A -:103A3000603A0020002002402301674508B5054B8D -:103A40001B7833B9FFF7DAFF034A136943F08003A9 -:103A5000136108BD603A0020002002407F289ABF11 -:103A600000F58030C0020020704700004FF4006075 -:103A700070470000802070477F2808B50BD8FFF7FB -:103A8000EDFF00F500630268013204D10430834287 -:103A9000F9D1012008BD0020FCE700007F2810B507 -:103AA00004461CD8FFF7AAFFFFF7B2FF0D4BF32225 -:103AB000DA6002221A61FFF7D1FF58611A6942F0F9 -:103AC00040021A614FF40061FFF798FF00F034F9EB -:103AD000FFF7B4FF2046BDE81040FFF7CDBF002040 -:103AE00010BD00BF002002402DE9F84312F0010391 -:103AF000144606D01F4B40F2F3221A600020BDE8A6 -:103B0000F88385181C4A954204D91A4A4FF43E712D -:103B10001160F3E7FFF77CFFFFF770FFDFF86880C5 -:103B2000451A4FF00109012C05EB01060F4603D899 -:103B3000FFF784FF0120E2E73B88C8F8109033804C -:103B40000020FFF75BFFC8F81000338831F8022B24 -:103B50009BB29A420CD0074B40F20F321A60074BCF -:103B60001E60074B1C60074B1F60FFF767FFC6E72F -:103B7000023CD8E75C3A002000000408503A0020DC -:103B8000583A0020543A002000200240084908B565 -:103B90000B7828B11BB9FFF73BFF01230B7008BD61 -:103BA000002BFCD0BDE808400870FFF747BF00BFFE -:103BB000603A002008B54FF420414FF0005000F06B -:103BC000BDF8BDE808404FF400514FF0805000F0C0 -:103BD000B5B800000846114600F05EBE012000F0B6 -:103BE0005BBE0000084600F075BE000030B583B033 -:103BF000FFF71EFE0E4B0F4DDB692A684FF47A71FA -:103C000001FB03F3934237BF0B4A0B495168146819 -:103C10002B602EBFD1E90041013151601C1941F1E7 -:103C200000010191FFF70EFE0199204603B030BD5F -:103C300020380020643A0020683A002030B583B074 -:103C4000FFF7F6FD114B124DDB692A684FF47A71CC -:103C500001FB03F3934237BF0E4A0E4951681468C3 -:103C60002B602EBFD1E90041013151601C1941F197 -:103C700000010191FFF7E6FD01994FF47A720023EC -:103C80002046FCF795FA03B030BD00BF2038002075 -:103C9000643A0020683A002010B50244064BD2B2C4 -:103CA000904200D110BD441C00B253F8200041F8EE -:103CB000040BE0B2F4E700BF502800400F4B30B5D2 -:103CC0001C6A240407D41C6A44F440741C621C6AF5 -:103CD00044F400441C620A4C236843F4807323605C -:103CE0000244084BD2B2904200D130BD441C00B215 -:103CF00051F8045B43F82050E0B2F4E700100240B2 -:103D0000007000405028004007B5012201A90020A2 -:103D1000FFF7C2FF019803B05DF804FB13B504463A -:103D2000FFF7F2FFA04205D0012201A90020019473 -:103D3000FFF7C4FF02B010BD7047000070470000DD -:103D400070470000074B45F255521A6002225A6034 -:103D500040F6FF729A604CF6CC421A60024B012288 -:103D60001A70704700300040743A0020034B1B78F3 -:103D70001BB1034B4AF6AA221A607047743A00201E -:103D800000300040044B1A682AB902F1804202F563 -:103D90000432526A1A607047703A0020024B4FF0AA -:103DA00080725A62704700BF0010024008B5FFF7EA -:103DB000E9FF024B1868C0F3407008BD703A00205C -:103DC00070470000FEE700000A4B0B480B4A904288 -:103DD0000BD30B4BDA1C121AC11E22F003028B42CA -:103DE00038BF00220021FDF7A5BA53F8041B40F8A4 -:103DF000041BECE7EC4B0008583C0020583C00202A -:103E0000583C0020FEE7000070B51B4B0163002505 -:103E1000044686B0586085620E46FFF7E1FB04F168 -:103E20001003C4E904334FF0FF33A361134BE56182 -:103E3000D969A5600A462B46C4E9082304F1340178 -:103E4000C4E900440E4AE562256580232046FFF759 -:103E500009FD0123E0600B4A03750092726801922C -:103E6000B268CDE90223084B6846CDE90435FFF777 -:103E700021FD06B070BD00BF483A00202038002068 -:103E8000884A00088D4A0008053E00084B684360D8 -:103E90008B688360CB68C3600B6943614B690362C5 -:103EA0008B6943620B6803607047000008B51B4BC9 -:103EB0009A6A42F4FC029A629A6A22F4FC029A62BA -:103EC0009A6A5A6942F4FC025A61154A5B691146C2 -:103ED0004FF09040FFF7DAFF02F11C0100F580601F -:103EE000FFF7D4FF02F1380100F58060FFF7CEFF45 -:103EF00002F1540100F58060FFF7C8FF02F1700184 -:103F000000F58060FFF7C2FF02F18C0100F58060D0 -:103F1000FFF7BCFFBDE8084000F05AB800100240AF -:103F2000944A000808B500F093F9FFF759FCBDE882 -:103F30000840FFF727BF00007047000010B5214C74 -:103F4000A36A63F4FC03A362A36A03F4FC03A36201 -:103F50004FF0FF32A36A23692261236900232361A2 -:103F60002169E168E260E268E360E268E2691649BB -:103F700042F08052E261E2690A6842F480720A60AB -:103F8000226A02F44072B2F5407F1EBF4FF48032C5 -:103F900022622362236A1B0407D4236A43F440731A -:103FA0002362236A43F40043236200F031F9A369DA -:103FB000064A43F00103A361A369136843F0200399 -:103FC000136010BD0010024000700040000001406E -:103FD0001E4B1A6842F001021A601A689007FCD55D -:103FE0005A6822F003025A605A6812F00C02FBD1A0 -:103FF000196801F0F90119605A601A6842F48032B8 -:104000001A601A689103FCD5114A5A604FF40452A1 -:10401000DA6230221A631A6842F080721A601A68F3 -:104020009201FCD50B4912220A600A6802F00702CD -:10403000022AFAD15A6842F002025A605A6802F023 -:104040000C02082AFAD11A6B1A637047001002405A -:1040500000241D0000200240084A08B55169136879 -:104060000B4003F00103536123B1054A13680BB100 -:1040700050689847BDE80840FFF7D6BA00040140F1 -:10408000783A0020084A08B5516913680B4003F0DC -:104090000203536123B1054A93680BB1D068984776 -:1040A000BDE80840FFF7C0BA00040140783A00209C -:1040B000084A08B5516913680B4003F004035361C3 -:1040C00023B1054A13690BB150699847BDE8084010 -:1040D000FFF7AABA00040140783A0020084A08B560 -:1040E000516913680B4003F00803536123B1054A7B -:1040F00093690BB1D0699847BDE80840FFF794BABF -:1041000000040140783A0020084A08B55169136854 -:104110000B4003F01003536123B1054A136A0BB13E -:10412000506A9847BDE80840FFF77EBA0004014096 -:10413000783A0020174B10B55A691C68144004F4F3 -:1041400078725A61A30604D5134A936A0BB1D06AF8 -:104150009847600604D5104A136B0BB1506B984713 -:10416000210604D50C4A936B0BB1D06B9847E2053E -:1041700004D5094A136C0BB1506C9847A30504D5BC -:10418000054A936C0BB1D06C9847BDE81040FFF71F -:104190004BBA00BF00040140783A00201A4B10B51A -:1041A0005A691C68144004F47C425A61620504D5C3 -:1041B000164A136D0BB1506D9847230504D5134A69 -:1041C000936D0BB1D06D9847E00404D50F4A136E80 -:1041D0000BB1506E9847A10404D50C4A936E0BB1F5 -:1041E000D06E9847620404D5084A136F0BB1506F24 -:1041F0009847230404D5054A936F0BB1D06F9847B5 -:10420000BDE81040FFF710BA00040140783A0020E2 -:10421000062108B50846FFF731FA06210720FFF707 -:104220002DFA06210820FFF729FA06210920FFF7B9 -:1042300025FA06210A20FFF721FA06211720FFF7A9 -:104240001DFABDE8084006212820FFF717BA000034 -:1042500008B5FFF773FE00F067F800F03DF8FFF7D0 -:104260006BFEBDE8084000F05DB8000002684368DE -:104270001143016003B1184770470000143000F08B -:104280002FBA00004FF0FF33143000F029BA0000BD -:10429000383000F0A5BA00004FF0FF33383000F09E -:1042A0009FBA0000143000F0F5B900004FF0FF3164 -:1042B000143000F0EFB90000383000F04FBA0000C1 -:1042C0004FF0FF32383000F049BA0000012914BF26 -:1042D0006FF013000020704700F06CB8044B0360CF -:1042E0000023C0E90233436001230374704700BF19 -:1042F0003C4B000838B5C36904460D461BB9042180 -:104300000844FFF7B3FF294604F1140000F0A6F9B2 -:10431000002806DA201D4FF40061BDE83840FFF7A1 -:10432000A5BF38BD00F00EB80023054A1946013379 -:10433000102BC2E9001102F10802F8D1704700BF4A -:10434000783A00204FF0E023044A5A6100229A6133 -:1043500007221A6108210B20FFF7A6B93F190100B7 -:1043600008B5302383F31188FFF760FA002383F345 -:10437000118808BD08B5FFF7F3FFBDE80840FFF757 -:1043800053B90000026843681143016003B1184744 -:1043900070470000024A136843F0C003136070477F -:1043A00000380140024A136843F0C00313607047AD -:1043B0000044004037B51D4C1D4D2046FFF78EFFD1 -:1043C000009404F114001B490023202200F038F966 -:1043D0002022009404F13800174B184900F0B2F97C -:1043E000174BC4E91735174C0C212520FFF746F968 -:1043F0002046FFF773FF04F11400134900940023D3 -:10440000202200F01DF904F13800104B10490094EF -:10441000202200F097F90F4B0C212620C4E9173514 -:1044200003B0BDE83040FFF729B900BFF83A0020DB -:1044300000512502D03B002095430008103C00208D -:1044400000380140643B0020F03B0020A5430008F9 -:10445000303C0020004400402DE9F047C66D37682D -:10446000F46934622107054619D014F0080118BF19 -:104470004FF48071E20748BF41F02001A30748BF15 -:1044800041F04001600748BF41F08001302383F3D1 -:104490001188281DFFF776FF002383F31188E205BA -:1044A0000AD5302383F311884FF48061281DFFF76C -:1044B00069FF002383F311884FF030094FF0000AA1 -:1044C00014F0200838D13B0616D54FF0300905F11D -:1044D000380A200610D589F31188504600F066F995 -:1044E000002836DA0821281DFFF74CFF27F080034B -:1044F0003360002383F31188790614D5620612D540 -:10450000302383F31188D5E913239A4208D12B6C09 -:1045100033B11021281D27F04007FFF733FF376024 -:10452000002383F31188E30619D5AA6E1369B3B18A -:10453000BDE8F0475069184789F31188B38C95F8A6 -:10454000641028461940FFF7D5FE8AF31188F469F4 -:10455000B6E780B2308588F31188F469B9E7BDE821 -:10456000F087000008B50348FFF776FFBDE8084074 -:10457000FFF75AB8F83A002008B50348FFF76CFF78 -:10458000BDE80840FFF750B8643B0020F8B5154679 -:1045900082680669AA420B46816938BF8568761A27 -:1045A000B54204460BD218462A46FCF7B1FEA36971 -:1045B0002B44A361A3685B1BA3602846F8BD0CD9FC -:1045C00018463246FCF7A4FEAF1BE1683A46304479 -:1045D000FCF79EFEE3683B44EBE718462A46FCF7EF -:1045E00097FEE368E5E7000083689342F7B5154658 -:1045F000044638BF8568D0E90460361AB5420BD24C -:104600002A46FCF785FE63692B446361A36828464C -:104610005B1BA36003B0F0BD0DD932460191FCF7DE -:1046200077FE0199E068AF1B3A463144FCF770FE13 -:10463000E3683B44E9E72A46FCF76AFEE368E4E7FF -:1046400010B50A440024C361029B8460C0E90000E5 -:10465000C0E90511C1600261036210BD08B5D0E96F -:104660000532934201D1826882B982680132826048 -:104670005A1C42611970D0E904329A4224BFC368BF -:1046800043610021FFF748F9002008BD4FF0FF30DB -:10469000FBE7000070B5302304460E4683F3118813 -:1046A000A568A5B1A368A269013BA360531CA361DF -:1046B00015782269934224BFE368A361E3690BB1D3 -:1046C00020469847002383F31188284607E03146A7 -:1046D0002046FFF711F90028E2DA85F3118870BD52 -:1046E0002DE9F74F04460E4617469846D0F81C9021 -:1046F0004FF0300A8AF311884FF0000B154665B170 -:104700002A4631462046FFF741FF034660B941463D -:104710002046FFF7F1F80028F1D0002383F3118839 -:10472000781B03B0BDE8F08FB9F1000F03D0019002 -:104730002046C847019B8BF31188ED1A1E448AF36B -:104740001188DCE7C0E90511C160C3611144009B19 -:104750008260C0E90000016103627047F8B5044659 -:104760000D461646302383F31188A768A7B1A368C6 -:10477000013BA36063695A1C62611D70D4E9043275 -:104780009A4224BFE3686361E3690BB1204698470E -:10479000002080F3118807E031462046FFF7ACF88F -:1047A0000028E2DA87F31188F8BD0000D0E905237C -:1047B0009A4210B501D182687AB98268013282606A -:1047C0005A1C82611C7803699A4224BFC3688361C2 -:1047D0000021FFF7A1F8204610BD4FF0FF30FBE7A6 -:1047E0002DE9F74F04460E4617469846D0F81C9020 -:1047F0004FF0300A8AF311884FF0000B154665B16F -:104800002A4631462046FFF7EFFE034660B941468F -:104810002046FFF771F80028F1D0002383F31188B8 -:10482000781B03B0BDE8F08FB9F1000F03D0019001 -:104830002046C847019B8BF31188ED1A1E448AF36A -:104840001188DCE70B460146184600F02DB8000041 -:1048500000F040B8012838BF012010B504462046BA -:1048600000F030F830B900F007F808B900F00CF8A3 -:104870008047F4E710BD0000024B1868BFF35B8F60 -:10488000704700BF503C002008B5062000F084F8B7 -:104890000120FFF7ABF80000024B0A4601461868FA -:1048A000FFF798B91811002010B5054C13462CB12C -:1048B0000A4601460220AFF3008010BD2046FCE707 -:1048C00000000000024B01461868FFF787B900BFDF -:1048D00018110020024B01461868FFF783B900BF8A -:1048E0001811002010B501390244904201D1002076 -:1048F00005E0037811F8014FA34201D0181B10BD49 -:104900000130F2E72DE9F041A3B1C91A177801444B -:10491000044603F1FF3C8C42204601D9002009E007 -:104920000578BD4204F10104F5D10CEB0405D6185D -:10493000A54201D1BDE8F08115F8018D16F801ED11 -:10494000F045F5D0E7E700001F2938B504460D46CD -:1049500004D9162303604FF0FF3038BD426C12B10A -:1049600052F821304BB9204600F030F82A46014673 -:104970002046BDE8384000F017B8012B0AD0591C7A -:1049800003D1162303600120E7E7002442F8254005 -:10499000284698470020E0E7024B01461868FFF7D9 -:1049A000D3BF00BF1811002038B5074D00230446BF -:1049B000084611462B60FFF71DF8431C02D12B68F7 -:1049C00003B1236038BD00BF543C0020FFF70CB892 -:1049D000034611F8012B03F8012B002AF9D1704787 -:1049E0006F72672E6172647570696C6F742E6633B6 -:1049F00030332D4D313030323500000040A2E4F12B -:104A0000646891060041A3E5F26569920700000021 -:104A10004261642043414E496661636520696E646A -:104A200065782E00800000000080000000008000FB -:104A30000000000000000000351B000819230008DA -:104A400079220008451B0008791B0008751D000825 -:104A5000491B0008591B00084D1B0008551B000886 -:104A6000511B00089D1C00085D1B0008E52500087F -:104A70006D1B0008711C000863300000784A0008B4 -:104A800078380020483A00206D61696E0069646CD6 -:104A900065000000A001A82A00000000FAAABEAA32 -:104AA00050001424EFFF0000007700007097090009 -:104AB0000100000000000000AAAAAAAA010000004C -:104AC000FFFF0000000000000000000000000000E8 -:104AD00000000000AAAAAAAA00000000FFFF000030 -:104AE00000000000000000000000000000000000C6 -:104AF000AAAAAAAA00000000FFFF00000000000010 -:104B0000000000000000000000000000AAAAAAAAFD -:104B100000000000FFFF0000000000000000000097 -:104B20000000000000000000AAAAAAAA00000000DD -:104B3000FFFF000000000000000000000000000077 -:104B40009942000885420008C1420008AD420008B1 -:104B5000B9420008A5420008914200087D420008C1 -:104B6000CD4200087CB6FF7F01000000000000007D -:104B7000EC030000000000000098030000000000AB -:104B8000FE2A0100D20400001C11002000000000D9 -:104B90000000000000000000000000000000000015 -:104BA0000000000000000000000000000000000005 -:104BB00000000000000000000000000000000000F5 -:104BC00000000000000000000000000000000000E5 -:104BD00000000000000000000000000000000000D5 -:0C4BE000000000000000000000000000C9 +:1000000000090020B1010008E52200089D22000837 +:10001000C52200089D220008BD220008B301000887 +:10002000B3010008B3010008B3010008D932000889 +:10003000B3010008B3010008B3010008A94000089B +:10004000B3010008B3010008B3010008B3010008C0 +:10005000B3010008B30100088D3D0008B93D000858 +:10006000E53D0008113E00083D3E0008B3010008D0 +:10007000B3010008B3010008B3010008B301000890 +:10008000B3010008B3010008B301000851220008C1 +:100090007D2200088D220008B3010008693E000897 +:1000A000B3010008B3010008B3010008B301000860 +:1000B000B3010008B3010008B3010008B301000850 +:1000C000B3010008B3010008B3010008B301000840 +:1000D000B301000899420008AD420008B3010008CE +:1000E000D13E0008B3010008B3010008B3010008C5 +:1000F000B3010008B3010008B3010008B301000810 +:10010000B3010008B3010008B3010008B3010008FF +:10011000B3010008B3010008B3010008B3010008EF +:10012000B3010008B3010008B3010008B3010008DF +:10013000B3010008B3010008B3010008B3010008CF +:10014000B3010008B3010008B3010008B3010008BF +:10015000B3010008B3010008B3010008B3010008AF +:10016000B3010008B3010008B3010008B30100089F +:10017000B3010008B3010008B3010008B30100088F +:10018000B3010008B3010008B3010008B30100087F +:10019000B3010008B3010008B3010008B30100086F +:1001A000190F00080000000000000000000000001F +:1001B00002E000F000F8FEE772B6374880F30888E6 +:1001C000364880F3098836483649086040F2000016 +:1001D000CCF200004EF63471CEF200010860BFF39D +:1001E0004F8FBFF36F8F40F20000C0F2F0004EF669 +:1001F0008851CEF200010860BFF34F8FBFF36F8FBD +:100200004FF00000E1EE100A4EF63C71CEF2000114 +:100210000860062080F31488BFF36F8F03F06AFC38 +:1002200003F0DEFC4FF055301F491B4A91423CBFA2 +:1002300041F8040BFAE71D49184A91423CBF41F8C6 +:10024000040BFAE71A491B4A1B4B9A423EBF51F86E +:10025000040B42F8040BF8E700201849184A9142B1 +:100260003CBF41F8040BFAE703F048FC03F0F4FC50 +:10027000144C154DAC4203DA54F8041B8847F9E7D7 +:1002800000F042F8114C124DAC4203DA54F8041B52 +:100290008847F9E703F030BC000900200011002076 +:1002A0000000000808ED00E0000100200009002027 +:1002B00098480008001100207C11002080110020C7 +:1002C000543C0020A0010008A4010008A40100087B +:1002D000A40100082DE9F04F2DED108AC1F80CD0D3 +:1002E000C3689D46BDEC108ABDE8F08F002383F300 +:1002F00011882846A047002003F052F9FEE703F0DA +:10030000DBF800DFFEE70000F8B500F017FE03F0B1 +:1003100095FB074603F0E4FB064600283ED12B4B35 +:100320009F423BD001339F423BD0294B27F0FF0235 +:100330009A4239D1F8B200F03DFC354642F21074D1 +:1003400000F03EFC08B10024254601F0ADF878B37A +:10035000032000F043F80024254636B11D4B9F4290 +:1003600003D003F0B5FB00242546002003F070FB0A +:10037000194B1B6913F040031FD00DB100F044F876 +:1003800000F050FC01F0B6FF0546C4B101F0B2FF29 +:10039000401BA04213D900F037F8F3E7354600249C +:1003A000CEE704460125CBE705464FF47A74C7E74C +:1003B000B4F57A7F08BF0125CFE71C46E0E700F0DF +:1003C00079FC012003F0F2F8DFE700BF010007B07D +:1003D000000008B0263A09B000040048084B187025 +:1003E00003280CD8DFE800F008050208022000F01E +:1003F00001BE022000F0F6BD024B00225A60704799 +:10040000801100208411002038B501F04DF830B182 +:100410001F4B03221A701F4B00225A6038BD1E4B1F +:100420001E4A19680131F9D004339342F9D11C4CAA +:10043000194DD4F80428AA42F0D31A4B9B6803F153 +:10044000006303F5D0439A42E8D203F015FB03F0B2 +:1004500027FB002000F08CFD0220FFF7BFFF124BAE +:10046000DA690022DA61D96999699A619B6972B681 +:100470004FF0E0233021C3F8085DD4F80038D4F8F9 +:10048000042881F311889D4683F308881047C5E747 +:1004900080110020841100200068000820680008F6 +:1004A000006000080011002000100240094A136893 +:1004B00049F2690099B21B0C00FB01331360064B33 +:1004C000186844F2506182B2000C01FB020018600F +:1004D00080B27047141100201011002010B50021C7 +:1004E0001022044600F0A0FD034B03CB20606160A6 +:1004F0001868A06010BD00BFACF7FF1F2DE9F041E8 +:10050000ADF54E7D0DF134086CAC40F27512074626 +:100510000D460EA80021C8F8001000F085FD4FF42C +:10052000C4720021204600F07FFD01F0E3FE254B60 +:100530004FF47A72B0FBF2F0186093E807000223E0 +:1005400084E807000DF5E9702382FFF7C7FF4EF638 +:1005500003431D49238406A804F0D4F8192384F822 +:1005600032310DF2E32206AB0DF1300C1E4603CE04 +:10057000664510605160334602F10802F6D13378C7 +:10058000137041460122204600F09AFD0023039398 +:10059000AB7E029305F11903019380B20123CDE9EB +:1005A00004800093E97E05A3D3E90023384602F0D6 +:1005B00069FA0DF54E7DBDE8F08100BF9E6AC42149 +:1005C000818A46EE8C110020144700082DE9F04185 +:1005D0002C4C237ADAB080460D465BBB27A928460F +:1005E00000F07EFE0746002842D19DF89D60C82E8F +:1005F0003ED801464FF4A662204600F015FD4FF4A8 +:100600008073C4F8F8314FF40073C4F80C334FF41E +:100610004073C4F8203432460DF19E0104F1090004 +:1006200000F0F0FC26449DF89C30777223720BB9E1 +:10063000EB7E23728122002106AC27A800F0F4FC97 +:100640000122214627A800F087FE00230393AB7EFA +:10065000029305F1190380B201932823CDE90440E8 +:100660000093E97E05A3D3E90023404602F00AFA8D +:100670005AB0BDE8F08100BFAFF30080264172722E +:10068000DF25D7B7B0320020F0B5254E4FF48A757C +:1006900005FB0065F1B096F8D83085F8DC30002411 +:1006A000D822214685F8E8403AA800F0BDFC06F1C2 +:1006B000090000F0B1FCD5F8E4308DF8F000C2B2CA +:1006C00006AF06F109010DF1F100CDE93A3400F071 +:1006D00099FC394601223AA800F06AFE80B2CDE9C1 +:1006E000047008230127CDE9023706F1D8030193EE +:1006F00030230093317A0B4807A3D3E9002302F09B +:10070000C1F9A04206DD01F0F5FDC5F8E00038466C +:1007100071B0F0BD2046FBE778F6339F93CACD8DCC +:10072000B0320020A42100202DE9F0411D4D1E4EC5 +:100730001E4F86B0284602F0D1F9034658B3002474 +:10074000CDE90344ADF81440027B8DF8142099687C +:100750004068029403AA03C21B68DFF8548043F088 +:100760000043029301F0C8FD821941F10003009497 +:1007700002A9384601F072F8A04205DD284602F0D1 +:10078000B1F988F80040D5E798F80030072B05D874 +:10079000013388F8003006B0BDE8F081014802F06E +:1007A000A1F9F8E7A421002040420F00D821002041 +:1007B000E537002070B50D4614461E4602F0BEF81F +:1007C00050B9022E10D1012C0ED112A3D3E900236F +:1007D000C5E90023012007E0282C10D005D8012C02 +:1007E00009D0052C0FD0002070BD302CFBD10BA3FD +:1007F000D3E90023ECE70BA3D3E90023E8E70BA33D +:10080000D3E90023E4E70BA3D3E90023E0E700BF2B +:10081000AFF30080401DA12026812A0B78F6339F7C +:1008200093CACD8D9E6AC421818A46EE264172729A +:10083000DF25D7B7F017304A39059E5638B505463B +:100840000E4C0021013500F0B5FBA4F82C55B4F88E +:100850002C0500F097FB78B1B4F82C0500F0A2FB52 +:10086000014648B9B4F82C0500F0A4FBB4F82C35C7 +:100870000133A4F82C35EAE738BD00BFB0320020C0 +:1008800010B50A4B0A4A1A6003F5805393F86020AA +:100890003AB9DC6D2CB1204600F080FE204603F012 +:1008A00071FEBDE81040034800F078BED82100205A +:1008B0006C470008203200202DE9F04F8FB000AFC8 +:1008C00005460C4602F03AF8002849D1237E022B57 +:1008D0001BD1E38A012B18D101F00CFD0646FFF76E +:1008E000E5FD03464FF4C870DFF8C482B3FBF0F2B5 +:1008F00006F5167602FB103316FA83F3C8F80030BB +:10090000E37E33B9A34B00221A703C37BD46BDE8E5 +:10091000F08F07F12401204600F0A0FC0028F4D15C +:1009200007F11400FFF7DAFD97F8264007F11401EC +:10093000224607F1270003F06FFE0028E2D10F2CBA +:1009400008D8944B1C70D8F80030A3F51673C8F87B +:100950000030DAE797F82410284601F0E7FFD4E7E3 +:10096000E38A282B2BD010D8012B23D0052BCCD1F8 +:10097000BFF34F8F8849894BCA6802F4E062134382 +:10098000CB60BFF34F8F00BFFDE7302BBDD1844E4E +:10099000E17E327A9142B8D1607E3146002291F8F0 +:1009A000DC50854200F0A5800132042A01F58A71ED +:1009B000F5D1AAE721462846FFF7A0FDA5E7214685 +:1009C0002846FFF703FEA0E7B2F8EC507B6005F184 +:1009D00003094FEA99094FEA8902D11DC908A8EB1A +:1009E000C1039D46EB460021584600F01DFB04F173 +:1009F000EE012A463144584600F004FB7B6813B9E7 +:100A0000012000F0B5FA96F8D20000F0BBFA0446D7 +:100A100030B9307200F0D6FA204600F0A9FAB1E001 +:100A2000D6F8D4203AB996F8D200B6F82C258242EE +:100A300001D8FFF703FFD6F8D4202A44944208D205 +:100A400096F8D200B6F82C250130824201D8FFF783 +:100A5000F5FE70685FFA89F2594600F0EDFA08B9C0 +:100A6000C54679E0726896F8D2002A447260D6F8DA +:100A7000D42005EB0209C6F8D49000F083FA814532 +:100A800009D396F8D220D6F8D4000132001B86F89C +:100A9000D220C6F8D400FF2D0FD80024347200F005 +:100AA00091FA204600F064FA00F0FEFC3D4B1881FC +:100AB00008B9FFF7A9FCC54627E7BB6896F8D90037 +:100AC0000AFB0362FB68D2F8E41082F8E83001F513 +:100AD0008061C2F8E030C2F8E410FFF7D5FDFFF7FF +:100AE00023FE96F8D920013202F0030286F8D920BD +:100AF000B6E74FF48A7A0AFB02F505F1EA013144C0 +:100B0000204600F081FCF86000287FF4FEAE3544FA +:100B1000012285F8E82001F0EDFBD5F8E020D6EDC4 +:100B2000007ADFED216A801A192838BF192040F6B3 +:100B3000B832904228BF1046B8EE677A07EE900AA6 +:100B4000F8EEE77A67EEA67ADFED186AE7EE267A26 +:100B5000FCEEE77AC6ED007A96F8D930BB60BA6849 +:100B600073680AFB02F4321992F8E81059B1D2F80E +:100B7000E4108B42E8463FF427AF002182F8E810EA +:100B8000C2F8E010C5467368064A9B0A0133138118 +:100B9000BBE600BF9D21002000ED00E00400FA0547 +:100BA000B03200208C110020CDCCCC3D6666663F73 +:100BB000A0210020014B1870704700BF9811002041 +:100BC00038B54FF00054134B22689A4220D1124B93 +:100BD000627D12481A70237D03724FF48073C0F84F +:100BE000F8314FF40073C0F80C3300254FF4407314 +:100BF000C0F820340A49C0F8E450C922093000F096 +:100C000001FAE0222946204600F00EFA012038BD04 +:100C10000020FCE79AAD44C598110020B0320020B6 +:100C20001600002037B500F03FFC194D1949288106 +:100C30000223012218486B7101F0F8F90023019397 +:100C4000164B174900931748174B4FF4805201F089 +:100C500045FE164B197811B1124801F067FE01F0FC +:100C600049FB0446FFF722FC4FF4C873B0FBF3F2D4 +:100C700002FB130304F5167010FA83F00C4B186096 +:100C800002F02EFF08B10F232B8103B030BD00BF4F +:100C90008C11002040420F00D8210020B507000829 +:100CA0009C110020A4210020B90800089811002000 +:100CB000A02100202DE9F04F2DED028B8EA7D7E962 +:100CC00000670FF23C29D9E90089864C95B00DAD3B +:100CD0009FED828BFFF728FDDFF82CB200230C93E9 +:100CE000ADF83C300D936B6000230DF125028DEDC6 +:100CF000008B4FF0010A09A958468DF825308DF870 +:100D000024A001F041F99DF824200023002A40F09E +:100D1000AB80204601F012FE0546002847D1DFF8DF +:100D2000ECB101F0E7FADBF8003098423FD301F074 +:100D3000E1FA0790FFF7BAFB079A4FF4C873B0FBCC +:100D4000F3F101FB130302F5167010FA83F0CBF8F0 +:100D50000000DFF8BCB19BF800100791002914BF18 +:100D60002B46534610A88DF83030FFF7B7FB079994 +:100D7000C1F11002D2B2062A10AB28BF06221944D4 +:100D80000DF13100079200F03DF9079A0CAB039387 +:100D9000182302930132544BD2B2CDE900A304923E +:100DA0003B463246204601F00FFE8BF8005001F022 +:100DB000A1FA4E4A4E4D1368C31AB3F57A7F32D367 +:100DC000106001F099FA02460B46204601F094FEAD +:100DD000204601F0B3FD30B32B7ADFF838A1002BA9 +:100DE00014BF032302238AF8053001F083FA0DF1C2 +:100DF000400B4FF47A730122B0FBF3F05946CAF866 +:100E00000000504600F002FA18230293394B019378 +:100E100080B240F25513CDE903B0009342464B46F1 +:100E2000204601F0D1FD2B7ACBB101F063FA4FF0EF +:100E3000000A83464FF48A7295F8D900504400F0B6 +:100E4000030002FB005393F8E81089B30AF1010A8A +:100E5000BAF1040FF0D12B7A002B7FF438AF15B024 +:100E6000BDEC028BBDE8F08F4FF0904110A84A69AD +:100E700082F010024A611946102200F0D5F80DF1F7 +:100E800026030AAA0CA9584600F0E8FD95E80300DD +:100E900011AB83E803009DF83C308DF84C300C9B7F +:100EA000109310A9DDE90A23204601F0F9FF1BE7A2 +:100EB000D3F8E01049B12B68FA2B38BFFA23ABEB1B +:100EC00001010533B1EB430FC0D3FFF7DDFB4FF456 +:100ED0008A720028BAD1BEE7AFF30080000000009C +:100EE00000000000A42100209C210020E037002009 +:100EF000B0320020E4370020401DA12026812A0BBB +:100F0000F1C6A7C1D068080FD8210020A021002079 +:100F10009D2100208C11002008B5054800F03AFE04 +:100F2000BDE80840034A0449002003F025BB00BF88 +:100F3000D8210020203800208108000870B502F078 +:100F40000DFC094E094D3080002428683388834207 +:100F500008D902F0FFFB2B6804440133B4F5D04FED +:100F60002B60F2D370BD00BF14380020E83700209A +:100F700002F080BC00F10060920000F5D04002F069 +:100F800027BC0000054B1A68054B1B889B1A83423F +:100F900002D9104402F0DEBB00207047E837002081 +:100FA00014380020024B1B68184402F0D9BB00BF64 +:100FB000E8370020024B1B68184402F0E3BB00BF77 +:100FC000E8370020064991F8243033B10023086A3D +:100FD00081F824300822FFF7CDBF0120704700BF01 +:100FE000EC370020022802BF4FF0904310229A6194 +:100FF00070470000022802BF4FF090434FF4801268 +:101000009A61704710B50023934203D0CC5CC4545E +:101010000133F9E710BD000003460246D01A12F969 +:10102000011B0029FAD1704702440346934202D0C3 +:1010300003F8011BFAE770472DE9F8431F4D1446EA +:1010400095F824200746884652BBDFF870909CB381 +:1010500095F824302BB92022FF2148462F62FFF754 +:10106000E3FF95F82400C0F10802A24228BF2246FF +:10107000D6B24146920005EB8000FFF7C3FF95F81A +:101080002430A41B1E44F6B2082E17449044E4B248 +:1010900085F82460DBD1FFF795FF0028D7D108E061 +:1010A0002B6A03EB82038342CFD0FFF78BFF00282C +:1010B000CBD10020BDE8F8830120FBE7EC3700200E +:1010C0002DE9F0470D46044600219046284640F29F +:1010D0007912FFF7A9FF234620220021284601F0BC +:1010E00081FE231D02222021284601F07BFE631D84 +:1010F00003222221284601F075FEA31D032225218B +:10110000284601F06FFE04F108031022282128462A +:1011100001F068FE04F1100308223821284601F08E +:1011200061FE04F1110308224021284601F05AFE15 +:1011300004F1120308224821284601F053FE04F16D +:10114000140320225021284601F04CFE04F118031C +:1011500040227021284601F045FE04F120030822B8 +:10116000B021284601F03EFE04F121030822B821F7 +:10117000284601F037FE04F12207C0263B463146DF +:1011800008222846083601F02DFEB6F5A07F07F1AB +:101190000107F3D104F1320308223146284601F059 +:1011A00021FE002704F1330A94F832304FEAC709D0 +:1011B0009F4209F5A47615D3B8F1000F08D1314646 +:1011C00004F599730722284601F00CFE09F24F1628 +:1011D000274694F832213B1B93420CD3F01DC008E4 +:1011E000BDE8F0870AEB070308223146284601F0E4 +:1011F000F9FD0137D8E707F23313314608222846B4 +:1012000001F0F0FD08360137E3E7000013B50446AE +:101210000846002101602346C0F8031020220190F7 +:1012200001F0E0FD0198231D0222202101F0DAFDEA +:101230000198631D0322222101F0D4FD0198A31D12 +:101240000322252101F0CEFD019804F108031022AC +:10125000282101F0C7FD072002B010BDF7B500231B +:10126000047F00910E4607221946054601F07EFCD8 +:10127000731C0093012200230721284601F076FC0D +:10128000C4B9B31C0093052223460821284601F067 +:101290006DFC0D243746B278BB1B934211D32B7FD4 +:1012A000A88A0734E408BBB9844294BF0020012017 +:1012B00003B0F0BDAB8ADB00083BDB08B370082449 +:1012C000E8E7FB1C0093214600230822284601F092 +:1012D0004DFC08340137DEE7201A18BF0120E7E78C +:1012E000F7B50023047F00910E46082219460546F3 +:1012F00001F03CFC731CC4B908220093114623463C +:10130000284601F033FC1024012372785F1C013B56 +:10131000934211D32B7FA88A0734E408BBB98442D7 +:1013200094BF0020012003B0F0BDAB8ADB00083B76 +:10133000DB0873700824E7E7F319009321460023C4 +:101340000822284601F012FC08343B46DDE7201A4B +:1013500018BF0120E7E70000F8B50E460546144621 +:10136000002181223046FFF75FFE2B460822002134 +:10137000304601F037FD7CB96B1C0722082130464E +:1013800001F030FD0F2401236A785F1C013B93427A +:1013900004D3E01DC008F8BD0824F4E7EB1921468A +:1013A0000822304601F01EFD08343B46ECE7000001 +:1013B000F8B50E46054614460021CE223046FFF70A +:1013C00033FE2B4628220021304601F00BFD7CB96C +:1013D00005F1080308222821304601F003FD3024DE +:1013E0002F462A7A7B1B934204D3E01DC008F8BD28 +:1013F0002824F5E707F1090321460822304601F0C9 +:10140000F1FC08340137ECE7F7B5047F00910E4694 +:10141000012310220021054601F0A8FBC4B9B31C2A +:101420000093092223461021284601F09FFB19242E +:1014300037467288BB1B9A4211D82B7FA88A073483 +:10144000E408BBB9844294BF0020012003B0F0BD82 +:10145000AB8ADB00103BDB0873801024E8E73B1D00 +:101460000093214600230822284601F07FFB083420 +:101470000137DEE7201A18BF0120E7E730B5094D34 +:101480000A4491420DD011F8013B5840082340F323 +:101490000004013B2C4013F0FF0384EA5000F6D116 +:1014A000EFE730BD2083B8EDF7B5364A10685168D4 +:1014B0006B4603C36A4634493448082303F0BCF83A +:1014C000044690BB0A25324A106851686B4603C334 +:1014D0006A4630492D48082303F0AEF80446002838 +:1014E00047D00369B3F5663F43D8B0F86620B2F53C +:1014F0007B7F3ED1284A024402F15C018B4238D303 +:101500005C3B224900209E1AFFF7B8FF324607468F +:1015100004F164010020FFF7B1FFA3689F4228D1C6 +:10152000E368984208BF002523E00369B3F5663FEE +:1015300026D8428BB2F57B7F20D1174A024402F1B4 +:1015400010018B4218D3103B104900209D1AFFF761 +:1015500095FF2A46064604F118010020FFF78EFF8A +:10156000A3689E4202D1E368984201D00D25AAE704 +:101570000025284603B0F0BD1025A4E70C25A2E7FE +:101580000B25A0E730470008DC970300006800083F +:1015900039470008909703000898FFF710B5037CBF +:1015A000044613B9006803F02FF8204610BD000070 +:1015B0000023BFF35B8FC360BFF35B8FBFF35B8F11 +:1015C0008360BFF35B8F7047BFF35B8F0068BFF32F +:1015D0005B8F704770B505460C30FFF7F5FF05F1DE +:1015E000080604463046FFF7EFFFA04206D9304612 +:1015F0006D68FFF7E9FF2544281A70BD3046FFF7F4 +:10160000E3FF201AF9E7000070B50546406898B17D +:1016100005F10800FFF7D8FF05F10C060446304637 +:10162000FFF7D2FF8442304694BF6D680025FFF774 +:10163000CBFF013C2C44201A70BD000038B50C468D +:101640000546FFF7C7FFA04210D305F10800FFF7DA +:10165000BBFF04446868B4FBF0F100FB1144BFF326 +:101660005B8F0120AC60BFF35B8F38BD0020FCE7CF +:101670002DE9F041144607460D46FFF7C5FF8442A9 +:1016800028BF0446D4B1B84658F80C6B4046FFF763 +:101690009BFF3044286040467E68FFF795FF331A71 +:1016A0009C4203D86C600120BDE8F0816B60A41BF4 +:1016B0003B68AB602044E8600220F5E72046F3E792 +:1016C00038B50C460546FFF79FFFA04210D305F141 +:1016D0000C00FFF779FF04446868B4FBF0F100FBED +:1016E0001144BFF35B8F0120EC60BFF35B8F38BD0B +:1016F0000020FCE72DE9FF41884669460746FFF7D1 +:10170000B7FF6C4606B204EBC6060025B44209D00A +:101710006268206808EB0501FFF774FC6368083411 +:101720001D44F3E729463846FFF7CAFF284604B0B0 +:10173000BDE8F081F8B505460C300F46FFF744FFD1 +:1017400005F1080604463046FFF73EFFA04230464A +:1017500088BF6C68FFF738FF201A386020B1304628 +:101760002C68FFF731FF2044F8BD000073B5144624 +:1017700006460D46FFF72EFF844228BF044601901F +:10178000DCB101A93046FFF7D5FF019B33B93268C0 +:10179000C5E90233C5E9002401200CE09C4238BFB2 +:1017A00001942860019868608442F5D93368AB6081 +:1017B000241AEC60022002B070BD2046FBE7000056 +:1017C0002DE9FF410F466946FFF7D0FF6C4600B296 +:1017D00004EBC0050026AC4209D0D4F8048054F8CC +:1017E000081BB8194246FFF70DFC4644F3E73046A4 +:1017F00004B0BDE8F081000038B50546FFF7E0FF12 +:10180000044601462846FFF719FF204638BD000070 +:1018100010B4026854681A4623465DF8044B184712 +:10182000002070470020704770470000002070477C +:101830000E20704700F5805090F8C800C0F34000BB +:101840007047000000F5805090F9D000704700000C +:1018500000F58050C0F8CC1001207047F7B50C6837 +:10186000BDF8207014F0005470D10D7B082D6DD898 +:10187000302585F311884569AE6876010CD4AC68D3 +:10188000240108D4AC6814F080545DD184F311882D +:10189000204603B0F0BD01240E6804F1180C002EA0 +:1018A000B8BFF6004FEA0C1CB4BF46F0040676053C +:1018B00045F80C600E680FFA84FC16F0804F18BFD4 +:1018C00005EB0C1E05EB0C1C1EBFDEF8806146F01C +:1018D0000206CEF880610E7BCCF8846105EB04151E +:1018E0008E68C5F88C614E68C5F88861DCF8805157 +:1018F00045F00105CCF8805100EB441641F2680533 +:101900002E4405EB44150544C6E9002308350E4670 +:1019100001F10C0C56F804EB45F804EB6645F9D1DF +:10192000843436882E8000EB441407F003052679B2 +:1019300026F00B0635432571002484F311880097A7 +:1019400000F0FAFC0120A4E70224A5E74FF0FF30E5 +:101950009FE7000013B500F580540191E06DFFF79B +:1019600053FE1F280AD90199E06D2022FFF7C2FE1D +:10197000A0F120035842584102B010BD0020FBE7FF +:1019800008B5302383F3118800F58050C06DFFF750 +:101990000FFE002383F3118808BD000000220260BF +:1019A000828142608260704710B500220023C0E946 +:1019B00000230023044603810C30FFF7EFFF20468D +:1019C00010BD0000F0B5054600F580500C4690F8BB +:1019D000C83013F0040FC3F3800108BF114661F350 +:1019E000820304F1840680F8C83005EB461389B001 +:1019F0001B79D8072ED57AB319072DD46846FFF77F +:101A0000D3FF05EB441303F5835303F1180703AA2F +:101A1000103318685968144603C40833BB42224681 +:101A2000F7D1186820609B88A380DDE90E23CDE9FB +:101A300000230123ADF808302B686946DB6B28468C +:101A4000984705EB46152B791A075CBF43F008034E +:101A50002B7101E0002AF4D109B0F0BD2DE9F04767 +:101A60009A4688B0074688469146302383F311880A +:101A700007F580546846FFF797FFE06DFFF7AAFD72 +:101A80001F282AD9E06D20226946FFF7B5FE2028DD +:101A900023D103AD444605AB2E4603CE9E422060C3 +:101AA0006160354604F10804F6D130682060B388DF +:101AB000A380DDE90023C9E90023BDF80830AAF8B6 +:101AC0000030002383F3118853464A464146384686 +:101AD00008B0BDE8F04700F01DBC002080F311887D +:101AE00008B0BDE8F08700002DE9F84F0023C0E9F9 +:101AF0000133254B044640F8183B0F46FFF74EFFD5 +:101B000004F12800FFF750FF04F1480804F582555E +:101B10004646083530462036FFF746FFAE42F9D13B +:101B200004F580554FF480534FF00009C5E913398F +:101B3000C5F848800123EE6504F5875804F58456FE +:101B4000C5F8549085F8583085F86030083608F1AB +:101B500008084FF0000A4FF0000B46E908ABA6F169 +:101B60001800FFF71BFF203646F8289C4645F4D1A5 +:101B700085F8D07017B1054800F0B6FB044B6361DF +:101B80002046BDE8F88F00BF6C47000844470008B6 +:101B90000064004010B5044B197804464A1C1A70C2 +:101BA000FFF7A2FF204610BD1C3800202DE9F047AA +:101BB000002950D0294B2A4FB7FBF1F599428CBF31 +:101BC0000A231123581EB5FBF3FC03FB1C53C4B2BC +:101BD0002BB102280346F5D80020BDE8F0870CF1B0 +:101BE000FF36B6F5806FF7D2C4EBC40E0EF10303D7 +:101BF0004FEAE309C3F3C703A4EB030809F1010AA1 +:101C00004FF47A755FFA88F009FB05555AFA88F89F +:101C1000B5FBF8F5B5F5617FC1BF0EF1FF33C3F336 +:101C2000C703E01AC0B25C1C50FA84F40CFB04F445 +:101C3000B7FBF4F4A142CFD1013BDBB20F2BCBD8E1 +:101C40000138C0B20728C7D80021107116809170E2 +:101C5000D3700120C1E70846BFE700BF3F420F0035 +:101C60000051250270B505460E464FF47A746B6933 +:101C70005B6803F00103B3424FF0010004D001F0B0 +:101C800095FC013CF3D1204670BD000030B542699F +:101C9000936913F0700F16D000230B4C936103F17E +:101CA000840200EB421211794D0709D5890707D547 +:101CB000416954F823508D60117941F0040111718C +:101CC0000133032BEBD130BD5847000873B51D46D7 +:101CD000436916469A68D207044609D59A680121D5 +:101CE0009960C2F34002CDE900650021FFF76AFE6A +:101CF00063699A68D1050BD59A684FF48071996031 +:101D0000C2F34022CDE9006501212046FFF75AFECB +:101D100063699A68D2030BD59A684FF48031996051 +:101D2000C2F34042CDE9006502212046FFF74AFE9A +:101D300004F58053D3F8CC0010B103681B699847B1 +:101D4000204602B0BDE87040FFF7A0BFF8B50446DA +:101D50004669002972D106F10C073868800770D0F7 +:101D600006EB01153868D5F8B00110F0040FD5F86E +:101D7000B0011ABFC00840F00040400DA061D5F886 +:101D8000B0C11CF0020F1CBF40F08040A061D5F82C +:101D9000B40106EB011100F00F0084F82400D1F823 +:101DA000B8012077D1F8B801000A6077D1F8B801FE +:101DB000000CA077D1F8B801000EE077D1F8BC0193 +:101DC00084F82000D1F8BC01000A84F82100D1F881 +:101DD000BC01000C84F82200D1F8BC11090E84F873 +:101DE00023103821396004F1340004F1180104F1A2 +:101DF000240551F8046B40F8046BA942F9D1098815 +:101E00000180C4E90A2321460023238651F8283B98 +:101E10002046DB6B984704F5805393F8C820D3F82D +:101E2000CC0042F0040283F8C82010B103681B699B +:101E300098472046BDE8F840FFF728BF06F1100795 +:101E40008BE7F8BD10B5044600F056FA02460B4683 +:101E500052EA030102D0013A63F100030449086821 +:101E600020B12146BDE81040FFF770BF10BD00BF94 +:101E700018380020F0B5302181F31188DFF848C010 +:101E800000F583510831002404F1840500EB451569 +:101E90002E7977070ED4F6060CD5D1E90076974255 +:101EA0009E4107D246695CF82470B7602E7946F0EF +:101EB00004062E710134032C01F12001E4D100232A +:101EC00083F31188F0BD00BF5847000808B53023E0 +:101ED00083F31188FFF7DAFE002383F3118808BD2E +:101EE000F8B543690546986800F0E050B0F1E05F4E +:101EF0000F4621D0F8B1302383F3118805F58354C0 +:101F00001034002606F1840305EB43131B791A07EE +:101F100006D50136032E04F12004F3D1012007E099 +:101F20005B07F6D42146384600F040FA0028F0D18D +:101F3000002383F31188F8BD0120FCE708B53023A6 +:101F400083F3118800F58050C06DFFF743FB002339 +:101F500083F3118843090CBF0120002008BD000055 +:101F6000F8B51D46002313700F4606461446FFF7CA +:101F7000E5FF80F00100387025B129463046FFF7B3 +:101F8000AFFF2070F8BD00002DE9B8410C461546A2 +:101F90001F46804600F0B0F90B462178024609B989 +:101FA000287850B14046FFF765FFFFF78FFF3B46AB +:101FB0002A462146FFF7D4FF0120BDE8B881000082 +:101FC00070B5302686F31188174BDA6942F000723B +:101FD000DA611A6942F000721A611A6922F000721D +:101FE0001A61002383F3118800F5805494F8C830F7 +:101FF00013F0010516D1A9B186F31188032113202E +:1020000001F0C8F90321142001F0C4F903211520BF +:1020100001F0C0F994F8C83043F0010384F8C830E7 +:1020200085F3118870BD00BF001002402DE9F04714 +:1020300000F5805588B095F8D030012B04468846CD +:10204000164600F28180814F57F823200AB947F8DD +:102050002300D7F800A0C4F80C802674BAF1000F52 +:1020600064D095F8D030012B70D001212046FFF7C5 +:10207000A7FF302383F311886269136823F00203FA +:1020800013606269136843F00103136063690027FA +:102090005F6187F3118801212046FFF7E3FD0028E7 +:1020A00000F09580E86DFFF783FA04F58359BA468E +:1020B00009F10809202200216846FEF7B5FF02A8B1 +:1020C000FFF76CFCCDF818A06A4609EB07030DF189 +:1020D000180E9446BCE80300F44518605960624647 +:1020E00003F10803F5D1DCF80000186020379CF8F4 +:1020F00004201A71602FDDD195F8C8306FF3820388 +:10210000002785F8C8306A4641462046ADF8007081 +:10211000ADF802708DF80470FFF748FD636948BBA5 +:102120004FF400421A6008B0BDE8F08741F2D800D1 +:1021300002F02AFA814610B15146FFF7D5FCC7F8E4 +:102140000090B9F1000F8CD10020ECE738680368EB +:102150001B6B98470146002887D13868FFF730FF8E +:102160003868036832465B684146984700287FF428 +:102170007CAFE9E761221A609DF802309DF80320E8 +:102180001B06120402F4702203F040731343BDF8DF +:102190000020C2F3090213439DF804201205022E09 +:1021A00002F4E0020CBF4FF00041002113436269CA +:1021B0000B43D361636913225A616269136823F088 +:1021C0000103136039462046FFF74CFD08B96369E7 +:1021D000A6E795F8D03093BB6169D1F8002242F0B0 +:1021E0000102C1F800226169D1F8002222F47C5278 +:1021F00022F00E02C1F800226169D1F8002242F4F7 +:102200006062C1F800226269C2F814326269C2F8E1 +:102210000432626941F6FF71C2F80C126269C2F8B9 +:1022200040326269C2F8443263690122C3F81C2259 +:102230006269D2F8003223F00103C2F8003295F847 +:10224000C83043F0020385F8C8306CE71838002026 +:1022500008B500F051F850EA0103024602D0421ED0 +:1022600061F10001044B186810B10B46FFF72EFD19 +:10227000BDE8084001F064B81838002008B5002017 +:10228000FFF7E0FDBDE8084001F05AB808B50120AD +:10229000FFF7D8FDBDE8084001F052B800B59BB08B +:1022A000EFF3098168226846FEF7ACFEEFF3058381 +:1022B000014B9B6BFEE700BF00ED00E008B5FFF7A8 +:1022C000EDFF000000B59BB0EFF30981682268467E +:1022D000FEF798FEEFF30583014B5B6BFEE700BF53 +:1022E00000ED00E0FEE700000FB408B5029801F031 +:1022F0000DF9FEE701F040BB01F0ECBA13B56C46F6 +:1023000084E80600031D94E8030083E8050001202B +:1023100002B010BD73B58568019155B11B885B078C +:1023200007D4D0E900369B6B9847019AC1B230467A +:10233000A847012002B070BDF0B5866889B0054697 +:102340000C465EB1BDF838305B070AD4D0E90037DF +:102350009B6B98472246C1B23846B047012009B06E +:10236000F0BD00220023CDE900230023ADF80830A2 +:102370000A4603AB01F10806106851681C4603C405 +:102380000832B2422346F7D1106820609288A280BA +:10239000FFF7B2FF0423ADF808302B68CDE9000148 +:1023A000DB6B694628469847D8E7000030B50368DC +:1023B0000968DD0FB5EBD17F23F0604421F0604266 +:1023C0004FEAD1700BD0002BB8BFA40C0029B8BFC6 +:1023D000920C944202D034BF0120002030BD9442C0 +:1023E00005D1C1F38070C3F380738342F6D1944268 +:1023F0002CBF00200120F1E72DE9F041456A15B915 +:102400004162BDE8F0814B6823F06047C3F38A4620 +:102410004FEAD37EC3F3807816EA230638BF3E46E0 +:10242000AC462B465A68BEEBD27F22F060440AD0FD +:10243000002A18DAA40CB44217D19D420FD10D60C6 +:10244000DEE71346EEE7A74207D102F08044C2F36D +:10245000807242450BD054B1EFE708D2EDE7CCF8DB +:1024600000100B60CDE7B44201D0B442E5D81A6841 +:102470009C46002AE5D11960C3E700002DE9F0472A +:10248000089D01F007044FEAD508224405F007052E +:1024900000EBD1004FF47F49944201D1BDE8F087B1 +:1024A00004F0070705F0070A57453E4638BF564671 +:1024B000C6F10806111B8E4228BF0E46E10808EB44 +:1024C000D50E415C13F80EC0B94029FA06F721FA7F +:1024D0000AF1FFB28CEA010147FA0AF739408CEAA7 +:1024E000010C03F80EC034443544D5E780EA0120DE +:1024F000082341F2210201B24000002980B203F119 +:10250000FF33B8BF504013F0FF03F4D17047000011 +:1025100038B50C468D18A54200D138BD14F8011B02 +:10252000FFF7E4FFF7E7000042684AB11368436031 +:102530004389818901339BB29942438138BF8381AA +:102540001046704770B588B0202204460D46684694 +:102550000021FEF769FD20460495FFF7E5FF0246DE +:1025600058B16B46054608AE1C4603CCB442286001 +:102570006960234605F10805F6D1104608B070BD24 +:10258000082817D909280CD00A280CD00B280CD001 +:102590000C280CD00D280CD00E2814BF4020302061 +:1025A00070470C2070471020704714207047182087 +:1025B0007047202070470000082817D90C280CD934 +:1025C00010280CD914280CD918280CD920280CD97B +:1025D00030288CBF0F200E207047092070470A203A +:1025E00070470B2070470C2070470D20704700008B +:1025F0002DE9F843078C072F04461ED9D0E902982D +:1026000000254FF6FF73C5F12006A5F1200029FA39 +:1026100005F108FA06F628FA00F031430143C9B281 +:102620001846FFF763FF0835402D0346EBD1E169FB +:102630003A46BDE8F843FFF76BBF4FF6FF70BDE8C1 +:10264000F883000010B54B6823B9CA8A63F3090206 +:10265000CA8210BD04691A681C600361C38A013B09 +:10266000C3824A60EFE700002DE9F84F1D46CB8A90 +:102670000F46C3F309010529814692460B4630D027 +:102680000020AAB207F11A049EB2042E1FFA80F8A5 +:102690000FD8904503F1010306D3FB8A0A4462F385 +:1026A0000903FB8201201AE01AF80060E6540130A9 +:1026B000EAE79045F1D2A1F1050B1C237C68BBFB36 +:1026C000F3F203FB12BB1FFA8BF6002C45D14846F0 +:1026D000FFF72AFF044638B978606FF00200BDE8C2 +:1026E000F88F4FF00008E6E7002606607860ADB28C +:1026F0004FF0000B454510D90AEB0803221D13F8D3 +:10270000011B9155B1B208F101081B291FFA88F885 +:102710002BD0454506F10106F1D8FB8AC3F3090227 +:10272000154465F30903BCE7013292B21C462368E5 +:10273000002BF9D16B1F0B441C21B3FBF1F30133C8 +:102740009BB29A42D3D2BBF1000FD0D14846FFF7DB +:10275000EBFE20B9C4F800B0BFE70122E7E7C0F8FC +:1027600000B05E4620600446C1E74545D5D94846DD +:10277000FFF7DAFE08B92060AFE7C0F800B0002626 +:1027800020600446B6E700002DE9F04F2DED028BE6 +:102790001C4683B05B69019207468846002B00F017 +:1027A0009A80238C2BB1E269002A00F09480072BD9 +:1027B00035D807F10C00FFF7B7FE054638B96FF0C2 +:1027C0000205284603B0BDEC028BBDE8F08F142251 +:1027D0000021FEF729FC228CE16905F10800FEF7D3 +:1027E00011FC208C013080B2FFF7E6FEFFF7C8FE37 +:1027F000013880B22084013028746369228C1B78F0 +:102800002A4403F01F0363F03F0348F000411372B2 +:10281000384669602946FFF7EFFD0125D1E700F151 +:102820000C034FF0000908EE103A4FF0800A4E46B4 +:102830004D4618EE100AFFF777FE83460028BED0FB +:1028400014220021FEF7F0FB002E3AD1019BABF8D9 +:10285000083002220BF1080E1FFA82FC0CF1010075 +:10286000BCF1060F218C80B201D88E422BD3FFF72A +:10287000A3FEFFF785FE62691278013802F01F029D +:102880008E4208BF4FF0400A42EA49121BFA80F11B +:102890004AEA020A013048F0004281F808A08BF8A9 +:1028A0001000CBF8042059463846FFF7A5FD238CCD +:1028B0000135B3422DB289F001094FF0000AB8D1B9 +:1028C0007FE70022C6E7E169895D0EF80210013654 +:1028D000B6B20132C0E76FF0010572E7F8B51546F0 +:1028E0000E463022002104461F46FEF79DFB069B44 +:1028F0006360B5F5001F079BA76034BF6A094FF6F8 +:10290000FF72A36297B2E66104F1100000239A42BD +:1029100006D800230360A782E3822383E360F8BD27 +:102920000660013330462036F1E7000003781BB91A +:102930004BB2002BC8BF0170704700000078704791 +:10294000F8B50C46C969074611B9238C002B37D15D +:10295000257E1F2D34D8387828BB228C072A2CD806 +:10296000268A36F003032BD14FF6FF70FFF7D0FD18 +:1029700020F001003102400441EA0561400C41EAC7 +:1029800040254FF6FF72234629463846FFF7FCFEE6 +:10299000002807DD626913780133DBB21F2B88BF83 +:1029A00000231370F8BD218A2D0645EA0125054351 +:1029B0002046FFF71DFE0246E5E76FF00300F1E752 +:1029C0006FF00100EEE7000070B58AB004461646CD +:1029D0000021282268461D46FEF726FBBDF8383048 +:1029E000ADF810300F9B05939DF840308DF81830EE +:1029F000119B07936946BDF84830ADF8203020465A +:102A0000CDE90265FFF79CFF0AB070BD2DE9F041EA +:102A1000D36905460C4616460BB9138C5BBB377E53 +:102A20001F2F28D895F80080B8F1000F26D0304627 +:102A3000FFF7DEFD3378210241EAC33141EA0801A4 +:102A4000338A41EA076141EA03410246334641F0D5 +:102A500080012846FFF798FE00280ADD3378012B15 +:102A600007D1726913780133DBB21F2B88BF0023B3 +:102A70001370BDE8F0816FF00100FAE76FF003001A +:102A8000F7E70000F0B58BB004460D46174600216D +:102A9000282268461E46FEF7C7FA9DF84C305A1E9B +:102AA000534253418DF800309DF84030ADF810305E +:102AB000119B05939DF848308DF81830149B0793AF +:102AC0006A46BDF85430ADF8203029462046CDE99D +:102AD0000276FFF79BFF0BB0F0BD0000406A00B12B +:102AE00004307047436A1A68426202691A600361DF +:102AF000C38A013BC38270472DE9F041D0F82080A2 +:102B0000194E14461D464146002709B9BDE8F0811B +:102B1000D1E90223A21A65EB0303964277EB030384 +:102B20001ED2036A8B420DD1FFF78CFD036A1B682E +:102B3000036203690B60C38A0161016A013BC382BE +:102B40008846E2E7FFF77EFD0B68C8F800300369AE +:102B50000B60C38A0161013BC382D8F80010D4E73F +:102B600088460968D1E700BF80841E002DE9F04F38 +:102B70008BB00D46DDF8509014469B4680460028E9 +:102B800000F01981B9F1000F00F01581531E3F2BA1 +:102B900000F21181012A03D1BBF1000F40F00B813B +:102BA0000023CDE90833B8F81430B5EBC30F4FEA72 +:102BB000C30703D300200BB0BDE8F08F2B199F4251 +:102BC000D8F80C303ABF7F1BFFB227461BB9D8F8A4 +:102BD0001030002B7AD0272D4ED8C5F12806B742E9 +:102BE0004FF000032CBFF6B23E4600932946D8F8BA +:102BF000080008AB3246FFF741FCA7EB060A354454 +:102C00005FFA8AFAB8F8143003F10053053BDB0091 +:102C10000493D8F80C3003932821039B13B1BAF125 +:102C2000000F2CD1D8F8100040B1BAF1000F05D038 +:102C3000009608AB5246691AFFF720FC38B2002F05 +:102C4000B8D066070AD00AAB03EBD401624211F890 +:102C5000083C02F00702134101F8083C082C3CD95B +:102C6000102C40F2B580202C40F2B780BBF1000F51 +:102C700000F09C80082334E0BA460026C2E7049B9B +:102C8000E02B28BFE02306930B44AB42059314D9F5 +:102C90005A1B03980096924534BF5246D2B2691A25 +:102CA00008AB04300792FFF7E9FB079A1644AAEB3A +:102CB000020A1544F6B25FFA8AFA049B069A05994D +:102CC0009B1A0493039B1B680393A6E70093D8F811 +:102CD000080008AB3A462946AEE7BBF1000F13D017 +:102CE0000123B4EBC30F6CD0082C12D89DF8203010 +:102CF000621E23FA02F2D50706D54FF0FF3202FA20 +:102D000004F423438DF820309DF8203089F80030FA +:102D100051E7102C12D8BDF82030621E23FA02F2BF +:102D2000D10706D54FF0FF3202FA04F42343ADF881 +:102D30002030BDF82030A9F800303CE7202C0FD817 +:102D40000899631E21FA03F3DA0705D54FF0FF3225 +:102D500002FA04F40C430894089BC9F800302AE7EF +:102D6000402C2BD0DDE90865611EC4F12102A4F1DD +:102D7000210326FA01F105FA02F225FA03F31143C1 +:102D80001943CB0712D50122A4F12003C4F120017D +:102D900002FA03F322FA01F1A240524243EA01038C +:102DA00063EB430332432B43CDE90823DDE90823DA +:102DB000C9E90023FFE66FF00100FCE66FF00800B0 +:102DC000F9E6082CA0D9102CB3D9202CEED8C3E7F3 +:102DD000BBF1000FADD0022383E7BBF1000FBBD0E6 +:102DE00004237EE730B5012A144638BF0124402C65 +:102DF00085B028BF40240025012ACDE9025518D806 +:102E00001B788DF8083063070AD004AB03EBD405B8 +:102E1000624215F8083C02F00702934005F8083CAE +:102E2000009103462246002102A8FFF727FB05B0C8 +:102E300030BD082AE4D9102A03D81B88ADF8083021 +:102E4000E1E7202A8DBFD3E900231B680293CDE977 +:102E50000223D8E710B5CB681BB98B600B618B825E +:102E600010BD04691A681C600361C38A013BC382F8 +:102E7000CA60F0E703064CBFC0F3C03002207047C1 +:102E800008B50246FFF7F6FF022806D15306C2F343 +:102E90000F2001D100F0030008BDC2F30740FBE79B +:102EA0002DE9F04F93B0CDE903230A68044610469C +:102EB000FFF7E0FF022814BFC2F306260026002A0F +:102EC0000D46824680F2F28112F0C04940F0EE8158 +:102ED000097B002900F0EA81022803D02378B3425D +:102EE00040F0E781C2F304630693104602F07F03CB +:102EF0000593FFF7C5FF059B29444FEA834848EA3D +:102F00000A4848EA4668CE7800230022CDE9082323 +:102F1000F309834648EA0008029367D0059B0093B3 +:102F200002466768534608A92046B847002800F0C3 +:102F3000C381276A4FB9414604F10C00FFF702FB39 +:102F4000074690B96FF0020054E03B6998450DD0F8 +:102F50003F68002FF9D1414604F10C00FFF7F2FA67 +:102F600007460028EED0236A3B60276297F817C017 +:102F700006F01F08CCF3840CACEB08001FFA80FEAF +:102F80000028B8BF0EF12000A8EB0C031FFA83FE47 +:102F9000D7E90221B8BF00B2002B0793BEBF0EF1E4 +:102FA00020031BB2079352EA010338D0039BDFF8DA +:102FB00024E39A1A049B4FF0000C63EB0101964541 +:102FC0007CEB01032BD36B7B97F81AE0734519D187 +:102FD000029B002B78D0012821DC7868F8B9DFF853 +:102FE000F0C2944570EB010316D337E0276A27B986 +:102FF0006FF00C0013B0BDE8F08F3B699845B5D079 +:103000003F68F4E7B24890427CEB010301D3002013 +:10301000F0E7029B002BFAD0079B0F2B17DCFA7D01 +:10302000B30002F0030203F07C031343FB7539463F +:103030002046FFF707FB6B7BBB76029B3BB9FB7D12 +:10304000C3F38402013262F38603FB75D0E76A7B27 +:10305000BB7E9A42DBD1029B002B35D0B309022BF9 +:1030600032D0039BBB60049BFB60142200210DA89F +:10307000FDF7DAFF039B0A93049B0B932B1D0C9324 +:103080002B7BADF83EB0013BDBB2ADF83C30069B8C +:103090008DF84230059B8DF8433094F82C308DF834 +:1030A00040A083F001038DF844308DF84180A3687F +:1030B0000AA920469847FB7DC3F38403013303F03C +:1030C0001F039B02FB82A2E7FB7DC6F34012B2EB1B +:1030D000D31F40F0F480C3F38403434540F0F280F3 +:1030E000029A2B7BB609002A4DD0F2075DD4032B40 +:1030F00040F2EB80039BBB60049BFB602B7BAE1D0F +:10310000033BDBB23246394604F10C00FFF7ACFA60 +:1031100000280CDA39462046FFF794FAFB7DC3F30A +:103120008403013303F01F039B02FB820AE7DDE9FE +:103130000884AB883B834FF6FF73C9F12000A9F1E7 +:10314000200228FA09F104FA00F0014324FA02F2FD +:1031500011431846C9B2FFF7C9F909F10809B9F1D5 +:10316000400F0346E9D1B8822A7B033AD2B23146F6 +:10317000FFF7CEF9FB7DB882DA43C2F3C01262F3E7 +:10318000C713FB7543E786B92E1D013BDBB2324600 +:10319000394604F10C00FFF767FA0028BADB2A7BF6 +:1031A000B88A013AD2B23146E2E7F98AC1F309019D +:1031B000013B0429DAB25BD8281D002307F11B0666 +:1031C0009A4208D910F801CB06F801C00131013349 +:1031D0000529DBB2F4D103990A9104990B9193422A +:1031E00007F11B010C9138BF043379680D9134BF8E +:1031F00055FA83F300230E93FB8AADF83EB0C3F378 +:1032000009031A44069B8DF84230059B8DF8433024 +:1032100094F82C30ADF83C2083F001038DF8443055 +:1032200000238DF840A08DF841807B602A7BB88A0E +:10323000013A291DFFF76CF93B8BB882834203D119 +:10324000A3680AA92046984720460AA9FFF702FE6C +:10325000FB7DBA8AC3F38403013303F01F039B028F +:10326000FB823B8B9A420CBF00206FF01000C1E63E +:103270007B68002BAFD0052001E01C3033461E6870 +:10328000002EFAD1091A081D2E1D184401EB090C55 +:10329000BCF11B0F5FFA89F39DD89A429BD916F8AF +:1032A000013B00F8013B09F10109EFE76FF009006C +:1032B000A0E66FF00A009DE66FF00B009AE66FF053 +:1032C0000D0097E66FF00E0094E66FF00F0091E6A8 +:1032D00040420F0080841E00EFF3098305494A6BCA +:1032E00022F001024A63683383F30988002383F3E1 +:1032F0001188704700EF00E0302080F3118862B63B +:103300000C4B0D4AD96821F4E0610904090C0A4309 +:10331000DA60D3F8FC20094942F08072C3F8FC203F +:103320000A6842F001020A602022DA7783F822005C +:10333000704700BF00ED00E00003FA05001000E058 +:1033400010B5302383F311880E4B5B6813F40063D0 +:1033500014D0F1EE103AEFF30984683C4FF080731B +:10336000E361094BDB6B236684F3098800F098F86E +:1033700010B1064BA36110BD054BFBE783F3118829 +:10338000F9E700BF00ED00E000EF00E0FF020008F9 +:103390000203000800F1604303F561430901C9B26B +:1033A00083F80013012200F01F039A4043099B0099 +:1033B00003F1604303F56143C3F880211A6070474D +:1033C00000F16040090100F56D40C9B20176704717 +:1033D00000230375826803691B6899689142FBD2D8 +:1033E0005A6803604260106058607047002303759C +:1033F000826803691B6899689142FBD85A68036028 +:10340000426010605860704708B50846302383F367 +:1034100011880B7D032B05D0042B0DD02BB983F322 +:10342000118808BD8B6900221A604FF0FF33836159 +:10343000FFF7CEFF0023F2E7D1E9003213605A60B4 +:10344000F3E70000FFF7C4BF054BD968087518689B +:1034500002681A60536001220275D860FCF73ABF17 +:103460002838002030B50C4BDD684B1C87B0044673 +:103470000FD02B46094A684600F0D8F82046FFF7DF +:10348000E3FF009B13B1684600F0DAF8A86907B0C3 +:1034900030BDFFF7D9FFF9E72838002009340008CC +:1034A000044B1A68DB6890689B68984294BF0020C0 +:1034B0000120704728380020084B10B51C68D868D8 +:1034C00022681A60536001222275DC60FFF78EFFCC +:1034D00001462046BDE81040FCF7FCBE283800201D +:1034E00038B5074C0749084801230025237065605B +:1034F00000F024FB0223237085F3118838BD00BF40 +:10350000503A0020B04700082838002008B572B6AD +:10351000044B186500F0C2F900F0ACFA024B03222C +:103520001A70FEE728380020503A002000F09AB8C0 +:103530008B60022308618B82084670478368A3F181 +:10354000840243F8142C026943F8442C426943F87E +:10355000402C094A43F8242CC26843F8182C022254 +:1035600003F80C2C002203F80B2C044A43F8102C0F +:10357000A3F12000704700BFED02000828380020AA +:1035800008B5FFF7DBFFBDE80840FFF75BBF0000B1 +:10359000024BDB6898610F20FFF756BF28380020E8 +:1035A000302383F31188FFF7F3BF000008B501460D +:1035B000302383F311880820FFF754FF002383F39F +:1035C000118808BD064BDB6839B1426818605A6043 +:1035D000136043600420FFF745BF4FF0FF30704792 +:1035E000283800200368984206D01A6802605060AC +:1035F00099611846FFF726BF7047000010B50A4CC6 +:1036000023699A6891420CD85A68816003604260CD +:1036100010609A685860511A99604FF0FF33A361A7 +:1036200010BD1B68891AECE72838002010B4C0E9E7 +:10363000032300235DF8044B4361FFF7DFBF000065 +:10364000036881689A680A449A60426813605A6005 +:1036500000230360024B4FF0FF329A61704700BFB6 +:103660002838002070B5124DEB692A460133EB6112 +:1036700052F8103F934206D09A68013A9A60302679 +:103680002C69A36803B170BDD4E900210A605160C0 +:10369000236083F31188D4E903312046984786F3E9 +:1036A000118861690029EBD02046FFF7A7FFE7E703 +:1036B00028380020054A30B5D369D2E908451B1BDC +:1036C000181945F10001C2E9080130BD2838002071 +:1036D00000207047FEE70000704700004FF0FF3009 +:1036E00070470000BFF34F8F024AD368DB07FCD45A +:1036F000704700BF0020024008B5074B1B7853B944 +:10370000FFF7F0FF054B1A69120641BF044A5A60E1 +:1037100002F188325A6008BD683A00200020024059 +:103720002301674508B5054B1B7833B9FFF7DAFF6E +:10373000034A136943F08003136108BD683A00200F +:10374000002002407F289ABF00F58030C002002090 +:10375000704700004FF40060704700008020704701 +:103760007F2808B50BD8FFF7EDFF00F5006302686E +:10377000013204D104308342F9D1012008BD002078 +:10378000FCE700007F2810B504461CD8FFF7AAFF0D +:10379000FFF7B2FF0D4BF322DA6002221A61FFF746 +:1037A000D1FF58611A6942F040021A614FF400617A +:1037B000FFF798FF00F05AF9FFF7B4FF2046BDE885 +:1037C0001040FFF7CDBF002010BD00BF0020024019 +:1037D0002DE9F84312F00103144606D01F4B40F2C6 +:1037E00003321A600020BDE8F88385181C4A954210 +:1037F00004D91A4A4FF442711160F3E7FFF77CFFD6 +:10380000FFF770FFDFF86880451A4FF00109012CBF +:1038100005EB01060F4603D8FFF784FF0120E2E71E +:103820003B88C8F8109033800020FFF75BFFC8F892 +:103830001000338831F8022B9BB29A420CD0074B10 +:1038400040F21F321A60074B1E60074B1C60074B8B +:103850001F60FFF767FFC6E7023CD8E7643A002025 +:1038600000000408583A0020603A00205C3A00202A +:1038700000200240084908B50B7828B11BB9FFF7B2 +:103880003BFF01230B7008BD002BFCD0BDE80840B6 +:103890000870FFF747BF00BF683A002008B5064828 +:1038A0004FF41F4100F0E4F8BDE808404FF4005128 +:1038B0004FF0805000F0DCB80001002008461146AF +:1038C00000F084BE012000F081BE0000084600F038 +:1038D0009BBE000038B5EFF31185BDBBEFF3058447 +:1038E000C4F308043023C4B183F31188FFF7E2FE68 +:1038F0004C014201121A44EAD06464EB01049300C3 +:10390000A4001B1844EA927441EB0401C900D800DA +:1039100041EA537185F3118838BD83F31188FFF7AD +:10392000C9FE4D014201121A45EAD06565EB010559 +:103930009300AD001B1845EA927541EB0501C900E3 +:10394000D80041EA537184F3118838BDFFF7B2FE05 +:103950004B014401241A43EAD06363EB0103A20044 +:103960009B00121843EA947341EB0301C900D00095 +:1039700041EA527138BD00BF38B5FFF7ABFF114CBB +:10398000114AC00840EA4170A0FB025EC908A0FBD2 +:10399000040C1CEB050CA1FB04404FF000035B4141 +:1039A000A1FB02121CEB040C43EB000011EB0E0117 +:1039B00042F10002411842F10000090941EA007099 +:1039C00038BD00BFCFF753E3A59BC42010B5024418 +:1039D000064BD2B2904200D110BD441C00B253F845 +:1039E000200041F8040BE0B2F4E700BF502800408B +:1039F0000F4B30B51C6A240407D41C6A44F440748D +:103A00001C621C6A44F400441C620A4C236843F4A0 +:103A1000807323600244084BD2B2904200D130BD83 +:103A2000441C00B251F8045B43F82050E0B2F4E7C4 +:103A300000100240007000405028004007B50122ED +:103A400001A90020FFF7C2FF019803B05DF804FB55 +:103A500013B50446FFF7F2FFA04205D0012201A9E9 +:103A600000200194FFF7C4FF02B010BD70470000B2 +:103A70007047000070470000074B45F255521A602E +:103A800002225A6040F6FF729A604CF6CC421A60ED +:103A9000024B01221A70704700300040703A00203B +:103AA000034B1B781BB1034B4AF6AA221A607047DE +:103AB000703A002000300040044B1A682AB902F125 +:103AC000804202F50432526A1A6070476C3A002054 +:103AD000024B4FF080725A62704700BF00100240E4 +:103AE00008B5FFF7E9FF024B1868C0F3407008BD46 +:103AF0006C3A002070470000FEE700000A4B0B48BC +:103B00000B4A90420BD30B4BDA1C121AC11E22F047 +:103B100003028B4238BF00220021FDF785BA53F81B +:103B2000041B40F8041BECE714490008543C002037 +:103B3000543C0020543C0020FEE7000070B51B4BB5 +:103B400001630025044686B0586085620E46FFF783 +:103B5000D3FB04F11003C4E904334FF0FF33A36136 +:103B6000134BE561D969A5600A462B46C4E90823D1 +:103B700004F13401C4E900440E4AE562256580235E +:103B80002046FFF7D5FC0123E0600B4A0375009245 +:103B900072680192B268CDE90223084B6846CDE90C +:103BA0000435FFF7EDFC06B070BD00BF503A0020B1 +:103BB00028380020BC470008C1470008393B0008EE +:103BC0004B6843608B688360CB68C3600B6943615B +:103BD0004B6903628B6943620B68036070470000A6 +:103BE00008B51B4B9A6A42F4FC029A629A6A22F464 +:103BF000FC029A629A6A5A6942F4FC025A61154AB6 +:103C00005B6911464FF09040FFF7DAFF02F11C01AB +:103C100000F58060FFF7D4FF02F1380100F5806005 +:103C2000FFF7CEFF02F1540100F58060FFF7C8FFF7 +:103C300002F1700100F58060FFF7C2FF02F18C0114 +:103C400000F58060FFF7BCFFBDE8084000F05AB8FF +:103C500000100240C847000808B500F093F9FFF7CC +:103C60003FFCBDE80840FFF727BF00007047000099 +:103C700010B5214CA36A63F4FC03A362A36A03F4A6 +:103C8000FC03A3624FF0FF32A36A23692261236918 +:103C9000002323612169E168E260E268E360E26891 +:103CA000E269164942F08052E261E2690A6842F430 +:103CB00080720A60226A02F44072B2F5407F1EBF31 +:103CC0004FF4803222622362236A1B0407D4236AE2 +:103CD00043F440732362236A43F40043236200F0F9 +:103CE00031F9A369064A43F00103A361A36913688C +:103CF00043F02003136010BD00100240007000402C +:103D0000000001401E4B1A6842F001021A601A6856 +:103D10009007FCD55A6822F003025A605A6812F0E4 +:103D20000C02FBD1196801F0F90119605A601A6898 +:103D300042F480321A601A689103FCD5114A5A6025 +:103D40004FF40452DA6230221A631A6842F0807229 +:103D50001A601A689201FCD50B4912220A600A689F +:103D600002F00702022AFAD15A6842F002025A60AF +:103D70005A6802F00C02082AFAD11A6B1A637047CB +:103D80000010024000241D0000200240084A08B52F +:103D9000516913680B4003F00103536123B1054AD5 +:103DA00013680BB150689847BDE80840FFF7C8BAE0 +:103DB00000040140743A0020084A08B551691368AC +:103DC0000B4003F00203536123B1054A93680BB122 +:103DD000D0689847BDE80840FFF7B2BA0004014038 +:103DE000743A0020084A08B5516913680B4003F083 +:103DF0000403536123B1054A13690BB15069984715 +:103E0000BDE80840FFF79CBA00040140743A002066 +:103E1000084A08B5516913680B4003F00803536161 +:103E200023B1054A93690BB1D0699847BDE80840B2 +:103E3000FFF786BA00040140743A0020084A08B52A +:103E4000516913680B4003F01003536123B1054A15 +:103E5000136A0BB1506A9847BDE80840FFF770BA83 +:103E600000040140743A0020174B10B55A691C68D1 +:103E7000144004F478725A61A30604D5134A936A75 +:103E80000BB1D06A9847600604D5104A136B0BB18A +:103E9000506B9847210604D50C4A936B0BB1D06B3D +:103EA0009847E20504D5094A136C0BB1506C98474A +:103EB000A30504D5054A936C0BB1D06C9847BDE8B7 +:103EC0001040FFF73DBA00BF00040140743A0020E3 +:103ED0001A4B10B55A691C68144004F47C425A61AC +:103EE000620504D5164A136D0BB1506D9847230532 +:103EF00004D5134A936D0BB1D06D9847E00404D5F7 +:103F00000F4A136E0BB1506E9847A10404D50C4AAA +:103F1000936E0BB1D06E9847620404D5084A136FB4 +:103F20000BB1506F9847230404D5054A936F0BB12A +:103F3000D06F9847BDE81040FFF702BA0004014077 +:103F4000743A0020062108B50846FFF723FA062137 +:103F50000720FFF71FFA06210820FFF71BFA0621AA +:103F60000920FFF717FA06210A20FFF713FA0621A6 +:103F70001720FFF70FFABDE8084006212820FFF7B9 +:103F800009BA000008B5FFF773FE00F067F800F00B +:103F90003DF8FFF76BFEBDE8084000F05DB800009B +:103FA000026843681143016003B11847704700007D +:103FB000143000F02FBA00004FF0FF33143000F03F +:103FC00029BA0000383000F0A5BA00004FF0FF33E6 +:103FD000383000F09FBA0000143000F0F5B900004E +:103FE0004FF0FF31143000F0EFB90000383000F02E +:103FF0004FBA00004FF0FF32383000F049BA0000ED +:10400000012914BF6FF013000020704700F06CB856 +:10401000044B03600023C0E90233436001230374AF +:10402000704700BF7048000838B5C36904460D46A4 +:104030001BB904210844FFF7B3FF294604F114001B +:1040400000F0A6F9002806DA201D4FF40061BDE853 +:104050003840FFF7A5BF38BD00F00EB80023054A71 +:1040600019460133102BC2E9001102F10802F8D100 +:10407000704700BF743A00204FF0E023044A5A61B1 +:1040800000229A6107221A6108210B20FFF798B9D4 +:104090003F19010008B5302383F31188FFF746FA72 +:1040A000002383F3118808BD08B5FFF7F3FFBDE8CF +:1040B0000840FFF745B900000268436811430160FA +:1040C00003B1184770470000024A136843F0C00369 +:1040D0001360704700380140024A136843F0C00380 +:1040E000136070470044004037B51D4C1D4D2046FD +:1040F000FFF78EFF009404F114001B4900232022D7 +:1041000000F038F92022009404F13800174B1849C8 +:1041100000F0B2F9174BC4E91735174C0C212520D4 +:10412000FFF738F92046FFF773FF04F11400134935 +:1041300000940023202200F01DF904F13800104BF8 +:1041400010490094202200F097F90F4B0C212620F3 +:10415000C4E9173503B0BDE83040FFF71BB900BF15 +:10416000F43A002000512502CC3B0020C940000851 +:104170000C3C002000380140603B0020EC3B00205C +:10418000D94000082C3C0020004400402DE9F047B5 +:10419000C66D3768F46934622107054619D014F0FA +:1041A000080118BF4FF48071E20748BF41F02001B9 +:1041B000A30748BF41F04001600748BF41F08001BC +:1041C000302383F31188281DFFF776FF002383F344 +:1041D0001188E2050AD5302383F311884FF48061FA +:1041E000281DFFF769FF002383F311884FF0300982 +:1041F0004FF0000A14F0200838D13B0616D54FF0D6 +:10420000300905F1380A200610D589F31188504687 +:1042100000F066F9002836DA0821281DFFF74CFF68 +:1042200027F080033360002383F31188790614D5C7 +:10423000620612D5302383F31188D5E913239A42FD +:1042400008D12B6C33B11021281D27F04007FFF750 +:1042500033FF3760002383F31188E30619D5AA6E74 +:104260001369B3B1BDE8F0475069184789F3118865 +:10427000B38C95F8641028461940FFF7D5FE8AF3F1 +:104280001188F469B6E780B2308588F31188F46943 +:10429000B9E7BDE8F087000008B50348FFF776FFEF +:1042A000BDE80840FFF74CB8F43A002008B50348D1 +:1042B000FFF76CFFBDE80840FFF742B8603B002005 +:1042C000F8B5154682680669AA420B46816938BF6F +:1042D0008568761AB54204460BD218462A46FCF782 +:1042E00091FEA3692B44A361A3685B1BA3602846CE +:1042F000F8BD0CD918463246FCF784FEAF1BE168C6 +:104300003A463044FCF77EFEE3683B44EBE7184650 +:104310002A46FCF777FEE368E5E7000083689342EE +:10432000F7B51546044638BF8568D0E90460361AEB +:10433000B5420BD22A46FCF765FE63692B446361E4 +:10434000A36828465B1BA36003B0F0BD0DD93246BD +:104350000191FCF757FE0199E068AF1B3A463144E2 +:10436000FCF750FEE3683B44E9E72A46FCF74AFEC7 +:10437000E368E4E710B50A440024C361029B84604B +:10438000C0E90000C0E90511C1600261036210BD0F +:1043900008B5D0E90532934201D1826882B98268BA +:1043A000013282605A1C42611970D0E904329A428B +:1043B00024BFC36843610021FFF714F9002008BD42 +:1043C0004FF0FF30FBE7000070B5302304460E4687 +:1043D00083F31188A568A5B1A368A269013BA36016 +:1043E000531CA36115782269934224BFE368A3613B +:1043F000E3690BB120469847002383F311882846D0 +:1044000007E031462046FFF7DDF80028E2DA85F3C1 +:10441000118870BD2DE9F74F04460E4617469846A1 +:10442000D0F81C904FF0300A8AF311884FF0000B3F +:10443000154665B12A4631462046FFF741FF03463F +:1044400060B941462046FFF7BDF80028F1D00023AF +:1044500083F31188781B03B0BDE8F08FB9F1000F2A +:1044600003D001902046C847019B8BF31188ED1AB9 +:104470001E448AF31188DCE7C0E90511C160C361FD +:104480001144009B8260C0E9000001610362704733 +:10449000F8B504460D461646302383F31188A76805 +:1044A000A7B1A368013BA36063695A1C62611D70D8 +:1044B000D4E904329A4224BFE3686361E3690BB133 +:1044C00020469847002080F3118807E031462046B7 +:1044D000FFF778F80028E2DA87F31188F8BD0000CA +:1044E000D0E905239A4210B501D182687AB9826871 +:1044F000013282605A1C82611C7803699A4224BF8F +:10450000C36883610021FFF76DF8204610BD4FF0AE +:10451000FF30FBE72DE9F74F04460E461746984655 +:10452000D0F81C904FF0300A8AF311884FF0000B3E +:10453000154665B12A4631462046FFF7EFFE034691 +:1045400060B941462046FFF73DF80028F1D000232E +:1045500083F31188781B03B0BDE8F08FB9F1000F29 +:1045600003D001902046C847019B8BF31188ED1AB8 +:104570001E448AF31188DCE70B460146184600F01A +:104580002DB8000000F040B8012838BF012010B558 +:104590000446204600F030F830B900F007F808B9BA +:1045A00000F00CF88047F4E710BD0000024B1868DB +:1045B000BFF35B8F704700BF4C3C002008B506205E +:1045C00000F084F80120FFF785F80000024B0A464E +:1045D00001461868FFF772B91811002010B5054C94 +:1045E00013462CB10A4601460220AFF3008010BDED +:1045F0002046FCE700000000024B01461868FFF768 +:1046000061B900BF18110020024B01461868FFF77E +:104610005DB900BF1811002010B501390244904265 +:1046200001D1002005E0037811F8014FA34201D029 +:10463000181B10BD0130F2E72DE9F041A3B1C91AF2 +:1046400017780144044603F1FF3C8C42204601D90F +:10465000002009E00578BD4204F10104F5D10CEB1E +:104660000405D618A54201D1BDE8F08115F8018DE9 +:1046700016F801EDF045F5D0E7E700001F2938B541 +:1046800004460D4604D9162303604FF0FF3038BDB1 +:10469000426C12B152F821304BB9204600F030F88C +:1046A0002A4601462046BDE8384000F017B8012BE5 +:1046B0000AD0591C03D1162303600120E7E7002428 +:1046C00042F82540284698470020E0E7024B014683 +:1046D0001868FFF7D3BF00BF1811002038B5074D89 +:1046E00000230446084611462B60FEF7F7FF431CE3 +:1046F00002D12B6803B1236038BD00BF503C0020BD +:10470000FEF7E6BF034611F8012B03F8012B002A40 +:10471000F9D170476F72672E6172647570696C6F42 +:10472000742E663330332D4D313030323500000079 +:1047300040A2E4F1646891060041A3E5F265699244 +:10474000070000004261642043414E496661636591 +:1047500020696E6465782E008000000000800000F3 +:104760000000800000000000000000001118000898 +:104770002D200008891F0008511800085D18000846 +:104780005D1A0008211800083118000825180008D3 +:104790002D1800082918000881190008351800088C +:1047A000FD22000845180008551900086330000074 +:1047B000AC47000880380020503A00206D61696ED7 +:1047C0000069646C65000000A001A82A00000000D8 +:1047D000FAAABEAA50001424EFFF000000770000E0 +:1047E000709709000100000000000000AAAAAAAA10 +:1047F00001000000FFFF00000000000000000000BA +:104800000000000000000000AAAAAAAA0000000000 +:10481000FFFF00000000000000000000000000009A +:1048200000000000AAAAAAAA00000000FFFF0000E2 +:104830000000000000000000000000000000000078 +:10484000AAAAAAAA00000000FFFF000000000000C2 +:10485000000000000000000000000000AAAAAAAAB0 +:1048600000000000FFFF000000000000000000004A +:1048700000000000CD3F0008B93F0008F53F0008E8 +:10488000E13F0008ED3F0008D93F0008C53F0008A0 +:10489000B13F000801400008EC03000000000000E8 +:1048A0000098030000000000FE2A0100D20400006E +:1048B0001C110020000000000000000000000000AB +:1048C00000000000000000000000000000000000E8 +:1048D00000000000000000000000000000000000D8 +:1048E00000000000000000000000000000000000C8 +:1048F00000000000000000000000000000000000B8 +:1049000000000000000000000000000000000000A7 +:0449100000000000A3 :00000001FF diff --git a/Tools/bootloaders/f303-M10070_bl.bin b/Tools/bootloaders/f303-M10070_bl.bin index e09904fb01dd9a..2af7ec43025bbd 100755 Binary files a/Tools/bootloaders/f303-M10070_bl.bin and b/Tools/bootloaders/f303-M10070_bl.bin differ diff --git a/Tools/bootloaders/f303-M10070_bl.elf b/Tools/bootloaders/f303-M10070_bl.elf index 403ba5566ccc74..92ed42ffe9cedd 100755 Binary files a/Tools/bootloaders/f303-M10070_bl.elf and b/Tools/bootloaders/f303-M10070_bl.elf differ diff --git a/Tools/bootloaders/f303-M10070_bl.hex b/Tools/bootloaders/f303-M10070_bl.hex index 9f424cf403bd91..40838464d60ae7 100644 --- a/Tools/bootloaders/f303-M10070_bl.hex +++ b/Tools/bootloaders/f303-M10070_bl.hex @@ -1,1217 +1,1172 @@ :020000040800F2 -:1000000000090020B5040008CD250008852500085A -:10001000AD25000885250008A5250008B7040008BF -:10002000B7040008B7040008B7040008C135000889 -:10003000B7040008B7040008B704000875430008B7 -:10004000B7040008B7040008B7040008B7040008A4 -:10005000B7040008B70400085940000885400008AC -:10006000B1400008DD40000809410008B70400085D -:10007000B7040008B7040008B7040008B704000874 -:10008000B7040008B7040008B704000839250008C1 -:100090006525000875250008B704000835410008EB -:1000A000B7040008B7040008B7040008B704000844 -:1000B000B7040008B7040008B7040008B704000834 -:1000C000B7040008B7040008B7040008B704000824 -:1000D000B70400086545000879450008B704000822 -:1000E0009D410008B7040008B7040008B7040008E1 -:1000F000B7040008B7040008B7040008B7040008F4 -:10010000B7040008B7040008B7040008B7040008E3 -:10011000B7040008B7040008B7040008B7040008D3 -:10012000B7040008B7040008B7040008B7040008C3 -:10013000B7040008B7040008B7040008B7040008B3 -:10014000B7040008B7040008B7040008B7040008A3 -:10015000B7040008B7040008B7040008B704000893 -:10016000B7040008B7040008B7040008B704000883 -:10017000B7040008B7040008B7040008B704000873 -:10018000B7040008B7040008B7040008B704000863 -:10019000B7040008B7040008B7040008B704000853 -:1001A0002112000800000000000000000000000014 -:1001B00053B94AB9002908BF00281CBF4FF0FF31CE -:1001C0004FF0FF3000F074B9ADF1080C6DE904CECA -:1001D00000F006F8DDF804E0DDE9022304B0704722 -:1001E0002DE9F047089D04468E46002B4DD18A42EA -:1001F000944669D9B2FA82F252B101FA02F3C2F11D -:10020000200120FA01F10CFA02FC41EA030E9440AD -:100210004FEA1C48210CBEFBF8F61FFA8CF708FBCE -:1002200016E341EA034306FB07F199420AD91CEBA6 -:10023000030306F1FF3080F01F81994240F21C81D8 -:10024000023E63445B1AA4B2B3FBF8F008FB103320 -:1002500044EA034400FB07F7A7420AD91CEB040455 -:1002600000F1FF3380F00A81A74240F20781644425 -:10027000023840EA0640E41B00261DB1D4400023AA -:10028000C5E900433146BDE8F0878B4209D9002D0E -:1002900000F0EF800026C5E9000130463146BDE898 -:1002A000F087B3FA83F6002E4AD18B4202D3824202 -:1002B00000F2F980841A61EB030301209E46002DB1 -:1002C000E0D0C5E9004EDDE702B9FFDEB2FA82F206 -:1002D000002A40F09280A1EB0C014FEA1C471FFA64 -:1002E0008CFE0126200CB1FBF7F307FB131140EA4B -:1002F00001410EFB03F0884208D91CEB010103F118 -:10030000FF3802D2884200F2CB804346091AA4B2D9 -:10031000B1FBF7F007FB101144EA01440EFB00FEAD -:10032000A64508D91CEB040400F1FF3102D2A64512 -:1003300000F2BB800846A4EB0E0440EA03409CE7B1 -:10034000C6F12007B34022FA07FC4CEA030C20FA5E -:1003500007F401FA06F31C43F9404FEA1C4900FA7E -:1003600006F3B1FBF9F8200C1FFA8CFE09FB1811FB -:1003700040EA014108FB0EF0884202FA06F20BD96E -:100380001CEB010108F1FF3A80F08880884240F2BE -:100390008580A8F102086144091AA4B2B1FBF9F002 -:1003A00009FB101144EA014100FB0EFE8E4508D9FD -:1003B0001CEB010100F1FF346CD28E456AD9023882 -:1003C000614440EA0840A0FB0294A1EB0E01A14267 -:1003D000C846A64656D353D05DB1B3EB080261EBD5 -:1003E0000E0101FA07F722FA06F3F1401F43C5E9AF -:1003F000007100263146BDE8F087C2F12003D840E5 -:100400000CFA02FC21FA03F3914001434FEA1C4726 -:100410001FFA8CFEB3FBF7F007FB10360B0C43EA18 -:10042000064300FB0EF69E4204FA02F408D91CEBC8 -:10043000030300F1FF382FD29E422DD902386344C6 -:100440009B1B89B2B3FBF7F607FB163341EA034166 -:1004500006FB0EF38B4208D91CEB010106F1FF38B5 -:1004600016D28B4214D9023E6144C91A46EA0046AC -:1004700038E72E46284605E70646E3E61846F8E63E -:100480004B45A9D2B9EB020864EB0C0E0138A3E787 -:100490004646EAE7204694E74046D1E7D0467BE768 -:1004A000023B614432E7304609E76444023842E7E0 -:1004B000704700BF02E000F000F8FEE772B6374870 -:1004C00080F30888364880F3098836483649086042 -:1004D00040F20000CCF200004EF63471CEF2000182 -:1004E0000860BFF34F8FBFF36F8F40F20000C0F280 -:1004F000F0004EF68851CEF200010860BFF34F8F36 -:10050000BFF36F8F4FF00000E1EE100A4EF63C7122 -:10051000CEF200010860062080F31488BFF36F8FCD -:1005200003F04EFC03F0C2FC4FF055301F491B4A4C -:1005300091423CBF41F8040BFAE71D49184A914229 -:100540003CBF41F8040BFAE71A491B4A1B4B9A427D -:100550003EBF51F8040B42F8040BF8E7002018499D -:10056000184A91423CBF41F8040BFAE703F02CFC17 -:1005700003F0D8FC144C154DAC4203DA54F8041BBC -:100580008847F9E700F042F8114C124DAC4203DA0B -:1005900054F8041B8847F9E703F014BC0009002055 -:1005A000001100200000000808ED00E0000100201C -:1005B00000090020704B0008001100207C11002071 -:1005C00080110020583C0020A0010008A401000870 -:1005D000A4010008A40100082DE9F04F2DED108AB8 -:1005E000C1F80CD0C3689D46BDEC108ABDE8F08F01 -:1005F000002383F311882846A047002003F06AF9FE -:10060000FEE703F0CDF800DFFEE70000F8B500F0EC -:1006100019FE03F079FB074603F0C8FB05460028E6 -:1006200040D12C4B9F423DD001339F423DD02A4BBD -:1006300027F0FF029A423BD1F8B200F03FFC2E4671 -:1006400042F2107400F040FC08B10024264601F08C -:10065000B1F888B3032000F045F80024264635B1F0 -:100660001E4B9F4203D003F099FB00242646002036 -:1006700003F054FB1A4B1B6913F0400322D00EB158 -:1006800000F046F800F052FC00F0DEFD01F0A6FF9D -:100690000546CCB101F0A2FF401BA04214D900F0E6 -:1006A00037F8F3E72E460024CCE704460126C9E7D5 -:1006B00006464FF47A74C5E7002CD0D04FF47A7414 -:1006C0000126CCE71C46DDE700F078FC012003F0B2 -:1006D00007F9DEE7010007B0000008B0263A09B0CC -:1006E00000040048084B187003280CD8DFE800F01D -:1006F00008050208022000F003BE022000F0F8BD49 -:10070000024B00225A6070478011002084110020A3 -:1007100038B501F04FF830B11F4B03221A701F4B50 -:1007200000225A6038BD1E4B1E4A19680131F9D0AB -:1007300004339342F9D11C4C194DD4F80428AA4231 -:10074000F0D31A4B9B6803F1006303F5D0439A4240 -:10075000E8D203F0F7FA03F009FB002000F08EFD69 -:100760000220FFF7BFFF124BDA690022DA61D96974 -:1007700099699A619B6972B64FF0E0233021C3F802 -:10078000085DD4F80038D4F8042881F311889D4618 -:1007900083F308881047C5E78011002084110020EA -:1007A00000680008206800080060000800110020B0 -:1007B00000100240094A136849F2690099B21B0C03 -:1007C00000FB01331360064B186844F2506182B29B -:1007D000000C01FB0200186080B270471411002069 -:1007E0001011002010B500211022044600F0A2FDD7 -:1007F000034B03CB206061601868A06010BD00BF90 -:10080000ACF7FF1F2DE9F041ADF54E7D0DF1340839 -:100810006CAC40F2751207460D460EA80021C8F8D0 -:10082000001000F087FD4FF4C4720021204600F054 -:1008300081FD01F0D3FE254B4FF47A72B0FBF2F04C -:10084000186093E80700022384E807000DF5E970BB -:100850002382FFF7C7FF4EF603431D49238406A8F2 -:1008600004F0B6F8192384F832310DF2E32206AB16 -:100870000DF1300C1E4603CE6645106051603346C4 -:1008800002F10802F6D13378137041460122204666 -:1008900000F09CFD00230393AB7E029305F1190346 -:1008A000019380B20123CDE904800093E97E05A382 -:1008B000D3E90023384602F059FA0DF54E7DBDE824 -:1008C000F08100BF9E6AC421818A46EE8C1100200F -:1008D000E04900082DE9F0412C4C237ADAB080463B -:1008E0000D465BBB27A9284600F080FE074600287E -:1008F00042D19DF89D60C82E3ED801464FF4A662B5 -:10090000204600F017FD4FF48073C4F8F8314FF41F -:100910000073C4F80C334FF44073C4F820343246EB -:100920000DF19E0104F1090000F0F2FC26449DF84F -:100930009C30777223720BB9EB7E237281220021E7 -:1009400006AC27A800F0F6FC0122214627A800F0FB -:1009500089FE00230393AB7E029305F1190380B255 -:1009600001932823CDE904400093E97E05A3D3E950 -:100970000023404602F0FAF95AB0BDE8F08100BF0A -:10098000AFF3008026417272DF25D7B7A83200206E -:10099000F0B5254E4FF48A7505FB0065F1B096F869 -:1009A000D83085F8DC300024D822214685F8E8408C -:1009B0003AA800F0BFFC06F1090000F0B3FCD5F83E -:1009C000E4308DF8F000C2B206AF06F109010DF176 -:1009D000F100CDE93A3400F09BFC394601223AA8F7 -:1009E00000F06CFE80B2CDE9047008230127CDE948 -:1009F000023706F1D803019330230093317A0B4874 -:100A000007A3D3E9002302F0B1F9A04206DD01F00B -:100A1000E5FDC5F8E000384671B0F0BD2046FBE7C3 -:100A200078F6339F93CACD8DA8320020A4210020F0 -:100A30002DE9F0411D4D1E4E1E4F86B0284602F096 -:100A4000C1F9034658B30024CDE90344ADF814407E -:100A5000027B8DF8142099684068029403AA03C2AF -:100A60001B68DFF8548043F00043029301F0B8FDA7 -:100A7000821941F10003009402A9384601F07CF884 -:100A8000A04205DD284602F0A1F988F80040D5E72C -:100A900098F80030072B05D8013388F8003006B0ED -:100AA000BDE8F081014802F091F9F8E7A4210020A7 -:100AB00040420F00D8210020DD37002070B50D46E0 -:100AC00014461E4602F0AEF850B9022E10D1012C89 -:100AD0000ED112A3D3E90023C5E90023012007E0CA -:100AE000282C10D005D8012C09D0052C0FD00020BF -:100AF00070BD302CFBD10BA3D3E90023ECE70BA393 -:100B0000D3E90023E8E70BA3D3E90023E4E70BA331 -:100B1000D3E90023E0E700BFAFF30080401DA12030 -:100B200026812A0B78F6339F93CACD8D9E6AC42105 -:100B3000818A46EE26417272DF25D7B7F017304A18 -:100B400039059E5638B505460E4C0021013500F09A -:100B5000B7FBA4F82C55B4F82C0500F099FB78B13C -:100B6000B4F82C0500F0A4FB014648B9B4F82C05F4 -:100B700000F0A6FBB4F82C350133A4F82C35EAE7D5 -:100B800038BD00BFA832002010B50A4B0A4A1A60CF -:100B900003F5805393F860203AB9DC6D2CB1204600 -:100BA00000F082FE204603F053FEBDE810400348EB -:100BB00000F07ABED8210020384A000820320020F8 -:100BC0002DE9F04F8FB000AF05460C4602F02AF831 -:100BD000002849D1237E022B1BD1E38A012B18D197 -:100BE00001F0FCFC0646FFF7E5FD03464FF4C87034 -:100BF000DFF8C482B3FBF0F206F5167602FB103381 -:100C000016FA83F3C8F80030E37E33B9A34B002211 -:100C10001A703C37BD46BDE8F08F07F1240120462D -:100C200000F0A2FC0028F4D107F11400FFF7DAFD70 -:100C300097F8264007F11401224607F1270003F038 -:100C400051FE0028E2D10F2C08D8944B1C70D8F824 -:100C50000030A3F51673C8F80030DAE797F82410CF -:100C6000284601F0D7FFD4E7E38A282B2BD010D8F1 -:100C7000012B23D0052BCCD1BFF34F8F8849894B53 -:100C8000CA6802F4E0621343CB60BFF34F8F00BF2A -:100C9000FDE7302BBDD1844EE17E327A9142B8D14E -:100CA000607E3146002291F8DC50854200F0A5803C -:100CB0000132042A01F58A71F5D1AAE721462846B6 -:100CC000FFF7A0FDA5E721462846FFF703FEA0E7B2 -:100CD000B2F8EC507B6005F103094FEA99094FEA3D -:100CE0008902D11DC908A8EBC1039D46EB4600212E -:100CF000584600F01FFB04F1EE012A4631445846E5 -:100D000000F006FB7B6813B9012000F0B7FA96F8F3 -:100D1000D20000F0BDFA044630B9307200F0D8FAC3 -:100D2000204600F0ABFAB1E0D6F8D4203AB996F8F4 -:100D3000D200B6F82C25824201D8FFF703FFD6F87F -:100D4000D4202A44944208D296F8D200B6F82C2532 -:100D50000130824201D8FFF7F5FE70685FFA89F230 -:100D6000594600F0EFFA08B9C54679E0726896F87E -:100D7000D2002A447260D6F8D42005EB0209C6F8E6 -:100D8000D49000F085FA814509D396F8D220D6F8A0 -:100D9000D4000132001B86F8D220C6F8D400FF2D03 -:100DA0000FD80024347200F093FA204600F066FA5F -:100DB00000F000FD3D4B188108B9FFF7A9FCC546BE -:100DC00027E7BB6896F8D9000AFB0362FB68D2F8F4 -:100DD000E41082F8E83001F58061C2F8E030C2F832 -:100DE000E410FFF7D5FDFFF723FE96F8D920013276 -:100DF00002F0030286F8D920B6E74FF48A7A0AFB9C -:100E000002F505F1EA013144204600F083FCF86068 -:100E100000287FF4FEAE3544012285F8E82001F079 -:100E2000DDFBD5F8E020D6ED007ADFED216A801AEF -:100E3000192838BF192040F6B832904228BF104612 -:100E4000B8EE677A07EE900AF8EEE77A67EEA67AD0 -:100E5000DFED186AE7EE267AFCEEE77AC6ED007A57 -:100E600096F8D930BB60BA6873680AFB02F432198D -:100E700092F8E81059B1D2F8E4108B42E8463FF4FA -:100E800027AF002182F8E810C2F8E010C546736869 -:100E9000064A9B0A01331381BBE600BF9D21002057 -:100EA00000ED00E00400FA05A83200208C110020BB -:100EB000CDCCCC3D6666663FA0210020014B18706A -:100EC000704700BF9811002038B54FF00054134B05 -:100ED00022689A4220D1124B627D12481A70237DFB -:100EE00003724FF48073C0F8F8314FF40073C0F808 -:100EF0000C3300254FF44073C0F820340A49C0F881 -:100F0000E450C922093000F003FAE02229462046C5 -:100F100000F010FA012038BD0020FCE79AAD44C56E -:100F200098110020A83200201600002037B500F0EC -:100F300041FC194D194928810223012218486B717F -:100F400001F0EAF900230193164B17490093174863 -:100F5000174B4FF4805201F035FE164B197811B142 -:100F6000124801F057FE01F039FB0446FFF722FC5E -:100F70004FF4C873B0FBF3F202FB130304F51670D1 -:100F800010FA83F00C4B186002F010FF08B10F2329 -:100F90002B8103B030BD00BF8C11002040420F00F8 -:100FA000D8210020BD0A00089C110020A4210020A7 -:100FB000C10B000898110020A02100202DE9F04F5E -:100FC0002DED028B8EA7D7E900670FF23C29D9E9F6 -:100FD0000089864C95B00DAD9FED828BFFF728FD03 -:100FE000DFF82CB200230C93ADF83C300D936B600E -:100FF00000230DF125028DED008B4FF0010A09A9A8 -:1010000058468DF825308DF824A001F035F99DF86B -:1010100024200023002A40F0AB80204601F002FE8D -:101020000546002847D1DFF8ECB101F0D7FADBF82C -:10103000003098423FD301F0D1FA0790FFF7BAFB96 -:10104000079A4FF4C873B0FBF3F101FB130302F5E9 -:10105000167010FA83F0CBF80000DFF8BCB19BF8F3 -:1010600000100791002914BF2B46534610A88DF895 -:101070003030FFF7B7FB0799C1F11002D2B2062A50 -:1010800010AB28BF062219440DF13100079200F081 -:101090003FF9079A0CAB0393182302930132544B88 -:1010A000D2B2CDE900A304923B463246204601F07D -:1010B000FFFD8BF8005001F091FA4E4A4E4D136837 -:1010C000C31AB3F57A7F32D3106001F089FA024671 -:1010D0000B46204601F084FE204601F0A3FD30B30C -:1010E0002B7ADFF838A1002B14BF032302238AF8E0 -:1010F000053001F073FA0DF1400B4FF47A730122C1 -:10110000B0FBF3F05946CAF80000504600F004FA6C -:1011100018230293394B019380B240F25513CDE965 -:1011200003B0009342464B46204601F0C1FD2B7AA6 -:10113000CBB101F053FA4FF0000A83464FF48A72A4 -:1011400095F8D900504400F0030002FB005393F8D7 -:10115000E81089B30AF1010ABAF1040FF0D12B7A31 -:10116000002B7FF438AF15B0BDEC028BBDE8F08FDB -:101170004FF0904110A84A6982F010024A61194666 -:10118000102200F0D7F80DF126030AAA0CA9584640 -:1011900000F0F0FD95E8030011AB83E803009DF833 -:1011A0003C308DF84C300C9B109310A9DDE90A23DC -:1011B000204601F0E9FF1BE7D3F8E01049B12B68A6 -:1011C000FA2B38BFFA23ABEB01010533B1EB430F28 -:1011D000C0D3FFF7DDFB4FF48A720028BAD1BEE717 -:1011E000AFF300800000000000000000A4210020F8 -:1011F0009C210020D8370020A8320020DC370020B6 -:10120000401DA12026812A0BF1C6A7C1D068080F76 -:10121000D8210020A02100209D2100208C11002039 -:1012200008B5054800F040FEBDE80840034A0449FF -:10123000002003F007BB00BFD82100201838002091 -:10124000890B00087047000070B502F013FC094ECE -:10125000094D3080002428683388834208D902F081 -:1012600005FC2B6804440133B4F5D04F2B60F2D356 -:1012700070BD00BF0C380020E037002002F086BCB3 -:1012800000F10060920000F5D04002F02DBC00009B -:10129000054B1A68054B1B889B1A834202D91044E0 -:1012A00002F0E4BB00207047E03700200C3800203B -:1012B000024B1B68184402F0DFBB00BFE037002080 -:1012C000024B1B68184402F0E9BB00BFE037002066 -:1012D000064991F8243033B10023086A81F824309C -:1012E0000822FFF7CDBF0120704700BFE437002080 -:1012F000022802BF4FF0904310229A61704700000D -:10130000022802BF4FF090434FF480129A61704759 -:1013100010B50023934203D0CC5CC4540133F9E7E9 -:1013200010BD000003460246D01A12F9011B002925 -:10133000FAD1704702440346934202D003F8011BDE -:10134000FAE770472DE9F8431F4D144695F824201D -:101350000746884652BBDFF870909CB395F824305E -:101360002BB92022FF2148462F62FFF7E3FF95F8B3 -:101370002400C0F10802A24228BF2246D6B241464C -:10138000920005EB8000FFF7C3FF95F82430A41B03 -:101390001E44F6B2082E17449044E4B285F8246047 -:1013A000DBD1FFF795FF0028D7D108E02B6A03EBCC -:1013B00082038342CFD0FFF78BFF0028CBD10020E0 -:1013C000BDE8F8830120FBE7E43700202DE9F04772 -:1013D0000D46044600219046284640F27912FFF758 -:1013E000A9FF234620220021284601F06FFE231D7D -:1013F00002222021284601F069FE631D03222221DA -:10140000284601F063FEA31D03222521284601F092 -:101410005DFE04F1080310222821284601F056FE43 -:1014200004F1100308223821284601F04FFE04F190 -:10143000110308224021284601F048FE04F112035E -:1014400008224821284601F041FE04F1140320221D -:101450005021284601F03AFE04F118034022702181 -:10146000284601F033FE04F120030822B02128466B -:1014700001F02CFE04F121030822B821284601F0D6 -:1014800025FE04F12207C0263B46314608222846A5 -:10149000083601F01BFEB6F5A07F07F10107F3D176 -:1014A00004F1320308223146284601F00FFE0027DE -:1014B00004F1330A94F832304FEAC7099F4209F524 -:1014C000A47615D3B8F1000F08D1314604F599730D -:1014D0000722284601F0FAFD09F24F16274694F834 -:1014E00032213B1B93420CD3F01DC008BDE8F087AE -:1014F0000AEB070308223146284601F0E7FD0137D1 -:10150000D8E707F2331331460822284601F0DEFD02 -:1015100008360137E3E7000013B50446084600210A -:1015200001602346C0F803102022019001F0CEFD97 -:101530000198231D0222202101F0C8FD0198631D9E -:101540000322222101F0C2FD0198A31D03222521BF -:1015500001F0BCFD019804F108031022282101F0DC -:10156000B5FD072002B010BDF7B50023047F009140 -:101570000E4607221946054601F06CFC731C0093C9 -:10158000012200230721284601F064FCC4B9B31CE2 -:101590000093052223460821284601F05BFC0D2418 -:1015A0003746B278BB1B934211D32B7FA88A0734EE -:1015B000E408BBB9844294BF0020012003B0F0BD11 -:1015C000AB8ADB00083BDB08B3700824E8E7FB1CB0 -:1015D0000093214600230822284601F03BFC0834F2 -:1015E0000137DEE7201A18BF0120E7E7F7B500232F -:1015F000047F00910E4608221946054601F02AFC98 -:10160000731CC4B90822009311462346284601F0F2 -:1016100021FC1024012372785F1C013B934211D3FB -:101620002B7FA88A0734E408BBB9844294BF00200A -:10163000012003B0F0BDAB8ADB00083BDB08737010 -:101640000824E7E7F31900932146002308222846DF -:1016500001F000FC08343B46DDE7201A18BF0120EA -:10166000E7E70000F8B50E46054614460021812242 -:101670003046FFF75FFE2B4608220021304601F07E -:1016800025FD7CB96B1C07220821304601F01EFDA8 -:101690000F2401236A785F1C013B934204D3E01DB1 -:1016A000C008F8BD0824F4E7EB19214608223046AB -:1016B00001F00CFD08343B46ECE70000F8B50E469F -:1016C000054614460021CE223046FFF733FE2B4656 -:1016D00028220021304601F0F9FC7CB905F108030D -:1016E00008222821304601F0F1FC30242F462A7AC6 -:1016F0007B1B934204D3E01DC008F8BD2824F5E706 -:1017000007F1090321460822304601F0DFFC0834C6 -:101710000137ECE7F7B5047F00910E460123102254 -:101720000021054601F096FBC4B9B31C00930922C1 -:1017300023461021284601F08DFB19243746728874 -:10174000BB1B9A4211D82B7FA88A0734E408BBB987 -:10175000844294BF0020012003B0F0BDAB8ADB00BF -:10176000103BDB0873801024E8E73B1D0093214603 -:1017700000230822284601F06DFB08340137DEE71C -:10178000201A18BF0120E7E730B5094D0A449142FD -:101790000DD011F8013B5840082340F30004013BF1 -:1017A0002C4013F0FF0384EA5000F6D1EFE730BD80 -:1017B0002083B8EDF7B5364A106851686B4603C30D -:1017C0006A4634493448082303F09CF8044690BB29 -:1017D0000A25324A106851686B4603C36A4630498D -:1017E0002D48082303F08EF80446002847D00369EB -:1017F000B3F5663F43D8B0F86620B2F57B7F3ED1A3 -:10180000284A024402F15C018B4238D35C3B2249F6 -:1018100000209E1AFFF7B8FF3246074604F1640124 -:101820000020FFF7B1FFA3689F4228D1E3689842E8 -:1018300008BF002523E00369B3F5663F26D8428B35 -:10184000B2F57B7F20D1174A024402F110018B428E -:1018500018D3103B104900209D1AFFF795FF2A4628 -:10186000064604F118010020FFF78EFFA3689E4290 -:1018700002D1E368984201D00D25AAE70025284649 -:1018800003B0F0BD1025A4E70C25A2E70B25A0E7C7 -:10189000FC490008DC97030000680008054A0008BE -:1018A000909703000898FFF710B5037C044613B91E -:1018B000006803F00FF8204610BD00000023BFF3BE -:1018C0005B8FC360BFF35B8FBFF35B8F8360BFF33E -:1018D0005B8F7047BFF35B8F0068BFF35B8F704710 -:1018E00070B505460C30FFF7F5FF05F10806044614 -:1018F0003046FFF7EFFFA04206D930466D68FFF78C -:10190000E9FF2544281A70BD3046FFF7E3FF201A8F -:10191000F9E7000070B50546406898B105F1080088 -:10192000FFF7D8FF05F10C0604463046FFF7D2FF5B -:101930008442304694BF6D680025FFF7CBFF013C21 -:101940002C44201A70BD000038B50C460546FFF740 -:10195000C7FFA04210D305F10800FFF7BBFF044406 -:101960006868B4FBF0F100FB1144BFF35B8F01200A -:10197000AC60BFF35B8F38BD0020FCE72DE9F04180 -:10198000144607460D46FFF7C5FF844228BF0446AC -:10199000D4B1B84658F80C6B4046FFF79BFF304473 -:1019A000286040467E68FFF795FF331A9C4203D8B3 -:1019B0006C600120BDE8F0816B60A41B3B68AB60EC -:1019C0002044E8600220F5E72046F3E738B50C46EE -:1019D0000546FFF79FFFA04210D305F10C00FFF76B -:1019E00079FF04446868B4FBF0F100FB1144BFF3D5 -:1019F0005B8F0120EC60BFF35B8F38BD0020FCE7FC -:101A00002DE9FF41884669460746FFF7B7FF6C4658 -:101A100006B204EBC6060025B44209D0626820680D -:101A200008EB0501FFF774FC636808341D44F3E715 -:101A300029463846FFF7CAFF284604B0BDE8F081C2 -:101A4000F8B505460C300F46FFF744FF05F10806D0 -:101A500004463046FFF73EFFA042304688BF6C6820 -:101A6000FFF738FF201A386020B130462C68FFF7A6 -:101A700031FF2044F8BD000073B5144606460D46FC -:101A8000FFF72EFF844228BF04460190DCB101A974 -:101A90003046FFF7D5FF019B33B93268C5E9023301 -:101AA000C5E9002401200CE09C4238BF0194286065 -:101AB000019868608442F5D93368AB60241AEC6001 -:101AC000022002B070BD2046FBE700002DE9FF4177 -:101AD0000F466946FFF7D0FF6C4600B204EBC00525 -:101AE0000026AC4209D0D4F8048054F8081BB81979 -:101AF0004246FFF70DFC4644F3E7304604B0BDE82C -:101B0000F081000038B50546FFF7E0FF04460146C6 -:101B10002846FFF719FF204638BD0000302383F325 -:101B2000118862B670470000002383F3118862B603 -:101B30007047000010B4026854681A4623465DF8E6 -:101B4000044B184701207047002070470020704761 -:101B500070470000002070470E20704700F580504D -:101B600090F8C800C0F340007047000000F58050B6 -:101B700090F9C90070470000F7B50C68BDF82070F7 -:101B800014F000541E466FD10B7B082B6CD8FFF766 -:101B9000C5FF4569AB685B010CD4AB681B0108D479 -:101BA000AC6814F080545DD1FFF7BEFF204603B04F -:101BB000F0BD01240B6804F1180C002BB8BFDB004A -:101BC0004FEA0C1CB4BF43F004035B0545F80C302E -:101BD0000B680FFA84FC13F0804F18BF05EB0C1E46 -:101BE00005EB0C1C1EBFDEF8803143F00203CEF87B -:101BF00080310B7BCCF8843105EB04158B68C5F87C -:101C00008C314B68C5F88831DCF8803143F0010332 -:101C1000CCF8803100EB441541F268031D4403EB1E -:101C200044130344C5E9002608330D4601F10C0CAA -:101C300055F804EB43F804EB6545F9D184342D885D -:101C40001D8000EB441407F00303257925F00B05F4 -:101C50002B432371FFF768FF0097334600F0E0FC49 -:101C60000120A4E70224A5E74FF0FF309FE7000022 -:101C700013B500F580540191E06DFFF74BFE1F286E -:101C80000AD90199E06D2022FFF7BAFEA0F12003E6 -:101C90005842584102B010BD0020FBE708B500F5DE -:101CA0008050FFF73BFFC06DFFF708FEBDE808401E -:101CB000FFF73ABF00220260828142608260704773 -:101CC00010B500220023C0E900230023044603814D -:101CD0000C30FFF7EFFF204610BD0000F0B50546C1 -:101CE00000F580500C4690F8C83013F0040FC3F391 -:101CF000800108BF114661F3820304F1840680F875 -:101D0000C83005EB461389B01B79D8072ED57AB3B6 -:101D100019072DD46846FFF7D3FF05EB441303F5ED -:101D2000835303F1180703AA10331868596814463F -:101D300003C40833BB422246F7D1186820609B8851 -:101D4000A380DDE90E23CDE900230123ADF808309F -:101D50002B686946DB6B2846984705EB46152B79BF -:101D60001A075CBF43F008032B7101E0002AF4D18D -:101D700009B0F0BD2DE9F047074688B007F580545B -:101D800068469A468846FFF7C9FE9146FFF798FFD6 -:101D9000E06DFFF7A5FD1F2829D9E06D20226946D7 -:101DA000FFF7B0FE202822D103AD444605AB2E46F6 -:101DB00003CE9E4220606160354604F10804F6D1EE -:101DC00030682060B388A380DDE90023C9E90023DF -:101DD000BDF80830AAF80030FFF7A6FE4A46534681 -:101DE0004146384608B0BDE8F04700F007BCFFF7B1 -:101DF0009BFE002008B0BDE8F08700002DE9F84FF9 -:101E00000023C0E90133254B044640F8183B0F4638 -:101E1000FFF750FF04F12800FFF752FF04F14808D4 -:101E200004F582554646083530462036FFF748FF10 -:101E3000AE42F9D104F580554FF480534FF00009BC -:101E4000C5E91339C5F848800123EE6504F58758C4 -:101E500004F58456C5F8549085F8583085F86030FC -:101E6000083608F108084FF0000A4FF0000B46E969 -:101E700008ABA6F11800FFF71DFF203646F8289C96 -:101E80004645F4D185F8C97017B1054800F0A0FBAC -:101E9000044B63612046BDE8F88F00BF384A000854 -:101EA000104A00080064004010B5044B197804463D -:101EB0004A1C1A70FFF7A2FF204610BD14380020FC -:101EC0002DE9F047002950D0294B2A4FB7FBF1F5F7 -:101ED00099428CBF0A231123581EB5FBF3FC03FB68 -:101EE0001C53C4B22BB102280346F5D80020BDE82C -:101EF000F0870CF1FF36B6F5806FF7D2C4EBC40E55 -:101F00000EF103034FEAE309C3F3C703A4EB03088D -:101F100009F1010A4FF47A755FFA88F009FB05555B -:101F20005AFA88F8B5FBF8F5B5F5617FC1BF0EF137 -:101F3000FF33C3F3C703E01AC0B25C1C50FA84F449 -:101F40000CFB04F4B7FBF4F4A142CFD1013BDBB2AC -:101F50000F2BCBD80138C0B20728C7D80021107189 -:101F600016809170D3700120C1E70846BFE700BF1B -:101F70003F420F000051250270B505460E464FF452 -:101F80007A746B695B6803F00103B3424FF00100A0 -:101F900004D001F0A5FC013CF3D1204670BD000047 -:101FA00030B54269936913F0700F16D000230B4CC3 -:101FB000936103F1840200EB421211794D0709D5B8 -:101FC000890707D5416954F823508D60117941F094 -:101FD000040111710133032BEBD130BD244A0008F9 -:101FE00073B51D46436916469A68D207044609D55B -:101FF0009A6801219960C2F34002CDE90065002191 -:10200000FFF76CFE63699A68D1050BD59A684FF4A7 -:1020100080719960C2F34022CDE90065012120461C -:10202000FFF75CFE63699A68D2030BD59A684FF498 -:1020300080319960C2F34042CDE90065022120461B -:10204000FFF74CFE204602B0BDE87040FFF7A8BF86 -:10205000F8B50446466900296CD106F10C073868CA -:1020600080076AD006EB01153868D5F8B00110F08A -:10207000040FD5F8B0011ABFC00840F00040400D71 -:10208000A061D5F8B0C11CF0020F1CBF40F0804029 -:10209000A061D5F8B40106EB011100F00F0084F83F -:1020A0002400D1F8B8012077D1F8B801000A607790 -:1020B000D1F8B801000CA077D1F8B801000EE07794 -:1020C000D1F8BC0184F82000D1F8BC01000A84F8E2 -:1020D0002100D1F8BC01000C84F82200D1F8BC1119 -:1020E000090E84F823103821396004F1340004F11A -:1020F000180104F1240551F8046B40F8046BA9425F -:10210000F9D109880180C4E90A23214600232386E6 -:1021100051F8283B2046DB6B984704F58052204657 -:1021200092F8C83043F0040382F8C830BDE8F840A4 -:10213000FFF736BF06F1100791E7F8BD10B504466A -:1021400000F04EFA02460B4652EA030102D0013A71 -:1021500063F100030449086820B12146BDE810403E -:10216000FFF776BF10BD00BF10380020F8B500F5AE -:1021700083511E46FFF7D2FCDFF844C0083100242B -:1021800004F1840500EB45152B795F070ED4DB06BF -:102190000CD5D1E900739742B34107D243695CF88B -:1021A00024709F602B7943F004032B710134032CBE -:1021B00001F12001E4D1BDE8F840FFF7B5BC00BF54 -:1021C000244A000808B5FFF7A9FCFFF7E9FEBDE8BF -:1021D0000840FFF7A9BC0000F8B5436905469868B8 -:1021E00000F0E050B0F1E05F0F461FD0E8B1FFF71C -:1021F00095FC05F583541034002606F1840305EBA5 -:1022000043131B791A0706D50136032E04F1200467 -:10221000F3D1012007E05B07F6D42146384600F0F1 -:1022200039FA0028F0D1FFF77FFCF8BD0120FCE768 -:1022300000F5805008B5FFF771FCC06DFFF750FB4B -:10224000FFF772FC43090CBF0120002008BD00000D -:10225000F8B51D46002313700F4606461446FFF7D7 -:10226000E7FF80F00100387025B129463046FFF7BE -:10227000B3FF2070F8BD00002DE9B8410C461546AB -:102280001F46804600F0ACF90B462178024609B99A -:10229000287850B14046FFF769FFFFF793FF3B46B0 -:1022A0002A462146FFF7D4FF0120BDE8B88100008F -:1022B00010B5FFF733FC174BDA6942F00072DA61B0 -:1022C0001A6942F000721A611A6900F5805422F00E -:1022D00000721A61FFF728FC94F8C830DB0718D4A5 -:1022E000B9B103211320FFF719FC01F0C7F903214D -:1022F000142001F0C3F90321152001F0BFF994F86F -:10230000C83043F0010384F8C830BDE81040FFF73F -:102310000BBC10BD001002402DE9F04700F58055C0 -:1023200088B095F8C930012B0446884616467FD8F8 -:10233000804F57F823200AB947F82300D7F800A0A8 -:10234000C4F80C802674BAF1000F63D095F8C93038 -:10235000012B6FD001212046FFF7AAFFFFF7DEFB1C -:102360006269136823F0020313606269136843F023 -:1023700001031360636900275F6101212046FFF7B5 -:10238000D3FBFFF7F9FD002800F09580E86DFFF71B -:1023900095FA04F58359BA4609F10809202200216B -:1023A0006846FEF7C7FF02A8FFF784FCCDF818A027 -:1023B0006A4609EB07030DF1180E9446BCE80300CA -:1023C000F44518605960624603F10803F5D1DCF862 -:1023D0000000186020379CF804201A71602FDDD1AE -:1023E00095F8C8306FF38203002785F8C8306A4635 -:1023F00041462046ADF80070ADF802708DF80470CB -:10240000FFF75EFD636948BB4FF400421A6008B0F5 -:10241000BDE8F08741F2D00002F01CFA814610B10D -:102420005146FFF7EBFCC7F80090B9F1000F8DD1D2 -:102430000020ECE7386803681B6B984701460028CA -:1024400088D13868FFF734FF3868036832465B6824 -:102450004146984700287FF47DAFE9E761221A6082 -:102460009DF802309DF803201B06120402F470222E -:1024700003F040731343BDF80020C2F30902134375 -:102480009DF804201205022E02F4E0020CBF4FF06A -:1024900000410021134362690B43D3616369132236 -:1024A0005A616269136823F00103136039462046BC -:1024B000FFF762FD08B96369A6E795F8C93093BBD9 -:1024C0006169D1F8002242F00102C1F8002261697D -:1024D000D1F8002222F47C5222F00E02C1F8002230 -:1024E0006169D1F8002242F46062C1F80022626999 -:1024F000C2F814326269C2F80432626941F6FF71AF -:10250000C2F80C126269C2F840326269C2F8443201 -:1025100063690122C3F81C226269D2F8003223F0F9 -:102520000103C2F8003295F8C83043F0020385F881 -:10253000C8306CE71038002008B500F051F850EAB8 -:102540000103024602D0421E61F10001044B1868EB -:1025500010B10B46FFF744FDBDE8084001F064B838 -:102560001038002008B50020FFF7E8FDBDE808405E -:1025700001F05AB808B50120FFF7E0FDBDE80840BA -:1025800001F052B800B59BB0EFF3098168226846AC -:10259000FEF7BEFEEFF30583014B9B6BFEE700BF2A -:1025A00000ED00E008B5FFF7EDFF000000B59BB0BF -:1025B000EFF3098168226846FEF7AAFEEFF3058370 -:1025C000014B5B6BFEE700BF00ED00E0FEE70000A3 -:1025D0000FB408B5029801F019F9FEE701F02EBB1F -:1025E00001F004BB13B56C4684E80600031D94E8B3 -:1025F000030083E80500012002B010BD73B58568B3 -:10260000019155B11B885B0707D4D0E900369B6B5D -:102610009847019AC1B23046A847012002B070BD68 -:10262000F0B5866889B005460C465EB1BDF8383015 -:102630005B070AD4D0E900379B6B98472246C1B2AA -:102640003846B047012009B0F0BD00220023CDE993 -:1026500000230023ADF808300A4603AB01F1080659 -:10266000106851681C4603C40832B2422346F7D1B1 -:10267000106820609288A280FFF7B2FF0423ADF8B3 -:1026800008302B68CDE90001DB6B69462846984786 -:10269000D8E7000030B503680968DD0FB5EBD17FDE -:1026A00023F0604421F060424FEAD1700BD0002B40 -:1026B000B8BFA40C0029B8BF920C944202D034BF1A -:1026C0000120002030BD944205D1C1F38070C3F3D6 -:1026D00080738342F6D194422CBF00200120F1E7A1 -:1026E0002DE9F041456A15B94162BDE8F0814B68BA -:1026F00023F06047C3F38A464FEAD37EC3F3807862 -:1027000016EA230638BF3E46AC462B465A68BEEB57 -:10271000D27F22F060440AD0002A18DAA40CB44216 -:1027200017D19D420FD10D60DEE71346EEE7A742B9 -:1027300007D102F08044C2F3807242450BD054B1FD -:10274000EFE708D2EDE7CCF800100B60CDE7B4421C -:1027500001D0B442E5D81A689C46002AE5D1196038 -:10276000C3E700002DE9F047089D01F007044FEA98 -:10277000D508224405F0070500EBD1004FF47F494E -:10278000944201D1BDE8F08704F0070705F0070A7D -:1027900057453E4638BF5646C6F10806111B8E42C5 -:1027A00028BF0E46E10808EBD50E415C13F80EC0B9 -:1027B000B94029FA06F721FA0AF1FFB28CEA0101C1 -:1027C00047FA0AF739408CEA010C03F80EC034448A -:1027D0003544D5E780EA0120082341F2210201B205 -:1027E0004000002980B203F1FF33B8BF504013F01E -:1027F000FF03F4D17047000038B50C468D18A54290 -:1028000000D138BD14F8011BFFF7E4FFF7E7000023 -:1028100042684AB1136843604389818901339BB29E -:102820009942438138BF83811046704770B588B0A4 -:10283000202204460D4668460021FEF77BFD204617 -:102840000495FFF7E5FF024658B16B46054608AE12 -:102850001C4603CCB44228606960234605F1080594 -:10286000F6D1104608B070BD082817D909280CD039 -:102870000A280CD00B280CD00C280CD00D280CD01A -:102880000E2814BF4020302070470C2070471020C5 -:1028900070471420704718207047202070470000B0 -:1028A000082817D90C280CD910280CD914280CD9B1 -:1028B00018280CD920280CD930288CBF0F200E20C6 -:1028C0007047092070470A2070470B2070470C2082 -:1028D00070470D20704700002DE9F843078C072F43 -:1028E00004461ED9D0E9029800254FF6FF73C5F1C2 -:1028F0002006A5F1200029FA05F108FA06F628FAC3 -:1029000000F031430143C9B21846FFF763FF0835B1 -:10291000402D0346EBD1E1693A46BDE8F843FFF7A5 -:102920006BBF4FF6FF70BDE8F883000010B54B6831 -:1029300023B9CA8A63F30902CA8210BD04691A68FE -:102940001C600361C38A013BC3824A60EFE7000059 -:102950002DE9F84F1D46CB8A0F46C3F3090105291F -:10296000814692460B4630D00020AAB207F11A04E5 -:102970009EB2042E1FFA80F80FD8904503F1010390 -:1029800006D3FB8A0A4462F30903FB8201201AE0A2 -:102990001AF80060E6540130EAE79045F1D2A1F15F -:1029A000050B1C237C68BBFBF3F203FB12BB1FFA75 -:1029B0008BF6002C45D14846FFF72AFF044638B96C -:1029C00078606FF00200BDE8F88F4FF00008E6E78E -:1029D000002606607860ADB24FF0000B454510D977 -:1029E0000AEB0803221D13F8011B9155B1B208F13F -:1029F00001081B291FFA88F82BD0454506F101066E -:102A0000F1D8FB8AC3F30902154465F30903BCE757 -:102A1000013292B21C462368002BF9D16B1F0B4484 -:102A20001C21B3FBF1F301339BB29A42D3D2BBF129 -:102A3000000FD0D14846FFF7EBFE20B9C4F800B034 -:102A4000BFE70122E7E7C0F800B05E462060044619 -:102A5000C1E74545D5D94846FFF7DAFE08B92060F9 -:102A6000AFE7C0F800B0002620600446B6E70000DB -:102A70002DE9F04F2DED028B1C4683B05B6901926E -:102A800007468846002B00F09A80238C2BB1E26920 -:102A9000002A00F09480072B35D807F10C00FFF7CF -:102AA000B7FE054638B96FF00205284603B0BDEC05 -:102AB000028BBDE8F08F14220021FEF73BFC228C34 -:102AC000E16905F10800FEF723FC208C013080B29B -:102AD000FFF7E6FEFFF7C8FE013880B22084013020 -:102AE00028746369228C1B782A4403F01F0363F067 -:102AF0003F0348F000411372384669602946FFF7EA -:102B0000EFFD0125D1E700F10C034FF0000908EEBD -:102B1000103A4FF0800A4E464D4618EE100AFFF765 -:102B200077FE83460028BED014220021FEF702FC67 -:102B3000002E3AD1019BABF8083002220BF1080EAF -:102B40001FFA82FC0CF10100BCF1060F218C80B24F -:102B500001D88E422BD3FFF7A3FEFFF785FE6269F3 -:102B60001278013802F01F028E4208BF4FF0400A6F -:102B700042EA49121BFA80F14AEA020A013048F09F -:102B8000004281F808A08BF81000CBF804205946C9 -:102B90003846FFF7A5FD238C0135B3422DB289F0ED -:102BA00001094FF0000AB8D17FE70022C6E7E169CA -:102BB000895D0EF802100136B6B20132C0E76FF03F -:102BC000010572E7F8B515460E463022002104468D -:102BD0001F46FEF7AFFB069B6360B5F5001F079B22 -:102BE000A76034BF6A094FF6FF72A36297B2E6612D -:102BF00004F1100000239A4206D800230360A78244 -:102C0000E3822383E360F8BD06600133304620365B -:102C1000F1E7000003781BB94BB2002BC8BF01706D -:102C20007047000000787047F8B50C46C969074640 -:102C300011B9238C002B37D1257E1F2D34D838783D -:102C400028BB228C072A2CD8268A36F003032BD1E6 -:102C50004FF6FF70FFF7D0FD20F001003102400475 -:102C600041EA0561400C41EA40254FF6FF722346D8 -:102C700029463846FFF7FCFE002807DD6269137815 -:102C80000133DBB21F2B88BF00231370F8BD218AEC -:102C90002D0645EA012505432046FFF71DFE0246A5 -:102CA000E5E76FF00300F1E76FF00100EEE70000E9 -:102CB00070B58AB0044616460021282268461D4693 -:102CC000FEF738FBBDF83830ADF810300F9B059398 -:102CD0009DF840308DF81830119B07936946BDF878 -:102CE0004830ADF820302046CDE90265FFF79CFF63 -:102CF0000AB070BD2DE9F041D36905460C46164671 -:102D00000BB9138C5BBB377E1F2F28D895F800803A -:102D1000B8F1000F26D03046FFF7DEFD33782102F0 -:102D200041EAC33141EA0801338A41EA076141EAD5 -:102D300003410246334641F080012846FFF798FEE2 -:102D400000280ADD3378012B07D17269137801332B -:102D5000DBB21F2B88BF00231370BDE8F0816FF03A -:102D60000100FAE76FF00300F7E70000F0B58BB061 -:102D700004460D4617460021282268461E46FEF7E7 -:102D8000D9FA9DF84C305A1E534253418DF8003009 -:102D90009DF84030ADF81030119B05939DF84830F8 -:102DA0008DF81830149B07936A46BDF85430ADF87F -:102DB000203029462046CDE90276FFF79BFF0BB075 -:102DC000F0BD0000406A00B104307047436A1A68E1 -:102DD000426202691A600361C38A013BC382704781 -:102DE0002DE9F041D0F82080194E14461D46414689 -:102DF000002709B9BDE8F081D1E90223A21A65EBE9 -:102E00000303964277EB03031ED2036A8B420DD174 -:102E1000FFF78CFD036A1B68036203690B60C38ABA -:102E20000161016A013BC3828846E2E7FFF77EFD4C -:102E30000B68C8F8003003690B60C38A0161013B6D -:102E4000C382D8F80010D4E788460968D1E700BFEC -:102E500080841E002DE9F04F8BB00D46DDF85090B8 -:102E600014469B468046002800F01981B9F1000FF6 -:102E700000F01581531E3F2B00F21181012A03D16E -:102E8000BBF1000F40F00B810023CDE90833B8F807 -:102E90001430B5EBC30F4FEAC30703D300200BB0C8 -:102EA000BDE8F08F2B199F42D8F80C303ABF7F1B3A -:102EB000FFB227461BB9D8F81030002B7AD0272D47 -:102EC0004ED8C5F12806B7424FF000032CBFF6B22A -:102ED0003E4600932946D8F8080008AB3246FFF773 -:102EE00041FCA7EB060A35445FFA8AFAB8F81430B9 -:102EF00003F10053053BDB000493D8F80C30039337 -:102F00002821039B13B1BAF1000F2CD1D8F810007F -:102F100040B1BAF1000F05D0009608AB5246691ACD -:102F2000FFF720FC38B2002FB8D066070AD00AABF2 -:102F300003EBD401624211F8083C02F0070213418E -:102F400001F8083C082C3CD9102C40F2B580202C0C -:102F500040F2B780BBF1000F00F09C80082334E002 -:102F6000BA460026C2E7049BE02B28BFE023069365 -:102F70000B44AB42059314D95A1B03980096924513 -:102F800034BF5246D2B2691A08AB04300792FFF739 -:102F9000E9FB079A1644AAEB020A1544F6B25FFA57 -:102FA0008AFA049B069A05999B1A0493039B1B6853 -:102FB0000393A6E70093D8F8080008AB3A462946E1 -:102FC000AEE7BBF1000F13D00123B4EBC30F6CD0FD -:102FD000082C12D89DF82030621E23FA02F2D50781 -:102FE00006D54FF0FF3202FA04F423438DF8203067 -:102FF0009DF8203089F8003051E7102C12D8BDF828 -:103000002030621E23FA02F2D10706D54FF0FF32BC -:1030100002FA04F42343ADF82030BDF82030A9F8BB -:1030200000303CE7202C0FD80899631E21FA03F3E7 -:10303000DA0705D54FF0FF3202FA04F40C43089486 -:10304000089BC9F800302AE7402C2BD0DDE9086541 -:10305000611EC4F12102A4F1210326FA01F105FA4F -:1030600002F225FA03F311431943CB0712D50122CB -:10307000A4F12003C4F1200102FA03F322FA01F1C2 -:10308000A240524243EA010363EB430332432B4322 -:10309000CDE90823DDE90823C9E90023FFE66FF045 -:1030A0000100FCE66FF00800F9E6082CA0D9102C0E -:1030B000B3D9202CEED8C3E7BBF1000FADD002236B -:1030C00083E7BBF1000FBBD004237EE730B5012AB4 -:1030D000144638BF0124402C85B028BF4024002569 -:1030E000012ACDE9025518D81B788DF808306307FE -:1030F0000AD004AB03EBD405624215F8083C02F099 -:103100000702934005F8083C00910346224600213F -:1031100002A8FFF727FB05B030BD082AE4D9102A22 -:1031200003D81B88ADF80830E1E7202A8DBFD3E92A -:1031300000231B680293CDE90223D8E710B5CB68C2 -:103140001BB98B600B618B8210BD04691A681C600F -:103150000361C38A013BC382CA60F0E703064CBF28 -:10316000C0F3C0300220704708B50246FFF7F6FFF3 -:10317000022806D15306C2F30F2001D100F003004C -:1031800008BDC2F30740FBE72DE9F04F93B0CDE94E -:1031900003230A6804461046FFF7E0FF022814BF25 -:1031A000C2F306260026002A0D46824680F2F281EE -:1031B00012F0C04940F0EE81097B002900F0EA815D -:1031C000022803D02378B34240F0E781C2F30463BE -:1031D0000693104602F07F030593FFF7C5FF059B9A -:1031E00029444FEA834848EA0A4848EA4668CE78C4 -:1031F00000230022CDE90823F309834648EA0008AA -:10320000029367D0059B009302466768534608A95E -:103210002046B847002800F0C381276A4FB94146CD -:1032200004F10C00FFF702FB074690B96FF00200B3 -:1032300054E03B6998450DD03F68002FF9D14146D5 -:1032400004F10C00FFF7F2FA07460028EED0236ADB -:103250003B60276297F817C006F01F08CCF3840C78 -:10326000ACEB08001FFA80FE0028B8BF0EF120006A -:10327000A8EB0C031FFA83FED7E90221B8BF00B206 -:10328000002B0793BEBF0EF120031BB2079352EA37 -:10329000010338D0039BDFF824E39A1A049B4FF014 -:1032A000000C63EB010196457CEB01032BD36B7B98 -:1032B00097F81AE0734519D1029B002B78D00128AA -:1032C00021DC7868F8B9DFF8F0C2944570EB0103AF -:1032D00016D337E0276A27B96FF00C0013B0BDE8AA -:1032E000F08F3B699845B5D03F68F4E7B24890420B -:1032F0007CEB010301D30020F0E7029B002BFAD006 -:10330000079B0F2B17DCFA7DB30002F0030203F0DA -:103310007C031343FB7539462046FFF707FB6B7BA5 -:10332000BB76029B3BB9FB7DC3F38402013262F39F -:103330008603FB75D0E76A7BBB7E9A42DBD1029B9A -:10334000002B35D0B309022B32D0039BBB60049B0A -:10335000FB60142200210DA8FDF7ECFF039B0A93EC -:10336000049B0B932B1D0C932B7BADF83EB0013BC4 -:10337000DBB2ADF83C30069B8DF84230059B8DF8F2 -:10338000433094F82C308DF840A083F001038DF881 -:1033900044308DF84180A3680AA920469847FB7DF8 -:1033A000C3F38403013303F01F039B02FB82A2E7F4 -:1033B000FB7DC6F34012B2EBD31F40F0F480C3F3A1 -:1033C0008403434540F0F280029A2B7BB609002A21 -:1033D0004DD0F2075DD4032B40F2EB80039BBB6022 -:1033E000049BFB602B7BAE1D033BDBB232463946B0 -:1033F00004F10C00FFF7ACFA00280CDA394620463D -:10340000FFF794FAFB7DC3F38403013303F01F033A -:103410009B02FB820AE7DDE90884AB883B834FF619 -:10342000FF73C9F12000A9F1200228FA09F104FA7A -:1034300000F0014324FA02F211431846C9B2FFF723 -:10344000C9F909F10809B9F1400F0346E9D1B88279 -:103450002A7B033AD2B23146FFF7CEF9FB7DB88220 -:10346000DA43C2F3C01262F3C713FB7543E786B9B0 -:103470002E1D013BDBB23246394604F10C00FFF74A -:1034800067FA0028BADB2A7BB88A013AD2B2314601 -:10349000E2E7F98AC1F30901013B0429DAB25BD8FA -:1034A000281D002307F11B069A4208D910F801CB0A -:1034B00006F801C0013101330529DBB2F4D10399CB -:1034C0000A9104990B91934207F11B010C9138BFAB -:1034D000043379680D9134BF55FA83F300230E93BA -:1034E000FB8AADF83EB0C3F309031A44069B8DF87E -:1034F0004230059B8DF8433094F82C30ADF83C20D9 -:1035000083F001038DF8443000238DF840A08DF83E -:1035100041807B602A7BB88A013A291DFFF76CF94C -:103520003B8BB882834203D1A3680AA920469847FF -:1035300020460AA9FFF702FEFB7DBA8AC3F3840383 -:10354000013303F01F039B02FB823B8B9A420CBFAB -:1035500000206FF01000C1E67B68002BAFD0052083 -:1035600001E01C3033461E68002EFAD1091A081DEE -:103570002E1D184401EB090CBCF11B0F5FFA89F3F7 -:103580009DD89A429BD916F8013B00F8013B09F1FE -:103590000109EFE76FF00900A0E66FF00A009DE671 -:1035A0006FF00B009AE66FF00D0097E66FF00E00DB -:1035B00094E66FF00F0091E640420F0080841E00F9 -:1035C000EFF3098305494A6B22F001024A6368332D -:1035D00083F30988002383F31188704700EF00E02C -:1035E000302080F3118862B60C4B0D4AD96821F463 -:1035F000E0610904090C0A43DA60D3F8FC200949A8 -:1036000042F08072C3F8FC200A6842F001020A60AE -:103610002022DA7783F82200704700BF00ED00E037 -:103620000003FA05001000E010B5302383F3118881 -:103630000E4B5B6813F4006314D0F1EE103AEFF315 -:103640000984683C4FF08073E361094BDB6B2366B0 -:1036500084F3098800F098F810B1064BA36110BDFF -:10366000054BFBE783F31188F9E700BF00ED00E0AD -:1036700000EF00E0030600080606000800F16043C2 -:1036800003F561430901C9B283F80013012200F078 -:103690001F039A4043099B0003F1604303F5614314 -:1036A000C3F880211A60704700F16040090100F5FD -:1036B0006D40C9B2017670470023037582680369C3 -:1036C0001B6899689142FBD25A680360426010609F -:1036D0005860704700230375826803691B68996806 -:1036E0009142FBD85A68036042601060586070478E -:1036F00008B50846302383F311880B7D032B05D0D2 -:10370000042B0DD02BB983F3118808BD8B690022DF -:103710001A604FF0FF338361FFF7CEFF0023F2E71B -:10372000D1E9003213605A60F3E70000FFF7C4BF2D -:10373000054BD9680875186802681A605360012241 -:103740000275D860FCF748BF2038002030B50C4B1C -:10375000DD684B1C87B004460FD02B46094A6846EB -:1037600000F0FEF82046FFF7E3FF009B13B1684628 -:1037700000F000F9A86907B030BDFFF7D9FFF9E7FD -:1037800020380020F1360008044B1A68DB68906886 -:103790009B68984294BF0020012070472038002089 -:1037A000084B10B51C68D86822681A605360012263 -:1037B0002275DC60FFF78EFF01462046BDE8104011 -:1037C000FCF70ABF20380020044B1A68DB689268B7 -:1037D0009B689A4201D9FFF7E3BF70472038002069 -:1037E00038B5074C07490848012300252370656058 -:1037F00000F00AFB0223237085F3118838BD00BF57 -:10380000483A00207C4A00082038002008B572B6EB -:10381000044B186500F0CEF900F092FA024B032237 -:103820001A70FEE720380020483A002000F0B4B8B3 -:10383000EFF3118020B9EFF30583302282F3118872 -:103840007047000010B530B9EFF30584C4F30804E5 -:1038500014B180F3118810BDFFF7B6FF84F311880F -:10386000F9E700008B60022308618B8208467047ED -:103870008368A3F1840243F8142C026943F8442CB2 -:10388000426943F8402C094A43F8242CC26843F8A3 -:10389000182C022203F80C2C002203F80B2C044AEB -:1038A00043F8102CA3F12000704700BFF105000879 -:1038B0002038002008B5FFF7DBFFBDE80840FFF720 -:1038C00035BF0000024BDB6898610F20FFF730BF67 -:1038D00020380020302383F31188FFF7F3BF000066 -:1038E00008B50146302383F311880820FFF72EFF27 -:1038F000002383F3118808BD064BDB6839B14268A9 -:1039000018605A60136043600420FFF71FBF4FF038 -:10391000FF307047203800200368984206D01A68AC -:103920000260506099611846FFF700BF70470000C1 -:1039300010B50A4C23699A6891420CD85A68816084 -:103940000360426010609A685860511A99604FF0A5 -:10395000FF33A36110BD1B68891AECE720380020F3 -:1039600010B4C0E9032300235DF8044B4361FFF763 -:10397000DFBF0000036881689A680A449A60426861 -:1039800013605A6000230360024B4FF0FF329A61CC -:10399000704700BF2038002070B5124DEB692A46F1 -:1039A0000133EB6152F8103F934206D09A68013A16 -:1039B0009A6030262C69A36803B170BDD4E9002158 -:1039C0000A605160236083F31188D4E903312046F3 -:1039D000984786F3118861690029EBD02046FFF7EC -:1039E000A7FFE7E72038002000207047FEE700002F -:1039F000704700004FF0FF3070470000BFF34F8F5B -:103A0000024AD368DB07FCD4704700BF00200240A5 -:103A100008B5074B1B7853B9FFF7F0FF054B1A6940 -:103A2000120641BF044A5A6002F188325A6008BD4A -:103A3000603A0020002002402301674508B5054B8D -:103A40001B7833B9FFF7DAFF034A136943F08003A9 -:103A5000136108BD603A0020002002407F289ABF11 -:103A600000F58030C0020020704700004FF4006075 -:103A700070470000802070477F2808B50BD8FFF7FB -:103A8000EDFF00F500630268013204D10430834287 -:103A9000F9D1012008BD0020FCE700007F2810B507 -:103AA00004461CD8FFF7AAFFFFF7B2FF0D4BF32225 -:103AB000DA6002221A61FFF7D1FF58611A6942F0F9 -:103AC00040021A614FF40061FFF798FF00F034F9EB -:103AD000FFF7B4FF2046BDE81040FFF7CDBF002040 -:103AE00010BD00BF002002402DE9F84312F0010391 -:103AF000144606D01F4B40F2F3221A600020BDE8A6 -:103B0000F88385181C4A954204D91A4A4FF43E712D -:103B10001160F3E7FFF77CFFFFF770FFDFF86880C5 -:103B2000451A4FF00109012C05EB01060F4603D899 -:103B3000FFF784FF0120E2E73B88C8F8109033804C -:103B40000020FFF75BFFC8F81000338831F8022B24 -:103B50009BB29A420CD0074B40F20F321A60074BCF -:103B60001E60074B1C60074B1F60FFF767FFC6E72F -:103B7000023CD8E75C3A002000000408503A0020DC -:103B8000583A0020543A002000200240084908B565 -:103B90000B7828B11BB9FFF73BFF01230B7008BD61 -:103BA000002BFCD0BDE808400870FFF747BF00BFFE -:103BB000603A002008B54FF420414FF0005000F06B -:103BC000BDF8BDE808404FF400514FF0805000F0C0 -:103BD000B5B800000846114600F05EBE012000F0B6 -:103BE0005BBE0000084600F075BE000030B583B033 -:103BF000FFF71EFE0E4B0F4DDB692A684FF47A71FA -:103C000001FB03F3934237BF0B4A0B495168146819 -:103C10002B602EBFD1E90041013151601C1941F1E7 -:103C200000010191FFF70EFE0199204603B030BD5F -:103C300020380020643A0020683A002030B583B074 -:103C4000FFF7F6FD114B124DDB692A684FF47A71CC -:103C500001FB03F3934237BF0E4A0E4951681468C3 -:103C60002B602EBFD1E90041013151601C1941F197 -:103C700000010191FFF7E6FD01994FF47A720023EC -:103C80002046FCF795FA03B030BD00BF2038002075 -:103C9000643A0020683A002010B50244064BD2B2C4 -:103CA000904200D110BD441C00B253F8200041F8EE -:103CB000040BE0B2F4E700BF502800400F4B30B5D2 -:103CC0001C6A240407D41C6A44F440741C621C6AF5 -:103CD00044F400441C620A4C236843F4807323605C -:103CE0000244084BD2B2904200D130BD441C00B215 -:103CF00051F8045B43F82050E0B2F4E700100240B2 -:103D0000007000405028004007B5012201A90020A2 -:103D1000FFF7C2FF019803B05DF804FB13B504463A -:103D2000FFF7F2FFA04205D0012201A90020019473 -:103D3000FFF7C4FF02B010BD7047000070470000DD -:103D400070470000074B45F255521A6002225A6034 -:103D500040F6FF729A604CF6CC421A60024B012288 -:103D60001A70704700300040743A0020034B1B78F3 -:103D70001BB1034B4AF6AA221A607047743A00201E -:103D800000300040044B1A682AB902F1804202F563 -:103D90000432526A1A607047703A0020024B4FF0AA -:103DA00080725A62704700BF0010024008B5FFF7EA -:103DB000E9FF024B1868C0F3407008BD703A00205C -:103DC00070470000FEE700000A4B0B480B4A904288 -:103DD0000BD30B4BDA1C121AC11E22F003028B42CA -:103DE00038BF00220021FDF7A5BA53F8041B40F8A4 -:103DF000041BECE7EC4B0008583C0020583C00202A -:103E0000583C0020FEE7000070B51B4B0163002505 -:103E1000044686B0586085620E46FFF7E1FB04F168 -:103E20001003C4E904334FF0FF33A361134BE56182 -:103E3000D969A5600A462B46C4E9082304F1340178 -:103E4000C4E900440E4AE562256580232046FFF759 -:103E500009FD0123E0600B4A03750092726801922C -:103E6000B268CDE90223084B6846CDE90435FFF777 -:103E700021FD06B070BD00BF483A00202038002068 -:103E8000884A00088D4A0008053E00084B684360D8 -:103E90008B688360CB68C3600B6943614B690362C5 -:103EA0008B6943620B6803607047000008B51B4BC9 -:103EB0009A6A42F4FC029A629A6A22F4FC029A62BA -:103EC0009A6A5A6942F4FC025A61154A5B691146C2 -:103ED0004FF09040FFF7DAFF02F11C0100F580601F -:103EE000FFF7D4FF02F1380100F58060FFF7CEFF45 -:103EF00002F1540100F58060FFF7C8FF02F1700184 -:103F000000F58060FFF7C2FF02F18C0100F58060D0 -:103F1000FFF7BCFFBDE8084000F05AB800100240AF -:103F2000944A000808B500F093F9FFF759FCBDE882 -:103F30000840FFF727BF00007047000010B5214C74 -:103F4000A36A63F4FC03A362A36A03F4FC03A36201 -:103F50004FF0FF32A36A23692261236900232361A2 -:103F60002169E168E260E268E360E268E2691649BB -:103F700042F08052E261E2690A6842F480720A60AB -:103F8000226A02F44072B2F5407F1EBF4FF48032C5 -:103F900022622362236A1B0407D4236A43F440731A -:103FA0002362236A43F40043236200F031F9A369DA -:103FB000064A43F00103A361A369136843F0200399 -:103FC000136010BD0010024000700040000001406E -:103FD0001E4B1A6842F001021A601A689007FCD55D -:103FE0005A6822F003025A605A6812F00C02FBD1A0 -:103FF000196801F0F90119605A601A6842F48032B8 -:104000001A601A689103FCD5114A5A604FF40452A1 -:10401000DA6230221A631A6842F080721A601A68F3 -:104020009201FCD50B4912220A600A6802F00702CD -:10403000022AFAD15A6842F002025A605A6802F023 -:104040000C02082AFAD11A6B1A637047001002405A -:1040500000241D0000200240084A08B55169136879 -:104060000B4003F00103536123B1054A13680BB100 -:1040700050689847BDE80840FFF7D6BA00040140F1 -:10408000783A0020084A08B5516913680B4003F0DC -:104090000203536123B1054A93680BB1D068984776 -:1040A000BDE80840FFF7C0BA00040140783A00209C -:1040B000084A08B5516913680B4003F004035361C3 -:1040C00023B1054A13690BB150699847BDE8084010 -:1040D000FFF7AABA00040140783A0020084A08B560 -:1040E000516913680B4003F00803536123B1054A7B -:1040F00093690BB1D0699847BDE80840FFF794BABF -:1041000000040140783A0020084A08B55169136854 -:104110000B4003F01003536123B1054A136A0BB13E -:10412000506A9847BDE80840FFF77EBA0004014096 -:10413000783A0020174B10B55A691C68144004F4F3 -:1041400078725A61A30604D5134A936A0BB1D06AF8 -:104150009847600604D5104A136B0BB1506B984713 -:10416000210604D50C4A936B0BB1D06B9847E2053E -:1041700004D5094A136C0BB1506C9847A30504D5BC -:10418000054A936C0BB1D06C9847BDE81040FFF71F -:104190004BBA00BF00040140783A00201A4B10B51A -:1041A0005A691C68144004F47C425A61620504D5C3 -:1041B000164A136D0BB1506D9847230504D5134A69 -:1041C000936D0BB1D06D9847E00404D50F4A136E80 -:1041D0000BB1506E9847A10404D50C4A936E0BB1F5 -:1041E000D06E9847620404D5084A136F0BB1506F24 -:1041F0009847230404D5054A936F0BB1D06F9847B5 -:10420000BDE81040FFF710BA00040140783A0020E2 -:10421000062108B50846FFF731FA06210720FFF707 -:104220002DFA06210820FFF729FA06210920FFF7B9 -:1042300025FA06210A20FFF721FA06211720FFF7A9 -:104240001DFABDE8084006212820FFF717BA000034 -:1042500008B5FFF773FE00F067F800F03DF8FFF7D0 -:104260006BFEBDE8084000F05DB8000002684368DE -:104270001143016003B1184770470000143000F08B -:104280002FBA00004FF0FF33143000F029BA0000BD -:10429000383000F0A5BA00004FF0FF33383000F09E -:1042A0009FBA0000143000F0F5B900004FF0FF3164 -:1042B000143000F0EFB90000383000F04FBA0000C1 -:1042C0004FF0FF32383000F049BA0000012914BF26 -:1042D0006FF013000020704700F06CB8044B0360CF -:1042E0000023C0E90233436001230374704700BF19 -:1042F0003C4B000838B5C36904460D461BB9042180 -:104300000844FFF7B3FF294604F1140000F0A6F9B2 -:10431000002806DA201D4FF40061BDE83840FFF7A1 -:10432000A5BF38BD00F00EB80023054A1946013379 -:10433000102BC2E9001102F10802F8D1704700BF4A -:10434000783A00204FF0E023044A5A6100229A6133 -:1043500007221A6108210B20FFF7A6B93F190100B7 -:1043600008B5302383F31188FFF760FA002383F345 -:10437000118808BD08B5FFF7F3FFBDE80840FFF757 -:1043800053B90000026843681143016003B1184744 -:1043900070470000024A136843F0C003136070477F -:1043A00000380140024A136843F0C00313607047AD -:1043B0000044004037B51D4C1D4D2046FFF78EFFD1 -:1043C000009404F114001B490023202200F038F966 -:1043D0002022009404F13800174B184900F0B2F97C -:1043E000174BC4E91735174C0C212520FFF746F968 -:1043F0002046FFF773FF04F11400134900940023D3 -:10440000202200F01DF904F13800104B10490094EF -:10441000202200F097F90F4B0C212620C4E9173514 -:1044200003B0BDE83040FFF729B900BFF83A0020DB -:1044300000512502D03B002095430008103C00208D -:1044400000380140643B0020F03B0020A5430008F9 -:10445000303C0020004400402DE9F047C66D37682D -:10446000F46934622107054619D014F0080118BF19 -:104470004FF48071E20748BF41F02001A30748BF15 -:1044800041F04001600748BF41F08001302383F3D1 -:104490001188281DFFF776FF002383F31188E205BA -:1044A0000AD5302383F311884FF48061281DFFF76C -:1044B00069FF002383F311884FF030094FF0000AA1 -:1044C00014F0200838D13B0616D54FF0300905F11D -:1044D000380A200610D589F31188504600F066F995 -:1044E000002836DA0821281DFFF74CFF27F080034B -:1044F0003360002383F31188790614D5620612D540 -:10450000302383F31188D5E913239A4208D12B6C09 -:1045100033B11021281D27F04007FFF733FF376024 -:10452000002383F31188E30619D5AA6E1369B3B18A -:10453000BDE8F0475069184789F31188B38C95F8A6 -:10454000641028461940FFF7D5FE8AF31188F469F4 -:10455000B6E780B2308588F31188F469B9E7BDE821 -:10456000F087000008B50348FFF776FFBDE8084074 -:10457000FFF75AB8F83A002008B50348FFF76CFF78 -:10458000BDE80840FFF750B8643B0020F8B5154679 -:1045900082680669AA420B46816938BF8568761A27 -:1045A000B54204460BD218462A46FCF7B1FEA36971 -:1045B0002B44A361A3685B1BA3602846F8BD0CD9FC -:1045C00018463246FCF7A4FEAF1BE1683A46304479 -:1045D000FCF79EFEE3683B44EBE718462A46FCF7EF -:1045E00097FEE368E5E7000083689342F7B5154658 -:1045F000044638BF8568D0E90460361AB5420BD24C -:104600002A46FCF785FE63692B446361A36828464C -:104610005B1BA36003B0F0BD0DD932460191FCF7DE -:1046200077FE0199E068AF1B3A463144FCF770FE13 -:10463000E3683B44E9E72A46FCF76AFEE368E4E7FF -:1046400010B50A440024C361029B8460C0E90000E5 -:10465000C0E90511C1600261036210BD08B5D0E96F -:104660000532934201D1826882B982680132826048 -:104670005A1C42611970D0E904329A4224BFC368BF -:1046800043610021FFF748F9002008BD4FF0FF30DB -:10469000FBE7000070B5302304460E4683F3118813 -:1046A000A568A5B1A368A269013BA360531CA361DF -:1046B00015782269934224BFE368A361E3690BB1D3 -:1046C00020469847002383F31188284607E03146A7 -:1046D0002046FFF711F90028E2DA85F3118870BD52 -:1046E0002DE9F74F04460E4617469846D0F81C9021 -:1046F0004FF0300A8AF311884FF0000B154665B170 -:104700002A4631462046FFF741FF034660B941463D -:104710002046FFF7F1F80028F1D0002383F3118839 -:10472000781B03B0BDE8F08FB9F1000F03D0019002 -:104730002046C847019B8BF31188ED1A1E448AF36B -:104740001188DCE7C0E90511C160C3611144009B19 -:104750008260C0E90000016103627047F8B5044659 -:104760000D461646302383F31188A768A7B1A368C6 -:10477000013BA36063695A1C62611D70D4E9043275 -:104780009A4224BFE3686361E3690BB1204698470E -:10479000002080F3118807E031462046FFF7ACF88F -:1047A0000028E2DA87F31188F8BD0000D0E905237C -:1047B0009A4210B501D182687AB98268013282606A -:1047C0005A1C82611C7803699A4224BFC3688361C2 -:1047D0000021FFF7A1F8204610BD4FF0FF30FBE7A6 -:1047E0002DE9F74F04460E4617469846D0F81C9020 -:1047F0004FF0300A8AF311884FF0000B154665B16F -:104800002A4631462046FFF7EFFE034660B941468F -:104810002046FFF771F80028F1D0002383F31188B8 -:10482000781B03B0BDE8F08FB9F1000F03D0019001 -:104830002046C847019B8BF31188ED1A1E448AF36A -:104840001188DCE70B460146184600F02DB8000041 -:1048500000F040B8012838BF012010B504462046BA -:1048600000F030F830B900F007F808B900F00CF8A3 -:104870008047F4E710BD0000024B1868BFF35B8F60 -:10488000704700BF503C002008B5062000F084F8B7 -:104890000120FFF7ABF80000024B0A4601461868FA -:1048A000FFF798B91811002010B5054C13462CB12C -:1048B0000A4601460220AFF3008010BD2046FCE707 -:1048C00000000000024B01461868FFF787B900BFDF -:1048D00018110020024B01461868FFF783B900BF8A -:1048E0001811002010B501390244904201D1002076 -:1048F00005E0037811F8014FA34201D0181B10BD49 -:104900000130F2E72DE9F041A3B1C91A177801444B -:10491000044603F1FF3C8C42204601D9002009E007 -:104920000578BD4204F10104F5D10CEB0405D6185D -:10493000A54201D1BDE8F08115F8018D16F801ED11 -:10494000F045F5D0E7E700001F2938B504460D46CD -:1049500004D9162303604FF0FF3038BD426C12B10A -:1049600052F821304BB9204600F030F82A46014673 -:104970002046BDE8384000F017B8012B0AD0591C7A -:1049800003D1162303600120E7E7002442F8254005 -:10499000284698470020E0E7024B01461868FFF7D9 -:1049A000D3BF00BF1811002038B5074D00230446BF -:1049B000084611462B60FFF71DF8431C02D12B68F7 -:1049C00003B1236038BD00BF543C0020FFF70CB892 -:1049D000034611F8012B03F8012B002AF9D1704787 -:1049E0006F72672E6172647570696C6F742E6633B6 -:1049F00030332D4D313030373000000040A2E4F12B -:104A0000646891060041A3E5F26569920700000021 -:104A10004261642043414E496661636520696E646A -:104A200065782E00800000000080000000008000FB -:104A30000000000000000000351B000819230008DA -:104A400079220008451B0008791B0008751D000825 -:104A5000491B0008591B00084D1B0008551B000886 -:104A6000511B00089D1C00085D1B0008E52500087F -:104A70006D1B0008711C000863300000784A0008B4 -:104A800078380020483A00206D61696E0069646CD6 -:104A900065000000A001A82A00000000FAAABEAA32 -:104AA00050001424EFFF0000007700007097090009 -:104AB0000100000000000000AAAAAAAA010000004C -:104AC000FFFF0000000000000000000000000000E8 -:104AD00000000000AAAAAAAA00000000FFFF000030 -:104AE00000000000000000000000000000000000C6 -:104AF000AAAAAAAA00000000FFFF00000000000010 -:104B0000000000000000000000000000AAAAAAAAFD -:104B100000000000FFFF0000000000000000000097 -:104B20000000000000000000AAAAAAAA00000000DD -:104B3000FFFF000000000000000000000000000077 -:104B40009942000885420008C1420008AD420008B1 -:104B5000B9420008A5420008914200087D420008C1 -:104B6000CD4200087CB6FF7F01000000000000007D -:104B7000EC030000000000000098030000000000AB -:104B8000FE2A0100D20400001C11002000000000D9 -:104B90000000000000000000000000000000000015 -:104BA0000000000000000000000000000000000005 -:104BB00000000000000000000000000000000000F5 -:104BC00000000000000000000000000000000000E5 -:104BD00000000000000000000000000000000000D5 -:0C4BE000000000000000000000000000C9 +:1000000000090020B1010008E52200089D22000837 +:10001000C52200089D220008BD220008B301000887 +:10002000B3010008B3010008B3010008D932000889 +:10003000B3010008B3010008B3010008A94000089B +:10004000B3010008B3010008B3010008B3010008C0 +:10005000B3010008B30100088D3D0008B93D000858 +:10006000E53D0008113E00083D3E0008B3010008D0 +:10007000B3010008B3010008B3010008B301000890 +:10008000B3010008B3010008B301000851220008C1 +:100090007D2200088D220008B3010008693E000897 +:1000A000B3010008B3010008B3010008B301000860 +:1000B000B3010008B3010008B3010008B301000850 +:1000C000B3010008B3010008B3010008B301000840 +:1000D000B301000899420008AD420008B3010008CE +:1000E000D13E0008B3010008B3010008B3010008C5 +:1000F000B3010008B3010008B3010008B301000810 +:10010000B3010008B3010008B3010008B3010008FF +:10011000B3010008B3010008B3010008B3010008EF +:10012000B3010008B3010008B3010008B3010008DF +:10013000B3010008B3010008B3010008B3010008CF +:10014000B3010008B3010008B3010008B3010008BF +:10015000B3010008B3010008B3010008B3010008AF +:10016000B3010008B3010008B3010008B30100089F +:10017000B3010008B3010008B3010008B30100088F +:10018000B3010008B3010008B3010008B30100087F +:10019000B3010008B3010008B3010008B30100086F +:1001A000190F00080000000000000000000000001F +:1001B00002E000F000F8FEE772B6374880F30888E6 +:1001C000364880F3098836483649086040F2000016 +:1001D000CCF200004EF63471CEF200010860BFF39D +:1001E0004F8FBFF36F8F40F20000C0F2F0004EF669 +:1001F0008851CEF200010860BFF34F8FBFF36F8FBD +:100200004FF00000E1EE100A4EF63C71CEF2000114 +:100210000860062080F31488BFF36F8F03F06AFC38 +:1002200003F0DEFC4FF055301F491B4A91423CBFA2 +:1002300041F8040BFAE71D49184A91423CBF41F8C6 +:10024000040BFAE71A491B4A1B4B9A423EBF51F86E +:10025000040B42F8040BF8E700201849184A9142B1 +:100260003CBF41F8040BFAE703F048FC03F0F4FC50 +:10027000144C154DAC4203DA54F8041B8847F9E7D7 +:1002800000F042F8114C124DAC4203DA54F8041B52 +:100290008847F9E703F030BC000900200011002076 +:1002A0000000000808ED00E0000100200009002027 +:1002B00098480008001100207C11002080110020C7 +:1002C000543C0020A0010008A4010008A40100087B +:1002D000A40100082DE9F04F2DED108AC1F80CD0D3 +:1002E000C3689D46BDEC108ABDE8F08F002383F300 +:1002F00011882846A047002003F052F9FEE703F0DA +:10030000DBF800DFFEE70000F8B500F017FE03F0B1 +:1003100095FB074603F0E4FB064600283ED12B4B35 +:100320009F423BD001339F423BD0294B27F0FF0235 +:100330009A4239D1F8B200F03DFC354642F21074D1 +:1003400000F03EFC08B10024254601F0ADF878B37A +:10035000032000F043F80024254636B11D4B9F4290 +:1003600003D003F0B5FB00242546002003F070FB0A +:10037000194B1B6913F040031FD00DB100F044F876 +:1003800000F050FC01F0B6FF0546C4B101F0B2FF29 +:10039000401BA04213D900F037F8F3E7354600249C +:1003A000CEE704460125CBE705464FF47A74C7E74C +:1003B000B4F57A7F08BF0125CFE71C46E0E700F0DF +:1003C00079FC012003F0F2F8DFE700BF010007B07D +:1003D000000008B0263A09B000040048084B187025 +:1003E00003280CD8DFE800F008050208022000F01E +:1003F00001BE022000F0F6BD024B00225A60704799 +:10040000801100208411002038B501F04DF830B182 +:100410001F4B03221A701F4B00225A6038BD1E4B1F +:100420001E4A19680131F9D004339342F9D11C4CAA +:10043000194DD4F80428AA42F0D31A4B9B6803F153 +:10044000006303F5D0439A42E8D203F015FB03F0B2 +:1004500027FB002000F08CFD0220FFF7BFFF124BAE +:10046000DA690022DA61D96999699A619B6972B681 +:100470004FF0E0233021C3F8085DD4F80038D4F8F9 +:10048000042881F311889D4683F308881047C5E747 +:1004900080110020841100200068000820680008F6 +:1004A000006000080011002000100240094A136893 +:1004B00049F2690099B21B0C00FB01331360064B33 +:1004C000186844F2506182B2000C01FB020018600F +:1004D00080B27047141100201011002010B50021C7 +:1004E0001022044600F0A0FD034B03CB20606160A6 +:1004F0001868A06010BD00BFACF7FF1F2DE9F041E8 +:10050000ADF54E7D0DF134086CAC40F27512074626 +:100510000D460EA80021C8F8001000F085FD4FF42C +:10052000C4720021204600F07FFD01F0E3FE254B60 +:100530004FF47A72B0FBF2F0186093E807000223E0 +:1005400084E807000DF5E9702382FFF7C7FF4EF638 +:1005500003431D49238406A804F0D4F8192384F822 +:1005600032310DF2E32206AB0DF1300C1E4603CE04 +:10057000664510605160334602F10802F6D13378C7 +:10058000137041460122204600F09AFD0023039398 +:10059000AB7E029305F11903019380B20123CDE9EB +:1005A00004800093E97E05A3D3E90023384602F0D6 +:1005B00069FA0DF54E7DBDE8F08100BF9E6AC42149 +:1005C000818A46EE8C110020144700082DE9F04185 +:1005D0002C4C237ADAB080460D465BBB27A928460F +:1005E00000F07EFE0746002842D19DF89D60C82E8F +:1005F0003ED801464FF4A662204600F015FD4FF4A8 +:100600008073C4F8F8314FF40073C4F80C334FF41E +:100610004073C4F8203432460DF19E0104F1090004 +:1006200000F0F0FC26449DF89C30777223720BB9E1 +:10063000EB7E23728122002106AC27A800F0F4FC97 +:100640000122214627A800F087FE00230393AB7EFA +:10065000029305F1190380B201932823CDE90440E8 +:100660000093E97E05A3D3E90023404602F00AFA8D +:100670005AB0BDE8F08100BFAFF30080264172722E +:10068000DF25D7B7B0320020F0B5254E4FF48A757C +:1006900005FB0065F1B096F8D83085F8DC30002411 +:1006A000D822214685F8E8403AA800F0BDFC06F1C2 +:1006B000090000F0B1FCD5F8E4308DF8F000C2B2CA +:1006C00006AF06F109010DF1F100CDE93A3400F071 +:1006D00099FC394601223AA800F06AFE80B2CDE9C1 +:1006E000047008230127CDE9023706F1D8030193EE +:1006F00030230093317A0B4807A3D3E9002302F09B +:10070000C1F9A04206DD01F0F5FDC5F8E00038466C +:1007100071B0F0BD2046FBE778F6339F93CACD8DCC +:10072000B0320020A42100202DE9F0411D4D1E4EC5 +:100730001E4F86B0284602F0D1F9034658B3002474 +:10074000CDE90344ADF81440027B8DF8142099687C +:100750004068029403AA03C21B68DFF8548043F088 +:100760000043029301F0C8FD821941F10003009497 +:1007700002A9384601F072F8A04205DD284602F0D1 +:10078000B1F988F80040D5E798F80030072B05D874 +:10079000013388F8003006B0BDE8F081014802F06E +:1007A000A1F9F8E7A421002040420F00D821002041 +:1007B000E537002070B50D4614461E4602F0BEF81F +:1007C00050B9022E10D1012C0ED112A3D3E900236F +:1007D000C5E90023012007E0282C10D005D8012C02 +:1007E00009D0052C0FD0002070BD302CFBD10BA3FD +:1007F000D3E90023ECE70BA3D3E90023E8E70BA33D +:10080000D3E90023E4E70BA3D3E90023E0E700BF2B +:10081000AFF30080401DA12026812A0B78F6339F7C +:1008200093CACD8D9E6AC421818A46EE264172729A +:10083000DF25D7B7F017304A39059E5638B505463B +:100840000E4C0021013500F0B5FBA4F82C55B4F88E +:100850002C0500F097FB78B1B4F82C0500F0A2FB52 +:10086000014648B9B4F82C0500F0A4FBB4F82C35C7 +:100870000133A4F82C35EAE738BD00BFB0320020C0 +:1008800010B50A4B0A4A1A6003F5805393F86020AA +:100890003AB9DC6D2CB1204600F080FE204603F012 +:1008A00071FEBDE81040034800F078BED82100205A +:1008B0006C470008203200202DE9F04F8FB000AFC8 +:1008C00005460C4602F03AF8002849D1237E022B57 +:1008D0001BD1E38A012B18D101F00CFD0646FFF76E +:1008E000E5FD03464FF4C870DFF8C482B3FBF0F2B5 +:1008F00006F5167602FB103316FA83F3C8F80030BB +:10090000E37E33B9A34B00221A703C37BD46BDE8E5 +:10091000F08F07F12401204600F0A0FC0028F4D15C +:1009200007F11400FFF7DAFD97F8264007F11401EC +:10093000224607F1270003F06FFE0028E2D10F2CBA +:1009400008D8944B1C70D8F80030A3F51673C8F87B +:100950000030DAE797F82410284601F0E7FFD4E7E3 +:10096000E38A282B2BD010D8012B23D0052BCCD1F8 +:10097000BFF34F8F8849894BCA6802F4E062134382 +:10098000CB60BFF34F8F00BFFDE7302BBDD1844E4E +:10099000E17E327A9142B8D1607E3146002291F8F0 +:1009A000DC50854200F0A5800132042A01F58A71ED +:1009B000F5D1AAE721462846FFF7A0FDA5E7214685 +:1009C0002846FFF703FEA0E7B2F8EC507B6005F184 +:1009D00003094FEA99094FEA8902D11DC908A8EB1A +:1009E000C1039D46EB460021584600F01DFB04F173 +:1009F000EE012A463144584600F004FB7B6813B9E7 +:100A0000012000F0B5FA96F8D20000F0BBFA0446D7 +:100A100030B9307200F0D6FA204600F0A9FAB1E001 +:100A2000D6F8D4203AB996F8D200B6F82C258242EE +:100A300001D8FFF703FFD6F8D4202A44944208D205 +:100A400096F8D200B6F82C250130824201D8FFF783 +:100A5000F5FE70685FFA89F2594600F0EDFA08B9C0 +:100A6000C54679E0726896F8D2002A447260D6F8DA +:100A7000D42005EB0209C6F8D49000F083FA814532 +:100A800009D396F8D220D6F8D4000132001B86F89C +:100A9000D220C6F8D400FF2D0FD80024347200F005 +:100AA00091FA204600F064FA00F0FEFC3D4B1881FC +:100AB00008B9FFF7A9FCC54627E7BB6896F8D90037 +:100AC0000AFB0362FB68D2F8E41082F8E83001F513 +:100AD0008061C2F8E030C2F8E410FFF7D5FDFFF7FF +:100AE00023FE96F8D920013202F0030286F8D920BD +:100AF000B6E74FF48A7A0AFB02F505F1EA013144C0 +:100B0000204600F081FCF86000287FF4FEAE3544FA +:100B1000012285F8E82001F0EDFBD5F8E020D6EDC4 +:100B2000007ADFED216A801A192838BF192040F6B3 +:100B3000B832904228BF1046B8EE677A07EE900AA6 +:100B4000F8EEE77A67EEA67ADFED186AE7EE267A26 +:100B5000FCEEE77AC6ED007A96F8D930BB60BA6849 +:100B600073680AFB02F4321992F8E81059B1D2F80E +:100B7000E4108B42E8463FF427AF002182F8E810EA +:100B8000C2F8E010C5467368064A9B0A0133138118 +:100B9000BBE600BF9D21002000ED00E00400FA0547 +:100BA000B03200208C110020CDCCCC3D6666663F73 +:100BB000A0210020014B1870704700BF9811002041 +:100BC00038B54FF00054134B22689A4220D1124B93 +:100BD000627D12481A70237D03724FF48073C0F84F +:100BE000F8314FF40073C0F80C3300254FF4407314 +:100BF000C0F820340A49C0F8E450C922093000F096 +:100C000001FAE0222946204600F00EFA012038BD04 +:100C10000020FCE79AAD44C598110020B0320020B6 +:100C20001600002037B500F03FFC194D1949288106 +:100C30000223012218486B7101F0F8F90023019397 +:100C4000164B174900931748174B4FF4805201F089 +:100C500045FE164B197811B1124801F067FE01F0FC +:100C600049FB0446FFF722FC4FF4C873B0FBF3F2D4 +:100C700002FB130304F5167010FA83F00C4B186096 +:100C800002F02EFF08B10F232B8103B030BD00BF4F +:100C90008C11002040420F00D8210020B507000829 +:100CA0009C110020A4210020B90800089811002000 +:100CB000A02100202DE9F04F2DED028B8EA7D7E962 +:100CC00000670FF23C29D9E90089864C95B00DAD3B +:100CD0009FED828BFFF728FDDFF82CB200230C93E9 +:100CE000ADF83C300D936B6000230DF125028DEDC6 +:100CF000008B4FF0010A09A958468DF825308DF870 +:100D000024A001F041F99DF824200023002A40F09E +:100D1000AB80204601F012FE0546002847D1DFF8DF +:100D2000ECB101F0E7FADBF8003098423FD301F074 +:100D3000E1FA0790FFF7BAFB079A4FF4C873B0FBCC +:100D4000F3F101FB130302F5167010FA83F0CBF8F0 +:100D50000000DFF8BCB19BF800100791002914BF18 +:100D60002B46534610A88DF83030FFF7B7FB079994 +:100D7000C1F11002D2B2062A10AB28BF06221944D4 +:100D80000DF13100079200F03DF9079A0CAB039387 +:100D9000182302930132544BD2B2CDE900A304923E +:100DA0003B463246204601F00FFE8BF8005001F022 +:100DB000A1FA4E4A4E4D1368C31AB3F57A7F32D367 +:100DC000106001F099FA02460B46204601F094FEAD +:100DD000204601F0B3FD30B32B7ADFF838A1002BA9 +:100DE00014BF032302238AF8053001F083FA0DF1C2 +:100DF000400B4FF47A730122B0FBF3F05946CAF866 +:100E00000000504600F002FA18230293394B019378 +:100E100080B240F25513CDE903B0009342464B46F1 +:100E2000204601F0D1FD2B7ACBB101F063FA4FF0EF +:100E3000000A83464FF48A7295F8D900504400F0B6 +:100E4000030002FB005393F8E81089B30AF1010A8A +:100E5000BAF1040FF0D12B7A002B7FF438AF15B024 +:100E6000BDEC028BBDE8F08F4FF0904110A84A69AD +:100E700082F010024A611946102200F0D5F80DF1F7 +:100E800026030AAA0CA9584600F0E8FD95E80300DD +:100E900011AB83E803009DF83C308DF84C300C9B7F +:100EA000109310A9DDE90A23204601F0F9FF1BE7A2 +:100EB000D3F8E01049B12B68FA2B38BFFA23ABEB1B +:100EC00001010533B1EB430FC0D3FFF7DDFB4FF456 +:100ED0008A720028BAD1BEE7AFF30080000000009C +:100EE00000000000A42100209C210020E037002009 +:100EF000B0320020E4370020401DA12026812A0BBB +:100F0000F1C6A7C1D068080FD8210020A021002079 +:100F10009D2100208C11002008B5054800F03AFE04 +:100F2000BDE80840034A0449002003F025BB00BF88 +:100F3000D8210020203800208108000870B502F078 +:100F40000DFC094E094D3080002428683388834207 +:100F500008D902F0FFFB2B6804440133B4F5D04FED +:100F60002B60F2D370BD00BF14380020E83700209A +:100F700002F080BC00F10060920000F5D04002F069 +:100F800027BC0000054B1A68054B1B889B1A83423F +:100F900002D9104402F0DEBB00207047E837002081 +:100FA00014380020024B1B68184402F0D9BB00BF64 +:100FB000E8370020024B1B68184402F0E3BB00BF77 +:100FC000E8370020064991F8243033B10023086A3D +:100FD00081F824300822FFF7CDBF0120704700BF01 +:100FE000EC370020022802BF4FF0904310229A6194 +:100FF00070470000022802BF4FF090434FF4801268 +:101000009A61704710B50023934203D0CC5CC4545E +:101010000133F9E710BD000003460246D01A12F969 +:10102000011B0029FAD1704702440346934202D0C3 +:1010300003F8011BFAE770472DE9F8431F4D1446EA +:1010400095F824200746884652BBDFF870909CB381 +:1010500095F824302BB92022FF2148462F62FFF754 +:10106000E3FF95F82400C0F10802A24228BF2246FF +:10107000D6B24146920005EB8000FFF7C3FF95F81A +:101080002430A41B1E44F6B2082E17449044E4B248 +:1010900085F82460DBD1FFF795FF0028D7D108E061 +:1010A0002B6A03EB82038342CFD0FFF78BFF00282C +:1010B000CBD10020BDE8F8830120FBE7EC3700200E +:1010C0002DE9F0470D46044600219046284640F29F +:1010D0007912FFF7A9FF234620220021284601F0BC +:1010E00081FE231D02222021284601F07BFE631D84 +:1010F00003222221284601F075FEA31D032225218B +:10110000284601F06FFE04F108031022282128462A +:1011100001F068FE04F1100308223821284601F08E +:1011200061FE04F1110308224021284601F05AFE15 +:1011300004F1120308224821284601F053FE04F16D +:10114000140320225021284601F04CFE04F118031C +:1011500040227021284601F045FE04F120030822B8 +:10116000B021284601F03EFE04F121030822B821F7 +:10117000284601F037FE04F12207C0263B463146DF +:1011800008222846083601F02DFEB6F5A07F07F1AB +:101190000107F3D104F1320308223146284601F059 +:1011A00021FE002704F1330A94F832304FEAC709D0 +:1011B0009F4209F5A47615D3B8F1000F08D1314646 +:1011C00004F599730722284601F00CFE09F24F1628 +:1011D000274694F832213B1B93420CD3F01DC008E4 +:1011E000BDE8F0870AEB070308223146284601F0E4 +:1011F000F9FD0137D8E707F23313314608222846B4 +:1012000001F0F0FD08360137E3E7000013B50446AE +:101210000846002101602346C0F8031020220190F7 +:1012200001F0E0FD0198231D0222202101F0DAFDEA +:101230000198631D0322222101F0D4FD0198A31D12 +:101240000322252101F0CEFD019804F108031022AC +:10125000282101F0C7FD072002B010BDF7B500231B +:10126000047F00910E4607221946054601F07EFCD8 +:10127000731C0093012200230721284601F076FC0D +:10128000C4B9B31C0093052223460821284601F067 +:101290006DFC0D243746B278BB1B934211D32B7FD4 +:1012A000A88A0734E408BBB9844294BF0020012017 +:1012B00003B0F0BDAB8ADB00083BDB08B370082449 +:1012C000E8E7FB1C0093214600230822284601F092 +:1012D0004DFC08340137DEE7201A18BF0120E7E78C +:1012E000F7B50023047F00910E46082219460546F3 +:1012F00001F03CFC731CC4B908220093114623463C +:10130000284601F033FC1024012372785F1C013B56 +:10131000934211D32B7FA88A0734E408BBB98442D7 +:1013200094BF0020012003B0F0BDAB8ADB00083B76 +:10133000DB0873700824E7E7F319009321460023C4 +:101340000822284601F012FC08343B46DDE7201A4B +:1013500018BF0120E7E70000F8B50E460546144621 +:10136000002181223046FFF75FFE2B460822002134 +:10137000304601F037FD7CB96B1C0722082130464E +:1013800001F030FD0F2401236A785F1C013B93427A +:1013900004D3E01DC008F8BD0824F4E7EB1921468A +:1013A0000822304601F01EFD08343B46ECE7000001 +:1013B000F8B50E46054614460021CE223046FFF70A +:1013C00033FE2B4628220021304601F00BFD7CB96C +:1013D00005F1080308222821304601F003FD3024DE +:1013E0002F462A7A7B1B934204D3E01DC008F8BD28 +:1013F0002824F5E707F1090321460822304601F0C9 +:10140000F1FC08340137ECE7F7B5047F00910E4694 +:10141000012310220021054601F0A8FBC4B9B31C2A +:101420000093092223461021284601F09FFB19242E +:1014300037467288BB1B9A4211D82B7FA88A073483 +:10144000E408BBB9844294BF0020012003B0F0BD82 +:10145000AB8ADB00103BDB0873801024E8E73B1D00 +:101460000093214600230822284601F07FFB083420 +:101470000137DEE7201A18BF0120E7E730B5094D34 +:101480000A4491420DD011F8013B5840082340F323 +:101490000004013B2C4013F0FF0384EA5000F6D116 +:1014A000EFE730BD2083B8EDF7B5364A10685168D4 +:1014B0006B4603C36A4634493448082303F0BCF83A +:1014C000044690BB0A25324A106851686B4603C334 +:1014D0006A4630492D48082303F0AEF80446002838 +:1014E00047D00369B3F5663F43D8B0F86620B2F53C +:1014F0007B7F3ED1284A024402F15C018B4238D303 +:101500005C3B224900209E1AFFF7B8FF324607468F +:1015100004F164010020FFF7B1FFA3689F4228D1C6 +:10152000E368984208BF002523E00369B3F5663FEE +:1015300026D8428BB2F57B7F20D1174A024402F1B4 +:1015400010018B4218D3103B104900209D1AFFF761 +:1015500095FF2A46064604F118010020FFF78EFF8A +:10156000A3689E4202D1E368984201D00D25AAE704 +:101570000025284603B0F0BD1025A4E70C25A2E7FE +:101580000B25A0E730470008DC970300006800083F +:1015900039470008909703000898FFF710B5037CBF +:1015A000044613B9006803F02FF8204610BD000070 +:1015B0000023BFF35B8FC360BFF35B8FBFF35B8F11 +:1015C0008360BFF35B8F7047BFF35B8F0068BFF32F +:1015D0005B8F704770B505460C30FFF7F5FF05F1DE +:1015E000080604463046FFF7EFFFA04206D9304612 +:1015F0006D68FFF7E9FF2544281A70BD3046FFF7F4 +:10160000E3FF201AF9E7000070B50546406898B17D +:1016100005F10800FFF7D8FF05F10C060446304637 +:10162000FFF7D2FF8442304694BF6D680025FFF774 +:10163000CBFF013C2C44201A70BD000038B50C468D +:101640000546FFF7C7FFA04210D305F10800FFF7DA +:10165000BBFF04446868B4FBF0F100FB1144BFF326 +:101660005B8F0120AC60BFF35B8F38BD0020FCE7CF +:101670002DE9F041144607460D46FFF7C5FF8442A9 +:1016800028BF0446D4B1B84658F80C6B4046FFF763 +:101690009BFF3044286040467E68FFF795FF331A71 +:1016A0009C4203D86C600120BDE8F0816B60A41BF4 +:1016B0003B68AB602044E8600220F5E72046F3E792 +:1016C00038B50C460546FFF79FFFA04210D305F141 +:1016D0000C00FFF779FF04446868B4FBF0F100FBED +:1016E0001144BFF35B8F0120EC60BFF35B8F38BD0B +:1016F0000020FCE72DE9FF41884669460746FFF7D1 +:10170000B7FF6C4606B204EBC6060025B44209D00A +:101710006268206808EB0501FFF774FC6368083411 +:101720001D44F3E729463846FFF7CAFF284604B0B0 +:10173000BDE8F081F8B505460C300F46FFF744FFD1 +:1017400005F1080604463046FFF73EFFA04230464A +:1017500088BF6C68FFF738FF201A386020B1304628 +:101760002C68FFF731FF2044F8BD000073B5144624 +:1017700006460D46FFF72EFF844228BF044601901F +:10178000DCB101A93046FFF7D5FF019B33B93268C0 +:10179000C5E90233C5E9002401200CE09C4238BFB2 +:1017A00001942860019868608442F5D93368AB6081 +:1017B000241AEC60022002B070BD2046FBE7000056 +:1017C0002DE9FF410F466946FFF7D0FF6C4600B296 +:1017D00004EBC0050026AC4209D0D4F8048054F8CC +:1017E000081BB8194246FFF70DFC4644F3E73046A4 +:1017F00004B0BDE8F081000038B50546FFF7E0FF12 +:10180000044601462846FFF719FF204638BD000070 +:1018100010B4026854681A4623465DF8044B184712 +:10182000002070470020704770470000002070477C +:101830000E20704700F5805090F8C800C0F34000BB +:101840007047000000F5805090F9D000704700000C +:1018500000F58050C0F8CC1001207047F7B50C6837 +:10186000BDF8207014F0005470D10D7B082D6DD898 +:10187000302585F311884569AE6876010CD4AC68D3 +:10188000240108D4AC6814F080545DD184F311882D +:10189000204603B0F0BD01240E6804F1180C002EA0 +:1018A000B8BFF6004FEA0C1CB4BF46F0040676053C +:1018B00045F80C600E680FFA84FC16F0804F18BFD4 +:1018C00005EB0C1E05EB0C1C1EBFDEF8806146F01C +:1018D0000206CEF880610E7BCCF8846105EB04151E +:1018E0008E68C5F88C614E68C5F88861DCF8805157 +:1018F00045F00105CCF8805100EB441641F2680533 +:101900002E4405EB44150544C6E9002308350E4670 +:1019100001F10C0C56F804EB45F804EB6645F9D1DF +:10192000843436882E8000EB441407F003052679B2 +:1019300026F00B0635432571002484F311880097A7 +:1019400000F0FAFC0120A4E70224A5E74FF0FF30E5 +:101950009FE7000013B500F580540191E06DFFF79B +:1019600053FE1F280AD90199E06D2022FFF7C2FE1D +:10197000A0F120035842584102B010BD0020FBE7FF +:1019800008B5302383F3118800F58050C06DFFF750 +:101990000FFE002383F3118808BD000000220260BF +:1019A000828142608260704710B500220023C0E946 +:1019B00000230023044603810C30FFF7EFFF20468D +:1019C00010BD0000F0B5054600F580500C4690F8BB +:1019D000C83013F0040FC3F3800108BF114661F350 +:1019E000820304F1840680F8C83005EB461389B001 +:1019F0001B79D8072ED57AB319072DD46846FFF77F +:101A0000D3FF05EB441303F5835303F1180703AA2F +:101A1000103318685968144603C40833BB42224681 +:101A2000F7D1186820609B88A380DDE90E23CDE9FB +:101A300000230123ADF808302B686946DB6B28468C +:101A4000984705EB46152B791A075CBF43F008034E +:101A50002B7101E0002AF4D109B0F0BD2DE9F04767 +:101A60009A4688B0074688469146302383F311880A +:101A700007F580546846FFF797FFE06DFFF7AAFD72 +:101A80001F282AD9E06D20226946FFF7B5FE2028DD +:101A900023D103AD444605AB2E4603CE9E422060C3 +:101AA0006160354604F10804F6D130682060B388DF +:101AB000A380DDE90023C9E90023BDF80830AAF8B6 +:101AC0000030002383F3118853464A464146384686 +:101AD00008B0BDE8F04700F01DBC002080F311887D +:101AE00008B0BDE8F08700002DE9F84F0023C0E9F9 +:101AF0000133254B044640F8183B0F46FFF74EFFD5 +:101B000004F12800FFF750FF04F1480804F582555E +:101B10004646083530462036FFF746FFAE42F9D13B +:101B200004F580554FF480534FF00009C5E913398F +:101B3000C5F848800123EE6504F5875804F58456FE +:101B4000C5F8549085F8583085F86030083608F1AB +:101B500008084FF0000A4FF0000B46E908ABA6F169 +:101B60001800FFF71BFF203646F8289C4645F4D1A5 +:101B700085F8D07017B1054800F0B6FB044B6361DF +:101B80002046BDE8F88F00BF6C47000844470008B6 +:101B90000064004010B5044B197804464A1C1A70C2 +:101BA000FFF7A2FF204610BD1C3800202DE9F047AA +:101BB000002950D0294B2A4FB7FBF1F599428CBF31 +:101BC0000A231123581EB5FBF3FC03FB1C53C4B2BC +:101BD0002BB102280346F5D80020BDE8F0870CF1B0 +:101BE000FF36B6F5806FF7D2C4EBC40E0EF10303D7 +:101BF0004FEAE309C3F3C703A4EB030809F1010AA1 +:101C00004FF47A755FFA88F009FB05555AFA88F89F +:101C1000B5FBF8F5B5F5617FC1BF0EF1FF33C3F336 +:101C2000C703E01AC0B25C1C50FA84F40CFB04F445 +:101C3000B7FBF4F4A142CFD1013BDBB20F2BCBD8E1 +:101C40000138C0B20728C7D80021107116809170E2 +:101C5000D3700120C1E70846BFE700BF3F420F0035 +:101C60000051250270B505460E464FF47A746B6933 +:101C70005B6803F00103B3424FF0010004D001F0B0 +:101C800095FC013CF3D1204670BD000030B542699F +:101C9000936913F0700F16D000230B4C936103F17E +:101CA000840200EB421211794D0709D5890707D547 +:101CB000416954F823508D60117941F0040111718C +:101CC0000133032BEBD130BD5847000873B51D46D7 +:101CD000436916469A68D207044609D59A680121D5 +:101CE0009960C2F34002CDE900650021FFF76AFE6A +:101CF00063699A68D1050BD59A684FF48071996031 +:101D0000C2F34022CDE9006501212046FFF75AFECB +:101D100063699A68D2030BD59A684FF48031996051 +:101D2000C2F34042CDE9006502212046FFF74AFE9A +:101D300004F58053D3F8CC0010B103681B699847B1 +:101D4000204602B0BDE87040FFF7A0BFF8B50446DA +:101D50004669002972D106F10C073868800770D0F7 +:101D600006EB01153868D5F8B00110F0040FD5F86E +:101D7000B0011ABFC00840F00040400DA061D5F886 +:101D8000B0C11CF0020F1CBF40F08040A061D5F82C +:101D9000B40106EB011100F00F0084F82400D1F823 +:101DA000B8012077D1F8B801000A6077D1F8B801FE +:101DB000000CA077D1F8B801000EE077D1F8BC0193 +:101DC00084F82000D1F8BC01000A84F82100D1F881 +:101DD000BC01000C84F82200D1F8BC11090E84F873 +:101DE00023103821396004F1340004F1180104F1A2 +:101DF000240551F8046B40F8046BA942F9D1098815 +:101E00000180C4E90A2321460023238651F8283B98 +:101E10002046DB6B984704F5805393F8C820D3F82D +:101E2000CC0042F0040283F8C82010B103681B699B +:101E300098472046BDE8F840FFF728BF06F1100795 +:101E40008BE7F8BD10B5044600F056FA02460B4683 +:101E500052EA030102D0013A63F100030449086821 +:101E600020B12146BDE81040FFF770BF10BD00BF94 +:101E700018380020F0B5302181F31188DFF848C010 +:101E800000F583510831002404F1840500EB451569 +:101E90002E7977070ED4F6060CD5D1E90076974255 +:101EA0009E4107D246695CF82470B7602E7946F0EF +:101EB00004062E710134032C01F12001E4D100232A +:101EC00083F31188F0BD00BF5847000808B53023E0 +:101ED00083F31188FFF7DAFE002383F3118808BD2E +:101EE000F8B543690546986800F0E050B0F1E05F4E +:101EF0000F4621D0F8B1302383F3118805F58354C0 +:101F00001034002606F1840305EB43131B791A07EE +:101F100006D50136032E04F12004F3D1012007E099 +:101F20005B07F6D42146384600F040FA0028F0D18D +:101F3000002383F31188F8BD0120FCE708B53023A6 +:101F400083F3118800F58050C06DFFF743FB002339 +:101F500083F3118843090CBF0120002008BD000055 +:101F6000F8B51D46002313700F4606461446FFF7CA +:101F7000E5FF80F00100387025B129463046FFF7B3 +:101F8000AFFF2070F8BD00002DE9B8410C461546A2 +:101F90001F46804600F0B0F90B462178024609B989 +:101FA000287850B14046FFF765FFFFF78FFF3B46AB +:101FB0002A462146FFF7D4FF0120BDE8B881000082 +:101FC00070B5302686F31188174BDA6942F000723B +:101FD000DA611A6942F000721A611A6922F000721D +:101FE0001A61002383F3118800F5805494F8C830F7 +:101FF00013F0010516D1A9B186F31188032113202E +:1020000001F0C8F90321142001F0C4F903211520BF +:1020100001F0C0F994F8C83043F0010384F8C830E7 +:1020200085F3118870BD00BF001002402DE9F04714 +:1020300000F5805588B095F8D030012B04468846CD +:10204000164600F28180814F57F823200AB947F8DD +:102050002300D7F800A0C4F80C802674BAF1000F52 +:1020600064D095F8D030012B70D001212046FFF7C5 +:10207000A7FF302383F311886269136823F00203FA +:1020800013606269136843F00103136063690027FA +:102090005F6187F3118801212046FFF7E3FD0028E7 +:1020A00000F09580E86DFFF783FA04F58359BA468E +:1020B00009F10809202200216846FEF7B5FF02A8B1 +:1020C000FFF76CFCCDF818A06A4609EB07030DF189 +:1020D000180E9446BCE80300F44518605960624647 +:1020E00003F10803F5D1DCF80000186020379CF8F4 +:1020F00004201A71602FDDD195F8C8306FF3820388 +:10210000002785F8C8306A4641462046ADF8007081 +:10211000ADF802708DF80470FFF748FD636948BBA5 +:102120004FF400421A6008B0BDE8F08741F2D800D1 +:1021300002F02AFA814610B15146FFF7D5FCC7F8E4 +:102140000090B9F1000F8CD10020ECE738680368EB +:102150001B6B98470146002887D13868FFF730FF8E +:102160003868036832465B684146984700287FF428 +:102170007CAFE9E761221A609DF802309DF80320E8 +:102180001B06120402F4702203F040731343BDF8DF +:102190000020C2F3090213439DF804201205022E09 +:1021A00002F4E0020CBF4FF00041002113436269CA +:1021B0000B43D361636913225A616269136823F088 +:1021C0000103136039462046FFF74CFD08B96369E7 +:1021D000A6E795F8D03093BB6169D1F8002242F0B0 +:1021E0000102C1F800226169D1F8002222F47C5278 +:1021F00022F00E02C1F800226169D1F8002242F4F7 +:102200006062C1F800226269C2F814326269C2F8E1 +:102210000432626941F6FF71C2F80C126269C2F8B9 +:1022200040326269C2F8443263690122C3F81C2259 +:102230006269D2F8003223F00103C2F8003295F847 +:10224000C83043F0020385F8C8306CE71838002026 +:1022500008B500F051F850EA0103024602D0421ED0 +:1022600061F10001044B186810B10B46FFF72EFD19 +:10227000BDE8084001F064B81838002008B5002017 +:10228000FFF7E0FDBDE8084001F05AB808B50120AD +:10229000FFF7D8FDBDE8084001F052B800B59BB08B +:1022A000EFF3098168226846FEF7ACFEEFF3058381 +:1022B000014B9B6BFEE700BF00ED00E008B5FFF7A8 +:1022C000EDFF000000B59BB0EFF30981682268467E +:1022D000FEF798FEEFF30583014B5B6BFEE700BF53 +:1022E00000ED00E0FEE700000FB408B5029801F031 +:1022F0000DF9FEE701F040BB01F0ECBA13B56C46F6 +:1023000084E80600031D94E8030083E8050001202B +:1023100002B010BD73B58568019155B11B885B078C +:1023200007D4D0E900369B6B9847019AC1B230467A +:10233000A847012002B070BDF0B5866889B0054697 +:102340000C465EB1BDF838305B070AD4D0E90037DF +:102350009B6B98472246C1B23846B047012009B06E +:10236000F0BD00220023CDE900230023ADF80830A2 +:102370000A4603AB01F10806106851681C4603C405 +:102380000832B2422346F7D1106820609288A280BA +:10239000FFF7B2FF0423ADF808302B68CDE9000148 +:1023A000DB6B694628469847D8E7000030B50368DC +:1023B0000968DD0FB5EBD17F23F0604421F0604266 +:1023C0004FEAD1700BD0002BB8BFA40C0029B8BFC6 +:1023D000920C944202D034BF0120002030BD9442C0 +:1023E00005D1C1F38070C3F380738342F6D1944268 +:1023F0002CBF00200120F1E72DE9F041456A15B915 +:102400004162BDE8F0814B6823F06047C3F38A4620 +:102410004FEAD37EC3F3807816EA230638BF3E46E0 +:10242000AC462B465A68BEEBD27F22F060440AD0FD +:10243000002A18DAA40CB44217D19D420FD10D60C6 +:10244000DEE71346EEE7A74207D102F08044C2F36D +:10245000807242450BD054B1EFE708D2EDE7CCF8DB +:1024600000100B60CDE7B44201D0B442E5D81A6841 +:102470009C46002AE5D11960C3E700002DE9F0472A +:10248000089D01F007044FEAD508224405F007052E +:1024900000EBD1004FF47F49944201D1BDE8F087B1 +:1024A00004F0070705F0070A57453E4638BF564671 +:1024B000C6F10806111B8E4228BF0E46E10808EB44 +:1024C000D50E415C13F80EC0B94029FA06F721FA7F +:1024D0000AF1FFB28CEA010147FA0AF739408CEAA7 +:1024E000010C03F80EC034443544D5E780EA0120DE +:1024F000082341F2210201B24000002980B203F119 +:10250000FF33B8BF504013F0FF03F4D17047000011 +:1025100038B50C468D18A54200D138BD14F8011B02 +:10252000FFF7E4FFF7E7000042684AB11368436031 +:102530004389818901339BB29942438138BF8381AA +:102540001046704770B588B0202204460D46684694 +:102550000021FEF769FD20460495FFF7E5FF0246DE +:1025600058B16B46054608AE1C4603CCB442286001 +:102570006960234605F10805F6D1104608B070BD24 +:10258000082817D909280CD00A280CD00B280CD001 +:102590000C280CD00D280CD00E2814BF4020302061 +:1025A00070470C2070471020704714207047182087 +:1025B0007047202070470000082817D90C280CD934 +:1025C00010280CD914280CD918280CD920280CD97B +:1025D00030288CBF0F200E207047092070470A203A +:1025E00070470B2070470C2070470D20704700008B +:1025F0002DE9F843078C072F04461ED9D0E902982D +:1026000000254FF6FF73C5F12006A5F1200029FA39 +:1026100005F108FA06F628FA00F031430143C9B281 +:102620001846FFF763FF0835402D0346EBD1E169FB +:102630003A46BDE8F843FFF76BBF4FF6FF70BDE8C1 +:10264000F883000010B54B6823B9CA8A63F3090206 +:10265000CA8210BD04691A681C600361C38A013B09 +:10266000C3824A60EFE700002DE9F84F1D46CB8A90 +:102670000F46C3F309010529814692460B4630D027 +:102680000020AAB207F11A049EB2042E1FFA80F8A5 +:102690000FD8904503F1010306D3FB8A0A4462F385 +:1026A0000903FB8201201AE01AF80060E6540130A9 +:1026B000EAE79045F1D2A1F1050B1C237C68BBFB36 +:1026C000F3F203FB12BB1FFA8BF6002C45D14846F0 +:1026D000FFF72AFF044638B978606FF00200BDE8C2 +:1026E000F88F4FF00008E6E7002606607860ADB28C +:1026F0004FF0000B454510D90AEB0803221D13F8D3 +:10270000011B9155B1B208F101081B291FFA88F885 +:102710002BD0454506F10106F1D8FB8AC3F3090227 +:10272000154465F30903BCE7013292B21C462368E5 +:10273000002BF9D16B1F0B441C21B3FBF1F30133C8 +:102740009BB29A42D3D2BBF1000FD0D14846FFF7DB +:10275000EBFE20B9C4F800B0BFE70122E7E7C0F8FC +:1027600000B05E4620600446C1E74545D5D94846DD +:10277000FFF7DAFE08B92060AFE7C0F800B0002626 +:1027800020600446B6E700002DE9F04F2DED028BE6 +:102790001C4683B05B69019207468846002B00F017 +:1027A0009A80238C2BB1E269002A00F09480072BD9 +:1027B00035D807F10C00FFF7B7FE054638B96FF0C2 +:1027C0000205284603B0BDEC028BBDE8F08F142251 +:1027D0000021FEF729FC228CE16905F10800FEF7D3 +:1027E00011FC208C013080B2FFF7E6FEFFF7C8FE37 +:1027F000013880B22084013028746369228C1B78F0 +:102800002A4403F01F0363F03F0348F000411372B2 +:10281000384669602946FFF7EFFD0125D1E700F151 +:102820000C034FF0000908EE103A4FF0800A4E46B4 +:102830004D4618EE100AFFF777FE83460028BED0FB +:1028400014220021FEF7F0FB002E3AD1019BABF8D9 +:10285000083002220BF1080E1FFA82FC0CF1010075 +:10286000BCF1060F218C80B201D88E422BD3FFF72A +:10287000A3FEFFF785FE62691278013802F01F029D +:102880008E4208BF4FF0400A42EA49121BFA80F11B +:102890004AEA020A013048F0004281F808A08BF8A9 +:1028A0001000CBF8042059463846FFF7A5FD238CCD +:1028B0000135B3422DB289F001094FF0000AB8D1B9 +:1028C0007FE70022C6E7E169895D0EF80210013654 +:1028D000B6B20132C0E76FF0010572E7F8B51546F0 +:1028E0000E463022002104461F46FEF79DFB069B44 +:1028F0006360B5F5001F079BA76034BF6A094FF6F8 +:10290000FF72A36297B2E66104F1100000239A42BD +:1029100006D800230360A782E3822383E360F8BD27 +:102920000660013330462036F1E7000003781BB91A +:102930004BB2002BC8BF0170704700000078704791 +:10294000F8B50C46C969074611B9238C002B37D15D +:10295000257E1F2D34D8387828BB228C072A2CD806 +:10296000268A36F003032BD14FF6FF70FFF7D0FD18 +:1029700020F001003102400441EA0561400C41EAC7 +:1029800040254FF6FF72234629463846FFF7FCFEE6 +:10299000002807DD626913780133DBB21F2B88BF83 +:1029A00000231370F8BD218A2D0645EA0125054351 +:1029B0002046FFF71DFE0246E5E76FF00300F1E752 +:1029C0006FF00100EEE7000070B58AB004461646CD +:1029D0000021282268461D46FEF726FBBDF8383048 +:1029E000ADF810300F9B05939DF840308DF81830EE +:1029F000119B07936946BDF84830ADF8203020465A +:102A0000CDE90265FFF79CFF0AB070BD2DE9F041EA +:102A1000D36905460C4616460BB9138C5BBB377E53 +:102A20001F2F28D895F80080B8F1000F26D0304627 +:102A3000FFF7DEFD3378210241EAC33141EA0801A4 +:102A4000338A41EA076141EA03410246334641F0D5 +:102A500080012846FFF798FE00280ADD3378012B15 +:102A600007D1726913780133DBB21F2B88BF0023B3 +:102A70001370BDE8F0816FF00100FAE76FF003001A +:102A8000F7E70000F0B58BB004460D46174600216D +:102A9000282268461E46FEF7C7FA9DF84C305A1E9B +:102AA000534253418DF800309DF84030ADF810305E +:102AB000119B05939DF848308DF81830149B0793AF +:102AC0006A46BDF85430ADF8203029462046CDE99D +:102AD0000276FFF79BFF0BB0F0BD0000406A00B12B +:102AE00004307047436A1A68426202691A600361DF +:102AF000C38A013BC38270472DE9F041D0F82080A2 +:102B0000194E14461D464146002709B9BDE8F0811B +:102B1000D1E90223A21A65EB0303964277EB030384 +:102B20001ED2036A8B420DD1FFF78CFD036A1B682E +:102B3000036203690B60C38A0161016A013BC382BE +:102B40008846E2E7FFF77EFD0B68C8F800300369AE +:102B50000B60C38A0161013BC382D8F80010D4E73F +:102B600088460968D1E700BF80841E002DE9F04F38 +:102B70008BB00D46DDF8509014469B4680460028E9 +:102B800000F01981B9F1000F00F01581531E3F2BA1 +:102B900000F21181012A03D1BBF1000F40F00B813B +:102BA0000023CDE90833B8F81430B5EBC30F4FEA72 +:102BB000C30703D300200BB0BDE8F08F2B199F4251 +:102BC000D8F80C303ABF7F1BFFB227461BB9D8F8A4 +:102BD0001030002B7AD0272D4ED8C5F12806B742E9 +:102BE0004FF000032CBFF6B23E4600932946D8F8BA +:102BF000080008AB3246FFF741FCA7EB060A354454 +:102C00005FFA8AFAB8F8143003F10053053BDB0091 +:102C10000493D8F80C3003932821039B13B1BAF125 +:102C2000000F2CD1D8F8100040B1BAF1000F05D038 +:102C3000009608AB5246691AFFF720FC38B2002F05 +:102C4000B8D066070AD00AAB03EBD401624211F890 +:102C5000083C02F00702134101F8083C082C3CD95B +:102C6000102C40F2B580202C40F2B780BBF1000F51 +:102C700000F09C80082334E0BA460026C2E7049B9B +:102C8000E02B28BFE02306930B44AB42059314D9F5 +:102C90005A1B03980096924534BF5246D2B2691A25 +:102CA00008AB04300792FFF7E9FB079A1644AAEB3A +:102CB000020A1544F6B25FFA8AFA049B069A05994D +:102CC0009B1A0493039B1B680393A6E70093D8F811 +:102CD000080008AB3A462946AEE7BBF1000F13D017 +:102CE0000123B4EBC30F6CD0082C12D89DF8203010 +:102CF000621E23FA02F2D50706D54FF0FF3202FA20 +:102D000004F423438DF820309DF8203089F80030FA +:102D100051E7102C12D8BDF82030621E23FA02F2BF +:102D2000D10706D54FF0FF3202FA04F42343ADF881 +:102D30002030BDF82030A9F800303CE7202C0FD817 +:102D40000899631E21FA03F3DA0705D54FF0FF3225 +:102D500002FA04F40C430894089BC9F800302AE7EF +:102D6000402C2BD0DDE90865611EC4F12102A4F1DD +:102D7000210326FA01F105FA02F225FA03F31143C1 +:102D80001943CB0712D50122A4F12003C4F120017D +:102D900002FA03F322FA01F1A240524243EA01038C +:102DA00063EB430332432B43CDE90823DDE90823DA +:102DB000C9E90023FFE66FF00100FCE66FF00800B0 +:102DC000F9E6082CA0D9102CB3D9202CEED8C3E7F3 +:102DD000BBF1000FADD0022383E7BBF1000FBBD0E6 +:102DE00004237EE730B5012A144638BF0124402C65 +:102DF00085B028BF40240025012ACDE9025518D806 +:102E00001B788DF8083063070AD004AB03EBD405B8 +:102E1000624215F8083C02F00702934005F8083CAE +:102E2000009103462246002102A8FFF727FB05B0C8 +:102E300030BD082AE4D9102A03D81B88ADF8083021 +:102E4000E1E7202A8DBFD3E900231B680293CDE977 +:102E50000223D8E710B5CB681BB98B600B618B825E +:102E600010BD04691A681C600361C38A013BC382F8 +:102E7000CA60F0E703064CBFC0F3C03002207047C1 +:102E800008B50246FFF7F6FF022806D15306C2F343 +:102E90000F2001D100F0030008BDC2F30740FBE79B +:102EA0002DE9F04F93B0CDE903230A68044610469C +:102EB000FFF7E0FF022814BFC2F306260026002A0F +:102EC0000D46824680F2F28112F0C04940F0EE8158 +:102ED000097B002900F0EA81022803D02378B3425D +:102EE00040F0E781C2F304630693104602F07F03CB +:102EF0000593FFF7C5FF059B29444FEA834848EA3D +:102F00000A4848EA4668CE7800230022CDE9082323 +:102F1000F309834648EA0008029367D0059B0093B3 +:102F200002466768534608A92046B847002800F0C3 +:102F3000C381276A4FB9414604F10C00FFF702FB39 +:102F4000074690B96FF0020054E03B6998450DD0F8 +:102F50003F68002FF9D1414604F10C00FFF7F2FA67 +:102F600007460028EED0236A3B60276297F817C017 +:102F700006F01F08CCF3840CACEB08001FFA80FEAF +:102F80000028B8BF0EF12000A8EB0C031FFA83FE47 +:102F9000D7E90221B8BF00B2002B0793BEBF0EF1E4 +:102FA00020031BB2079352EA010338D0039BDFF8DA +:102FB00024E39A1A049B4FF0000C63EB0101964541 +:102FC0007CEB01032BD36B7B97F81AE0734519D187 +:102FD000029B002B78D0012821DC7868F8B9DFF853 +:102FE000F0C2944570EB010316D337E0276A27B986 +:102FF0006FF00C0013B0BDE8F08F3B699845B5D079 +:103000003F68F4E7B24890427CEB010301D3002013 +:10301000F0E7029B002BFAD0079B0F2B17DCFA7D01 +:10302000B30002F0030203F07C031343FB7539463F +:103030002046FFF707FB6B7BBB76029B3BB9FB7D12 +:10304000C3F38402013262F38603FB75D0E76A7B27 +:10305000BB7E9A42DBD1029B002B35D0B309022BF9 +:1030600032D0039BBB60049BFB60142200210DA89F +:10307000FDF7DAFF039B0A93049B0B932B1D0C9324 +:103080002B7BADF83EB0013BDBB2ADF83C30069B8C +:103090008DF84230059B8DF8433094F82C308DF834 +:1030A00040A083F001038DF844308DF84180A3687F +:1030B0000AA920469847FB7DC3F38403013303F03C +:1030C0001F039B02FB82A2E7FB7DC6F34012B2EB1B +:1030D000D31F40F0F480C3F38403434540F0F280F3 +:1030E000029A2B7BB609002A4DD0F2075DD4032B40 +:1030F00040F2EB80039BBB60049BFB602B7BAE1D0F +:10310000033BDBB23246394604F10C00FFF7ACFA60 +:1031100000280CDA39462046FFF794FAFB7DC3F30A +:103120008403013303F01F039B02FB820AE7DDE9FE +:103130000884AB883B834FF6FF73C9F12000A9F1E7 +:10314000200228FA09F104FA00F0014324FA02F2FD +:1031500011431846C9B2FFF7C9F909F10809B9F1D5 +:10316000400F0346E9D1B8822A7B033AD2B23146F6 +:10317000FFF7CEF9FB7DB882DA43C2F3C01262F3E7 +:10318000C713FB7543E786B92E1D013BDBB2324600 +:10319000394604F10C00FFF767FA0028BADB2A7BF6 +:1031A000B88A013AD2B23146E2E7F98AC1F309019D +:1031B000013B0429DAB25BD8281D002307F11B0666 +:1031C0009A4208D910F801CB06F801C00131013349 +:1031D0000529DBB2F4D103990A9104990B9193422A +:1031E00007F11B010C9138BF043379680D9134BF8E +:1031F00055FA83F300230E93FB8AADF83EB0C3F378 +:1032000009031A44069B8DF84230059B8DF8433024 +:1032100094F82C30ADF83C2083F001038DF8443055 +:1032200000238DF840A08DF841807B602A7BB88A0E +:10323000013A291DFFF76CF93B8BB882834203D119 +:10324000A3680AA92046984720460AA9FFF702FE6C +:10325000FB7DBA8AC3F38403013303F01F039B028F +:10326000FB823B8B9A420CBF00206FF01000C1E63E +:103270007B68002BAFD0052001E01C3033461E6870 +:10328000002EFAD1091A081D2E1D184401EB090C55 +:10329000BCF11B0F5FFA89F39DD89A429BD916F8AF +:1032A000013B00F8013B09F10109EFE76FF009006C +:1032B000A0E66FF00A009DE66FF00B009AE66FF053 +:1032C0000D0097E66FF00E0094E66FF00F0091E6A8 +:1032D00040420F0080841E00EFF3098305494A6BCA +:1032E00022F001024A63683383F30988002383F3E1 +:1032F0001188704700EF00E0302080F3118862B63B +:103300000C4B0D4AD96821F4E0610904090C0A4309 +:10331000DA60D3F8FC20094942F08072C3F8FC203F +:103320000A6842F001020A602022DA7783F822005C +:10333000704700BF00ED00E00003FA05001000E058 +:1033400010B5302383F311880E4B5B6813F40063D0 +:1033500014D0F1EE103AEFF30984683C4FF080731B +:10336000E361094BDB6B236684F3098800F098F86E +:1033700010B1064BA36110BD054BFBE783F3118829 +:10338000F9E700BF00ED00E000EF00E0FF020008F9 +:103390000203000800F1604303F561430901C9B26B +:1033A00083F80013012200F01F039A4043099B0099 +:1033B00003F1604303F56143C3F880211A6070474D +:1033C00000F16040090100F56D40C9B20176704717 +:1033D00000230375826803691B6899689142FBD2D8 +:1033E0005A6803604260106058607047002303759C +:1033F000826803691B6899689142FBD85A68036028 +:10340000426010605860704708B50846302383F367 +:1034100011880B7D032B05D0042B0DD02BB983F322 +:10342000118808BD8B6900221A604FF0FF33836159 +:10343000FFF7CEFF0023F2E7D1E9003213605A60B4 +:10344000F3E70000FFF7C4BF054BD968087518689B +:1034500002681A60536001220275D860FCF73ABF17 +:103460002838002030B50C4BDD684B1C87B0044673 +:103470000FD02B46094A684600F0D8F82046FFF7DF +:10348000E3FF009B13B1684600F0DAF8A86907B0C3 +:1034900030BDFFF7D9FFF9E72838002009340008CC +:1034A000044B1A68DB6890689B68984294BF0020C0 +:1034B0000120704728380020084B10B51C68D868D8 +:1034C00022681A60536001222275DC60FFF78EFFCC +:1034D00001462046BDE81040FCF7FCBE283800201D +:1034E00038B5074C0749084801230025237065605B +:1034F00000F024FB0223237085F3118838BD00BF40 +:10350000503A0020B04700082838002008B572B6AD +:10351000044B186500F0C2F900F0ACFA024B03222C +:103520001A70FEE728380020503A002000F09AB8C0 +:103530008B60022308618B82084670478368A3F181 +:10354000840243F8142C026943F8442C426943F87E +:10355000402C094A43F8242CC26843F8182C022254 +:1035600003F80C2C002203F80B2C044A43F8102C0F +:10357000A3F12000704700BFED02000828380020AA +:1035800008B5FFF7DBFFBDE80840FFF75BBF0000B1 +:10359000024BDB6898610F20FFF756BF28380020E8 +:1035A000302383F31188FFF7F3BF000008B501460D +:1035B000302383F311880820FFF754FF002383F39F +:1035C000118808BD064BDB6839B1426818605A6043 +:1035D000136043600420FFF745BF4FF0FF30704792 +:1035E000283800200368984206D01A6802605060AC +:1035F00099611846FFF726BF7047000010B50A4CC6 +:1036000023699A6891420CD85A68816003604260CD +:1036100010609A685860511A99604FF0FF33A361A7 +:1036200010BD1B68891AECE72838002010B4C0E9E7 +:10363000032300235DF8044B4361FFF7DFBF000065 +:10364000036881689A680A449A60426813605A6005 +:1036500000230360024B4FF0FF329A61704700BFB6 +:103660002838002070B5124DEB692A460133EB6112 +:1036700052F8103F934206D09A68013A9A60302679 +:103680002C69A36803B170BDD4E900210A605160C0 +:10369000236083F31188D4E903312046984786F3E9 +:1036A000118861690029EBD02046FFF7A7FFE7E703 +:1036B00028380020054A30B5D369D2E908451B1BDC +:1036C000181945F10001C2E9080130BD2838002071 +:1036D00000207047FEE70000704700004FF0FF3009 +:1036E00070470000BFF34F8F024AD368DB07FCD45A +:1036F000704700BF0020024008B5074B1B7853B944 +:10370000FFF7F0FF054B1A69120641BF044A5A60E1 +:1037100002F188325A6008BD683A00200020024059 +:103720002301674508B5054B1B7833B9FFF7DAFF6E +:10373000034A136943F08003136108BD683A00200F +:10374000002002407F289ABF00F58030C002002090 +:10375000704700004FF40060704700008020704701 +:103760007F2808B50BD8FFF7EDFF00F5006302686E +:10377000013204D104308342F9D1012008BD002078 +:10378000FCE700007F2810B504461CD8FFF7AAFF0D +:10379000FFF7B2FF0D4BF322DA6002221A61FFF746 +:1037A000D1FF58611A6942F040021A614FF400617A +:1037B000FFF798FF00F05AF9FFF7B4FF2046BDE885 +:1037C0001040FFF7CDBF002010BD00BF0020024019 +:1037D0002DE9F84312F00103144606D01F4B40F2C6 +:1037E00003321A600020BDE8F88385181C4A954210 +:1037F00004D91A4A4FF442711160F3E7FFF77CFFD6 +:10380000FFF770FFDFF86880451A4FF00109012CBF +:1038100005EB01060F4603D8FFF784FF0120E2E71E +:103820003B88C8F8109033800020FFF75BFFC8F892 +:103830001000338831F8022B9BB29A420CD0074B10 +:1038400040F21F321A60074B1E60074B1C60074B8B +:103850001F60FFF767FFC6E7023CD8E7643A002025 +:1038600000000408583A0020603A00205C3A00202A +:1038700000200240084908B50B7828B11BB9FFF7B2 +:103880003BFF01230B7008BD002BFCD0BDE80840B6 +:103890000870FFF747BF00BF683A002008B5064828 +:1038A0004FF41F4100F0E4F8BDE808404FF4005128 +:1038B0004FF0805000F0DCB80001002008461146AF +:1038C00000F084BE012000F081BE0000084600F038 +:1038D0009BBE000038B5EFF31185BDBBEFF3058447 +:1038E000C4F308043023C4B183F31188FFF7E2FE68 +:1038F0004C014201121A44EAD06464EB01049300C3 +:10390000A4001B1844EA927441EB0401C900D800DA +:1039100041EA537185F3118838BD83F31188FFF7AD +:10392000C9FE4D014201121A45EAD06565EB010559 +:103930009300AD001B1845EA927541EB0501C900E3 +:10394000D80041EA537184F3118838BDFFF7B2FE05 +:103950004B014401241A43EAD06363EB0103A20044 +:103960009B00121843EA947341EB0301C900D00095 +:1039700041EA527138BD00BF38B5FFF7ABFF114CBB +:10398000114AC00840EA4170A0FB025EC908A0FBD2 +:10399000040C1CEB050CA1FB04404FF000035B4141 +:1039A000A1FB02121CEB040C43EB000011EB0E0117 +:1039B00042F10002411842F10000090941EA007099 +:1039C00038BD00BFCFF753E3A59BC42010B5024418 +:1039D000064BD2B2904200D110BD441C00B253F845 +:1039E000200041F8040BE0B2F4E700BF502800408B +:1039F0000F4B30B51C6A240407D41C6A44F440748D +:103A00001C621C6A44F400441C620A4C236843F4A0 +:103A1000807323600244084BD2B2904200D130BD83 +:103A2000441C00B251F8045B43F82050E0B2F4E7C4 +:103A300000100240007000405028004007B50122ED +:103A400001A90020FFF7C2FF019803B05DF804FB55 +:103A500013B50446FFF7F2FFA04205D0012201A9E9 +:103A600000200194FFF7C4FF02B010BD70470000B2 +:103A70007047000070470000074B45F255521A602E +:103A800002225A6040F6FF729A604CF6CC421A60ED +:103A9000024B01221A70704700300040703A00203B +:103AA000034B1B781BB1034B4AF6AA221A607047DE +:103AB000703A002000300040044B1A682AB902F125 +:103AC000804202F50432526A1A6070476C3A002054 +:103AD000024B4FF080725A62704700BF00100240E4 +:103AE00008B5FFF7E9FF024B1868C0F3407008BD46 +:103AF0006C3A002070470000FEE700000A4B0B48BC +:103B00000B4A90420BD30B4BDA1C121AC11E22F047 +:103B100003028B4238BF00220021FDF785BA53F81B +:103B2000041B40F8041BECE714490008543C002037 +:103B3000543C0020543C0020FEE7000070B51B4BB5 +:103B400001630025044686B0586085620E46FFF783 +:103B5000D3FB04F11003C4E904334FF0FF33A36136 +:103B6000134BE561D969A5600A462B46C4E90823D1 +:103B700004F13401C4E900440E4AE562256580235E +:103B80002046FFF7D5FC0123E0600B4A0375009245 +:103B900072680192B268CDE90223084B6846CDE90C +:103BA0000435FFF7EDFC06B070BD00BF503A0020B1 +:103BB00028380020BC470008C1470008393B0008EE +:103BC0004B6843608B688360CB68C3600B6943615B +:103BD0004B6903628B6943620B68036070470000A6 +:103BE00008B51B4B9A6A42F4FC029A629A6A22F464 +:103BF000FC029A629A6A5A6942F4FC025A61154AB6 +:103C00005B6911464FF09040FFF7DAFF02F11C01AB +:103C100000F58060FFF7D4FF02F1380100F5806005 +:103C2000FFF7CEFF02F1540100F58060FFF7C8FFF7 +:103C300002F1700100F58060FFF7C2FF02F18C0114 +:103C400000F58060FFF7BCFFBDE8084000F05AB8FF +:103C500000100240C847000808B500F093F9FFF7CC +:103C60003FFCBDE80840FFF727BF00007047000099 +:103C700010B5214CA36A63F4FC03A362A36A03F4A6 +:103C8000FC03A3624FF0FF32A36A23692261236918 +:103C9000002323612169E168E260E268E360E26891 +:103CA000E269164942F08052E261E2690A6842F430 +:103CB00080720A60226A02F44072B2F5407F1EBF31 +:103CC0004FF4803222622362236A1B0407D4236AE2 +:103CD00043F440732362236A43F40043236200F0F9 +:103CE00031F9A369064A43F00103A361A36913688C +:103CF00043F02003136010BD00100240007000402C +:103D0000000001401E4B1A6842F001021A601A6856 +:103D10009007FCD55A6822F003025A605A6812F0E4 +:103D20000C02FBD1196801F0F90119605A601A6898 +:103D300042F480321A601A689103FCD5114A5A6025 +:103D40004FF40452DA6230221A631A6842F0807229 +:103D50001A601A689201FCD50B4912220A600A689F +:103D600002F00702022AFAD15A6842F002025A60AF +:103D70005A6802F00C02082AFAD11A6B1A637047CB +:103D80000010024000241D0000200240084A08B52F +:103D9000516913680B4003F00103536123B1054AD5 +:103DA00013680BB150689847BDE80840FFF7C8BAE0 +:103DB00000040140743A0020084A08B551691368AC +:103DC0000B4003F00203536123B1054A93680BB122 +:103DD000D0689847BDE80840FFF7B2BA0004014038 +:103DE000743A0020084A08B5516913680B4003F083 +:103DF0000403536123B1054A13690BB15069984715 +:103E0000BDE80840FFF79CBA00040140743A002066 +:103E1000084A08B5516913680B4003F00803536161 +:103E200023B1054A93690BB1D0699847BDE80840B2 +:103E3000FFF786BA00040140743A0020084A08B52A +:103E4000516913680B4003F01003536123B1054A15 +:103E5000136A0BB1506A9847BDE80840FFF770BA83 +:103E600000040140743A0020174B10B55A691C68D1 +:103E7000144004F478725A61A30604D5134A936A75 +:103E80000BB1D06A9847600604D5104A136B0BB18A +:103E9000506B9847210604D50C4A936B0BB1D06B3D +:103EA0009847E20504D5094A136C0BB1506C98474A +:103EB000A30504D5054A936C0BB1D06C9847BDE8B7 +:103EC0001040FFF73DBA00BF00040140743A0020E3 +:103ED0001A4B10B55A691C68144004F47C425A61AC +:103EE000620504D5164A136D0BB1506D9847230532 +:103EF00004D5134A936D0BB1D06D9847E00404D5F7 +:103F00000F4A136E0BB1506E9847A10404D50C4AAA +:103F1000936E0BB1D06E9847620404D5084A136FB4 +:103F20000BB1506F9847230404D5054A936F0BB12A +:103F3000D06F9847BDE81040FFF702BA0004014077 +:103F4000743A0020062108B50846FFF723FA062137 +:103F50000720FFF71FFA06210820FFF71BFA0621AA +:103F60000920FFF717FA06210A20FFF713FA0621A6 +:103F70001720FFF70FFABDE8084006212820FFF7B9 +:103F800009BA000008B5FFF773FE00F067F800F00B +:103F90003DF8FFF76BFEBDE8084000F05DB800009B +:103FA000026843681143016003B11847704700007D +:103FB000143000F02FBA00004FF0FF33143000F03F +:103FC00029BA0000383000F0A5BA00004FF0FF33E6 +:103FD000383000F09FBA0000143000F0F5B900004E +:103FE0004FF0FF31143000F0EFB90000383000F02E +:103FF0004FBA00004FF0FF32383000F049BA0000ED +:10400000012914BF6FF013000020704700F06CB856 +:10401000044B03600023C0E90233436001230374AF +:10402000704700BF7048000838B5C36904460D46A4 +:104030001BB904210844FFF7B3FF294604F114001B +:1040400000F0A6F9002806DA201D4FF40061BDE853 +:104050003840FFF7A5BF38BD00F00EB80023054A71 +:1040600019460133102BC2E9001102F10802F8D100 +:10407000704700BF743A00204FF0E023044A5A61B1 +:1040800000229A6107221A6108210B20FFF798B9D4 +:104090003F19010008B5302383F31188FFF746FA72 +:1040A000002383F3118808BD08B5FFF7F3FFBDE8CF +:1040B0000840FFF745B900000268436811430160FA +:1040C00003B1184770470000024A136843F0C00369 +:1040D0001360704700380140024A136843F0C00380 +:1040E000136070470044004037B51D4C1D4D2046FD +:1040F000FFF78EFF009404F114001B4900232022D7 +:1041000000F038F92022009404F13800174B1849C8 +:1041100000F0B2F9174BC4E91735174C0C212520D4 +:10412000FFF738F92046FFF773FF04F11400134935 +:1041300000940023202200F01DF904F13800104BF8 +:1041400010490094202200F097F90F4B0C212620F3 +:10415000C4E9173503B0BDE83040FFF71BB900BF15 +:10416000F43A002000512502CC3B0020C940000851 +:104170000C3C002000380140603B0020EC3B00205C +:10418000D94000082C3C0020004400402DE9F047B5 +:10419000C66D3768F46934622107054619D014F0FA +:1041A000080118BF4FF48071E20748BF41F02001B9 +:1041B000A30748BF41F04001600748BF41F08001BC +:1041C000302383F31188281DFFF776FF002383F344 +:1041D0001188E2050AD5302383F311884FF48061FA +:1041E000281DFFF769FF002383F311884FF0300982 +:1041F0004FF0000A14F0200838D13B0616D54FF0D6 +:10420000300905F1380A200610D589F31188504687 +:1042100000F066F9002836DA0821281DFFF74CFF68 +:1042200027F080033360002383F31188790614D5C7 +:10423000620612D5302383F31188D5E913239A42FD +:1042400008D12B6C33B11021281D27F04007FFF750 +:1042500033FF3760002383F31188E30619D5AA6E74 +:104260001369B3B1BDE8F0475069184789F3118865 +:10427000B38C95F8641028461940FFF7D5FE8AF3F1 +:104280001188F469B6E780B2308588F31188F46943 +:10429000B9E7BDE8F087000008B50348FFF776FFEF +:1042A000BDE80840FFF74CB8F43A002008B50348D1 +:1042B000FFF76CFFBDE80840FFF742B8603B002005 +:1042C000F8B5154682680669AA420B46816938BF6F +:1042D0008568761AB54204460BD218462A46FCF782 +:1042E00091FEA3692B44A361A3685B1BA3602846CE +:1042F000F8BD0CD918463246FCF784FEAF1BE168C6 +:104300003A463044FCF77EFEE3683B44EBE7184650 +:104310002A46FCF777FEE368E5E7000083689342EE +:10432000F7B51546044638BF8568D0E90460361AEB +:10433000B5420BD22A46FCF765FE63692B446361E4 +:10434000A36828465B1BA36003B0F0BD0DD93246BD +:104350000191FCF757FE0199E068AF1B3A463144E2 +:10436000FCF750FEE3683B44E9E72A46FCF74AFEC7 +:10437000E368E4E710B50A440024C361029B84604B +:10438000C0E90000C0E90511C1600261036210BD0F +:1043900008B5D0E90532934201D1826882B98268BA +:1043A000013282605A1C42611970D0E904329A428B +:1043B00024BFC36843610021FFF714F9002008BD42 +:1043C0004FF0FF30FBE7000070B5302304460E4687 +:1043D00083F31188A568A5B1A368A269013BA36016 +:1043E000531CA36115782269934224BFE368A3613B +:1043F000E3690BB120469847002383F311882846D0 +:1044000007E031462046FFF7DDF80028E2DA85F3C1 +:10441000118870BD2DE9F74F04460E4617469846A1 +:10442000D0F81C904FF0300A8AF311884FF0000B3F +:10443000154665B12A4631462046FFF741FF03463F +:1044400060B941462046FFF7BDF80028F1D00023AF +:1044500083F31188781B03B0BDE8F08FB9F1000F2A +:1044600003D001902046C847019B8BF31188ED1AB9 +:104470001E448AF31188DCE7C0E90511C160C361FD +:104480001144009B8260C0E9000001610362704733 +:10449000F8B504460D461646302383F31188A76805 +:1044A000A7B1A368013BA36063695A1C62611D70D8 +:1044B000D4E904329A4224BFE3686361E3690BB133 +:1044C00020469847002080F3118807E031462046B7 +:1044D000FFF778F80028E2DA87F31188F8BD0000CA +:1044E000D0E905239A4210B501D182687AB9826871 +:1044F000013282605A1C82611C7803699A4224BF8F +:10450000C36883610021FFF76DF8204610BD4FF0AE +:10451000FF30FBE72DE9F74F04460E461746984655 +:10452000D0F81C904FF0300A8AF311884FF0000B3E +:10453000154665B12A4631462046FFF7EFFE034691 +:1045400060B941462046FFF73DF80028F1D000232E +:1045500083F31188781B03B0BDE8F08FB9F1000F29 +:1045600003D001902046C847019B8BF31188ED1AB8 +:104570001E448AF31188DCE70B460146184600F01A +:104580002DB8000000F040B8012838BF012010B558 +:104590000446204600F030F830B900F007F808B9BA +:1045A00000F00CF88047F4E710BD0000024B1868DB +:1045B000BFF35B8F704700BF4C3C002008B506205E +:1045C00000F084F80120FFF785F80000024B0A464E +:1045D00001461868FFF772B91811002010B5054C94 +:1045E00013462CB10A4601460220AFF3008010BDED +:1045F0002046FCE700000000024B01461868FFF768 +:1046000061B900BF18110020024B01461868FFF77E +:104610005DB900BF1811002010B501390244904265 +:1046200001D1002005E0037811F8014FA34201D029 +:10463000181B10BD0130F2E72DE9F041A3B1C91AF2 +:1046400017780144044603F1FF3C8C42204601D90F +:10465000002009E00578BD4204F10104F5D10CEB1E +:104660000405D618A54201D1BDE8F08115F8018DE9 +:1046700016F801EDF045F5D0E7E700001F2938B541 +:1046800004460D4604D9162303604FF0FF3038BDB1 +:10469000426C12B152F821304BB9204600F030F88C +:1046A0002A4601462046BDE8384000F017B8012BE5 +:1046B0000AD0591C03D1162303600120E7E7002428 +:1046C00042F82540284698470020E0E7024B014683 +:1046D0001868FFF7D3BF00BF1811002038B5074D89 +:1046E00000230446084611462B60FEF7F7FF431CE3 +:1046F00002D12B6803B1236038BD00BF503C0020BD +:10470000FEF7E6BF034611F8012B03F8012B002A40 +:10471000F9D170476F72672E6172647570696C6F42 +:10472000742E663330332D4D313030373000000079 +:1047300040A2E4F1646891060041A3E5F265699244 +:10474000070000004261642043414E496661636591 +:1047500020696E6465782E008000000000800000F3 +:104760000000800000000000000000001118000898 +:104770002D200008891F0008511800085D18000846 +:104780005D1A0008211800083118000825180008D3 +:104790002D1800082918000881190008351800088C +:1047A000FD22000845180008551900086330000074 +:1047B000AC47000880380020503A00206D61696ED7 +:1047C0000069646C65000000A001A82A00000000D8 +:1047D000FAAABEAA50001424EFFF000000770000E0 +:1047E000709709000100000000000000AAAAAAAA10 +:1047F00001000000FFFF00000000000000000000BA +:104800000000000000000000AAAAAAAA0000000000 +:10481000FFFF00000000000000000000000000009A +:1048200000000000AAAAAAAA00000000FFFF0000E2 +:104830000000000000000000000000000000000078 +:10484000AAAAAAAA00000000FFFF000000000000C2 +:10485000000000000000000000000000AAAAAAAAB0 +:1048600000000000FFFF000000000000000000004A +:1048700000000000CD3F0008B93F0008F53F0008E8 +:10488000E13F0008ED3F0008D93F0008C53F0008A0 +:10489000B13F000801400008EC03000000000000E8 +:1048A0000098030000000000FE2A0100D20400006E +:1048B0001C110020000000000000000000000000AB +:1048C00000000000000000000000000000000000E8 +:1048D00000000000000000000000000000000000D8 +:1048E00000000000000000000000000000000000C8 +:1048F00000000000000000000000000000000000B8 +:1049000000000000000000000000000000000000A7 +:0449100000000000A3 :00000001FF diff --git a/Tools/bootloaders/f303-MatekGPS_bl.bin b/Tools/bootloaders/f303-MatekGPS_bl.bin index b011dbc79a2cee..cc7f9dc927a9a9 100755 Binary files a/Tools/bootloaders/f303-MatekGPS_bl.bin and b/Tools/bootloaders/f303-MatekGPS_bl.bin differ diff --git a/Tools/bootloaders/f303-MatekGPS_bl.elf b/Tools/bootloaders/f303-MatekGPS_bl.elf index dd3736d8abc76a..ca17f19803d4d1 100755 Binary files a/Tools/bootloaders/f303-MatekGPS_bl.elf and b/Tools/bootloaders/f303-MatekGPS_bl.elf differ diff --git a/Tools/bootloaders/f303-MatekGPS_bl.hex b/Tools/bootloaders/f303-MatekGPS_bl.hex index fa31d391a6aafc..1a59ad847b383c 100644 --- a/Tools/bootloaders/f303-MatekGPS_bl.hex +++ b/Tools/bootloaders/f303-MatekGPS_bl.hex @@ -1,1218 +1,1172 @@ :020000040800F2 -:1000000000090020B5040008D52500088D2500084A -:10001000B52500088D250008AD250008B7040008A7 -:10002000B7040008B7040008B7040008C935000881 -:10003000B7040008B7040008B70400087D430008AF -:10004000B7040008B7040008B7040008B7040008A4 -:10005000B7040008B7040008614000088D4000089C -:10006000B9400008E540000811410008B704000845 -:10007000B7040008B7040008B7040008B704000874 -:10008000B7040008B7040008B704000841250008B9 -:100090006D2500087D250008B70400083D410008D3 -:1000A000B7040008B7040008B7040008B704000844 -:1000B000B7040008B7040008B7040008B704000834 -:1000C000B7040008B7040008B7040008B704000824 -:1000D000B70400086D45000881450008B704000812 -:1000E000A5410008B7040008B7040008B7040008D9 -:1000F000B7040008B7040008B7040008B7040008F4 -:10010000B7040008B7040008B7040008B7040008E3 -:10011000B7040008B7040008B7040008B7040008D3 -:10012000B7040008B7040008B7040008B7040008C3 -:10013000B7040008B7040008B7040008B7040008B3 -:10014000B7040008B7040008B7040008B7040008A3 -:10015000B7040008B7040008B7040008B704000893 -:10016000B7040008B7040008B7040008B704000883 -:10017000B7040008B7040008B7040008B704000873 -:10018000B7040008B7040008B7040008B704000863 -:10019000B7040008B7040008B7040008B704000853 -:1001A000291200080000000000000000000000000C -:1001B00053B94AB9002908BF00281CBF4FF0FF31CE -:1001C0004FF0FF3000F074B9ADF1080C6DE904CECA -:1001D00000F006F8DDF804E0DDE9022304B0704722 -:1001E0002DE9F047089D04468E46002B4DD18A42EA -:1001F000944669D9B2FA82F252B101FA02F3C2F11D -:10020000200120FA01F10CFA02FC41EA030E9440AD -:100210004FEA1C48210CBEFBF8F61FFA8CF708FBCE -:1002200016E341EA034306FB07F199420AD91CEBA6 -:10023000030306F1FF3080F01F81994240F21C81D8 -:10024000023E63445B1AA4B2B3FBF8F008FB103320 -:1002500044EA034400FB07F7A7420AD91CEB040455 -:1002600000F1FF3380F00A81A74240F20781644425 -:10027000023840EA0640E41B00261DB1D4400023AA -:10028000C5E900433146BDE8F0878B4209D9002D0E -:1002900000F0EF800026C5E9000130463146BDE898 -:1002A000F087B3FA83F6002E4AD18B4202D3824202 -:1002B00000F2F980841A61EB030301209E46002DB1 -:1002C000E0D0C5E9004EDDE702B9FFDEB2FA82F206 -:1002D000002A40F09280A1EB0C014FEA1C471FFA64 -:1002E0008CFE0126200CB1FBF7F307FB131140EA4B -:1002F00001410EFB03F0884208D91CEB010103F118 -:10030000FF3802D2884200F2CB804346091AA4B2D9 -:10031000B1FBF7F007FB101144EA01440EFB00FEAD -:10032000A64508D91CEB040400F1FF3102D2A64512 -:1003300000F2BB800846A4EB0E0440EA03409CE7B1 -:10034000C6F12007B34022FA07FC4CEA030C20FA5E -:1003500007F401FA06F31C43F9404FEA1C4900FA7E -:1003600006F3B1FBF9F8200C1FFA8CFE09FB1811FB -:1003700040EA014108FB0EF0884202FA06F20BD96E -:100380001CEB010108F1FF3A80F08880884240F2BE -:100390008580A8F102086144091AA4B2B1FBF9F002 -:1003A00009FB101144EA014100FB0EFE8E4508D9FD -:1003B0001CEB010100F1FF346CD28E456AD9023882 -:1003C000614440EA0840A0FB0294A1EB0E01A14267 -:1003D000C846A64656D353D05DB1B3EB080261EBD5 -:1003E0000E0101FA07F722FA06F3F1401F43C5E9AF -:1003F000007100263146BDE8F087C2F12003D840E5 -:100400000CFA02FC21FA03F3914001434FEA1C4726 -:100410001FFA8CFEB3FBF7F007FB10360B0C43EA18 -:10042000064300FB0EF69E4204FA02F408D91CEBC8 -:10043000030300F1FF382FD29E422DD902386344C6 -:100440009B1B89B2B3FBF7F607FB163341EA034166 -:1004500006FB0EF38B4208D91CEB010106F1FF38B5 -:1004600016D28B4214D9023E6144C91A46EA0046AC -:1004700038E72E46284605E70646E3E61846F8E63E -:100480004B45A9D2B9EB020864EB0C0E0138A3E787 -:100490004646EAE7204694E74046D1E7D0467BE768 -:1004A000023B614432E7304609E76444023842E7E0 -:1004B000704700BF02E000F000F8FEE772B6374870 -:1004C00080F30888364880F3098836483649086042 -:1004D00040F20000CCF200004EF63471CEF2000182 -:1004E0000860BFF34F8FBFF36F8F40F20000C0F280 -:1004F000F0004EF68851CEF200010860BFF34F8F36 -:10050000BFF36F8F4FF00000E1EE100A4EF63C7122 -:10051000CEF200010860062080F31488BFF36F8FCD -:1005200003F052FC03F0C6FC4FF055301F491B4A44 -:1005300091423CBF41F8040BFAE71D49184A914229 -:100540003CBF41F8040BFAE71A491B4A1B4B9A427D -:100550003EBF51F8040B42F8040BF8E7002018499D -:10056000184A91423CBF41F8040BFAE703F030FC13 -:1005700003F0DCFC144C154DAC4203DA54F8041BB8 -:100580008847F9E700F042F8114C124DAC4203DA0B -:1005900054F8041B8847F9E703F018BC0009002051 -:1005A000001100200000000808ED00E0000100201C -:1005B00000090020784B0008001100207C11002069 -:1005C00080110020583C0020A0010008A401000870 -:1005D000A4010008A40100082DE9F04F2DED108AB8 -:1005E000C1F80CD0C3689D46BDEC108ABDE8F08F01 -:1005F000002383F311882846A047002003F06EF9FA -:10060000FEE703F0D1F800DFFEE70000F8B500F0E8 -:100610001DFE03F07DFB074603F0CCFB05460028DA -:1006200040D12C4B9F423DD001339F423DD02A4BBD -:1006300027F0FF029A423BD1F8B200F043FC2E466D -:1006400042F2107400F044FC08B10024264601F088 -:10065000B5F888B3032000F045F80024264635B1EC -:100660001E4B9F4203D003F09DFB00242646002032 -:1006700003F058FB1A4B1B6913F0400322D00EB154 -:1006800000F046F800F056FC00F0E2FD01F0AAFF91 -:100690000546CCB101F0A6FF401BA04214D900F0E2 -:1006A00037F8F3E72E460024CCE704460126C9E7D5 -:1006B00006464FF47A74C5E7002CD0D04FF47A7414 -:1006C0000126CCE71C46DDE700F07CFC012003F0AE -:1006D0000BF9DEE7010007B0000008B0263A09B0C8 -:1006E00000040048084B187003280CD8DFE800F01D -:1006F00008050208022000F007BE022000F0FCBD41 -:10070000024B00225A6070478011002084110020A3 -:1007100038B501F053F830B11F4B03221A701F4B4C -:1007200000225A6038BD1E4B1E4A19680131F9D0AB -:1007300004339342F9D11C4C194DD4F80428AA4231 -:10074000F0D31A4B9B6803F1006303F5D0439A4240 -:10075000E8D203F0FBFA03F00DFB002000F092FD5D -:100760000220FFF7BFFF124BDA690022DA61D96974 -:1007700099699A619B6972B64FF0E0233021C3F802 -:10078000085DD4F80038D4F8042881F311889D4618 -:1007900083F308881047C5E78011002084110020EA -:1007A00000680008206800080060000800110020B0 -:1007B00000100240094A136849F2690099B21B0C03 -:1007C00000FB01331360064B186844F2506182B29B -:1007D000000C01FB0200186080B270471411002069 -:1007E0001011002010B500211022044600F0A6FDD3 -:1007F000034B03CB206061601868A06010BD00BF90 -:10080000ACF7FF1F2DE9F041ADF54E7D0DF1340839 -:100810006CAC40F2751207460D460EA80021C8F8D0 -:10082000001000F08BFD4FF4C4720021204600F050 -:1008300085FD01F0D7FE274B4FF47A72B0FBF2F042 -:10084000186093E80700022384E807000DF5E970BB -:100850002382FFF7C7FF4EF603431F49238406A8F0 -:1008600004F0BAF81B2384F832310DF2E32206AB10 -:100870000DF1300C1E4603CE6645106051603346C4 -:1008800002F10802F6D13188B378937011802046C6 -:100890004146012200F09EFD00230393AB7E0293AC -:1008A00005F11903019380B20123CDE9048000937F -:1008B000E97E06A3D3E90023384602F05BFA0DF582 -:1008C0004E7DBDE8F08100BFAFF300809E6AC42179 -:1008D000818A46EE8C110020E84900082DE9F0419C -:1008E0002C4C237ADAB080460D465BBB27A92846FC -:1008F00000F080FE0746002842D19DF89D60C82E7A -:100900003ED801464FF4A662204600F017FD4FF492 -:100910008073C4F8F8314FF40073C4F80C334FF40B -:100920004073C4F8203432460DF19E0104F10900F1 -:1009300000F0F2FC26449DF89C30777223720BB9CC -:10094000EB7E23728122002106AC27A800F0F6FC82 -:100950000122214627A800F089FE00230393AB7EE5 -:10096000029305F1190380B201932823CDE90440D5 -:100970000093E97E05A3D3E90023404602F0FAF98B -:100980005AB0BDE8F08100BFAFF30080264172721B -:10099000DF25D7B7A8320020F0B5254E4FF48A7571 -:1009A00005FB0065F1B096F8D83085F8DC300024FE -:1009B000D822214685F8E8403AA800F0BFFC06F1AD -:1009C000090000F0B3FCD5F8E4308DF8F000C2B2B5 -:1009D00006AF06F109010DF1F100CDE93A3400F05E -:1009E0009BFC394601223AA800F06CFE80B2CDE9AA -:1009F000047008230127CDE9023706F1D8030193DB -:100A000030230093317A0B4807A3D3E9002302F087 -:100A1000B1F9A04206DD01F0E5FDC5F8E000384679 -:100A200071B0F0BD2046FBE778F6339F93CACD8DB9 -:100A3000A8320020A42100202DE9F0411D4D1E4EBA -:100A40001E4F86B0284602F0C1F9034658B3002471 -:100A5000CDE90344ADF81440027B8DF81420996869 -:100A60004068029403AA03C21B68DFF8548043F075 -:100A70000043029301F0B8FD821941F10003009494 -:100A800002A9384601F07CF8A04205DD284602F0B4 -:100A9000A1F988F80040D5E798F80030072B05D871 -:100AA000013388F8003006B0BDE8F081014802F05B -:100AB00091F9F8E7A421002040420F00D82100203E -:100AC000DD37002070B50D4614461E4602F0AEF824 -:100AD00050B9022E10D1012C0ED112A3D3E900235C -:100AE000C5E90023012007E0282C10D005D8012CEF -:100AF00009D0052C0FD0002070BD302CFBD10BA3EA -:100B0000D3E90023ECE70BA3D3E90023E8E70BA329 -:100B1000D3E90023E4E70BA3D3E90023E0E700BF18 -:100B2000AFF30080401DA12026812A0B78F6339F69 -:100B300093CACD8D9E6AC421818A46EE2641727287 -:100B4000DF25D7B7F017304A39059E5638B5054628 -:100B50000E4C0021013500F0B7FBA4F82C55B4F879 -:100B60002C0500F099FB78B1B4F82C0500F0A4FB3B -:100B7000014648B9B4F82C0500F0A6FBB4F82C35B2 -:100B80000133A4F82C35EAE738BD00BFA8320020B5 -:100B900010B50A4B0A4A1A6003F5805393F8602097 -:100BA0003AB9DC6D2CB1204600F082FE204603F0FD -:100BB00053FEBDE81040034800F07ABED821002063 -:100BC000404A0008203200202DE9F04F8FB000AFDE -:100BD00005460C4602F02AF8002849D1237E022B54 -:100BE0001BD1E38A012B18D101F0FCFC0646FFF76C -:100BF000E1FD03464FF4C870DFF8C482B3FBF0F2A6 -:100C000006F5167602FB103316FA83F3C8F80030A7 -:100C1000E37E33B9A34B00221A703C37BD46BDE8D2 -:100C2000F08F07F12401204600F0A2FC0028F4D147 -:100C300007F11400FFF7D6FD97F8264007F11401DD -:100C4000224607F1270003F051FE0028E2D10F2CC5 -:100C500008D8944B1C70D8F80030A3F51673C8F868 -:100C60000030DAE797F82410284601F0D7FFD4E7E0 -:100C7000E38A282B2BD010D8012B23D0052BCCD1E5 -:100C8000BFF34F8F8849894BCA6802F4E06213436F -:100C9000CB60BFF34F8F00BFFDE7302BBDD1844E3B -:100CA000E17E327A9142B8D1607E3146002291F8DD -:100CB000DC50854200F0A5800132042A01F58A71DA -:100CC000F5D1AAE721462846FFF79CFDA5E7214676 -:100CD0002846FFF703FEA0E7B2F8EC507B6005F171 -:100CE00003094FEA99094FEA8902D11DC908A8EB07 -:100CF000C1039D46EB460021584600F01FFB04F15E -:100D0000EE012A463144584600F006FB7B6813B9D1 -:100D1000012000F0B7FA96F8D20000F0BDFA0446C0 -:100D200030B9307200F0D8FA204600F0ABFAB1E0EA -:100D3000D6F8D4203AB996F8D200B6F82C258242DB -:100D400001D8FFF703FFD6F8D4202A44944208D2F2 -:100D500096F8D200B6F82C250130824201D8FFF770 -:100D6000F5FE70685FFA89F2594600F0EFFA08B9AB -:100D7000C54679E0726896F8D2002A447260D6F8C7 -:100D8000D42005EB0209C6F8D49000F085FA81451D -:100D900009D396F8D220D6F8D4000132001B86F889 -:100DA000D220C6F8D400FF2D0FD80024347200F0F2 -:100DB00093FA204600F066FA00F000FD3D4B1881E2 -:100DC00008B9FFF7A5FCC54627E7BB6896F8D90028 -:100DD0000AFB0362FB68D2F8E41082F8E83001F500 -:100DE0008061C2F8E030C2F8E410FFF7D5FDFFF7EC -:100DF00023FE96F8D920013202F0030286F8D920AA -:100E0000B6E74FF48A7A0AFB02F505F1EA013144AC -:100E1000204600F083FCF86000287FF4FEAE3544E5 -:100E2000012285F8E82001F0DDFBD5F8E020D6EDC1 -:100E3000007ADFED216A801A192838BF192040F6A0 -:100E4000B832904228BF1046B8EE677A07EE900A93 -:100E5000F8EEE77A67EEA67ADFED186AE7EE267A13 -:100E6000FCEEE77AC6ED007A96F8D930BB60BA6836 -:100E700073680AFB02F4321992F8E81059B1D2F8FB -:100E8000E4108B42E8463FF427AF002182F8E810D7 -:100E9000C2F8E010C5467368064A9B0A0133138105 -:100EA000BBE600BF9D21002000ED00E00400FA0534 -:100EB000A83200208C110020CDCCCC3D6666663F68 -:100EC000A0210020014B1870704700BF981100202E -:100ED00038B54FF00054134B22689A4220D1124B80 -:100EE000627D12481A70237D03724FF48073C0F83C -:100EF000F8314FF40073C0F80C3300254FF4407301 -:100F0000C0F820340A49C0F8E450C922093000F082 -:100F100003FAE0222946204600F010FA012038BDED -:100F20000020FCE79AAD44C598110020A8320020AB -:100F30001600002037B500F041FC194D19492881F1 -:100F40000223012218486B7101F0EAF90023019392 -:100F5000164B174900931748174B4FF4805201F076 -:100F600035FE164B197811B1124801F057FE01F009 -:100F700039FB0446FFF71EFC4FF4C873B0FBF3F2D5 -:100F800002FB130304F5167010FA83F00C4B186083 -:100F900002F010FF08B10F232B8103B030BD00BF5A -:100FA0008C11002040420F00D8210020C50A000803 -:100FB0009C110020A4210020C90B000898110020DA -:100FC000A02100202DE9F04F2DED028B8EA7D7E94F -:100FD00000670FF23C29D9E90089864C95B00DAD28 -:100FE0009FED828BFFF728FDDFF82CB200230C93D6 -:100FF000ADF83C300D936B6000230DF125028DEDB3 -:10100000008B4FF0010A09A958468DF825308DF85C -:1010100024A001F035F99DF824200023002A40F097 -:10102000AB80204601F002FE0546002847D1DFF8DC -:10103000ECB101F0D7FADBF8003098423FD301F071 -:10104000D1FA0790FFF7B6FB079A4FF4C873B0FBCD -:10105000F3F101FB130302F5167010FA83F0CBF8DD -:101060000000DFF8BCB19BF800100791002914BF05 -:101070002B46534610A88DF83030FFF7B3FB079985 -:10108000C1F11002D2B2062A10AB28BF06221944C1 -:101090000DF13100079200F03FF9079A0CAB039372 -:1010A000182302930132544BD2B2CDE900A304922B -:1010B0003B463246204601F0FFFD8BF8005001F020 -:1010C00091FA4E4A4E4D1368C31AB3F57A7F32D364 -:1010D000106001F089FA02460B46204601F084FEBA -:1010E000204601F0A3FD30B32B7ADFF838A1002BA6 -:1010F00014BF032302238AF8053001F073FA0DF1BF -:10110000400B4FF47A730122B0FBF3F05946CAF852 -:101110000000504600F004FA18230293394B019363 -:1011200080B240F25513CDE903B0009342464B46DE -:10113000204601F0C1FD2B7ACBB101F053FA4FF0FC -:10114000000A83464FF48A7295F8D900504400F0A3 -:10115000030002FB005393F8E81089B30AF1010A77 -:10116000BAF1040FF0D12B7A002B7FF438AF15B011 -:10117000BDEC028BBDE8F08F4FF0904110A84A699A -:1011800082F010024A611946102200F0D7F80DF1E2 -:1011900026030AAA0CA9584600F0F0FD95E80300C2 -:1011A00011AB83E803009DF83C308DF84C300C9B6C -:1011B000109310A9DDE90A23204601F0E9FF1BE79F -:1011C000D3F8E01049B12B68FA2B38BFFA23ABEB08 -:1011D00001010533B1EB430FC0D3FFF7DDFB4FF443 -:1011E0008A720028BAD1BEE7AFF300800000000089 -:1011F00000000000A42100209C210020D8370020FE -:10120000A8320020DC370020401DA12026812A0BB7 -:10121000F1C6A7C1D068080FD8210020A021002066 -:101220009D2100208C11002008B5054800F040FEEB -:10123000BDE80840034A0449002003F007BB00BF93 -:10124000D821002018380020910B000870470000BA -:1012500070B502F013FC094E094D30800024286857 -:101260003388834208D902F005FC2B68044401331B -:10127000B4F5D04F2B60F2D370BD00BF0C38002006 -:10128000E037002002F086BC00F10060920000F51B -:10129000D04002F02DBC0000054B1A68054B1B889E -:1012A0009B1A834202D9104402F0E4BB002070472D -:1012B000E03700200C380020024B1B68184402F075 -:1012C000DFBB00BFE0370020024B1B68184402F070 -:1012D000E9BB00BFE0370020064991F8243033B164 -:1012E0000023086A81F824300822FFF7CDBF0120CF -:1012F000704700BFE4370020022802BF4FF0904340 -:1013000010229A6170470000022802BF4FF09043FC -:101310004FF480129A61704710B50023934203D0B6 -:10132000CC5CC4540133F9E710BD0000034602460B -:10133000D01A12F9011B0029FAD170470244034662 -:10134000934202D003F8011BFAE770472DE9F843F6 -:101350001F4D144695F824200746884652BBDFF8F7 -:1013600070909CB395F824302BB92022FF21484679 -:101370002F62FFF7E3FF95F82400C0F10802A242B4 -:1013800028BF2246D6B24146920005EB8000FFF707 -:10139000C3FF95F82430A41B1E44F6B2082E174450 -:1013A0009044E4B285F82460DBD1FFF795FF002874 -:1013B000D7D108E02B6A03EB82038342CFD0FFF73B -:1013C0008BFF0028CBD10020BDE8F8830120FBE78C -:1013D000E43700202DE9F0470D46044600219046F1 -:1013E000284640F27912FFF7A9FF23462022002168 -:1013F000284601F06FFE231D02222021284601F01D -:1014000069FE631D03222221284601F063FEA31D0D -:1014100003222521284601F05DFE04F10803102275 -:101420002821284601F056FE04F110030822382135 -:10143000284601F04FFE04F11103082240212846FE -:1014400001F048FE04F1120308224821284601F069 -:1014500041FE04F1140320225021284601F03AFEF7 -:1014600004F1180340227021284601F033FE04F1F4 -:1014700020030822B021284601F02CFE04F12103AC -:101480000822B821284601F025FE04F12207C026D3 -:101490003B46314608222846083601F01BFEB6F5C9 -:1014A000A07F07F10107F3D104F13203082231468E -:1014B000284601F00FFE002704F1330A94F8323079 -:1014C0004FEAC7099F4209F5A47615D3B8F1000F7A -:1014D00008D1314604F599730722284601F0FAFD38 -:1014E00009F24F16274694F832213B1B93420CD346 -:1014F000F01DC008BDE8F0870AEB0703082231465B -:10150000284601F0E7FD0137D8E707F233133146EB -:101510000822284601F0DEFD08360137E3E7000027 -:1015200013B504460846002101602346C0F80310A5 -:101530002022019001F0CEFD0198231D02222021DE -:1015400001F0C8FD0198631D0322222101F0C2FDB4 -:101550000198A31D0322252101F0BCFD019804F18F -:1015600008031022282101F0B5FD072002B010BDAC -:10157000F7B50023047F00910E4607221946054661 -:1015800001F06CFC731C0093012200230721284604 -:1015900001F064FCC4B9B31C009305222346082162 -:1015A000284601F05BFC0D243746B278BB1B934202 -:1015B00011D32B7FA88A0734E408BBB9844294BFB7 -:1015C0000020012003B0F0BDAB8ADB00083BDB0844 -:1015D000B3700824E8E7FB1C00932146002308228F -:1015E000284601F03BFC08340137DEE7201A18BF1B -:1015F0000120E7E7F7B50023047F00910E4608229B -:101600001946054601F02AFC731CC4B90822009350 -:1016100011462346284601F021FC1024012372784C -:101620005F1C013B934211D32B7FA88A0734E40847 -:10163000BBB9844294BF0020012003B0F0BDAB8A47 -:10164000DB00083BDB0873700824E7E7F31900931D -:10165000214600230822284601F000FC08343B46BE -:10166000DDE7201A18BF0120E7E70000F8B50E46B5 -:1016700005461446002181223046FFF75FFE2B46C7 -:1016800008220021304601F025FD7CB96B1C0722A1 -:101690000821304601F01EFD0F2401236A785F1CEB -:1016A000013B934204D3E01DC008F8BD0824F4E7D1 -:1016B000EB1921460822304601F00CFD08343B4668 -:1016C000ECE70000F8B50E46054614460021CE2290 -:1016D0003046FFF733FE2B4628220021304601F02A -:1016E000F9FC7CB905F1080308222821304601F0F5 -:1016F000F1FC30242F462A7A7B1B934204D3E01D51 -:10170000C008F8BD2824F5E707F10903214608229F -:10171000304601F0DFFC08340137ECE7F7B5047F11 -:1017200000910E46012310220021054601F096FB90 -:10173000C4B9B31C0093092223461021284601F0A6 -:101740008DFB192437467288BB1B9A4211D82B7F18 -:10175000A88A0734E408BBB9844294BF0020012062 -:1017600003B0F0BDAB8ADB00103BDB0873801024B4 -:10177000E8E73B1D0093214600230822284601F09C -:101780006DFB08340137DEE7201A18BF0120E7E7B8 -:1017900030B5094D0A4491420DD011F8013B584033 -:1017A000082340F30004013B2C4013F0FF0384EABC -:1017B0005000F6D1EFE730BD2083B8EDF7B5364ADB -:1017C000106851686B4603C36A463449344808239D -:1017D00003F09CF8044690BB0A25324A1068516811 -:1017E0006B4603C36A4630492D48082303F08EF840 -:1017F0000446002847D00369B3F5663F43D8B0F8E4 -:101800006620B2F57B7F3ED1284A024402F15C019A -:101810008B4238D35C3B224900209E1AFFF7B8FF69 -:101820003246074604F164010020FFF7B1FFA368C8 -:101830009F4228D1E368984208BF002523E003694E -:10184000B3F5663F26D8428BB2F57B7F20D1174A8D -:10185000024402F110018B4218D3103B10490020C2 -:101860009D1AFFF795FF2A46064604F1180100204D -:10187000FFF78EFFA3689E4202D1E368984201D031 -:101880000D25AAE70025284603B0F0BD1025A4E7E2 -:101890000C25A2E70B25A0E7044A0008DC9703000B -:1018A000006800080D4A0008909703000898FFF7A9 -:1018B00010B5037C044613B9006803F00FF8204606 -:1018C00010BD00000023BFF35B8FC360BFF35B8FCD -:1018D000BFF35B8F8360BFF35B8F7047BFF35B8F9A -:1018E0000068BFF35B8F704770B505460C30FFF79B -:1018F000F5FF05F1080604463046FFF7EFFFA0426A -:1019000006D930466D68FFF7E9FF2544281A70BDF7 -:101910003046FFF7E3FF201AF9E7000070B50546EF -:10192000406898B105F10800FFF7D8FF05F10C06F3 -:1019300004463046FFF7D2FF8442304694BF6D68BC -:101940000025FFF7CBFF013C2C44201A70BD00009E -:1019500038B50C460546FFF7C7FFA04210D305F186 -:101960000800FFF7BBFF04446868B4FBF0F100FB1C -:101970001144BFF35B8F0120AC60BFF35B8F38BDB8 -:101980000020FCE72DE9F041144607460D46FFF71D -:10199000C5FF844228BF0446D4B1B84658F80C6B42 -:1019A0004046FFF79BFF3044286040467E68FFF7C3 -:1019B00095FF331A9C4203D86C600120BDE8F0818A -:1019C0006B60A41B3B68AB602044E8600220F5E735 -:1019D0002046F3E738B50C460546FFF79FFFA042C7 -:1019E00010D305F10C00FFF779FF04446868B4FBDD -:1019F000F0F100FB1144BFF35B8F0120EC60BFF3FB -:101A00005B8F38BD0020FCE72DE9FF418846694621 -:101A10000746FFF7B7FF6C4606B204EBC606002583 -:101A2000B44209D06268206808EB0501FFF774FC36 -:101A3000636808341D44F3E729463846FFF7CAFFB8 -:101A4000284604B0BDE8F081F8B505460C300F46D5 -:101A5000FFF744FF05F1080604463046FFF73EFF56 -:101A6000A042304688BF6C68FFF738FF201A386004 -:101A700020B130462C68FFF731FF2044F8BD00004C -:101A800073B5144606460D46FFF72EFF844228BF65 -:101A900004460190DCB101A93046FFF7D5FF019B58 -:101AA00033B93268C5E90233C5E9002401200CE0EE -:101AB0009C4238BF01942860019868608442F5D93F -:101AC0003368AB60241AEC60022002B070BD20467F -:101AD000FBE700002DE9FF410F466946FFF7D0FF05 -:101AE0006C4600B204EBC0050026AC4209D0D4F825 -:101AF000048054F8081BB8194246FFF70DFC464411 -:101B0000F3E7304604B0BDE8F081000038B5054683 -:101B1000FFF7E0FF044601462846FFF719FF20467D -:101B200038BD0000302383F3118862B6704700008F -:101B3000002383F3118862B67047000010B4026876 -:101B400054681A4623465DF8044B18470120704735 -:101B50000020704700207047704700000020704749 -:101B60000E20704700F5805090F8C800C0F3400088 -:101B70007047000000F5805090F9C90070470000E0 -:101B8000F7B50C68BDF8207014F000541E466FD1F4 -:101B90000B7B082B6CD8FFF7C5FF4569AB685B0171 -:101BA0000CD4AB681B0108D4AC6814F080545DD130 -:101BB000FFF7BEFF204603B0F0BD01240B6804F11F -:101BC000180C002BB8BFDB004FEA0C1CB4BF43F06D -:101BD00004035B0545F80C300B680FFA84FC13F026 -:101BE000804F18BF05EB0C1E05EB0C1C1EBFDEF86A -:101BF000803143F00203CEF880310B7BCCF8843186 -:101C000005EB04158B68C5F88C314B68C5F8883135 -:101C1000DCF8803143F00103CCF8803100EB44154F -:101C200041F268031D4403EB44130344C5E9002655 -:101C300008330D4601F10C0C55F804EB43F804EBA6 -:101C40006545F9D184342D881D8000EB441407F0DC -:101C50000303257925F00B052B432371FFF768FF5C -:101C60000097334600F0E0FC0120A4E70224A5E73A -:101C70004FF0FF309FE7000013B500F5805401914D -:101C8000E06DFFF74BFE1F280AD90199E06D202275 -:101C9000FFF7BAFEA0F120035842584102B010BD30 -:101CA0000020FBE708B500F58050FFF73BFFC06D53 -:101CB000FFF708FEBDE80840FFF73ABF00220260C8 -:101CC000828142608260704710B500220023C0E923 -:101CD00000230023044603810C30FFF7EFFF20466A -:101CE00010BD0000F0B5054600F580500C4690F898 -:101CF000C83013F0040FC3F3800108BF114661F32D -:101D0000820304F1840680F8C83005EB461389B0DD -:101D10001B79D8072ED57AB319072DD46846FFF75B -:101D2000D3FF05EB441303F5835303F1180703AA0C -:101D3000103318685968144603C40833BB4222465E -:101D4000F7D1186820609B88A380DDE90E23CDE9D8 -:101D500000230123ADF808302B686946DB6B284669 -:101D6000984705EB46152B791A075CBF43F008032B -:101D70002B7101E0002AF4D109B0F0BD2DE9F04744 -:101D8000074688B007F5805468469A468846FFF7AC -:101D9000C9FE9146FFF798FFE06DFFF7A5FD1F28EC -:101DA00029D9E06D20226946FFF7B0FE202822D114 -:101DB00003AD444605AB2E4603CE9E4220606160D3 -:101DC000354604F10804F6D130682060B388A3805A -:101DD000DDE90023C9E90023BDF80830AAF8003086 -:101DE000FFF7A6FE4A4653464146384608B0BDE8CE -:101DF000F04700F007BCFFF79BFE002008B0BDE8ED -:101E0000F08700002DE9F84F0023C0E90133254B8E -:101E1000044640F8183B0F46FFF750FF04F1280036 -:101E2000FFF752FF04F1480804F58255464608358D -:101E300030462036FFF748FFAE42F9D104F5805511 -:101E40004FF480534FF00009C5E91339C5F84880B5 -:101E50000123EE6504F5875804F58456C5F85490BF -:101E600085F8583085F86030083608F108084FF0DA -:101E7000000A4FF0000B46E908ABA6F11800FFF787 -:101E80001DFF203646F8289C4645F4D185F8C970D8 -:101E900017B1054800F0A0FB044B63612046BDE884 -:101EA000F88F00BF404A0008184A0008006400404C -:101EB00010B5044B197804464A1C1A70FFF7A2FFAC -:101EC000204610BD143800202DE9F047002950D0DD -:101ED000294B2A4FB7FBF1F599428CBF0A231123F6 -:101EE000581EB5FBF3FC03FB1C53C4B22BB10228F4 -:101EF0000346F5D80020BDE8F0870CF1FF36B6F5B3 -:101F0000806FF7D2C4EBC40E0EF103034FEAE3096E -:101F1000C3F3C703A4EB030809F1010A4FF47A7570 -:101F20005FFA88F009FB05555AFA88F8B5FBF8F511 -:101F3000B5F5617FC1BF0EF1FF33C3F3C703E01AEC -:101F4000C0B25C1C50FA84F40CFB04F4B7FBF4F44C -:101F5000A142CFD1013BDBB20F2BCBD80138C0B2AD -:101F60000728C7D80021107116809170D370012006 -:101F7000C1E70846BFE700BF3F420F0000512502FE -:101F800070B505460E464FF47A746B695B6803F0D2 -:101F90000103B3424FF0010004D001F0A5FC013C65 -:101FA000F3D1204670BD000030B54269936913F04B -:101FB000700F16D000230B4C936103F1840200EBE9 -:101FC000421211794D0709D5890707D5416954F89F -:101FD00023508D60117941F0040111710133032BFD -:101FE000EBD130BD2C4A000873B51D464369164637 -:101FF0009A68D207044609D59A6801219960C2F30C -:102000004002CDE900650021FFF76CFE63699A6824 -:10201000D1050BD59A684FF480719960C2F34022C4 -:10202000CDE9006501212046FFF75CFE63699A68EF -:10203000D2030BD59A684FF480319960C2F34042C5 -:10204000CDE9006502212046FFF74CFE204602B094 -:10205000BDE87040FFF7A8BFF8B5044646690029FF -:102060006CD106F10C07386880076AD006EB0115C1 -:102070003868D5F8B00110F0040FD5F8B0011ABFD8 -:10208000C00840F00040400DA061D5F8B0C11CF080 -:10209000020F1CBF40F08040A061D5F8B40106EBF0 -:1020A000011100F00F0084F82400D1F8B801207766 -:1020B000D1F8B801000A6077D1F8B801000CA07718 -:1020C000D1F8B801000EE077D1F8BC0184F8200007 -:1020D000D1F8BC01000A84F82100D1F8BC01000C41 -:1020E00084F82200D1F8BC11090E84F8231038219D -:1020F000396004F1340004F1180104F1240551F8A9 -:10210000046B40F8046BA942F9D109880180C4E945 -:102110000A2321460023238651F8283B2046DB6B07 -:10212000984704F58052204692F8C83043F00403E3 -:1021300082F8C830BDE8F840FFF736BF06F1100757 -:1021400091E7F8BD10B5044600F04EFA02460B4682 -:1021500052EA030102D0013A63F10003044908681E -:1021600020B12146BDE81040FFF776BF10BD00BF8B -:1021700010380020F8B500F583511E46FFF7D2FC59 -:10218000DFF844C00831002404F1840500EB451554 -:102190002B795F070ED4DB060CD5D1E9007397428B -:1021A000B34107D243695CF824709F602B7943F0F8 -:1021B00004032B710134032C01F12001E4D1BDE8AB -:1021C000F840FFF7B5BC00BF2C4A000808B5FFF780 -:1021D000A9FCFFF7E9FEBDE80840FFF7A9BC000035 -:1021E000F8B543690546986800F0E050B0F1E05F4B -:1021F0000F461FD0E8B1FFF795FC05F58354103466 -:10220000002606F1840305EB43131B791A0706D554 -:102210000136032E04F12004F3D1012007E05B070F -:10222000F6D42146384600F039FA0028F0D1FFF7FD -:102230007FFCF8BD0120FCE700F5805008B5FFF7F2 -:1022400071FCC06DFFF750FBFFF772FC43090CBF38 -:102250000120002008BD0000F8B51D4600231370C2 -:102260000F4606461446FFF7E7FF80F0010038707E -:1022700025B129463046FFF7B3FF2070F8BD0000B6 -:102280002DE9B8410C4615461F46804600F0ACF9D2 -:102290000B462178024609B9287850B14046FFF72D -:1022A00069FFFFF793FF3B462A462146FFF7D4FF1D -:1022B0000120BDE8B881000010B5FFF733FC174BD3 -:1022C000DA6942F00072DA611A6942F000721A614A -:1022D0001A6900F5805422F000721A61FFF728FC99 -:1022E00094F8C830DB0718D4B9B103211320FFF7E5 -:1022F00019FC01F0C7F90321142001F0C3F90321EF -:10230000152001F0BFF994F8C83043F0010384F8B8 -:10231000C830BDE81040FFF70BBC10BD00100240F4 -:102320002DE9F04700F5805588B095F8C930012BAC -:102330000446884616467FD8804F57F823200AB9AE -:1023400047F82300D7F800A0C4F80C802674BAF12F -:10235000000F63D095F8C930012B6FD001212046C2 -:10236000FFF7AAFFFFF7DEFB6269136823F00203A1 -:1023700013606269136843F0010313606369002707 -:102380005F6101212046FFF7D3FBFFF7F9FD00282D -:1023900000F09580E86DFFF795FA04F58359BA4689 -:1023A00009F10809202200216846FEF7C7FF02A8AC -:1023B000FFF784FCCDF818A06A4609EB07030DF17E -:1023C000180E9446BCE80300F44518605960624654 -:1023D00003F10803F5D1DCF80000186020379CF801 -:1023E00004201A71602FDDD195F8C8306FF3820395 -:1023F000002785F8C8306A4641462046ADF800708F -:10240000ADF802708DF80470FFF75EFD636948BB9C -:102410004FF400421A6008B0BDE8F08741F2D000E6 -:1024200002F01CFA814610B15146FFF7EBFCC7F8E9 -:102430000090B9F1000F8DD10020ECE738680368F7 -:102440001B6B98470146002888D13868FFF734FF96 -:102450003868036832465B684146984700287FF435 -:102460007DAFE9E761221A609DF802309DF80320F4 -:102470001B06120402F4702203F040731343BDF8EC -:102480000020C2F3090213439DF804201205022E16 -:1024900002F4E0020CBF4FF00041002113436269D7 -:1024A0000B43D361636913225A616269136823F095 -:1024B0000103136039462046FFF762FD08B96369DE -:1024C000A6E795F8C93093BB6169D1F8002242F0C4 -:1024D0000102C1F800226169D1F8002222F47C5285 -:1024E00022F00E02C1F800226169D1F8002242F404 -:1024F0006062C1F800226269C2F814326269C2F8EF -:102500000432626941F6FF71C2F80C126269C2F8C6 -:1025100040326269C2F8443263690122C3F81C2266 -:102520006269D2F8003223F00103C2F8003295F854 -:10253000C83043F0020385F8C8306CE7103800203B -:1025400008B500F051F850EA0103024602D0421EDD -:1025500061F10001044B186810B10B46FFF744FD10 -:10256000BDE8084001F064B81038002008B500202C -:10257000FFF7E8FDBDE8084001F05AB808B50120B2 -:10258000FFF7E0FDBDE8084001F052B800B59BB090 -:10259000EFF3098168226846FEF7BEFEEFF305837C -:1025A000014B9B6BFEE700BF00ED00E008B5FFF7B5 -:1025B000EDFF000000B59BB0EFF30981682268468B -:1025C000FEF7AAFEEFF30583014B5B6BFEE700BF4E -:1025D00000ED00E0FEE700000FB408B5029801F03E -:1025E00019F9FEE701F02EBB01F004BB13B56C46F0 -:1025F00084E80600031D94E8030083E80500012039 -:1026000002B010BD73B58568019155B11B885B0799 -:1026100007D4D0E900369B6B9847019AC1B2304687 -:10262000A847012002B070BDF0B5866889B00546A4 -:102630000C465EB1BDF838305B070AD4D0E90037EC -:102640009B6B98472246C1B23846B047012009B07B -:10265000F0BD00220023CDE900230023ADF80830AF -:102660000A4603AB01F10806106851681C4603C412 -:102670000832B2422346F7D1106820609288A280C7 -:10268000FFF7B2FF0423ADF808302B68CDE9000155 -:10269000DB6B694628469847D8E7000030B50368E9 -:1026A0000968DD0FB5EBD17F23F0604421F0604273 -:1026B0004FEAD1700BD0002BB8BFA40C0029B8BFD3 -:1026C000920C944202D034BF0120002030BD9442CD -:1026D00005D1C1F38070C3F380738342F6D1944275 -:1026E0002CBF00200120F1E72DE9F041456A15B922 -:1026F0004162BDE8F0814B6823F06047C3F38A462E -:102700004FEAD37EC3F3807816EA230638BF3E46ED -:10271000AC462B465A68BEEBD27F22F060440AD00A -:10272000002A18DAA40CB44217D19D420FD10D60D3 -:10273000DEE71346EEE7A74207D102F08044C2F37A -:10274000807242450BD054B1EFE708D2EDE7CCF8E8 -:1027500000100B60CDE7B44201D0B442E5D81A684E -:102760009C46002AE5D11960C3E700002DE9F04737 -:10277000089D01F007044FEAD508224405F007053B -:1027800000EBD1004FF47F49944201D1BDE8F087BE -:1027900004F0070705F0070A57453E4638BF56467E -:1027A000C6F10806111B8E4228BF0E46E10808EB51 -:1027B000D50E415C13F80EC0B94029FA06F721FA8C -:1027C0000AF1FFB28CEA010147FA0AF739408CEAB4 -:1027D000010C03F80EC034443544D5E780EA0120EB -:1027E000082341F2210201B24000002980B203F126 -:1027F000FF33B8BF504013F0FF03F4D1704700001F -:1028000038B50C468D18A54200D138BD14F8011B0F -:10281000FFF7E4FFF7E7000042684AB1136843603E -:102820004389818901339BB29942438138BF8381B7 -:102830001046704770B588B0202204460D466846A1 -:102840000021FEF77BFD20460495FFF7E5FF0246D9 -:1028500058B16B46054608AE1C4603CCB44228600E -:102860006960234605F10805F6D1104608B070BD31 -:10287000082817D909280CD00A280CD00B280CD00E -:102880000C280CD00D280CD00E2814BF402030206E -:1028900070470C2070471020704714207047182094 -:1028A0007047202070470000082817D90C280CD941 -:1028B00010280CD914280CD918280CD920280CD988 -:1028C00030288CBF0F200E207047092070470A2047 -:1028D00070470B2070470C2070470D207047000098 -:1028E0002DE9F843078C072F04461ED9D0E902983A -:1028F00000254FF6FF73C5F12006A5F1200029FA47 -:1029000005F108FA06F628FA00F031430143C9B28E -:102910001846FFF763FF0835402D0346EBD1E16908 -:102920003A46BDE8F843FFF76BBF4FF6FF70BDE8CE -:10293000F883000010B54B6823B9CA8A63F3090213 -:10294000CA8210BD04691A681C600361C38A013B16 -:10295000C3824A60EFE700002DE9F84F1D46CB8A9D -:102960000F46C3F309010529814692460B4630D034 -:102970000020AAB207F11A049EB2042E1FFA80F8B2 -:102980000FD8904503F1010306D3FB8A0A4462F392 -:102990000903FB8201201AE01AF80060E6540130B6 -:1029A000EAE79045F1D2A1F1050B1C237C68BBFB43 -:1029B000F3F203FB12BB1FFA8BF6002C45D14846FD -:1029C000FFF72AFF044638B978606FF00200BDE8CF -:1029D000F88F4FF00008E6E7002606607860ADB299 -:1029E0004FF0000B454510D90AEB0803221D13F8E0 -:1029F000011B9155B1B208F101081B291FFA88F893 -:102A00002BD0454506F10106F1D8FB8AC3F3090234 -:102A1000154465F30903BCE7013292B21C462368F2 -:102A2000002BF9D16B1F0B441C21B3FBF1F30133D5 -:102A30009BB29A42D3D2BBF1000FD0D14846FFF7E8 -:102A4000EBFE20B9C4F800B0BFE70122E7E7C0F809 -:102A500000B05E4620600446C1E74545D5D94846EA -:102A6000FFF7DAFE08B92060AFE7C0F800B0002633 -:102A700020600446B6E700002DE9F04F2DED028BF3 -:102A80001C4683B05B69019207468846002B00F024 -:102A90009A80238C2BB1E269002A00F09480072BE6 -:102AA00035D807F10C00FFF7B7FE054638B96FF0CF -:102AB0000205284603B0BDEC028BBDE8F08F14225E -:102AC0000021FEF73BFC228CE16905F10800FEF7CE -:102AD00023FC208C013080B2FFF7E6FEFFF7C8FE32 -:102AE000013880B22084013028746369228C1B78FD -:102AF0002A4403F01F0363F03F0348F000411372C0 -:102B0000384669602946FFF7EFFD0125D1E700F15E -:102B10000C034FF0000908EE103A4FF0800A4E46C1 -:102B20004D4618EE100AFFF777FE83460028BED008 -:102B300014220021FEF702FC002E3AD1019BABF8D3 -:102B4000083002220BF1080E1FFA82FC0CF1010082 -:102B5000BCF1060F218C80B201D88E422BD3FFF737 -:102B6000A3FEFFF785FE62691278013802F01F02AA -:102B70008E4208BF4FF0400A42EA49121BFA80F128 -:102B80004AEA020A013048F0004281F808A08BF8B6 -:102B90001000CBF8042059463846FFF7A5FD238CDA -:102BA0000135B3422DB289F001094FF0000AB8D1C6 -:102BB0007FE70022C6E7E169895D0EF80210013661 -:102BC000B6B20132C0E76FF0010572E7F8B51546FD -:102BD0000E463022002104461F46FEF7AFFB069B3F -:102BE0006360B5F5001F079BA76034BF6A094FF605 -:102BF000FF72A36297B2E66104F1100000239A42CB -:102C000006D800230360A782E3822383E360F8BD34 -:102C10000660013330462036F1E7000003781BB927 -:102C20004BB2002BC8BF017070470000007870479E -:102C3000F8B50C46C969074611B9238C002B37D16A -:102C4000257E1F2D34D8387828BB228C072A2CD813 -:102C5000268A36F003032BD14FF6FF70FFF7D0FD25 -:102C600020F001003102400441EA0561400C41EAD4 -:102C700040254FF6FF72234629463846FFF7FCFEF3 -:102C8000002807DD626913780133DBB21F2B88BF90 -:102C900000231370F8BD218A2D0645EA012505435E -:102CA0002046FFF71DFE0246E5E76FF00300F1E75F -:102CB0006FF00100EEE7000070B58AB004461646DA -:102CC0000021282268461D46FEF738FBBDF8383043 -:102CD000ADF810300F9B05939DF840308DF81830FB -:102CE000119B07936946BDF84830ADF82030204667 -:102CF000CDE90265FFF79CFF0AB070BD2DE9F041F8 -:102D0000D36905460C4616460BB9138C5BBB377E60 -:102D10001F2F28D895F80080B8F1000F26D0304634 -:102D2000FFF7DEFD3378210241EAC33141EA0801B1 -:102D3000338A41EA076141EA03410246334641F0E2 -:102D400080012846FFF798FE00280ADD3378012B22 -:102D500007D1726913780133DBB21F2B88BF0023C0 -:102D60001370BDE8F0816FF00100FAE76FF0030027 -:102D7000F7E70000F0B58BB004460D46174600217A -:102D8000282268461E46FEF7D9FA9DF84C305A1E96 -:102D9000534253418DF800309DF84030ADF810306B -:102DA000119B05939DF848308DF81830149B0793BC -:102DB0006A46BDF85430ADF8203029462046CDE9AA -:102DC0000276FFF79BFF0BB0F0BD0000406A00B138 -:102DD00004307047436A1A68426202691A600361EC -:102DE000C38A013BC38270472DE9F041D0F82080AF -:102DF000194E14461D464146002709B9BDE8F08129 -:102E0000D1E90223A21A65EB0303964277EB030391 -:102E10001ED2036A8B420DD1FFF78CFD036A1B683B -:102E2000036203690B60C38A0161016A013BC382CB -:102E30008846E2E7FFF77EFD0B68C8F800300369BB -:102E40000B60C38A0161013BC382D8F80010D4E74C -:102E500088460968D1E700BF80841E002DE9F04F45 -:102E60008BB00D46DDF8509014469B4680460028F6 -:102E700000F01981B9F1000F00F01581531E3F2BAE -:102E800000F21181012A03D1BBF1000F40F00B8148 -:102E90000023CDE90833B8F81430B5EBC30F4FEA7F -:102EA000C30703D300200BB0BDE8F08F2B199F425E -:102EB000D8F80C303ABF7F1BFFB227461BB9D8F8B1 -:102EC0001030002B7AD0272D4ED8C5F12806B742F6 -:102ED0004FF000032CBFF6B23E4600932946D8F8C7 -:102EE000080008AB3246FFF741FCA7EB060A354461 -:102EF0005FFA8AFAB8F8143003F10053053BDB009F -:102F00000493D8F80C3003932821039B13B1BAF132 -:102F1000000F2CD1D8F8100040B1BAF1000F05D045 -:102F2000009608AB5246691AFFF720FC38B2002F12 -:102F3000B8D066070AD00AAB03EBD401624211F89D -:102F4000083C02F00702134101F8083C082C3CD968 -:102F5000102C40F2B580202C40F2B780BBF1000F5E -:102F600000F09C80082334E0BA460026C2E7049BA8 -:102F7000E02B28BFE02306930B44AB42059314D902 -:102F80005A1B03980096924534BF5246D2B2691A32 -:102F900008AB04300792FFF7E9FB079A1644AAEB47 -:102FA000020A1544F6B25FFA8AFA049B069A05995A -:102FB0009B1A0493039B1B680393A6E70093D8F81E -:102FC000080008AB3A462946AEE7BBF1000F13D024 -:102FD0000123B4EBC30F6CD0082C12D89DF820301D -:102FE000621E23FA02F2D50706D54FF0FF3202FA2D -:102FF00004F423438DF820309DF8203089F8003008 -:1030000051E7102C12D8BDF82030621E23FA02F2CC -:10301000D10706D54FF0FF3202FA04F42343ADF88E -:103020002030BDF82030A9F800303CE7202C0FD824 -:103030000899631E21FA03F3DA0705D54FF0FF3232 -:1030400002FA04F40C430894089BC9F800302AE7FC -:10305000402C2BD0DDE90865611EC4F12102A4F1EA -:10306000210326FA01F105FA02F225FA03F31143CE -:103070001943CB0712D50122A4F12003C4F120018A -:1030800002FA03F322FA01F1A240524243EA010399 -:1030900063EB430332432B43CDE90823DDE90823E7 -:1030A000C9E90023FFE66FF00100FCE66FF00800BD -:1030B000F9E6082CA0D9102CB3D9202CEED8C3E700 -:1030C000BBF1000FADD0022383E7BBF1000FBBD0F3 -:1030D00004237EE730B5012A144638BF0124402C72 -:1030E00085B028BF40240025012ACDE9025518D813 -:1030F0001B788DF8083063070AD004AB03EBD405C6 -:10310000624215F8083C02F00702934005F8083CBB -:10311000009103462246002102A8FFF727FB05B0D5 -:1031200030BD082AE4D9102A03D81B88ADF808302E -:10313000E1E7202A8DBFD3E900231B680293CDE984 -:103140000223D8E710B5CB681BB98B600B618B826B -:1031500010BD04691A681C600361C38A013BC38205 -:10316000CA60F0E703064CBFC0F3C03002207047CE -:1031700008B50246FFF7F6FF022806D15306C2F350 -:103180000F2001D100F0030008BDC2F30740FBE7A8 -:103190002DE9F04F93B0CDE903230A6804461046A9 -:1031A000FFF7E0FF022814BFC2F306260026002A1C -:1031B0000D46824680F2F28112F0C04940F0EE8165 -:1031C000097B002900F0EA81022803D02378B3426A -:1031D00040F0E781C2F304630693104602F07F03D8 -:1031E0000593FFF7C5FF059B29444FEA834848EA4A -:1031F0000A4848EA4668CE7800230022CDE9082331 -:10320000F309834648EA0008029367D0059B0093C0 -:1032100002466768534608A92046B847002800F0D0 -:10322000C381276A4FB9414604F10C00FFF702FB46 -:10323000074690B96FF0020054E03B6998450DD005 -:103240003F68002FF9D1414604F10C00FFF7F2FA74 -:1032500007460028EED0236A3B60276297F817C024 -:1032600006F01F08CCF3840CACEB08001FFA80FEBC -:103270000028B8BF0EF12000A8EB0C031FFA83FE54 -:10328000D7E90221B8BF00B2002B0793BEBF0EF1F1 -:1032900020031BB2079352EA010338D0039BDFF8E7 -:1032A00024E39A1A049B4FF0000C63EB010196454E -:1032B0007CEB01032BD36B7B97F81AE0734519D194 -:1032C000029B002B78D0012821DC7868F8B9DFF860 -:1032D000F0C2944570EB010316D337E0276A27B993 -:1032E0006FF00C0013B0BDE8F08F3B699845B5D086 -:1032F0003F68F4E7B24890427CEB010301D3002021 -:10330000F0E7029B002BFAD0079B0F2B17DCFA7D0E -:10331000B30002F0030203F07C031343FB7539464C -:103320002046FFF707FB6B7BBB76029B3BB9FB7D1F -:10333000C3F38402013262F38603FB75D0E76A7B34 -:10334000BB7E9A42DBD1029B002B35D0B309022B06 -:1033500032D0039BBB60049BFB60142200210DA8AC -:10336000FDF7ECFF039B0A93049B0B932B1D0C931F -:103370002B7BADF83EB0013BDBB2ADF83C30069B99 -:103380008DF84230059B8DF8433094F82C308DF841 -:1033900040A083F001038DF844308DF84180A3688C -:1033A0000AA920469847FB7DC3F38403013303F049 -:1033B0001F039B02FB82A2E7FB7DC6F34012B2EB28 -:1033C000D31F40F0F480C3F38403434540F0F28000 -:1033D000029A2B7BB609002A4DD0F2075DD4032B4D -:1033E00040F2EB80039BBB60049BFB602B7BAE1D1C -:1033F000033BDBB23246394604F10C00FFF7ACFA6E -:1034000000280CDA39462046FFF794FAFB7DC3F317 -:103410008403013303F01F039B02FB820AE7DDE90B -:103420000884AB883B834FF6FF73C9F12000A9F1F4 -:10343000200228FA09F104FA00F0014324FA02F20A -:1034400011431846C9B2FFF7C9F909F10809B9F1E2 -:10345000400F0346E9D1B8822A7B033AD2B2314603 -:10346000FFF7CEF9FB7DB882DA43C2F3C01262F3F4 -:10347000C713FB7543E786B92E1D013BDBB232460D -:10348000394604F10C00FFF767FA0028BADB2A7B03 -:10349000B88A013AD2B23146E2E7F98AC1F30901AA -:1034A000013B0429DAB25BD8281D002307F11B0673 -:1034B0009A4208D910F801CB06F801C00131013356 -:1034C0000529DBB2F4D103990A9104990B91934237 -:1034D00007F11B010C9138BF043379680D9134BF9B -:1034E00055FA83F300230E93FB8AADF83EB0C3F385 -:1034F00009031A44069B8DF84230059B8DF8433032 -:1035000094F82C30ADF83C2083F001038DF8443062 -:1035100000238DF840A08DF841807B602A7BB88A1B -:10352000013A291DFFF76CF93B8BB882834203D126 -:10353000A3680AA92046984720460AA9FFF702FE79 -:10354000FB7DBA8AC3F38403013303F01F039B029C -:10355000FB823B8B9A420CBF00206FF01000C1E64B -:103560007B68002BAFD0052001E01C3033461E687D -:10357000002EFAD1091A081D2E1D184401EB090C62 -:10358000BCF11B0F5FFA89F39DD89A429BD916F8BC -:10359000013B00F8013B09F10109EFE76FF0090079 -:1035A000A0E66FF00A009DE66FF00B009AE66FF060 -:1035B0000D0097E66FF00E0094E66FF00F0091E6B5 -:1035C00040420F0080841E00EFF3098305494A6BD7 -:1035D00022F001024A63683383F30988002383F3EE -:1035E0001188704700EF00E0302080F3118862B648 -:1035F0000C4B0D4AD96821F4E0610904090C0A4317 -:10360000DA60D3F8FC20094942F08072C3F8FC204C -:103610000A6842F001020A602022DA7783F8220069 -:10362000704700BF00ED00E00003FA05001000E065 -:1036300010B5302383F311880E4B5B6813F40063DD -:1036400014D0F1EE103AEFF30984683C4FF0807328 -:10365000E361094BDB6B236684F3098800F098F87B -:1036600010B1064BA36110BD054BFBE783F3118836 -:10367000F9E700BF00ED00E000EF00E003060008FE -:103680000606000800F1604303F561430901C9B271 -:1036900083F80013012200F01F039A4043099B00A6 -:1036A00003F1604303F56143C3F880211A6070475A -:1036B00000F16040090100F56D40C9B20176704724 -:1036C00000230375826803691B6899689142FBD2E5 -:1036D0005A680360426010605860704700230375A9 -:1036E000826803691B6899689142FBD85A68036035 -:1036F000426010605860704708B50846302383F375 -:1037000011880B7D032B05D0042B0DD02BB983F32F -:10371000118808BD8B6900221A604FF0FF33836166 -:10372000FFF7CEFF0023F2E7D1E9003213605A60C1 -:10373000F3E70000FFF7C4BF054BD96808751868A8 -:1037400002681A60536001220275D860FCF744BF1A -:103750002038002030B50C4BDD684B1C87B0044688 -:103760000FD02B46094A684600F0FEF82046FFF7C6 -:10377000E3FF009B13B1684600F000F9A86907B0A9 -:1037800030BDFFF7D9FFF9E720380020F9360008EF -:10379000044B1A68DB6890689B68984294BF0020CD -:1037A0000120704720380020084B10B51C68D868ED -:1037B00022681A60536001222275DC60FFF78EFFD9 -:1037C00001462046BDE81040FCF706BF2038002027 -:1037D000044B1A68DB6892689B689A4201D9FFF72C -:1037E000E3BF70472038002038B5074C0749084828 -:1037F000012300252370656000F00AFB022323707B -:1038000085F3118838BD00BF483A0020844A00087B -:103810002038002008B572B6044B186500F0CEF9C8 -:1038200000F092FA024B03221A70FEE720380020C3 -:10383000483A002000F0B4B8EFF3118020B9EFF35C -:103840000583302282F311887047000010B530B92B -:10385000EFF30584C4F3080414B180F3118810BD9C -:10386000FFF7B6FF84F31188F9E700008B600223AD -:1038700008618B82084670478368A3F1840243F88D -:10388000142C026943F8442C426943F8402C094A3D -:1038900043F8242CC26843F8182C022203F80C2C9D -:1038A000002203F80B2C044A43F8102CA3F120004B -:1038B000704700BFF10500082038002008B5FFF769 -:1038C000DBFFBDE80840FFF735BF0000024BDB68B7 -:1038D00098610F20FFF730BF20380020302383F39A -:1038E0001188FFF7F3BF000008B50146302383F3CA -:1038F00011880820FFF72EFF002383F3118808BDED -:10390000064BDB6839B1426818605A601360436047 -:103910000420FFF71FBF4FF0FF3070472038002012 -:103920000368984206D01A68026050609961184690 -:10393000FFF700BF7047000010B50A4C23699A6872 -:1039400091420CD85A6881600360426010609A68A6 -:103950005860511A99604FF0FF33A36110BD1B6886 -:10396000891AECE72038002010B4C0E903230023B3 -:103970005DF8044B4361FFF7DFBF00000368816817 -:103980009A680A449A60426813605A600023036090 -:10399000024B4FF0FF329A61704700BF2038002081 -:1039A00070B5124DEB692A460133EB6152F8103FB6 -:1039B000934206D09A68013A9A6030262C69A3682F -:1039C00003B170BDD4E900210A605160236083F324 -:1039D0001188D4E903312046984786F3118861693C -:1039E0000029EBD02046FFF7A7FFE7E720380020AB -:1039F00000207047FEE70000704700004FF0FF30E6 -:103A000070470000BFF34F8F024AD368DB07FCD436 -:103A1000704700BF0020024008B5074B1B7853B920 -:103A2000FFF7F0FF054B1A69120641BF044A5A60BE -:103A300002F188325A6008BD603A0020002002403E -:103A40002301674508B5054B1B7833B9FFF7DAFF4B -:103A5000034A136943F08003136108BD603A0020F4 -:103A6000002002407F289ABF00F58030C00200206D -:103A7000704700004FF400607047000080207047DE -:103A80007F2808B50BD8FFF7EDFF00F5006302684B -:103A9000013204D104308342F9D1012008BD002055 -:103AA000FCE700007F2810B504461CD8FFF7AAFFEA -:103AB000FFF7B2FF0D4BF322DA6002221A61FFF723 -:103AC000D1FF58611A6942F040021A614FF4006157 -:103AD000FFF798FF00F034F9FFF7B4FF2046BDE888 -:103AE0001040FFF7CDBF002010BD00BF00200240F6 -:103AF0002DE9F84312F00103144606D01F4B40F2A3 -:103B0000F3221A600020BDE8F88385181C4A95420C -:103B100004D91A4A4FF43E711160F3E7FFF77CFFB6 -:103B2000FFF770FFDFF86880451A4FF00109012C9C -:103B300005EB01060F4603D8FFF784FF0120E2E7FB -:103B40003B88C8F8109033800020FFF75BFFC8F86F -:103B50001000338831F8022B9BB29A420CD0074BED -:103B600040F20F321A60074B1E60074B1C60074B78 -:103B70001F60FFF767FFC6E7023CD8E75C3A00200A -:103B800000000408503A0020583A0020543A00201F -:103B900000200240084908B50B7828B11BB9FFF78F -:103BA0003BFF01230B7008BD002BFCD0BDE8084093 -:103BB0000870FFF747BF00BF603A002008B54FF418 -:103BC00020414FF0005000F0BDF8BDE808404FF430 -:103BD00000514FF0805000F0B5B800000846114683 -:103BE00000F05EBE012000F05BBE0000084600F061 -:103BF00075BE000030B583B0FFF71EFE0E4B0F4DB3 -:103C0000DB692A684FF47A7101FB03F3934237BFF3 -:103C10000B4A0B49516814682B602EBFD1E9004153 -:103C2000013151601C1941F100010191FFF70EFEB5 -:103C30000199204603B030BD20380020643A0020AE -:103C4000683A002030B583B0FFF7F6FD114B124DF6 -:103C5000DB692A684FF47A7101FB03F3934237BFA3 -:103C60000E4A0E49516814682B602EBFD1E90041FD -:103C7000013151601C1941F100010191FFF7E6FD8E -:103C800001994FF47A7200232046FCF791FA03B0B1 -:103C900030BD00BF20380020643A0020683A002080 -:103CA00010B50244064BD2B2904200D110BD441C64 -:103CB00000B253F8200041F8040BE0B2F4E700BF73 -:103CC000502800400F4B30B51C6A240407D41C6AEE -:103CD00044F440741C621C6A44F400441C620A4CA4 -:103CE000236843F4807323600244084BD2B29042AD -:103CF00000D130BD441C00B251F8045B43F82050A1 -:103D0000E0B2F4E70010024000700040502800408C -:103D100007B5012201A90020FFF7C2FF019803B0F7 -:103D20005DF804FB13B50446FFF7F2FFA04205D08F -:103D3000012201A900200194FFF7C4FF02B010BDC9 -:103D4000704700007047000070470000074B45F2C5 -:103D500055521A6002225A6040F6FF729A604CF681 -:103D6000CC421A60024B01221A70704700300040AA -:103D7000743A0020034B1B781BB1034B4AF6AA226E -:103D80001A607047743A002000300040044B1A68F3 -:103D90002AB902F1804202F50432526A1A60704771 -:103DA000703A0020024B4FF080725A62704700BF99 -:103DB0000010024008B5FFF7E9FF024B1868C0F396 -:103DC000407008BD703A002070470000FEE7000018 -:103DD0000A4B0B480B4A90420BD30B4BDA1C121ABE -:103DE000C11E22F003028B4238BF00220021FDF7E2 -:103DF000A5BA53F8041B40F8041BECE7F44B000889 -:103E0000583C0020583C0020583C0020FEE70000B1 -:103E100070B51B4B01630025044686B0586085626F -:103E20000E46FFF7E1FB04F11003C4E904334FF041 -:103E3000FF33A361134BE561D969A5600A462B46A0 -:103E4000C4E9082304F13401C4E900440E4AE562E0 -:103E5000256580232046FFF709FD0123E0600B4A1A -:103E60000375009272680192B268CDE90223084B93 -:103E70006846CDE90435FFF721FD06B070BD00BFEF -:103E8000483A002020380020904A0008954A00084F -:103E90000D3E00084B6843608B688360CB68C3604D -:103EA0000B6943614B6903628B6943620B68036072 -:103EB0007047000008B51B4B9A6A42F4FC029A62F4 -:103EC0009A6A22F4FC029A629A6A5A6942F4FC02E3 -:103ED0005A61154A5B6911464FF09040FFF7DAFFCF -:103EE00002F11C0100F58060FFF7D4FF02F13801F8 -:103EF00000F58060FFF7CEFF02F1540100F580600D -:103F0000FFF7C8FF02F1700100F58060FFF7C2FF04 -:103F100002F18C0100F58060FFF7BCFFBDE80840AE -:103F200000F05AB8001002409C4A000808B500F0A2 -:103F300093F9FFF759FCBDE80840FFF727BF0000E1 -:103F40007047000010B5214CA36A63F4FC03A36220 -:103F5000A36A03F4FC03A3624FF0FF32A36A236950 -:103F600022612369002323612169E168E260E2683C -:103F7000E360E268E269164942F08052E261E26978 -:103F80000A6842F480720A60226A02F44072B2F552 -:103F9000407F1EBF4FF4803222622362236A1B04DB -:103FA00007D4236A43F440732362236A43F4004333 -:103FB000236200F031F9A369064A43F00103A361CB -:103FC000A369136843F02003136010BD0010024082 -:103FD00000700040000001401E4B1A6842F00102D0 -:103FE0001A601A689007FCD55A6822F003025A60DA -:103FF0005A6812F00C02FBD1196801F0F90119603E -:104000005A601A6842F480321A601A689103FCD52B -:10401000114A5A604FF40452DA6230221A631A6865 -:1040200042F080721A601A689201FCD50B49122284 -:104030000A600A6802F00702022AFAD15A6842F0BE -:1040400002025A605A6802F00C02082AFAD11A6B6E -:104050001A6370470010024000241D000020024037 -:10406000084A08B5516913680B4003F00103536116 -:1040700023B1054A13680BB150689847BDE8084062 -:10408000FFF7D6BA00040140783A0020084A08B584 -:10409000516913680B4003F00203536123B1054AD1 -:1040A00093680BB1D0689847BDE80840FFF7C0BAE5 -:1040B00000040140783A0020084A08B551691368A5 -:1040C0000B4003F00403536123B1054A13690BB19C -:1040D00050699847BDE80840FFF7AABA00040140BC -:1040E000783A0020084A08B5516913680B4003F07C -:1040F0000803536123B1054A93690BB1D06998470E -:10410000BDE80840FFF794BA00040140783A002067 -:10411000084A08B5516913680B4003F01003536156 -:1041200023B1054A136A0BB1506A9847BDE80840AD -:10413000FFF77EBA00040140783A0020174B10B513 -:104140005A691C68144004F478725A61A30604D5B5 -:10415000134A936A0BB1D06A9847600604D5104A97 -:10416000136B0BB1506B9847210604D50C4A936B27 -:104170000BB1D06B9847E20504D5094A136C0BB11B -:10418000506C9847A30504D5054A936C0BB1D06CCD -:104190009847BDE81040FFF74BBA00BF000401404C -:1041A000783A00201A4B10B55A691C68144004F480 -:1041B0007C425A61620504D5164A136D0BB1506DED -:1041C0009847230504D5134A936D0BB1D06D9847DA -:1041D000E00404D50F4A136E0BB1506E9847A1044A -:1041E00004D50C4A936E0BB1D06E9847620404D587 -:1041F000084A136F0BB1506F9847230404D5054A42 -:10420000936F0BB1D06F9847BDE81040FFF710BA1D -:1042100000040140783A0020062108B50846FFF75F -:1042200031FA06210720FFF72DFA06210820FFF7B3 -:1042300029FA06210920FFF725FA06210A20FFF7AF -:1042400021FA06211720FFF71DFABDE808400621D4 -:104250002820FFF717BA000008B5FFF773FE00F03B -:1042600067F800F03DF8FFF76BFEBDE8084000F08E -:104270005DB80000026843681143016003B118474C -:1042800070470000143000F02FBA00004FF0FF33E9 -:10429000143000F029BA0000383000F0A5BA000050 -:1042A0004FF0FF33383000F09FBA0000143000F0B8 -:1042B000F5B900004FF0FF31143000F0EFB9000005 -:1042C000383000F04FBA00004FF0FF32383000F0C5 -:1042D00049BA0000012914BF6FF013000020704795 -:1042E00000F06CB8044B03600023C0E90233436064 -:1042F00001230374704700BF444B000838B5C369FD -:1043000004460D461BB904210844FFF7B3FF2946B4 -:1043100004F1140000F0A6F9002806DA201D4FF47D -:104320000061BDE83840FFF7A5BF38BD00F00EB80A -:104330000023054A19460133102BC2E9001102F18E -:104340000802F8D1704700BF783A00204FF0E02310 -:10435000044A5A6100229A6107221A6108210B203F -:10436000FFF7A6B93F19010008B5302383F3118880 -:10437000FFF760FA002383F3118808BD08B5FFF743 -:10438000F3FFBDE80840FFF753B900000268436837 -:104390001143016003B1184770470000024A1368D7 -:1043A00043F0C0031360704700380140024A1368AD -:1043B00043F0C003136070470044004037B51D4C04 -:1043C0001D4D2046FFF78EFF009404F114001B4999 -:1043D0000023202200F038F92022009404F1380054 -:1043E000174B184900F0B2F9174BC4E91735174CB1 -:1043F0000C212520FFF746F92046FFF773FF04F153 -:104400001400134900940023202200F01DF904F148 -:104410003800104B10490094202200F097F90F4B00 -:104420000C212620C4E9173503B0BDE83040FFF762 -:1044300029B900BFF83A002000512502D03B0020E6 -:104440009D430008103C002000380140643B0020E0 -:10445000F03B0020AD430008303C00200044004009 -:104460002DE9F047C66D3768F469346221070546C7 -:1044700019D014F0080118BF4FF48071E20748BF4B -:1044800041F02001A30748BF41F04001600748BF49 -:1044900041F08001302383F31188281DFFF776FF58 -:1044A000002383F31188E2050AD5302383F31188B2 -:1044B0004FF48061281DFFF769FF002383F3118803 -:1044C0004FF030094FF0000A14F0200838D13B06B5 -:1044D00016D54FF0300905F1380A200610D589F3BA -:1044E0001188504600F066F9002836DA0821281DA8 -:1044F000FFF74CFF27F080033360002383F311881C -:10450000790614D5620612D5302383F31188D5E9D4 -:1045100013239A4208D12B6C33B11021281D27F0A8 -:104520004007FFF733FF3760002383F31188E3066A -:1045300019D5AA6E1369B3B1BDE8F04750691847A1 -:1045400089F31188B38C95F8641028461940FFF759 -:10455000D5FE8AF31188F469B6E780B2308588F316 -:104560001188F469B9E7BDE8F087000008B5034891 -:10457000FFF776FFBDE80840FFF75AB8F83A002089 -:1045800008B50348FFF76CFFBDE80840FFF750B8D7 -:10459000643B0020F8B5154682680669AA420B46BE -:1045A000816938BF8568761AB54204460BD2184631 -:1045B0002A46FCF7B1FEA3692B44A361A3685B1BE9 -:1045C000A3602846F8BD0CD918463246FCF7A4FE75 -:1045D000AF1BE1683A463044FCF79EFEE3683B447B -:1045E000EBE718462A46FCF797FEE368E5E700008C -:1045F00083689342F7B51546044638BF8568D0E90D -:104600000460361AB5420BD22A46FCF785FE636970 -:104610002B446361A36828465B1BA36003B0F0BD15 -:104620000DD932460191FCF777FE0199E068AF1B86 -:104630003A463144FCF770FEE3683B44E9E72A461A -:10464000FCF76AFEE368E4E710B50A440024C3619E -:10465000029B8460C0E90000C0E90511C1600261ED -:10466000036210BD08B5D0E90532934201D18268DA -:1046700082B98268013282605A1C42611970D0E9A5 -:1046800004329A4224BFC36843610021FFF748F90E -:10469000002008BD4FF0FF30FBE7000070B530236D -:1046A00004460E4683F31188A568A5B1A368A269E4 -:1046B000013BA360531CA36115782269934224BF78 -:1046C000E368A361E3690BB120469847002383F3B5 -:1046D0001188284607E031462046FFF711F90028E7 -:1046E000E2DA85F3118870BD2DE9F74F04460E46D6 -:1046F00017469846D0F81C904FF0300A8AF311887C -:104700004FF0000B154665B12A4631462046FFF7AB -:1047100041FF034660B941462046FFF7F1F8002803 -:10472000F1D0002383F31188781B03B0BDE8F08F2C -:10473000B9F1000F03D001902046C847019B8BF3CD -:104740001188ED1A1E448AF31188DCE7C0E90511CF -:10475000C160C3611144009B8260C0E90000016137 -:1047600003627047F8B504460D461646302383F3BE -:104770001188A768A7B1A368013BA36063695A1CAD -:1047800062611D70D4E904329A4224BFE368636118 -:10479000E3690BB120469847002080F3118807E0B9 -:1047A00031462046FFF7ACF80028E2DA87F311889B -:1047B000F8BD0000D0E905239A4210B501D1826806 -:1047C0007AB98268013282605A1C82611C7803695E -:1047D0009A4224BFC36883610021FFF7A1F82046F5 -:1047E00010BD4FF0FF30FBE72DE9F74F04460E46B2 -:1047F00017469846D0F81C904FF0300A8AF311887B -:104800004FF0000B154665B12A4631462046FFF7AA -:10481000EFFE034660B941462046FFF771F80028D5 -:10482000F1D0002383F31188781B03B0BDE8F08F2B -:10483000B9F1000F03D001902046C847019B8BF3CC -:104840001188ED1A1E448AF31188DCE70B460146F5 -:10485000184600F02DB8000000F040B8012838BF1D -:10486000012010B50446204600F030F830B900F0C1 -:1048700007F808B900F00CF88047F4E710BD000015 -:10488000024B1868BFF35B8F704700BF503C00209D -:1048900008B5062000F084F80120FFF7ABF800000F -:1048A000024B0A4601461868FFF798B91811002014 -:1048B00010B5054C13462CB10A4601460220AFF351 -:1048C000008010BD2046FCE700000000024B0146BE -:1048D0001868FFF787B900BF18110020024B014686 -:1048E0001868FFF783B900BF1811002010B501390F -:1048F0000244904201D1002005E0037811F8014FF5 -:10490000A34201D0181B10BD0130F2E72DE9F041A0 -:10491000A3B1C91A17780144044603F1FF3C8C4245 -:10492000204601D9002009E00578BD4204F10104C8 -:10493000F5D10CEB0405D618A54201D1BDE8F081F4 -:1049400015F8018D16F801EDF045F5D0E7E7000008 -:104950001F2938B504460D4604D9162303604FF0CD -:10496000FF3038BD426C12B152F821304BB92046AD -:1049700000F030F82A4601462046BDE8384000F0F5 -:1049800017B8012B0AD0591C03D11623036001204C -:10499000E7E7002442F82540284698470020E0E752 -:1049A000024B01461868FFF7D3BF00BF1811002063 -:1049B00038B5074D00230446084611462B60FFF723 -:1049C0001DF8431C02D12B6803B1236038BD00BF22 -:1049D000543C0020FFF70CB8034611F8012B03F8F4 -:1049E000012B002AF9D170476F72672E61726475CE -:1049F00070696C6F742E663330332D4D6174656B46 -:104A00004750530040A2E4F1646891060041A3E5D9 -:104A1000F2656992070000004261642043414E49FB -:104A20006661636520696E6465782E008000000011 -:104A30000080000000008000000000000000000076 -:104A40003D1B000821230008812200084D1B00089F -:104A5000811B00087D1D0008511B0008611B000818 -:104A6000551B00085D1B0008591B0008A51C000809 -:104A7000651B0008ED250008751B0008791C00085F -:104A800063300000804A000878380020483A00204F -:104A90006D61696E0069646C65000000A001A82A60 -:104AA00000000000FAAABEAA50001424EFFF000084 -:104AB00000770000709709000000A00000000000CF -:104AC000AAAAFAAA00005000FFFF000000000000A0 -:104AD000007700000000000000000000AAAAAAAAB7 -:104AE00000000000FFFF00000000000000000000C8 -:104AF0000000000000000000AAAAAAAA000000000E -:104B0000FFFF0000000000000000000000000000A7 -:104B100000000000AAAAAAAA00000000FFFF0000EF -:104B20000000000000000000000000000000000085 -:104B3000AAAAAAAA00000000FFFF000000000000CF -:104B40000000000000000000A14200088D420008A3 -:104B5000C9420008B5420008C1420008AD42000841 -:104B60009942000885420008D542000874B6FF7FCC -:104B70000100000000000000EC0300000000000045 -:104B80000098030000000000FE2A0100D20400008B -:104B90001C110020000000000000000000000000C8 -:104BA0000000000000000000000000000000000005 -:104BB00000000000000000000000000000000000F5 -:104BC00000000000000000000000000000000000E5 -:104BD00000000000000000000000000000000000D5 -:104BE00000000000000000000000000000000000C5 -:044BF00000000000C1 +:1000000000090020B1010008ED220008A522000827 +:10001000CD220008A5220008C5220008B30100086F +:10002000B3010008B3010008B3010008E132000881 +:10003000B3010008B3010008B3010008B140000893 +:10004000B3010008B3010008B3010008B3010008C0 +:10005000B3010008B3010008953D0008C13D000848 +:10006000ED3D0008193E0008453E0008B3010008B8 +:10007000B3010008B3010008B3010008B301000890 +:10008000B3010008B3010008B301000859220008B9 +:100090008522000895220008B3010008713E00087F +:1000A000B3010008B3010008B3010008B301000860 +:1000B000B3010008B3010008B3010008B301000850 +:1000C000B3010008B3010008B3010008B301000840 +:1000D000B3010008A1420008B5420008B3010008BE +:1000E000D93E0008B3010008B3010008B3010008BD +:1000F000B3010008B3010008B3010008B301000810 +:10010000B3010008B3010008B3010008B3010008FF +:10011000B3010008B3010008B3010008B3010008EF +:10012000B3010008B3010008B3010008B3010008DF +:10013000B3010008B3010008B3010008B3010008CF +:10014000B3010008B3010008B3010008B3010008BF +:10015000B3010008B3010008B3010008B3010008AF +:10016000B3010008B3010008B3010008B30100089F +:10017000B3010008B3010008B3010008B30100088F +:10018000B3010008B3010008B3010008B30100087F +:10019000B3010008B3010008B3010008B30100086F +:1001A000210F000800000000000000000000000017 +:1001B00002E000F000F8FEE772B6374880F30888E6 +:1001C000364880F3098836483649086040F2000016 +:1001D000CCF200004EF63471CEF200010860BFF39D +:1001E0004F8FBFF36F8F40F20000C0F2F0004EF669 +:1001F0008851CEF200010860BFF34F8FBFF36F8FBD +:100200004FF00000E1EE100A4EF63C71CEF2000114 +:100210000860062080F31488BFF36F8F03F06EFC34 +:1002200003F0E2FC4FF055301F491B4A91423CBF9E +:1002300041F8040BFAE71D49184A91423CBF41F8C6 +:10024000040BFAE71A491B4A1B4B9A423EBF51F86E +:10025000040B42F8040BF8E700201849184A9142B1 +:100260003CBF41F8040BFAE703F04CFC03F0F8FC48 +:10027000144C154DAC4203DA54F8041B8847F9E7D7 +:1002800000F042F8114C124DAC4203DA54F8041B52 +:100290008847F9E703F034BC000900200011002072 +:1002A0000000000808ED00E0000100200009002027 +:1002B000A0480008001100207C11002080110020BF +:1002C000543C0020A0010008A4010008A40100087B +:1002D000A40100082DE9F04F2DED108AC1F80CD0D3 +:1002E000C3689D46BDEC108ABDE8F08F002383F300 +:1002F00011882846A047002003F056F9FEE703F0D6 +:10030000DFF800DFFEE70000F8B500F01BFE03F0A9 +:1003100099FB074603F0E8FB064600283ED12B4B2D +:100320009F423BD001339F423BD0294B27F0FF0235 +:100330009A4239D1F8B200F041FC354642F21074CD +:1003400000F042FC08B10024254601F0B1F878B372 +:10035000032000F043F80024254636B11D4B9F4290 +:1003600003D003F0B9FB00242546002003F074FB02 +:10037000194B1B6913F040031FD00DB100F044F876 +:1003800000F054FC01F0BAFF0546C4B101F0B6FF1D +:10039000401BA04213D900F037F8F3E7354600249C +:1003A000CEE704460125CBE705464FF47A74C7E74C +:1003B000B4F57A7F08BF0125CFE71C46E0E700F0DF +:1003C0007DFC012003F0F6F8DFE700BF010007B075 +:1003D000000008B0263A09B000040048084B187025 +:1003E00003280CD8DFE800F008050208022000F01E +:1003F00005BE022000F0FABD024B00225A60704791 +:10040000801100208411002038B501F051F830B17E +:100410001F4B03221A701F4B00225A6038BD1E4B1F +:100420001E4A19680131F9D004339342F9D11C4CAA +:10043000194DD4F80428AA42F0D31A4B9B6803F153 +:10044000006303F5D0439A42E8D203F019FB03F0AE +:100450002BFB002000F090FD0220FFF7BFFF124BA6 +:10046000DA690022DA61D96999699A619B6972B681 +:100470004FF0E0233021C3F8085DD4F80038D4F8F9 +:10048000042881F311889D4683F308881047C5E747 +:1004900080110020841100200068000820680008F6 +:1004A000006000080011002000100240094A136893 +:1004B00049F2690099B21B0C00FB01331360064B33 +:1004C000186844F2506182B2000C01FB020018600F +:1004D00080B27047141100201011002010B50021C7 +:1004E0001022044600F0A4FD034B03CB20606160A2 +:1004F0001868A06010BD00BFACF7FF1F2DE9F041E8 +:10050000ADF54E7D0DF134086CAC40F27512074626 +:100510000D460EA80021C8F8001000F089FD4FF428 +:10052000C4720021204600F083FD01F0E7FE274B56 +:100530004FF47A72B0FBF2F0186093E807000223E0 +:1005400084E807000DF5E9702382FFF7C7FF4EF638 +:1005500003431F49238406A804F0D8F81B2384F81A +:1005600032310DF2E32206AB0DF1300C1E4603CE04 +:10057000664510605160334602F10802F6D13188B9 +:10058000B3789370118020464146012200F09CFD13 +:1005900000230393AB7E029305F11903019380B20C +:1005A0000123CDE904800093E97E06A3D3E900236B +:1005B000384602F06BFA0DF54E7DBDE8F08100BFC4 +:1005C000AFF300809E6AC421818A46EE8C11002020 +:1005D0001C4700082DE9F0412C4C237ADAB0804604 +:1005E0000D465BBB27A9284600F07EFE0746002883 +:1005F00042D19DF89D60C82E3ED801464FF4A662B8 +:10060000204600F015FD4FF48073C4F8F8314FF424 +:100610000073C4F80C334FF44073C4F820343246EE +:100620000DF19E0104F1090000F0F0FC26449DF854 +:100630009C30777223720BB9EB7E237281220021EA +:1006400006AC27A800F0F4FC0122214627A800F000 +:1006500087FE00230393AB7E029305F1190380B25A +:1006600001932823CDE904400093E97E05A3D3E953 +:100670000023404602F00AFA5AB0BDE8F08100BFFC +:10068000AFF3008026417272DF25D7B7B032002069 +:10069000F0B5254E4FF48A7505FB0065F1B096F86C +:1006A000D83085F8DC300024D822214685F8E8408F +:1006B0003AA800F0BDFC06F1090000F0B1FCD5F845 +:1006C000E4308DF8F000C2B206AF06F109010DF179 +:1006D000F100CDE93A3400F099FC394601223AA8FC +:1006E00000F06AFE80B2CDE9047008230127CDE94D +:1006F000023706F1D803019330230093317A0B4877 +:1007000007A3D3E9002302F0C1F9A04206DD01F0FE +:10071000F5FDC5F8E000384671B0F0BD2046FBE7B6 +:1007200078F6339F93CACD8DB0320020A4210020EB +:100730002DE9F0411D4D1E4E1E4F86B0284602F099 +:10074000D1F9034658B30024CDE90344ADF8144071 +:10075000027B8DF8142099684068029403AA03C2B2 +:100760001B68DFF8548043F00043029301F0C8FD9A +:10077000821941F10003009402A9384601F072F891 +:10078000A04205DD284602F0B1F988F80040D5E71F +:1007900098F80030072B05D8013388F8003006B0F0 +:1007A000BDE8F081014802F0A1F9F8E7A42100209A +:1007B00040420F00D8210020E537002070B50D46DB +:1007C00014461E4602F0BEF850B9022E10D1012C7C +:1007D0000ED112A3D3E90023C5E90023012007E0CD +:1007E000282C10D005D8012C09D0052C0FD00020C2 +:1007F00070BD302CFBD10BA3D3E90023ECE70BA396 +:10080000D3E90023E8E70BA3D3E90023E4E70BA334 +:10081000D3E90023E0E700BFAFF30080401DA12033 +:1008200026812A0B78F6339F93CACD8D9E6AC42108 +:10083000818A46EE26417272DF25D7B7F017304A1B +:1008400039059E5638B505460E4C0021013500F09D +:10085000B5FBA4F82C55B4F82C0500F097FB78B143 +:10086000B4F82C0500F0A2FB014648B9B4F82C05F9 +:1008700000F0A4FBB4F82C350133A4F82C35EAE7DA +:1008800038BD00BFB032002010B50A4B0A4A1A60CA +:1008900003F5805393F860203AB9DC6D2CB1204603 +:1008A00000F080FE204603F071FEBDE810400348D2 +:1008B00000F078BED82100207447000820320020C4 +:1008C0002DE9F04F8FB000AF05460C4602F03AF824 +:1008D000002849D1237E022B1BD1E38A012B18D19A +:1008E00001F00CFD0646FFF7E1FD03464FF4C8702A +:1008F000DFF8C482B3FBF0F206F5167602FB103384 +:1009000016FA83F3C8F80030E37E33B9A34B002214 +:100910001A703C37BD46BDE8F08F07F12401204630 +:1009200000F0A0FC0028F4D107F11400FFF7D6FD79 +:1009300097F8264007F11401224607F1270003F03B +:100940006FFE0028E2D10F2C08D8944B1C70D8F809 +:100950000030A3F51673C8F80030DAE797F82410D2 +:10096000284601F0E7FFD4E7E38A282B2BD010D8E4 +:10097000012B23D0052BCCD1BFF34F8F8849894B56 +:10098000CA6802F4E0621343CB60BFF34F8F00BF2D +:10099000FDE7302BBDD1844EE17E327A9142B8D151 +:1009A000607E3146002291F8DC50854200F0A5803F +:1009B0000132042A01F58A71F5D1AAE721462846B9 +:1009C000FFF79CFDA5E721462846FFF703FEA0E7B9 +:1009D000B2F8EC507B6005F103094FEA99094FEA40 +:1009E0008902D11DC908A8EBC1039D46EB46002131 +:1009F000584600F01DFB04F1EE012A4631445846EA +:100A000000F004FB7B6813B9012000F0B5FA96F8FA +:100A1000D20000F0BBFA044630B9307200F0D6FACA +:100A2000204600F0A9FAB1E0D6F8D4203AB996F8F9 +:100A3000D200B6F82C25824201D8FFF703FFD6F882 +:100A4000D4202A44944208D296F8D200B6F82C2535 +:100A50000130824201D8FFF7F5FE70685FFA89F233 +:100A6000594600F0EDFA08B9C54679E0726896F883 +:100A7000D2002A447260D6F8D42005EB0209C6F8E9 +:100A8000D49000F083FA814509D396F8D220D6F8A5 +:100A9000D4000132001B86F8D220C6F8D400FF2D06 +:100AA0000FD80024347200F091FA204600F064FA66 +:100AB00000F0FEFC3D4B188108B9FFF7A5FCC546C8 +:100AC00027E7BB6896F8D9000AFB0362FB68D2F8F7 +:100AD000E41082F8E83001F58061C2F8E030C2F835 +:100AE000E410FFF7D5FDFFF723FE96F8D920013279 +:100AF00002F0030286F8D920B6E74FF48A7A0AFB9F +:100B000002F505F1EA013144204600F081FCF8606D +:100B100000287FF4FEAE3544012285F8E82001F07C +:100B2000EDFBD5F8E020D6ED007ADFED216A801AE2 +:100B3000192838BF192040F6B832904228BF104615 +:100B4000B8EE677A07EE900AF8EEE77A67EEA67AD3 +:100B5000DFED186AE7EE267AFCEEE77AC6ED007A5A +:100B600096F8D930BB60BA6873680AFB02F4321990 +:100B700092F8E81059B1D2F8E4108B42E8463FF4FD +:100B800027AF002182F8E810C2F8E010C54673686C +:100B9000064A9B0A01331381BBE600BF9D2100205A +:100BA00000ED00E00400FA05B03200208C110020B6 +:100BB000CDCCCC3D6666663FA0210020014B18706D +:100BC000704700BF9811002038B54FF00054134B08 +:100BD00022689A4220D1124B627D12481A70237DFE +:100BE00003724FF48073C0F8F8314FF40073C0F80B +:100BF0000C3300254FF44073C0F820340A49C0F884 +:100C0000E450C922093000F001FAE02229462046CA +:100C100000F00EFA012038BD0020FCE79AAD44C573 +:100C200098110020B03200201600002037B500F0E7 +:100C30003FFC194D194928810223012218486B7184 +:100C400001F0F8F900230193164B17490093174858 +:100C5000174B4FF4805201F045FE164B197811B135 +:100C6000124801F067FE01F049FB0446FFF71EFC45 +:100C70004FF4C873B0FBF3F202FB130304F51670D4 +:100C800010FA83F00C4B186002F02EFF08B10F230E +:100C90002B8103B030BD00BF8C11002040420F00FB +:100CA000D8210020BD0700089C110020A4210020AD +:100CB000C108000898110020A02100202DE9F04F64 +:100CC0002DED028B8EA7D7E900670FF23C29D9E9F9 +:100CD0000089864C95B00DAD9FED828BFFF728FD06 +:100CE000DFF82CB200230C93ADF83C300D936B6011 +:100CF00000230DF125028DED008B4FF0010A09A9AB +:100D000058468DF825308DF824A001F041F99DF862 +:100D100024200023002A40F0AB80204601F012FE80 +:100D20000546002847D1DFF8ECB101F0E7FADBF81F +:100D3000003098423FD301F0E1FA0790FFF7B6FB8D +:100D4000079A4FF4C873B0FBF3F101FB130302F5EC +:100D5000167010FA83F0CBF80000DFF8BCB19BF8F6 +:100D600000100791002914BF2B46534610A88DF898 +:100D70003030FFF7B3FB0799C1F11002D2B2062A57 +:100D800010AB28BF062219440DF13100079200F084 +:100D90003DF9079A0CAB0393182302930132544B8D +:100DA000D2B2CDE900A304923B463246204601F080 +:100DB0000FFE8BF8005001F0A1FA4E4A4E4D136819 +:100DC000C31AB3F57A7F32D3106001F099FA024664 +:100DD0000B46204601F094FE204601F0B3FD30B3EF +:100DE0002B7ADFF838A1002B14BF032302238AF8E3 +:100DF000053001F083FA0DF1400B4FF47A730122B4 +:100E0000B0FBF3F05946CAF80000504600F002FA71 +:100E100018230293394B019380B240F25513CDE968 +:100E200003B0009342464B46204601F0D1FD2B7A99 +:100E3000CBB101F063FA4FF0000A83464FF48A7297 +:100E400095F8D900504400F0030002FB005393F8DA +:100E5000E81089B30AF1010ABAF1040FF0D12B7A34 +:100E6000002B7FF438AF15B0BDEC028BBDE8F08FDE +:100E70004FF0904110A84A6982F010024A61194669 +:100E8000102200F0D5F80DF126030AAA0CA9584645 +:100E900000F0E8FD95E8030011AB83E803009DF83E +:100EA0003C308DF84C300C9B109310A9DDE90A23DF +:100EB000204601F0F9FF1BE7D3F8E01049B12B6899 +:100EC000FA2B38BFFA23ABEB01010533B1EB430F2B +:100ED000C0D3FFF7DDFB4FF48A720028BAD1BEE71A +:100EE000AFF300800000000000000000A4210020FB +:100EF0009C210020E0370020B0320020E4370020A1 +:100F0000401DA12026812A0BF1C6A7C1D068080F79 +:100F1000D8210020A02100209D2100208C1100203C +:100F200008B5054800F03AFEBDE80840034A044908 +:100F3000002003F025BB00BFD8210020203800206E +:100F40008908000870B502F00DFC094E094D30808B +:100F5000002428683388834208D902F0FFFB2B68FD +:100F600004440133B4F5D04F2B60F2D370BD00BF01 +:100F700014380020E837002002F080BC00F1006047 +:100F8000920000F5D04002F027BC0000054B1A6823 +:100F9000054B1B889B1A834202D9104402F0DEBB2A +:100FA00000207047E837002014380020024B1B68EF +:100FB000184402F0D9BB00BFE8370020024B1B6881 +:100FC000184402F0E3BB00BFE8370020064991F85F +:100FD000243033B10023086A81F824300822FFF757 +:100FE000CDBF0120704700BFEC370020022802BFB0 +:100FF0004FF0904310229A6170470000022802BF10 +:101000004FF090434FF480129A61704710B500235F +:10101000934203D0CC5CC4540133F9E710BD000007 +:1010200003460246D01A12F9011B0029FAD1704773 +:1010300002440346934202D003F8011BFAE77047CB +:101040002DE9F8431F4D144695F82420074688469D +:1010500052BBDFF870909CB395F824302BB9202256 +:10106000FF2148462F62FFF7E3FF95F82400C0F107 +:101070000802A24228BF2246D6B24146920005EBA2 +:101080008000FFF7C3FF95F82430A41B1E44F6B27E +:10109000082E17449044E4B285F82460DBD1FFF7B2 +:1010A00095FF0028D7D108E02B6A03EB8203834227 +:1010B000CFD0FFF78BFF0028CBD10020BDE8F8830D +:1010C0000120FBE7EC3700202DE9F0470D460446F0 +:1010D00000219046284640F27912FFF7A9FF2346E7 +:1010E00020220021284601F081FE231D022220211A +:1010F000284601F07BFE631D03222221284601F0D1 +:1011000075FEA31D03222521284601F06FFE04F180 +:10111000080310222821284601F068FE04F110037C +:1011200008223821284601F061FE04F1110308224B +:101130004021284601F05AFE04F1120308224821FA +:10114000284601F053FE04F11403202250212846C2 +:1011500001F04CFE04F1180340227021284601F0F2 +:1011600045FE04F120030822B021284601F03EFE8E +:1011700004F121030822B821284601F037FE04F1CA +:101180002207C0263B46314608222846083601F091 +:101190002DFEB6F5A07F07F10107F3D104F132036C +:1011A00008223146284601F021FE002704F1330AC7 +:1011B00094F832304FEAC7099F4209F5A47615D357 +:1011C000B8F1000F08D1314604F59973072228467B +:1011D00001F00CFE09F24F16274694F832213B1B12 +:1011E00093420CD3F01DC008BDE8F0870AEB07035B +:1011F00008223146284601F0F9FD0137D8E707F209 +:10120000331331460822284601F0F0FD0836013735 +:10121000E3E7000013B504460846002101602346B9 +:10122000C0F803102022019001F0E0FD0198231D79 +:101230000222202101F0DAFD0198631D0322222100 +:1012400001F0D4FD0198A31D0322252101F0CEFD5C +:10125000019804F108031022282101F0C7FD07209E +:1012600002B010BDF7B50023047F00910E4607229F +:101270001946054601F07EFC731C009301220023F1 +:101280000721284601F076FCC4B9B31C009305225F +:1012900023460821284601F06DFC0D243746B2781C +:1012A000BB1B934211D32B7FA88A0734E408BBB938 +:1012B000844294BF0020012003B0F0BDAB8ADB0064 +:1012C000083BDB08B3700824E8E7FB1C00932146C9 +:1012D00000230822284601F04DFC08340137DEE7E0 +:1012E000201A18BF0120E7E7F7B50023047F00911B +:1012F0000E4608221946054601F03CFC731CC4B991 +:101300000822009311462346284601F033FC10249E +:10131000012372785F1C013B934211D32B7FA88A73 +:101320000734E408BBB9844294BF0020012003B015 +:10133000F0BDAB8ADB00083BDB0873700824E7E7ED +:10134000F3190093214600230822284601F012FCDD +:1013500008343B46DDE7201A18BF0120E7E700000C +:10136000F8B50E4605461446002181223046FFF7A7 +:101370005FFE2B4608220021304601F037FD7CB984 +:101380006B1C07220821304601F030FD0F24012399 +:101390006A785F1C013B934204D3E01DC008F8BD8E +:1013A0000824F4E7EB1921460822304601F01EFD1F +:1013B00008343B46ECE70000F8B50E4605461446F7 +:1013C0000021CE223046FFF733FE2B462822002193 +:1013D000304601F00BFD7CB905F1080308222821F5 +:1013E000304601F003FD30242F462A7A7B1B9342BE +:1013F00004D3E01DC008F8BD2824F5E707F1090370 +:1014000021460822304601F0F1FC08340137ECE7B0 +:10141000F7B5047F00910E460123102200210546F6 +:1014200001F0A8FBC4B9B31C009309222346102184 +:10143000284601F09FFB192437467288BB1B9A424D +:1014400011D82B7FA88A0734E408BBB9844294BF23 +:101450000020012003B0F0BDAB8ADB00103BDB08AD +:1014600073801024E8E73B1D0093214600230822E7 +:10147000284601F07FFB08340137DEE7201A18BF49 +:101480000120E7E730B5094D0A4491420DD011F82B +:10149000013B5840082340F30004013B2C4013F06B +:1014A000FF0384EA5000F6D1EFE730BD2083B8EDAA +:1014B000F7B5364A106851686B4603C36A4634492B +:1014C0003448082303F0BCF8044690BB0A25324A8E +:1014D000106851686B4603C36A4630492D4808239B +:1014E00003F0AEF80446002847D00369B3F5663F21 +:1014F00043D8B0F86620B2F57B7F3ED1284A02443B +:1015000002F15C018B4238D35C3B224900209E1AD9 +:10151000FFF7B8FF3246074604F164010020FFF7E9 +:10152000B1FFA3689F4228D1E368984208BF002515 +:1015300023E00369B3F5663F26D8428BB2F57B7F83 +:1015400020D1174A024402F110018B4218D3103BFC +:10155000104900209D1AFFF795FF2A46064604F120 +:1015600018010020FFF78EFFA3689E4202D1E368B6 +:10157000984201D00D25AAE70025284603B0F0BD0A +:101580001025A4E70C25A2E70B25A0E738470008A3 +:10159000DC970300006800084147000890970300AB +:1015A0000898FFF710B5037C044613B9006803F0F0 +:1015B0002FF8204610BD00000023BFF35B8FC360EF +:1015C000BFF35B8FBFF35B8F8360BFF35B8F7047AD +:1015D000BFF35B8F0068BFF35B8F704770B5054644 +:1015E0000C30FFF7F5FF05F1080604463046FFF71B +:1015F000EFFFA04206D930466D68FFF7E9FF2544AA +:10160000281A70BD3046FFF7E3FF201AF9E7000003 +:1016100070B50546406898B105F10800FFF7D8FF9E +:1016200005F10C0604463046FFF7D2FF84423046EF +:1016300094BF6D680025FFF7CBFF013C2C44201AB6 +:1016400070BD000038B50C460546FFF7C7FFA04245 +:1016500010D305F10800FFF7BBFF04446868B4FB32 +:10166000F0F100FB1144BFF35B8F0120AC60BFF3CE +:101670005B8F38BD0020FCE72DE9F041144607469A +:101680000D46FFF7C5FF844228BF0446D4B1B846D3 +:1016900058F80C6B4046FFF79BFF304428604046EB +:1016A0007E68FFF795FF331A9C4203D86C600120D7 +:1016B000BDE8F0816B60A41B3B68AB602044E86030 +:1016C0000220F5E72046F3E738B50C460546FFF75C +:1016D0009FFFA04210D305F10C00FFF779FF0444EF +:1016E0006868B4FBF0F100FB1144BFF35B8F01208D +:1016F000EC60BFF35B8F38BD0020FCE72DE9FF41B4 +:10170000884669460746FFF7B7FF6C4606B204EB0A +:10171000C6060025B44209D06268206808EB0501BE +:10172000FFF774FC636808341D44F3E72946384624 +:10173000FFF7CAFF284604B0BDE8F081F8B50546BA +:101740000C300F46FFF744FF05F10806044630460B +:10175000FFF73EFFA042304688BF6C68FFF738FFB6 +:10176000201A386020B130462C68FFF731FF204442 +:10177000F8BD000073B5144606460D46FFF72EFF70 +:10178000844228BF04460190DCB101A93046FFF72E +:10179000D5FF019B33B93268C5E90233C5E900249E +:1017A00001200CE09C4238BF0194286001986860D9 +:1017B0008442F5D93368AB60241AEC60022002B091 +:1017C00070BD2046FBE700002DE9FF410F4669464A +:1017D000FFF7D0FF6C4600B204EBC0050026AC4218 +:1017E00009D0D4F8048054F8081BB8194246FFF712 +:1017F0000DFC4644F3E7304604B0BDE8F08100003C +:1018000038B50546FFF7E0FF044601462846FFF7D6 +:1018100019FF204638BD000010B4026854681A460B +:1018200023465DF8044B184700207047002070479E +:1018300070470000002070470E20704700F5805070 +:1018400090F8C800C0F340007047000000F58050D9 +:1018500090F9D0007047000000F58050C0F8CC101F +:1018600001207047F7B50C68BDF8207014F00054E3 +:1018700070D10D7B082D6DD8302585F31188456911 +:10188000AE6876010CD4AC68240108D4AC6814F0BE +:1018900080545DD184F31188204603B0F0BD01244B +:1018A0000E6804F1180C002EB8BFF6004FEA0C1CAD +:1018B000B4BF46F00406760545F80C600E680FFAD2 +:1018C00084FC16F0804F18BF05EB0C1E05EB0C1CBA +:1018D0001EBFDEF8806146F00206CEF880610E7B06 +:1018E000CCF8846105EB04158E68C5F88C614E68F0 +:1018F000C5F88861DCF8805145F00105CCF88051CD +:1019000000EB441641F268052E4405EB44150544EE +:10191000C6E9002308350E4601F10C0C56F804EB1D +:1019200045F804EB6645F9D1843436882E8000EB07 +:10193000441407F00305267926F00B06354325717C +:10194000002484F31188009700F0FAFC0120A4E73A +:101950000224A5E74FF0FF309FE7000013B500F524 +:1019600080540191E06DFFF753FE1F280AD90199B9 +:10197000E06D2022FFF7C2FEA0F12003584258413B +:1019800002B010BD0020FBE708B5302383F31188B7 +:1019900000F58050C06DFFF70FFE002383F3118820 +:1019A00008BD0000002202608281426082607047B0 +:1019B00010B500220023C0E9002300230446038160 +:1019C0000C30FFF7EFFF204610BD0000F0B50546D4 +:1019D00000F580500C4690F8C83013F0040FC3F3A4 +:1019E000800108BF114661F3820304F1840680F888 +:1019F000C83005EB461389B01B79D8072ED57AB3CA +:101A000019072DD46846FFF7D3FF05EB441303F500 +:101A1000835303F1180703AA103318685968144652 +:101A200003C40833BB422246F7D1186820609B8864 +:101A3000A380DDE90E23CDE900230123ADF80830B2 +:101A40002B686946DB6B2846984705EB46152B79D2 +:101A50001A075CBF43F008032B7101E0002AF4D1A0 +:101A600009B0F0BD2DE9F0479A4688B00746884690 +:101A70009146302383F3118807F580546846FFF7B9 +:101A800097FFE06DFFF7AAFD1F282AD9E06D2022FD +:101A90006946FFF7B5FE202823D103AD444605ABC8 +:101AA0002E4603CE9E4220606160354604F1080454 +:101AB000F6D130682060B388A380DDE90023C9E94E +:101AC0000023BDF80830AAF80030002383F3118802 +:101AD00053464A464146384608B0BDE8F04700F054 +:101AE0001DBC002080F3118808B0BDE8F08700001D +:101AF0002DE9F84F0023C0E90133254B044640F897 +:101B0000183B0F46FFF74EFF04F12800FFF750FF88 +:101B100004F1480804F5825546460835304620361B +:101B2000FFF746FFAE42F9D104F580554FF48053DC +:101B30004FF00009C5E91339C5F848800123EE6567 +:101B400004F5875804F58456C5F8549085F8583044 +:101B500085F86030083608F108084FF0000A4FF0A9 +:101B6000000B46E908ABA6F11800FFF71BFF203673 +:101B700046F8289C4645F4D185F8D07017B1054841 +:101B800000F0B6FB044B63612046BDE8F88F00BF50 +:101B9000744700084C4700080064004010B5044B2F +:101BA000197804464A1C1A70FFF7A2FF204610BDA0 +:101BB0001C3800202DE9F047002950D0294B2A4F2E +:101BC000B7FBF1F599428CBF0A231123581EB5FBD0 +:101BD000F3FC03FB1C53C4B22BB102280346F5D817 +:101BE0000020BDE8F0870CF1FF36B6F5806FF7D224 +:101BF000C4EBC40E0EF103034FEAE309C3F3C703BA +:101C0000A4EB030809F1010A4FF47A755FFA88F032 +:101C100009FB05555AFA88F8B5FBF8F5B5F5617F6B +:101C2000C1BF0EF1FF33C3F3C703E01AC0B25C1C9F +:101C300050FA84F40CFB04F4B7FBF4F4A142CFD1C6 +:101C4000013BDBB20F2BCBD80138C0B20728C7D875 +:101C50000021107116809170D3700120C1E70846F1 +:101C6000BFE700BF3F420F000051250270B5054697 +:101C70000E464FF47A746B695B6803F00103B3425C +:101C80004FF0010004D001F095FC013CF3D1204657 +:101C900070BD000030B54269936913F0700F16D023 +:101CA00000230B4C936103F1840200EB4212117983 +:101CB0004D0709D5890707D5416954F823508D6030 +:101CC000117941F0040111710133032BEBD130BDC7 +:101CD0006047000873B51D46436916469A68D207E7 +:101CE000044609D59A6801219960C2F34002CDE902 +:101CF00000650021FFF76AFE63699A68D1050BD57C +:101D00009A684FF480719960C2F34022CDE9006572 +:101D100001212046FFF75AFE63699A68D2030BD56A +:101D20009A684FF480319960C2F34042CDE9006572 +:101D300002212046FFF74AFE04F58053D3F8CC0079 +:101D400010B103681B699847204602B0BDE8704097 +:101D5000FFF7A0BFF8B504464669002972D106F125 +:101D60000C073868800770D006EB01153868D5F885 +:101D7000B00110F0040FD5F8B0011ABFC00840F050 +:101D80000040400DA061D5F8B0C11CF0020F1CBF8F +:101D900040F08040A061D5F8B40106EB011100F0DD +:101DA0000F0084F82400D1F8B8012077D1F8B801E9 +:101DB000000A6077D1F8B801000CA077D1F8B8011B +:101DC000000EE077D1F8BC0184F82000D1F8BC0106 +:101DD000000A84F82100D1F8BC01000C84F822002C +:101DE000D1F8BC11090E84F823103821396004F1B0 +:101DF000340004F1180104F1240551F8046B40F893 +:101E0000046BA942F9D109880180C4E90A2321465B +:101E10000023238651F8283B2046DB6B984704F5C6 +:101E2000805393F8C820D3F8CC0042F0040283F822 +:101E3000C82010B103681B6998472046BDE8F840E8 +:101E4000FFF728BF06F110078BE7F8BD10B5044671 +:101E500000F056FA02460B4652EA030102D0013A5C +:101E600063F100030449086820B12146BDE8104031 +:101E7000FFF770BF10BD00BF18380020F0B530214B +:101E800081F31188DFF848C000F583510831002440 +:101E900004F1840500EB45152E7977070ED4F6067C +:101EA0000CD5D1E9007697429E4107D246695CF88D +:101EB0002470B7602E7946F004062E710134032C8D +:101EC00001F12001E4D1002383F31188F0BD00BFAC +:101ED0006047000808B5302383F31188FFF7DAFE66 +:101EE000002383F3118808BDF8B543690546986857 +:101EF00000F0E050B0F1E05F0F4621D0F8B13023A0 +:101F000083F3118805F583541034002606F1840309 +:101F100005EB43131B791A0706D50136032E04F18E +:101F20002004F3D1012007E05B07F6D421463846B0 +:101F300000F040FA0028F0D1002383F31188F8BDA7 +:101F40000120FCE708B5302383F3118800F58050A9 +:101F5000C06DFFF743FB002383F3118843090CBFD7 +:101F60000120002008BD0000F8B51D4600231370B5 +:101F70000F4606461446FFF7E5FF80F00100387073 +:101F800025B129463046FFF7AFFF2070F8BD0000AD +:101F90002DE9B8410C4615461F46804600F0B0F9C1 +:101FA0000B462178024609B9287850B14046FFF720 +:101FB00065FFFFF78FFF3B462A462146FFF7D4FF18 +:101FC0000120BDE8B881000070B5302686F3118885 +:101FD000174BDA6942F00072DA611A6942F0007256 +:101FE0001A611A6922F000721A61002383F31188C2 +:101FF00000F5805494F8C83013F0010516D1A9B14A +:1020000086F311880321132001F0C8F9032114205D +:1020100001F0C4F90321152001F0C0F994F8C8308B +:1020200043F0010384F8C83085F3118870BD00BF08 +:10203000001002402DE9F04700F5805588B095F872 +:10204000D030012B04468846164600F28180814F2D +:1020500057F823200AB947F82300D7F800A0C4F89E +:102060000C802674BAF1000F64D095F8D030012BA3 +:1020700070D001212046FFF7A7FF302383F311889A +:102080006269136823F0020313606269136843F006 +:1020900001031360636900275F6187F311880121E1 +:1020A0002046FFF7E3FD002800F09580E86DFFF77C +:1020B00083FA04F58359BA4609F108092022002160 +:1020C0006846FEF7B5FF02A8FFF76CFCCDF818A034 +:1020D0006A4609EB07030DF1180E9446BCE80300AD +:1020E000F44518605960624603F10803F5D1DCF845 +:1020F0000000186020379CF804201A71602FDDD191 +:1021000095F8C8306FF38203002785F8C8306A4617 +:1021100041462046ADF80070ADF802708DF80470AD +:10212000FFF748FD636948BB4FF400421A6008B0EE +:10213000BDE8F08741F2D80002F02AFA814610B1DA +:102140005146FFF7D5FCC7F80090B9F1000F8CD1CC +:102150000020ECE7386803681B6B984701460028AD +:1021600087D13868FFF730FF3868036832465B680C +:102170004146984700287FF47CAFE9E761221A6066 +:102180009DF802309DF803201B06120402F4702211 +:1021900003F040731343BDF80020C2F30902134358 +:1021A0009DF804201205022E02F4E0020CBF4FF04D +:1021B00000410021134362690B43D3616369132219 +:1021C0005A616269136823F001031360394620469F +:1021D000FFF74CFD08B96369A6E795F8D03093BBCB +:1021E0006169D1F8002242F00102C1F80022616960 +:1021F000D1F8002222F47C5222F00E02C1F8002213 +:102200006169D1F8002242F46062C1F8002262697B +:10221000C2F814326269C2F80432626941F6FF7191 +:10222000C2F80C126269C2F840326269C2F84432E4 +:1022300063690122C3F81C226269D2F8003223F0DC +:102240000103C2F8003295F8C83043F0020385F864 +:10225000C8306CE71838002008B500F051F850EA93 +:102260000103024602D0421E61F10001044B1868CE +:1022700010B10B46FFF72EFDBDE8084001F064B831 +:102280001838002008B50020FFF7E0FDBDE8084041 +:1022900001F05AB808B50120FFF7D8FDBDE80840A5 +:1022A00001F052B800B59BB0EFF30981682268468F +:1022B000FEF7ACFEEFF30583014B9B6BFEE700BF1F +:1022C00000ED00E008B5FFF7EDFF000000B59BB0A2 +:1022D000EFF3098168226846FEF798FEEFF3058365 +:1022E000014B5B6BFEE700BF00ED00E0FEE7000086 +:1022F0000FB408B5029801F00DF9FEE701F040BBFC +:1023000001F0ECBA13B56C4684E80600031D94E8AE +:10231000030083E80500012002B010BD73B5856895 +:10232000019155B11B885B0707D4D0E900369B6B40 +:102330009847019AC1B23046A847012002B070BD4B +:10234000F0B5866889B005460C465EB1BDF83830F8 +:102350005B070AD4D0E900379B6B98472246C1B28D +:102360003846B047012009B0F0BD00220023CDE976 +:1023700000230023ADF808300A4603AB01F108063C +:10238000106851681C4603C40832B2422346F7D194 +:10239000106820609288A280FFF7B2FF0423ADF896 +:1023A00008302B68CDE90001DB6B69462846984769 +:1023B000D8E7000030B503680968DD0FB5EBD17FC1 +:1023C00023F0604421F060424FEAD1700BD0002B23 +:1023D000B8BFA40C0029B8BF920C944202D034BFFD +:1023E0000120002030BD944205D1C1F38070C3F3B9 +:1023F00080738342F6D194422CBF00200120F1E784 +:102400002DE9F041456A15B94162BDE8F0814B689C +:1024100023F06047C3F38A464FEAD37EC3F3807844 +:1024200016EA230638BF3E46AC462B465A68BEEB3A +:10243000D27F22F060440AD0002A18DAA40CB442F9 +:1024400017D19D420FD10D60DEE71346EEE7A7429C +:1024500007D102F08044C2F3807242450BD054B1E0 +:10246000EFE708D2EDE7CCF800100B60CDE7B442FF +:1024700001D0B442E5D81A689C46002AE5D119601B +:10248000C3E700002DE9F047089D01F007044FEA7B +:10249000D508224405F0070500EBD1004FF47F4931 +:1024A000944201D1BDE8F08704F0070705F0070A60 +:1024B00057453E4638BF5646C6F10806111B8E42A8 +:1024C00028BF0E46E10808EBD50E415C13F80EC09C +:1024D000B94029FA06F721FA0AF1FFB28CEA0101A4 +:1024E00047FA0AF739408CEA010C03F80EC034446D +:1024F0003544D5E780EA0120082341F2210201B2E8 +:102500004000002980B203F1FF33B8BF504013F000 +:10251000FF03F4D17047000038B50C468D18A54272 +:1025200000D138BD14F8011BFFF7E4FFF7E7000006 +:1025300042684AB1136843604389818901339BB281 +:102540009942438138BF83811046704770B588B087 +:10255000202204460D4668460021FEF769FD20460C +:102560000495FFF7E5FF024658B16B46054608AEF5 +:102570001C4603CCB44228606960234605F1080577 +:10258000F6D1104608B070BD082817D909280CD01C +:102590000A280CD00B280CD00C280CD00D280CD0FD +:1025A0000E2814BF4020302070470C2070471020A8 +:1025B0007047142070471820704720207047000093 +:1025C000082817D90C280CD910280CD914280CD994 +:1025D00018280CD920280CD930288CBF0F200E20A9 +:1025E0007047092070470A2070470B2070470C2065 +:1025F00070470D20704700002DE9F843078C072F26 +:1026000004461ED9D0E9029800254FF6FF73C5F1A4 +:102610002006A5F1200029FA05F108FA06F628FAA5 +:1026200000F031430143C9B21846FFF763FF083594 +:10263000402D0346EBD1E1693A46BDE8F843FFF788 +:102640006BBF4FF6FF70BDE8F883000010B54B6814 +:1026500023B9CA8A63F30902CA8210BD04691A68E1 +:102660001C600361C38A013BC3824A60EFE700003C +:102670002DE9F84F1D46CB8A0F46C3F30901052902 +:10268000814692460B4630D00020AAB207F11A04C8 +:102690009EB2042E1FFA80F80FD8904503F1010373 +:1026A00006D3FB8A0A4462F30903FB8201201AE085 +:1026B0001AF80060E6540130EAE79045F1D2A1F142 +:1026C000050B1C237C68BBFBF3F203FB12BB1FFA58 +:1026D0008BF6002C45D14846FFF72AFF044638B94F +:1026E00078606FF00200BDE8F88F4FF00008E6E771 +:1026F000002606607860ADB24FF0000B454510D95A +:102700000AEB0803221D13F8011B9155B1B208F121 +:1027100001081B291FFA88F82BD0454506F1010650 +:10272000F1D8FB8AC3F30902154465F30903BCE73A +:10273000013292B21C462368002BF9D16B1F0B4467 +:102740001C21B3FBF1F301339BB29A42D3D2BBF10C +:10275000000FD0D14846FFF7EBFE20B9C4F800B017 +:10276000BFE70122E7E7C0F800B05E4620600446FC +:10277000C1E74545D5D94846FFF7DAFE08B92060DC +:10278000AFE7C0F800B0002620600446B6E70000BE +:102790002DE9F04F2DED028B1C4683B05B69019251 +:1027A00007468846002B00F09A80238C2BB1E26903 +:1027B000002A00F09480072B35D807F10C00FFF7B2 +:1027C000B7FE054638B96FF00205284603B0BDECE8 +:1027D000028BBDE8F08F14220021FEF729FC228C29 +:1027E000E16905F10800FEF711FC208C013080B290 +:1027F000FFF7E6FEFFF7C8FE013880B22084013003 +:1028000028746369228C1B782A4403F01F0363F049 +:102810003F0348F000411372384669602946FFF7CC +:10282000EFFD0125D1E700F10C034FF0000908EEA0 +:10283000103A4FF0800A4E464D4618EE100AFFF748 +:1028400077FE83460028BED014220021FEF7F0FB5D +:10285000002E3AD1019BABF8083002220BF1080E92 +:102860001FFA82FC0CF10100BCF1060F218C80B232 +:1028700001D88E422BD3FFF7A3FEFFF785FE6269D6 +:102880001278013802F01F028E4208BF4FF0400A52 +:1028900042EA49121BFA80F14AEA020A013048F082 +:1028A000004281F808A08BF81000CBF804205946AC +:1028B0003846FFF7A5FD238C0135B3422DB289F0D0 +:1028C00001094FF0000AB8D17FE70022C6E7E169AD +:1028D000895D0EF802100136B6B20132C0E76FF022 +:1028E000010572E7F8B515460E4630220021044670 +:1028F0001F46FEF79DFB069B6360B5F5001F079B17 +:10290000A76034BF6A094FF6FF72A36297B2E6610F +:1029100004F1100000239A4206D800230360A78226 +:10292000E3822383E360F8BD06600133304620363E +:10293000F1E7000003781BB94BB2002BC8BF017050 +:102940007047000000787047F8B50C46C969074623 +:1029500011B9238C002B37D1257E1F2D34D8387820 +:1029600028BB228C072A2CD8268A36F003032BD1C9 +:102970004FF6FF70FFF7D0FD20F001003102400458 +:1029800041EA0561400C41EA40254FF6FF722346BB +:1029900029463846FFF7FCFE002807DD62691378F8 +:1029A0000133DBB21F2B88BF00231370F8BD218ACF +:1029B0002D0645EA012505432046FFF71DFE024688 +:1029C000E5E76FF00300F1E76FF00100EEE70000CC +:1029D00070B58AB0044616460021282268461D4676 +:1029E000FEF726FBBDF83830ADF810300F9B05938D +:1029F0009DF840308DF81830119B07936946BDF85B +:102A00004830ADF820302046CDE90265FFF79CFF45 +:102A10000AB070BD2DE9F041D36905460C46164653 +:102A20000BB9138C5BBB377E1F2F28D895F800801D +:102A3000B8F1000F26D03046FFF7DEFD33782102D3 +:102A400041EAC33141EA0801338A41EA076141EAB8 +:102A500003410246334641F080012846FFF798FEC5 +:102A600000280ADD3378012B07D17269137801330E +:102A7000DBB21F2B88BF00231370BDE8F0816FF01D +:102A80000100FAE76FF00300F7E70000F0B58BB044 +:102A900004460D4617460021282268461E46FEF7CA +:102AA000C7FA9DF84C305A1E534253418DF80030FE +:102AB0009DF84030ADF81030119B05939DF84830DB +:102AC0008DF81830149B07936A46BDF85430ADF862 +:102AD000203029462046CDE90276FFF79BFF0BB058 +:102AE000F0BD0000406A00B104307047436A1A68C4 +:102AF000426202691A600361C38A013BC382704764 +:102B00002DE9F041D0F82080194E14461D4641466B +:102B1000002709B9BDE8F081D1E90223A21A65EBCB +:102B20000303964277EB03031ED2036A8B420DD157 +:102B3000FFF78CFD036A1B68036203690B60C38A9D +:102B40000161016A013BC3828846E2E7FFF77EFD2F +:102B50000B68C8F8003003690B60C38A0161013B50 +:102B6000C382D8F80010D4E788460968D1E700BFCF +:102B700080841E002DE9F04F8BB00D46DDF850909B +:102B800014469B468046002800F01981B9F1000FD9 +:102B900000F01581531E3F2B00F21181012A03D151 +:102BA000BBF1000F40F00B810023CDE90833B8F8EA +:102BB0001430B5EBC30F4FEAC30703D300200BB0AB +:102BC000BDE8F08F2B199F42D8F80C303ABF7F1B1D +:102BD000FFB227461BB9D8F81030002B7AD0272D2A +:102BE0004ED8C5F12806B7424FF000032CBFF6B20D +:102BF0003E4600932946D8F8080008AB3246FFF756 +:102C000041FCA7EB060A35445FFA8AFAB8F814309B +:102C100003F10053053BDB000493D8F80C30039319 +:102C20002821039B13B1BAF1000F2CD1D8F8100062 +:102C300040B1BAF1000F05D0009608AB5246691AB0 +:102C4000FFF720FC38B2002FB8D066070AD00AABD5 +:102C500003EBD401624211F8083C02F00702134171 +:102C600001F8083C082C3CD9102C40F2B580202CEF +:102C700040F2B780BBF1000F00F09C80082334E0E5 +:102C8000BA460026C2E7049BE02B28BFE023069348 +:102C90000B44AB42059314D95A1B039800969245F6 +:102CA00034BF5246D2B2691A08AB04300792FFF71C +:102CB000E9FB079A1644AAEB020A1544F6B25FFA3A +:102CC0008AFA049B069A05999B1A0493039B1B6836 +:102CD0000393A6E70093D8F8080008AB3A462946C4 +:102CE000AEE7BBF1000F13D00123B4EBC30F6CD0E0 +:102CF000082C12D89DF82030621E23FA02F2D50764 +:102D000006D54FF0FF3202FA04F423438DF8203049 +:102D10009DF8203089F8003051E7102C12D8BDF80A +:102D20002030621E23FA02F2D10706D54FF0FF329F +:102D300002FA04F42343ADF82030BDF82030A9F89E +:102D400000303CE7202C0FD80899631E21FA03F3CA +:102D5000DA0705D54FF0FF3202FA04F40C43089469 +:102D6000089BC9F800302AE7402C2BD0DDE9086524 +:102D7000611EC4F12102A4F1210326FA01F105FA32 +:102D800002F225FA03F311431943CB0712D50122AE +:102D9000A4F12003C4F1200102FA03F322FA01F1A5 +:102DA000A240524243EA010363EB430332432B4305 +:102DB000CDE90823DDE90823C9E90023FFE66FF028 +:102DC0000100FCE66FF00800F9E6082CA0D9102CF1 +:102DD000B3D9202CEED8C3E7BBF1000FADD002234E +:102DE00083E7BBF1000FBBD004237EE730B5012A97 +:102DF000144638BF0124402C85B028BF402400254C +:102E0000012ACDE9025518D81B788DF808306307E0 +:102E10000AD004AB03EBD405624215F8083C02F07B +:102E20000702934005F8083C009103462246002122 +:102E300002A8FFF727FB05B030BD082AE4D9102A05 +:102E400003D81B88ADF80830E1E7202A8DBFD3E90D +:102E500000231B680293CDE90223D8E710B5CB68A5 +:102E60001BB98B600B618B8210BD04691A681C60F2 +:102E70000361C38A013BC382CA60F0E703064CBF0B +:102E8000C0F3C0300220704708B50246FFF7F6FFD6 +:102E9000022806D15306C2F30F2001D100F003002F +:102EA00008BDC2F30740FBE72DE9F04F93B0CDE931 +:102EB00003230A6804461046FFF7E0FF022814BF08 +:102EC000C2F306260026002A0D46824680F2F281D1 +:102ED00012F0C04940F0EE81097B002900F0EA8140 +:102EE000022803D02378B34240F0E781C2F30463A1 +:102EF0000693104602F07F030593FFF7C5FF059B7D +:102F000029444FEA834848EA0A4848EA4668CE78A6 +:102F100000230022CDE90823F309834648EA00088C +:102F2000029367D0059B009302466768534608A941 +:102F30002046B847002800F0C381276A4FB94146B0 +:102F400004F10C00FFF702FB074690B96FF0020096 +:102F500054E03B6998450DD03F68002FF9D14146B8 +:102F600004F10C00FFF7F2FA07460028EED0236ABE +:102F70003B60276297F817C006F01F08CCF3840C5B +:102F8000ACEB08001FFA80FE0028B8BF0EF120004D +:102F9000A8EB0C031FFA83FED7E90221B8BF00B2E9 +:102FA000002B0793BEBF0EF120031BB2079352EA1A +:102FB000010338D0039BDFF824E39A1A049B4FF0F7 +:102FC000000C63EB010196457CEB01032BD36B7B7B +:102FD00097F81AE0734519D1029B002B78D001288D +:102FE00021DC7868F8B9DFF8F0C2944570EB010392 +:102FF00016D337E0276A27B96FF00C0013B0BDE88D +:10300000F08F3B699845B5D03F68F4E7B2489042ED +:103010007CEB010301D30020F0E7029B002BFAD0E8 +:10302000079B0F2B17DCFA7DB30002F0030203F0BD +:103030007C031343FB7539462046FFF707FB6B7B88 +:10304000BB76029B3BB9FB7DC3F38402013262F382 +:103050008603FB75D0E76A7BBB7E9A42DBD1029B7D +:10306000002B35D0B309022B32D0039BBB60049BED +:10307000FB60142200210DA8FDF7DAFF039B0A93E1 +:10308000049B0B932B1D0C932B7BADF83EB0013BA7 +:10309000DBB2ADF83C30069B8DF84230059B8DF8D5 +:1030A000433094F82C308DF840A083F001038DF864 +:1030B00044308DF84180A3680AA920469847FB7DDB +:1030C000C3F38403013303F01F039B02FB82A2E7D7 +:1030D000FB7DC6F34012B2EBD31F40F0F480C3F384 +:1030E0008403434540F0F280029A2B7BB609002A04 +:1030F0004DD0F2075DD4032B40F2EB80039BBB6005 +:10310000049BFB602B7BAE1D033BDBB23246394692 +:1031100004F10C00FFF7ACFA00280CDA394620461F +:10312000FFF794FAFB7DC3F38403013303F01F031D +:103130009B02FB820AE7DDE90884AB883B834FF6FC +:10314000FF73C9F12000A9F1200228FA09F104FA5D +:1031500000F0014324FA02F211431846C9B2FFF706 +:10316000C9F909F10809B9F1400F0346E9D1B8825C +:103170002A7B033AD2B23146FFF7CEF9FB7DB88203 +:10318000DA43C2F3C01262F3C713FB7543E786B993 +:103190002E1D013BDBB23246394604F10C00FFF72D +:1031A00067FA0028BADB2A7BB88A013AD2B23146E4 +:1031B000E2E7F98AC1F30901013B0429DAB25BD8DD +:1031C000281D002307F11B069A4208D910F801CBED +:1031D00006F801C0013101330529DBB2F4D10399AE +:1031E0000A9104990B91934207F11B010C9138BF8E +:1031F000043379680D9134BF55FA83F300230E939D +:10320000FB8AADF83EB0C3F309031A44069B8DF860 +:103210004230059B8DF8433094F82C30ADF83C20BB +:1032200083F001038DF8443000238DF840A08DF821 +:1032300041807B602A7BB88A013A291DFFF76CF92F +:103240003B8BB882834203D1A3680AA920469847E2 +:1032500020460AA9FFF702FEFB7DBA8AC3F3840366 +:10326000013303F01F039B02FB823B8B9A420CBF8E +:1032700000206FF01000C1E67B68002BAFD0052066 +:1032800001E01C3033461E68002EFAD1091A081DD1 +:103290002E1D184401EB090CBCF11B0F5FFA89F3DA +:1032A0009DD89A429BD916F8013B00F8013B09F1E1 +:1032B0000109EFE76FF00900A0E66FF00A009DE654 +:1032C0006FF00B009AE66FF00D0097E66FF00E00BE +:1032D00094E66FF00F0091E640420F0080841E00DC +:1032E000EFF3098305494A6B22F001024A63683310 +:1032F00083F30988002383F31188704700EF00E00F +:10330000302080F3118862B60C4B0D4AD96821F445 +:10331000E0610904090C0A43DA60D3F8FC2009498A +:1033200042F08072C3F8FC200A6842F001020A6091 +:103330002022DA7783F82200704700BF00ED00E01A +:103340000003FA05001000E010B5302383F3118864 +:103350000E4B5B6813F4006314D0F1EE103AEFF3F8 +:103360000984683C4FF08073E361094BDB6B236693 +:1033700084F3098800F098F810B1064BA36110BDE2 +:10338000054BFBE783F31188F9E700BF00ED00E090 +:1033900000EF00E0FF0200080203000800F16043B4 +:1033A00003F561430901C9B283F80013012200F05B +:1033B0001F039A4043099B0003F1604303F56143F7 +:1033C000C3F880211A60704700F16040090100F5E0 +:1033D0006D40C9B2017670470023037582680369A6 +:1033E0001B6899689142FBD25A6803604260106082 +:1033F0005860704700230375826803691B689968E9 +:103400009142FBD85A680360426010605860704770 +:1034100008B50846302383F311880B7D032B05D0B4 +:10342000042B0DD02BB983F3118808BD8B690022C2 +:103430001A604FF0FF338361FFF7CEFF0023F2E7FE +:10344000D1E9003213605A60F3E70000FFF7C4BF10 +:10345000054BD9680875186802681A605360012224 +:103460000275D860FCF736BF2838002030B50C4B09 +:10347000DD684B1C87B004460FD02B46094A6846CE +:1034800000F0D8F82046FFF7E3FF009B13B1684631 +:1034900000F0DAF8A86907B030BDFFF7D9FFF9E707 +:1034A0002838002011340008044B1A68DB68906843 +:1034B0009B68984294BF0020012070472838002064 +:1034C000084B10B51C68D86822681A605360012246 +:1034D0002275DC60FFF78EFF01462046BDE81040F4 +:1034E000FCF7F8BE2838002038B5074C07490848D3 +:1034F000012300252370656000F024FB0223237064 +:1035000085F3118838BD00BF503A0020B847000845 +:103510002838002008B572B6044B186500F0C2F9CF +:1035200000F0ACFA024B03221A70FEE728380020A4 +:10353000503A002000F09AB88B60022308618B8219 +:10354000084670478368A3F1840243F8142C02698B +:1035500043F8442C426943F8402C094A43F8242C90 +:10356000C26843F8182C022203F80C2C002203F83E +:103570000B2C044A43F8102CA3F12000704700BF25 +:10358000ED0200082838002008B5FFF7DBFFBDE892 +:103590000840FFF75BBF0000024BDB6898610F201B +:1035A000FFF756BF28380020302383F31188FFF738 +:1035B000F3BF000008B50146302383F311880820CB +:1035C000FFF754FF002383F3118808BD064BDB6827 +:1035D00039B1426818605A60136043600420FFF7F5 +:1035E00045BF4FF0FF3070472838002003689842ED +:1035F00006D01A680260506099611846FFF726BF2E +:103600007047000010B50A4C23699A6891420CD8A3 +:103610005A6881600360426010609A685860511A6D +:1036200099604FF0FF33A36110BD1B68891AECE766 +:103630002838002010B4C0E9032300235DF8044BB0 +:103640004361FFF7DFBF0000036881689A680A449E +:103650009A60426813605A6000230360024B4FF087 +:10366000FF329A61704700BF2838002070B5124DB4 +:10367000EB692A460133EB6152F8103F934206D0C2 +:103680009A68013A9A6030262C69A36803B170BD2C +:10369000D4E900210A605160236083F31188D4E9E2 +:1036A00003312046984786F3118861690029EBD0E1 +:1036B0002046FFF7A7FFE7E728380020054A30B586 +:1036C000D369D2E908451B1B181945F10001C2E96D +:1036D000080130BD2838002000207047FEE70000B8 +:1036E000704700004FF0FF3070470000BFF34F8F6E +:1036F000024AD368DB07FCD4704700BF00200240B9 +:1037000008B5074B1B7853B9FFF7F0FF054B1A6953 +:10371000120641BF044A5A6002F188325A6008BD5D +:10372000683A0020002002402301674508B5054B98 +:103730001B7833B9FFF7DAFF034A136943F08003BC +:10374000136108BD683A0020002002407F289ABF1C +:1037500000F58030C0020020704700004FF4006088 +:1037600070470000802070477F2808B50BD8FFF70E +:10377000EDFF00F500630268013204D1043083429A +:10378000F9D1012008BD0020FCE700007F2810B51A +:1037900004461CD8FFF7AAFFFFF7B2FF0D4BF32238 +:1037A000DA6002221A61FFF7D1FF58611A6942F00C +:1037B00040021A614FF40061FFF798FF00F05AF9D8 +:1037C000FFF7B4FF2046BDE81040FFF7CDBF002053 +:1037D00010BD00BF002002402DE9F84312F00103A4 +:1037E000144606D01F4B40F203321A600020BDE899 +:1037F000F88385181C4A954204D91A4A4FF442713D +:103800001160F3E7FFF77CFFFFF770FFDFF86880D8 +:10381000451A4FF00109012C05EB01060F4603D8AC +:10382000FFF784FF0120E2E73B88C8F8109033805F +:103830000020FFF75BFFC8F81000338831F8022B37 +:103840009BB29A420CD0074B40F21F321A60074BD2 +:103850001E60074B1C60074B1F60FFF767FFC6E742 +:10386000023CD8E7643A002000000408583A0020DF +:10387000603A00205C3A002000200240084908B568 +:103880000B7828B11BB9FFF73BFF01230B7008BD74 +:10389000002BFCD0BDE808400870FFF747BF00BF11 +:1038A000683A002008B506484FF41F4100F0E4F8DC +:1038B000BDE808404FF400514FF0805000F0DCB8F4 +:1038C000000100200846114600F084BE012000F0EF +:1038D00081BE0000084600F09BBE000038B5EFF343 +:1038E0001185BDBBEFF30584C4F308043023C4B1D4 +:1038F00083F31188FFF7E2FE4C014201121A44EAF9 +:10390000D06464EB01049300A4001B1844EA927491 +:1039100041EB0401C900D80041EA537185F31188D5 +:1039200038BD83F31188FFF7C9FE4D014201121A19 +:1039300045EAD06565EB01059300AD001B1845EA2B +:10394000927541EB0501C900D80041EA537184F337 +:10395000118838BDFFF7B2FE4B014401241A43EA37 +:10396000D06363EB0103A2009B00121843EA947337 +:1039700041EB0301C900D00041EA527138BD00BFDC +:1039800038B5FFF7ABFF114C114AC00840EA41704F +:10399000A0FB025EC908A0FB040C1CEB050CA1FBFC +:1039A00004404FF000035B41A1FB02121CEB040C2E +:1039B00043EB000011EB0E0142F10002411842F10D +:1039C0000000090941EA007038BD00BFCFF753E39A +:1039D000A59BC42010B50244064BD2B2904200D140 +:1039E00010BD441C00B253F8200041F8040BE0B2B3 +:1039F000F4E700BF502800400F4B30B51C6A240488 +:103A000007D41C6A44F440741C621C6A44F40044E9 +:103A10001C620A4C236843F4807323600244084B01 +:103A2000D2B2904200D130BD441C00B251F8045BC8 +:103A300043F82050E0B2F4E700100240007000406C +:103A40005028004007B5012201A90020FFF7C2FF5E +:103A5000019803B05DF804FB13B50446FFF7F2FFCD +:103A6000A04205D0012201A900200194FFF7C4FF64 +:103A700002B010BD704700007047000070470000A2 +:103A8000074B45F255521A6002225A6040F6FF7207 +:103A90009A604CF6CC421A60024B01221A707047B1 +:103AA00000300040703A0020034B1B781BB1034BE1 +:103AB0004AF6AA221A607047703A0020003000408F +:103AC000044B1A682AB902F1804202F50432526AA4 +:103AD0001A6070476C3A0020024B4FF080725A62B5 +:103AE000704700BF0010024008B5FFF7E9FF024B26 +:103AF0001868C0F3407008BD6C3A002070470000A1 +:103B0000FEE700000A4B0B480B4A90420BD30B4BCD +:103B1000DA1C121AC11E22F003028B4238BF0022A7 +:103B20000021FDF785BA53F8041B40F8041BECE7AD +:103B30001C490008543C0020543C0020543C002008 +:103B4000FEE7000070B51B4B01630025044686B0FC +:103B5000586085620E46FFF7D3FB04F11003C4E9F9 +:103B600004334FF0FF33A361134BE561D969A560BE +:103B70000A462B46C4E9082304F13401C4E9004491 +:103B80000E4AE562256580232046FFF7D5FC012318 +:103B9000E0600B4A0375009272680192B268CDE949 +:103BA0000223084B6846CDE90435FFF7EDFC06B06B +:103BB00070BD00BF503A002028380020C4470008DC +:103BC000C9470008413B00084B6843608B6883602D +:103BD000CB68C3600B6943614B6903628B694362C5 +:103BE0000B6803607047000008B51B4B9A6A42F4EB +:103BF000FC029A629A6A22F4FC029A629A6A5A69F0 +:103C000042F4FC025A61154A5B6911464FF090403C +:103C1000FFF7DAFF02F11C0100F58060FFF7D4FF27 +:103C200002F1380100F58060FFF7CEFF02F1540188 +:103C300000F58060FFF7C8FF02F1700100F58060B9 +:103C4000FFF7C2FF02F18C0100F58060FFF7BCFFB7 +:103C5000BDE8084000F05AB800100240D047000804 +:103C600008B500F093F9FFF73FFCBDE80840FFF707 +:103C700027BF00007047000010B5214CA36A63F411 +:103C8000FC03A362A36A03F4FC03A3624FF0FF32B8 +:103C9000A36A236922612369002323612169E16802 +:103CA000E260E268E360E268E269164942F080524D +:103CB000E261E2690A6842F480720A60226A02F4F0 +:103CC0004072B2F5407F1EBF4FF480322262236201 +:103CD000236A1B0407D4236A43F440732362236AD4 +:103CE00043F40043236200F031F9A369064A43F02C +:103CF0000103A361A369136843F02003136010BD9F +:103D00000010024000700040000001401E4B1A6885 +:103D100042F001021A601A689007FCD55A6822F036 +:103D200003025A605A6812F00C02FBD1196801F0C4 +:103D3000F90119605A601A6842F480321A601A68F0 +:103D40009103FCD5114A5A604FF40452DA623022D2 +:103D50001A631A6842F080721A601A689201FCD5E0 +:103D60000B4912220A600A6802F00702022AFAD1FD +:103D70005A6842F002025A605A6802F00C02082A9D +:103D8000FAD11A6B1A6370470010024000241D001C +:103D900000200240084A08B5516913680B4003F03F +:103DA0000103536123B1054A13680BB1506898476A +:103DB000BDE80840FFF7C8BA00040140743A00208B +:103DC000084A08B5516913680B4003F002035361B8 +:103DD00023B1054A93680BB1D0689847BDE8084005 +:103DE000FFF7B2BA00040140743A0020084A08B54F +:103DF000516913680B4003F00403536123B1054A72 +:103E000013690BB150699847BDE80840FFF79CBAA9 +:103E100000040140743A0020084A08B5516913684B +:103E20000B4003F00803536123B1054A93690BB1BA +:103E3000D0699847BDE80840FFF786BA0004014002 +:103E4000743A0020084A08B5516913680B4003F022 +:103E50001003536123B1054A136A0BB1506A9847A6 +:103E6000BDE80840FFF770BA00040140743A002032 +:103E7000174B10B55A691C68144004F478725A61E3 +:103E8000A30604D5134A936A0BB1D06A984760061B +:103E900004D5104A136B0BB1506B9847210604D51B +:103EA0000C4A936B0BB1D06B9847E20504D5094AD5 +:103EB000136C0BB1506C9847A30504D5054A936C5D +:103EC0000BB1D06C9847BDE81040FFF73DBA00BF7A +:103ED00000040140743A00201A4B10B55A691C685E +:103EE000144004F47C425A61620504D5164A136DED +:103EF0000BB1506D9847230504D5134A936D0BB150 +:103F0000D06D9847E00404D50F4A136E0BB1506E84 +:103F10009847A10404D50C4A936E0BB1D06E984714 +:103F2000620404D5084A136F0BB1506F98472304FD +:103F300004D5054A936F0BB1D06F9847BDE8104088 +:103F4000FFF702BA00040140743A0020062108B5C8 +:103F50000846FFF723FA06210720FFF71FFA06217C +:103F60000820FFF71BFA06210920FFF717FA0621A0 +:103F70000A20FFF713FA06211720FFF70FFABDE812 +:103F8000084006212820FFF709BA000008B5FFF70E +:103F900073FE00F067F800F03DF8FFF76BFEBDE838 +:103FA000084000F05DB800000268436811430160FA +:103FB00003B1184770470000143000F02FBA00001A +:103FC0004FF0FF33143000F029BA0000383000F011 +:103FD000A5BA00004FF0FF33383000F09FBA000060 +:103FE000143000F0F5B900004FF0FF31143000F04C +:103FF000EFB90000383000F04FBA00004FF0FF3248 +:10400000383000F049BA0000012914BF6FF01300E6 +:104010000020704700F06CB8044B03600023C0E937 +:104020000233436001230374704700BF78480008DF +:1040300038B5C36904460D461BB904210844FFF78F +:10404000B3FF294604F1140000F0A6F9002806DAAF +:10405000201D4FF40061BDE83840FFF7A5BF38BD13 +:1040600000F00EB80023054A19460133102BC2E9AF +:10407000001102F10802F8D1704700BF743A002025 +:104080004FF0E023044A5A6100229A6107221A6124 +:1040900008210B20FFF798B93F19010008B530231C +:1040A00083F31188FFF746FA002383F3118808BDD4 +:1040B00008B5FFF7F3FFBDE80840FFF745B900007A +:1040C000026843681143016003B11847704700005C +:1040D000024A136843F0C003136070470038014080 +:1040E000024A136843F0C003136070470044004065 +:1040F00037B51D4C1D4D2046FFF78EFF009404F18F +:1041000014001B490023202200F038F920220094DB +:1041100004F13800174B184900F0B2F9174BC4E905 +:104120001735174C0C212520FFF738F92046FFF7EB +:1041300073FF04F11400134900940023202200F0BF +:104140001DF904F13800104B10490094202200F0B2 +:1041500097F90F4B0C212620C4E9173503B0BDE8B1 +:104160003040FFF71BB900BFF43A00200051250290 +:10417000CC3B0020D14000080C3C0020003801401E +:10418000603B0020EC3B0020E14000082C3C00207C +:10419000004400402DE9F047C66D3768F469346289 +:1041A0002107054619D014F0080118BF4FF480719B +:1041B000E20748BF41F02001A30748BF41F040019A +:1041C000600748BF41F08001302383F31188281D28 +:1041D000FFF776FF002383F31188E2050AD5302329 +:1041E00083F311884FF48061281DFFF769FF0023D6 +:1041F00083F311884FF030094FF0000A14F02008C3 +:1042000038D13B0616D54FF0300905F1380A2006A3 +:1042100010D589F31188504600F066F9002836DA87 +:104220000821281DFFF74CFF27F08003336000238F +:1042300083F31188790614D5620612D5302383F3EF +:104240001188D5E913239A4208D12B6C33B1102180 +:10425000281D27F04007FFF733FF3760002383F363 +:104260001188E30619D5AA6E1369B3B1BDE8F0470A +:104270005069184789F31188B38C95F86410284663 +:104280001940FFF7D5FE8AF31188F469B6E780B2CA +:10429000308588F31188F469B9E7BDE8F08700003C +:1042A00008B50348FFF776FFBDE80840FFF74CB8B4 +:1042B000F43A002008B50348FFF76CFFBDE808405A +:1042C000FFF742B8603B0020F8B5154682680669E2 +:1042D000AA420B46816938BF8568761AB542044602 +:1042E0000BD218462A46FCF791FEA3692B44A36122 +:1042F000A3685B1BA3602846F8BD0CD9184632465C +:10430000FCF784FEAF1BE1683A463044FCF77EFEC2 +:10431000E3683B44EBE718462A46FCF777FEE36880 +:10432000E5E7000083689342F7B51546044638BFB9 +:104330008568D0E90460361AB5420BD22A46FCF7EC +:1043400065FE63692B446361A36828465B1BA36019 +:1043500003B0F0BD0DD932460191FCF757FE01992B +:10436000E068AF1B3A463144FCF750FEE3683B443B +:10437000E9E72A46FCF74AFEE368E4E710B50A4499 +:104380000024C361029B8460C0E90000C0E90511FC +:10439000C1600261036210BD08B5D0E905329342E5 +:1043A00001D1826882B98268013282605A1C4261FE +:1043B0001970D0E904329A4224BFC36843610021D6 +:1043C000FFF714F9002008BD4FF0FF30FBE70000B5 +:1043D00070B5302304460E4683F31188A568A5B155 +:1043E000A368A269013BA360531CA36115782269ED +:1043F000934224BFE368A361E3690BB12046984769 +:10440000002383F31188284607E031462046FFF752 +:10441000DDF80028E2DA85F3118870BD2DE9F74F49 +:1044200004460E4617469846D0F81C904FF0300AC6 +:104430008AF311884FF0000B154665B12A463146C4 +:104440002046FFF741FF034660B941462046FFF78B +:10445000BDF80028F1D0002383F31188781B03B046 +:10446000BDE8F08FB9F1000F03D001902046C84796 +:10447000019B8BF31188ED1A1E448AF31188DCE747 +:10448000C0E90511C160C3611144009B8260C0E9AD +:104490000000016103627047F8B504460D461646F8 +:1044A000302383F31188A768A7B1A368013BA360F9 +:1044B00063695A1C62611D70D4E904329A4224BFB8 +:1044C000E3686361E3690BB120469847002080F3FD +:1044D000118807E031462046FFF778F80028E2DA35 +:1044E00087F31188F8BD0000D0E905239A4210B582 +:1044F00001D182687AB98268013282605A1C826175 +:104500001C7803699A4224BFC36883610021FFF7C6 +:104510006DF8204610BD4FF0FF30FBE72DE9F74F57 +:1045200004460E4617469846D0F81C904FF0300AC5 +:104530008AF311884FF0000B154665B12A463146C3 +:104540002046FFF7EFFE034660B941462046FFF7DD +:104550003DF80028F1D0002383F31188781B03B0C5 +:10456000BDE8F08FB9F1000F03D001902046C84795 +:10457000019B8BF31188ED1A1E448AF31188DCE746 +:104580000B460146184600F02DB8000000F040B878 +:10459000012838BF012010B50446204600F030F84D +:1045A00030B900F007F808B900F00CF88047F4E7DC +:1045B00010BD0000024B1868BFF35B8F704700BF4F +:1045C0004C3C002008B5062000F084F80120FFF7DD +:1045D00085F80000024B0A4601461868FFF772B9D9 +:1045E0001811002010B5054C13462CB10A4601469F +:1045F0000220AFF3008010BD2046FCE70000000061 +:10460000024B01461868FFF761B900BF181100207E +:10461000024B01461868FFF75DB900BF1811002072 +:1046200010B501390244904201D1002005E0037821 +:1046300011F8014FA34201D0181B10BD0130F2E761 +:104640002DE9F041A3B1C91A17780144044603F1DA +:10465000FF3C8C42204601D9002009E00578BD428C +:1046600004F10104F5D10CEB0405D618A54201D1E3 +:10467000BDE8F08115F8018D16F801EDF045F5D093 +:10468000E7E700001F2938B504460D4604D9162374 +:1046900003604FF0FF3038BD426C12B152F8213048 +:1046A0004BB9204600F030F82A4601462046BDE8C6 +:1046B000384000F017B8012B0AD0591C03D116233B +:1046C00003600120E7E7002442F825402846984788 +:1046D0000020E0E7024B01461868FFF7D3BF00BF98 +:1046E0001811002038B5074D00230446084611462E +:1046F0002B60FEF7F7FF431C02D12B6803B1236048 +:1047000038BD00BF503C0020FEF7E6BF034611F85D +:10471000012B03F8012B002AF9D170476F72672E25 +:104720006172647570696C6F742E663330332D4D11 +:104730006174656B4750530040A2E4F164689106D0 +:104740000041A3E5F2656992070000004261642020 +:1047500043414E496661636520696E6465782E0049 +:1047600080000000008000000000800000000000C9 +:10477000000000001918000835200008911F0008EB +:104780005918000865180008651A0008291800085B +:10479000391800082D1800083518000831180008CD +:1047A000891900083D180008052300084D18000865 +:1047B0005D19000863300000B4470008803800200D +:1047C000503A00206D61696E0069646C65000000FC +:1047D000A001A82A00000000FAAABEAA50001424D2 +:1047E000EFFF000000770000709709000000A000B4 +:1047F00000000000AAAAFAAA00005000FFFF000073 +:104800000000000000770000000000000000000031 +:10481000AAAAAAAA00000000FFFF000000000000F2 +:10482000000000000000000000000000AAAAAAAAE0 +:1048300000000000FFFF000000000000000000007A +:104840000000000000000000AAAAAAAA00000000C0 +:10485000FFFF00000000000000000000000000005A +:1048600000000000AAAAAAAA00000000FFFF0000A2 +:10487000000000000000000000000000D53F00081C +:10488000C13F0008FD3F0008E93F0008F53F000870 +:10489000E13F0008CD3F0008B93F0008094000088B +:1048A000EC0300000000000000980300000000007E +:1048B000FE2A0100D20400001C11002000000000AC +:1048C00000000000000000000000000000000000E8 +:1048D00000000000000000000000000000000000D8 +:1048E00000000000000000000000000000000000C8 +:1048F00000000000000000000000000000000000B8 +:1049000000000000000000000000000000000000A7 +:0C4910000000000000000000000000009B :00000001FF diff --git a/Tools/bootloaders/f303-PWM_bl.bin b/Tools/bootloaders/f303-PWM_bl.bin index 17ae202d0e3a8a..566e37bec0e0fb 100755 Binary files a/Tools/bootloaders/f303-PWM_bl.bin and b/Tools/bootloaders/f303-PWM_bl.bin differ diff --git a/Tools/bootloaders/f303-TempSensor_bl.bin b/Tools/bootloaders/f303-TempSensor_bl.bin index 928f635ffa6f97..ec7a3652b5fdf9 100755 Binary files a/Tools/bootloaders/f303-TempSensor_bl.bin and b/Tools/bootloaders/f303-TempSensor_bl.bin differ diff --git a/Tools/bootloaders/f303-Universal_bl.bin b/Tools/bootloaders/f303-Universal_bl.bin index eb9bebcbb2aca6..2261e310ae5b91 100755 Binary files a/Tools/bootloaders/f303-Universal_bl.bin and b/Tools/bootloaders/f303-Universal_bl.bin differ diff --git a/Tools/bootloaders/f303-Universal_bl.elf b/Tools/bootloaders/f303-Universal_bl.elf index 711136577c2da2..535bb279e61fe0 100755 Binary files a/Tools/bootloaders/f303-Universal_bl.elf and b/Tools/bootloaders/f303-Universal_bl.elf differ diff --git a/Tools/bootloaders/f303-Universal_bl.hex b/Tools/bootloaders/f303-Universal_bl.hex index feb060e57e8088..da1e3f4bf6f3e9 100644 --- a/Tools/bootloaders/f303-Universal_bl.hex +++ b/Tools/bootloaders/f303-Universal_bl.hex @@ -1,1217 +1,1172 @@ :020000040800F2 -:1000000000090020B5040008CD250008852500085A -:10001000AD25000885250008A5250008B7040008BF -:10002000B7040008B7040008B7040008C135000889 -:10003000B7040008B7040008B704000875430008B7 -:10004000B7040008B7040008B7040008B7040008A4 -:10005000B7040008B70400085940000885400008AC -:10006000B1400008DD40000809410008B70400085D -:10007000B7040008B7040008B7040008B704000874 -:10008000B7040008B7040008B704000839250008C1 -:100090006525000875250008B704000835410008EB -:1000A000B7040008B7040008B7040008B704000844 -:1000B000B7040008B7040008B7040008B704000834 -:1000C000B7040008B7040008B7040008B704000824 -:1000D000B70400086545000879450008B704000822 -:1000E0009D410008B7040008B7040008B7040008E1 -:1000F000B7040008B7040008B7040008B7040008F4 -:10010000B7040008B7040008B7040008B7040008E3 -:10011000B7040008B7040008B7040008B7040008D3 -:10012000B7040008B7040008B7040008B7040008C3 -:10013000B7040008B7040008B7040008B7040008B3 -:10014000B7040008B7040008B7040008B7040008A3 -:10015000B7040008B7040008B7040008B704000893 -:10016000B7040008B7040008B7040008B704000883 -:10017000B7040008B7040008B7040008B704000873 -:10018000B7040008B7040008B7040008B704000863 -:10019000B7040008B7040008B7040008B704000853 -:1001A0002112000800000000000000000000000014 -:1001B00053B94AB9002908BF00281CBF4FF0FF31CE -:1001C0004FF0FF3000F074B9ADF1080C6DE904CECA -:1001D00000F006F8DDF804E0DDE9022304B0704722 -:1001E0002DE9F047089D04468E46002B4DD18A42EA -:1001F000944669D9B2FA82F252B101FA02F3C2F11D -:10020000200120FA01F10CFA02FC41EA030E9440AD -:100210004FEA1C48210CBEFBF8F61FFA8CF708FBCE -:1002200016E341EA034306FB07F199420AD91CEBA6 -:10023000030306F1FF3080F01F81994240F21C81D8 -:10024000023E63445B1AA4B2B3FBF8F008FB103320 -:1002500044EA034400FB07F7A7420AD91CEB040455 -:1002600000F1FF3380F00A81A74240F20781644425 -:10027000023840EA0640E41B00261DB1D4400023AA -:10028000C5E900433146BDE8F0878B4209D9002D0E -:1002900000F0EF800026C5E9000130463146BDE898 -:1002A000F087B3FA83F6002E4AD18B4202D3824202 -:1002B00000F2F980841A61EB030301209E46002DB1 -:1002C000E0D0C5E9004EDDE702B9FFDEB2FA82F206 -:1002D000002A40F09280A1EB0C014FEA1C471FFA64 -:1002E0008CFE0126200CB1FBF7F307FB131140EA4B -:1002F00001410EFB03F0884208D91CEB010103F118 -:10030000FF3802D2884200F2CB804346091AA4B2D9 -:10031000B1FBF7F007FB101144EA01440EFB00FEAD -:10032000A64508D91CEB040400F1FF3102D2A64512 -:1003300000F2BB800846A4EB0E0440EA03409CE7B1 -:10034000C6F12007B34022FA07FC4CEA030C20FA5E -:1003500007F401FA06F31C43F9404FEA1C4900FA7E -:1003600006F3B1FBF9F8200C1FFA8CFE09FB1811FB -:1003700040EA014108FB0EF0884202FA06F20BD96E -:100380001CEB010108F1FF3A80F08880884240F2BE -:100390008580A8F102086144091AA4B2B1FBF9F002 -:1003A00009FB101144EA014100FB0EFE8E4508D9FD -:1003B0001CEB010100F1FF346CD28E456AD9023882 -:1003C000614440EA0840A0FB0294A1EB0E01A14267 -:1003D000C846A64656D353D05DB1B3EB080261EBD5 -:1003E0000E0101FA07F722FA06F3F1401F43C5E9AF -:1003F000007100263146BDE8F087C2F12003D840E5 -:100400000CFA02FC21FA03F3914001434FEA1C4726 -:100410001FFA8CFEB3FBF7F007FB10360B0C43EA18 -:10042000064300FB0EF69E4204FA02F408D91CEBC8 -:10043000030300F1FF382FD29E422DD902386344C6 -:100440009B1B89B2B3FBF7F607FB163341EA034166 -:1004500006FB0EF38B4208D91CEB010106F1FF38B5 -:1004600016D28B4214D9023E6144C91A46EA0046AC -:1004700038E72E46284605E70646E3E61846F8E63E -:100480004B45A9D2B9EB020864EB0C0E0138A3E787 -:100490004646EAE7204694E74046D1E7D0467BE768 -:1004A000023B614432E7304609E76444023842E7E0 -:1004B000704700BF02E000F000F8FEE772B6374870 -:1004C00080F30888364880F3098836483649086042 -:1004D00040F20000CCF200004EF63471CEF2000182 -:1004E0000860BFF34F8FBFF36F8F40F20000C0F280 -:1004F000F0004EF68851CEF200010860BFF34F8F36 -:10050000BFF36F8F4FF00000E1EE100A4EF63C7122 -:10051000CEF200010860062080F31488BFF36F8FCD -:1005200003F04EFC03F0C2FC4FF055301F491B4A4C -:1005300091423CBF41F8040BFAE71D49184A914229 -:100540003CBF41F8040BFAE71A491B4A1B4B9A427D -:100550003EBF51F8040B42F8040BF8E7002018499D -:10056000184A91423CBF41F8040BFAE703F02CFC17 -:1005700003F0D8FC144C154DAC4203DA54F8041BBC -:100580008847F9E700F042F8114C124DAC4203DA0B -:1005900054F8041B8847F9E703F014BC0009002055 -:1005A000001100200000000808ED00E0000100201C -:1005B00000090020704B0008001100207C11002071 -:1005C00080110020583C0020A0010008A401000870 -:1005D000A4010008A40100082DE9F04F2DED108AB8 -:1005E000C1F80CD0C3689D46BDEC108ABDE8F08F01 -:1005F000002383F311882846A047002003F06AF9FE -:10060000FEE703F0CDF800DFFEE70000F8B500F0EC -:1006100019FE03F079FB074603F0C8FB05460028E6 -:1006200040D12C4B9F423DD001339F423DD02A4BBD -:1006300027F0FF029A423BD1F8B200F03FFC2E4671 -:1006400042F2107400F040FC08B10024264601F08C -:10065000B1F888B3032000F045F80024264635B1F0 -:100660001E4B9F4203D003F099FB00242646002036 -:1006700003F054FB1A4B1B6913F0400322D00EB158 -:1006800000F046F800F052FC00F0DEFD01F0A6FF9D -:100690000546CCB101F0A2FF401BA04214D900F0E6 -:1006A00037F8F3E72E460024CCE704460126C9E7D5 -:1006B00006464FF47A74C5E7002CD0D04FF47A7414 -:1006C0000126CCE71C46DDE700F078FC012003F0B2 -:1006D00007F9DEE7010007B0000008B0263A09B0CC -:1006E00000040048084B187003280CD8DFE800F01D -:1006F00008050208022000F003BE022000F0F8BD49 -:10070000024B00225A6070478011002084110020A3 -:1007100038B501F04FF830B11F4B03221A701F4B50 -:1007200000225A6038BD1E4B1E4A19680131F9D0AB -:1007300004339342F9D11C4C194DD4F80428AA4231 -:10074000F0D31A4B9B6803F1006303F5D0439A4240 -:10075000E8D203F0F7FA03F009FB002000F08EFD69 -:100760000220FFF7BFFF124BDA690022DA61D96974 -:1007700099699A619B6972B64FF0E0233021C3F802 -:10078000085DD4F80038D4F8042881F311889D4618 -:1007900083F308881047C5E78011002084110020EA -:1007A00000680008206800080060000800110020B0 -:1007B00000100240094A136849F2690099B21B0C03 -:1007C00000FB01331360064B186844F2506182B29B -:1007D000000C01FB0200186080B270471411002069 -:1007E0001011002010B500211022044600F0A2FDD7 -:1007F000034B03CB206061601868A06010BD00BF90 -:10080000ACF7FF1F2DE9F041ADF5507D0DF13C082F -:100810006EAC40F2751207460D4610A80021C8F8CC -:10082000001000F087FD4FF4C4720021204600F054 -:1008300081FD01F0D3FE254B4FF47A72B0FBF2F04C -:10084000186093E80700022384E807000DF5ED70B7 -:100850002382FFF7C7FF4EF603431D49238407A8F1 -:1008600004F0B6F81C2384F832310DF2EB226B440D -:100870000DF1340C1E4603CE6645106051603346C0 -:1008800002F10802F6D1306810604146012220468C -:1008900000F09CFD00230393AB7E029305F1190346 -:1008A000019380B20123CDE904800093E97E05A382 -:1008B000D3E90023384602F059FA0DF5507DBDE822 -:1008C000F08100BF9E6AC421818A46EE8C1100200F -:1008D000E04900082DE9F0412C4C237ADAB080463B -:1008E0000D465BBB27A9284600F080FE074600287E -:1008F00042D19DF89D60C82E3ED801464FF4A662B5 -:10090000204600F017FD4FF48073C4F8F8314FF41F -:100910000073C4F80C334FF44073C4F820343246EB -:100920000DF19E0104F1090000F0F2FC26449DF84F -:100930009C30777223720BB9EB7E237281220021E7 -:1009400006AC27A800F0F6FC0122214627A800F0FB -:1009500089FE00230393AB7E029305F1190380B255 -:1009600001932823CDE904400093E97E05A3D3E950 -:100970000023404602F0FAF95AB0BDE8F08100BF0A -:10098000AFF3008026417272DF25D7B7A83200206E -:10099000F0B5254E4FF48A7505FB0065F1B096F869 -:1009A000D83085F8DC300024D822214685F8E8408C -:1009B0003AA800F0BFFC06F1090000F0B3FCD5F83E -:1009C000E4308DF8F000C2B206AF06F109010DF176 -:1009D000F100CDE93A3400F09BFC394601223AA8F7 -:1009E00000F06CFE80B2CDE9047008230127CDE948 -:1009F000023706F1D803019330230093317A0B4874 -:100A000007A3D3E9002302F0B1F9A04206DD01F00B -:100A1000E5FDC5F8E000384671B0F0BD2046FBE7C3 -:100A200078F6339F93CACD8DA8320020A4210020F0 -:100A30002DE9F0411D4D1E4E1E4F86B0284602F096 -:100A4000C1F9034658B30024CDE90344ADF814407E -:100A5000027B8DF8142099684068029403AA03C2AF -:100A60001B68DFF8548043F00043029301F0B8FDA7 -:100A7000821941F10003009402A9384601F07CF884 -:100A8000A04205DD284602F0A1F988F80040D5E72C -:100A900098F80030072B05D8013388F8003006B0ED -:100AA000BDE8F081014802F091F9F8E7A4210020A7 -:100AB00040420F00D8210020DD37002070B50D46E0 -:100AC00014461E4602F0AEF850B9022E10D1012C89 -:100AD0000ED112A3D3E90023C5E90023012007E0CA -:100AE000282C10D005D8012C09D0052C0FD00020BF -:100AF00070BD302CFBD10BA3D3E90023ECE70BA393 -:100B0000D3E90023E8E70BA3D3E90023E4E70BA331 -:100B1000D3E90023E0E700BFAFF30080401DA12030 -:100B200026812A0B78F6339F93CACD8D9E6AC42105 -:100B3000818A46EE26417272DF25D7B7F017304A18 -:100B400039059E5638B505460E4C0021013500F09A -:100B5000B7FBA4F82C55B4F82C0500F099FB78B13C -:100B6000B4F82C0500F0A4FB014648B9B4F82C05F4 -:100B700000F0A6FBB4F82C350133A4F82C35EAE7D5 -:100B800038BD00BFA832002010B50A4B0A4A1A60CF -:100B900003F5805393F860203AB9DC6D2CB1204600 -:100BA00000F082FE204603F053FEBDE810400348EB -:100BB00000F07ABED82100203C4A000820320020F4 -:100BC0002DE9F04F8FB000AF05460C4602F02AF831 -:100BD000002849D1237E022B1BD1E38A012B18D197 -:100BE00001F0FCFC0646FFF7E5FD03464FF4C87034 -:100BF000DFF8C482B3FBF0F206F5167602FB103381 -:100C000016FA83F3C8F80030E37E33B9A34B002211 -:100C10001A703C37BD46BDE8F08F07F1240120462D -:100C200000F0A2FC0028F4D107F11400FFF7DAFD70 -:100C300097F8264007F11401224607F1270003F038 -:100C400051FE0028E2D10F2C08D8944B1C70D8F824 -:100C50000030A3F51673C8F80030DAE797F82410CF -:100C6000284601F0D7FFD4E7E38A282B2BD010D8F1 -:100C7000012B23D0052BCCD1BFF34F8F8849894B53 -:100C8000CA6802F4E0621343CB60BFF34F8F00BF2A -:100C9000FDE7302BBDD1844EE17E327A9142B8D14E -:100CA000607E3146002291F8DC50854200F0A5803C -:100CB0000132042A01F58A71F5D1AAE721462846B6 -:100CC000FFF7A0FDA5E721462846FFF703FEA0E7B2 -:100CD000B2F8EC507B6005F103094FEA99094FEA3D -:100CE0008902D11DC908A8EBC1039D46EB4600212E -:100CF000584600F01FFB04F1EE012A4631445846E5 -:100D000000F006FB7B6813B9012000F0B7FA96F8F3 -:100D1000D20000F0BDFA044630B9307200F0D8FAC3 -:100D2000204600F0ABFAB1E0D6F8D4203AB996F8F4 -:100D3000D200B6F82C25824201D8FFF703FFD6F87F -:100D4000D4202A44944208D296F8D200B6F82C2532 -:100D50000130824201D8FFF7F5FE70685FFA89F230 -:100D6000594600F0EFFA08B9C54679E0726896F87E -:100D7000D2002A447260D6F8D42005EB0209C6F8E6 -:100D8000D49000F085FA814509D396F8D220D6F8A0 -:100D9000D4000132001B86F8D220C6F8D400FF2D03 -:100DA0000FD80024347200F093FA204600F066FA5F -:100DB00000F000FD3D4B188108B9FFF7A9FCC546BE -:100DC00027E7BB6896F8D9000AFB0362FB68D2F8F4 -:100DD000E41082F8E83001F58061C2F8E030C2F832 -:100DE000E410FFF7D5FDFFF723FE96F8D920013276 -:100DF00002F0030286F8D920B6E74FF48A7A0AFB9C -:100E000002F505F1EA013144204600F083FCF86068 -:100E100000287FF4FEAE3544012285F8E82001F079 -:100E2000DDFBD5F8E020D6ED007ADFED216A801AEF -:100E3000192838BF192040F6B832904228BF104612 -:100E4000B8EE677A07EE900AF8EEE77A67EEA67AD0 -:100E5000DFED186AE7EE267AFCEEE77AC6ED007A57 -:100E600096F8D930BB60BA6873680AFB02F432198D -:100E700092F8E81059B1D2F8E4108B42E8463FF4FA -:100E800027AF002182F8E810C2F8E010C546736869 -:100E9000064A9B0A01331381BBE600BF9D21002057 -:100EA00000ED00E00400FA05A83200208C110020BB -:100EB000CDCCCC3D6666663FA0210020014B18706A -:100EC000704700BF9811002038B54FF00054134B05 -:100ED00022689A4220D1124B627D12481A70237DFB -:100EE00003724FF48073C0F8F8314FF40073C0F808 -:100EF0000C3300254FF44073C0F820340A49C0F881 -:100F0000E450C922093000F003FAE02229462046C5 -:100F100000F010FA012038BD0020FCE79AAD44C56E -:100F200098110020A83200201600002037B500F0EC -:100F300041FC194D194928810223012218486B717F -:100F400001F0EAF900230193164B17490093174863 -:100F5000174B4FF4805201F035FE164B197811B142 -:100F6000124801F057FE01F039FB0446FFF722FC5E -:100F70004FF4C873B0FBF3F202FB130304F51670D1 -:100F800010FA83F00C4B186002F010FF08B10F2329 -:100F90002B8103B030BD00BF8C11002040420F00F8 -:100FA000D8210020BD0A00089C110020A4210020A7 -:100FB000C10B000898110020A02100202DE9F04F5E -:100FC0002DED028B8EA7D7E900670FF23C29D9E9F6 -:100FD0000089864C95B00DAD9FED828BFFF728FD03 -:100FE000DFF82CB200230C93ADF83C300D936B600E -:100FF00000230DF125028DED008B4FF0010A09A9A8 -:1010000058468DF825308DF824A001F035F99DF86B -:1010100024200023002A40F0AB80204601F002FE8D -:101020000546002847D1DFF8ECB101F0D7FADBF82C -:10103000003098423FD301F0D1FA0790FFF7BAFB96 -:10104000079A4FF4C873B0FBF3F101FB130302F5E9 -:10105000167010FA83F0CBF80000DFF8BCB19BF8F3 -:1010600000100791002914BF2B46534610A88DF895 -:101070003030FFF7B7FB0799C1F11002D2B2062A50 -:1010800010AB28BF062219440DF13100079200F081 -:101090003FF9079A0CAB0393182302930132544B88 -:1010A000D2B2CDE900A304923B463246204601F07D -:1010B000FFFD8BF8005001F091FA4E4A4E4D136837 -:1010C000C31AB3F57A7F32D3106001F089FA024671 -:1010D0000B46204601F084FE204601F0A3FD30B30C -:1010E0002B7ADFF838A1002B14BF032302238AF8E0 -:1010F000053001F073FA0DF1400B4FF47A730122C1 -:10110000B0FBF3F05946CAF80000504600F004FA6C -:1011100018230293394B019380B240F25513CDE965 -:1011200003B0009342464B46204601F0C1FD2B7AA6 -:10113000CBB101F053FA4FF0000A83464FF48A72A4 -:1011400095F8D900504400F0030002FB005393F8D7 -:10115000E81089B30AF1010ABAF1040FF0D12B7A31 -:10116000002B7FF438AF15B0BDEC028BBDE8F08FDB -:101170004FF0904110A84A6982F010024A61194666 -:10118000102200F0D7F80DF126030AAA0CA9584640 -:1011900000F0F0FD95E8030011AB83E803009DF833 -:1011A0003C308DF84C300C9B109310A9DDE90A23DC -:1011B000204601F0E9FF1BE7D3F8E01049B12B68A6 -:1011C000FA2B38BFFA23ABEB01010533B1EB430F28 -:1011D000C0D3FFF7DDFB4FF48A720028BAD1BEE717 -:1011E000AFF300800000000000000000A4210020F8 -:1011F0009C210020D8370020A8320020DC370020B6 -:10120000401DA12026812A0BF1C6A7C1D068080F76 -:10121000D8210020A02100209D2100208C11002039 -:1012200008B5054800F040FEBDE80840034A0449FF -:10123000002003F007BB00BFD82100201838002091 -:10124000890B00087047000070B502F013FC094ECE -:10125000094D3080002428683388834208D902F081 -:1012600005FC2B6804440133B4F5D04F2B60F2D356 -:1012700070BD00BF0C380020E037002002F086BCB3 -:1012800000F10060920000F5D04002F02DBC00009B -:10129000054B1A68054B1B889B1A834202D91044E0 -:1012A00002F0E4BB00207047E03700200C3800203B -:1012B000024B1B68184402F0DFBB00BFE037002080 -:1012C000024B1B68184402F0E9BB00BFE037002066 -:1012D000064991F8243033B10023086A81F824309C -:1012E0000822FFF7CDBF0120704700BFE437002080 -:1012F000022802BF4FF0904310229A61704700000D -:10130000022802BF4FF090434FF480129A61704759 -:1013100010B50023934203D0CC5CC4540133F9E7E9 -:1013200010BD000003460246D01A12F9011B002925 -:10133000FAD1704702440346934202D003F8011BDE -:10134000FAE770472DE9F8431F4D144695F824201D -:101350000746884652BBDFF870909CB395F824305E -:101360002BB92022FF2148462F62FFF7E3FF95F8B3 -:101370002400C0F10802A24228BF2246D6B241464C -:10138000920005EB8000FFF7C3FF95F82430A41B03 -:101390001E44F6B2082E17449044E4B285F8246047 -:1013A000DBD1FFF795FF0028D7D108E02B6A03EBCC -:1013B00082038342CFD0FFF78BFF0028CBD10020E0 -:1013C000BDE8F8830120FBE7E43700202DE9F04772 -:1013D0000D46044600219046284640F27912FFF758 -:1013E000A9FF234620220021284601F06FFE231D7D -:1013F00002222021284601F069FE631D03222221DA -:10140000284601F063FEA31D03222521284601F092 -:101410005DFE04F1080310222821284601F056FE43 -:1014200004F1100308223821284601F04FFE04F190 -:10143000110308224021284601F048FE04F112035E -:1014400008224821284601F041FE04F1140320221D -:101450005021284601F03AFE04F118034022702181 -:10146000284601F033FE04F120030822B02128466B -:1014700001F02CFE04F121030822B821284601F0D6 -:1014800025FE04F12207C0263B46314608222846A5 -:10149000083601F01BFEB6F5A07F07F10107F3D176 -:1014A00004F1320308223146284601F00FFE0027DE -:1014B00004F1330A94F832304FEAC7099F4209F524 -:1014C000A47615D3B8F1000F08D1314604F599730D -:1014D0000722284601F0FAFD09F24F16274694F834 -:1014E00032213B1B93420CD3F01DC008BDE8F087AE -:1014F0000AEB070308223146284601F0E7FD0137D1 -:10150000D8E707F2331331460822284601F0DEFD02 -:1015100008360137E3E7000013B50446084600210A -:1015200001602346C0F803102022019001F0CEFD97 -:101530000198231D0222202101F0C8FD0198631D9E -:101540000322222101F0C2FD0198A31D03222521BF -:1015500001F0BCFD019804F108031022282101F0DC -:10156000B5FD072002B010BDF7B50023047F009140 -:101570000E4607221946054601F06CFC731C0093C9 -:10158000012200230721284601F064FCC4B9B31CE2 -:101590000093052223460821284601F05BFC0D2418 -:1015A0003746B278BB1B934211D32B7FA88A0734EE -:1015B000E408BBB9844294BF0020012003B0F0BD11 -:1015C000AB8ADB00083BDB08B3700824E8E7FB1CB0 -:1015D0000093214600230822284601F03BFC0834F2 -:1015E0000137DEE7201A18BF0120E7E7F7B500232F -:1015F000047F00910E4608221946054601F02AFC98 -:10160000731CC4B90822009311462346284601F0F2 -:1016100021FC1024012372785F1C013B934211D3FB -:101620002B7FA88A0734E408BBB9844294BF00200A -:10163000012003B0F0BDAB8ADB00083BDB08737010 -:101640000824E7E7F31900932146002308222846DF -:1016500001F000FC08343B46DDE7201A18BF0120EA -:10166000E7E70000F8B50E46054614460021812242 -:101670003046FFF75FFE2B4608220021304601F07E -:1016800025FD7CB96B1C07220821304601F01EFDA8 -:101690000F2401236A785F1C013B934204D3E01DB1 -:1016A000C008F8BD0824F4E7EB19214608223046AB -:1016B00001F00CFD08343B46ECE70000F8B50E469F -:1016C000054614460021CE223046FFF733FE2B4656 -:1016D00028220021304601F0F9FC7CB905F108030D -:1016E00008222821304601F0F1FC30242F462A7AC6 -:1016F0007B1B934204D3E01DC008F8BD2824F5E706 -:1017000007F1090321460822304601F0DFFC0834C6 -:101710000137ECE7F7B5047F00910E460123102254 -:101720000021054601F096FBC4B9B31C00930922C1 -:1017300023461021284601F08DFB19243746728874 -:10174000BB1B9A4211D82B7FA88A0734E408BBB987 -:10175000844294BF0020012003B0F0BDAB8ADB00BF -:10176000103BDB0873801024E8E73B1D0093214603 -:1017700000230822284601F06DFB08340137DEE71C -:10178000201A18BF0120E7E730B5094D0A449142FD -:101790000DD011F8013B5840082340F30004013BF1 -:1017A0002C4013F0FF0384EA5000F6D1EFE730BD80 -:1017B0002083B8EDF7B5364A106851686B4603C30D -:1017C0006A4634493448082303F09CF8044690BB29 -:1017D0000A25324A106851686B4603C36A4630498D -:1017E0002D48082303F08EF80446002847D00369EB -:1017F000B3F5663F43D8B0F86620B2F57B7F3ED1A3 -:10180000284A024402F15C018B4238D35C3B2249F6 -:1018100000209E1AFFF7B8FF3246074604F1640124 -:101820000020FFF7B1FFA3689F4228D1E3689842E8 -:1018300008BF002523E00369B3F5663F26D8428B35 -:10184000B2F57B7F20D1174A024402F110018B428E -:1018500018D3103B104900209D1AFFF795FF2A4628 -:10186000064604F118010020FFF78EFFA3689E4290 -:1018700002D1E368984201D00D25AAE70025284649 -:1018800003B0F0BD1025A4E70C25A2E70B25A0E7C7 -:10189000004A0008DC97030000680008094A0008B5 -:1018A000909703000898FFF710B5037C044613B91E -:1018B000006803F00FF8204610BD00000023BFF3BE -:1018C0005B8FC360BFF35B8FBFF35B8F8360BFF33E -:1018D0005B8F7047BFF35B8F0068BFF35B8F704710 -:1018E00070B505460C30FFF7F5FF05F10806044614 -:1018F0003046FFF7EFFFA04206D930466D68FFF78C -:10190000E9FF2544281A70BD3046FFF7E3FF201A8F -:10191000F9E7000070B50546406898B105F1080088 -:10192000FFF7D8FF05F10C0604463046FFF7D2FF5B -:101930008442304694BF6D680025FFF7CBFF013C21 -:101940002C44201A70BD000038B50C460546FFF740 -:10195000C7FFA04210D305F10800FFF7BBFF044406 -:101960006868B4FBF0F100FB1144BFF35B8F01200A -:10197000AC60BFF35B8F38BD0020FCE72DE9F04180 -:10198000144607460D46FFF7C5FF844228BF0446AC -:10199000D4B1B84658F80C6B4046FFF79BFF304473 -:1019A000286040467E68FFF795FF331A9C4203D8B3 -:1019B0006C600120BDE8F0816B60A41B3B68AB60EC -:1019C0002044E8600220F5E72046F3E738B50C46EE -:1019D0000546FFF79FFFA04210D305F10C00FFF76B -:1019E00079FF04446868B4FBF0F100FB1144BFF3D5 -:1019F0005B8F0120EC60BFF35B8F38BD0020FCE7FC -:101A00002DE9FF41884669460746FFF7B7FF6C4658 -:101A100006B204EBC6060025B44209D0626820680D -:101A200008EB0501FFF774FC636808341D44F3E715 -:101A300029463846FFF7CAFF284604B0BDE8F081C2 -:101A4000F8B505460C300F46FFF744FF05F10806D0 -:101A500004463046FFF73EFFA042304688BF6C6820 -:101A6000FFF738FF201A386020B130462C68FFF7A6 -:101A700031FF2044F8BD000073B5144606460D46FC -:101A8000FFF72EFF844228BF04460190DCB101A974 -:101A90003046FFF7D5FF019B33B93268C5E9023301 -:101AA000C5E9002401200CE09C4238BF0194286065 -:101AB000019868608442F5D93368AB60241AEC6001 -:101AC000022002B070BD2046FBE700002DE9FF4177 -:101AD0000F466946FFF7D0FF6C4600B204EBC00525 -:101AE0000026AC4209D0D4F8048054F8081BB81979 -:101AF0004246FFF70DFC4644F3E7304604B0BDE82C -:101B0000F081000038B50546FFF7E0FF04460146C6 -:101B10002846FFF719FF204638BD0000302383F325 -:101B2000118862B670470000002383F3118862B603 -:101B30007047000010B4026854681A4623465DF8E6 -:101B4000044B184701207047002070470020704761 -:101B500070470000002070470E20704700F580504D -:101B600090F8C800C0F340007047000000F58050B6 -:101B700090F9C90070470000F7B50C68BDF82070F7 -:101B800014F000541E466FD10B7B082B6CD8FFF766 -:101B9000C5FF4569AB685B010CD4AB681B0108D479 -:101BA000AC6814F080545DD1FFF7BEFF204603B04F -:101BB000F0BD01240B6804F1180C002BB8BFDB004A -:101BC0004FEA0C1CB4BF43F004035B0545F80C302E -:101BD0000B680FFA84FC13F0804F18BF05EB0C1E46 -:101BE00005EB0C1C1EBFDEF8803143F00203CEF87B -:101BF00080310B7BCCF8843105EB04158B68C5F87C -:101C00008C314B68C5F88831DCF8803143F0010332 -:101C1000CCF8803100EB441541F268031D4403EB1E -:101C200044130344C5E9002608330D4601F10C0CAA -:101C300055F804EB43F804EB6545F9D184342D885D -:101C40001D8000EB441407F00303257925F00B05F4 -:101C50002B432371FFF768FF0097334600F0E0FC49 -:101C60000120A4E70224A5E74FF0FF309FE7000022 -:101C700013B500F580540191E06DFFF74BFE1F286E -:101C80000AD90199E06D2022FFF7BAFEA0F12003E6 -:101C90005842584102B010BD0020FBE708B500F5DE -:101CA0008050FFF73BFFC06DFFF708FEBDE808401E -:101CB000FFF73ABF00220260828142608260704773 -:101CC00010B500220023C0E900230023044603814D -:101CD0000C30FFF7EFFF204610BD0000F0B50546C1 -:101CE00000F580500C4690F8C83013F0040FC3F391 -:101CF000800108BF114661F3820304F1840680F875 -:101D0000C83005EB461389B01B79D8072ED57AB3B6 -:101D100019072DD46846FFF7D3FF05EB441303F5ED -:101D2000835303F1180703AA10331868596814463F -:101D300003C40833BB422246F7D1186820609B8851 -:101D4000A380DDE90E23CDE900230123ADF808309F -:101D50002B686946DB6B2846984705EB46152B79BF -:101D60001A075CBF43F008032B7101E0002AF4D18D -:101D700009B0F0BD2DE9F047074688B007F580545B -:101D800068469A468846FFF7C9FE9146FFF798FFD6 -:101D9000E06DFFF7A5FD1F2829D9E06D20226946D7 -:101DA000FFF7B0FE202822D103AD444605AB2E46F6 -:101DB00003CE9E4220606160354604F10804F6D1EE -:101DC00030682060B388A380DDE90023C9E90023DF -:101DD000BDF80830AAF80030FFF7A6FE4A46534681 -:101DE0004146384608B0BDE8F04700F007BCFFF7B1 -:101DF0009BFE002008B0BDE8F08700002DE9F84FF9 -:101E00000023C0E90133254B044640F8183B0F4638 -:101E1000FFF750FF04F12800FFF752FF04F14808D4 -:101E200004F582554646083530462036FFF748FF10 -:101E3000AE42F9D104F580554FF480534FF00009BC -:101E4000C5E91339C5F848800123EE6504F58758C4 -:101E500004F58456C5F8549085F8583085F86030FC -:101E6000083608F108084FF0000A4FF0000B46E969 -:101E700008ABA6F11800FFF71DFF203646F8289C96 -:101E80004645F4D185F8C97017B1054800F0A0FBAC -:101E9000044B63612046BDE8F88F00BF3C4A000850 -:101EA000144A00080064004010B5044B1978044639 -:101EB0004A1C1A70FFF7A2FF204610BD14380020FC -:101EC0002DE9F047002950D0294B2A4FB7FBF1F5F7 -:101ED00099428CBF0A231123581EB5FBF3FC03FB68 -:101EE0001C53C4B22BB102280346F5D80020BDE82C -:101EF000F0870CF1FF36B6F5806FF7D2C4EBC40E55 -:101F00000EF103034FEAE309C3F3C703A4EB03088D -:101F100009F1010A4FF47A755FFA88F009FB05555B -:101F20005AFA88F8B5FBF8F5B5F5617FC1BF0EF137 -:101F3000FF33C3F3C703E01AC0B25C1C50FA84F449 -:101F40000CFB04F4B7FBF4F4A142CFD1013BDBB2AC -:101F50000F2BCBD80138C0B20728C7D80021107189 -:101F600016809170D3700120C1E70846BFE700BF1B -:101F70003F420F000051250270B505460E464FF452 -:101F80007A746B695B6803F00103B3424FF00100A0 -:101F900004D001F0A5FC013CF3D1204670BD000047 -:101FA00030B54269936913F0700F16D000230B4CC3 -:101FB000936103F1840200EB421211794D0709D5B8 -:101FC000890707D5416954F823508D60117941F094 -:101FD000040111710133032BEBD130BD284A0008F5 -:101FE00073B51D46436916469A68D207044609D55B -:101FF0009A6801219960C2F34002CDE90065002191 -:10200000FFF76CFE63699A68D1050BD59A684FF4A7 -:1020100080719960C2F34022CDE90065012120461C -:10202000FFF75CFE63699A68D2030BD59A684FF498 -:1020300080319960C2F34042CDE90065022120461B -:10204000FFF74CFE204602B0BDE87040FFF7A8BF86 -:10205000F8B50446466900296CD106F10C073868CA -:1020600080076AD006EB01153868D5F8B00110F08A -:10207000040FD5F8B0011ABFC00840F00040400D71 -:10208000A061D5F8B0C11CF0020F1CBF40F0804029 -:10209000A061D5F8B40106EB011100F00F0084F83F -:1020A0002400D1F8B8012077D1F8B801000A607790 -:1020B000D1F8B801000CA077D1F8B801000EE07794 -:1020C000D1F8BC0184F82000D1F8BC01000A84F8E2 -:1020D0002100D1F8BC01000C84F82200D1F8BC1119 -:1020E000090E84F823103821396004F1340004F11A -:1020F000180104F1240551F8046B40F8046BA9425F -:10210000F9D109880180C4E90A23214600232386E6 -:1021100051F8283B2046DB6B984704F58052204657 -:1021200092F8C83043F0040382F8C830BDE8F840A4 -:10213000FFF736BF06F1100791E7F8BD10B504466A -:1021400000F04EFA02460B4652EA030102D0013A71 -:1021500063F100030449086820B12146BDE810403E -:10216000FFF776BF10BD00BF10380020F8B500F5AE -:1021700083511E46FFF7D2FCDFF844C0083100242B -:1021800004F1840500EB45152B795F070ED4DB06BF -:102190000CD5D1E900739742B34107D243695CF88B -:1021A00024709F602B7943F004032B710134032CBE -:1021B00001F12001E4D1BDE8F840FFF7B5BC00BF54 -:1021C000284A000808B5FFF7A9FCFFF7E9FEBDE8BB -:1021D0000840FFF7A9BC0000F8B5436905469868B8 -:1021E00000F0E050B0F1E05F0F461FD0E8B1FFF71C -:1021F00095FC05F583541034002606F1840305EBA5 -:1022000043131B791A0706D50136032E04F1200467 -:10221000F3D1012007E05B07F6D42146384600F0F1 -:1022200039FA0028F0D1FFF77FFCF8BD0120FCE768 -:1022300000F5805008B5FFF771FCC06DFFF750FB4B -:10224000FFF772FC43090CBF0120002008BD00000D -:10225000F8B51D46002313700F4606461446FFF7D7 -:10226000E7FF80F00100387025B129463046FFF7BE -:10227000B3FF2070F8BD00002DE9B8410C461546AB -:102280001F46804600F0ACF90B462178024609B99A -:10229000287850B14046FFF769FFFFF793FF3B46B0 -:1022A0002A462146FFF7D4FF0120BDE8B88100008F -:1022B00010B5FFF733FC174BDA6942F00072DA61B0 -:1022C0001A6942F000721A611A6900F5805422F00E -:1022D00000721A61FFF728FC94F8C830DB0718D4A5 -:1022E000B9B103211320FFF719FC01F0C7F903214D -:1022F000142001F0C3F90321152001F0BFF994F86F -:10230000C83043F0010384F8C830BDE81040FFF73F -:102310000BBC10BD001002402DE9F04700F58055C0 -:1023200088B095F8C930012B0446884616467FD8F8 -:10233000804F57F823200AB947F82300D7F800A0A8 -:10234000C4F80C802674BAF1000F63D095F8C93038 -:10235000012B6FD001212046FFF7AAFFFFF7DEFB1C -:102360006269136823F0020313606269136843F023 -:1023700001031360636900275F6101212046FFF7B5 -:10238000D3FBFFF7F9FD002800F09580E86DFFF71B -:1023900095FA04F58359BA4609F10809202200216B -:1023A0006846FEF7C7FF02A8FFF784FCCDF818A027 -:1023B0006A4609EB07030DF1180E9446BCE80300CA -:1023C000F44518605960624603F10803F5D1DCF862 -:1023D0000000186020379CF804201A71602FDDD1AE -:1023E00095F8C8306FF38203002785F8C8306A4635 -:1023F00041462046ADF80070ADF802708DF80470CB -:10240000FFF75EFD636948BB4FF400421A6008B0F5 -:10241000BDE8F08741F2D00002F01CFA814610B10D -:102420005146FFF7EBFCC7F80090B9F1000F8DD1D2 -:102430000020ECE7386803681B6B984701460028CA -:1024400088D13868FFF734FF3868036832465B6824 -:102450004146984700287FF47DAFE9E761221A6082 -:102460009DF802309DF803201B06120402F470222E -:1024700003F040731343BDF80020C2F30902134375 -:102480009DF804201205022E02F4E0020CBF4FF06A -:1024900000410021134362690B43D3616369132236 -:1024A0005A616269136823F00103136039462046BC -:1024B000FFF762FD08B96369A6E795F8C93093BBD9 -:1024C0006169D1F8002242F00102C1F8002261697D -:1024D000D1F8002222F47C5222F00E02C1F8002230 -:1024E0006169D1F8002242F46062C1F80022626999 -:1024F000C2F814326269C2F80432626941F6FF71AF -:10250000C2F80C126269C2F840326269C2F8443201 -:1025100063690122C3F81C226269D2F8003223F0F9 -:102520000103C2F8003295F8C83043F0020385F881 -:10253000C8306CE71038002008B500F051F850EAB8 -:102540000103024602D0421E61F10001044B1868EB -:1025500010B10B46FFF744FDBDE8084001F064B838 -:102560001038002008B50020FFF7E8FDBDE808405E -:1025700001F05AB808B50120FFF7E0FDBDE80840BA -:1025800001F052B800B59BB0EFF3098168226846AC -:10259000FEF7BEFEEFF30583014B9B6BFEE700BF2A -:1025A00000ED00E008B5FFF7EDFF000000B59BB0BF -:1025B000EFF3098168226846FEF7AAFEEFF3058370 -:1025C000014B5B6BFEE700BF00ED00E0FEE70000A3 -:1025D0000FB408B5029801F019F9FEE701F02EBB1F -:1025E00001F004BB13B56C4684E80600031D94E8B3 -:1025F000030083E80500012002B010BD73B58568B3 -:10260000019155B11B885B0707D4D0E900369B6B5D -:102610009847019AC1B23046A847012002B070BD68 -:10262000F0B5866889B005460C465EB1BDF8383015 -:102630005B070AD4D0E900379B6B98472246C1B2AA -:102640003846B047012009B0F0BD00220023CDE993 -:1026500000230023ADF808300A4603AB01F1080659 -:10266000106851681C4603C40832B2422346F7D1B1 -:10267000106820609288A280FFF7B2FF0423ADF8B3 -:1026800008302B68CDE90001DB6B69462846984786 -:10269000D8E7000030B503680968DD0FB5EBD17FDE -:1026A00023F0604421F060424FEAD1700BD0002B40 -:1026B000B8BFA40C0029B8BF920C944202D034BF1A -:1026C0000120002030BD944205D1C1F38070C3F3D6 -:1026D00080738342F6D194422CBF00200120F1E7A1 -:1026E0002DE9F041456A15B94162BDE8F0814B68BA -:1026F00023F06047C3F38A464FEAD37EC3F3807862 -:1027000016EA230638BF3E46AC462B465A68BEEB57 -:10271000D27F22F060440AD0002A18DAA40CB44216 -:1027200017D19D420FD10D60DEE71346EEE7A742B9 -:1027300007D102F08044C2F3807242450BD054B1FD -:10274000EFE708D2EDE7CCF800100B60CDE7B4421C -:1027500001D0B442E5D81A689C46002AE5D1196038 -:10276000C3E700002DE9F047089D01F007044FEA98 -:10277000D508224405F0070500EBD1004FF47F494E -:10278000944201D1BDE8F08704F0070705F0070A7D -:1027900057453E4638BF5646C6F10806111B8E42C5 -:1027A00028BF0E46E10808EBD50E415C13F80EC0B9 -:1027B000B94029FA06F721FA0AF1FFB28CEA0101C1 -:1027C00047FA0AF739408CEA010C03F80EC034448A -:1027D0003544D5E780EA0120082341F2210201B205 -:1027E0004000002980B203F1FF33B8BF504013F01E -:1027F000FF03F4D17047000038B50C468D18A54290 -:1028000000D138BD14F8011BFFF7E4FFF7E7000023 -:1028100042684AB1136843604389818901339BB29E -:102820009942438138BF83811046704770B588B0A4 -:10283000202204460D4668460021FEF77BFD204617 -:102840000495FFF7E5FF024658B16B46054608AE12 -:102850001C4603CCB44228606960234605F1080594 -:10286000F6D1104608B070BD082817D909280CD039 -:102870000A280CD00B280CD00C280CD00D280CD01A -:102880000E2814BF4020302070470C2070471020C5 -:1028900070471420704718207047202070470000B0 -:1028A000082817D90C280CD910280CD914280CD9B1 -:1028B00018280CD920280CD930288CBF0F200E20C6 -:1028C0007047092070470A2070470B2070470C2082 -:1028D00070470D20704700002DE9F843078C072F43 -:1028E00004461ED9D0E9029800254FF6FF73C5F1C2 -:1028F0002006A5F1200029FA05F108FA06F628FAC3 -:1029000000F031430143C9B21846FFF763FF0835B1 -:10291000402D0346EBD1E1693A46BDE8F843FFF7A5 -:102920006BBF4FF6FF70BDE8F883000010B54B6831 -:1029300023B9CA8A63F30902CA8210BD04691A68FE -:102940001C600361C38A013BC3824A60EFE7000059 -:102950002DE9F84F1D46CB8A0F46C3F3090105291F -:10296000814692460B4630D00020AAB207F11A04E5 -:102970009EB2042E1FFA80F80FD8904503F1010390 -:1029800006D3FB8A0A4462F30903FB8201201AE0A2 -:102990001AF80060E6540130EAE79045F1D2A1F15F -:1029A000050B1C237C68BBFBF3F203FB12BB1FFA75 -:1029B0008BF6002C45D14846FFF72AFF044638B96C -:1029C00078606FF00200BDE8F88F4FF00008E6E78E -:1029D000002606607860ADB24FF0000B454510D977 -:1029E0000AEB0803221D13F8011B9155B1B208F13F -:1029F00001081B291FFA88F82BD0454506F101066E -:102A0000F1D8FB8AC3F30902154465F30903BCE757 -:102A1000013292B21C462368002BF9D16B1F0B4484 -:102A20001C21B3FBF1F301339BB29A42D3D2BBF129 -:102A3000000FD0D14846FFF7EBFE20B9C4F800B034 -:102A4000BFE70122E7E7C0F800B05E462060044619 -:102A5000C1E74545D5D94846FFF7DAFE08B92060F9 -:102A6000AFE7C0F800B0002620600446B6E70000DB -:102A70002DE9F04F2DED028B1C4683B05B6901926E -:102A800007468846002B00F09A80238C2BB1E26920 -:102A9000002A00F09480072B35D807F10C00FFF7CF -:102AA000B7FE054638B96FF00205284603B0BDEC05 -:102AB000028BBDE8F08F14220021FEF73BFC228C34 -:102AC000E16905F10800FEF723FC208C013080B29B -:102AD000FFF7E6FEFFF7C8FE013880B22084013020 -:102AE00028746369228C1B782A4403F01F0363F067 -:102AF0003F0348F000411372384669602946FFF7EA -:102B0000EFFD0125D1E700F10C034FF0000908EEBD -:102B1000103A4FF0800A4E464D4618EE100AFFF765 -:102B200077FE83460028BED014220021FEF702FC67 -:102B3000002E3AD1019BABF8083002220BF1080EAF -:102B40001FFA82FC0CF10100BCF1060F218C80B24F -:102B500001D88E422BD3FFF7A3FEFFF785FE6269F3 -:102B60001278013802F01F028E4208BF4FF0400A6F -:102B700042EA49121BFA80F14AEA020A013048F09F -:102B8000004281F808A08BF81000CBF804205946C9 -:102B90003846FFF7A5FD238C0135B3422DB289F0ED -:102BA00001094FF0000AB8D17FE70022C6E7E169CA -:102BB000895D0EF802100136B6B20132C0E76FF03F -:102BC000010572E7F8B515460E463022002104468D -:102BD0001F46FEF7AFFB069B6360B5F5001F079B22 -:102BE000A76034BF6A094FF6FF72A36297B2E6612D -:102BF00004F1100000239A4206D800230360A78244 -:102C0000E3822383E360F8BD06600133304620365B -:102C1000F1E7000003781BB94BB2002BC8BF01706D -:102C20007047000000787047F8B50C46C969074640 -:102C300011B9238C002B37D1257E1F2D34D838783D -:102C400028BB228C072A2CD8268A36F003032BD1E6 -:102C50004FF6FF70FFF7D0FD20F001003102400475 -:102C600041EA0561400C41EA40254FF6FF722346D8 -:102C700029463846FFF7FCFE002807DD6269137815 -:102C80000133DBB21F2B88BF00231370F8BD218AEC -:102C90002D0645EA012505432046FFF71DFE0246A5 -:102CA000E5E76FF00300F1E76FF00100EEE70000E9 -:102CB00070B58AB0044616460021282268461D4693 -:102CC000FEF738FBBDF83830ADF810300F9B059398 -:102CD0009DF840308DF81830119B07936946BDF878 -:102CE0004830ADF820302046CDE90265FFF79CFF63 -:102CF0000AB070BD2DE9F041D36905460C46164671 -:102D00000BB9138C5BBB377E1F2F28D895F800803A -:102D1000B8F1000F26D03046FFF7DEFD33782102F0 -:102D200041EAC33141EA0801338A41EA076141EAD5 -:102D300003410246334641F080012846FFF798FEE2 -:102D400000280ADD3378012B07D17269137801332B -:102D5000DBB21F2B88BF00231370BDE8F0816FF03A -:102D60000100FAE76FF00300F7E70000F0B58BB061 -:102D700004460D4617460021282268461E46FEF7E7 -:102D8000D9FA9DF84C305A1E534253418DF8003009 -:102D90009DF84030ADF81030119B05939DF84830F8 -:102DA0008DF81830149B07936A46BDF85430ADF87F -:102DB000203029462046CDE90276FFF79BFF0BB075 -:102DC000F0BD0000406A00B104307047436A1A68E1 -:102DD000426202691A600361C38A013BC382704781 -:102DE0002DE9F041D0F82080194E14461D46414689 -:102DF000002709B9BDE8F081D1E90223A21A65EBE9 -:102E00000303964277EB03031ED2036A8B420DD174 -:102E1000FFF78CFD036A1B68036203690B60C38ABA -:102E20000161016A013BC3828846E2E7FFF77EFD4C -:102E30000B68C8F8003003690B60C38A0161013B6D -:102E4000C382D8F80010D4E788460968D1E700BFEC -:102E500080841E002DE9F04F8BB00D46DDF85090B8 -:102E600014469B468046002800F01981B9F1000FF6 -:102E700000F01581531E3F2B00F21181012A03D16E -:102E8000BBF1000F40F00B810023CDE90833B8F807 -:102E90001430B5EBC30F4FEAC30703D300200BB0C8 -:102EA000BDE8F08F2B199F42D8F80C303ABF7F1B3A -:102EB000FFB227461BB9D8F81030002B7AD0272D47 -:102EC0004ED8C5F12806B7424FF000032CBFF6B22A -:102ED0003E4600932946D8F8080008AB3246FFF773 -:102EE00041FCA7EB060A35445FFA8AFAB8F81430B9 -:102EF00003F10053053BDB000493D8F80C30039337 -:102F00002821039B13B1BAF1000F2CD1D8F810007F -:102F100040B1BAF1000F05D0009608AB5246691ACD -:102F2000FFF720FC38B2002FB8D066070AD00AABF2 -:102F300003EBD401624211F8083C02F0070213418E -:102F400001F8083C082C3CD9102C40F2B580202C0C -:102F500040F2B780BBF1000F00F09C80082334E002 -:102F6000BA460026C2E7049BE02B28BFE023069365 -:102F70000B44AB42059314D95A1B03980096924513 -:102F800034BF5246D2B2691A08AB04300792FFF739 -:102F9000E9FB079A1644AAEB020A1544F6B25FFA57 -:102FA0008AFA049B069A05999B1A0493039B1B6853 -:102FB0000393A6E70093D8F8080008AB3A462946E1 -:102FC000AEE7BBF1000F13D00123B4EBC30F6CD0FD -:102FD000082C12D89DF82030621E23FA02F2D50781 -:102FE00006D54FF0FF3202FA04F423438DF8203067 -:102FF0009DF8203089F8003051E7102C12D8BDF828 -:103000002030621E23FA02F2D10706D54FF0FF32BC -:1030100002FA04F42343ADF82030BDF82030A9F8BB -:1030200000303CE7202C0FD80899631E21FA03F3E7 -:10303000DA0705D54FF0FF3202FA04F40C43089486 -:10304000089BC9F800302AE7402C2BD0DDE9086541 -:10305000611EC4F12102A4F1210326FA01F105FA4F -:1030600002F225FA03F311431943CB0712D50122CB -:10307000A4F12003C4F1200102FA03F322FA01F1C2 -:10308000A240524243EA010363EB430332432B4322 -:10309000CDE90823DDE90823C9E90023FFE66FF045 -:1030A0000100FCE66FF00800F9E6082CA0D9102C0E -:1030B000B3D9202CEED8C3E7BBF1000FADD002236B -:1030C00083E7BBF1000FBBD004237EE730B5012AB4 -:1030D000144638BF0124402C85B028BF4024002569 -:1030E000012ACDE9025518D81B788DF808306307FE -:1030F0000AD004AB03EBD405624215F8083C02F099 -:103100000702934005F8083C00910346224600213F -:1031100002A8FFF727FB05B030BD082AE4D9102A22 -:1031200003D81B88ADF80830E1E7202A8DBFD3E92A -:1031300000231B680293CDE90223D8E710B5CB68C2 -:103140001BB98B600B618B8210BD04691A681C600F -:103150000361C38A013BC382CA60F0E703064CBF28 -:10316000C0F3C0300220704708B50246FFF7F6FFF3 -:10317000022806D15306C2F30F2001D100F003004C -:1031800008BDC2F30740FBE72DE9F04F93B0CDE94E -:1031900003230A6804461046FFF7E0FF022814BF25 -:1031A000C2F306260026002A0D46824680F2F281EE -:1031B00012F0C04940F0EE81097B002900F0EA815D -:1031C000022803D02378B34240F0E781C2F30463BE -:1031D0000693104602F07F030593FFF7C5FF059B9A -:1031E00029444FEA834848EA0A4848EA4668CE78C4 -:1031F00000230022CDE90823F309834648EA0008AA -:10320000029367D0059B009302466768534608A95E -:103210002046B847002800F0C381276A4FB94146CD -:1032200004F10C00FFF702FB074690B96FF00200B3 -:1032300054E03B6998450DD03F68002FF9D14146D5 -:1032400004F10C00FFF7F2FA07460028EED0236ADB -:103250003B60276297F817C006F01F08CCF3840C78 -:10326000ACEB08001FFA80FE0028B8BF0EF120006A -:10327000A8EB0C031FFA83FED7E90221B8BF00B206 -:10328000002B0793BEBF0EF120031BB2079352EA37 -:10329000010338D0039BDFF824E39A1A049B4FF014 -:1032A000000C63EB010196457CEB01032BD36B7B98 -:1032B00097F81AE0734519D1029B002B78D00128AA -:1032C00021DC7868F8B9DFF8F0C2944570EB0103AF -:1032D00016D337E0276A27B96FF00C0013B0BDE8AA -:1032E000F08F3B699845B5D03F68F4E7B24890420B -:1032F0007CEB010301D30020F0E7029B002BFAD006 -:10330000079B0F2B17DCFA7DB30002F0030203F0DA -:103310007C031343FB7539462046FFF707FB6B7BA5 -:10332000BB76029B3BB9FB7DC3F38402013262F39F -:103330008603FB75D0E76A7BBB7E9A42DBD1029B9A -:10334000002B35D0B309022B32D0039BBB60049B0A -:10335000FB60142200210DA8FDF7ECFF039B0A93EC -:10336000049B0B932B1D0C932B7BADF83EB0013BC4 -:10337000DBB2ADF83C30069B8DF84230059B8DF8F2 -:10338000433094F82C308DF840A083F001038DF881 -:1033900044308DF84180A3680AA920469847FB7DF8 -:1033A000C3F38403013303F01F039B02FB82A2E7F4 -:1033B000FB7DC6F34012B2EBD31F40F0F480C3F3A1 -:1033C0008403434540F0F280029A2B7BB609002A21 -:1033D0004DD0F2075DD4032B40F2EB80039BBB6022 -:1033E000049BFB602B7BAE1D033BDBB232463946B0 -:1033F00004F10C00FFF7ACFA00280CDA394620463D -:10340000FFF794FAFB7DC3F38403013303F01F033A -:103410009B02FB820AE7DDE90884AB883B834FF619 -:10342000FF73C9F12000A9F1200228FA09F104FA7A -:1034300000F0014324FA02F211431846C9B2FFF723 -:10344000C9F909F10809B9F1400F0346E9D1B88279 -:103450002A7B033AD2B23146FFF7CEF9FB7DB88220 -:10346000DA43C2F3C01262F3C713FB7543E786B9B0 -:103470002E1D013BDBB23246394604F10C00FFF74A -:1034800067FA0028BADB2A7BB88A013AD2B2314601 -:10349000E2E7F98AC1F30901013B0429DAB25BD8FA -:1034A000281D002307F11B069A4208D910F801CB0A -:1034B00006F801C0013101330529DBB2F4D10399CB -:1034C0000A9104990B91934207F11B010C9138BFAB -:1034D000043379680D9134BF55FA83F300230E93BA -:1034E000FB8AADF83EB0C3F309031A44069B8DF87E -:1034F0004230059B8DF8433094F82C30ADF83C20D9 -:1035000083F001038DF8443000238DF840A08DF83E -:1035100041807B602A7BB88A013A291DFFF76CF94C -:103520003B8BB882834203D1A3680AA920469847FF -:1035300020460AA9FFF702FEFB7DBA8AC3F3840383 -:10354000013303F01F039B02FB823B8B9A420CBFAB -:1035500000206FF01000C1E67B68002BAFD0052083 -:1035600001E01C3033461E68002EFAD1091A081DEE -:103570002E1D184401EB090CBCF11B0F5FFA89F3F7 -:103580009DD89A429BD916F8013B00F8013B09F1FE -:103590000109EFE76FF00900A0E66FF00A009DE671 -:1035A0006FF00B009AE66FF00D0097E66FF00E00DB -:1035B00094E66FF00F0091E640420F0080841E00F9 -:1035C000EFF3098305494A6B22F001024A6368332D -:1035D00083F30988002383F31188704700EF00E02C -:1035E000302080F3118862B60C4B0D4AD96821F463 -:1035F000E0610904090C0A43DA60D3F8FC200949A8 -:1036000042F08072C3F8FC200A6842F001020A60AE -:103610002022DA7783F82200704700BF00ED00E037 -:103620000003FA05001000E010B5302383F3118881 -:103630000E4B5B6813F4006314D0F1EE103AEFF315 -:103640000984683C4FF08073E361094BDB6B2366B0 -:1036500084F3098800F098F810B1064BA36110BDFF -:10366000054BFBE783F31188F9E700BF00ED00E0AD -:1036700000EF00E0030600080606000800F16043C2 -:1036800003F561430901C9B283F80013012200F078 -:103690001F039A4043099B0003F1604303F5614314 -:1036A000C3F880211A60704700F16040090100F5FD -:1036B0006D40C9B2017670470023037582680369C3 -:1036C0001B6899689142FBD25A680360426010609F -:1036D0005860704700230375826803691B68996806 -:1036E0009142FBD85A68036042601060586070478E -:1036F00008B50846302383F311880B7D032B05D0D2 -:10370000042B0DD02BB983F3118808BD8B690022DF -:103710001A604FF0FF338361FFF7CEFF0023F2E71B -:10372000D1E9003213605A60F3E70000FFF7C4BF2D -:10373000054BD9680875186802681A605360012241 -:103740000275D860FCF748BF2038002030B50C4B1C -:10375000DD684B1C87B004460FD02B46094A6846EB -:1037600000F0FEF82046FFF7E3FF009B13B1684628 -:1037700000F000F9A86907B030BDFFF7D9FFF9E7FD -:1037800020380020F1360008044B1A68DB68906886 -:103790009B68984294BF0020012070472038002089 -:1037A000084B10B51C68D86822681A605360012263 -:1037B0002275DC60FFF78EFF01462046BDE8104011 -:1037C000FCF70ABF20380020044B1A68DB689268B7 -:1037D0009B689A4201D9FFF7E3BF70472038002069 -:1037E00038B5074C07490848012300252370656058 -:1037F00000F00AFB0223237085F3118838BD00BF57 -:10380000483A0020804A00082038002008B572B6E7 -:10381000044B186500F0CEF900F092FA024B032237 -:103820001A70FEE720380020483A002000F0B4B8B3 -:10383000EFF3118020B9EFF30583302282F3118872 -:103840007047000010B530B9EFF30584C4F30804E5 -:1038500014B180F3118810BDFFF7B6FF84F311880F -:10386000F9E700008B60022308618B8208467047ED -:103870008368A3F1840243F8142C026943F8442CB2 -:10388000426943F8402C094A43F8242CC26843F8A3 -:10389000182C022203F80C2C002203F80B2C044AEB -:1038A00043F8102CA3F12000704700BFF105000879 -:1038B0002038002008B5FFF7DBFFBDE80840FFF720 -:1038C00035BF0000024BDB6898610F20FFF730BF67 -:1038D00020380020302383F31188FFF7F3BF000066 -:1038E00008B50146302383F311880820FFF72EFF27 -:1038F000002383F3118808BD064BDB6839B14268A9 -:1039000018605A60136043600420FFF71FBF4FF038 -:10391000FF307047203800200368984206D01A68AC -:103920000260506099611846FFF700BF70470000C1 -:1039300010B50A4C23699A6891420CD85A68816084 -:103940000360426010609A685860511A99604FF0A5 -:10395000FF33A36110BD1B68891AECE720380020F3 -:1039600010B4C0E9032300235DF8044B4361FFF763 -:10397000DFBF0000036881689A680A449A60426861 -:1039800013605A6000230360024B4FF0FF329A61CC -:10399000704700BF2038002070B5124DEB692A46F1 -:1039A0000133EB6152F8103F934206D09A68013A16 -:1039B0009A6030262C69A36803B170BDD4E9002158 -:1039C0000A605160236083F31188D4E903312046F3 -:1039D000984786F3118861690029EBD02046FFF7EC -:1039E000A7FFE7E72038002000207047FEE700002F -:1039F000704700004FF0FF3070470000BFF34F8F5B -:103A0000024AD368DB07FCD4704700BF00200240A5 -:103A100008B5074B1B7853B9FFF7F0FF054B1A6940 -:103A2000120641BF044A5A6002F188325A6008BD4A -:103A3000603A0020002002402301674508B5054B8D -:103A40001B7833B9FFF7DAFF034A136943F08003A9 -:103A5000136108BD603A0020002002407F289ABF11 -:103A600000F58030C0020020704700004FF4006075 -:103A700070470000802070477F2808B50BD8FFF7FB -:103A8000EDFF00F500630268013204D10430834287 -:103A9000F9D1012008BD0020FCE700007F2810B507 -:103AA00004461CD8FFF7AAFFFFF7B2FF0D4BF32225 -:103AB000DA6002221A61FFF7D1FF58611A6942F0F9 -:103AC00040021A614FF40061FFF798FF00F034F9EB -:103AD000FFF7B4FF2046BDE81040FFF7CDBF002040 -:103AE00010BD00BF002002402DE9F84312F0010391 -:103AF000144606D01F4B40F2F3221A600020BDE8A6 -:103B0000F88385181C4A954204D91A4A4FF43E712D -:103B10001160F3E7FFF77CFFFFF770FFDFF86880C5 -:103B2000451A4FF00109012C05EB01060F4603D899 -:103B3000FFF784FF0120E2E73B88C8F8109033804C -:103B40000020FFF75BFFC8F81000338831F8022B24 -:103B50009BB29A420CD0074B40F20F321A60074BCF -:103B60001E60074B1C60074B1F60FFF767FFC6E72F -:103B7000023CD8E75C3A002000000408503A0020DC -:103B8000583A0020543A002000200240084908B565 -:103B90000B7828B11BB9FFF73BFF01230B7008BD61 -:103BA000002BFCD0BDE808400870FFF747BF00BFFE -:103BB000603A002008B54FF420414FF0005000F06B -:103BC000BDF8BDE808404FF400514FF0805000F0C0 -:103BD000B5B800000846114600F05EBE012000F0B6 -:103BE0005BBE0000084600F075BE000030B583B033 -:103BF000FFF71EFE0E4B0F4DDB692A684FF47A71FA -:103C000001FB03F3934237BF0B4A0B495168146819 -:103C10002B602EBFD1E90041013151601C1941F1E7 -:103C200000010191FFF70EFE0199204603B030BD5F -:103C300020380020643A0020683A002030B583B074 -:103C4000FFF7F6FD114B124DDB692A684FF47A71CC -:103C500001FB03F3934237BF0E4A0E4951681468C3 -:103C60002B602EBFD1E90041013151601C1941F197 -:103C700000010191FFF7E6FD01994FF47A720023EC -:103C80002046FCF795FA03B030BD00BF2038002075 -:103C9000643A0020683A002010B50244064BD2B2C4 -:103CA000904200D110BD441C00B253F8200041F8EE -:103CB000040BE0B2F4E700BF502800400F4B30B5D2 -:103CC0001C6A240407D41C6A44F440741C621C6AF5 -:103CD00044F400441C620A4C236843F4807323605C -:103CE0000244084BD2B2904200D130BD441C00B215 -:103CF00051F8045B43F82050E0B2F4E700100240B2 -:103D0000007000405028004007B5012201A90020A2 -:103D1000FFF7C2FF019803B05DF804FB13B504463A -:103D2000FFF7F2FFA04205D0012201A90020019473 -:103D3000FFF7C4FF02B010BD7047000070470000DD -:103D400070470000074B45F255521A6002225A6034 -:103D500040F6FF729A604CF6CC421A60024B012288 -:103D60001A70704700300040743A0020034B1B78F3 -:103D70001BB1034B4AF6AA221A607047743A00201E -:103D800000300040044B1A682AB902F1804202F563 -:103D90000432526A1A607047703A0020024B4FF0AA -:103DA00080725A62704700BF0010024008B5FFF7EA -:103DB000E9FF024B1868C0F3407008BD703A00205C -:103DC00070470000FEE700000A4B0B480B4A904288 -:103DD0000BD30B4BDA1C121AC11E22F003028B42CA -:103DE00038BF00220021FDF7A5BA53F8041B40F8A4 -:103DF000041BECE7EC4B0008583C0020583C00202A -:103E0000583C0020FEE7000070B51B4B0163002505 -:103E1000044686B0586085620E46FFF7E1FB04F168 -:103E20001003C4E904334FF0FF33A361134BE56182 -:103E3000D969A5600A462B46C4E9082304F1340178 -:103E4000C4E900440E4AE562256580232046FFF759 -:103E500009FD0123E0600B4A03750092726801922C -:103E6000B268CDE90223084B6846CDE90435FFF777 -:103E700021FD06B070BD00BF483A00202038002068 -:103E80008C4A0008914A0008053E00084B684360D0 -:103E90008B688360CB68C3600B6943614B690362C5 -:103EA0008B6943620B6803607047000008B51B4BC9 -:103EB0009A6A42F4FC029A629A6A22F4FC029A62BA -:103EC0009A6A5A6942F4FC025A61154A5B691146C2 -:103ED0004FF09040FFF7DAFF02F11C0100F580601F -:103EE000FFF7D4FF02F1380100F58060FFF7CEFF45 -:103EF00002F1540100F58060FFF7C8FF02F1700184 -:103F000000F58060FFF7C2FF02F18C0100F58060D0 -:103F1000FFF7BCFFBDE8084000F05AB800100240AF -:103F2000984A000808B500F093F9FFF759FCBDE87E -:103F30000840FFF727BF00007047000010B5214C74 -:103F4000A36A63F4FC03A362A36A03F4FC03A36201 -:103F50004FF0FF32A36A23692261236900232361A2 -:103F60002169E168E260E268E360E268E2691649BB -:103F700042F08052E261E2690A6842F480720A60AB -:103F8000226A02F44072B2F5407F1EBF4FF48032C5 -:103F900022622362236A1B0407D4236A43F440731A -:103FA0002362236A43F40043236200F031F9A369DA -:103FB000064A43F00103A361A369136843F0200399 -:103FC000136010BD0010024000700040000001406E -:103FD0001E4B1A6842F001021A601A689007FCD55D -:103FE0005A6822F003025A605A6812F00C02FBD1A0 -:103FF000196801F0F90119605A601A6842F48032B8 -:104000001A601A689103FCD5114A5A604FF40452A1 -:10401000DA6230221A631A6842F080721A601A68F3 -:104020009201FCD50B4912220A600A6802F00702CD -:10403000022AFAD15A6842F002025A605A6802F023 -:104040000C02082AFAD11A6B1A637047001002405A -:1040500000241D0000200240084A08B55169136879 -:104060000B4003F00103536123B1054A13680BB100 -:1040700050689847BDE80840FFF7D6BA00040140F1 -:10408000783A0020084A08B5516913680B4003F0DC -:104090000203536123B1054A93680BB1D068984776 -:1040A000BDE80840FFF7C0BA00040140783A00209C -:1040B000084A08B5516913680B4003F004035361C3 -:1040C00023B1054A13690BB150699847BDE8084010 -:1040D000FFF7AABA00040140783A0020084A08B560 -:1040E000516913680B4003F00803536123B1054A7B -:1040F00093690BB1D0699847BDE80840FFF794BABF -:1041000000040140783A0020084A08B55169136854 -:104110000B4003F01003536123B1054A136A0BB13E -:10412000506A9847BDE80840FFF77EBA0004014096 -:10413000783A0020174B10B55A691C68144004F4F3 -:1041400078725A61A30604D5134A936A0BB1D06AF8 -:104150009847600604D5104A136B0BB1506B984713 -:10416000210604D50C4A936B0BB1D06B9847E2053E -:1041700004D5094A136C0BB1506C9847A30504D5BC -:10418000054A936C0BB1D06C9847BDE81040FFF71F -:104190004BBA00BF00040140783A00201A4B10B51A -:1041A0005A691C68144004F47C425A61620504D5C3 -:1041B000164A136D0BB1506D9847230504D5134A69 -:1041C000936D0BB1D06D9847E00404D50F4A136E80 -:1041D0000BB1506E9847A10404D50C4A936E0BB1F5 -:1041E000D06E9847620404D5084A136F0BB1506F24 -:1041F0009847230404D5054A936F0BB1D06F9847B5 -:10420000BDE81040FFF710BA00040140783A0020E2 -:10421000062108B50846FFF731FA06210720FFF707 -:104220002DFA06210820FFF729FA06210920FFF7B9 -:1042300025FA06210A20FFF721FA06211720FFF7A9 -:104240001DFABDE8084006212820FFF717BA000034 -:1042500008B5FFF773FE00F067F800F03DF8FFF7D0 -:104260006BFEBDE8084000F05DB8000002684368DE -:104270001143016003B1184770470000143000F08B -:104280002FBA00004FF0FF33143000F029BA0000BD -:10429000383000F0A5BA00004FF0FF33383000F09E -:1042A0009FBA0000143000F0F5B900004FF0FF3164 -:1042B000143000F0EFB90000383000F04FBA0000C1 -:1042C0004FF0FF32383000F049BA0000012914BF26 -:1042D0006FF013000020704700F06CB8044B0360CF -:1042E0000023C0E90233436001230374704700BF19 -:1042F000404B000838B5C36904460D461BB904217C -:104300000844FFF7B3FF294604F1140000F0A6F9B2 -:10431000002806DA201D4FF40061BDE83840FFF7A1 -:10432000A5BF38BD00F00EB80023054A1946013379 -:10433000102BC2E9001102F10802F8D1704700BF4A -:10434000783A00204FF0E023044A5A6100229A6133 -:1043500007221A6108210B20FFF7A6B93F190100B7 -:1043600008B5302383F31188FFF760FA002383F345 -:10437000118808BD08B5FFF7F3FFBDE80840FFF757 -:1043800053B90000026843681143016003B1184744 -:1043900070470000024A136843F0C003136070477F -:1043A00000380140024A136843F0C00313607047AD -:1043B0000044004037B51D4C1D4D2046FFF78EFFD1 -:1043C000009404F114001B490023202200F038F966 -:1043D0002022009404F13800174B184900F0B2F97C -:1043E000174BC4E91735174C0C212520FFF746F968 -:1043F0002046FFF773FF04F11400134900940023D3 -:10440000202200F01DF904F13800104B10490094EF -:10441000202200F097F90F4B0C212620C4E9173514 -:1044200003B0BDE83040FFF729B900BFF83A0020DB -:1044300000512502D03B002095430008103C00208D -:1044400000380140643B0020F03B0020A5430008F9 -:10445000303C0020004400402DE9F047C66D37682D -:10446000F46934622107054619D014F0080118BF19 -:104470004FF48071E20748BF41F02001A30748BF15 -:1044800041F04001600748BF41F08001302383F3D1 -:104490001188281DFFF776FF002383F31188E205BA -:1044A0000AD5302383F311884FF48061281DFFF76C -:1044B00069FF002383F311884FF030094FF0000AA1 -:1044C00014F0200838D13B0616D54FF0300905F11D -:1044D000380A200610D589F31188504600F066F995 -:1044E000002836DA0821281DFFF74CFF27F080034B -:1044F0003360002383F31188790614D5620612D540 -:10450000302383F31188D5E913239A4208D12B6C09 -:1045100033B11021281D27F04007FFF733FF376024 -:10452000002383F31188E30619D5AA6E1369B3B18A -:10453000BDE8F0475069184789F31188B38C95F8A6 -:10454000641028461940FFF7D5FE8AF31188F469F4 -:10455000B6E780B2308588F31188F469B9E7BDE821 -:10456000F087000008B50348FFF776FFBDE8084074 -:10457000FFF75AB8F83A002008B50348FFF76CFF78 -:10458000BDE80840FFF750B8643B0020F8B5154679 -:1045900082680669AA420B46816938BF8568761A27 -:1045A000B54204460BD218462A46FCF7B1FEA36971 -:1045B0002B44A361A3685B1BA3602846F8BD0CD9FC -:1045C00018463246FCF7A4FEAF1BE1683A46304479 -:1045D000FCF79EFEE3683B44EBE718462A46FCF7EF -:1045E00097FEE368E5E7000083689342F7B5154658 -:1045F000044638BF8568D0E90460361AB5420BD24C -:104600002A46FCF785FE63692B446361A36828464C -:104610005B1BA36003B0F0BD0DD932460191FCF7DE -:1046200077FE0199E068AF1B3A463144FCF770FE13 -:10463000E3683B44E9E72A46FCF76AFEE368E4E7FF -:1046400010B50A440024C361029B8460C0E90000E5 -:10465000C0E90511C1600261036210BD08B5D0E96F -:104660000532934201D1826882B982680132826048 -:104670005A1C42611970D0E904329A4224BFC368BF -:1046800043610021FFF748F9002008BD4FF0FF30DB -:10469000FBE7000070B5302304460E4683F3118813 -:1046A000A568A5B1A368A269013BA360531CA361DF -:1046B00015782269934224BFE368A361E3690BB1D3 -:1046C00020469847002383F31188284607E03146A7 -:1046D0002046FFF711F90028E2DA85F3118870BD52 -:1046E0002DE9F74F04460E4617469846D0F81C9021 -:1046F0004FF0300A8AF311884FF0000B154665B170 -:104700002A4631462046FFF741FF034660B941463D -:104710002046FFF7F1F80028F1D0002383F3118839 -:10472000781B03B0BDE8F08FB9F1000F03D0019002 -:104730002046C847019B8BF31188ED1A1E448AF36B -:104740001188DCE7C0E90511C160C3611144009B19 -:104750008260C0E90000016103627047F8B5044659 -:104760000D461646302383F31188A768A7B1A368C6 -:10477000013BA36063695A1C62611D70D4E9043275 -:104780009A4224BFE3686361E3690BB1204698470E -:10479000002080F3118807E031462046FFF7ACF88F -:1047A0000028E2DA87F31188F8BD0000D0E905237C -:1047B0009A4210B501D182687AB98268013282606A -:1047C0005A1C82611C7803699A4224BFC3688361C2 -:1047D0000021FFF7A1F8204610BD4FF0FF30FBE7A6 -:1047E0002DE9F74F04460E4617469846D0F81C9020 -:1047F0004FF0300A8AF311884FF0000B154665B16F -:104800002A4631462046FFF7EFFE034660B941468F -:104810002046FFF771F80028F1D0002383F31188B8 -:10482000781B03B0BDE8F08FB9F1000F03D0019001 -:104830002046C847019B8BF31188ED1A1E448AF36A -:104840001188DCE70B460146184600F02DB8000041 -:1048500000F040B8012838BF012010B504462046BA -:1048600000F030F830B900F007F808B900F00CF8A3 -:104870008047F4E710BD0000024B1868BFF35B8F60 -:10488000704700BF503C002008B5062000F084F8B7 -:104890000120FFF7ABF80000024B0A4601461868FA -:1048A000FFF798B91811002010B5054C13462CB12C -:1048B0000A4601460220AFF3008010BD2046FCE707 -:1048C00000000000024B01461868FFF787B900BFDF -:1048D00018110020024B01461868FFF783B900BF8A -:1048E0001811002010B501390244904201D1002076 -:1048F00005E0037811F8014FA34201D0181B10BD49 -:104900000130F2E72DE9F041A3B1C91A177801444B -:10491000044603F1FF3C8C42204601D9002009E007 -:104920000578BD4204F10104F5D10CEB0405D6185D -:10493000A54201D1BDE8F08115F8018D16F801ED11 -:10494000F045F5D0E7E700001F2938B504460D46CD -:1049500004D9162303604FF0FF3038BD426C12B10A -:1049600052F821304BB9204600F030F82A46014673 -:104970002046BDE8384000F017B8012B0AD0591C7A -:1049800003D1162303600120E7E7002442F8254005 -:10499000284698470020E0E7024B01461868FFF7D9 -:1049A000D3BF00BF1811002038B5074D00230446BF -:1049B000084611462B60FFF71DF8431C02D12B68F7 -:1049C00003B1236038BD00BF543C0020FFF70CB892 -:1049D000034611F8012B03F8012B002AF9D1704787 -:1049E0006F72672E6172647570696C6F742E6633B6 -:1049F00030332D556E6976657273616C000000006E -:104A000040A2E4F1646891060041A3E5F265699271 -:104A1000070000004261642043414E4966616365BE -:104A200020696E6465782E00800000000080000020 -:104A3000000080000000000000000000351B00089E -:104A40001923000879220008451B0008791B00087B -:104A5000751D0008491B0008591B00084D1B000864 -:104A6000551B0008511B00089D1C00085D1B000819 -:104A7000E52500086D1B0008711C0008633000006C -:104A80007C4A000878380020483A00206D61696E41 -:104A90000069646C65000000A001A82A0000000005 -:104AA000FAAABEAA50001424EFFF0000007700000D -:104AB000709709000100000000000000AAAAAAAA3D -:104AC00001000000FFFF00000000000000000000E7 -:104AD0000000000000000000AAAAAAAA000000002E -:104AE000FFFF0000000000000000000000000000C8 -:104AF00000000000AAAAAAAA00000000FFFF000010 -:104B000000000000000000000000000000000000A5 -:104B1000AAAAAAAA00000000FFFF000000000000EF -:104B2000000000000000000000000000AAAAAAAADD -:104B300000000000FFFF0000000000000000000077 -:104B4000000000009942000885420008C1420008A8 -:104B5000AD420008B9420008A54200089142000891 -:104B60007D420008CD42000878B6FF7F01000000BA -:104B7000EC030000000000000098030000000000AB -:104B8000FE2A0100D20400001C11002000000000D9 -:104B90000000000000000000000000000000000015 -:104BA0000000000000000000000000000000000005 -:104BB00000000000000000000000000000000000F5 -:104BC00000000000000000000000000000000000E5 -:104BD00000000000000000000000000000000000D5 -:0C4BE000000000000000000000000000C9 +:1000000000090020B1010008E52200089D22000837 +:10001000C52200089D220008BD220008B301000887 +:10002000B3010008B3010008B3010008D932000889 +:10003000B3010008B3010008B3010008A94000089B +:10004000B3010008B3010008B3010008B3010008C0 +:10005000B3010008B30100088D3D0008B93D000858 +:10006000E53D0008113E00083D3E0008B3010008D0 +:10007000B3010008B3010008B3010008B301000890 +:10008000B3010008B3010008B301000851220008C1 +:100090007D2200088D220008B3010008693E000897 +:1000A000B3010008B3010008B3010008B301000860 +:1000B000B3010008B3010008B3010008B301000850 +:1000C000B3010008B3010008B3010008B301000840 +:1000D000B301000899420008AD420008B3010008CE +:1000E000D13E0008B3010008B3010008B3010008C5 +:1000F000B3010008B3010008B3010008B301000810 +:10010000B3010008B3010008B3010008B3010008FF +:10011000B3010008B3010008B3010008B3010008EF +:10012000B3010008B3010008B3010008B3010008DF +:10013000B3010008B3010008B3010008B3010008CF +:10014000B3010008B3010008B3010008B3010008BF +:10015000B3010008B3010008B3010008B3010008AF +:10016000B3010008B3010008B3010008B30100089F +:10017000B3010008B3010008B3010008B30100088F +:10018000B3010008B3010008B3010008B30100087F +:10019000B3010008B3010008B3010008B30100086F +:1001A000190F00080000000000000000000000001F +:1001B00002E000F000F8FEE772B6374880F30888E6 +:1001C000364880F3098836483649086040F2000016 +:1001D000CCF200004EF63471CEF200010860BFF39D +:1001E0004F8FBFF36F8F40F20000C0F2F0004EF669 +:1001F0008851CEF200010860BFF34F8FBFF36F8FBD +:100200004FF00000E1EE100A4EF63C71CEF2000114 +:100210000860062080F31488BFF36F8F03F06AFC38 +:1002200003F0DEFC4FF055301F491B4A91423CBFA2 +:1002300041F8040BFAE71D49184A91423CBF41F8C6 +:10024000040BFAE71A491B4A1B4B9A423EBF51F86E +:10025000040B42F8040BF8E700201849184A9142B1 +:100260003CBF41F8040BFAE703F048FC03F0F4FC50 +:10027000144C154DAC4203DA54F8041B8847F9E7D7 +:1002800000F042F8114C124DAC4203DA54F8041B52 +:100290008847F9E703F030BC000900200011002076 +:1002A0000000000808ED00E0000100200009002027 +:1002B000A0480008001100207C11002080110020BF +:1002C000543C0020A0010008A4010008A40100087B +:1002D000A40100082DE9F04F2DED108AC1F80CD0D3 +:1002E000C3689D46BDEC108ABDE8F08F002383F300 +:1002F00011882846A047002003F052F9FEE703F0DA +:10030000DBF800DFFEE70000F8B500F017FE03F0B1 +:1003100095FB074603F0E4FB064600283ED12B4B35 +:100320009F423BD001339F423BD0294B27F0FF0235 +:100330009A4239D1F8B200F03DFC354642F21074D1 +:1003400000F03EFC08B10024254601F0ADF878B37A +:10035000032000F043F80024254636B11D4B9F4290 +:1003600003D003F0B5FB00242546002003F070FB0A +:10037000194B1B6913F040031FD00DB100F044F876 +:1003800000F050FC01F0B6FF0546C4B101F0B2FF29 +:10039000401BA04213D900F037F8F3E7354600249C +:1003A000CEE704460125CBE705464FF47A74C7E74C +:1003B000B4F57A7F08BF0125CFE71C46E0E700F0DF +:1003C00079FC012003F0F2F8DFE700BF010007B07D +:1003D000000008B0263A09B000040048084B187025 +:1003E00003280CD8DFE800F008050208022000F01E +:1003F00001BE022000F0F6BD024B00225A60704799 +:10040000801100208411002038B501F04DF830B182 +:100410001F4B03221A701F4B00225A6038BD1E4B1F +:100420001E4A19680131F9D004339342F9D11C4CAA +:10043000194DD4F80428AA42F0D31A4B9B6803F153 +:10044000006303F5D0439A42E8D203F015FB03F0B2 +:1004500027FB002000F08CFD0220FFF7BFFF124BAE +:10046000DA690022DA61D96999699A619B6972B681 +:100470004FF0E0233021C3F8085DD4F80038D4F8F9 +:10048000042881F311889D4683F308881047C5E747 +:1004900080110020841100200068000820680008F6 +:1004A000006000080011002000100240094A136893 +:1004B00049F2690099B21B0C00FB01331360064B33 +:1004C000186844F2506182B2000C01FB020018600F +:1004D00080B27047141100201011002010B50021C7 +:1004E0001022044600F0A0FD034B03CB20606160A6 +:1004F0001868A06010BD00BFACF7FF1F2DE9F041E8 +:10050000ADF5507D0DF13C086EAC40F2751207461A +:100510000D4610A80021C8F8001000F085FD4FF42A +:10052000C4720021204600F07FFD01F0E3FE254B60 +:100530004FF47A72B0FBF2F0186093E807000223E0 +:1005400084E807000DF5ED702382FFF7C7FF4EF634 +:1005500003431D49238407A804F0D4F81C2384F81E +:1005600032310DF2EB226B440DF1340C1E4603CEFA +:10057000664510605160334602F10802F6D13068DA +:10058000106041460122204600F09AFD00230393AB +:10059000AB7E029305F11903019380B20123CDE9EB +:1005A00004800093E97E05A3D3E90023384602F0D6 +:1005B00069FA0DF5507DBDE8F08100BF9E6AC42147 +:1005C000818A46EE8C110020144700082DE9F04185 +:1005D0002C4C237ADAB080460D465BBB27A928460F +:1005E00000F07EFE0746002842D19DF89D60C82E8F +:1005F0003ED801464FF4A662204600F015FD4FF4A8 +:100600008073C4F8F8314FF40073C4F80C334FF41E +:100610004073C4F8203432460DF19E0104F1090004 +:1006200000F0F0FC26449DF89C30777223720BB9E1 +:10063000EB7E23728122002106AC27A800F0F4FC97 +:100640000122214627A800F087FE00230393AB7EFA +:10065000029305F1190380B201932823CDE90440E8 +:100660000093E97E05A3D3E90023404602F00AFA8D +:100670005AB0BDE8F08100BFAFF30080264172722E +:10068000DF25D7B7B0320020F0B5254E4FF48A757C +:1006900005FB0065F1B096F8D83085F8DC30002411 +:1006A000D822214685F8E8403AA800F0BDFC06F1C2 +:1006B000090000F0B1FCD5F8E4308DF8F000C2B2CA +:1006C00006AF06F109010DF1F100CDE93A3400F071 +:1006D00099FC394601223AA800F06AFE80B2CDE9C1 +:1006E000047008230127CDE9023706F1D8030193EE +:1006F00030230093317A0B4807A3D3E9002302F09B +:10070000C1F9A04206DD01F0F5FDC5F8E00038466C +:1007100071B0F0BD2046FBE778F6339F93CACD8DCC +:10072000B0320020A42100202DE9F0411D4D1E4EC5 +:100730001E4F86B0284602F0D1F9034658B3002474 +:10074000CDE90344ADF81440027B8DF8142099687C +:100750004068029403AA03C21B68DFF8548043F088 +:100760000043029301F0C8FD821941F10003009497 +:1007700002A9384601F072F8A04205DD284602F0D1 +:10078000B1F988F80040D5E798F80030072B05D874 +:10079000013388F8003006B0BDE8F081014802F06E +:1007A000A1F9F8E7A421002040420F00D821002041 +:1007B000E537002070B50D4614461E4602F0BEF81F +:1007C00050B9022E10D1012C0ED112A3D3E900236F +:1007D000C5E90023012007E0282C10D005D8012C02 +:1007E00009D0052C0FD0002070BD302CFBD10BA3FD +:1007F000D3E90023ECE70BA3D3E90023E8E70BA33D +:10080000D3E90023E4E70BA3D3E90023E0E700BF2B +:10081000AFF30080401DA12026812A0B78F6339F7C +:1008200093CACD8D9E6AC421818A46EE264172729A +:10083000DF25D7B7F017304A39059E5638B505463B +:100840000E4C0021013500F0B5FBA4F82C55B4F88E +:100850002C0500F097FB78B1B4F82C0500F0A2FB52 +:10086000014648B9B4F82C0500F0A4FBB4F82C35C7 +:100870000133A4F82C35EAE738BD00BFB0320020C0 +:1008800010B50A4B0A4A1A6003F5805393F86020AA +:100890003AB9DC6D2CB1204600F080FE204603F012 +:1008A00071FEBDE81040034800F078BED82100205A +:1008B00070470008203200202DE9F04F8FB000AFC4 +:1008C00005460C4602F03AF8002849D1237E022B57 +:1008D0001BD1E38A012B18D101F00CFD0646FFF76E +:1008E000E5FD03464FF4C870DFF8C482B3FBF0F2B5 +:1008F00006F5167602FB103316FA83F3C8F80030BB +:10090000E37E33B9A34B00221A703C37BD46BDE8E5 +:10091000F08F07F12401204600F0A0FC0028F4D15C +:1009200007F11400FFF7DAFD97F8264007F11401EC +:10093000224607F1270003F06FFE0028E2D10F2CBA +:1009400008D8944B1C70D8F80030A3F51673C8F87B +:100950000030DAE797F82410284601F0E7FFD4E7E3 +:10096000E38A282B2BD010D8012B23D0052BCCD1F8 +:10097000BFF34F8F8849894BCA6802F4E062134382 +:10098000CB60BFF34F8F00BFFDE7302BBDD1844E4E +:10099000E17E327A9142B8D1607E3146002291F8F0 +:1009A000DC50854200F0A5800132042A01F58A71ED +:1009B000F5D1AAE721462846FFF7A0FDA5E7214685 +:1009C0002846FFF703FEA0E7B2F8EC507B6005F184 +:1009D00003094FEA99094FEA8902D11DC908A8EB1A +:1009E000C1039D46EB460021584600F01DFB04F173 +:1009F000EE012A463144584600F004FB7B6813B9E7 +:100A0000012000F0B5FA96F8D20000F0BBFA0446D7 +:100A100030B9307200F0D6FA204600F0A9FAB1E001 +:100A2000D6F8D4203AB996F8D200B6F82C258242EE +:100A300001D8FFF703FFD6F8D4202A44944208D205 +:100A400096F8D200B6F82C250130824201D8FFF783 +:100A5000F5FE70685FFA89F2594600F0EDFA08B9C0 +:100A6000C54679E0726896F8D2002A447260D6F8DA +:100A7000D42005EB0209C6F8D49000F083FA814532 +:100A800009D396F8D220D6F8D4000132001B86F89C +:100A9000D220C6F8D400FF2D0FD80024347200F005 +:100AA00091FA204600F064FA00F0FEFC3D4B1881FC +:100AB00008B9FFF7A9FCC54627E7BB6896F8D90037 +:100AC0000AFB0362FB68D2F8E41082F8E83001F513 +:100AD0008061C2F8E030C2F8E410FFF7D5FDFFF7FF +:100AE00023FE96F8D920013202F0030286F8D920BD +:100AF000B6E74FF48A7A0AFB02F505F1EA013144C0 +:100B0000204600F081FCF86000287FF4FEAE3544FA +:100B1000012285F8E82001F0EDFBD5F8E020D6EDC4 +:100B2000007ADFED216A801A192838BF192040F6B3 +:100B3000B832904228BF1046B8EE677A07EE900AA6 +:100B4000F8EEE77A67EEA67ADFED186AE7EE267A26 +:100B5000FCEEE77AC6ED007A96F8D930BB60BA6849 +:100B600073680AFB02F4321992F8E81059B1D2F80E +:100B7000E4108B42E8463FF427AF002182F8E810EA +:100B8000C2F8E010C5467368064A9B0A0133138118 +:100B9000BBE600BF9D21002000ED00E00400FA0547 +:100BA000B03200208C110020CDCCCC3D6666663F73 +:100BB000A0210020014B1870704700BF9811002041 +:100BC00038B54FF00054134B22689A4220D1124B93 +:100BD000627D12481A70237D03724FF48073C0F84F +:100BE000F8314FF40073C0F80C3300254FF4407314 +:100BF000C0F820340A49C0F8E450C922093000F096 +:100C000001FAE0222946204600F00EFA012038BD04 +:100C10000020FCE79AAD44C598110020B0320020B6 +:100C20001600002037B500F03FFC194D1949288106 +:100C30000223012218486B7101F0F8F90023019397 +:100C4000164B174900931748174B4FF4805201F089 +:100C500045FE164B197811B1124801F067FE01F0FC +:100C600049FB0446FFF722FC4FF4C873B0FBF3F2D4 +:100C700002FB130304F5167010FA83F00C4B186096 +:100C800002F02EFF08B10F232B8103B030BD00BF4F +:100C90008C11002040420F00D8210020B507000829 +:100CA0009C110020A4210020B90800089811002000 +:100CB000A02100202DE9F04F2DED028B8EA7D7E962 +:100CC00000670FF23C29D9E90089864C95B00DAD3B +:100CD0009FED828BFFF728FDDFF82CB200230C93E9 +:100CE000ADF83C300D936B6000230DF125028DEDC6 +:100CF000008B4FF0010A09A958468DF825308DF870 +:100D000024A001F041F99DF824200023002A40F09E +:100D1000AB80204601F012FE0546002847D1DFF8DF +:100D2000ECB101F0E7FADBF8003098423FD301F074 +:100D3000E1FA0790FFF7BAFB079A4FF4C873B0FBCC +:100D4000F3F101FB130302F5167010FA83F0CBF8F0 +:100D50000000DFF8BCB19BF800100791002914BF18 +:100D60002B46534610A88DF83030FFF7B7FB079994 +:100D7000C1F11002D2B2062A10AB28BF06221944D4 +:100D80000DF13100079200F03DF9079A0CAB039387 +:100D9000182302930132544BD2B2CDE900A304923E +:100DA0003B463246204601F00FFE8BF8005001F022 +:100DB000A1FA4E4A4E4D1368C31AB3F57A7F32D367 +:100DC000106001F099FA02460B46204601F094FEAD +:100DD000204601F0B3FD30B32B7ADFF838A1002BA9 +:100DE00014BF032302238AF8053001F083FA0DF1C2 +:100DF000400B4FF47A730122B0FBF3F05946CAF866 +:100E00000000504600F002FA18230293394B019378 +:100E100080B240F25513CDE903B0009342464B46F1 +:100E2000204601F0D1FD2B7ACBB101F063FA4FF0EF +:100E3000000A83464FF48A7295F8D900504400F0B6 +:100E4000030002FB005393F8E81089B30AF1010A8A +:100E5000BAF1040FF0D12B7A002B7FF438AF15B024 +:100E6000BDEC028BBDE8F08F4FF0904110A84A69AD +:100E700082F010024A611946102200F0D5F80DF1F7 +:100E800026030AAA0CA9584600F0E8FD95E80300DD +:100E900011AB83E803009DF83C308DF84C300C9B7F +:100EA000109310A9DDE90A23204601F0F9FF1BE7A2 +:100EB000D3F8E01049B12B68FA2B38BFFA23ABEB1B +:100EC00001010533B1EB430FC0D3FFF7DDFB4FF456 +:100ED0008A720028BAD1BEE7AFF30080000000009C +:100EE00000000000A42100209C210020E037002009 +:100EF000B0320020E4370020401DA12026812A0BBB +:100F0000F1C6A7C1D068080FD8210020A021002079 +:100F10009D2100208C11002008B5054800F03AFE04 +:100F2000BDE80840034A0449002003F025BB00BF88 +:100F3000D8210020203800208108000870B502F078 +:100F40000DFC094E094D3080002428683388834207 +:100F500008D902F0FFFB2B6804440133B4F5D04FED +:100F60002B60F2D370BD00BF14380020E83700209A +:100F700002F080BC00F10060920000F5D04002F069 +:100F800027BC0000054B1A68054B1B889B1A83423F +:100F900002D9104402F0DEBB00207047E837002081 +:100FA00014380020024B1B68184402F0D9BB00BF64 +:100FB000E8370020024B1B68184402F0E3BB00BF77 +:100FC000E8370020064991F8243033B10023086A3D +:100FD00081F824300822FFF7CDBF0120704700BF01 +:100FE000EC370020022802BF4FF0904310229A6194 +:100FF00070470000022802BF4FF090434FF4801268 +:101000009A61704710B50023934203D0CC5CC4545E +:101010000133F9E710BD000003460246D01A12F969 +:10102000011B0029FAD1704702440346934202D0C3 +:1010300003F8011BFAE770472DE9F8431F4D1446EA +:1010400095F824200746884652BBDFF870909CB381 +:1010500095F824302BB92022FF2148462F62FFF754 +:10106000E3FF95F82400C0F10802A24228BF2246FF +:10107000D6B24146920005EB8000FFF7C3FF95F81A +:101080002430A41B1E44F6B2082E17449044E4B248 +:1010900085F82460DBD1FFF795FF0028D7D108E061 +:1010A0002B6A03EB82038342CFD0FFF78BFF00282C +:1010B000CBD10020BDE8F8830120FBE7EC3700200E +:1010C0002DE9F0470D46044600219046284640F29F +:1010D0007912FFF7A9FF234620220021284601F0BC +:1010E00081FE231D02222021284601F07BFE631D84 +:1010F00003222221284601F075FEA31D032225218B +:10110000284601F06FFE04F108031022282128462A +:1011100001F068FE04F1100308223821284601F08E +:1011200061FE04F1110308224021284601F05AFE15 +:1011300004F1120308224821284601F053FE04F16D +:10114000140320225021284601F04CFE04F118031C +:1011500040227021284601F045FE04F120030822B8 +:10116000B021284601F03EFE04F121030822B821F7 +:10117000284601F037FE04F12207C0263B463146DF +:1011800008222846083601F02DFEB6F5A07F07F1AB +:101190000107F3D104F1320308223146284601F059 +:1011A00021FE002704F1330A94F832304FEAC709D0 +:1011B0009F4209F5A47615D3B8F1000F08D1314646 +:1011C00004F599730722284601F00CFE09F24F1628 +:1011D000274694F832213B1B93420CD3F01DC008E4 +:1011E000BDE8F0870AEB070308223146284601F0E4 +:1011F000F9FD0137D8E707F23313314608222846B4 +:1012000001F0F0FD08360137E3E7000013B50446AE +:101210000846002101602346C0F8031020220190F7 +:1012200001F0E0FD0198231D0222202101F0DAFDEA +:101230000198631D0322222101F0D4FD0198A31D12 +:101240000322252101F0CEFD019804F108031022AC +:10125000282101F0C7FD072002B010BDF7B500231B +:10126000047F00910E4607221946054601F07EFCD8 +:10127000731C0093012200230721284601F076FC0D +:10128000C4B9B31C0093052223460821284601F067 +:101290006DFC0D243746B278BB1B934211D32B7FD4 +:1012A000A88A0734E408BBB9844294BF0020012017 +:1012B00003B0F0BDAB8ADB00083BDB08B370082449 +:1012C000E8E7FB1C0093214600230822284601F092 +:1012D0004DFC08340137DEE7201A18BF0120E7E78C +:1012E000F7B50023047F00910E46082219460546F3 +:1012F00001F03CFC731CC4B908220093114623463C +:10130000284601F033FC1024012372785F1C013B56 +:10131000934211D32B7FA88A0734E408BBB98442D7 +:1013200094BF0020012003B0F0BDAB8ADB00083B76 +:10133000DB0873700824E7E7F319009321460023C4 +:101340000822284601F012FC08343B46DDE7201A4B +:1013500018BF0120E7E70000F8B50E460546144621 +:10136000002181223046FFF75FFE2B460822002134 +:10137000304601F037FD7CB96B1C0722082130464E +:1013800001F030FD0F2401236A785F1C013B93427A +:1013900004D3E01DC008F8BD0824F4E7EB1921468A +:1013A0000822304601F01EFD08343B46ECE7000001 +:1013B000F8B50E46054614460021CE223046FFF70A +:1013C00033FE2B4628220021304601F00BFD7CB96C +:1013D00005F1080308222821304601F003FD3024DE +:1013E0002F462A7A7B1B934204D3E01DC008F8BD28 +:1013F0002824F5E707F1090321460822304601F0C9 +:10140000F1FC08340137ECE7F7B5047F00910E4694 +:10141000012310220021054601F0A8FBC4B9B31C2A +:101420000093092223461021284601F09FFB19242E +:1014300037467288BB1B9A4211D82B7FA88A073483 +:10144000E408BBB9844294BF0020012003B0F0BD82 +:10145000AB8ADB00103BDB0873801024E8E73B1D00 +:101460000093214600230822284601F07FFB083420 +:101470000137DEE7201A18BF0120E7E730B5094D34 +:101480000A4491420DD011F8013B5840082340F323 +:101490000004013B2C4013F0FF0384EA5000F6D116 +:1014A000EFE730BD2083B8EDF7B5364A10685168D4 +:1014B0006B4603C36A4634493448082303F0BCF83A +:1014C000044690BB0A25324A106851686B4603C334 +:1014D0006A4630492D48082303F0AEF80446002838 +:1014E00047D00369B3F5663F43D8B0F86620B2F53C +:1014F0007B7F3ED1284A024402F15C018B4238D303 +:101500005C3B224900209E1AFFF7B8FF324607468F +:1015100004F164010020FFF7B1FFA3689F4228D1C6 +:10152000E368984208BF002523E00369B3F5663FEE +:1015300026D8428BB2F57B7F20D1174A024402F1B4 +:1015400010018B4218D3103B104900209D1AFFF761 +:1015500095FF2A46064604F118010020FFF78EFF8A +:10156000A3689E4202D1E368984201D00D25AAE704 +:101570000025284603B0F0BD1025A4E70C25A2E7FE +:101580000B25A0E734470008DC970300006800083B +:101590003D470008909703000898FFF710B5037CBB +:1015A000044613B9006803F02FF8204610BD000070 +:1015B0000023BFF35B8FC360BFF35B8FBFF35B8F11 +:1015C0008360BFF35B8F7047BFF35B8F0068BFF32F +:1015D0005B8F704770B505460C30FFF7F5FF05F1DE +:1015E000080604463046FFF7EFFFA04206D9304612 +:1015F0006D68FFF7E9FF2544281A70BD3046FFF7F4 +:10160000E3FF201AF9E7000070B50546406898B17D +:1016100005F10800FFF7D8FF05F10C060446304637 +:10162000FFF7D2FF8442304694BF6D680025FFF774 +:10163000CBFF013C2C44201A70BD000038B50C468D +:101640000546FFF7C7FFA04210D305F10800FFF7DA +:10165000BBFF04446868B4FBF0F100FB1144BFF326 +:101660005B8F0120AC60BFF35B8F38BD0020FCE7CF +:101670002DE9F041144607460D46FFF7C5FF8442A9 +:1016800028BF0446D4B1B84658F80C6B4046FFF763 +:101690009BFF3044286040467E68FFF795FF331A71 +:1016A0009C4203D86C600120BDE8F0816B60A41BF4 +:1016B0003B68AB602044E8600220F5E72046F3E792 +:1016C00038B50C460546FFF79FFFA04210D305F141 +:1016D0000C00FFF779FF04446868B4FBF0F100FBED +:1016E0001144BFF35B8F0120EC60BFF35B8F38BD0B +:1016F0000020FCE72DE9FF41884669460746FFF7D1 +:10170000B7FF6C4606B204EBC6060025B44209D00A +:101710006268206808EB0501FFF774FC6368083411 +:101720001D44F3E729463846FFF7CAFF284604B0B0 +:10173000BDE8F081F8B505460C300F46FFF744FFD1 +:1017400005F1080604463046FFF73EFFA04230464A +:1017500088BF6C68FFF738FF201A386020B1304628 +:101760002C68FFF731FF2044F8BD000073B5144624 +:1017700006460D46FFF72EFF844228BF044601901F +:10178000DCB101A93046FFF7D5FF019B33B93268C0 +:10179000C5E90233C5E9002401200CE09C4238BFB2 +:1017A00001942860019868608442F5D93368AB6081 +:1017B000241AEC60022002B070BD2046FBE7000056 +:1017C0002DE9FF410F466946FFF7D0FF6C4600B296 +:1017D00004EBC0050026AC4209D0D4F8048054F8CC +:1017E000081BB8194246FFF70DFC4644F3E73046A4 +:1017F00004B0BDE8F081000038B50546FFF7E0FF12 +:10180000044601462846FFF719FF204638BD000070 +:1018100010B4026854681A4623465DF8044B184712 +:10182000002070470020704770470000002070477C +:101830000E20704700F5805090F8C800C0F34000BB +:101840007047000000F5805090F9D000704700000C +:1018500000F58050C0F8CC1001207047F7B50C6837 +:10186000BDF8207014F0005470D10D7B082D6DD898 +:10187000302585F311884569AE6876010CD4AC68D3 +:10188000240108D4AC6814F080545DD184F311882D +:10189000204603B0F0BD01240E6804F1180C002EA0 +:1018A000B8BFF6004FEA0C1CB4BF46F0040676053C +:1018B00045F80C600E680FFA84FC16F0804F18BFD4 +:1018C00005EB0C1E05EB0C1C1EBFDEF8806146F01C +:1018D0000206CEF880610E7BCCF8846105EB04151E +:1018E0008E68C5F88C614E68C5F88861DCF8805157 +:1018F00045F00105CCF8805100EB441641F2680533 +:101900002E4405EB44150544C6E9002308350E4670 +:1019100001F10C0C56F804EB45F804EB6645F9D1DF +:10192000843436882E8000EB441407F003052679B2 +:1019300026F00B0635432571002484F311880097A7 +:1019400000F0FAFC0120A4E70224A5E74FF0FF30E5 +:101950009FE7000013B500F580540191E06DFFF79B +:1019600053FE1F280AD90199E06D2022FFF7C2FE1D +:10197000A0F120035842584102B010BD0020FBE7FF +:1019800008B5302383F3118800F58050C06DFFF750 +:101990000FFE002383F3118808BD000000220260BF +:1019A000828142608260704710B500220023C0E946 +:1019B00000230023044603810C30FFF7EFFF20468D +:1019C00010BD0000F0B5054600F580500C4690F8BB +:1019D000C83013F0040FC3F3800108BF114661F350 +:1019E000820304F1840680F8C83005EB461389B001 +:1019F0001B79D8072ED57AB319072DD46846FFF77F +:101A0000D3FF05EB441303F5835303F1180703AA2F +:101A1000103318685968144603C40833BB42224681 +:101A2000F7D1186820609B88A380DDE90E23CDE9FB +:101A300000230123ADF808302B686946DB6B28468C +:101A4000984705EB46152B791A075CBF43F008034E +:101A50002B7101E0002AF4D109B0F0BD2DE9F04767 +:101A60009A4688B0074688469146302383F311880A +:101A700007F580546846FFF797FFE06DFFF7AAFD72 +:101A80001F282AD9E06D20226946FFF7B5FE2028DD +:101A900023D103AD444605AB2E4603CE9E422060C3 +:101AA0006160354604F10804F6D130682060B388DF +:101AB000A380DDE90023C9E90023BDF80830AAF8B6 +:101AC0000030002383F3118853464A464146384686 +:101AD00008B0BDE8F04700F01DBC002080F311887D +:101AE00008B0BDE8F08700002DE9F84F0023C0E9F9 +:101AF0000133254B044640F8183B0F46FFF74EFFD5 +:101B000004F12800FFF750FF04F1480804F582555E +:101B10004646083530462036FFF746FFAE42F9D13B +:101B200004F580554FF480534FF00009C5E913398F +:101B3000C5F848800123EE6504F5875804F58456FE +:101B4000C5F8549085F8583085F86030083608F1AB +:101B500008084FF0000A4FF0000B46E908ABA6F169 +:101B60001800FFF71BFF203646F8289C4645F4D1A5 +:101B700085F8D07017B1054800F0B6FB044B6361DF +:101B80002046BDE8F88F00BF7047000848470008AE +:101B90000064004010B5044B197804464A1C1A70C2 +:101BA000FFF7A2FF204610BD1C3800202DE9F047AA +:101BB000002950D0294B2A4FB7FBF1F599428CBF31 +:101BC0000A231123581EB5FBF3FC03FB1C53C4B2BC +:101BD0002BB102280346F5D80020BDE8F0870CF1B0 +:101BE000FF36B6F5806FF7D2C4EBC40E0EF10303D7 +:101BF0004FEAE309C3F3C703A4EB030809F1010AA1 +:101C00004FF47A755FFA88F009FB05555AFA88F89F +:101C1000B5FBF8F5B5F5617FC1BF0EF1FF33C3F336 +:101C2000C703E01AC0B25C1C50FA84F40CFB04F445 +:101C3000B7FBF4F4A142CFD1013BDBB20F2BCBD8E1 +:101C40000138C0B20728C7D80021107116809170E2 +:101C5000D3700120C1E70846BFE700BF3F420F0035 +:101C60000051250270B505460E464FF47A746B6933 +:101C70005B6803F00103B3424FF0010004D001F0B0 +:101C800095FC013CF3D1204670BD000030B542699F +:101C9000936913F0700F16D000230B4C936103F17E +:101CA000840200EB421211794D0709D5890707D547 +:101CB000416954F823508D60117941F0040111718C +:101CC0000133032BEBD130BD5C47000873B51D46D3 +:101CD000436916469A68D207044609D59A680121D5 +:101CE0009960C2F34002CDE900650021FFF76AFE6A +:101CF00063699A68D1050BD59A684FF48071996031 +:101D0000C2F34022CDE9006501212046FFF75AFECB +:101D100063699A68D2030BD59A684FF48031996051 +:101D2000C2F34042CDE9006502212046FFF74AFE9A +:101D300004F58053D3F8CC0010B103681B699847B1 +:101D4000204602B0BDE87040FFF7A0BFF8B50446DA +:101D50004669002972D106F10C073868800770D0F7 +:101D600006EB01153868D5F8B00110F0040FD5F86E +:101D7000B0011ABFC00840F00040400DA061D5F886 +:101D8000B0C11CF0020F1CBF40F08040A061D5F82C +:101D9000B40106EB011100F00F0084F82400D1F823 +:101DA000B8012077D1F8B801000A6077D1F8B801FE +:101DB000000CA077D1F8B801000EE077D1F8BC0193 +:101DC00084F82000D1F8BC01000A84F82100D1F881 +:101DD000BC01000C84F82200D1F8BC11090E84F873 +:101DE00023103821396004F1340004F1180104F1A2 +:101DF000240551F8046B40F8046BA942F9D1098815 +:101E00000180C4E90A2321460023238651F8283B98 +:101E10002046DB6B984704F5805393F8C820D3F82D +:101E2000CC0042F0040283F8C82010B103681B699B +:101E300098472046BDE8F840FFF728BF06F1100795 +:101E40008BE7F8BD10B5044600F056FA02460B4683 +:101E500052EA030102D0013A63F100030449086821 +:101E600020B12146BDE81040FFF770BF10BD00BF94 +:101E700018380020F0B5302181F31188DFF848C010 +:101E800000F583510831002404F1840500EB451569 +:101E90002E7977070ED4F6060CD5D1E90076974255 +:101EA0009E4107D246695CF82470B7602E7946F0EF +:101EB00004062E710134032C01F12001E4D100232A +:101EC00083F31188F0BD00BF5C47000808B53023DC +:101ED00083F31188FFF7DAFE002383F3118808BD2E +:101EE000F8B543690546986800F0E050B0F1E05F4E +:101EF0000F4621D0F8B1302383F3118805F58354C0 +:101F00001034002606F1840305EB43131B791A07EE +:101F100006D50136032E04F12004F3D1012007E099 +:101F20005B07F6D42146384600F040FA0028F0D18D +:101F3000002383F31188F8BD0120FCE708B53023A6 +:101F400083F3118800F58050C06DFFF743FB002339 +:101F500083F3118843090CBF0120002008BD000055 +:101F6000F8B51D46002313700F4606461446FFF7CA +:101F7000E5FF80F00100387025B129463046FFF7B3 +:101F8000AFFF2070F8BD00002DE9B8410C461546A2 +:101F90001F46804600F0B0F90B462178024609B989 +:101FA000287850B14046FFF765FFFFF78FFF3B46AB +:101FB0002A462146FFF7D4FF0120BDE8B881000082 +:101FC00070B5302686F31188174BDA6942F000723B +:101FD000DA611A6942F000721A611A6922F000721D +:101FE0001A61002383F3118800F5805494F8C830F7 +:101FF00013F0010516D1A9B186F31188032113202E +:1020000001F0C8F90321142001F0C4F903211520BF +:1020100001F0C0F994F8C83043F0010384F8C830E7 +:1020200085F3118870BD00BF001002402DE9F04714 +:1020300000F5805588B095F8D030012B04468846CD +:10204000164600F28180814F57F823200AB947F8DD +:102050002300D7F800A0C4F80C802674BAF1000F52 +:1020600064D095F8D030012B70D001212046FFF7C5 +:10207000A7FF302383F311886269136823F00203FA +:1020800013606269136843F00103136063690027FA +:102090005F6187F3118801212046FFF7E3FD0028E7 +:1020A00000F09580E86DFFF783FA04F58359BA468E +:1020B00009F10809202200216846FEF7B5FF02A8B1 +:1020C000FFF76CFCCDF818A06A4609EB07030DF189 +:1020D000180E9446BCE80300F44518605960624647 +:1020E00003F10803F5D1DCF80000186020379CF8F4 +:1020F00004201A71602FDDD195F8C8306FF3820388 +:10210000002785F8C8306A4641462046ADF8007081 +:10211000ADF802708DF80470FFF748FD636948BBA5 +:102120004FF400421A6008B0BDE8F08741F2D800D1 +:1021300002F02AFA814610B15146FFF7D5FCC7F8E4 +:102140000090B9F1000F8CD10020ECE738680368EB +:102150001B6B98470146002887D13868FFF730FF8E +:102160003868036832465B684146984700287FF428 +:102170007CAFE9E761221A609DF802309DF80320E8 +:102180001B06120402F4702203F040731343BDF8DF +:102190000020C2F3090213439DF804201205022E09 +:1021A00002F4E0020CBF4FF00041002113436269CA +:1021B0000B43D361636913225A616269136823F088 +:1021C0000103136039462046FFF74CFD08B96369E7 +:1021D000A6E795F8D03093BB6169D1F8002242F0B0 +:1021E0000102C1F800226169D1F8002222F47C5278 +:1021F00022F00E02C1F800226169D1F8002242F4F7 +:102200006062C1F800226269C2F814326269C2F8E1 +:102210000432626941F6FF71C2F80C126269C2F8B9 +:1022200040326269C2F8443263690122C3F81C2259 +:102230006269D2F8003223F00103C2F8003295F847 +:10224000C83043F0020385F8C8306CE71838002026 +:1022500008B500F051F850EA0103024602D0421ED0 +:1022600061F10001044B186810B10B46FFF72EFD19 +:10227000BDE8084001F064B81838002008B5002017 +:10228000FFF7E0FDBDE8084001F05AB808B50120AD +:10229000FFF7D8FDBDE8084001F052B800B59BB08B +:1022A000EFF3098168226846FEF7ACFEEFF3058381 +:1022B000014B9B6BFEE700BF00ED00E008B5FFF7A8 +:1022C000EDFF000000B59BB0EFF30981682268467E +:1022D000FEF798FEEFF30583014B5B6BFEE700BF53 +:1022E00000ED00E0FEE700000FB408B5029801F031 +:1022F0000DF9FEE701F040BB01F0ECBA13B56C46F6 +:1023000084E80600031D94E8030083E8050001202B +:1023100002B010BD73B58568019155B11B885B078C +:1023200007D4D0E900369B6B9847019AC1B230467A +:10233000A847012002B070BDF0B5866889B0054697 +:102340000C465EB1BDF838305B070AD4D0E90037DF +:102350009B6B98472246C1B23846B047012009B06E +:10236000F0BD00220023CDE900230023ADF80830A2 +:102370000A4603AB01F10806106851681C4603C405 +:102380000832B2422346F7D1106820609288A280BA +:10239000FFF7B2FF0423ADF808302B68CDE9000148 +:1023A000DB6B694628469847D8E7000030B50368DC +:1023B0000968DD0FB5EBD17F23F0604421F0604266 +:1023C0004FEAD1700BD0002BB8BFA40C0029B8BFC6 +:1023D000920C944202D034BF0120002030BD9442C0 +:1023E00005D1C1F38070C3F380738342F6D1944268 +:1023F0002CBF00200120F1E72DE9F041456A15B915 +:102400004162BDE8F0814B6823F06047C3F38A4620 +:102410004FEAD37EC3F3807816EA230638BF3E46E0 +:10242000AC462B465A68BEEBD27F22F060440AD0FD +:10243000002A18DAA40CB44217D19D420FD10D60C6 +:10244000DEE71346EEE7A74207D102F08044C2F36D +:10245000807242450BD054B1EFE708D2EDE7CCF8DB +:1024600000100B60CDE7B44201D0B442E5D81A6841 +:102470009C46002AE5D11960C3E700002DE9F0472A +:10248000089D01F007044FEAD508224405F007052E +:1024900000EBD1004FF47F49944201D1BDE8F087B1 +:1024A00004F0070705F0070A57453E4638BF564671 +:1024B000C6F10806111B8E4228BF0E46E10808EB44 +:1024C000D50E415C13F80EC0B94029FA06F721FA7F +:1024D0000AF1FFB28CEA010147FA0AF739408CEAA7 +:1024E000010C03F80EC034443544D5E780EA0120DE +:1024F000082341F2210201B24000002980B203F119 +:10250000FF33B8BF504013F0FF03F4D17047000011 +:1025100038B50C468D18A54200D138BD14F8011B02 +:10252000FFF7E4FFF7E7000042684AB11368436031 +:102530004389818901339BB29942438138BF8381AA +:102540001046704770B588B0202204460D46684694 +:102550000021FEF769FD20460495FFF7E5FF0246DE +:1025600058B16B46054608AE1C4603CCB442286001 +:102570006960234605F10805F6D1104608B070BD24 +:10258000082817D909280CD00A280CD00B280CD001 +:102590000C280CD00D280CD00E2814BF4020302061 +:1025A00070470C2070471020704714207047182087 +:1025B0007047202070470000082817D90C280CD934 +:1025C00010280CD914280CD918280CD920280CD97B +:1025D00030288CBF0F200E207047092070470A203A +:1025E00070470B2070470C2070470D20704700008B +:1025F0002DE9F843078C072F04461ED9D0E902982D +:1026000000254FF6FF73C5F12006A5F1200029FA39 +:1026100005F108FA06F628FA00F031430143C9B281 +:102620001846FFF763FF0835402D0346EBD1E169FB +:102630003A46BDE8F843FFF76BBF4FF6FF70BDE8C1 +:10264000F883000010B54B6823B9CA8A63F3090206 +:10265000CA8210BD04691A681C600361C38A013B09 +:10266000C3824A60EFE700002DE9F84F1D46CB8A90 +:102670000F46C3F309010529814692460B4630D027 +:102680000020AAB207F11A049EB2042E1FFA80F8A5 +:102690000FD8904503F1010306D3FB8A0A4462F385 +:1026A0000903FB8201201AE01AF80060E6540130A9 +:1026B000EAE79045F1D2A1F1050B1C237C68BBFB36 +:1026C000F3F203FB12BB1FFA8BF6002C45D14846F0 +:1026D000FFF72AFF044638B978606FF00200BDE8C2 +:1026E000F88F4FF00008E6E7002606607860ADB28C +:1026F0004FF0000B454510D90AEB0803221D13F8D3 +:10270000011B9155B1B208F101081B291FFA88F885 +:102710002BD0454506F10106F1D8FB8AC3F3090227 +:10272000154465F30903BCE7013292B21C462368E5 +:10273000002BF9D16B1F0B441C21B3FBF1F30133C8 +:102740009BB29A42D3D2BBF1000FD0D14846FFF7DB +:10275000EBFE20B9C4F800B0BFE70122E7E7C0F8FC +:1027600000B05E4620600446C1E74545D5D94846DD +:10277000FFF7DAFE08B92060AFE7C0F800B0002626 +:1027800020600446B6E700002DE9F04F2DED028BE6 +:102790001C4683B05B69019207468846002B00F017 +:1027A0009A80238C2BB1E269002A00F09480072BD9 +:1027B00035D807F10C00FFF7B7FE054638B96FF0C2 +:1027C0000205284603B0BDEC028BBDE8F08F142251 +:1027D0000021FEF729FC228CE16905F10800FEF7D3 +:1027E00011FC208C013080B2FFF7E6FEFFF7C8FE37 +:1027F000013880B22084013028746369228C1B78F0 +:102800002A4403F01F0363F03F0348F000411372B2 +:10281000384669602946FFF7EFFD0125D1E700F151 +:102820000C034FF0000908EE103A4FF0800A4E46B4 +:102830004D4618EE100AFFF777FE83460028BED0FB +:1028400014220021FEF7F0FB002E3AD1019BABF8D9 +:10285000083002220BF1080E1FFA82FC0CF1010075 +:10286000BCF1060F218C80B201D88E422BD3FFF72A +:10287000A3FEFFF785FE62691278013802F01F029D +:102880008E4208BF4FF0400A42EA49121BFA80F11B +:102890004AEA020A013048F0004281F808A08BF8A9 +:1028A0001000CBF8042059463846FFF7A5FD238CCD +:1028B0000135B3422DB289F001094FF0000AB8D1B9 +:1028C0007FE70022C6E7E169895D0EF80210013654 +:1028D000B6B20132C0E76FF0010572E7F8B51546F0 +:1028E0000E463022002104461F46FEF79DFB069B44 +:1028F0006360B5F5001F079BA76034BF6A094FF6F8 +:10290000FF72A36297B2E66104F1100000239A42BD +:1029100006D800230360A782E3822383E360F8BD27 +:102920000660013330462036F1E7000003781BB91A +:102930004BB2002BC8BF0170704700000078704791 +:10294000F8B50C46C969074611B9238C002B37D15D +:10295000257E1F2D34D8387828BB228C072A2CD806 +:10296000268A36F003032BD14FF6FF70FFF7D0FD18 +:1029700020F001003102400441EA0561400C41EAC7 +:1029800040254FF6FF72234629463846FFF7FCFEE6 +:10299000002807DD626913780133DBB21F2B88BF83 +:1029A00000231370F8BD218A2D0645EA0125054351 +:1029B0002046FFF71DFE0246E5E76FF00300F1E752 +:1029C0006FF00100EEE7000070B58AB004461646CD +:1029D0000021282268461D46FEF726FBBDF8383048 +:1029E000ADF810300F9B05939DF840308DF81830EE +:1029F000119B07936946BDF84830ADF8203020465A +:102A0000CDE90265FFF79CFF0AB070BD2DE9F041EA +:102A1000D36905460C4616460BB9138C5BBB377E53 +:102A20001F2F28D895F80080B8F1000F26D0304627 +:102A3000FFF7DEFD3378210241EAC33141EA0801A4 +:102A4000338A41EA076141EA03410246334641F0D5 +:102A500080012846FFF798FE00280ADD3378012B15 +:102A600007D1726913780133DBB21F2B88BF0023B3 +:102A70001370BDE8F0816FF00100FAE76FF003001A +:102A8000F7E70000F0B58BB004460D46174600216D +:102A9000282268461E46FEF7C7FA9DF84C305A1E9B +:102AA000534253418DF800309DF84030ADF810305E +:102AB000119B05939DF848308DF81830149B0793AF +:102AC0006A46BDF85430ADF8203029462046CDE99D +:102AD0000276FFF79BFF0BB0F0BD0000406A00B12B +:102AE00004307047436A1A68426202691A600361DF +:102AF000C38A013BC38270472DE9F041D0F82080A2 +:102B0000194E14461D464146002709B9BDE8F0811B +:102B1000D1E90223A21A65EB0303964277EB030384 +:102B20001ED2036A8B420DD1FFF78CFD036A1B682E +:102B3000036203690B60C38A0161016A013BC382BE +:102B40008846E2E7FFF77EFD0B68C8F800300369AE +:102B50000B60C38A0161013BC382D8F80010D4E73F +:102B600088460968D1E700BF80841E002DE9F04F38 +:102B70008BB00D46DDF8509014469B4680460028E9 +:102B800000F01981B9F1000F00F01581531E3F2BA1 +:102B900000F21181012A03D1BBF1000F40F00B813B +:102BA0000023CDE90833B8F81430B5EBC30F4FEA72 +:102BB000C30703D300200BB0BDE8F08F2B199F4251 +:102BC000D8F80C303ABF7F1BFFB227461BB9D8F8A4 +:102BD0001030002B7AD0272D4ED8C5F12806B742E9 +:102BE0004FF000032CBFF6B23E4600932946D8F8BA +:102BF000080008AB3246FFF741FCA7EB060A354454 +:102C00005FFA8AFAB8F8143003F10053053BDB0091 +:102C10000493D8F80C3003932821039B13B1BAF125 +:102C2000000F2CD1D8F8100040B1BAF1000F05D038 +:102C3000009608AB5246691AFFF720FC38B2002F05 +:102C4000B8D066070AD00AAB03EBD401624211F890 +:102C5000083C02F00702134101F8083C082C3CD95B +:102C6000102C40F2B580202C40F2B780BBF1000F51 +:102C700000F09C80082334E0BA460026C2E7049B9B +:102C8000E02B28BFE02306930B44AB42059314D9F5 +:102C90005A1B03980096924534BF5246D2B2691A25 +:102CA00008AB04300792FFF7E9FB079A1644AAEB3A +:102CB000020A1544F6B25FFA8AFA049B069A05994D +:102CC0009B1A0493039B1B680393A6E70093D8F811 +:102CD000080008AB3A462946AEE7BBF1000F13D017 +:102CE0000123B4EBC30F6CD0082C12D89DF8203010 +:102CF000621E23FA02F2D50706D54FF0FF3202FA20 +:102D000004F423438DF820309DF8203089F80030FA +:102D100051E7102C12D8BDF82030621E23FA02F2BF +:102D2000D10706D54FF0FF3202FA04F42343ADF881 +:102D30002030BDF82030A9F800303CE7202C0FD817 +:102D40000899631E21FA03F3DA0705D54FF0FF3225 +:102D500002FA04F40C430894089BC9F800302AE7EF +:102D6000402C2BD0DDE90865611EC4F12102A4F1DD +:102D7000210326FA01F105FA02F225FA03F31143C1 +:102D80001943CB0712D50122A4F12003C4F120017D +:102D900002FA03F322FA01F1A240524243EA01038C +:102DA00063EB430332432B43CDE90823DDE90823DA +:102DB000C9E90023FFE66FF00100FCE66FF00800B0 +:102DC000F9E6082CA0D9102CB3D9202CEED8C3E7F3 +:102DD000BBF1000FADD0022383E7BBF1000FBBD0E6 +:102DE00004237EE730B5012A144638BF0124402C65 +:102DF00085B028BF40240025012ACDE9025518D806 +:102E00001B788DF8083063070AD004AB03EBD405B8 +:102E1000624215F8083C02F00702934005F8083CAE +:102E2000009103462246002102A8FFF727FB05B0C8 +:102E300030BD082AE4D9102A03D81B88ADF8083021 +:102E4000E1E7202A8DBFD3E900231B680293CDE977 +:102E50000223D8E710B5CB681BB98B600B618B825E +:102E600010BD04691A681C600361C38A013BC382F8 +:102E7000CA60F0E703064CBFC0F3C03002207047C1 +:102E800008B50246FFF7F6FF022806D15306C2F343 +:102E90000F2001D100F0030008BDC2F30740FBE79B +:102EA0002DE9F04F93B0CDE903230A68044610469C +:102EB000FFF7E0FF022814BFC2F306260026002A0F +:102EC0000D46824680F2F28112F0C04940F0EE8158 +:102ED000097B002900F0EA81022803D02378B3425D +:102EE00040F0E781C2F304630693104602F07F03CB +:102EF0000593FFF7C5FF059B29444FEA834848EA3D +:102F00000A4848EA4668CE7800230022CDE9082323 +:102F1000F309834648EA0008029367D0059B0093B3 +:102F200002466768534608A92046B847002800F0C3 +:102F3000C381276A4FB9414604F10C00FFF702FB39 +:102F4000074690B96FF0020054E03B6998450DD0F8 +:102F50003F68002FF9D1414604F10C00FFF7F2FA67 +:102F600007460028EED0236A3B60276297F817C017 +:102F700006F01F08CCF3840CACEB08001FFA80FEAF +:102F80000028B8BF0EF12000A8EB0C031FFA83FE47 +:102F9000D7E90221B8BF00B2002B0793BEBF0EF1E4 +:102FA00020031BB2079352EA010338D0039BDFF8DA +:102FB00024E39A1A049B4FF0000C63EB0101964541 +:102FC0007CEB01032BD36B7B97F81AE0734519D187 +:102FD000029B002B78D0012821DC7868F8B9DFF853 +:102FE000F0C2944570EB010316D337E0276A27B986 +:102FF0006FF00C0013B0BDE8F08F3B699845B5D079 +:103000003F68F4E7B24890427CEB010301D3002013 +:10301000F0E7029B002BFAD0079B0F2B17DCFA7D01 +:10302000B30002F0030203F07C031343FB7539463F +:103030002046FFF707FB6B7BBB76029B3BB9FB7D12 +:10304000C3F38402013262F38603FB75D0E76A7B27 +:10305000BB7E9A42DBD1029B002B35D0B309022BF9 +:1030600032D0039BBB60049BFB60142200210DA89F +:10307000FDF7DAFF039B0A93049B0B932B1D0C9324 +:103080002B7BADF83EB0013BDBB2ADF83C30069B8C +:103090008DF84230059B8DF8433094F82C308DF834 +:1030A00040A083F001038DF844308DF84180A3687F +:1030B0000AA920469847FB7DC3F38403013303F03C +:1030C0001F039B02FB82A2E7FB7DC6F34012B2EB1B +:1030D000D31F40F0F480C3F38403434540F0F280F3 +:1030E000029A2B7BB609002A4DD0F2075DD4032B40 +:1030F00040F2EB80039BBB60049BFB602B7BAE1D0F +:10310000033BDBB23246394604F10C00FFF7ACFA60 +:1031100000280CDA39462046FFF794FAFB7DC3F30A +:103120008403013303F01F039B02FB820AE7DDE9FE +:103130000884AB883B834FF6FF73C9F12000A9F1E7 +:10314000200228FA09F104FA00F0014324FA02F2FD +:1031500011431846C9B2FFF7C9F909F10809B9F1D5 +:10316000400F0346E9D1B8822A7B033AD2B23146F6 +:10317000FFF7CEF9FB7DB882DA43C2F3C01262F3E7 +:10318000C713FB7543E786B92E1D013BDBB2324600 +:10319000394604F10C00FFF767FA0028BADB2A7BF6 +:1031A000B88A013AD2B23146E2E7F98AC1F309019D +:1031B000013B0429DAB25BD8281D002307F11B0666 +:1031C0009A4208D910F801CB06F801C00131013349 +:1031D0000529DBB2F4D103990A9104990B9193422A +:1031E00007F11B010C9138BF043379680D9134BF8E +:1031F00055FA83F300230E93FB8AADF83EB0C3F378 +:1032000009031A44069B8DF84230059B8DF8433024 +:1032100094F82C30ADF83C2083F001038DF8443055 +:1032200000238DF840A08DF841807B602A7BB88A0E +:10323000013A291DFFF76CF93B8BB882834203D119 +:10324000A3680AA92046984720460AA9FFF702FE6C +:10325000FB7DBA8AC3F38403013303F01F039B028F +:10326000FB823B8B9A420CBF00206FF01000C1E63E +:103270007B68002BAFD0052001E01C3033461E6870 +:10328000002EFAD1091A081D2E1D184401EB090C55 +:10329000BCF11B0F5FFA89F39DD89A429BD916F8AF +:1032A000013B00F8013B09F10109EFE76FF009006C +:1032B000A0E66FF00A009DE66FF00B009AE66FF053 +:1032C0000D0097E66FF00E0094E66FF00F0091E6A8 +:1032D00040420F0080841E00EFF3098305494A6BCA +:1032E00022F001024A63683383F30988002383F3E1 +:1032F0001188704700EF00E0302080F3118862B63B +:103300000C4B0D4AD96821F4E0610904090C0A4309 +:10331000DA60D3F8FC20094942F08072C3F8FC203F +:103320000A6842F001020A602022DA7783F822005C +:10333000704700BF00ED00E00003FA05001000E058 +:1033400010B5302383F311880E4B5B6813F40063D0 +:1033500014D0F1EE103AEFF30984683C4FF080731B +:10336000E361094BDB6B236684F3098800F098F86E +:1033700010B1064BA36110BD054BFBE783F3118829 +:10338000F9E700BF00ED00E000EF00E0FF020008F9 +:103390000203000800F1604303F561430901C9B26B +:1033A00083F80013012200F01F039A4043099B0099 +:1033B00003F1604303F56143C3F880211A6070474D +:1033C00000F16040090100F56D40C9B20176704717 +:1033D00000230375826803691B6899689142FBD2D8 +:1033E0005A6803604260106058607047002303759C +:1033F000826803691B6899689142FBD85A68036028 +:10340000426010605860704708B50846302383F367 +:1034100011880B7D032B05D0042B0DD02BB983F322 +:10342000118808BD8B6900221A604FF0FF33836159 +:10343000FFF7CEFF0023F2E7D1E9003213605A60B4 +:10344000F3E70000FFF7C4BF054BD968087518689B +:1034500002681A60536001220275D860FCF73ABF17 +:103460002838002030B50C4BDD684B1C87B0044673 +:103470000FD02B46094A684600F0D8F82046FFF7DF +:10348000E3FF009B13B1684600F0DAF8A86907B0C3 +:1034900030BDFFF7D9FFF9E72838002009340008CC +:1034A000044B1A68DB6890689B68984294BF0020C0 +:1034B0000120704728380020084B10B51C68D868D8 +:1034C00022681A60536001222275DC60FFF78EFFCC +:1034D00001462046BDE81040FCF7FCBE283800201D +:1034E00038B5074C0749084801230025237065605B +:1034F00000F024FB0223237085F3118838BD00BF40 +:10350000503A0020B44700082838002008B572B6A9 +:10351000044B186500F0C2F900F0ACFA024B03222C +:103520001A70FEE728380020503A002000F09AB8C0 +:103530008B60022308618B82084670478368A3F181 +:10354000840243F8142C026943F8442C426943F87E +:10355000402C094A43F8242CC26843F8182C022254 +:1035600003F80C2C002203F80B2C044A43F8102C0F +:10357000A3F12000704700BFED02000828380020AA +:1035800008B5FFF7DBFFBDE80840FFF75BBF0000B1 +:10359000024BDB6898610F20FFF756BF28380020E8 +:1035A000302383F31188FFF7F3BF000008B501460D +:1035B000302383F311880820FFF754FF002383F39F +:1035C000118808BD064BDB6839B1426818605A6043 +:1035D000136043600420FFF745BF4FF0FF30704792 +:1035E000283800200368984206D01A6802605060AC +:1035F00099611846FFF726BF7047000010B50A4CC6 +:1036000023699A6891420CD85A68816003604260CD +:1036100010609A685860511A99604FF0FF33A361A7 +:1036200010BD1B68891AECE72838002010B4C0E9E7 +:10363000032300235DF8044B4361FFF7DFBF000065 +:10364000036881689A680A449A60426813605A6005 +:1036500000230360024B4FF0FF329A61704700BFB6 +:103660002838002070B5124DEB692A460133EB6112 +:1036700052F8103F934206D09A68013A9A60302679 +:103680002C69A36803B170BDD4E900210A605160C0 +:10369000236083F31188D4E903312046984786F3E9 +:1036A000118861690029EBD02046FFF7A7FFE7E703 +:1036B00028380020054A30B5D369D2E908451B1BDC +:1036C000181945F10001C2E9080130BD2838002071 +:1036D00000207047FEE70000704700004FF0FF3009 +:1036E00070470000BFF34F8F024AD368DB07FCD45A +:1036F000704700BF0020024008B5074B1B7853B944 +:10370000FFF7F0FF054B1A69120641BF044A5A60E1 +:1037100002F188325A6008BD683A00200020024059 +:103720002301674508B5054B1B7833B9FFF7DAFF6E +:10373000034A136943F08003136108BD683A00200F +:10374000002002407F289ABF00F58030C002002090 +:10375000704700004FF40060704700008020704701 +:103760007F2808B50BD8FFF7EDFF00F5006302686E +:10377000013204D104308342F9D1012008BD002078 +:10378000FCE700007F2810B504461CD8FFF7AAFF0D +:10379000FFF7B2FF0D4BF322DA6002221A61FFF746 +:1037A000D1FF58611A6942F040021A614FF400617A +:1037B000FFF798FF00F05AF9FFF7B4FF2046BDE885 +:1037C0001040FFF7CDBF002010BD00BF0020024019 +:1037D0002DE9F84312F00103144606D01F4B40F2C6 +:1037E00003321A600020BDE8F88385181C4A954210 +:1037F00004D91A4A4FF442711160F3E7FFF77CFFD6 +:10380000FFF770FFDFF86880451A4FF00109012CBF +:1038100005EB01060F4603D8FFF784FF0120E2E71E +:103820003B88C8F8109033800020FFF75BFFC8F892 +:103830001000338831F8022B9BB29A420CD0074B10 +:1038400040F21F321A60074B1E60074B1C60074B8B +:103850001F60FFF767FFC6E7023CD8E7643A002025 +:1038600000000408583A0020603A00205C3A00202A +:1038700000200240084908B50B7828B11BB9FFF7B2 +:103880003BFF01230B7008BD002BFCD0BDE80840B6 +:103890000870FFF747BF00BF683A002008B5064828 +:1038A0004FF41F4100F0E4F8BDE808404FF4005128 +:1038B0004FF0805000F0DCB80001002008461146AF +:1038C00000F084BE012000F081BE0000084600F038 +:1038D0009BBE000038B5EFF31185BDBBEFF3058447 +:1038E000C4F308043023C4B183F31188FFF7E2FE68 +:1038F0004C014201121A44EAD06464EB01049300C3 +:10390000A4001B1844EA927441EB0401C900D800DA +:1039100041EA537185F3118838BD83F31188FFF7AD +:10392000C9FE4D014201121A45EAD06565EB010559 +:103930009300AD001B1845EA927541EB0501C900E3 +:10394000D80041EA537184F3118838BDFFF7B2FE05 +:103950004B014401241A43EAD06363EB0103A20044 +:103960009B00121843EA947341EB0301C900D00095 +:1039700041EA527138BD00BF38B5FFF7ABFF114CBB +:10398000114AC00840EA4170A0FB025EC908A0FBD2 +:10399000040C1CEB050CA1FB04404FF000035B4141 +:1039A000A1FB02121CEB040C43EB000011EB0E0117 +:1039B00042F10002411842F10000090941EA007099 +:1039C00038BD00BFCFF753E3A59BC42010B5024418 +:1039D000064BD2B2904200D110BD441C00B253F845 +:1039E000200041F8040BE0B2F4E700BF502800408B +:1039F0000F4B30B51C6A240407D41C6A44F440748D +:103A00001C621C6A44F400441C620A4C236843F4A0 +:103A1000807323600244084BD2B2904200D130BD83 +:103A2000441C00B251F8045B43F82050E0B2F4E7C4 +:103A300000100240007000405028004007B50122ED +:103A400001A90020FFF7C2FF019803B05DF804FB55 +:103A500013B50446FFF7F2FFA04205D0012201A9E9 +:103A600000200194FFF7C4FF02B010BD70470000B2 +:103A70007047000070470000074B45F255521A602E +:103A800002225A6040F6FF729A604CF6CC421A60ED +:103A9000024B01221A70704700300040703A00203B +:103AA000034B1B781BB1034B4AF6AA221A607047DE +:103AB000703A002000300040044B1A682AB902F125 +:103AC000804202F50432526A1A6070476C3A002054 +:103AD000024B4FF080725A62704700BF00100240E4 +:103AE00008B5FFF7E9FF024B1868C0F3407008BD46 +:103AF0006C3A002070470000FEE700000A4B0B48BC +:103B00000B4A90420BD30B4BDA1C121AC11E22F047 +:103B100003028B4238BF00220021FDF785BA53F81B +:103B2000041B40F8041BECE71C490008543C00202F +:103B3000543C0020543C0020FEE7000070B51B4BB5 +:103B400001630025044686B0586085620E46FFF783 +:103B5000D3FB04F11003C4E904334FF0FF33A36136 +:103B6000134BE561D969A5600A462B46C4E90823D1 +:103B700004F13401C4E900440E4AE562256580235E +:103B80002046FFF7D5FC0123E0600B4A0375009245 +:103B900072680192B268CDE90223084B6846CDE90C +:103BA0000435FFF7EDFC06B070BD00BF503A0020B1 +:103BB00028380020C0470008C5470008393B0008E6 +:103BC0004B6843608B688360CB68C3600B6943615B +:103BD0004B6903628B6943620B68036070470000A6 +:103BE00008B51B4B9A6A42F4FC029A629A6A22F464 +:103BF000FC029A629A6A5A6942F4FC025A61154AB6 +:103C00005B6911464FF09040FFF7DAFF02F11C01AB +:103C100000F58060FFF7D4FF02F1380100F5806005 +:103C2000FFF7CEFF02F1540100F58060FFF7C8FFF7 +:103C300002F1700100F58060FFF7C2FF02F18C0114 +:103C400000F58060FFF7BCFFBDE8084000F05AB8FF +:103C500000100240CC47000808B500F093F9FFF7C8 +:103C60003FFCBDE80840FFF727BF00007047000099 +:103C700010B5214CA36A63F4FC03A362A36A03F4A6 +:103C8000FC03A3624FF0FF32A36A23692261236918 +:103C9000002323612169E168E260E268E360E26891 +:103CA000E269164942F08052E261E2690A6842F430 +:103CB00080720A60226A02F44072B2F5407F1EBF31 +:103CC0004FF4803222622362236A1B0407D4236AE2 +:103CD00043F440732362236A43F40043236200F0F9 +:103CE00031F9A369064A43F00103A361A36913688C +:103CF00043F02003136010BD00100240007000402C +:103D0000000001401E4B1A6842F001021A601A6856 +:103D10009007FCD55A6822F003025A605A6812F0E4 +:103D20000C02FBD1196801F0F90119605A601A6898 +:103D300042F480321A601A689103FCD5114A5A6025 +:103D40004FF40452DA6230221A631A6842F0807229 +:103D50001A601A689201FCD50B4912220A600A689F +:103D600002F00702022AFAD15A6842F002025A60AF +:103D70005A6802F00C02082AFAD11A6B1A637047CB +:103D80000010024000241D0000200240084A08B52F +:103D9000516913680B4003F00103536123B1054AD5 +:103DA00013680BB150689847BDE80840FFF7C8BAE0 +:103DB00000040140743A0020084A08B551691368AC +:103DC0000B4003F00203536123B1054A93680BB122 +:103DD000D0689847BDE80840FFF7B2BA0004014038 +:103DE000743A0020084A08B5516913680B4003F083 +:103DF0000403536123B1054A13690BB15069984715 +:103E0000BDE80840FFF79CBA00040140743A002066 +:103E1000084A08B5516913680B4003F00803536161 +:103E200023B1054A93690BB1D0699847BDE80840B2 +:103E3000FFF786BA00040140743A0020084A08B52A +:103E4000516913680B4003F01003536123B1054A15 +:103E5000136A0BB1506A9847BDE80840FFF770BA83 +:103E600000040140743A0020174B10B55A691C68D1 +:103E7000144004F478725A61A30604D5134A936A75 +:103E80000BB1D06A9847600604D5104A136B0BB18A +:103E9000506B9847210604D50C4A936B0BB1D06B3D +:103EA0009847E20504D5094A136C0BB1506C98474A +:103EB000A30504D5054A936C0BB1D06C9847BDE8B7 +:103EC0001040FFF73DBA00BF00040140743A0020E3 +:103ED0001A4B10B55A691C68144004F47C425A61AC +:103EE000620504D5164A136D0BB1506D9847230532 +:103EF00004D5134A936D0BB1D06D9847E00404D5F7 +:103F00000F4A136E0BB1506E9847A10404D50C4AAA +:103F1000936E0BB1D06E9847620404D5084A136FB4 +:103F20000BB1506F9847230404D5054A936F0BB12A +:103F3000D06F9847BDE81040FFF702BA0004014077 +:103F4000743A0020062108B50846FFF723FA062137 +:103F50000720FFF71FFA06210820FFF71BFA0621AA +:103F60000920FFF717FA06210A20FFF713FA0621A6 +:103F70001720FFF70FFABDE8084006212820FFF7B9 +:103F800009BA000008B5FFF773FE00F067F800F00B +:103F90003DF8FFF76BFEBDE8084000F05DB800009B +:103FA000026843681143016003B11847704700007D +:103FB000143000F02FBA00004FF0FF33143000F03F +:103FC00029BA0000383000F0A5BA00004FF0FF33E6 +:103FD000383000F09FBA0000143000F0F5B900004E +:103FE0004FF0FF31143000F0EFB90000383000F02E +:103FF0004FBA00004FF0FF32383000F049BA0000ED +:10400000012914BF6FF013000020704700F06CB856 +:10401000044B03600023C0E90233436001230374AF +:10402000704700BF7448000838B5C36904460D46A0 +:104030001BB904210844FFF7B3FF294604F114001B +:1040400000F0A6F9002806DA201D4FF40061BDE853 +:104050003840FFF7A5BF38BD00F00EB80023054A71 +:1040600019460133102BC2E9001102F10802F8D100 +:10407000704700BF743A00204FF0E023044A5A61B1 +:1040800000229A6107221A6108210B20FFF798B9D4 +:104090003F19010008B5302383F31188FFF746FA72 +:1040A000002383F3118808BD08B5FFF7F3FFBDE8CF +:1040B0000840FFF745B900000268436811430160FA +:1040C00003B1184770470000024A136843F0C00369 +:1040D0001360704700380140024A136843F0C00380 +:1040E000136070470044004037B51D4C1D4D2046FD +:1040F000FFF78EFF009404F114001B4900232022D7 +:1041000000F038F92022009404F13800174B1849C8 +:1041100000F0B2F9174BC4E91735174C0C212520D4 +:10412000FFF738F92046FFF773FF04F11400134935 +:1041300000940023202200F01DF904F13800104BF8 +:1041400010490094202200F097F90F4B0C212620F3 +:10415000C4E9173503B0BDE83040FFF71BB900BF15 +:10416000F43A002000512502CC3B0020C940000851 +:104170000C3C002000380140603B0020EC3B00205C +:10418000D94000082C3C0020004400402DE9F047B5 +:10419000C66D3768F46934622107054619D014F0FA +:1041A000080118BF4FF48071E20748BF41F02001B9 +:1041B000A30748BF41F04001600748BF41F08001BC +:1041C000302383F31188281DFFF776FF002383F344 +:1041D0001188E2050AD5302383F311884FF48061FA +:1041E000281DFFF769FF002383F311884FF0300982 +:1041F0004FF0000A14F0200838D13B0616D54FF0D6 +:10420000300905F1380A200610D589F31188504687 +:1042100000F066F9002836DA0821281DFFF74CFF68 +:1042200027F080033360002383F31188790614D5C7 +:10423000620612D5302383F31188D5E913239A42FD +:1042400008D12B6C33B11021281D27F04007FFF750 +:1042500033FF3760002383F31188E30619D5AA6E74 +:104260001369B3B1BDE8F0475069184789F3118865 +:10427000B38C95F8641028461940FFF7D5FE8AF3F1 +:104280001188F469B6E780B2308588F31188F46943 +:10429000B9E7BDE8F087000008B50348FFF776FFEF +:1042A000BDE80840FFF74CB8F43A002008B50348D1 +:1042B000FFF76CFFBDE80840FFF742B8603B002005 +:1042C000F8B5154682680669AA420B46816938BF6F +:1042D0008568761AB54204460BD218462A46FCF782 +:1042E00091FEA3692B44A361A3685B1BA3602846CE +:1042F000F8BD0CD918463246FCF784FEAF1BE168C6 +:104300003A463044FCF77EFEE3683B44EBE7184650 +:104310002A46FCF777FEE368E5E7000083689342EE +:10432000F7B51546044638BF8568D0E90460361AEB +:10433000B5420BD22A46FCF765FE63692B446361E4 +:10434000A36828465B1BA36003B0F0BD0DD93246BD +:104350000191FCF757FE0199E068AF1B3A463144E2 +:10436000FCF750FEE3683B44E9E72A46FCF74AFEC7 +:10437000E368E4E710B50A440024C361029B84604B +:10438000C0E90000C0E90511C1600261036210BD0F +:1043900008B5D0E90532934201D1826882B98268BA +:1043A000013282605A1C42611970D0E904329A428B +:1043B00024BFC36843610021FFF714F9002008BD42 +:1043C0004FF0FF30FBE7000070B5302304460E4687 +:1043D00083F31188A568A5B1A368A269013BA36016 +:1043E000531CA36115782269934224BFE368A3613B +:1043F000E3690BB120469847002383F311882846D0 +:1044000007E031462046FFF7DDF80028E2DA85F3C1 +:10441000118870BD2DE9F74F04460E4617469846A1 +:10442000D0F81C904FF0300A8AF311884FF0000B3F +:10443000154665B12A4631462046FFF741FF03463F +:1044400060B941462046FFF7BDF80028F1D00023AF +:1044500083F31188781B03B0BDE8F08FB9F1000F2A +:1044600003D001902046C847019B8BF31188ED1AB9 +:104470001E448AF31188DCE7C0E90511C160C361FD +:104480001144009B8260C0E9000001610362704733 +:10449000F8B504460D461646302383F31188A76805 +:1044A000A7B1A368013BA36063695A1C62611D70D8 +:1044B000D4E904329A4224BFE3686361E3690BB133 +:1044C00020469847002080F3118807E031462046B7 +:1044D000FFF778F80028E2DA87F31188F8BD0000CA +:1044E000D0E905239A4210B501D182687AB9826871 +:1044F000013282605A1C82611C7803699A4224BF8F +:10450000C36883610021FFF76DF8204610BD4FF0AE +:10451000FF30FBE72DE9F74F04460E461746984655 +:10452000D0F81C904FF0300A8AF311884FF0000B3E +:10453000154665B12A4631462046FFF7EFFE034691 +:1045400060B941462046FFF73DF80028F1D000232E +:1045500083F31188781B03B0BDE8F08FB9F1000F29 +:1045600003D001902046C847019B8BF31188ED1AB8 +:104570001E448AF31188DCE70B460146184600F01A +:104580002DB8000000F040B8012838BF012010B558 +:104590000446204600F030F830B900F007F808B9BA +:1045A00000F00CF88047F4E710BD0000024B1868DB +:1045B000BFF35B8F704700BF4C3C002008B506205E +:1045C00000F084F80120FFF785F80000024B0A464E +:1045D00001461868FFF772B91811002010B5054C94 +:1045E00013462CB10A4601460220AFF3008010BDED +:1045F0002046FCE700000000024B01461868FFF768 +:1046000061B900BF18110020024B01461868FFF77E +:104610005DB900BF1811002010B501390244904265 +:1046200001D1002005E0037811F8014FA34201D029 +:10463000181B10BD0130F2E72DE9F041A3B1C91AF2 +:1046400017780144044603F1FF3C8C42204601D90F +:10465000002009E00578BD4204F10104F5D10CEB1E +:104660000405D618A54201D1BDE8F08115F8018DE9 +:1046700016F801EDF045F5D0E7E700001F2938B541 +:1046800004460D4604D9162303604FF0FF3038BDB1 +:10469000426C12B152F821304BB9204600F030F88C +:1046A0002A4601462046BDE8384000F017B8012BE5 +:1046B0000AD0591C03D1162303600120E7E7002428 +:1046C00042F82540284698470020E0E7024B014683 +:1046D0001868FFF7D3BF00BF1811002038B5074D89 +:1046E00000230446084611462B60FEF7F7FF431CE3 +:1046F00002D12B6803B1236038BD00BF503C0020BD +:10470000FEF7E6BF034611F8012B03F8012B002A40 +:10471000F9D170476F72672E6172647570696C6F42 +:10472000742E663330332D556E6976657273616C05 +:104730000000000040A2E4F1646891060041A3E596 +:10474000F2656992070000004261642043414E49CE +:104750006661636520696E6465782E0080000000E4 +:104760000080000000008000000000000000000049 +:10477000111800082D200008891F00085118000892 +:104780005D1800085D1A000821180008311800089B +:10479000251800082D18000829180008811900089C +:1047A00035180008FD2200084518000855190008B2 +:1047B00063300000B047000880380020503A0020E5 +:1047C0006D61696E0069646C65000000A001A82A33 +:1047D00000000000FAAABEAA50001424EFFF000057 +:1047E0000077000070970900010000000000000041 +:1047F000AAAAAAAA01000000FFFF00000000000012 +:10480000000000000000000000000000AAAAAAAA00 +:1048100000000000FFFF000000000000000000009A +:104820000000000000000000AAAAAAAA00000000E0 +:10483000FFFF00000000000000000000000000007A +:1048400000000000AAAAAAAA00000000FFFF0000C2 +:104850000000000000000000000000000000000058 +:10486000AAAAAAAA00000000FFFF000000000000A2 +:104870000000000000000000CD3F0008B93F000824 +:10488000F53F0008E13F0008ED3F0008D93F000870 +:10489000C53F0008B13F00080140000800000000CB +:1048A000EC0300000000000000980300000000007E +:1048B000FE2A0100D20400001C11002000000000AC +:1048C00000000000000000000000000000000000E8 +:1048D00000000000000000000000000000000000D8 +:1048E00000000000000000000000000000000000C8 +:1048F00000000000000000000000000000000000B8 +:1049000000000000000000000000000000000000A7 +:0C4910000000000000000000000000009B :00000001FF diff --git a/Tools/bootloaders/f405-MatekAirspeed_bl.bin b/Tools/bootloaders/f405-MatekAirspeed_bl.bin index 75eac16a24a4ac..48b53f5f02a569 100755 Binary files a/Tools/bootloaders/f405-MatekAirspeed_bl.bin and b/Tools/bootloaders/f405-MatekAirspeed_bl.bin differ diff --git a/Tools/bootloaders/f405-MatekAirspeed_bl.hex b/Tools/bootloaders/f405-MatekAirspeed_bl.hex index 989d82a4d68cb8..929f367d44a551 100644 --- a/Tools/bootloaders/f405-MatekAirspeed_bl.hex +++ b/Tools/bootloaders/f405-MatekAirspeed_bl.hex @@ -1,1741 +1,1691 @@ :020000040800F2 -:1000000000070020F5040008A92E0008612E000852 -:10001000892E0008612E0008812E0008F7040008D0 -:10002000F7040008F7040008F70400089D3E0008E4 -:10003000F7040008F7040008F7040008F7040008B4 -:10004000F7040008F7040008F7040008F7040008A4 -:10005000F7040008F70400086D64000895640008C0 -:10006000BD640008E56400080D650008F704000899 -:10007000F7040008F7040008F7040008F704000874 -:10008000F7040008F7040008F7040008152E00081C -:10009000412E0008512E0008F704000835650008BD -:1000A000F7040008F7040008F7040008F704000844 -:1000B00009660008F7040008F7040008F7040008C0 -:1000C000F7040008F7040008F7040008F704000824 -:1000D000F7040008F7040008F7040008F704000814 -:1000E00099650008F7040008F7040008F704000801 -:1000F000F7040008F7040008F7040008F7040008F4 -:10010000F7040008F7040008F7040008F7040008E3 -:10011000F7040008F7040008F7040008F7040008D3 -:10012000F7040008F7040008F7040008F7040008C3 -:10013000F7040008F7040008F7040008F7040008B3 -:10014000F7040008F7040008F7040008615A0008E3 -:10015000F7040008F7040008F7040008F704000893 -:10016000F7040008F7040008F7040008F704000883 -:10017000F7040008F7040008F7040008F704000873 -:10018000F7040008F7040008F7040008F704000863 -:10019000F7040008F7040008F7040008F704000853 -:1001A000F7040008F7040008F7040008F704000843 -:1001B000F7040008F7040008F7040008F704000833 -:1001C000F7040008F7040008F7040008F704000823 -:1001D000F7040008F7040008F7040008F704000813 -:1001E0005D18000800000000000000000000000092 -:1001F00053B94AB9002908BF00281CBF4FF0FF318E -:100200004FF0FF3000F074B9ADF1080C6DE904CE89 -:1002100000F006F8DDF804E0DDE9022304B07047E1 -:100220002DE9F047089D04468E46002B4DD18A42A9 -:10023000944669D9B2FA82F252B101FA02F3C2F1DC -:10024000200120FA01F10CFA02FC41EA030E94406D -:100250004FEA1C48210CBEFBF8F61FFA8CF708FB8E -:1002600016E341EA034306FB07F199420AD91CEB66 -:10027000030306F1FF3080F01F81994240F21C8198 -:10028000023E63445B1AA4B2B3FBF8F008FB1033E0 -:1002900044EA034400FB07F7A7420AD91CEB040415 -:1002A00000F1FF3380F00A81A74240F207816444E5 -:1002B000023840EA0640E41B00261DB1D44000236A -:1002C000C5E900433146BDE8F0878B4209D9002DCE -:1002D00000F0EF800026C5E9000130463146BDE858 -:1002E000F087B3FA83F6002E4AD18B4202D38242C2 -:1002F00000F2F980841A61EB030301209E46002D71 -:10030000E0D0C5E9004EDDE702B9FFDEB2FA82F2C5 -:10031000002A40F09280A1EB0C014FEA1C471FFA23 -:100320008CFE0126200CB1FBF7F307FB131140EA0A -:1003300001410EFB03F0884208D91CEB010103F1D7 -:10034000FF3802D2884200F2CB804346091AA4B299 -:10035000B1FBF7F007FB101144EA01440EFB00FE6D -:10036000A64508D91CEB040400F1FF3102D2A645D2 -:1003700000F2BB800846A4EB0E0440EA03409CE771 -:10038000C6F12007B34022FA07FC4CEA030C20FA1E -:1003900007F401FA06F31C43F9404FEA1C4900FA3E -:1003A00006F3B1FBF9F8200C1FFA8CFE09FB1811BB -:1003B00040EA014108FB0EF0884202FA06F20BD92E -:1003C0001CEB010108F1FF3A80F08880884240F27E -:1003D0008580A8F102086144091AA4B2B1FBF9F0C2 -:1003E00009FB101144EA014100FB0EFE8E4508D9BD -:1003F0001CEB010100F1FF346CD28E456AD9023842 -:10040000614440EA0840A0FB0294A1EB0E01A14226 -:10041000C846A64656D353D05DB1B3EB080261EB94 -:100420000E0101FA07F722FA06F3F1401F43C5E96E -:10043000007100263146BDE8F087C2F12003D840A4 -:100440000CFA02FC21FA03F3914001434FEA1C47E6 -:100450001FFA8CFEB3FBF7F007FB10360B0C43EAD8 -:10046000064300FB0EF69E4204FA02F408D91CEB88 -:10047000030300F1FF382FD29E422DD90238634486 -:100480009B1B89B2B3FBF7F607FB163341EA034126 -:1004900006FB0EF38B4208D91CEB010106F1FF3875 -:1004A00016D28B4214D9023E6144C91A46EA00466C -:1004B00038E72E46284605E70646E3E61846F8E6FE -:1004C0004B45A9D2B9EB020864EB0C0E0138A3E747 -:1004D0004646EAE7204694E74046D1E7D0467BE728 -:1004E000023B614432E7304609E76444023842E7A0 -:1004F000704700BF02E000F000F8FEE772B6374830 -:1005000080F30888364880F3098836483649086001 -:1005100040F20000CCF200004EF63471CEF2000141 -:100520000860BFF34F8FBFF36F8F40F20000C0F23F -:10053000F0004EF68851CEF200010860BFF34F8FF5 -:10054000BFF36F8F4FF00000E1EE100A4EF63C71E2 -:10055000CEF200010860062080F31488BFF36F8F8D -:1005600004F046FF05F02AFE4FF055301F491B4AA4 -:1005700091423CBF41F8040BFAE71D49184A9142E9 -:100580003CBF41F8040BFAE71A491B4A1B4B9A423D -:100590003EBF51F8040B42F8040BF8E7002018495D -:1005A000184A91423CBF41F8040BFAE704F024FFDB -:1005B00005F058FE144C154DAC4203DA54F8041BF8 -:1005C0008847F9E700F042F8114C124DAC4203DACB -:1005D00054F8041B8847F9E704F00CBF000700201B -:1005E000002300200000000808ED00E000010020CA -:1005F00000070020F86B000800230020B023002033 -:10060000B023002048560020E0010008E401000863 -:10061000E4010008E40100082DE9F04F2DED108AF7 -:10062000C1F80CD0C3689D46BDEC108ABDE8F08FC0 -:10063000002383F311882846A047002004F0E6F940 -:10064000FEE704F03FF900DFFEE70000F8B501F037 -:1006500017F904F067FE074604F0B6FE0546B8BB7E -:10066000204B9F4234D001339F4234D01E4B27F0A1 -:10067000FF029A4232D1F8B200F00EFF2E4642F24B -:10068000107400F00FFF08B10024264601F0FAFCB8 -:1006900020B1032000F07CF80024264635B1134B2E -:1006A0009F4203D004F088FE00242646002004F078 -:1006B00043FE0EB100F082F801F094FA00F05EFF04 -:1006C00001F044F9204600F0D5F800F077F8F9E79A -:1006D0002E460024D5E704460126D2E7064641F21D -:1006E0008834CEE7010007B0000008B0263A09B010 -:1006F00008B501F0FDF8A0F120035842584108BDAB -:1007000007B541F21203022101A8ADF8043001F04F -:100710000DF903B05DF804FB38B5302383F311887D -:10072000174803680BB104F03DFA164A1448002339 -:100730004FF47A7104F02CFA002383F31188124CE1 -:10074000236813B12368013B2360636813B16368B6 -:10075000013B63600D4D2B7833B963687BB9022090 -:1007600001F0BAF9322363602B78032B07D1636859 -:100770002BB9022001F0B0F94FF47A73636038BDF1 -:10078000B023002019070008D0240020C82300202F -:10079000084B187003280CD8DFE800F008050208A1 -:1007A000022001F08FB9022001F082B9024B002231 -:1007B0005A607047C8230020D024002010B501F0F3 -:1007C00061FC30B1244B03221A70244B00225A6082 -:1007D00010BD234B234A1C4619680131F8D004335D -:1007E0009342F9D16268204B9A42F1D91F4B9B6822 -:1007F00003F1006303F580339A42E9D204F0B0FDBF -:1008000004F0C2FD002001F0BBF80220FFF7C0FF9A -:10081000174B1A6C00221A64196E1A66196E596CFD -:100820005A64596E5A665A6E1A6942F000521A6139 -:100830001A6922F000521A611B6972B64FF0E02368 -:100840003021C3F8084DD4E9003281F311889D4668 -:1008500083F308881047BBE7C8230020D02400207A -:100860000000010820000108FFFF0008002300200D -:10087000003802402DE9F04F93B0AC4B009020229D -:10088000FF210AA89D6801F057F9A94A1378A3B976 -:10089000A848012103601170302383F31188036895 -:1008A0000BB104F07FF9A44AA24800234FF47A71F7 -:1008B00004F06EF9002383F31188009B13B19F4B62 -:1008C000009A1A609E4A009C1378032B1EBF0023D7 -:1008D00013709A4A4FF0000A18BF5360D346564629 -:1008E000D146012001F0EEF824B1944B1B68002B97 -:1008F00000F01582002000F0FBFF0390039B002B0B -:1009000001DA00F083FE039B002BEDDB012001F0F8 -:10091000CFF8039B213B162BE3D801A252F823F01A -:100920007D090008A5090008390A0008E308000845 -:10093000E3080008E3080008C30A0008930C000855 -:10094000AD0B00080F0C0008370C00085D0C000808 -:10095000E30800086F0C0008E3080008E10C000839 -:100960001D0A0008E3080008250D00088909000891 -:100970001D0A0008E30800080F0C00080220FFF71A -:10098000B7FE002840F0F581009B0221BAF1000F6C -:1009900008BF1C4605A841F21233ADF8143000F030 -:1009A000C5FF9EE74FF47A7000F0A2FF071EEBDB55 -:1009B0000220FFF79DFE0028E6D0013F052F00F240 -:1009C000DA81DFE807F0030A0D10133605230593DB -:1009D000042105A800F0AAFF17E054480421F9E714 -:1009E00058480421F6E758480421F3E74FF01C0863 -:1009F000404600F0C7FF08F104080590042105A84F -:100A000000F094FFB8F12C0FF2D1012000FA07F7A3 -:100A100047EA0B0B5FFA8BFB4FF0000901F0D8F8A7 -:100A200026B10BF00B030B2B08BF0024FFF768FE69 -:100A300057E746480421CDE7002EA5D00BF00B0365 -:100A40000B2BA1D10220FFF753FE074600289BD0B5 -:100A5000012000F095FF0220FFF79AFE00261FFA02 -:100A600086F8404600F09CFF044690B100214046C5 -:100A700000F0AEFF01360028F1D1BA46044641F23B -:100A80001213022105A8ADF814303E4600F04EFFC7 -:100A900027E70120FFF77CFE2546244B9B68AB42ED -:100AA00007D9284600F06EFF013040F06781043519 -:100AB000F3E7234B00251D70204BBA465D603E4690 -:100AC000ACE7002E3FF460AF0BF00B030B2B7FF471 -:100AD0005BAF0220FFF75CFE322000F009FFB0F1AF -:100AE0000008FFF651AF18F003077FF44DAF0F4A2F -:100AF000926808EB050393423FF646AFB8F5807F56 -:100B00003FF742AF124B0193B84523DD4FF47A70A3 -:100B100000F0EEFE0390039A002AFFF635AF019B2A -:100B2000039A03F8012B0137EDE700BF00230020F3 -:100B3000CC240020B023002019070008D024002076 -:100B4000C823002004230020082300200C230020B9 -:100B5000CC230020C820FFF7CBFD074600283FF438 -:100B600013AF1F2D11D8C5F1200242450AAB25F065 -:100B7000030028BF424683490192184400F0B6FFA3 -:100B8000019A8048FF2100F0D7FF4FEAA8037D4972 -:100B90000193C8F38702284600F0D6FF06460028D6 -:100BA0003FF46DAF019B05EB830537E70220FFF7AC -:100BB0009FFD00283FF4E8AE00F02AFF00283FF434 -:100BC000E3AE0027B846704B9B68BB4218D91F2F75 -:100BD00011D80A9B01330ED027F0030312AA134445 -:100BE00053F8203C05934046042205A901F002FA7F -:100BF00004378046E7E7384600F0C4FE0590F2E788 -:100C0000CDF81480042105A800F090FE06E700232B -:100C1000642104A8049300F07FFE00287FF4B4AEA2 -:100C20000220FFF765FD00283FF4AEAE049800F007 -:100C3000D7FE0590E6E70023642104A8049300F0A2 -:100C40006BFE00287FF4A0AE0220FFF751FD0028C4 -:100C50003FF49AAE049800F0D3FEEAE70220FFF7D3 -:100C600047FD00283FF490AE00F0E2FEE1E70220ED -:100C7000FFF73EFD00283FF487AE05A9142000F0E1 -:100C8000DDFE04210746049004A800F04FFE39461B -:100C9000B9E7322000F02CFE071EFFF675AEBB0749 -:100CA0007FF472AE384A926807EB090393423FF62D -:100CB0006BAE0220FFF71CFD00283FF465AE27F065 -:100CC00003074F44B9453FF4A9AE484600F05AFE29 -:100CD0000421059005A800F029FE09F10409F1E7B7 -:100CE0004FF47A70FFF704FD00283FF44DAE00F09A -:100CF0008FFE002844D00A9B01330BD008220AA99A -:100D0000002000F021FF00283AD02022FF210AA86D -:100D100000F012FFFFF7F4FC1C4803F07DFE13B057 -:100D2000BDE8F08F002E3FF42FAE0BF00B030B2B22 -:100D30007FF42AAE0023642105A8059300F0ECFDA2 -:100D4000074600287FF420AE0220FFF7D1FC804642 -:100D500000283FF419AEFFF7D3FC41F2883003F0CE -:100D60005BFE059800F066FF464600F031FF3C460A -:100D7000B7E5064652E64FF0000905E6BA467EE6BC -:100D800037467CE6CC23002000230020A08601000B -:100D9000094A136849F2690099B21B0C00FB013340 -:100DA0001360064B186844F2506182B2000C01FBDC -:100DB0000200186080B2704718230020142300201E -:100DC00010B500211022044600F0B6FE034B03CB01 -:100DD000206061601868A06010BD00BF107AFF1F1E -:100DE0002DE9F041ADF5507D0DF13C086EAC40F2BF -:100DF000751207460D4610A80021C8F8001000F033 -:100E00009BFE4FF4C4720021204600F095FE02F0D4 -:100E100053F8254B4FF47A72B0FBF2F0186093E868 -:100E20000700022384E807000DF5ED702382FFF729 -:100E3000C7FF4FF203631D49238406A805F0F4FCA5 -:100E4000202384F832310DF2EB2606AB0DF1380C7D -:100E50001A4603CA624530607160134606F10806FF -:100E6000F6D141460122204600F0E6FE002303931E -:100E7000AB7E029305F11903019380B20123CDE902 -:100E800004800093E97E06A3D3E90023384602F0EC -:100E9000DBFB0DF5507DBDE8F08100BFAFF30080B6 -:100EA0009E6AC421818A46EED82400203868000852 -:100EB0002DE9F0412C4C237ADAB080460D465BBB1D -:100EC00027A9284600F0C8FF0746002842D19DF810 -:100ED0009D60C82E3ED801464FF4A662204600F021 -:100EE0002BFE4FF48073C4F8F8314FF40073C4F84C -:100EF0000C334FF44073C4F8203432460DF19E0198 -:100F000004F1090000F0F2FD26449DF89C30777250 -:100F100023720BB9EB7E23728122002106AC27A835 -:100F200000F00AFE0122214627A800F0D1FF00238D -:100F30000393AB7E029305F1190380B2019328233A -:100F4000CDE904400093E97E05A3D3E900234046A0 -:100F500002F07AFB5AB0BDE8F08100BFAFF3008029 -:100F600026417272DF25D7B7F0450020F0B5254E37 -:100F70004FF48A7505FB0065F1B096F8D83085F816 -:100F8000DC300024D822214685F8E8403AA800F059 -:100F9000D3FD06F1090000F0C7FDD5F8E4308DF867 -:100FA000F000C2B206AF06F109010DF1F100CDE982 -:100FB0003A3400F09BFD394601223AA800F0B4FF14 -:100FC00080B2CDE9047008230127CDE9023706F18C -:100FD000D803019330230093317A0B4807A3D3E958 -:100FE000002302F031FBA04206DD01F065FFC5F8E9 -:100FF000E000384671B0F0BD2046FBE778F6339F3D -:1010000093CACD8DF0450020F03400202DE9F04149 -:101010001D4D1E4E1E4F86B0284602F041FB034672 -:1010200058B30024CDE90344ADF81440027B8DF899 -:10103000142099684068029403AA03C21B68DFF871 -:10104000548043F00043029301F038FF821941F1CC -:101050000003009402A9384601F0FAF9A04205DD28 -:10106000284602F021FB88F80040D5E798F80030C8 -:10107000072B05D8013388F8003006B0BDE8F081B1 -:10108000014802F011FBF8E7F034002040420F0065 -:1010900020350020254B002070B50D4614461E4615 -:1010A00002F02EFA50B9022E10D1012C0ED112A34B -:1010B000D3E90023C5E90023012007E0282C10D044 -:1010C00005D8012C09D0052C0FD0002070BD302C84 -:1010D000FBD10BA3D3E90023ECE70BA3D3E9002357 -:1010E000E8E70BA3D3E90023E4E70BA3D3E900234C -:1010F000E0E700BFAFF30080401DA12026812A0B4E -:1011000078F6339F93CACD8D9E6AC421818A46EEBC -:1011100026417272DF25D7B7F017304A39059E563F -:1011200038B505460E4C0021013500F051FCA4F8FD -:101130002C55B4F82C0500F033FC78B1B4F82C052C -:1011400000F03EFC014648B9B4F82C0500F040FC24 -:10115000B4F82C350133A4F82C35EAE738BD00BFCC -:10116000F045002010B50A4B0A4A1A6003F5805377 -:1011700093F860203AB9DC6D2CB1204601F000F8FC -:10118000204605F091FABDE81040034800F0F8BF92 -:1011900020350020F8680008684500202DE9F04F50 -:1011A0008FB000AF05460C4602F0AAF9002849D1DD -:1011B000237E022B1BD1E38A012B18D101F07CFE88 -:1011C0000646FFF7E5FD03464FF4C870DFF8C4821A -:1011D000B3FBF0F206F5167602FB103316FA83F332 -:1011E000C8F80030E37E33B9A34B00221A703C37B5 -:1011F000BD46BDE8F08F07F12401204600F0EAFD6E -:101200000028F4D107F11400FFF7DAFD97F8264023 -:1012100007F11401224607F1270005F08FFA002894 -:10122000E2D10F2C08D8944B1C70D8F80030A3F5ED -:101230001673C8F80030DAE797F82410284602F051 -:1012400057F9D4E7E38A282B2BD010D8012B23D0D1 -:10125000052BCCD1BFF34F8F8849894BCA6802F464 -:10126000E0621343CB60BFF34F8F00BFFDE7302B2D -:10127000BDD1844EE17E327A9142B8D1607E314652 -:10128000002291F8DC50854200F0A5800132042A4A -:1012900001F58A71F5D1AAE721462846FFF7A0FD9E -:1012A000A5E721462846FFF703FEA0E7B2F8EC5079 -:1012B0007B6005F103094FEA99094FEA8902D11DC4 -:1012C000C908A8EBC1039D46EB460021584600F033 -:1012D00033FC04F1EE012A463144584600F006FC86 -:1012E0007B6813B9012000F04BFB96F8D20000F0A8 -:1012F00057FB044630B9307200F08AFB204600F0FC -:101300003FFBB1E0D6F8D4203AB996F8D200B6F84F -:101310002C25824201D8FFF703FFD6F8D4202A44B7 -:10132000944208D296F8D200B6F82C2501308242B9 -:1013300001D8FFF7F5FE70685FFA89F2594600F0B0 -:1013400003FC08B9C54679E0726896F8D2002A44D1 -:101350007260D6F8D42005EB0209C6F8D49000F0EC -:101360001FFB814509D396F8D220D6F8D40001326C -:10137000001B86F8D220C6F8D400FF2D0FD8002419 -:10138000347200F045FB204600F0FAFA00F07AFED5 -:101390003D4B188108B9FFF711FAC54627E7BB682E -:1013A00096F8D9000AFB0362FB68D2F8E41082F8D1 -:1013B000E83001F58061C2F8E030C2F8E410FFF7D0 -:1013C000D5FDFFF723FE96F8D920013202F0030283 -:1013D00086F8D920B6E74FF48A7A0AFB02F505F1C0 -:1013E000EA013144204600F0CBFDF86000287FF48C -:1013F000FEAE3544012285F8E82001F05DFDD5F808 -:10140000E020D6ED007ADFED216A801A192838BF76 -:10141000192040F6B832904228BF1046B8EE677ADD -:1014200007EE900AF8EEE77A67EEA67ADFED186A23 -:10143000E7EE267AFCEEE77AC6ED007A96F8D93028 -:10144000BB60BA6873680AFB02F4321992F8E810BC -:1014500059B1D2F8E4108B42E8463FF427AF00219F -:1014600082F8E810C2F8E010C5467368064A9B0A85 -:1014700001331381BBE600BFE934002000ED00E03A -:101480000400FA05F0450020D8240020CDCCCC3D46 -:101490006666663FEC340020014B1870704700BF51 -:1014A000E424002030B54FF000542B4B22689A42C0 -:1014B00085B007D003F092FF044620BB00242046ED -:1014C00005B030BD254B627D25481A70237D03721F -:1014D0004FF48073C0F8F8314FF40073C0F80C3348 -:1014E00000254FF44073C0F820341E49C0F8E45082 -:1014F000C922093000F0FAFA2046E022294600F01D -:101500001BFB0124DBE7184A184D136C43F00073F2 -:101510001364AA6D164B9A42D0D12B6E013B7E2BE1 -:10152000CCD8144A07CA01AB83E807001846032148 -:1015300000F076FD6B6D83424FF00003BED12A6D43 -:101540008A4201BFAB65054B2A6E1A7003BF0A4B76 -:10155000EA6D1A601C46B2E79AAD44C5E424002047 -:10156000F0450020160000200038024000660040D0 -:101570005041A0B0586600401023002037B51A4DE6 -:1015800000F080FD02236B71184B28811968184800 -:10159000012201F02FFB00230193164B1649009303 -:1015A0001648174B4FF4805201F07AFF154B19780B -:1015B00011B1124801F09CFF01F07EFC0446FFF7D8 -:1015C000E7FB4FF4C873B0FBF3F202FB130304F51F -:1015D000167010FA83F00C4B186003F0F5FE08B19A -:1015E0000F232B8103B030BDD8240020102300200E -:1015F0002035002099100008E8240020F034002055 -:101600009D110008E4240020EC3400202DE9F04F67 -:101610002DED028B0FF23829D9E90089834C93B064 -:101620000BAE9FED7E8BFFF7F1FC814FDFF828A218 -:1016300000230A93ADF834300B9373604FF0000B26 -:101640005B468DED008B01250DF11D0207A9384683 -:101650008DF81C508DF81DB001F07CFA9DF81C30FF -:10166000002B40F0A580204601F04AFF06460028E6 -:1016700045D1704F01F020FC3B6898423FD301F008 -:101680001BFC8246FFF784FB4FF4C873B0FBF3F2F8 -:1016900002FB13030AF5167010FA83F03860664FE8 -:1016A00097F800B0CBF1100ABBF1000F14BF33461E -:1016B0002B465FFA8AFA0EA88DF82830FFF780FBD8 -:1016C000BAF1060F28BF4FF0060A0EAB03EB0B0171 -:1016D00052460DF1290000F009FA0AAB03931823D2 -:1016E00002930AF10102554BD2B2CDE900530492A4 -:1016F00020464CA3D3E9002301F048FF3E7001F0DF -:10170000DBFB4F4A4F4D1368C31AB3F57A7F2ED3D4 -:10171000106001F0D3FB02460B46204601F0CEFFDD -:10172000204601F0EDFE10B32B7A474E002B14BF7C -:1017300003230223737101F0BFFB0EAF4FF47A73E2 -:101740000122B0FBF3F039463060304600F01AFB5E -:10175000182302933D4B019380B240F25513CDE91B -:101760000370009342464B46204601F00FFF2B7A50 -:1017700093B101F0A1FB002607464FF48A7A95F851 -:10178000D900304400F003000AFB005393F8E8202E -:1017900092B30136042EF2D1C82003F03DF92B7A22 -:1017A000002B7FF43DAF13B0BDEC028BBDE8F08F92 -:1017B000DAF8143083F48043CAF814305946102202 -:1017C0000EA800F0B9F90DF11E0308AA0AA93846BF -:1017D00000F03CFF96E803000FAB83E803009DF8A0 -:1017E00034308DF844300A9B0E930EA9DDE90823AE -:1017F000204602F037F921E7D3F8E02042B12B6808 -:10180000FA2B38BFFA23BA1A0533B2EB430FC0D311 -:10181000FFF7ACFB0028BCD1BEE700BF0000000012 -:1018200000000000401DA12026812A0BF03400207A -:1018300020350020EC340020E9340020E83400207A -:10184000204B0020F0450020D8240020244B00200D -:10185000F1C6A7C1D068080F0000024008B50548CE -:1018600000F08EFFBDE80840034A0449002004F060 -:1018700015BF00BF20350020604B00206511000817 -:101880007047000070B50F4B1B780133DBB2012BA2 -:101890000C4611D80C4D29684FF47A730E6AA2FBDE -:1018A0000332014622462846B047844204D1074B02 -:1018B00000221A70012070BD4FF4FA7003F0ACF8EA -:1018C0000020F8E71C230020D84D0020544B0020B6 -:1018D00070B504464FF47A76412C254628BF412541 -:1018E00006FB05F003F098F8641BF5D170BD00000D -:1018F00007B50023024601210DF107008DF80730DE -:10190000FFF7C0FF20B19DF8070003B05DF804FBAE -:101910004FF0FF30F9E700000A4608B50421FFF751 -:10192000B1FF80F00100C0B2404208BD30B4054CA8 -:101930002368DD69044B0A46AC460146204630BCAC -:10194000604700BFD84D0020A086010070B503F0AD -:1019500083FB094E094D3080002428683388834278 -:1019600008D903F073FB2B6804440133B4F5803FBE -:101970002B60F2D370BD00BF564B0020284B0020D7 -:1019800003F018BC00F1006000F58030006870477B -:1019900000F10060920000F5803003F0A3BB00006E -:1019A000054B1A68054B1B889B1A834202D91044C9 -:1019B00003F04CBB00207047284B0020564B002002 -:1019C000024B1B68184403F049BB00BF284B0020A2 -:1019D000024B1B68184403F059BB00BF284B002082 -:1019E00010F003030AD1B0F5047F05D200F10050D6 -:1019F000A0F51040D0F80038184670470023FBE7E8 -:101A000000F10050A0F51040D0F8100A7047000017 -:101A1000064991F8243033B10023086A81F8243054 -:101A20000822FFF7B5BF0120704700BF2C4B0020F4 -:101A3000014B1868704700BF002004E070B5194BD7 -:101A40001D68194B0138C5F30B0408442D0C042202 -:101A50001E88A6420BD15C680A46013C82421346AE -:101A60000FD214F9016F4EB102F8016BF6E7013A9B -:101A700003F10803ECD181420B4602D22C2203F879 -:101A8000012B0A4A05241688AE4204D1984284BF2D -:101A9000967803F8016B013C02F10402F3D1581A65 -:101AA00070BD00BF002004E09C6800088868000842 -:101AB000022802BF024B4FF080429A61704700BF7C -:101AC00000000240022802BF024B4FF480429A619C -:101AD000704700BF00000240022801BF024A53695C -:101AE00083F48043536170470000024010B5002327 -:101AF000934203D0CC5CC4540133F9E710BD00001D -:101B000010B5013810F9013F3BB191F900409C42FA -:101B100003D11AB10131013AF4E71AB191F9002069 -:101B2000981A10BD1046FCE703460246D01A12F977 -:101B3000011B0029FAD1704702440346934202D0A8 -:101B400003F8011BFAE770472DE9F8431F4D1446CF -:101B500095F824200746884652BBDFF870909CB366 -:101B600095F824302BB92022FF2148462F62FFF739 -:101B7000E3FF95F82400C0F10802A24228BF2246E4 -:101B8000D6B24146920005EB8000FFF7AFFF95F813 -:101B90002430A41B1E44F6B2082E17449044E4B22D -:101BA00085F82460DBD1FFF733FF0028D7D108E0A8 -:101BB0002B6A03EB82038342CFD0FFF729FF002873 -:101BC000CBD10020BDE8F8830120FBE72C4B00209F -:101BD000024B1A78024B1A70704700BF544B00201A -:101BE0001C23002010B5104C104802F045FA214685 -:101BF0000E4802F06DFA2468626DD2F8043843F0A2 -:101C00000203C2F804384FF47A70FFF761FE084906 -:101C1000204602F063FB626DD2F8043823F0020321 -:101C2000C2F8043810BD00BFE4690008D84D002098 -:101C3000EC690008704700002DE9F0470D460446A6 -:101C400000219046284640F27912FFF775FF23469F -:101C500020220021284601F0A7FE231D0222202178 -:101C6000284601F0A1FE631D03222221284601F02F -:101C70009BFEA31D03222521284601F095FE04F1B9 -:101C8000080310222821284601F08EFE04F11003DB -:101C900008223821284601F087FE04F111030822AA -:101CA0004021284601F080FE04F112030822482159 -:101CB000284601F079FE04F1140320225021284621 -:101CC00001F072FE04F1180340227021284601F051 -:101CD0006BFE04F120030822B021284601F064FEC7 -:101CE00004F121030822B821284601F05DFE04F129 -:101CF0002207C0263B46314608222846083601F016 -:101D000053FEB6F5A07F07F10107F3D104F13203CA -:101D100008223146284601F047FE002704F1330A25 -:101D200094F832304FEAC7099F4209F5A47615D3DB -:101D3000B8F1000F08D1314604F5997307222846FF -:101D400001F032FE09F24F16274694F832213B1B70 -:101D500093420CD3F01DC008BDE8F0870AEB0703DF -:101D600008223146284601F01FFE0137D8E707F266 -:101D7000331331460822284601F016FE0836013793 -:101D8000E3E7000013B5044608460021016023463E -:101D9000C0F803102022019001F006FE0198231DD7 -:101DA0000222202101F000FE0198631D032222215E -:101DB00001F0FAFD0198A31D0322252101F0F4FD95 -:101DC000019804F108031022282101F0EDFD0720FD -:101DD00002B010BDF7B50023047F00910E46072224 -:101DE0001946054601F0A4FC731C00930122002350 -:101DF0000721284601F09CFCC4B9B31C00930522BE -:101E000023460821284601F093FC0D243746B2787A -:101E1000BB1B934211D32B7FA88A0734E408BBB9BC -:101E2000844294BF0020012003B0F0BDAB8ADB00E8 -:101E3000083BDB08B3700824E8E7FB1C009321464D -:101E400000230822284601F073FC08340137DEE73E -:101E5000201A18BF0120E7E7F7B50023047F00919F -:101E60000E4608221946054601F062FC731CC4B9EF -:101E70000822009311462346284601F059FC1024FD -:101E8000012372785F1C013B934211D32B7FA88AF8 -:101E90000734E408BBB9844294BF0020012003B09A -:101EA000F0BDAB8ADB00083BDB0873700824E7E772 -:101EB000F3190093214600230822284601F038FC3C -:101EC00008343B46DDE7201A18BF0120E7E7000091 -:101ED000F8B50E4605461446002181223046FFF72C -:101EE0002BFE2B4608220021304601F05DFD7CB917 -:101EF0006B1C07220821304601F056FD0F240123F8 -:101F00006A785F1C013B934204D3E01DC008F8BD12 -:101F10000824F4E7EB1921460822304601F044FD7D -:101F200008343B46ECE70000F8B50E46054614467B -:101F30000021CE223046FFF7FFFD2B46282200214C -:101F4000304601F031FD7CB905F108030822282153 -:101F5000304601F029FD30242F462A7A7B1B93421C -:101F600004D3E01DC008F8BD2824F5E707F10903F4 -:101F700021460822304601F017FD08340137ECE70E -:101F8000F7B5047F00910E4601231022002105467B -:101F900001F0CEFBC4B9B31C0093092223461021E3 -:101FA000284601F0C5FB192437467288BB1B9A42AC -:101FB00011D82B7FA88A0734E408BBB9844294BFA8 -:101FC0000020012003B0F0BDAB8ADB00103BDB0832 -:101FD00073801024E8E73B1D00932146002308226C -:101FE000284601F0A5FB08340137DEE7201A18BFA8 -:101FF0000120E7E730B5094D0A4491420DD011F8B0 -:10200000013B5840082340F30004013B2C4013F0EF -:10201000FF0384EA5000F6D1EFE730BD2083B8ED2E -:10202000F7B54FF0FF33DFF854C0DFF854E000EBB2 -:1020300081011A4688421CD050F8044B019401AF2C -:10204000042417F8015B82EA05620825DB181646AE -:1020500005F1FF355241002EBCBF83EA0C0382EA32 -:102060000E0215F0FF05F1D1013C14F0FF04E8D198 -:10207000E0E7D843D14303B0F0BD00BF9336EAA9EF -:10208000EBE1F042F7B5384A106851686B4603C37C -:102090006A4636493648082304F060FB04460028A7 -:1020A00033D10A25334A106851686B4603C36A4628 -:1020B00031492F48082304F051FB0446002849D039 -:1020C0000369B3F5702F45D8B0F8661040F2F632C8 -:1020D00091423FD1294A024402F15C018B4239D33B -:1020E0005C3B234900209E1AFFF784FF32460746D7 -:1020F00004F164010020FFF77DFFA3689F4229D10E -:10210000E368984208BF002524E00369B3F5702F07 -:1021100027D8418B40F2F632914220D1174A02442F -:1021200002F110018B4218D3103B114900209D1A77 -:10213000FFF760FF2A46064604F118010020FFF76A -:1021400059FFA3689E4202D1E368984201D00D2551 -:10215000A8E70025284603B0F0BD1025A2E70C250E -:10216000A0E70B259EE700BFBC680008DCFF0E005F -:1021700000000108C568000890FF0E000800FFF786 -:1021800010B5037C044613B9006804F0CFFA20466A -:1021900010BD00000023BFF35B8FC360BFF35B8FF4 -:1021A000BFF35B8F8360BFF35B8F7047BFF35B8FC1 -:1021B0000068BFF35B8F704770B505460C30FFF7C2 -:1021C000F5FF05F1080604463046FFF7EFFFA04291 -:1021D00006D930466D68FFF7E9FF2544281A70BD1F -:1021E0003046FFF7E3FF201AF9E7000070B5054617 -:1021F000406898B105F10800FFF7D8FF05F10C061B -:1022000004463046FFF7D2FF8442304694BF6D68E3 -:102210000025FFF7CBFF013C2C44201A70BD0000C5 -:1022200038B50C460546FFF7C7FFA04210D305F1AD -:102230000800FFF7BBFF04446868B4FBF0F100FB43 -:102240001144BFF35B8F0120AC60BFF35B8F38BDDF -:102250000020FCE72DE9F041144607460D46FFF744 -:10226000C5FF844228BF0446D4B1B84658F80C6B69 -:102270004046FFF79BFF3044286040467E68FFF7EA -:1022800095FF331A9C4203D86C600120BDE8F081B1 -:102290006B60A41B3B68AB602044E8600220F5E75C -:1022A0002046F3E738B50C460546FFF79FFFA042EE -:1022B00010D305F10C00FFF779FF04446868B4FB04 -:1022C000F0F100FB1144BFF35B8F0120EC60BFF322 -:1022D0005B8F38BD0020FCE72DE9FF418846694649 -:1022E0000746FFF7B7FF6C4606B204EBC6060025AB -:1022F000B44209D06268206808EB0501FFF7F6FBDD -:10230000636808341D44F3E729463846FFF7CAFFDF -:10231000284604B0BDE8F081F8B505460C300F46FC -:10232000FFF744FF05F1080604463046FFF73EFF7D -:10233000A042304688BF6C68FFF738FF201A38602B -:1023400020B130462C68FFF731FF2044F8BD000073 -:1023500073B5144606460D46FFF72EFF844228BF8C -:1023600004460190DCB101A93046FFF7D5FF019B7F -:1023700033B93268C5E90233C5E9002401200CE015 -:102380009C4238BF01942860019868608442F5D966 -:102390003368AB60241AEC60022002B070BD2046A6 -:1023A000FBE700002DE9FF410F466946FFF7D0FF2C -:1023B0006C4600B204EBC0050026AC4209D0D4F84C -:1023C000048054F8081BB8194246FFF78FFB4644B7 -:1023D000F3E7304604B0BDE8F081000038B50546AB -:1023E000FFF7E0FF044601462846FFF719FF2046A5 -:1023F00038BD0000302383F3118862B670470000B7 -:10240000002383F3118862B67047000010B402689D -:1024100054681A4623465DF8044B1847012070475C -:102420000020704700207047704700000020704770 -:102430000E20704700F5805090F8C800C0F34000AF -:102440007047000000F5805090F9C9007047000007 -:10245000F7B50C68BDF8207014F000541E466FD11B -:102460000B7B082B6CD8FFF7C5FF4569AB685B0198 -:102470000CD4AB681B0108D4AC6814F080545DD157 -:10248000FFF7BEFF204603B0F0BD01240B6804F146 -:10249000180C002BB8BFDB004FEA0C1CB4BF43F094 -:1024A00004035B0545F80C300B680FFA84FC13F04D -:1024B000804F18BF05EB0C1E05EB0C1C1EBFDEF891 -:1024C000803143F00203CEF880310B7BCCF88431AD -:1024D00005EB04158B68C5F88C314B68C5F888315D -:1024E000DCF8803143F00103CCF8803100EB441577 -:1024F00041F268031D4403EB44130344C5E900267D -:1025000008330D4601F10C0C55F804EB43F804EBCD -:102510006545F9D184342D881D8000EB441407F003 -:102520000303257925F00B052B432371FFF768FF83 -:102530000097334600F0E2FC0120A4E70224A5E75F -:102540004FF0FF309FE7000013B500F58054019174 -:10255000E06DFFF74BFE1F280AD90199E06D20229C -:10256000FFF7BAFEA0F120035842584102B010BD57 -:102570000020FBE708B500F58050FFF73BFFC06D7A -:10258000FFF708FEBDE80840FFF73ABF00220260EF -:10259000828142608260704710B500220023C0E94A -:1025A00000230023044603810C30FFF7EFFF204691 -:1025B00010BD0000F0B5054600F580500C4690F8BF -:1025C000C83013F0040FC3F3800108BF114661F354 -:1025D000820304F1840680F8C83005EB461389B005 -:1025E0001B79D8072ED57AB319072DD46846FFF783 -:1025F000D3FF05EB441303F5835303F1180703AA34 -:10260000103318685968144603C40833BB42224685 -:10261000F7D1186820609B88A380DDE90E23CDE9FF -:1026200000230123ADF808302B686946DB6B284690 -:10263000984705EB46152B791A075CBF43F0080352 -:102640002B7101E0002AF4D109B0F0BD2DE9F0476B -:10265000074688B007F5805468469A468846FFF7D3 -:10266000C9FE9146FFF798FFE06DFFF7A5FD1F2813 -:1026700029D9E06D20226946FFF7B0FE202822D13B -:1026800003AD444605AB2E4603CE9E4220606160FA -:10269000354604F10804F6D130682060B388A38081 -:1026A000DDE90023C9E90023BDF80830AAF80030AD -:1026B000FFF7A6FE4A4653464146384608B0BDE8F5 -:1026C000F04700F009BCFFF79BFE002008B0BDE812 -:1026D000F08700002DE9F84F0023C0E90133254BB6 -:1026E000044640F8183B0F46FFF750FF04F128005E -:1026F000FFF752FF04F1480804F5825546460835B5 -:1027000030462036FFF748FFAE42F9D104F5805538 -:102710004FF480534FF00009C5E91339C5F84880DC -:102720000123EE6504F5875804F58456C5F85490E6 -:1027300085F8583085F86030083608F108084FF001 -:10274000000A4FF0000B46E908ABA6F11800FFF7AE -:102750001DFF203646F8289C4645F4D185F8C970FF -:1027600017B1054800F0A2FB044B63612046BDE8A9 -:10277000F88F00BFF8680008D068000800640040C7 -:1027800010B5044B197804464A1C1A70FFF7A2FFD3 -:10279000204610BD5C4B00202DE9F047002950D0A9 -:1027A000294B2A4FB7FBF1F599428CBF0A2311231D -:1027B000581EB5FBF3FC03FB1C53C4B22BB102281B -:1027C0000346F5D80020BDE8F0870CF1FF36B6F5DA -:1027D000806FF7D2C4EBC40E0EF103034FEAE30996 -:1027E000C3F3C703A4EB030809F1010A4FF47A7598 -:1027F0005FFA88F009FB05555AFA88F8B5FBF8F539 -:10280000B5F5617FC1BF0EF1FF33C3F3C703E01A13 -:10281000C0B25C1C50FA84F40CFB04F4B7FBF4F473 -:10282000A142CFD1013BDBB20F2BCBD80138C0B2D4 -:102830000728C7D80021107116809170D37001202D -:10284000C1E70846BFE700BF3F420F0080DE8002BD -:1028500070B505460E464FF47A746B695B6803F0F9 -:102860000103B34207D04FF47A7002F0D5F8013C6F -:10287000F3D1204670BD0120FCE7000030B542696D -:10288000936913F0700F16D000230B4C936103F182 -:10289000840200EB421211794D0709D5890707D54B -:1028A000416954F823508D60117941F00401117190 -:1028B0000133032BEBD130BDE468000873B51D462E -:1028C000436916469A68D207044609D59A680121D9 -:1028D0009960C2F34002CDE900650021FFF76AFE6E -:1028E00063699A68D1050BD59A684FF48071996035 -:1028F000C2F34022CDE9006501212046FFF75AFED0 -:1029000063699A68D2030BD59A684FF48031996055 -:10291000C2F34042CDE9006502212046FFF74AFE9E -:10292000204602B0BDE87040FFF7A8BFF8B50446E6 -:10293000466900296CD106F10C07386880076AD017 -:1029400006EB01153868D5F8B00110F0040FD5F882 -:10295000B0011ABFC00840F00040400DA061D5F89A -:10296000B0C11CF0020F1CBF40F08040A061D5F840 -:10297000B40106EB011100F00F0084F82400D1F837 -:10298000B8012077D1F8B801000A6077D1F8B80112 -:10299000000CA077D1F8B801000EE077D1F8BC01A7 -:1029A00084F82000D1F8BC01000A84F82100D1F895 -:1029B000BC01000C84F82200D1F8BC11090E84F887 -:1029C00023103821396004F1340004F1180104F1B6 -:1029D000240551F8046B40F8046BA942F9D1098829 -:1029E0000180C4E90A2321460023238651F8283BAD -:1029F0002046DB6B984704F58052204692F8C83099 -:102A000043F0040382F8C830BDE8F840FFF736BF52 -:102A100006F1100791E7F8BD10B5044600F04EFA34 -:102A200002460B4652EA030102D0013A63F1000369 -:102A30000449086820B12146BDE81040FFF776BF81 -:102A400010BD00BF584B0020F8B500F583511E465D -:102A5000FFF7D0FCDFF844C00831002404F18405FE -:102A600000EB45152B795F070ED4DB060CD5D1E9B9 -:102A700000739742B34107D243695CF824709F60AA -:102A80002B7943F004032B710134032C01F1200155 -:102A9000E4D1BDE8F840FFF7B3BC00BFE46800082C -:102AA00008B5FFF7A7FCFFF7E9FEBDE80840FFF710 -:102AB000A7BC0000F8B543690546986800F0E050EF -:102AC000B0F1E05F0F461FD0E8B1FFF793FC05F5CA -:102AD00083541034002606F1840305EB43131B795D -:102AE0001A0706D50136032E04F12004F3D1012084 -:102AF00007E05B07F6D42146384600F039FA002893 -:102B0000F0D1FFF77DFCF8BD0120FCE700F5805017 -:102B100008B5FFF76FFCC06DFFF74EFBFFF770FCC9 -:102B200043090CBF0120002008BD0000F8B51D4678 -:102B3000002313700F4606461446FFF7E7FF80F0A8 -:102B40000100387025B129463046FFF7B3FF2070E9 -:102B5000F8BD00002DE9B8410C4615461F468046D9 -:102B600000F0ACF90B462178024609B9287850B13B -:102B70004046FFF769FFFFF793FF3B462A46214691 -:102B8000FFF7D4FF0120BDE8B881000010B5FFF7C2 -:102B900031FC174B1A6C42F000721A641A6A42F048 -:102BA00000721A621A6A00F5805422F000721A62EA -:102BB000FFF726FC94F8C830DB0718D4B9B103211D -:102BC0001320FFF717FC01F0C7F90321142001F0CF -:102BD000C3F90321152001F0BFF994F8C83043F080 -:102BE000010384F8C830BDE81040FFF709BC10BDF0 -:102BF000003802402DE9F04700F5805588B095F87F -:102C0000C930012B0446884616467FD8804F57F8B6 -:102C100023200AB947F82300D7F800A0C4F80C8095 -:102C20002674BAF1000F63D095F8C930012B6FD02C -:102C300001212046FFF7AAFFFFF7DCFB626913685A -:102C400023F0020313606269136843F00103136009 -:102C5000636900275F6101212046FFF7D1FBFFF781 -:102C6000F7FD002800F09580E86DFFF793FA04F572 -:102C70008359BA4609F10809202200216846FEF767 -:102C80005BFF02A8FFF782FCCDF818A06A4609EBAB -:102C900007030DF1180E9446BCE80300F4451860D4 -:102CA0005960624603F10803F5D1DCF800001860B2 -:102CB00020379CF804201A71602FDDD195F8C830B8 -:102CC0006FF38203002785F8C8306A4641462046E4 -:102CD000ADF80070ADF802708DF80470FFF75CFD80 -:102CE000636948BB4FF400421A6008B0BDE8F08742 -:102CF00041F2D00003F0DAFC814610B15146FFF7F3 -:102D0000E9FCC7F80090B9F1000F8DD10020ECE785 -:102D1000386803681B6B98470146002888D13868DB -:102D2000FFF734FF3868036832465B6841469847CE -:102D300000287FF47DAFE9E761221A609DF8023038 -:102D40009DF803201B06120402F4702203F0407366 -:102D50001343BDF80020C2F3090213439DF8042079 -:102D60001205022E02F4E0020CBF4FF000410021D8 -:102D7000134362690B43D361636913225A61626929 -:102D8000136823F00103136039462046FFF760FD06 -:102D900008B96369A6E795F8C93093BB6169D1F8B2 -:102DA000002242F00102C1F800226169D1F800223C -:102DB00022F47C5222F00E02C1F800226169D1F89F -:102DC000002242F46062C1F800226269C2F8143243 -:102DD0006269C2F80432626941F6FF71C2F80C12EE -:102DE0006269C2F840326269C2F844326369012202 -:102DF000C3F81C226269D2F8003223F00103C2F842 -:102E0000003295F8C83043F0020385F8C8306CE70B -:102E1000584B002008B500F051F850EA0103024673 -:102E200002D0421E61F10001044B186810B10B463C -:102E3000FFF744FDBDE8084001F064B8584B00209E -:102E400008B50020FFF7E8FDBDE8084001F05AB8DA -:102E500008B50120FFF7E0FDBDE8084001F052B8D9 -:102E600000B59BB0EFF3098168226846FEF73EFE8D -:102E7000EFF30583014B9B6BFEE700BF00ED00E025 -:102E800008B5FFF7EDFF000000B59BB0EFF3098137 -:102E900068226846FEF72AFEEFF30583014B5B6B61 -:102EA000FEE700BF00ED00E0FEE700000FB408B54C -:102EB000029801F03DFDFEE702F0D2B902F0AAB996 -:102EC00013B56C4684E80600031D94E8030083E80C -:102ED0000500012002B010BD73B58568019155B1A0 -:102EE0001B885B0707D4D0E900369B6B9847019A93 -:102EF000C1B23046A847012002B070BDF0B5866867 -:102F000089B005460C465EB1BDF838305B070AD47F -:102F1000D0E900379B6B98472246C1B23846B0478C -:102F2000012009B0F0BD00220023CDE900230023D9 -:102F3000ADF808300A4603AB01F108061068516885 -:102F40001C4603C40832B2422346F7D11068206001 -:102F50009288A280FFF7B2FF0423ADF808302B68F7 -:102F6000CDE90001DB6B694628469847D8E70000A9 -:102F700030B503680968DD0FB5EBD17F23F06044FD -:102F800021F060424FEAD1700BD0002BB8BFA40CE7 -:102F90000029B8BF920C944202D034BF0120002017 -:102FA00030BD944205D1C1F38070C3F38073834276 -:102FB000F6D194422CBF00200120F1E72DE9F04129 -:102FC000456A15B94162BDE8F0814B6823F060475E -:102FD000C3F38A464FEAD37EC3F3807816EA23060A -:102FE00038BF3E46AC462B465A68BEEBD27F22F035 -:102FF00060440AD0002A18DAA40CB44217D19D42CA -:103000000FD10D60DEE71346EEE7A74207D102F0CD -:103010008044C2F3807242450BD054B1EFE708D22E -:10302000EDE7CCF800100B60CDE7B44201D0B4421C -:10303000E5D81A689C46002AE5D11960C3E700006C -:103040002DE9F047089D01F007044FEAD508224416 -:1030500005F0070500EBD1004FF47F49944201D100 -:10306000BDE8F08704F0070705F0070A57453E461C -:1030700038BF5646C6F10806111B8E4228BF0E46C1 -:10308000E10808EBD50E415C13F80EC0B94029FAEF -:1030900006F721FA0AF1FFB28CEA010147FA0AF7B2 -:1030A00039408CEA010C03F80EC034443544D5E7AE -:1030B00080EA0120082341F2210201B240000029E8 -:1030C00080B203F1FF33B8BF504013F0FF03F4D1D7 -:1030D0007047000038B50C468D18A54200D138BDA8 -:1030E00014F8011BFFF7E4FFF7E7000042684AB15C -:1030F000136843604389818901339BB299424381BC -:1031000038BF83811046704770B588B020220446CE -:103110000D4668460021FEF70FFD20460495FFF797 -:10312000E5FF024658B16B46054608AE1C4603CC87 -:10313000B44228606960234605F10805F6D11046BF -:1031400008B070BD082817D909280CD00A280CD05F -:103150000B280CD00C280CD00D280CD00E2814BF36 -:103160004020302070470C207047102070471420FA -:10317000704718207047202070470000082817D992 -:103180000C280CD910280CD914280CD918280CD9C3 -:1031900020280CD930288CBF0F200E207047092022 -:1031A00070470A2070470B2070470C2070470D2095 -:1031B000704700002DE9F843078C072F04461ED9FD -:1031C000D0E9029800254FF6FF73C5F12006A5F15E -:1031D000200029FA05F108FA06F628FA00F0314332 -:1031E0000143C9B21846FFF763FF0835402D034677 -:1031F000EBD1E1693A46BDE8F843FFF76BBF4FF604 -:10320000FF70BDE8F883000010B54B6823B9CA8A87 -:1032100063F30902CA8210BD04691A681C60036165 -:10322000C38A013BC3824A60EFE700002DE9F84FF3 -:103230001D46CB8A0F46C3F30901052981469246F4 -:103240000B4630D00020AAB207F11A049EB2042E19 -:103250001FFA80F80FD8904503F1010306D3FB8ACB -:103260000A4462F30903FB8201201AE01AF80060A5 -:10327000E6540130EAE79045F1D2A1F1050B1C2399 -:103280007C68BBFBF3F203FB12BB1FFA8BF6002C2E -:1032900045D14846FFF72AFF044638B978606FF0F9 -:1032A0000200BDE8F88F4FF00008E6E70026066050 -:1032B0007860ADB24FF0000B454510D90AEB08031A -:1032C000221D13F8011B9155B1B208F101081B2909 -:1032D0001FFA88F82BD0454506F10106F1D8FB8A84 -:1032E000C3F30902154465F30903BCE7013292B246 -:1032F0001C462368002BF9D16B1F0B441C21B3FB28 -:10330000F1F301339BB29A42D3D2BBF1000FD0D17B -:103310004846FFF7EBFE20B9C4F800B0BFE7012232 -:10332000E7E7C0F800B05E4620600446C1E74545C7 -:10333000D5D94846FFF7DAFE08B92060AFE7C0F8F4 -:1033400000B0002620600446B6E700002DE9F04FEB -:103350002DED028B1C4683B05B69019207468846BF -:10336000002B00F09A80238C2BB1E269002A00F038 -:103370009480072B35D807F10C00FFF7B7FE054600 -:1033800038B96FF00205284603B0BDEC028BBDE8EA -:10339000F08F14220021FEF7CFFB228CE16905F1AA -:1033A0000800FEF7A3FB208C013080B2FFF7E6FE99 -:1033B000FFF7C8FE013880B22084013028746369A9 -:1033C000228C1B782A4403F01F0363F03F0348F06C -:1033D00000411372384669602946FFF7EFFD012569 -:1033E000D1E700F10C034FF0000908EE103A4FF05E -:1033F000800A4E464D4618EE100AFFF777FE8346C8 -:103400000028BED014220021FEF796FB002E3AD1F0 -:10341000019BABF8083002220BF1080E1FFA82FC68 -:103420000CF10100BCF1060F218C80B201D88E4254 -:103430002BD3FFF7A3FEFFF785FE626912780138F0 -:1034400002F01F028E4208BF4FF0400A42EA4912C2 -:103450001BFA80F14AEA020A013048F0004281F882 -:1034600008A08BF81000CBF8042059463846FFF727 -:10347000A5FD238C0135B3422DB289F001094FF02F -:10348000000AB8D17FE70022C6E7E169895D0EF83E -:1034900002100136B6B20132C0E76FF0010572E7E3 -:1034A000F8B515460E463022002104461F46FEF7A9 -:1034B00043FB069B6360B5F5001F079BA76034BF05 -:1034C0006A094FF6FF72A36297B2E66104F1100039 -:1034D00000239A4206D800230360A782E382238355 -:1034E000E360F8BD0660013330462036F1E70000A6 -:1034F00003781BB94BB2002BC8BF017070470000A6 -:1035000000787047F8B50C46C969074611B9238C95 -:10351000002B37D1257E1F2D34D8387828BB228C3C -:10352000072A2CD8268A36F003032BD14FF6FF70DA -:10353000FFF7D0FD20F001003102400441EA0561AF -:10354000400C41EA40254FF6FF7223462946384693 -:10355000FFF7FCFE002807DD626913780133DBB258 -:103560001F2B88BF00231370F8BD218A2D0645EA62 -:10357000012505432046FFF71DFE0246E5E76FF0F3 -:103580000300F1E76FF00100EEE7000070B58AB0CC -:10359000044616460021282268461D46FEF7CCFA4E -:1035A000BDF83830ADF810300F9B05939DF84030D2 -:1035B0008DF81830119B07936946BDF84830ADF877 -:1035C00020302046CDE90265FFF79CFF0AB070BDB0 -:1035D0002DE9F041D36905460C4616460BB9138C0C -:1035E0005BBB377E1F2F28D895F80080B8F1000FFD -:1035F00026D03046FFF7DEFD3378210241EAC331A1 -:1036000041EA0801338A41EA076141EA034102467F -:10361000334641F080012846FFF798FE00280ADD76 -:103620003378012B07D1726913780133DBB21F2B7A -:1036300088BF00231370BDE8F0816FF00100FAE746 -:103640006FF00300F7E70000F0B58BB004460D46BD -:1036500017460021282268461E46FEF76DFA9DF89F -:103660004C305A1E534253418DF800309DF8403083 -:10367000ADF81030119B05939DF848308DF8183047 -:10368000149B07936A46BDF85430ADF820302946A4 -:103690002046CDE90276FFF79BFF0BB0F0BD00009E -:1036A000406A00B104307047436A1A684262026996 -:1036B0001A600361C38A013BC38270472DE9F04160 -:1036C000D0F82080194E14461D464146002709B9FE -:1036D000BDE8F081D1E90223A21A65EB030396420B -:1036E00077EB03031ED2036A8B420DD1FFF78CFDEB -:1036F000036A1B68036203690B60C38A0161016A84 -:10370000013BC3828846E2E7FFF77EFD0B68C8F8FD -:10371000003003690B60C38A0161013BC382D8F8A2 -:103720000010D4E788460968D1E700BF80841E00F6 -:103730002DE9F04F8BB00D46DDF8509014469B46B6 -:103740008046002800F01981B9F1000F00F01581C2 -:10375000531E3F2B00F21181012A03D1BBF1000F50 -:1037600040F00B810023CDE90833B8F81430B5EBF5 -:10377000C30F4FEAC30703D300200BB0BDE8F08F9F -:103780002B199F42D8F80C303ABF7F1BFFB2274657 -:103790001BB9D8F81030002B7AD0272D4ED8C5F1A0 -:1037A0002806B7424FF000032CBFF6B23E46009306 -:1037B0002946D8F8080008AB3246FFF741FCA7EBD2 -:1037C000060A35445FFA8AFAB8F8143003F1005358 -:1037D000053BDB000493D8F80C3003932821039BAE -:1037E00013B1BAF1000F2CD1D8F8100040B1BAF1E2 -:1037F000000F05D0009608AB5246691AFFF720FC6F -:1038000038B2002FB8D066070AD00AAB03EBD40158 -:10381000624211F8083C02F00702134101F8083C2B -:10382000082C3CD9102C40F2B580202C40F2B780F7 -:10383000BBF1000F00F09C80082334E0BA4600265C -:10384000C2E7049BE02B28BFE02306930B44AB4266 -:10385000059314D95A1B03980096924534BF5246DB -:10386000D2B2691A08AB04300792FFF7E9FB079A56 -:103870001644AAEB020A1544F6B25FFA8AFA049BD0 -:10388000069A05999B1A0493039B1B680393A6E76A -:103890000093D8F8080008AB3A462946AEE7BBF1DA -:1038A000000F13D00123B4EBC30F6CD0082C12D837 -:1038B0009DF82030621E23FA02F2D50706D54FF09C -:1038C000FF3202FA04F423438DF820309DF82030B3 -:1038D00089F8003051E7102C12D8BDF82030621E54 -:1038E00023FA02F2D10706D54FF0FF3202FA04F4B0 -:1038F0002343ADF82030BDF82030A9F800303CE774 -:10390000202C0FD80899631E21FA03F3DA0705D596 -:103910004FF0FF3202FA04F40C430894089BC9F8F4 -:1039200000302AE7402C2BD0DDE90865611EC4F188 -:103930002102A4F1210326FA01F105FA02F225FA87 -:1039400003F311431943CB0712D50122A4F120033D -:10395000C4F1200102FA03F322FA01F1A24052421B -:1039600043EA010363EB430332432B43CDE90823CE -:10397000DDE90823C9E90023FFE66FF00100FCE65A -:103980006FF00800F9E6082CA0D9102CB3D9202C30 -:10399000EED8C3E7BBF1000FADD0022383E7BBF144 -:1039A000000FBBD004237EE730B5012A144638BF90 -:1039B0000124402C85B028BF40240025012ACDE9F0 -:1039C000025518D81B788DF8083063070AD004AB6D -:1039D00003EBD405624215F8083C02F0070293405D -:1039E00005F8083C009103462246002102A8FFF793 -:1039F00027FB05B030BD082AE4D9102A03D81B885C -:103A0000ADF80830E1E7202A8DBFD3E900231B6819 -:103A10000293CDE90223D8E710B5CB681BB98B60C0 -:103A20000B618B8210BD04691A681C600361C38A34 -:103A3000013BC382CA60F0E703064CBFC0F3C0304D -:103A40000220704708B50246FFF7F6FF022806D1AC -:103A50005306C2F30F2001D100F0030008BDC2F3EA -:103A60000740FBE72DE9F04F93B0CDE903230A6847 -:103A700004461046FFF7E0FF022814BFC2F30626F3 -:103A80000026002A0D46824680F2F28112F0C049DB -:103A900040F0EE81097B002900F0EA81022803D082 -:103AA0002378B34240F0E781C2F3046306931046E3 -:103AB00002F07F030593FFF7C5FF059B29444FEAFA -:103AC000834848EA0A4848EA4668CE78002300223C -:103AD000CDE90823F309834648EA0008029367D03A -:103AE000059B009302466768534608A92046B847DD -:103AF000002800F0C381276A4FB9414604F10C0049 -:103B0000FFF702FB074690B96FF0020054E03B69F3 -:103B100098450DD03F68002FF9D1414604F10C00C3 -:103B2000FFF7F2FA07460028EED0236A3B602762CF -:103B300097F817C006F01F08CCF3840CACEB080014 -:103B40001FFA80FE0028B8BF0EF12000A8EB0C037E -:103B50001FFA83FED7E90221B8BF00B2002B0793FA -:103B6000BEBF0EF120031BB2079352EA010338D007 -:103B7000039BDFF824E39A1A049B4FF0000C63EBDD -:103B8000010196457CEB01032BD36B7B97F81AE080 -:103B9000734519D1029B002B78D0012821DC78686D -:103BA000F8B9DFF8F0C2944570EB010316D337E0A3 -:103BB000276A27B96FF00C0013B0BDE8F08F3B699E -:103BC0009845B5D03F68F4E7B24890427CEB0103DA -:103BD00001D30020F0E7029B002BFAD0079B0F2BAC -:103BE00017DCFA7DB30002F0030203F07C031343F9 -:103BF000FB7539462046FFF707FB6B7BBB76029BC4 -:103C00003BB9FB7DC3F38402013262F38603FB758B -:103C1000D0E76A7BBB7E9A42DBD1029B002B35D07A -:103C2000B309022B32D0039BBB60049BFB601422C0 -:103C300000210DA8FDF780FF039B0A93049B0B93C3 -:103C40002B1D0C932B7BADF83EB0013BDBB2ADF8E6 -:103C50003C30069B8DF84230059B8DF8433094F83C -:103C60002C308DF840A083F001038DF844308DF89E -:103C70004180A3680AA920469847FB7DC3F38403CB -:103C8000013303F01F039B02FB82A2E7FB7DC6F317 -:103C90004012B2EBD31F40F0F480C3F384034345DA -:103CA00040F0F280029A2B7BB609002A4DD0F20731 -:103CB0005DD4032B40F2EB80039BBB60049BFB6055 -:103CC0002B7BAE1D033BDBB23246394604F10C00C0 -:103CD000FFF7ACFA00280CDA39462046FFF794FAD1 -:103CE000FB7DC3F38403013303F01F039B02FB82BC -:103CF0000AE7DDE90884AB883B834FF6FF73C9F11F -:103D00002000A9F1200228FA09F104FA00F0014389 -:103D100024FA02F211431846C9B2FFF7C9F909F1B2 -:103D20000809B9F1400F0346E9D1B8822A7B033A6A -:103D3000D2B23146FFF7CEF9FB7DB882DA43C2F347 -:103D4000C01262F3C713FB7543E786B92E1D013B12 -:103D5000DBB23246394604F10C00FFF767FA00285F -:103D6000BADB2A7BB88A013AD2B23146E2E7F98A55 -:103D7000C1F30901013B0429DAB25BD8281D0023F5 -:103D800007F11B069A4208D910F801CB06F801C0CA -:103D9000013101330529DBB2F4D103990A91049969 -:103DA0000B91934207F11B010C9138BF04337968E2 -:103DB0000D9134BF55FA83F300230E93FB8AADF8BF -:103DC0003EB0C3F309031A44069B8DF84230059BAD -:103DD0008DF8433094F82C30ADF83C2083F001038B -:103DE0008DF8443000238DF840A08DF841807B6031 -:103DF0002A7BB88A013A291DFFF76CF93B8BB88200 -:103E0000834203D1A3680AA92046984720460AA9FD -:103E1000FFF702FEFB7DBA8AC3F38403013303F08C -:103E20001F039B02FB823B8B9A420CBF00206FF06A -:103E30001000C1E67B68002BAFD0052001E01C30EC -:103E400033461E68002EFAD1091A081D2E1D18448B -:103E500001EB090CBCF11B0F5FFA89F39DD89A4264 -:103E60009BD916F8013B00F8013B09F10109EFE786 -:103E70006FF00900A0E66FF00A009DE66FF00B00FE -:103E80009AE66FF00D0097E66FF00E0094E66FF083 -:103E90000F0091E640420F0080841E00EFF309837B -:103EA00005494A6B22F001024A63683383F30988AB -:103EB000002383F31188704700EF00E0302080F387 -:103EC000118862B60C4B0D4AD96821F4E0610904EF -:103ED000090C0A43DA60D3F8FC20094942F08072E9 -:103EE000C3F8FC200A6842F001020A602022DA7757 -:103EF00083F82200704700BF00ED00E00003FA05E0 -:103F0000001000E010B5302383F311880E4B5B687E -:103F100013F4006314D0F1EE103AEFF30984683C17 -:103F20004FF08073E361094BDB6B236684F30988F0 -:103F300000F0BCFC10B1064BA36110BD054BFBE7C4 -:103F400083F31188F9E700BF00ED00E000EF00E027 -:103F5000430600084606000800F1604303F561438C -:103F60000901C9B283F80013012200F01F039A402F -:103F700043099B0003F1604303F56143C3F88021CB -:103F80001A607047026843681143016003B1184723 -:103F90007047000013B5446BD4F894341A68117854 -:103FA000042915D1217C022912D119791289012302 -:103FB0008B4013420CD101A904F14C0001F0BAFF6F -:103FC000D4F89444019B21790246206800F0D0F98E -:103FD00002B010BD143001F03DBF00004FF0FF33C0 -:103FE000143001F037BF00004C3002F00FB8000071 -:103FF0004FF0FF334C3002F009B80000143001F0EC -:104000000BBF00004FF0FF31143001F005BF00007E -:104010004C3001F0DBBF00004FF0FF324C3001F0BC -:10402000D5BF00000020704710B5D0F894341A684E -:1040300011780429044617D1017C022914D1597939 -:10404000528901238B4013420ED1143001F09EFEA1 -:10405000024648B1D4F894444FF4807361792068E3 -:10406000BDE8104000F072B910BD0000406BFFF7D2 -:10407000DBBF0000704700007FB5124B03600023D8 -:104080004360C0E90233012502260F4B0574044644 -:104090000290019300F18402294600964FF4807348 -:1040A000143001F04FFE094B0294CDE9006304F592 -:1040B00023724FF48073294604F14C0001F016FF7F -:1040C00004B070BD386900086D400008953F0008D5 -:1040D0000B68302282F311880A7903EB8202906127 -:1040E0004A79093243F822008A7912B103EB82033C -:1040F00098610223C0F894140374002080F311889F -:104100007047000038B5037F044613B190F854306F -:10411000ABB9201D01250221FFF734FF04F1140083 -:1041200025776FF0010100F09FFC84F8545004F1F2 -:104130004C006FF00101BDE8384000F095BC38BD7F -:1041400010B5012104460430FFF71CFF002323773C -:1041500084F8543010BD000038B5044600251430F2 -:1041600001F008FE04F14C00257701F0D7FE201D78 -:1041700084F854500121FFF705FF2046BDE8384080 -:10418000FFF752BF90F8443003F06003202B07D1B3 -:1041900090F84520212A4FF0000303D81F2A06D8A3 -:1041A00000207047222AFBD1C0E90E3303E0034A06 -:1041B00082630722C2630364012070471D2300202D -:1041C00037B5D0F894341A681178042904461AD106 -:1041D000017C022917D11979128901238B401342DE -:1041E00011D100F14C05284601F058FF58B101A942 -:1041F000284601F09FFED4F89444019B21790246A1 -:10420000206800F0B5F803B030BD0000F0B500EB59 -:10421000810385B09E6904460D46FEB1302383F3C9 -:10422000118804EB8507301D0821FFF7ABFEFB6802 -:104230005B691B6806F14C001BB1019001F088FE20 -:10424000019803A901F076FE024648B1039B294676 -:10425000204600F08DF8002383F3118805B0F0BDEF -:10426000FB685A691268002AF5D01B8A013B13408B -:10427000F1D104F14402EAE7093138B550F82140A0 -:10428000DCB1302383F31188D4F894241368527975 -:1042900003EB8203DB689B695D6845B1042160180C -:1042A000FFF770FE294604F1140001F079FD204665 -:1042B000FFF7BAFE002383F3118838BD7047000072 -:1042C00001F0EEB8012303700023C0E90133C3619C -:1042D00083620362C36243620363704738B5044676 -:1042E000302383F311880025C0E90355C0E9055543 -:1042F000416001F0E5F80223237085F31188284618 -:1043000038BD000070B500EB810305465069DA60E6 -:104310000E46144618B110220021FDF70DFCA069CD -:1043200018B110220021FDF707FC31462846BDE8F0 -:10433000704001F08FB90000826802F001128260C3 -:104340000022C0E90422826101F010BAF0B400EB4F -:1043500081044789E4680125A4698D403D43458176 -:1043600023600023A2606360F0BC01F02BBA000060 -:10437000F0B400EB81040789E468012564698D408D -:104380003D43058123600023A2606360F0BC01F01F -:10439000A5BA000070B50223002504460370C0E9E9 -:1043A0000255C0E90455C564856180F8345001F0B8 -:1043B000EDF863681B6823B129462046BDE87040CC -:1043C000184770BD0378052B10B504460AD080F855 -:1043D00050300523037043681B680BB104219847D4 -:1043E0000023A36010BD00000178052906D190F8D4 -:1043F0005020436802701B6803B1184770470000E3 -:1044000070B590F83430044613B1002380F834308E -:1044100004F14402204601F0CBF963689B68B3B90C -:1044200094F8443013F0600535D00021204601F0A7 -:104430006BFC0021204601F05DFC63681B6813B132 -:10444000062120469847062384F8343070BD204664 -:1044500098470028E4D0B4F84A30E26B9A4288BF0B -:10446000E36394F94430E56B002B4FF0300380F2A6 -:104470000381002D00F0F280092284F8342083F3B8 -:1044800011880021D4E90E232046FFF771FF002395 -:1044900083F31188DAE794F8452003F07F0343EAB9 -:1044A000022340F20232934200F0C58021D8B3F5D6 -:1044B000807F48D00DD8012B3FD0022B00F0938095 -:1044C000002BB2D104F14C02A2630222E263236406 -:1044D000C1E7B3F5817F00F09B80B3F5407FA4D1A5 -:1044E00094F84630012BA0D1B4F84C3043F00203CD -:1044F00032E0B3F5006F4DD017D8B3F5A06F31D0CF -:10450000A3F5C063012B90D8636894F846205E68D9 -:1045100094F84710B4F848302046B047002884D0BB -:104520004368A3630368E3631AE0B3F5106F36D002 -:1045300040F6024293427FF478AF5C4BA3630223C0 -:10454000E3630023C3E794F84630012B7FF46DAF9B -:10455000B4F84C3023F00203C4E90E55A4F84C30F3 -:10456000256478E7B4F84430B3F5A06F0ED194F821 -:10457000463084F84E30204601F060F863681B68CE -:1045800013B1012120469847032323700023C4E977 -:104590000E339CE704F14F03A3630123C3E72378A1 -:1045A000042B10D1302383F311882046FFF7C4FE7B -:1045B00085F311880321636884F84F5021701B68CC -:1045C0000BB12046984794F84630002BDED084F893 -:1045D0004F300423237063681B68002BD6D0022160 -:1045E00020469847D2E794F848301D0603F00F01A3 -:1045F00020460AD501F0CEF8012804D002287FF425 -:1046000014AF2B4B9AE72B4B98E701F0B5F8F3E783 -:1046100094F84630002B7FF408AF94F8483013F03C -:104620000F01B3D01A06204602D501F081FBADE799 -:1046300001F074FBAAE794F84630002B7FF4F5AE46 -:1046400094F8483013F00F01A0D01B06204602D585 -:1046500001F05AFB9AE701F04DFB97E7142284F82A -:10466000342083F311882B462A4629462046FFF73B -:104670006DFE85F31188E9E65DB1152284F83420DA -:1046800083F311880021D4E90E232046FFF75EFE54 -:10469000FDE60B2284F8342083F311882B462A464A -:1046A00029462046FFF764FEE3E700BF686900087B -:1046B000606900086469000838B590F83430044631 -:1046C000002B3ED0063BDAB20F2A34D80F2B32D85B -:1046D000DFE803F037313108223231313131313105 -:1046E00031313737C56BB0F84A309D4214D2C368B8 -:1046F0001B8AB5FBF3F203FB12556DB9302383F32C -:1047000011882B462A462946FFF732FE85F3118889 -:104710000A2384F834300EE0142384F83430302334 -:1047200083F3118800231A4619462046FFF70EFE30 -:10473000002383F3118838BD036C03B1984700232D -:10474000E7E70021204601F0DFFA0021204601F0D2 -:10475000D1FA63681B6813B10621204698470623E7 -:10476000D7E7000010B590F83430142B044629D058 -:1047700017D8062B05D001D81BB110BD093B022B61 -:10478000FBD80021204601F0BFFA0021204601F0AD -:10479000B1FA63681B6813B10621204698470623C7 -:1047A00019E0152BE9D10B2380F83430302383F343 -:1047B000118800231A461946FFF7DAFD002383F318 -:1047C0001188DAE7C3689B695B68002BD5D1036C5D -:1047D00003B19847002384F83430CEE700230375F3 -:1047E000826803691B6899689142FBD25A6803602A -:1047F0004260106058607047002303758268036947 -:104800001B6899689142FBD85A6803604260106047 -:104810005860704708B50846302383F311880B7D34 -:10482000032B05D0042B0DD02BB983F3118808BDC1 -:104830008B6900221A604FF0FF338361FFF7CEFFD0 -:104840000023F2E7D1E9003213605A60F3E7000079 -:10485000FFF7C4BF054BD9680875186802681A606D -:10486000536001220275D860FBF7D6BE684B00206A -:1048700030B50C4BDD684B1C87B004460FD02B467F -:10488000094A684600F084F92046FFF7E3FF009BE1 -:1048900013B1684600F086F9A86907B030BDFFF78C -:1048A000D9FFF9E7684B002015480008044B1A6847 -:1048B000DB6890689B68984294BF00200120704795 -:1048C000684B0020084B10B51C68D86822681A6035 -:1048D000536001222275DC60FFF78EFF01462046FF -:1048E000BDE81040FBF798BE684B0020044B1A68E7 -:1048F000DB6892689B689A4201D9FFF7E3BF704773 -:10490000684B002038B5074C0749084801230025AB -:104910002370656001F0FAFB0223237085F3118890 -:1049200038BD00BFD04D002070690008684B0020E2 -:1049300008B572B6044B186500F050FC00F00EFD8F -:10494000024B03221A70FEE7684B0020D04D002076 -:1049500000F05EB9EFF3118020B9EFF30583302248 -:1049600082F311887047000010B530B9EFF3058469 -:10497000C4F3080414B180F3118810BDFFF7B6FF2B -:1049800084F31188F9E70000034A516853685B1A01 -:104990009842FBD8704700BF001000E08B600223F4 -:1049A00008618B82084670478368A3F1840243F84C -:1049B000142C026943F8442C426943F8402C094AFC -:1049C00043F8242CC26843F8182C022203F80C2C5C -:1049D000002203F80B2C044A43F8102CA3F120000A -:1049E000704700BF31060008684B002008B5FFF78C -:1049F000DBFFBDE80840FFF72BBF0000024BDB6880 -:104A000098610F20FFF726BF684B0020302383F307 -:104A10001188FFF7F3BF000008B50146302383F388 -:104A200011880820FFF724FF002383F3118808BDB5 -:104A3000064BDB6839B1426818605A601360436006 -:104A40000420FFF715BF4FF0FF307047684B002080 -:104A50000368984206D01A6802605060996118464F -:104A6000FFF7F6BE7047000038B504460D462068D3 -:104A7000844200D138BD036823605C608561FFF724 -:104A8000E7FEF4E710B503689C68A2420CD85C68A6 -:104A90008A600B604C602160596099688A1A9A603C -:104AA0004FF0FF33836010BD1B68121BECE7000062 -:104AB0000A2938BF0A2170B504460D460A26601936 -:104AC00001F01EFB01F00AFB041BA54203D8751C74 -:104AD0002E460446F3E70A2E04D9BDE870400120B3 -:104AE00001F054BB70BD0000F8B5144B0D46D96100 -:104AF00003F1100141600A2A1969826038BF0A2255 -:104B0000016048601861A818144601F0EBFA0A2702 -:104B100001F0E4FA431BA342064606D37C1C281985 -:104B200001F0EEFA27463546F2E70A2F04D9BDE830 -:104B3000F840012001F02ABBF8BD00BF684B0020FF -:104B4000F8B506460D4601F0C9FA0F4A134653F868 -:104B5000107F9F4206D12A4601463046BDE8F84004 -:104B6000FFF7C2BFD169BB68441A2C1928BF2C4675 -:104B7000A34202D92946FFF79BFF2246314603484C -:104B8000BDE8F840FFF77EBF684B0020784B00205F -:104B900010B4C0E9032300235DF8044B4361FFF721 -:104BA000CFBF000010B5194C236998420DD0D0E951 -:104BB0000032816813605A609A680A449A60002340 -:104BC00003604FF0FF33A36110BD2346026843F832 -:104BD000102F53600022026022699A4203D1BDE87F -:104BE000104001F087BA936881680B44936001F02C -:104BF00075FA2269E1699268441AA242E4D9114423 -:104C0000BDE81040091AFFF753BF00BF684B0020F2 -:104C10002DE9F047DFF8BC8008F110072C4ED8F8DA -:104C2000105001F05BFAD8F81C40AA68031B9A42A6 -:104C30003ED81444D5E900324FF00009C8F81C40B2 -:104C400013605A60C5F80090D8F81030B34201D113 -:104C500001F050FA89F31188D5E9033128469847C5 -:104C6000302383F311886B69002BD8D001F036FA1A -:104C70006A69A0EB04094A4582460DD2022001F080 -:104C800085FA0022D8F81030B34208D151462846A0 -:104C9000BDE8F047FFF728BF121A2244F2E712EBF3 -:104CA000090938BF4A4629463846FFF7EBFEB5E703 -:104CB000D8F81030B34208D01444211AC8F81C00A8 -:104CC000A960BDE8F047FFF7F3BEBDE8F08700BF7D -:104CD000784B0020684B002000207047FEE7000062 -:104CE000704700004FF0FF307047000002290CD0E1 -:104CF000032904D00129074818BF00207047032A60 -:104D000005D8054800EBC2007047044870470020F2 -:104D1000704700BF486A00082C230020FC69000887 -:104D200070B59AB00546084601A9144600F0C2F8CD -:104D300001A8FCF7F9FE431C5B00C5E90034002222 -:104D4000237003236370C6B201AB02341046D1B2A4 -:104D50008E4204F1020401D81AB070BD13F8011B91 -:104D600004F8021C04F8010C0132F0E708B5302306 -:104D700083F311880348FFF723FA002383F3118894 -:104D800008BD00BFD84D002090F8443003F01F024A -:104D9000012A07D190F845200B2A03D10023C0E94E -:104DA0000E3315E003F06003202B08D1B0F8483033 -:104DB0002BB990F84520212A03D81F2A04D8FFF7E1 -:104DC000E1B9222AEBD0FAE7034A82630722C263E1 -:104DD00003640120704700BF2423002007B5052984 -:104DE00017D8DFE801F0191603191920302383F3CF -:104DF0001188104A01900121FFF784FA01980E4AA8 -:104E00000221FFF77FFA0D48FFF7A6F9002383F38D -:104E1000118803B05DF804FB302383F31188074841 -:104E2000FFF770F9F2E7302383F311880348FFF7A7 -:104E300087F9EBE79C690008C0690008D84D00209D -:104E400038B50C4D0C4C0D492A4604F10800FFF70B -:104E500067FF05F1CA0204F110000949FFF760FF7E -:104E600005F5CA7204F118000649BDE83840FFF79D -:104E700057BF00BFA05200202C2300207C690008EF -:104E8000866900089169000870B5044608460D4619 -:104E9000FCF74AFEC6B22046013403780BB9184627 -:104EA00070BD32462946FCF72BFE0028F3D10120C5 -:104EB000F6E700002DE9F04705460C46FCF734FE06 -:104EC0002B49C6B22846FFF7DFFF08B10B36F6B212 -:104ED00028492846FFF7D8FF08B11036F6B2632EEE -:104EE0000BD8DFF88C80DFF88C90234FDFF894A08C -:104EF0002E7846B92670BDE8F08729462046BDE8E1 -:104F0000F04701F091BC252E2ED1072241462846BC -:104F1000FCF7F6FD70B9194B224603F1100153F866 -:104F2000040B42F8040B8B42F9D11B881380073520 -:104F30001234DDE7082249462846FCF7E1FD98B91E -:104F40000F4BA21C197809090232C95D02F8041C32 -:104F500013F8011B01F00F015345C95D02F8031C52 -:104F6000F0D118340835C3E704F8016B0135BFE709 -:104F7000686A000891690008706A000846680008BD -:104F8000107AFF1F1C7AFF1FBFF34F8F024AD368AE -:104F9000DB03FCD4704700BF003C024008B5094B5E -:104FA0001B7873B9FFF7F0FF074B1A69002ABFBFE0 -:104FB000064A5A6002F188325A601A6822F4806206 -:104FC0001A6008BDFE540020003C024023016745E2 -:104FD00008B50B4B1B7893B9FFF7D6FF094B1A693D -:104FE00042F000421A611A6842F480521A601A684C -:104FF00022F480521A601A6842F480621A6008BD76 -:10500000FE540020003C02400B28F0B516D80C4C92 -:105010000C4923787BB90C4D0E460C234FF00062EF -:1050200055F8047B46F8042B013B13F0FF033A4488 -:10503000F6D10123237051F82000F0BD0020FCE7D9 -:105040003055002000550020846A0008014B53F8B9 -:1050500020007047846A00080C2070470B2810B5A8 -:10506000044601D9002010BDFFF7CEFF064B53F8D0 -:1050700024301844C21A0BB90120F4E71268013237 -:10508000F0D1043BF6E700BF846A00080B2810B596 -:10509000044621D8FFF778FFFFF780FF0F4AF3237C -:1050A000D360C300DBB243F4007343F00203136127 -:1050B000136943F480331361FFF766FFFFF7A4FF22 -:1050C000074B53F8241000F045F9FFF781FF204605 -:1050D000BDE81040FFF7C2BF002010BD003C0240F9 -:1050E000846A0008F8B512F00103144642D1821810 -:1050F000B2F1016F57D82D4B1B6813F0010352D04A -:105100002B4DFFF74BFFF323EB60FFF73DFF40F222 -:105110000127032C15D824F001046618244C401AEA -:1051200040F20117B142236900EB010524D123F0BD -:1051300001032361FFF74CFF0120F8BD043C04305C -:10514000E7E78307E7D12B6923F440732B612B69D1 -:105150003B432B6151F8046B0660BFF34F8FFFF7A1 -:1051600013FF03689E42E9D02B6923F001032B61F2 -:10517000FFF72EFF0020E0E723F44073236123694B -:105180003B4323610B882B80BFF34F8FFFF7FCFE5F -:105190002D8831F8023BADB2AB42C3D0236923F076 -:1051A00001032361E4E71846C7E700BF0038024067 -:1051B000003C0240084908B50B7828B11BB9FFF73D -:1051C000EDFE01230B7008BD002BFCD0BDE80840AC -:1051D0000870FFF7FDBE00BFFE54002008B54FF475 -:1051E00000314FF0005000F0B7F8BDE808404FF430 -:1051F00080314FF0805000F0AFB8000008461146F3 -:1052000001F076BA012001F073BA0000084601F0FF -:105210008DBA000070B582B0FFF79CFB0E4E0546BC -:1052200000F05CFF3268904237BF0C4A0B4951686E -:1052300014682EBFD1E900410131516004190346C1 -:1052400041F10001284601913360FFF78DFB019980 -:10525000204602B070BD00BF3455002038550020F4 -:1052600070B582B0FFF776FB104E054600F036FFB2 -:105270003268904237BF0E4A0D49516814682EBFFC -:10528000D1E9004101315160041941F100010346A7 -:10529000284601913360FFF767FB01994FF47A725A -:1052A00000232046FAF7A4FF02B070BD3455002059 -:1052B0003855002010B50244064BD2B2904200D1BE -:1052C00010BD441C00B253F8200041F8040BE0B2BA -:1052D000F4E700BF502800400F4B30B51C6F24048A -:1052E00007D41C6F44F400741C671C6F44F4004422 -:1052F0001C670A4C236843F4807323600244084B04 -:10530000D2B2904200D130BD441C00B251F8045BCF -:1053100043F82050E0B2F4E700380240007000404B -:105320005028004007B5012201A90020FFF7C2FF65 -:10533000019803B05DF804FB13B50446FFF7F2FFD4 -:10534000A04205D0012201A900200194FFF7C4FF6B -:1053500002B010BD704700007047000070470000A9 -:10536000074B45F255521A6002225A6040F6FF720E -:105370009A604CF6CC421A60024B01221A707047B8 -:105380000030004044550020034B1B781BB1034BF9 -:105390004AF6AA221A6070474455002000300040A7 -:1053A000034B1A681AB9034AD2F874281A60704776 -:1053B0004055002000300240024B4FF08072C3F88D -:1053C000742870470030024008B5FFF7E9FF024B30 -:1053D0001868C0F3407008BD4055002008B5FFF7BD -:1053E000DFFF024B1868C0F3007008BD4055002075 -:1053F00070470000FEE700000A4B0B480B4A904242 -:105400000BD30B4BDA1C121AC11E22F003028B4283 -:1054100038BF00220021FCF78FBB53F8041B40F873 -:10542000041BECE7A86C00084856002048560020F2 -:105430004856002070B5D0E915439E6800224FF011 -:10544000FF3504EB42135101D3F800090028BEBF19 -:10545000D3F8000940F08040C3F80009D3F8000BEE -:105460000028BEBFD3F8000B40F08040C3F8000B0B -:10547000013263189642C3F80859C3F8085BE0D2BA -:105480004FF00113C4F81C3870BD0000890141F0D1 -:105490002001016103699B06FCD41220FFF774BA56 -:1054A00010B5054C2046FEF70DFF4FF0A043636595 -:1054B000024BA36510BD00BF48550020D86A000804 -:1054C00070B50378012B054650D12A4B446D9842A4 -:1054D0001BD1294B5A6B42F080025A635A6D42F03D -:1054E00080025A655A6D5A6942F080025A615A69BF -:1054F00022F080025A610E2143205B69FEF72CFDE9 -:105500001E4BE3601E4BC4F800380023C4F8003E75 -:10551000C02323606E6D4FF40413A3633369002B23 -:10552000FCDA012333610C20FFF72EFA3369DB0725 -:10553000FCD41220FFF728FA3369002BFCDA00268E -:10554000A6602846FFF776FF6B68C4F81068DB6832 -:10555000C4F81468C4F81C684BB90A4BA3614FF037 -:10556000FF336361A36843F00103A36070BD064B82 -:10557000F4E700BF485500200038024040140040C6 -:1055800003002002003C30C0083C30C0F8B5446D38 -:10559000054600212046FFF779FFA96D00234FF053 -:1055A00001128F68C4F834384FF00066C4F81C2824 -:1055B0004FF0FF3004EB431201339F42C2F8006901 -:1055C000C2F8006BC2F80809C2F8080BF2D20B68E7 -:1055D0006A6DEB65636210231361166916F010069D -:1055E000FBD11220FFF7D0F9D4F8003823F4FE6382 -:1055F000C4F80038A36943F4402343F01003A361C7 -:105600000923C4F81038C4F814380A4BEB604FF083 -:10561000C043C4F8103B084BC4F8003BC4F8106901 -:10562000C4F80039EB6D03F1100243F48013EA650E -:10563000A362F8BDB46A000840800010426D90F883 -:105640004E10D2F8003823F4FE6343EA0113C2F887 -:10565000003870472DE9F84300EB8103456DDA68A7 -:10566000166806F00306731E022B05EB41130C4669 -:1056700080460FFA81F94FEA41104FF00001C3F85C -:10568000101B4FF0010104F1100398BFB60401FA9A -:1056900003F391698EBF334E06F1805606F500463E -:1056A00000293AD0578A04F15801490137436F5015 -:1056B000D5F81C180B43C5F81C382B180021C3F86B -:1056C000101953690127611EA7409BB3138A928B5F -:1056D0009B08012A88BF5343D8F85C20981842EAF7 -:1056E000034301F1400205EB8202C8F85C00214649 -:1056F00053602846FFF7CAFE08EB8900C3681B8A7F -:1057000043EA8453483464011E432E51D5F81C38B3 -:105710001F43C5F81C78BDE8F88305EB4917D7F897 -:10572000001B21F40041C7F8001BD5F81C1821EA22 -:105730000303C0E704F13F0305EB83030A4A5A6001 -:1057400028462146FFF7A2FE05EB4910D0F80039A4 -:1057500023F40043C0F80039D5F81C3823EA0707C2 -:10576000D7E700BF0080001000040002826D1268BD -:10577000C265FFF75FBE00005831436D49015B58B9 -:1057800013F4004004D013F4001F0CBF02200120CA -:10579000704700004831436D49015B5813F40040E5 -:1057A00004D013F4001F0CBF02200120704700003A -:1057B00000EB8101CB68196A0B6813604B6853607A -:1057C0007047000000EB810330B5DD68AA691368FB -:1057D000D36019B9402B84BF402313606B8A1468CF -:1057E000426D1C44013CB4FBF3F46343033323F0E8 -:1057F000030302EB411043EAC44343F0C043C0F843 -:10580000103B2B6803F00303012B09B20ED1D2F831 -:10581000083802EB411013F4807FD0F8003B14BF2E -:1058200043F0805343F00053C0F8003B02EB4112B9 -:10583000D2F8003B43F00443C2F8003B30BD000007 -:105840002DE9F041244D6E6D06EB40130446D3F86C -:10585000087BC3F8087B38070AD5D6F8143819072F -:1058600006D505EB84032146DB6828465B6898472C -:10587000FA071FD5D6F81438DB071BD505EB8403D0 -:10588000D968CCB98B69488A5A68B2FBF0F600FB3C -:1058900016228AB91868DA6890420DD2121AC3E942 -:1058A0000024302383F311880B482146FFF78AFF39 -:1058B00084F31188BDE8F081012303FA04F26B89B7 -:1058C00023EA02036B81CB68002BF3D02146024808 -:1058D000BDE8F041184700BF4855002000EB8103A8 -:1058E00070B5DD68436D6C692668E6604A0156BB99 -:1058F0001A444FF40020C2F810092A6802F003028B -:10590000012A0AB20ED1D3F8080803EB421410F4AE -:10591000807FD4F8000914BF40F0805040F0005060 -:10592000C4F8000903EB4212D2F8000940F0044029 -:10593000C2F80009D3F83408012202FA01F1014348 -:10594000C3F8341870BD19B9402E84BF40202060C0 -:1059500020682E8A8419013CB4FBF6F440EAC44066 -:1059600040F000501A44C6E72DE9F8433B4D6E6DF8 -:1059700006EB40130446D3F80889C3F8088918F0E9 -:10598000010F4FEA40171AD0D6F81038DB0716D5AA -:1059900005EB8003D9684B691868DA68904230D209 -:1059A000121A4FF000091A60C3F80490302383F3F1 -:1059B000118821462846FFF791FF89F3118818F0D6 -:1059C000800F1CD0D6F834380126A640334216D0BA -:1059D00005EB84036D6DD3F80CC0DCF814200134A2 -:1059E000E4B2D2F800E005EB04342F44516871456D -:1059F00015D3D5F8343823EA0606C5F83468BDE86F -:105A0000F883012303FA04F22B8923EA02032B8192 -:105A10008B68002BD3D0214628469847CFE7BCF8A7 -:105A20001000AEEB0103834228BF0346D7F81809E4 -:105A300080B2B3EB800FE2D89068A0F1040959F866 -:105A4000048FC4F80080A0EB09089844B8F1040F53 -:105A5000F5D818440B4490605360C7E748550020C0 -:105A60002DE9F74FA24C656D6E69AB691E4016F4C7 -:105A700080586E6107D02046FEF78CFC03B0BDE86D -:105A8000F04FFEF73FBA002E12DAD5F8003E9848E4 -:105A90009B071EBFD5F8003E23F00303C5F8003E68 -:105AA000D5F8043823F00103C5F80438FEF79CFC50 -:105AB000370505D58E48FFF7BDFC8D48FEF782FC03 -:105AC000B0040CD5D5F8083813F0060FEB6823F4B2 -:105AD00070530CBF43F4105343F4A053EB603107F1 -:105AE0001BD56368DB681BB9AB6923F00803AB61A6 -:105AF0002378052B0CD1D5F8003E7D489A071EBFB0 -:105B0000D5F8003E23F00303C5F8003EFEF76CFC19 -:105B10006368DB680BB176489847F30274D4B70228 -:105B200027D5D4F85490DFF8C8B100274FF0010A08 -:105B300009EB4712D2F8003B03F44023B3F5802F62 -:105B400011D1D2F8003B002B0DDA62890AFA07F373 -:105B500022EA0303638104EB8703DB68DB6813B18C -:105B6000394658469847A36D01379B68FFB29F425C -:105B7000DED9F00617D5676D3A6AC2F30A1002F053 -:105B80000F0302F4F012B2F5802F00F08580B2F519 -:105B9000402F08D104EB83030022DB681B6A07F562 -:105BA000805790426AD13003D5F8184813D5E103E5 -:105BB00002D50020FFF744FEA20302D50120FFF723 -:105BC0003FFE630302D50220FFF73AFE270302D50A -:105BD0000320FFF735FE75037FF550AFE00702D5D0 -:105BE0000020FFF7C1FEA10702D50120FFF7BCFE90 -:105BF000620702D50220FFF7B7FE23077FF53EAF0D -:105C00000320FFF7B1FE39E7636DDFF8E4A00193ED -:105C100000274FF00109A36D9B685FFA87FB9B4546 -:105C20003FF67DAF019B03EB4B13D3F8001901F452 -:105C30004021B1F5802F1FD1D3F8001900291BDABC -:105C4000D3F8001941F09041C3F80019D3F80019B6 -:105C50000029FBDB5946606DFFF718FC218909FA22 -:105C60000BF321EA0303238104EB8B03DB689B68BE -:105C700013B15946504698470137CCE7910708BF02 -:105C8000D7F80080072A98BF03F8018B02F10102C0 -:105C900098BF4FEA182884E7023304EB830207F524 -:105CA00080575268D2F818C0DCF80820DCE9001CE4 -:105CB000A1EB0C0C002188420AD104EB8304636839 -:105CC0009B699A6802449A605A6802445A606AE77B -:105CD00011F0030F08BFD7F800808C4588BF02F889 -:105CE000018B01F1010188BF4FEA1828E3E700BFEB -:105CF00048550020436D03EB4111D1F8003B43F4BC -:105D00000013C1F8003B7047436D03EB4111D1F81C -:105D1000003943F40013C1F800397047436D03EBB9 -:105D20004111D1F8003B23F40013C1F8003B704748 -:105D3000436D03EB4111D1F8003923F40013C1F88E -:105D40000039704730B5039C0172043304FB03250E -:105D5000C0E90653049B03630021059BC160C0E9B1 -:105D60000000C0E90422C0E90842C0E90A11436307 -:105D700030BD0000416A0022C0E90411C0E90A22D6 -:105D8000C2606FF00101FEF76FBE0000D0E904327F -:105D9000934201D1C2680AB9181D704700207047AC -:105DA00003691960C2680132C260C2691344826922 -:105DB0000361934224BF436A03610021FEF748BE9A -:105DC00038B504460D46E3683BB16269131D12689D -:105DD000A3621344E362002007E0237A33B9294623 -:105DE0002046FEF725FE0028EDDA38BD6FF00100F1 -:105DF000FBE70000C368C269013BC3604369134409 -:105E000082694361934224BF436A436100238362F2 -:105E1000036B03B11847704770B53023044683F312 -:105E20001188866A3EB9FFF7CBFF054618B186F3A5 -:105E30001188284670BDA36AE26A13F8015BA36269 -:105E4000934202D32046FFF7D5FF002383F3118846 -:105E5000EFE700002DE9F84F04460E461746984636 -:105E60004FF0300989F311880025AA46D4F828B0EC -:105E7000BBF1000F09D141462046FFF7A1FF20B139 -:105E80008BF311882846BDE8F88FD4E90A12A7EBF6 -:105E9000050B521A934528BF9346BBF1400F1BD9FF -:105EA000334601F1400251F8040B43F8040B9142D0 -:105EB000F9D1A36A40334036A3624035D4E90A23BE -:105EC0009A4202D32046FFF795FF8AF31188BD421C -:105ED000D8D289F31188C9E730465A46FBF706FE47 -:105EE000A36A5B445E44A3625D44E7E710B5029C8D -:105EF0000172043303FB0421C0E906130023C0E947 -:105F00000A33039B0363049BC460C0E90000C0E93B -:105F10000422C0E90842436310BD0000026AC26067 -:105F2000426AC0E904220022C0E90A226FF001019E -:105F3000FEF79ABDD0E904239A4201D1C26822B982 -:105F4000184650F8043B0B60704700231846FAE7E8 -:105F5000C368C2690133C360436913448269436102 -:105F6000934224BF436A43610021FEF771BD0000E4 -:105F700038B504460D46E3683BB123691A1DA26299 -:105F8000E2691344E362002007E0237A33B929462B -:105F90002046FEF74DFD0028EDDA38BD6FF0010018 -:105FA000FBE7000003691960C268013AC260C26978 -:105FB000134482690361934224BF436A036100234F -:105FC0008362036B03B118477047000070B530233C -:105FD0000D460446114683F31188866A2EB9FFF7F1 -:105FE000C7FF10B186F3118870BDA36A1D70A36A44 -:105FF000E26A01339342A36204D3E1692046043983 -:10600000FFF7D0FF002080F31188EDE72DE9F84F6E -:1060100004460D46904699464FF0300A8AF311889F -:106020000026B346A76A4FB949462046FFF7A0FFAE -:1060300020B187F311883046BDE8F88FD4E90A070C -:106040003A1AA8EB0607974228BF1746402F1BD9DC -:1060500005F1400355F8042B40F8042B9D42F9D17B -:10606000A36A4033A3624036D4E90A239A4204D398 -:10607000E16920460439FFF795FF8BF31188464507 -:10608000D9D28AF31188CDE729463A46FBF72EFD8F -:10609000A36A3B443D44A3623E44E5E7D0E90423C0 -:1060A0009A4217D1C3689BB1836A8BB1043B9B1A98 -:1060B0000ED01360C368013BC360C3691A4483698F -:1060C00002619A4224BF436A036100238362012371 -:1060D000184670470023FBE700F0D2B84FF080432A -:1060E000586A70474FF08043002258631A610222B9 -:1060F000DA6070474FF080430022DA60704700009A -:106100004FF0804358637047FEE7000070B51B4BAB -:1061100001630025044686B0586085620E46FDF78F -:10612000CDFE04F11003C4E904334FF0FF33C4E99A -:106130000635C4E90044A560E562FFF7CFFF2B46B2 -:106140000246C4E9082304F134010D4A2565802381 -:106150002046FEF723FC0123E0600A4A0375009203 -:1061600072680192B268CDE90223074B6846CDE917 -:106170000435FEF73BFC06B070BD00BFD04D0020DB -:10618000E46A0008E96A000809610008024AD36A63 -:106190001843D062704700BF684B00204B684360D3 -:1061A0008B688360CB68C3600B6943614B69036292 -:1061B0008B6943620B6803607047000008B5264B8B -:1061C00026481A6940F2FF110A431A611A6922F43B -:1061D000FF7222F001021A611A691A6B0A431A63EC -:1061E0001A6D0A431A651E4A1B6D1146FFF7D6FF4A -:1061F00002F11C0100F58060FFF7D0FF02F13801C9 -:1062000000F58060FFF7CAFF02F1540100F58060DD -:10621000FFF7C4FF02F1700100F58060FFF7BEFFD9 -:1062200002F18C0100F58060FFF7B8FF02F1A801D0 -:1062300000F58060FFF7B2FF02F1C40100F5806055 -:10624000FFF7ACFF02F1E00100F58060FFF7A6FF69 -:10625000BDE8084000F090B800380240000002405D -:10626000F06A000808B500F0FBF9FEF74BFBFFF7FA -:1062700097F8BDE80840FEF7E3BD00007047000056 -:106280000F4B1A6C42F001021A641A6E42F00102BE -:106290001A660C4A1B6E936843F0010393604FF03B -:1062A000804353229A624FF0FF32DA6200229A61F1 -:1062B0005A63DA605A6001225A611A60704700BF5F -:1062C00000380240002004E04FF0804208B5116918 -:1062D000D3680B40D9B2C9439B07116107D530235E -:1062E00083F31188FEF734FB002383F3118808BD84 -:1062F0001F4B1A696FEAC2526FEAD2521A611A69C9 -:10630000C2F308021A614FF0FF301A695A695861E6 -:1063100000215A6959615A691A6A62F080521A62F8 -:106320001A6A02F080521A621A6A5A6A58625A6AE3 -:1063300059625A6A1A6C42F080521A641A6E42F01C -:1063400080521A661A6E0B4A106840F48070106012 -:10635000186F00F44070B0F5007F1EBF4FF480301E -:1063600018671967536823F40073536000F054B939 -:106370000038024000700040334B4FF080521A64E6 -:10638000324A4FF4404111601A6842F001021A602B -:106390001A689107FCD59A6822F003029A602A4B8A -:1063A0009A6812F00C02FBD1196801F0F90119602A -:1063B0009A601A6842F480321A601A689203FCD517 -:1063C0005A6F42F001025A671F4B5A6F9007FCD573 -:1063D0001F4A5A601A6842F080721A601B4A53685A -:1063E0005904FCD5184B1A689201FCD5194A9A60D9 -:1063F000194B1A68194B9A42194B21D1194A116845 -:10640000194A91421CD140F205121A60144A1368CD -:1064100003F00F03052BFAD10B4B9A6842F00202EE -:106420009A609A6802F00C02082AFAD15A6C42F477 -:1064300080425A645A6E42F480425A665B6E7047DC -:1064400040F20572E1E700BF0038024000700040F2 -:106450000854400700948838002004E011640020AC -:10646000003C024000ED00E041C20F41074A08B580 -:10647000536903F00103536123B1054A13680BB15B -:1064800050689847BDE80840FDF73CBD003C01401E -:10649000C0550020074A08B5536903F00203536151 -:1064A00023B1054A93680BB1D0689847BDE808400E -:1064B000FDF728BD003C0140C0550020074A08B543 -:1064C000536903F00403536123B1054A13690BB107 -:1064D00050699847BDE80840FDF714BD003C0140F5 -:1064E000C0550020074A08B5536903F008035361FB -:1064F00023B1054A93690BB1D0699847BDE80840BC -:10650000FDF700BD003C0140C0550020074A08B51A -:10651000536903F01003536123B1054A136A0BB1A9 -:10652000506A9847BDE80840FDF7ECBC003C0140CC -:10653000C0550020164B10B55C6904F478725A619E -:10654000A30604D5134A936A0BB1D06A9847600634 -:1065500004D5104A136B0BB1506B9847210604D534 -:106560000C4A936B0BB1D06B9847E20504D5094AEE -:10657000136C0BB1506C9847A30504D5054A936C76 -:106580000BB1D06C9847BDE81040FDF7BBBC00BF15 -:10659000003C0140C0550020194B10B55C6904F463 -:1065A0007C425A61620504D5164A136D0BB1506DD9 -:1065B0009847230504D5134A936D0BB1D06D9847C6 -:1065C000E00404D50F4A136E0BB1506E9847A10436 -:1065D00004D50C4A936E0BB1D06E9847620404D573 -:1065E000084A136F0BB1506F9847230404D5054A2E -:1065F000936F0BB1D06F9847BDE81040FDF782BC98 -:10660000003C0140C055002008B5FFF75DFEBDE825 -:106610000840FDF777BC0000062108B50846FDF7E5 -:106620009BFC06210720FDF797FC06210820FDF7BB -:1066300093FC06210920FDF78FFC06210A20FDF7B7 -:106640008BFC06211720FDF787FC06212820FDF78B -:1066500083FCBDE8084007211C20FDF77DBC00003D -:1066600008B5FFF745FE00F00BF8FDF729FEFDF732 -:1066700001FDFFF703FEBDE80840FFF72DBD000058 -:106680000023054A19460133102BC2E9001102F11B -:106690000802F8D1704700BFC05500200B460146E4 -:1066A000184600F02DB8000000F040B8012838BFAF -:1066B000012010B50446204600F030F830B900F053 -:1066C00007F808B900F00CF88047F4E710BD0000A7 -:1066D000024B1868BFF35B8F704700BF4056002025 -:1066E00008B5062000F084F80120FEF7F7FA000054 -:1066F000024B0A4601461868FEF780BD4C23002075 -:1067000010B5054C13462CB10A4601460220AFF3E2 -:10671000008010BD2046FCE700000000024B01464F -:106720001868FEF76FBD00BF4C230020024B0146E6 -:106730001868FEF76BBD00BF4C23002010B501396F -:106740000244904201D1002005E0037811F8014F86 -:10675000A34201D0181B10BD0130F2E72DE9F04132 -:10676000A3B1C91A17780144044603F1FF3C8C42D7 -:10677000204601D9002009E00578BD4204F101045A -:10678000F5D10CEB0405D618A54201D1BDE8F08186 -:1067900015F8018D16F801EDF045F5D0E7E700009A -:1067A0001F2938B504460D4604D9162303604FF05F -:1067B000FF3038BD426C12B152F821304BB920463F -:1067C00000F030F82A4601462046BDE8384000F087 -:1067D00017B8012B0AD0591C03D1162303600120DE -:1067E000E7E7002442F82540284698470020E0E7E4 -:1067F000024B01461868FFF7D3BF00BF4C230020AF -:1068000038B5074D00230446084611462B60FEF7B5 -:1068100069FA431C02D12B6803B1236038BD00BF65 -:1068200044560020FEF758BA034611F8012B03F82E -:10683000012B002AF9D170476F72672E617264755F -:1068400070696C6F742E663430352D4D6174656BD4 -:1068500041697273706565640000000053544D33E4 -:1068600032463F3F3F0053544D3332463430780078 -:1068700053544D3332463432780053544D333246FC -:106880003434365858000000012033000010410015 -:1068900001105A00031059000710310000000000D9 -:1068A0005C68000813040000666800081904000012 -:1068B00070680008210400007A68000840A2E4F132 -:1068C000646891060041A3E5F26569920700000043 -:1068D0004261642043414E496661636520696E648C -:1068E00065782E008000000000800000000080001D -:1068F00000000000000000000D240008F52B000837 -:10690000552B00081D240008512400084D260008BE -:106910002124000831240008252400082D24000823 -:10692000292400087525000835240008C12E000818 -:10693000452400084925000800000000F13F000838 -:10694000DD3F00081940000805400008114000081C -:10695000FD3F0008E93F0008D53F0008254000083A -:106960000000000001000000000000006330000093 -:106970006C690008C04B0020D04D00204172647546 -:1069800050696C6F740025424F415244252D424C92 -:10699000002553455249414C2500000002000000EB -:1069A000000000000D42000879420008400040004D -:1069B0007052002080520020020000000000000001 -:1069C0000300000000000000BD42000800000000BD -:1069D00010000000905200200000000001000000A4 -:1069E000000000004855002001010200DD4D0008B4 -:1069F000ED4C0008894D00086D4D00084300000073 -:106A0000046A000809024300020100C032090400C0 -:106A1000000102020100052400100105240100010B -:106A2000042402020524060001070582030800FF72 -:106A300009040100020A00000007050102400000ED -:106A4000070581024000000012000000506A0008A3 -:106A50001201100102000040091241570002010218 -:106A6000030100000403090425424F41524425005C -:106A70003031323334353637383941424344454674 -:106A80000000000000400000004000000040000046 -:106A900000400000000001000000020000000200B1 -:106AA00000000200000002000000020000000200DE -:106AB000000002000000000001440008B946000880 -:106AC0006547000840004000A8550020A855002058 -:106AD00001000000B85500208000000040010000C7 -:106AE000030000006D61696E0069646C6500000060 -:106AF000AA01A81200000000AAAAAAAA550114001F -:106B0000FFBF00008877000070A70A0000000A019C -:106B100000000000AAAAAAAA00000001FFFF0000CE -:106B200000000000990000000000A0160000000016 -:106B3000AAAAAAA600005011FFDF00000000000072 -:106B4000007708002000000000000000AAAAAAAAFE -:106B500010000000FFFF000000080000000000001F -:106B60000000000000000000AAAAAAAA000000007D -:106B7000FFFF000000000000000000000000000017 -:106B800000000000AAAAAAAA00000000FFFF00005F -:106B900000000000000000000000000000000000F5 -:106BA000AAAAAAAA00000000FFFF0000000000003F -:106BB0000000000000000000000000000A000000CB -:106BC00000000000030000000000000000000000C2 -:106BD00000000000000000000000000000000000B5 -:106BE0000000000000000000000000003496FF7F5D -:106BF0000100000000000000F6030000000000009B -:106C000000000F000000000040420F00FE2A0100BB -:106C1000D2040000FF00960000000008009600006B -:106C20000000080004000000646A00080000000082 -:106C30000000000000000000000000000000000054 -:106C400000000000502300200000000000000000B1 -:106C50000000000000000000000000000000000034 -:106C60000000000000000000000000000000000024 -:106C70000000000000000000000000000000000014 -:106C80000000000000000000000000000000000004 -:106C900000000000000000000000000000000000F4 -:086CA0000000000000000000EC +:1000000000070020F1010008D52B00088D2B000807 +:10001000B52B00088D2B0008AD2B0008F30100085C +:10002000F3010008F3010008F3010008C93B0008D0 +:10003000F3010008F3010008F3010008F3010008D0 +:10004000F3010008F3010008F3010008F3010008C0 +:10005000F3010008F30100085D61000885610008F4 +:10006000AD610008D5610008FD610008F3010008DA +:10007000F3010008F3010008F3010008F301000890 +:10008000F3010008F3010008F3010008412B000808 +:100090006D2B00087D2B0008F30100082562000885 +:1000A000F3010008F3010008F3010008F301000860 +:1000B000F9620008F3010008F3010008F3010008E9 +:1000C000F3010008F3010008F3010008F301000840 +:1000D000F3010008F3010008F3010008F301000830 +:1000E00089620008F3010008F3010008F301000829 +:1000F000F3010008F3010008F3010008F301000810 +:10010000F3010008F3010008F3010008F3010008FF +:10011000F3010008F3010008F3010008F3010008EF +:10012000F3010008F3010008F3010008F3010008DF +:10013000F3010008F3010008F3010008F3010008CF +:10014000F3010008F3010008F3010008515700080B +:10015000F3010008F3010008F3010008F3010008AF +:10016000F3010008F3010008F3010008F30100089F +:10017000F3010008F3010008F3010008F30100088F +:10018000F3010008F3010008F3010008F30100087F +:10019000F3010008F3010008F3010008F30100086F +:1001A000F3010008F3010008F3010008F30100085F +:1001B000F3010008F3010008F3010008F30100084F +:1001C000F3010008F3010008F3010008F30100083F +:1001D000F3010008F3010008F3010008F30100082F +:1001E0006915000800000000000000000000000089 +:1001F00002E000F000F8FEE772B6374880F30888A6 +:10020000364880F3098836483649086040F20000D5 +:10021000CCF200004EF63471CEF200010860BFF35C +:100220004F8FBFF36F8F40F20000C0F2F0004EF628 +:100230008851CEF200010860BFF34F8FBFF36F8F7C +:100240004FF00000E1EE100A4EF63C71CEF20001D4 +:100250000860062080F31488BFF36F8F04F040FF1E +:1002600005F024FE4FF055301F491B4A91423CBF18 +:1002700041F8040BFAE71D49184A91423CBF41F886 +:10028000040BFAE71A491B4A1B4B9A423EBF51F82E +:10029000040B42F8040BF8E700201849184A914271 +:1002A0003CBF41F8040BFAE704F01EFF05F052FED4 +:1002B000144C154DAC4203DA54F8041B8847F9E797 +:1002C00000F042F8114C124DAC4203DA54F8041B12 +:1002D0008847F9E704F006BF00070020002300204C +:1002E0000000000808ED00E00001002000070020E9 +:1002F000E068000800230020B0230020B023002085 +:1003000044560020E0010008E4010008E401000870 +:10031000E40100082DE9F04F2DED108AC1F80CD052 +:10032000C3689D46BDEC108ABDE8F08F002383F3BF +:1003300011882846A047002004F0D8F9FEE704F011 +:1003400057F900DFFEE70000F8B501F073F904F09B +:1003500061FE074604F0B0FE0546A8BB1F4B9F4256 +:1003600032D001339F4232D01D4B27F0FF029A4218 +:1003700030D1F8B200F016FF2E4642F2107400F0B1 +:1003800017FF08B10024264601F000FD20B103202C +:1003900000F07AF80024264635B1124B9F4203D074 +:1003A00004F082FE00242646002004F03DFE0EB13B +:1003B00000F080F801F09AFA00F066FF204600F0A5 +:1003C000DFF800F077F8F9E72E460024D7E7044677 +:1003D0000126D4E7064641F28834D0E7010007B091 +:1003E000000008B0263A09B008B501F0F5F8A0F110 +:1003F00020035842584108BD07B541F212030221BB +:1004000001A8ADF8043001F005F903B05DF804FB74 +:1004100038B5302383F31188174803680BB104F013 +:1004200031FA164A144800234FF47A7104F020FA86 +:10043000002383F31188124C236813B12368013B16 +:100440002360636813B16368013B63600D4D2B78D3 +:1004500033B963687BB9022001F0B2F932236360DB +:100460002B78032B07D163682BB9022001F0A8F980 +:100470004FF47A73636038BDB02300201104000884 +:10048000D0240020C8230020084B187003280CD863 +:10049000DFE800F008050208022001F087B9022019 +:1004A00001F07AB9024B00225A607047C82300203D +:1004B000D024002010B501F069FC30B1294B032293 +:1004C0001A70294B00225A6010BD284B284A1C463E +:1004D00019680131F8D004339342F9D16268254B91 +:1004E0009A42F1D9244B9B6803F1006303F58033F2 +:1004F0009A42E9D204F0ACFD04F0BEFD002001F008 +:10050000B3F80220FFF7C0FF1C4B1A6C00221A64DC +:10051000196E1A66196E596C5A64596E5A665A6E7B +:100520005A6942F080025A615A6922F080025A6187 +:100530005A691A6942F000521A611A6922F000528F +:100540001A611B6972B64FF0E0233021C3F8084DE1 +:10055000D4E9003281F311889D4683F3088810475F +:10056000B2E700BFC8230020D0240020000001080B +:1005700020000108FFFF000800230020003802408F +:100580002DE9F04F93B0AC4B00902022FF210AA838 +:100590009D6801F055F9A94A1378A3B9A84801212B +:1005A00003601170302383F3118803680BB104F0EA +:1005B00069F9A44AA24800234FF47A7104F058F96B +:1005C000002383F31188009B13B19F4B009A1A609C +:1005D0009E4A009C1378032B1EBF002313709A4A77 +:1005E0004FF0000A18BF5360D3465646D14601204B +:1005F00001F0DCF824B1944B1B68002B00F015824D +:10060000002000F0E9FF0390039B002B01DA00F0CB +:1006100083FE039B002BEDDB012001F0BDF8039B63 +:10062000213B162BE3D801A252F823F089060008DB +:10063000B106000845070008EF050008EF050008AF +:10064000EF050008CF0700089F090008B908000857 +:100650001B0900084309000869090008EF050008A4 +:100660007B090008EF050008ED09000829070008CC +:10067000EF050008310A0008950600082907000860 +:10068000EF0500081B0900080220FFF7ADFE002857 +:1006900040F0F581009B0221BAF1000F08BF1C4613 +:1006A00005A841F21233ADF8143000F0B3FF9EE715 +:1006B0004FF47A7000F090FF071EEBDB0220FFF78B +:1006C00093FE0028E6D0013F052F00F2DA81DFE833 +:1006D00007F0030A0D10133605230593042105A81E +:1006E00000F098FF17E054480421F9E75848042126 +:1006F000F6E758480421F3E74FF01C08404600F0A5 +:10070000B5FF08F104080590042105A800F082FF58 +:10071000B8F12C0FF2D1012000FA07F747EA0B0BD2 +:100720005FFA8BFB4FF0000901F0D6F826B10BF011 +:100730000B030B2B08BF0024FFF75EFE57E746486C +:100740000421CDE7002EA5D00BF00B030B2BA1D17C +:100750000220FFF749FE074600289BD0012000F049 +:1007600083FF0220FFF790FE00261FFA86F840461E +:1007700000F08AFF044690B10021404600F09CFF43 +:1007800001360028F1D1BA46044641F21213022183 +:1007900005A8ADF814303E4600F03CFF27E70120E5 +:1007A000FFF772FE2546244B9B68AB4207D92846CB +:1007B00000F05CFF013040F067810435F3E7234B24 +:1007C00000251D70204BBA465D603E46ACE7002E0A +:1007D0003FF460AF0BF00B030B2B7FF45BAF0220F9 +:1007E000FFF752FE322000F0F7FEB0F10008FFF6EE +:1007F00051AF18F003077FF44DAF0F4A926808EB32 +:10080000050393423FF646AFB8F5807F3FF742AF0E +:10081000124B0193B84523DD4FF47A7000F0DCFEF3 +:100820000390039A002AFFF635AF019B039A03F861 +:10083000012B0137EDE700BF00230020CC2400206E +:10084000B023002011040008D0240020C823002079 +:1008500004230020082300200C230020CC230020A8 +:10086000C820FFF7C1FD074600283FF413AF1F2D36 +:1008700011D8C5F1200242450AAB25F0030028BF7C +:10088000424683490192184400F0B4FF019A80481F +:10089000FF2100F0D5FF4FEAA8037D490193C8F37B +:1008A0008702284600F0D4FF064600283FF46DAFCB +:1008B000019B05EB830537E70220FFF795FD002834 +:1008C0003FF4E8AE00F018FF00283FF4E3AE002745 +:1008D000B846704B9B68BB4218D91F2F11D80A9B92 +:1008E00001330ED027F0030312AA134453F8203C1F +:1008F00005934046042205A901F000FA043780461A +:10090000E7E7384600F0B2FE0590F2E7CDF8148034 +:10091000042105A800F07EFE06E70023642104A858 +:10092000049300F06DFE00287FF4B4AE0220FFF7C0 +:100930005BFD00283FF4AEAE049800F0C5FE0590C4 +:10094000E6E70023642104A8049300F059FE002880 +:100950007FF4A0AE0220FFF747FD00283FF49AAED7 +:10096000049800F0C1FEEAE70220FFF73DFD0028F1 +:100970003FF490AE00F0D0FEE1E70220FFF734FD37 +:1009800000283FF487AE05A9142000F0CBFE042117 +:100990000746049004A800F03DFE3946B9E732202E +:1009A00000F01AFE071EFFF675AEBB077FF472AEAD +:1009B000384A926807EB090393423FF66BAE022078 +:1009C000FFF712FD00283FF465AE27F003074F4400 +:1009D000B9453FF4A9AE484600F048FE0421059011 +:1009E00005A800F017FE09F10409F1E74FF47A7049 +:1009F000FFF7FAFC00283FF44DAE00F07DFE002822 +:100A000044D00A9B01330BD008220AA9002000F031 +:100A10001FFF00283AD02022FF210AA800F010FF73 +:100A2000FFF7EAFC1C4803F067FE13B0BDE8F08F47 +:100A3000002E3FF42FAE0BF00B030B2B7FF42AAEEE +:100A40000023642105A8059300F0DAFD074600287D +:100A50007FF420AE0220FFF7C7FC804600283FF459 +:100A600019AEFFF7C9FC41F2883003F045FE059846 +:100A700000F064FF464600F02FFF3C46B7E506460F +:100A800052E64FF0000905E6BA467EE637467CE6B8 +:100A9000CC23002000230020A0860100094A13680F +:100AA00049F2690099B21B0C00FB01331360064B3D +:100AB000186844F2506182B2000C01FB0200186019 +:100AC00080B27047182300201423002010B50021A5 +:100AD0001022044600F0B4FE034B03CB206061609B +:100AE0001868A06010BD00BF107AFF1F2DE9F0410B +:100AF000ADF5507D0DF13C086EAC40F27512074625 +:100B00000D4610A80021C8F8001000F099FE4FF41F +:100B1000C4720021204600F093FE02F063F8254BDA +:100B20004FF47A72B0FBF2F0186093E807000223EA +:100B300084E807000DF5ED702382FFF7C7FF4FF241 +:100B400003631D49238406A805F0E6FC202384F8EE +:100B500032310DF2EB2606AB0DF1380C1A4603CA02 +:100B6000624530607160134606F10806F6D14146D1 +:100B70000122204600F0E4FE00230393AB7E0293A3 +:100B800005F11903019380B20123CDE9048000939C +:100B9000E97E06A3D3E90023384602F0EBFB0DF50E +:100BA000507DBDE8F08100BFAFF300809E6AC42194 +:100BB000818A46EED8240020286500082DE9F041FE +:100BC0002C4C237ADAB080460D465BBB27A9284619 +:100BD00000F0C6FF0746002842D19DF89D60C82E50 +:100BE0003ED801464FF4A662204600F029FE4FF49D +:100BF0008073C4F8F8314FF40073C4F80C334FF429 +:100C00004073C4F8203432460DF19E0104F109000E +:100C100000F0F0FD26449DF89C30777223720BB9EA +:100C2000EB7E23728122002106AC27A800F008FE8B +:100C30000122214627A800F0CFFF00230393AB7EBB +:100C4000029305F1190380B201932823CDE90440F2 +:100C50000093E97E05A3D3E90023404602F08AFB16 +:100C60005AB0BDE8F08100BFAFF300802641727238 +:100C7000DF25D7B7F8450020F0B5254E4FF48A752B +:100C800005FB0065F1B096F8D83085F8DC3000241B +:100C9000D822214685F8E8403AA800F0D1FD06F1B7 +:100CA000090000F0C5FDD5F8E4308DF8F000C2B2BF +:100CB00006AF06F109010DF1F100CDE93A3400F07B +:100CC00099FD394601223AA800F0B2FF80B2CDE981 +:100CD000047008230127CDE9023706F1D8030193F8 +:100CE00030230093317A0B4807A3D3E9002302F0A5 +:100CF00041FBA04206DD01F075FFC5F8E000384673 +:100D000071B0F0BD2046FBE778F6339F93CACD8DD6 +:100D1000F8450020F03400202DE9F0411D4D1E4E15 +:100D20001E4F86B0284602F051FB034658B30024FC +:100D3000CDE90344ADF81440027B8DF81420996886 +:100D40004068029403AA03C21B68DFF8548043F092 +:100D50000043029301F048FF821941F1000300941F +:100D600002A9384601F0F0F9A04205DD284602F05C +:100D700031FB88F80040D5E798F80030072B05D8FC +:100D8000013388F8003006B0BDE8F081014802F078 +:100D900021FBF8E7F034002040420F00203500200E +:100DA0002D4B002070B50D4614461E4602F03EFA4B +:100DB00050B9022E10D1012C0ED112A3D3E9002379 +:100DC000C5E90023012007E0282C10D005D8012C0C +:100DD00009D0052C0FD0002070BD302CFBD10BA307 +:100DE000D3E90023ECE70BA3D3E90023E8E70BA347 +:100DF000D3E90023E4E70BA3D3E90023E0E700BF36 +:100E0000AFF30080401DA12026812A0B78F6339F86 +:100E100093CACD8D9E6AC421818A46EE26417272A4 +:100E2000DF25D7B7F017304A39059E5638B5054645 +:100E30000E4C0021013500F03FFCA4F82C55B4F80D +:100E40002C0500F021FC78B1B4F82C0500F02CFC46 +:100E5000014648B9B4F82C0500F02EFCB4F82C3546 +:100E60000133A4F82C35EAE738BD00BFF84500206F +:100E700010B50A4B0A4A1A6003F5805393F86020B4 +:100E80003AB9DC6D2CB1204600F0FEFF204605F09B +:100E900083FABDE81040034800F0F6BF203500207B +:100EA000E8650008684500202DE9F04F8FB000AFDD +:100EB00005460C4602F0BAF9002849D1237E022BE0 +:100EC0001BD1E38A012B18D101F08CFE0646FFF7F7 +:100ED000E5FD03464FF4C870DFF8C482B3FBF0F2BF +:100EE00006F5167602FB103316FA83F3C8F80030C5 +:100EF000E37E33B9A34B00221A703C37BD46BDE8F0 +:100F0000F08F07F12401204600F0E8FD0028F4D11D +:100F100007F11400FFF7DAFD97F8264007F11401F6 +:100F2000224607F1270005F081FA0028E2D10F2CB4 +:100F300008D8944B1C70D8F80030A3F51673C8F885 +:100F40000030DAE797F82410284602F067F9D4E772 +:100F5000E38A282B2BD010D8012B23D0052BCCD102 +:100F6000BFF34F8F8849894BCA6802F4E06213438C +:100F7000CB60BFF34F8F00BFFDE7302BBDD1844E58 +:100F8000E17E327A9142B8D1607E3146002291F8FA +:100F9000DC50854200F0A5800132042A01F58A71F7 +:100FA000F5D1AAE721462846FFF7A0FDA5E721468F +:100FB0002846FFF703FEA0E7B2F8EC507B6005F18E +:100FC00003094FEA99094FEA8902D11DC908A8EB24 +:100FD000C1039D46EB460021584600F031FC04F168 +:100FE000EE012A463144584600F004FC7B6813B9F0 +:100FF000012000F039FB96F8D20000F045FB0446D2 +:1010000030B9307200F078FB204600F02DFBB1E0E3 +:10101000D6F8D4203AB996F8D200B6F82C258242F8 +:1010200001D8FFF703FFD6F8D4202A44944208D20F +:1010300096F8D200B6F82C250130824201D8FFF78D +:10104000F5FE70685FFA89F2594600F001FC08B9B4 +:10105000C54679E0726896F8D2002A447260D6F8E4 +:10106000D42005EB0209C6F8D49000F00DFB8145B1 +:1010700009D396F8D220D6F8D4000132001B86F8A6 +:10108000D220C6F8D400FF2D0FD80024347200F00F +:1010900033FB204600F0E8FA00F078FE3D4B188163 +:1010A00008B9FFF707FAC54627E7BB6896F8D900E5 +:1010B0000AFB0362FB68D2F8E41082F8E83001F51D +:1010C0008061C2F8E030C2F8E410FFF7D5FDFFF709 +:1010D00023FE96F8D920013202F0030286F8D920C7 +:1010E000B6E74FF48A7A0AFB02F505F1EA013144CA +:1010F000204600F0C9FDF86000287FF4FEAE3544BC +:10110000012285F8E82001F06DFDD5F8E020D6ED4C +:10111000007ADFED216A801A192838BF192040F6BD +:10112000B832904228BF1046B8EE677A07EE900AB0 +:10113000F8EEE77A67EEA67ADFED186AE7EE267A30 +:10114000FCEEE77AC6ED007A96F8D930BB60BA6853 +:1011500073680AFB02F4321992F8E81059B1D2F818 +:10116000E4108B42E8463FF427AF002182F8E810F4 +:10117000C2F8E010C5467368064A9B0A0133138122 +:10118000BBE600BFE934002000ED00E00400FA05F2 +:10119000F8450020D8240020CDCCCC3D6666663FC3 +:1011A000EC340020014B1870704700BFE42400208D +:1011B00030B54FF000542B4B22689A4285B007D0CF +:1011C00003F084FF044620BB0024204605B030BD58 +:1011D000254B627D25481A70237D03724FF480737E +:1011E000C0F8F8314FF40073C0F80C3300254FF409 +:1011F0004073C0F820341E49C0F8E450C9220930B9 +:1012000000F0F8FA2046E022294600F019FB0124FC +:10121000DBE7184A184D136C43F000731364AA6D92 +:10122000164B9A42D0D12B6E013B7E2BCCD8144A60 +:1012300007CA01AB83E807001846032100F074FDDC +:101240006B6D83424FF00003BED12A6D8A4201BF0D +:10125000AB65054B2A6E1A7003BF0A4BEA6D1A6024 +:101260001C46B2E79AAD44C5E4240020F8450020AE +:101270001600002000380240006600405041A0B037 +:10128000586600401023002037B51A4D00F07EFD4F +:1012900002236B71184B288119681848012201F04C +:1012A0003DFB00230193164B164900931648174B3C +:1012B0004FF4805201F08AFF154B197811B1124892 +:1012C00001F0ACFF01F08EFC0446FFF7E7FB4FF4A2 +:1012D000C873B0FBF3F202FB130304F5167010FAA7 +:1012E00083F00C4B186003F0E7FE08B10F232B814D +:1012F00003B030BDD824002010230020203500206A +:10130000A50D0008E8240020F0340020A90E0008F4 +:10131000E4240020EC3400202DE9F04F2DED028B69 +:101320000FF23829D9E90089834C93B00BAE9FEDB9 +:101330007E8BFFF7F1FC814FDFF828A200230A9390 +:10134000ADF834300B9373604FF0000B5B468DEDBE +:10135000008B01250DF11D0207A938468DF81C50A0 +:101360008DF81DB001F088FA9DF81C30002B40F07C +:10137000A580204601F05AFF0646002845D1704F4F +:1013800001F030FC3B6898423FD301F02BFC8246D1 +:10139000FFF784FB4FF4C873B0FBF3F202FB1303B7 +:1013A0000AF5167010FA83F03860664F97F800B0AF +:1013B000CBF1100ABBF1000F14BF33462B465FFA86 +:1013C0008AFA0EA88DF82830FFF780FBBAF1060FD5 +:1013D00028BF4FF0060A0EAB03EB0B0152460DF18E +:1013E000290000F007FA0AAB0393182302930AF1CD +:1013F0000102554BD2B2CDE90053049220464CA3D2 +:10140000D3E9002301F058FF3E7001F0EBFB4F4A97 +:101410004F4D1368C31AB3F57A7F2ED3106001F0D5 +:10142000E3FB02460B46204601F0DEFF204601F0BA +:10143000FDFE10B32B7A474E002B14BF032302236B +:10144000737101F0CFFB0EAF4FF47A730122B0FB42 +:10145000F3F039463060304600F018FB1823029351 +:101460003D4B019380B240F25513CDE903700093D8 +:1014700042464B46204601F01FFF2B7A93B101F004 +:10148000B1FB002607464FF48A7A95F8D90030441C +:1014900000F003000AFB005393F8E82092B30136F2 +:1014A000042EF2D1C82003F027F92B7A002B7FF409 +:1014B0003DAF13B0BDEC028BBDE8F08FDAF814300D +:1014C00083F48043CAF81430594610220EA800F065 +:1014D000B7F90DF11E0308AA0AA9384600F034FF37 +:1014E00096E803000FAB83E803009DF834308DF8D5 +:1014F00044300A9B0E930EA9DDE90823204602F032 +:1015000047F921E7D3F8E02042B12B68FA2B38BF26 +:10151000FA23BA1A0533B2EB430FC0D3FFF7ACFB83 +:101520000028BCD1BEE700BF0000000000000000A2 +:10153000401DA12026812A0BF034002020350020F8 +:10154000EC340020E9340020E8340020284B00204F +:10155000F8450020D82400202C4B0020F1C6A7C15C +:10156000D068080F0000024008B5054800F088FF69 +:10157000BDE80840034A0449002004F007BF00BF4B +:1015800020350020684B0020710E000870B50F4B0D +:101590001B780133DBB2012B0C4611D80C4D2968A6 +:1015A0004FF47A730E6AA2FB0332014622462846A4 +:1015B000B047844204D1074B00221A70012070BD4D +:1015C0004FF4FA7003F098F80020F8E71C2300208D +:1015D000E04D00205C4B002007B5002302460121AE +:1015E0000DF107008DF80730FFF7D0FF20B19DF80F +:1015F000070003B05DF804FB4FF0FF30F9E700008F +:101600000A4608B50421FFF7C1FF80F00100C0B20F +:10161000404208BD30B4054C2368DD69044B0A46DE +:10162000AC460146204630BC604700BFE04D00207C +:10163000A086010070B503F08FFB094E094D308084 +:10164000002428683388834208D903F07FFB2B6885 +:1016500004440133B4F5803F2B60F2D370BD00BF6A +:101660005E4B0020304B002003F024BC00F10060F2 +:1016700000F580300068704700F10060920000F5CE +:10168000803003F0AFBB0000054B1A68054B1B8888 +:101690009B1A834202D9104403F058BB00207047C4 +:1016A000304B00205E4B0020024B1B68184403F0B7 +:1016B00055BB00BF304B0020024B1B68184403F0A1 +:1016C00065BB00BF304B002010F003030AD1B0F51A +:1016D000047F05D200F10050A0F51040D0F800388A +:1016E000184670470023FBE700F10050A0F51040BA +:1016F000D0F8100A70470000064991F8243033B141 +:101700000023086A81F824300822FFF7B5BF0120C2 +:10171000704700BF344B0020014B1868704700BF72 +:10172000002004E070B5194B1D68194B0138C5F352 +:101730000B0408442D0C04221E88A6420BD15C68C1 +:101740000A46013C824213460FD214F9016F4EB192 +:1017500002F8016BF6E7013A03F10803ECD181428C +:101760000B4602D22C2203F8012B0A4A05241688C4 +:10177000AE4204D1984284BF967803F8016B013CD5 +:1017800002F10402F3D1581A70BD00BF002004E03A +:101790008C65000878650008022802BF024B4FF0F4 +:1017A00080429A61704700BF00000240022802BFD9 +:1017B000024B4FF480429A61704700BF0000024024 +:1017C000022801BF024A536983F480435361704782 +:1017D0000000024070B504464FF47A764CB1412CBB +:1017E000254628BF412506FB05F002F085FF641B56 +:1017F000F4E770BD10B50023934203D0CC5CC45411 +:101800000133F9E710BD000010B5013810F9013FB0 +:101810003BB191F900409C4203D11AB10131013A28 +:10182000F4E71AB191F90020981A10BD1046FCE7B0 +:1018300003460246D01A12F9011B0029FAD170475B +:1018400002440346934202D003F8011BFAE77047B3 +:101850002DE9F8431F4D144695F824200746884685 +:1018600052BBDFF870909CB395F824302BB920223E +:10187000FF2148462F62FFF7E3FF95F82400C0F1EF +:101880000802A24228BF2246D6B24146920005EB8A +:101890008000FFF7AFFF95F82430A41B1E44F6B27A +:1018A000082E17449044E4B285F82460DBD1FFF79A +:1018B00023FF0028D7D108E02B6A03EB8203834281 +:1018C000CFD0FFF719FF0028CBD10020BDE8F88367 +:1018D0000120FBE7344B0020024B1A78024B1A70B0 +:1018E000704700BF5C4B00201C23002010B5104C3B +:1018F000104802F057FA21460E4802F07FFA246899 +:10190000626DD2F8043843F00203C2F804384FF491 +:101910007A70FFF75FFF0849204602F075FB626DA1 +:10192000D2F8043823F00203C2F8043810BD00BF17 +:10193000D4660008E04D0020DC6600087047000017 +:101940002DE9F0470D46044600219046284640F216 +:101950007912FFF775FF234620220021284601F067 +:10196000B9FE231D02222021284601F0B3FE631D8B +:1019700003222221284601F0ADFEA31D03222521CA +:10198000284601F0A7FE04F108031022282128466A +:1019900001F0A0FE04F1100308223821284601F0CE +:1019A00099FE04F1110308224021284601F092FE1D +:1019B00004F1120308224821284601F08BFE04F1AD +:1019C000140320225021284601F084FE04F118035C +:1019D00040227021284601F07DFE04F120030822F8 +:1019E000B021284601F076FE04F121030822B82137 +:1019F000284601F06FFE04F12207C0263B4631461F +:101A000008222846083601F065FEB6F5A07F07F1EA +:101A10000107F3D104F1320308223146284601F0D0 +:101A200059FE002704F1330A94F832304FEAC7090F +:101A30009F4209F5A47615D3B8F1000F08D13146BD +:101A400004F599730722284601F044FE09F24F1667 +:101A5000274694F832213B1B93420CD3F01DC0085B +:101A6000BDE8F0870AEB070308223146284601F05B +:101A700031FE0137D8E707F23313314608222846F2 +:101A800001F028FE08360137E3E7000013B50446ED +:101A90000846002101602346C0F80310202201906F +:101AA00001F018FE0198231D0222202101F012FEF0 +:101AB0000198631D0322222101F00CFE0198A31D51 +:101AC0000322252101F006FE019804F108031022EB +:101AD000282101F0FFFD072002B010BDF7B500235B +:101AE000047F00910E4607221946054601F0B6FC18 +:101AF000731C0093012200230721284601F0AEFC4D +:101B0000C4B9B31C0093052223460821284601F0DE +:101B1000A5FC0D243746B278BB1B934211D32B7F13 +:101B2000A88A0734E408BBB9844294BF002001208E +:101B300003B0F0BDAB8ADB00083BDB08B3700824C0 +:101B4000E8E7FB1C0093214600230822284601F009 +:101B500085FC08340137DEE7201A18BF0120E7E7CB +:101B6000F7B50023047F00910E460822194605466A +:101B700001F074FC731CC4B908220093114623467B +:101B8000284601F06BFC1024012372785F1C013B96 +:101B9000934211D32B7FA88A0734E408BBB984424F +:101BA00094BF0020012003B0F0BDAB8ADB00083BEE +:101BB000DB0873700824E7E7F3190093214600233C +:101BC0000822284601F04AFC08343B46DDE7201A8B +:101BD00018BF0120E7E70000F8B50E460546144699 +:101BE000002181223046FFF72BFE2B4608220021E0 +:101BF000304601F06FFD7CB96B1C0722082130468E +:101C000001F068FD0F2401236A785F1C013B9342B9 +:101C100004D3E01DC008F8BD0824F4E7EB19214601 +:101C20000822304601F056FD08343B46ECE7000040 +:101C3000F8B50E46054614460021CE223046FFF781 +:101C4000FFFD2B4628220021304601F043FD7CB9E0 +:101C500005F1080308222821304601F03BFD30241D +:101C60002F462A7A7B1B934204D3E01DC008F8BD9F +:101C70002824F5E707F1090321460822304601F040 +:101C800029FD08340137ECE7F7B5047F00910E46D3 +:101C9000012310220021054601F0E0FBC4B9B31C6A +:101CA0000093092223461021284601F0D7FB19246E +:101CB00037467288BB1B9A4211D82B7FA88A0734FB +:101CC000E408BBB9844294BF0020012003B0F0BDFA +:101CD000AB8ADB00103BDB0873801024E8E73B1D78 +:101CE0000093214600230822284601F0B7FB083460 +:101CF0000137DEE7201A18BF0120E7E730B5094DAC +:101D00000A4491420DD011F8013B5840082340F39A +:101D10000004013B2C4013F0FF0384EA5000F6D18D +:101D2000EFE730BD2083B8EDF7B54FF0FF33DFF8B4 +:101D300054C0DFF854E000EB81011A4688421CD001 +:101D400050F8044B019401AF042417F8015B82EAB8 +:101D500005620825DB18164605F1FF355241002EB5 +:101D6000BCBF83EA0C0382EA0E0215F0FF05F1D135 +:101D7000013C14F0FF04E8D1E0E7D843D14303B0BD +:101D8000F0BD00BF9336EAA9EBE1F042F7B5384A5F +:101D9000106851686B4603C36A46364936480823C3 +:101DA00004F054FB0446002833D10A25334A106856 +:101DB00051686B4603C36A4631492F48082304F033 +:101DC00045FB0446002849D00369B3F5702F45D878 +:101DD000B0F8661040F2F63291423FD1294A0244EF +:101DE00002F15C018B4239D35C3B234900209E1AEF +:101DF000FFF784FF3246074604F164010020FFF735 +:101E00007DFFA3689F4229D1E368984208BF00255F +:101E100024E00369B3F5702F27D8418B40F2F632E6 +:101E2000914220D1174A024402F110018B4218D38B +:101E3000103B114900209D1AFFF760FF2A46064615 +:101E400004F118010020FFF759FFA3689E4202D158 +:101E5000E368984201D00D25A8E70025284603B085 +:101E6000F0BD1025A2E70C25A0E70B259EE700BFDB +:101E7000AC650008DCFF0E0000000108B565000835 +:101E800090FF0E000800FFF710B5037C044613B95D +:101E9000006804F0C3FA204610BD00000023BFF321 +:101EA0005B8FC360BFF35B8FBFF35B8F8360BFF358 +:101EB0005B8F7047BFF35B8F0068BFF35B8F70472A +:101EC00070B505460C30FFF7F5FF05F1080604462E +:101ED0003046FFF7EFFFA04206D930466D68FFF7A6 +:101EE000E9FF2544281A70BD3046FFF7E3FF201AAA +:101EF000F9E7000070B50546406898B105F10800A3 +:101F0000FFF7D8FF05F10C0604463046FFF7D2FF75 +:101F10008442304694BF6D680025FFF7CBFF013C3B +:101F20002C44201A70BD000038B50C460546FFF75A +:101F3000C7FFA04210D305F10800FFF7BBFF044420 +:101F40006868B4FBF0F100FB1144BFF35B8F012024 +:101F5000AC60BFF35B8F38BD0020FCE72DE9F0419A +:101F6000144607460D46FFF7C5FF844228BF0446C6 +:101F7000D4B1B84658F80C6B4046FFF79BFF30448D +:101F8000286040467E68FFF795FF331A9C4203D8CD +:101F90006C600120BDE8F0816B60A41B3B68AB6006 +:101FA0002044E8600220F5E72046F3E738B50C4608 +:101FB0000546FFF79FFFA04210D305F10C00FFF785 +:101FC00079FF04446868B4FBF0F100FB1144BFF3EF +:101FD0005B8F0120EC60BFF35B8F38BD0020FCE716 +:101FE0002DE9FF41884669460746FFF7B7FF6C4673 +:101FF00006B204EBC6060025B44209D06268206828 +:1020000008EB0501FFF7F6FB636808341D44F3E7AE +:1020100029463846FFF7CAFF284604B0BDE8F081DC +:10202000F8B505460C300F46FFF744FF05F10806EA +:1020300004463046FFF73EFFA042304688BF6C683A +:10204000FFF738FF201A386020B130462C68FFF7C0 +:1020500031FF2044F8BD000073B5144606460D4616 +:10206000FFF72EFF844228BF04460190DCB101A98E +:102070003046FFF7D5FF019B33B93268C5E902331B +:10208000C5E9002401200CE09C4238BF019428607F +:10209000019868608442F5D93368AB60241AEC601B +:1020A000022002B070BD2046FBE700002DE9FF4191 +:1020B0000F466946FFF7D0FF6C4600B204EBC0053F +:1020C0000026AC4209D0D4F8048054F8081BB81993 +:1020D0004246FFF78FFB4644F3E7304604B0BDE8C5 +:1020E000F081000038B50546FFF7E0FF04460146E1 +:1020F0002846FFF719FF204638BD000010B40268DB +:1021000054681A4623465DF8044B18470020704770 +:102110000020704770470000002070470E20704775 +:1021200000F5805090F8C800C0F3400070470000F0 +:1021300000F5805090F9D0007047000000F5805005 +:10214000C0F8CC1001207047F7B50C68BDF82070BE +:1021500014F0005470D10D7B082D6DD8302585F317 +:1021600011884569AE6876010CD4AC68240108D4A6 +:10217000AC6814F080545DD184F31188204603B01C +:10218000F0BD01240E6804F1180C002EB8BFF60053 +:102190004FEA0C1CB4BF46F00406760545F80C6007 +:1021A0000E680FFA84FC16F0804F18BF05EB0C1E6A +:1021B00005EB0C1C1EBFDEF8806146F00206CEF86F +:1021C00080610E7BCCF8846105EB04158E68C5F840 +:1021D0008C614E68C5F88861DCF8805145F00105D6 +:1021E000CCF8805100EB441641F268052E4405EB13 +:1021F00044150544C6E9002308350E4601F10C0CD0 +:1022000056F804EB45F804EB6645F9D1843436887A +:102210002E8000EB441407F00305267926F00B0608 +:1022200035432571002484F31188009700F0FCFCED +:102230000120A4E70224A5E74FF0FF309FE700004C +:1022400013B500F580540191E06DFFF753FE1F2890 +:102250000AD90199E06D2022FFF7C2FEA0F1200308 +:102260005842584102B010BD0020FBE708B53023AA +:1022700083F3118800F58050C06DFFF70FFE002337 +:1022800083F3118808BD0000002202608281426051 +:102290008260704710B500220023C0E900230023AC +:1022A000044603810C30FFF7EFFF204610BD00000D +:1022B000F0B5054600F580500C4690F8C83013F094 +:1022C000040FC3F3800108BF114661F3820304F1D8 +:1022D000840680F8C83005EB461389B01B79D8070F +:1022E0002ED57AB319072DD46846FFF7D3FF05EB37 +:1022F000441303F5835303F1180703AA1033186836 +:102300005968144603C40833BB422246F7D1186803 +:1023100020609B88A380DDE90E23CDE90023012303 +:10232000ADF808302B686946DB6B2846984705EB0B +:1023300046152B791A075CBF43F008032B7101E0A7 +:10234000002AF4D109B0F0BD2DE9F0479A4688B0D3 +:10235000074688469146302383F3118807F5805459 +:102360006846FFF797FFE06DFFF7AAFD1F282AD9FF +:10237000E06D20226946FFF7B5FE202823D103AD8A +:10238000444605AB2E4603CE9E4220606160354632 +:1023900004F10804F6D130682060B388A380DDE939 +:1023A0000023C9E90023BDF80830AAF80030002353 +:1023B00083F3118853464A464146384608B0BDE883 +:1023C000F04700F01FBC002080F3118808B0BDE882 +:1023D000F08700002DE9F84F0023C0E90133254BB9 +:1023E000044640F8183B0F46FFF74EFF04F1280063 +:1023F000FFF750FF04F1480804F5825546460835BA +:1024000030462036FFF746FFAE42F9D104F580553D +:102410004FF480534FF00009C5E91339C5F84880DF +:102420000123EE6504F5875804F58456C5F85490E9 +:1024300085F8583085F86030083608F108084FF004 +:10244000000A4FF0000B46E908ABA6F11800FFF7B1 +:102450001BFF203646F8289C4645F4D185F8D070FD +:1024600017B1054800F0B8FB044B63612046BDE896 +:10247000F88F00BFE8650008C065000800640040F0 +:1024800010B5044B197804464A1C1A70FFF7A2FFD6 +:10249000204610BD644B00202DE9F047002950D0A4 +:1024A000294B2A4FB7FBF1F599428CBF0A23112320 +:1024B000581EB5FBF3FC03FB1C53C4B22BB102281E +:1024C0000346F5D80020BDE8F0870CF1FF36B6F5DD +:1024D000806FF7D2C4EBC40E0EF103034FEAE30999 +:1024E000C3F3C703A4EB030809F1010A4FF47A759B +:1024F0005FFA88F009FB05555AFA88F8B5FBF8F53C +:10250000B5F5617FC1BF0EF1FF33C3F3C703E01A16 +:10251000C0B25C1C50FA84F40CFB04F4B7FBF4F476 +:10252000A142CFD1013BDBB20F2BCBD80138C0B2D7 +:102530000728C7D80021107116809170D370012030 +:10254000C1E70846BFE700BF3F420F0080DE8002C0 +:1025500070B505460E464FF47A746B695B6803F0FC +:102560000103B34207D04FF47A7002F0C5F8013C82 +:10257000F3D1204670BD0120FCE7000030B5426970 +:10258000936913F0700F16D000230B4C936103F185 +:10259000840200EB421211794D0709D5890707D54E +:1025A000416954F823508D60117941F00401117193 +:1025B0000133032BEBD130BDD465000873B51D4644 +:1025C000436916469A68D207044609D59A680121DC +:1025D0009960C2F34002CDE900650021FFF768FE73 +:1025E00063699A68D1050BD59A684FF48071996038 +:1025F000C2F34022CDE9006501212046FFF758FED5 +:1026000063699A68D2030BD59A684FF48031996058 +:10261000C2F34042CDE9006502212046FFF748FEA3 +:1026200004F58053D3F8CC0010B103681B699847B8 +:10263000204602B0BDE87040FFF7A0BFF8B50446E1 +:102640004669002972D106F10C073868800770D0FE +:1026500006EB01153868D5F8B00110F0040FD5F875 +:10266000B0011ABFC00840F00040400DA061D5F88D +:10267000B0C11CF0020F1CBF40F08040A061D5F833 +:10268000B40106EB011100F00F0084F82400D1F82A +:10269000B8012077D1F8B801000A6077D1F8B80105 +:1026A000000CA077D1F8B801000EE077D1F8BC019A +:1026B00084F82000D1F8BC01000A84F82100D1F888 +:1026C000BC01000C84F82200D1F8BC11090E84F87A +:1026D00023103821396004F1340004F1180104F1A9 +:1026E000240551F8046B40F8046BA942F9D109881C +:1026F0000180C4E90A2321460023238651F8283BA0 +:102700002046DB6B984704F5805393F8C820D3F834 +:10271000CC0042F0040283F8C82010B103681B69A2 +:1027200098472046BDE8F840FFF728BF06F110079C +:102730008BE7F8BD10B5044600F056FA02460B468A +:1027400052EA030102D0013A63F100030449086828 +:1027500020B12146BDE81040FFF770BF10BD00BF9B +:10276000604B0020F0B5302181F31188DFF848C0BC +:1027700000F583510831002404F1840500EB451570 +:102780002E7977070ED4F6060CD5D1E9007697425C +:102790009E4107D246695CF82470B7602E7946F0F6 +:1027A00004062E710134032C01F12001E4D1002331 +:1027B00083F31188F0BD00BFD465000808B530234D +:1027C00083F31188FFF7DAFE002383F3118808BD35 +:1027D000F8B543690546986800F0E050B0F1E05F55 +:1027E0000F4621D0F8B1302383F3118805F58354C7 +:1027F0001034002606F1840305EB43131B791A07F6 +:1028000006D50136032E04F12004F3D1012007E0A0 +:102810005B07F6D42146384600F040FA0028F0D194 +:10282000002383F31188F8BD0120FCE708B53023AD +:1028300083F3118800F58050C06DFFF741FB002342 +:1028400083F3118843090CBF0120002008BD00005C +:10285000F8B51D46002313700F4606461446FFF7D1 +:10286000E5FF80F00100387025B129463046FFF7BA +:10287000AFFF2070F8BD00002DE9B8410C461546A9 +:102880001F46804600F0B0F90B462178024609B990 +:10289000287850B14046FFF765FFFFF78FFF3B46B2 +:1028A0002A462146FFF7D4FF0120BDE8B881000089 +:1028B00070B5302686F31188174B1A6C42F00072FF +:1028C0001A641A6A42F000721A621A6A22F00072DE +:1028D0001A62002383F3118800F5805494F8C830FD +:1028E00013F0010516D1A9B186F311880321132035 +:1028F00001F0C8F90321142001F0C4F903211520C7 +:1029000001F0C0F994F8C83043F0010384F8C830EE +:1029100085F3118870BD00BF003802402DE9F047F3 +:1029200000F5805588B095F8D030012B04468846D4 +:10293000164600F28180814F57F823200AB947F8E4 +:102940002300D7F800A0C4F80C802674BAF1000F59 +:1029500064D095F8D030012B70D001212046FFF7CC +:10296000A7FF302383F311886269136823F0020301 +:1029700013606269136843F0010313606369002701 +:102980005F6187F3118801212046FFF7E1FD0028F0 +:1029900000F09580E86DFFF781FA04F58359BA4697 +:1029A00009F10809202200216846FEF749FF02A824 +:1029B000FFF76AFCCDF818A06A4609EB07030DF192 +:1029C000180E9446BCE80300F4451860596062464E +:1029D00003F10803F5D1DCF80000186020379CF8FB +:1029E00004201A71602FDDD195F8C8306FF382038F +:1029F000002785F8C8306A4641462046ADF8007089 +:102A0000ADF802708DF80470FFF746FD636948BBAE +:102A10004FF400421A6008B0BDE8F08741F2D800D8 +:102A200003F0BCFC814610B15146FFF7D3FCC7F858 +:102A30000090B9F1000F8CD10020ECE738680368F2 +:102A40001B6B98470146002887D13868FFF730FF95 +:102A50003868036832465B684146984700287FF42F +:102A60007CAFE9E761221A609DF802309DF80320EF +:102A70001B06120402F4702203F040731343BDF8E6 +:102A80000020C2F3090213439DF804201205022E10 +:102A900002F4E0020CBF4FF00041002113436269D1 +:102AA0000B43D361636913225A616269136823F08F +:102AB0000103136039462046FFF74AFD08B96369F0 +:102AC000A6E795F8D03093BB6169D1F8002242F0B7 +:102AD0000102C1F800226169D1F8002222F47C527F +:102AE00022F00E02C1F800226169D1F8002242F4FE +:102AF0006062C1F800226269C2F814326269C2F8E9 +:102B00000432626941F6FF71C2F80C126269C2F8C0 +:102B100040326269C2F8443263690122C3F81C2260 +:102B20006269D2F8003223F00103C2F8003295F84E +:102B3000C83043F0020385F8C8306CE7604B0020D2 +:102B400008B500F051F850EA0103024602D0421ED7 +:102B500061F10001044B186810B10B46FFF72EFD20 +:102B6000BDE8084001F064B8604B002008B50020C3 +:102B7000FFF7E0FDBDE8084001F05AB808B50120B4 +:102B8000FFF7D8FDBDE8084001F052B800B59BB092 +:102B9000EFF3098168226846FEF72CFEEFF3058308 +:102BA000014B9B6BFEE700BF00ED00E008B5FFF7AF +:102BB000EDFF000000B59BB0EFF309816822684685 +:102BC000FEF718FEEFF30583014B5B6BFEE700BFDA +:102BD00000ED00E0FEE700000FB408B5029801F038 +:102BE00031FDFEE702F0B4B902F096B913B56C46B8 +:102BF00084E80600031D94E8030083E80500012033 +:102C000002B010BD73B58568019155B11B885B0793 +:102C100007D4D0E900369B6B9847019AC1B2304681 +:102C2000A847012002B070BDF0B5866889B005469E +:102C30000C465EB1BDF838305B070AD4D0E90037E6 +:102C40009B6B98472246C1B23846B047012009B075 +:102C5000F0BD00220023CDE900230023ADF80830A9 +:102C60000A4603AB01F10806106851681C4603C40C +:102C70000832B2422346F7D1106820609288A280C1 +:102C8000FFF7B2FF0423ADF808302B68CDE900014F +:102C9000DB6B694628469847D8E7000030B50368E3 +:102CA0000968DD0FB5EBD17F23F0604421F060426D +:102CB0004FEAD1700BD0002BB8BFA40C0029B8BFCD +:102CC000920C944202D034BF0120002030BD9442C7 +:102CD00005D1C1F38070C3F380738342F6D194426F +:102CE0002CBF00200120F1E72DE9F041456A15B91C +:102CF0004162BDE8F0814B6823F06047C3F38A4628 +:102D00004FEAD37EC3F3807816EA230638BF3E46E7 +:102D1000AC462B465A68BEEBD27F22F060440AD004 +:102D2000002A18DAA40CB44217D19D420FD10D60CD +:102D3000DEE71346EEE7A74207D102F08044C2F374 +:102D4000807242450BD054B1EFE708D2EDE7CCF8E2 +:102D500000100B60CDE7B44201D0B442E5D81A6848 +:102D60009C46002AE5D11960C3E700002DE9F04731 +:102D7000089D01F007044FEAD508224405F0070535 +:102D800000EBD1004FF47F49944201D1BDE8F087B8 +:102D900004F0070705F0070A57453E4638BF564678 +:102DA000C6F10806111B8E4228BF0E46E10808EB4B +:102DB000D50E415C13F80EC0B94029FA06F721FA86 +:102DC0000AF1FFB28CEA010147FA0AF739408CEAAE +:102DD000010C03F80EC034443544D5E780EA0120E5 +:102DE000082341F2210201B24000002980B203F120 +:102DF000FF33B8BF504013F0FF03F4D17047000019 +:102E000038B50C468D18A54200D138BD14F8011B09 +:102E1000FFF7E4FFF7E7000042684AB11368436038 +:102E20004389818901339BB29942438138BF8381B1 +:102E30001046704770B588B0202204460D4668469B +:102E40000021FEF7FDFC20460495FFF7E5FF024652 +:102E500058B16B46054608AE1C4603CCB442286008 +:102E60006960234605F10805F6D1104608B070BD2B +:102E7000082817D909280CD00A280CD00B280CD008 +:102E80000C280CD00D280CD00E2814BF4020302068 +:102E900070470C207047102070471420704718208E +:102EA0007047202070470000082817D90C280CD93B +:102EB00010280CD914280CD918280CD920280CD982 +:102EC00030288CBF0F200E207047092070470A2041 +:102ED00070470B2070470C2070470D207047000092 +:102EE0002DE9F843078C072F04461ED9D0E9029834 +:102EF00000254FF6FF73C5F12006A5F1200029FA41 +:102F000005F108FA06F628FA00F031430143C9B288 +:102F10001846FFF763FF0835402D0346EBD1E16902 +:102F20003A46BDE8F843FFF76BBF4FF6FF70BDE8C8 +:102F3000F883000010B54B6823B9CA8A63F309020D +:102F4000CA8210BD04691A681C600361C38A013B10 +:102F5000C3824A60EFE700002DE9F84F1D46CB8A97 +:102F60000F46C3F309010529814692460B4630D02E +:102F70000020AAB207F11A049EB2042E1FFA80F8AC +:102F80000FD8904503F1010306D3FB8A0A4462F38C +:102F90000903FB8201201AE01AF80060E6540130B0 +:102FA000EAE79045F1D2A1F1050B1C237C68BBFB3D +:102FB000F3F203FB12BB1FFA8BF6002C45D14846F7 +:102FC000FFF72AFF044638B978606FF00200BDE8C9 +:102FD000F88F4FF00008E6E7002606607860ADB293 +:102FE0004FF0000B454510D90AEB0803221D13F8DA +:102FF000011B9155B1B208F101081B291FFA88F88D +:103000002BD0454506F10106F1D8FB8AC3F309022E +:10301000154465F30903BCE7013292B21C462368EC +:10302000002BF9D16B1F0B441C21B3FBF1F30133CF +:103030009BB29A42D3D2BBF1000FD0D14846FFF7E2 +:10304000EBFE20B9C4F800B0BFE70122E7E7C0F803 +:1030500000B05E4620600446C1E74545D5D94846E4 +:10306000FFF7DAFE08B92060AFE7C0F800B000262D +:1030700020600446B6E700002DE9F04F2DED028BED +:103080001C4683B05B69019207468846002B00F01E +:103090009A80238C2BB1E269002A00F09480072BE0 +:1030A00035D807F10C00FFF7B7FE054638B96FF0C9 +:1030B0000205284603B0BDEC028BBDE8F08F142258 +:1030C0000021FEF7BDFB228CE16905F10800FEF747 +:1030D00091FB208C013080B2FFF7E6FEFFF7C8FEBF +:1030E000013880B22084013028746369228C1B78F7 +:1030F0002A4403F01F0363F03F0348F000411372BA +:10310000384669602946FFF7EFFD0125D1E700F158 +:103110000C034FF0000908EE103A4FF0800A4E46BB +:103120004D4618EE100AFFF777FE83460028BED002 +:1031300014220021FEF784FB002E3AD1019BABF84C +:10314000083002220BF1080E1FFA82FC0CF101007C +:10315000BCF1060F218C80B201D88E422BD3FFF731 +:10316000A3FEFFF785FE62691278013802F01F02A4 +:103170008E4208BF4FF0400A42EA49121BFA80F122 +:103180004AEA020A013048F0004281F808A08BF8B0 +:103190001000CBF8042059463846FFF7A5FD238CD4 +:1031A0000135B3422DB289F001094FF0000AB8D1C0 +:1031B0007FE70022C6E7E169895D0EF8021001365B +:1031C000B6B20132C0E76FF0010572E7F8B51546F7 +:1031D0000E463022002104461F46FEF731FB069BB7 +:1031E0006360B5F5001F079BA76034BF6A094FF6FF +:1031F000FF72A36297B2E66104F1100000239A42C5 +:1032000006D800230360A782E3822383E360F8BD2E +:103210000660013330462036F1E7000003781BB921 +:103220004BB2002BC8BF0170704700000078704798 +:10323000F8B50C46C969074611B9238C002B37D164 +:10324000257E1F2D34D8387828BB228C072A2CD80D +:10325000268A36F003032BD14FF6FF70FFF7D0FD1F +:1032600020F001003102400441EA0561400C41EACE +:1032700040254FF6FF72234629463846FFF7FCFEED +:10328000002807DD626913780133DBB21F2B88BF8A +:1032900000231370F8BD218A2D0645EA0125054358 +:1032A0002046FFF71DFE0246E5E76FF00300F1E759 +:1032B0006FF00100EEE7000070B58AB004461646D4 +:1032C0000021282268461D46FEF7BAFABDF83830BC +:1032D000ADF810300F9B05939DF840308DF81830F5 +:1032E000119B07936946BDF84830ADF82030204661 +:1032F000CDE90265FFF79CFF0AB070BD2DE9F041F2 +:10330000D36905460C4616460BB9138C5BBB377E5A +:103310001F2F28D895F80080B8F1000F26D030462E +:10332000FFF7DEFD3378210241EAC33141EA0801AB +:10333000338A41EA076141EA03410246334641F0DC +:1033400080012846FFF798FE00280ADD3378012B1C +:1033500007D1726913780133DBB21F2B88BF0023BA +:103360001370BDE8F0816FF00100FAE76FF0030021 +:10337000F7E70000F0B58BB004460D461746002174 +:10338000282268461E46FEF75BFA9DF84C305A1E0E +:10339000534253418DF800309DF84030ADF8103065 +:1033A000119B05939DF848308DF81830149B0793B6 +:1033B0006A46BDF85430ADF8203029462046CDE9A4 +:1033C0000276FFF79BFF0BB0F0BD0000406A00B132 +:1033D00004307047436A1A68426202691A600361E6 +:1033E000C38A013BC38270472DE9F041D0F82080A9 +:1033F000194E14461D464146002709B9BDE8F08123 +:10340000D1E90223A21A65EB0303964277EB03038B +:103410001ED2036A8B420DD1FFF78CFD036A1B6835 +:10342000036203690B60C38A0161016A013BC382C5 +:103430008846E2E7FFF77EFD0B68C8F800300369B5 +:103440000B60C38A0161013BC382D8F80010D4E746 +:1034500088460968D1E700BF80841E002DE9F04F3F +:103460008BB00D46DDF8509014469B4680460028F0 +:1034700000F01981B9F1000F00F01581531E3F2BA8 +:1034800000F21181012A03D1BBF1000F40F00B8142 +:103490000023CDE90833B8F81430B5EBC30F4FEA79 +:1034A000C30703D300200BB0BDE8F08F2B199F4258 +:1034B000D8F80C303ABF7F1BFFB227461BB9D8F8AB +:1034C0001030002B7AD0272D4ED8C5F12806B742F0 +:1034D0004FF000032CBFF6B23E4600932946D8F8C1 +:1034E000080008AB3246FFF741FCA7EB060A35445B +:1034F0005FFA8AFAB8F8143003F10053053BDB0099 +:103500000493D8F80C3003932821039B13B1BAF12C +:10351000000F2CD1D8F8100040B1BAF1000F05D03F +:10352000009608AB5246691AFFF720FC38B2002F0C +:10353000B8D066070AD00AAB03EBD401624211F897 +:10354000083C02F00702134101F8083C082C3CD962 +:10355000102C40F2B580202C40F2B780BBF1000F58 +:1035600000F09C80082334E0BA460026C2E7049BA2 +:10357000E02B28BFE02306930B44AB42059314D9FC +:103580005A1B03980096924534BF5246D2B2691A2C +:1035900008AB04300792FFF7E9FB079A1644AAEB41 +:1035A000020A1544F6B25FFA8AFA049B069A059954 +:1035B0009B1A0493039B1B680393A6E70093D8F818 +:1035C000080008AB3A462946AEE7BBF1000F13D01E +:1035D0000123B4EBC30F6CD0082C12D89DF8203017 +:1035E000621E23FA02F2D50706D54FF0FF3202FA27 +:1035F00004F423438DF820309DF8203089F8003002 +:1036000051E7102C12D8BDF82030621E23FA02F2C6 +:10361000D10706D54FF0FF3202FA04F42343ADF888 +:103620002030BDF82030A9F800303CE7202C0FD81E +:103630000899631E21FA03F3DA0705D54FF0FF322C +:1036400002FA04F40C430894089BC9F800302AE7F6 +:10365000402C2BD0DDE90865611EC4F12102A4F1E4 +:10366000210326FA01F105FA02F225FA03F31143C8 +:103670001943CB0712D50122A4F12003C4F1200184 +:1036800002FA03F322FA01F1A240524243EA010393 +:1036900063EB430332432B43CDE90823DDE90823E1 +:1036A000C9E90023FFE66FF00100FCE66FF00800B7 +:1036B000F9E6082CA0D9102CB3D9202CEED8C3E7FA +:1036C000BBF1000FADD0022383E7BBF1000FBBD0ED +:1036D00004237EE730B5012A144638BF0124402C6C +:1036E00085B028BF40240025012ACDE9025518D80D +:1036F0001B788DF8083063070AD004AB03EBD405C0 +:10370000624215F8083C02F00702934005F8083CB5 +:10371000009103462246002102A8FFF727FB05B0CF +:1037200030BD082AE4D9102A03D81B88ADF8083028 +:10373000E1E7202A8DBFD3E900231B680293CDE97E +:103740000223D8E710B5CB681BB98B600B618B8265 +:1037500010BD04691A681C600361C38A013BC382FF +:10376000CA60F0E703064CBFC0F3C03002207047C8 +:1037700008B50246FFF7F6FF022806D15306C2F34A +:103780000F2001D100F0030008BDC2F30740FBE7A2 +:103790002DE9F04F93B0CDE903230A6804461046A3 +:1037A000FFF7E0FF022814BFC2F306260026002A16 +:1037B0000D46824680F2F28112F0C04940F0EE815F +:1037C000097B002900F0EA81022803D02378B34264 +:1037D00040F0E781C2F304630693104602F07F03D2 +:1037E0000593FFF7C5FF059B29444FEA834848EA44 +:1037F0000A4848EA4668CE7800230022CDE908232B +:10380000F309834648EA0008029367D0059B0093BA +:1038100002466768534608A92046B847002800F0CA +:10382000C381276A4FB9414604F10C00FFF702FB40 +:10383000074690B96FF0020054E03B6998450DD0FF +:103840003F68002FF9D1414604F10C00FFF7F2FA6E +:1038500007460028EED0236A3B60276297F817C01E +:1038600006F01F08CCF3840CACEB08001FFA80FEB6 +:103870000028B8BF0EF12000A8EB0C031FFA83FE4E +:10388000D7E90221B8BF00B2002B0793BEBF0EF1EB +:1038900020031BB2079352EA010338D0039BDFF8E1 +:1038A00024E39A1A049B4FF0000C63EB0101964548 +:1038B0007CEB01032BD36B7B97F81AE0734519D18E +:1038C000029B002B78D0012821DC7868F8B9DFF85A +:1038D000F0C2944570EB010316D337E0276A27B98D +:1038E0006FF00C0013B0BDE8F08F3B699845B5D080 +:1038F0003F68F4E7B24890427CEB010301D300201B +:10390000F0E7029B002BFAD0079B0F2B17DCFA7D08 +:10391000B30002F0030203F07C031343FB75394646 +:103920002046FFF707FB6B7BBB76029B3BB9FB7D19 +:10393000C3F38402013262F38603FB75D0E76A7B2E +:10394000BB7E9A42DBD1029B002B35D0B309022B00 +:1039500032D0039BBB60049BFB60142200210DA8A6 +:10396000FDF76EFF039B0A93049B0B932B1D0C9397 +:103970002B7BADF83EB0013BDBB2ADF83C30069B93 +:103980008DF84230059B8DF8433094F82C308DF83B +:1039900040A083F001038DF844308DF84180A36886 +:1039A0000AA920469847FB7DC3F38403013303F043 +:1039B0001F039B02FB82A2E7FB7DC6F34012B2EB22 +:1039C000D31F40F0F480C3F38403434540F0F280FA +:1039D000029A2B7BB609002A4DD0F2075DD4032B47 +:1039E00040F2EB80039BBB60049BFB602B7BAE1D16 +:1039F000033BDBB23246394604F10C00FFF7ACFA68 +:103A000000280CDA39462046FFF794FAFB7DC3F311 +:103A10008403013303F01F039B02FB820AE7DDE905 +:103A20000884AB883B834FF6FF73C9F12000A9F1EE +:103A3000200228FA09F104FA00F0014324FA02F204 +:103A400011431846C9B2FFF7C9F909F10809B9F1DC +:103A5000400F0346E9D1B8822A7B033AD2B23146FD +:103A6000FFF7CEF9FB7DB882DA43C2F3C01262F3EE +:103A7000C713FB7543E786B92E1D013BDBB2324607 +:103A8000394604F10C00FFF767FA0028BADB2A7BFD +:103A9000B88A013AD2B23146E2E7F98AC1F30901A4 +:103AA000013B0429DAB25BD8281D002307F11B066D +:103AB0009A4208D910F801CB06F801C00131013350 +:103AC0000529DBB2F4D103990A9104990B91934231 +:103AD00007F11B010C9138BF043379680D9134BF95 +:103AE00055FA83F300230E93FB8AADF83EB0C3F37F +:103AF00009031A44069B8DF84230059B8DF843302C +:103B000094F82C30ADF83C2083F001038DF844305C +:103B100000238DF840A08DF841807B602A7BB88A15 +:103B2000013A291DFFF76CF93B8BB882834203D120 +:103B3000A3680AA92046984720460AA9FFF702FE73 +:103B4000FB7DBA8AC3F38403013303F01F039B0296 +:103B5000FB823B8B9A420CBF00206FF01000C1E645 +:103B60007B68002BAFD0052001E01C3033461E6877 +:103B7000002EFAD1091A081D2E1D184401EB090C5C +:103B8000BCF11B0F5FFA89F39DD89A429BD916F8B6 +:103B9000013B00F8013B09F10109EFE76FF0090073 +:103BA000A0E66FF00A009DE66FF00B009AE66FF05A +:103BB0000D0097E66FF00E0094E66FF00F0091E6AF +:103BC00040420F0080841E00EFF3098305494A6BD1 +:103BD00022F001024A63683383F30988002383F3E8 +:103BE0001188704700EF00E0302080F3118862B642 +:103BF0000C4B0D4AD96821F4E0610904090C0A4311 +:103C0000DA60D3F8FC20094942F08072C3F8FC2046 +:103C10000A6842F001020A602022DA7783F8220063 +:103C2000704700BF00ED00E00003FA05001000E05F +:103C300010B5302383F311880E4B5B6813F40063D7 +:103C400014D0F1EE103AEFF30984683C4FF0807322 +:103C5000E361094BDB6B236684F3098800F0BCFC4D +:103C600010B1064BA36110BD054BFBE783F3118830 +:103C7000F9E700BF00ED00E000EF00E03F030008BF +:103C80004203000800F1604303F561430901C9B232 +:103C900083F80013012200F01F039A4043099B00A0 +:103CA00003F1604303F56143C3F880211A60704754 +:103CB000026843681143016003B118477047000070 +:103CC00013B5446BD4F894341A681178042915D1CB +:103CD000217C022912D11979128901238B401342C8 +:103CE0000CD101A904F14C0001F09CFFD4F89444DC +:103CF000019B21790246206800F0D0F902B010BD86 +:103D0000143001F01FBF00004FF0FF33143001F0FA +:103D100019BF00004C3001F0F1BF00004FF0FF333D +:103D20004C3001F0EBBF0000143001F0EDBE00009C +:103D30004FF0FF31143001F0E7BE00004C3001F0CD +:103D4000BDBF00004FF0FF324C3001F0B7BF0000A4 +:103D50000020704710B5D0F894341A6811780429FF +:103D6000044617D1017C022914D1597952890123C3 +:103D70008B4013420ED1143001F080FE024648B150 +:103D8000D4F894444FF4807361792068BDE8104002 +:103D900000F072B910BD0000406BFFF7DBBF000000 +:103DA000704700007FB5124B036000234360C0E9F9 +:103DB0000233012502260F4B05740446029001933D +:103DC00000F18402294600964FF48073143001F00C +:103DD00031FE094B0294CDE9006304F523724FF4E0 +:103DE0008073294604F14C0001F0F8FE04B070BD68 +:103DF00028660008993D0008C13C00080B68302285 +:103E000082F311880A7903EB820290614A790932C0 +:103E100043F822008A7912B103EB820398610223EE +:103E2000C0F894140374002080F3118870470000D8 +:103E300038B5037F044613B190F85430ABB9201D58 +:103E400001250221FFF734FF04F1140025776FF0FC +:103E5000010100F079FC84F8545004F14C006FF03B +:103E60000101BDE8384000F06FBC38BD10B501213C +:103E700004460430FFF71CFF0023237784F85430F6 +:103E800010BD000038B504460025143001F0EAFDED +:103E900004F14C00257701F0B9FE201D84F8545040 +:103EA0000121FFF705FF2046BDE83840FFF752BF6C +:103EB00090F8443003F06003202B07D190F84520A0 +:103EC000212A4FF0000303D81F2A06D8002070478C +:103ED000222AFBD1C0E90E3303E0034A82630722A2 +:103EE000C2630364012070471D23002037B5D0F85A +:103EF00094341A681178042904461AD1017C0229E5 +:103F000017D11979128901238B40134211D100F185 +:103F10004C05284601F03AFF58B101A9284601F0A6 +:103F200081FED4F89444019B21790246206800F078 +:103F3000B5F803B030BD0000F0B500EB810385B0EB +:103F40009E6904460D46FEB1302383F3118804EBCD +:103F50008507301D0821FFF7ABFEFB685B691B6816 +:103F600006F14C001BB1019001F06AFE019803A913 +:103F700001F058FE024648B1039B2946204600F056 +:103F80008DF8002383F3118805B0F0BDFB685A69F2 +:103F90001268002AF5D01B8A013B1340F1D104F1CD +:103FA0004402EAE7093138B550F82140DCB130234A +:103FB00083F31188D4F894241368527903EB8203B5 +:103FC000DB689B695D6845B104216018FFF770FEEE +:103FD000294604F1140001F05BFD2046FFF7BAFE0C +:103FE000002383F3118838BD7047000001F0D0B87A +:103FF000012303700023C0E90133C36183620362BC +:10400000C36243620363704738B50446302383F3C9 +:1040100011880025C0E90355C0E90555416001F04C +:10402000C7F80223237085F31188284638BD0000A5 +:1040300070B500EB810305465069DA600E46144600 +:1040400018B110220021FDF7FBFBA06918B1102266 +:104050000021FDF7F5FB31462846BDE8704001F030 +:1040600071B90000826802F0011282600022C0E98A +:104070000422826101F0F2B9F0B400EB81044789B7 +:10408000E4680125A4698D403D43458123600023F8 +:10409000A2606360F0BC01F00DBA0000F0B400EB68 +:1040A00081040789E468012564698D403D430581E9 +:1040B00023600023A2606360F0BC01F087BA0000B7 +:1040C00070B50223002504460370C0E90255C0E91B +:1040D0000455C564856180F8345001F0CFF86368F9 +:1040E0001B6823B129462046BDE87040184770BDC3 +:1040F0000378052B10B504460AD080F8503005230C +:10410000037043681B680BB1042198470023A36028 +:1041100010BD00000178052906D190F850204368B1 +:1041200002701B6803B118477047000070B590F823 +:104130003430044613B1002380F8343004F14402D3 +:10414000204601F0ADF963689B68B3B994F8443038 +:1041500013F0600535D00021204601F04DFC002110 +:10416000204601F03FFC63681B6813B1062120461E +:104170009847062384F8343070BD204698470028BD +:10418000E4D0B4F84A30E26B9A4288BFE36394F912 +:104190004430E56B002B4FF0300380F20381002D9B +:1041A00000F0F280092284F8342083F31188002182 +:1041B000D4E90E232046FFF771FF002383F3118813 +:1041C000DAE794F8452003F07F0343EA022340F244 +:1041D0000232934200F0C58021D8B3F5807F48D0E9 +:1041E0000DD8012B3FD0022B00F09380002BB2D1D1 +:1041F00004F14C02A2630222E2632364C1E7B3F537 +:10420000817F00F09B80B3F5407FA4D194F84630C5 +:10421000012BA0D1B4F84C3043F0020332E0B3F5E7 +:10422000006F4DD017D8B3F5A06F31D0A3F5C063A0 +:10423000012B90D8636894F846205E6894F8471084 +:10424000B4F848302046B047002884D04368A363C0 +:104250000368E3631AE0B3F5106F36D040F602420C +:1042600093427FF478AF5C4BA3630223E3630023A4 +:10427000C3E794F84630012B7FF46DAFB4F84C30AF +:1042800023F00203C4E90E55A4F84C30256478E706 +:10429000B4F84430B3F5A06F0ED194F8463084F8EA +:1042A0004E30204601F042F863681B6813B10121CB +:1042B00020469847032323700023C4E90E339CE76C +:1042C00004F14F03A3630123C3E72378042B10D128 +:1042D000302383F311882046FFF7C4FE85F311884D +:1042E0000321636884F84F5021701B680BB120468E +:1042F000984794F84630002BDED084F84F300423E2 +:10430000237063681B68002BD6D002212046984793 +:10431000D2E794F848301D0603F00F0120460AD575 +:1043200001F0B0F8012804D002287FF414AF2B4B21 +:104330009AE72B4B98E701F097F8F3E794F84630AB +:10434000002B7FF408AF94F8483013F00F01B3D07E +:104350001A06204602D501F063FBADE701F056FBDB +:10436000AAE794F84630002B7FF4F5AE94F8483075 +:1043700013F00F01A0D01B06204602D501F03CFB34 +:104380009AE701F02FFB97E7142284F8342083F397 +:1043900011882B462A4629462046FFF76DFE85F3F5 +:1043A0001188E9E65DB1152284F8342083F3118881 +:1043B0000021D4E90E232046FFF75EFEFDE60B2226 +:1043C00084F8342083F311882B462A462946204658 +:1043D000FFF764FEE3E700BF586600085066000878 +:1043E0005466000838B590F834300446002B3ED0AF +:1043F000063BDAB20F2A34D80F2B32D8DFE803F0AD +:1044000037313108223231313131313131313737C1 +:10441000C56BB0F84A309D4214D2C3681B8AB5FB05 +:10442000F3F203FB12556DB9302383F311882B4649 +:104430002A462946FFF732FE85F311880A2384F8BD +:1044400034300EE0142384F83430302383F31188A1 +:1044500000231A4619462046FFF70EFE002383F379 +:10446000118838BD036C03B198470023E7E70021AA +:10447000204601F0C1FA0021204601F0B3FA63683A +:104480001B6813B10621204698470623D7E7000092 +:1044900010B590F83430142B044629D017D8062BC9 +:1044A00005D001D81BB110BD093B022BFBD8002160 +:1044B000204601F0A1FA0021204601F093FA63683A +:1044C0001B6813B1062120469847062319E0152BD7 +:1044D000E9D10B2380F83430302383F31188002393 +:1044E0001A461946FFF7DAFD002383F31188DAE74D +:1044F000C3689B695B68002BD5D1036C03B19847F7 +:10450000002384F83430CEE7002303758268036902 +:104510001B6899689142FBD25A6803604260106040 +:104520005860704700230375826803691B689968A7 +:104530009142FBD85A68036042601060586070472F +:1045400008B50846302383F311880B7D032B05D073 +:10455000042B0DD02BB983F3118808BD8B69002281 +:104560001A604FF0FF338361FFF7CEFF0023F2E7BD +:10457000D1E9003213605A60F3E70000FFF7C4BFCF +:10458000054BD9680875186802681A6053600122E3 +:104590000275D860FBF7BEBE704B002030B50C4BE7 +:1045A000DD684B1C87B004460FD02B46094A68468D +:1045B00000F05EF92046FFF7E3FF009B13B1684669 +:1045C00000F060F9A86907B030BDFFF7D9FFF9E73F +:1045D000704B002041450008044B1A68DB68906866 +:1045E0009B68984294BF002001207047704B0020C8 +:1045F000084B10B51C68D86822681A605360012205 +:104600002275DC60FFF78EFF01462046BDE81040B2 +:10461000FBF780BE704B002038B5074C07490848AF +:10462000012300252370656001F0E8FB022323705D +:1046300085F3118838BD00BFD84D002060660008A2 +:10464000704B002008B572B6044B186500F046FCAC +:1046500000F0FCFC024B03221A70FEE7704B0020B6 +:10466000D84D002000F044B9034A516853685B1AE2 +:104670009842FBD8704700BF001000E08B60022317 +:1046800008618B82084670478368A3F1840243F86F +:10469000142C026943F8442C426943F8402C094A1F +:1046A00043F8242CC26843F8182C022203F80C2C7F +:1046B000002203F80B2C044A43F8102CA3F120002D +:1046C000704700BF2D030008704B002008B5FFF7AE +:1046D000DBFFBDE80840FFF751BF0000024BDB687D +:1046E00098610F20FFF74CBF704B0020302383F3FD +:1046F0001188FFF7F3BF000008B50146302383F3AC +:1047000011880820FFF74AFF002383F3118808BDB2 +:10471000064BDB6839B1426818605A601360436029 +:104720000420FFF73BBF4FF0FF307047704B002075 +:104730000368984206D01A68026050609961184672 +:10474000FFF71CBF7047000038B504460D462068CF +:10475000844200D138BD036823605C608561FFF747 +:104760000DFFF4E710B503689C68A2420CD85C68A2 +:104770008A600B604C602160596099688A1A9A605F +:104780004FF0FF33836010BD1B68121BECE7000085 +:104790000A2938BF0A2170B504460D460A26601959 +:1047A00001F026FB01F012FB041BA54203D8751C87 +:1047B0002E460446F3E70A2E04D9BDE870400120D6 +:1047C00001F05CBB70BD0000F8B5144B0D46D9611B +:1047D00003F1100141600A2A1969826038BF0A2278 +:1047E000016048601861A818144601F0F3FA0A271E +:1047F00001F0ECFA431BA342064606D37C1C2819A1 +:1048000001F0F6FA27463546F2E70A2F04D9BDE84B +:10481000F840012001F032BBF8BD00BF704B002012 +:10482000F8B506460D4601F0D1FA0F4A134653F883 +:10483000107F9F4206D12A4601463046BDE8F84027 +:10484000FFF7C2BFD169BB68441A2C1928BF2C4698 +:10485000A34202D92946FFF79BFF2246314603486F +:10486000BDE8F840FFF77EBF704B0020804B002072 +:1048700010B4C0E9032300235DF8044B4361FFF744 +:10488000CFBF000010B5194C236998420DD0D0E974 +:104890000032816813605A609A680A449A60002363 +:1048A00003604FF0FF33A36110BD2346026843F855 +:1048B000102F53600022026022699A4203D1BDE8A2 +:1048C000104001F08FBA936881680B44936001F047 +:1048D0007DFA2269E1699268441AA242E4D911443E +:1048E000BDE81040091AFFF753BF00BF704B00200E +:1048F0002DE9F047DFF8BC8008F110072C4ED8F8FE +:10490000105001F063FAD8F81C40AA68031B9A42C1 +:104910003ED81444D5E900324FF00009C8F81C40D5 +:1049200013605A60C5F80090D8F81030B34201D136 +:1049300001F058FA89F31188D5E9033128469847E0 +:10494000302383F311886B69002BD8D001F03EFA35 +:104950006A69A0EB04094A4582460DD2022001F0A3 +:104960008DFA0022D8F81030B34208D151462846BB +:10497000BDE8F047FFF728BF121A2244F2E712EB16 +:10498000090938BF4A4629463846FFF7EBFEB5E726 +:10499000D8F81030B34208D01444211AC8F81C00CB +:1049A000A960BDE8F047FFF7F3BEBDE8F08700BFA0 +:1049B000804B0020704B002038B501F007FA054A03 +:1049C000D2E90845031B181945F10001C2E90801A5 +:1049D00038BD00BF704B002000207047FEE700008C +:1049E000704700004FF0FF307047000002290CD0E4 +:1049F000032904D00129074818BF00207047032A63 +:104A000005D8054800EBC2007047044870470020F5 +:104A1000704700BF386700082C230020EC660008B0 +:104A200070B59AB00546084601A9144600F0C2F8D0 +:104A300001A8FCF7FDFE431C5B00C5E90034002221 +:104A4000237003236370C6B201AB02341046D1B2A7 +:104A50008E4204F1020401D81AB070BD13F8011B94 +:104A600004F8021C04F8010C0132F0E708B5302309 +:104A700083F311880348FFF739FA002383F3118881 +:104A800008BD00BFE04D002090F8443003F01F0245 +:104A9000012A07D190F845200B2A03D10023C0E951 +:104AA0000E3315E003F06003202B08D1B0F8483036 +:104AB0002BB990F84520212A03D81F2A04D8FFF7E4 +:104AC000F7B9222AEBD0FAE7034A82630722C263CE +:104AD00003640120704700BF2423002007B5052987 +:104AE00017D8DFE801F0191603191920302383F3D2 +:104AF0001188104A01900121FFF79AFA01980E4A95 +:104B00000221FFF795FA0D48FFF7BCF9002383F364 +:104B1000118803B05DF804FB302383F31188074844 +:104B2000FFF786F9F2E7302383F311880348FFF794 +:104B30009DF9EBE78C660008B0660008E04D0020A8 +:104B400038B50C4D0C4C0D492A4604F10800FFF70E +:104B500067FF05F1CA0204F110000949FFF760FF81 +:104B600005F5CA7204F118000649BDE83840FFF7A0 +:104B700057BF00BFA85200202C2300206C660008FD +:104B8000766600088166000870B5044608460D4642 +:104B9000FCF74EFEC6B22046013403780BB9184626 +:104BA00070BD32462946FCF72FFE0028F3D10120C4 +:104BB000F6E700002DE9F04705460C46FCF738FE05 +:104BC0002B49C6B22846FFF7DFFF08B10B36F6B215 +:104BD00028492846FFF7D8FF08B11036F6B2632EF1 +:104BE0000BD8DFF88C80DFF88C90234FDFF894A08F +:104BF0002E7846B92670BDE8F08729462046BDE8E4 +:104C0000F04701F089BC252E2ED1072241462846C7 +:104C1000FCF7FAFD70B9194B224603F1100153F865 +:104C2000040B42F8040B8B42F9D11B881380073523 +:104C30001234DDE7082249462846FCF7E5FD98B91D +:104C40000F4BA21C197809090232C95D02F8041C35 +:104C500013F8011B01F00F015345C95D02F8031C55 +:104C6000F0D118340835C3E704F8016B0135BFE70C +:104C7000586700088166000860670008366500080C +:104C8000107AFF1F1C7AFF1FBFF34F8F024AD368B1 +:104C9000DB03FCD4704700BF003C024008B5094B61 +:104CA0001B7873B9FFF7F0FF074B1A69002ABFBFE3 +:104CB000064A5A6002F188325A601A6822F4806209 +:104CC0001A6008BD06550020003C024023016745DC +:104CD00008B50B4B1B7893B9FFF7D6FF094B1A6940 +:104CE00042F000421A611A6842F480521A601A684F +:104CF00022F480521A601A6842F480621A6008BD79 +:104D000006550020003C02400B28F0B516D80C4C8C +:104D10000C4923787BB90C4D0E460C234FF00062F2 +:104D200055F8047B46F8042B013B13F0FF033A448B +:104D3000F6D10123237051F82000F0BD0020FCE7DC +:104D4000385500200855002074670008014B53F8BF +:104D500020007047746700080C2070470B2810B5BE +:104D6000044601D9002010BDFFF7CEFF064B53F8D3 +:104D700024301844C21A0BB90120F4E7126801323A +:104D8000F0D1043BF6E700BF746700080B2810B5AC +:104D9000044621D8FFF778FFFFF780FF0F4AF3237F +:104DA000D360C300DBB243F4007343F0020313612A +:104DB000136943F480331361FFF766FFFFF7A4FF25 +:104DC000074B53F8241000F03DF9FFF781FF204610 +:104DD000BDE81040FFF7C2BF002010BD003C0240FC +:104DE00074670008F8B512F00103144642D1821826 +:104DF000B2F1016F57D82D4B1B6813F0010352D04D +:104E00002B4DFFF74BFFF323EB60FFF73DFF40F225 +:104E10000127032C15D824F001046618244C401AED +:104E200040F20117B142236900EB010524D123F0C0 +:104E300001032361FFF74CFF0120F8BD043C04305F +:104E4000E7E78307E7D12B6923F440732B612B69D4 +:104E50003B432B6151F8046B0660BFF34F8FFFF7A4 +:104E600013FF03689E42E9D02B6923F001032B61F5 +:104E7000FFF72EFF0020E0E723F44073236123694E +:104E80003B4323610B882B80BFF34F8FFFF7FCFE62 +:104E90002D8831F8023BADB2AB42C3D0236923F079 +:104EA00001032361E4E71846C7E700BF003802406A +:104EB000003C0240084908B50B7828B11BB9FFF740 +:104EC000EDFE01230B7008BD002BFCD0BDE80840AF +:104ED0000870FFF7FDBE00BF0655002008B5064963 +:104EE000064800F0B1F8BDE808404FF480314FF0BB +:104EF000805000F0A9B800BF00FF010000010020B1 +:104F00000846114601F06CBA012001F069BA0000B0 +:104F1000084601F083BA000038B5EFF311859DB95A +:104F2000EFF30584C4F30804302334B183F311880C +:104F3000FFF742FD85F3118838BD83F31188FFF731 +:104F40003BFD84F3118838BDBDE83840FFF734BD20 +:104F500038B5FFF7E1FF114C114AC00840EA417033 +:104F6000A0FB025EC908A0FB040C1CEB050CA1FB16 +:104F700004404FF000035B41A1FB02121CEB040C48 +:104F800043EB000011EB0E0142F10002411842F127 +:104F90000000090941EA007038BD00BFCFF753E3B4 +:104FA000A59BC42010B50244064BD2B2904200D15A +:104FB00010BD441C00B253F8200041F8040BE0B2CD +:104FC000F4E700BF502800400F4B30B51C6F24049D +:104FD00007D41C6F44F400741C671C6F44F4004435 +:104FE0001C670A4C236843F4807323600244084B17 +:104FF000D2B2904200D130BD441C00B251F8045BE3 +:1050000043F82050E0B2F4E700380240007000405E +:105010005028004007B5012201A90020FFF7C2FF78 +:10502000019803B05DF804FB13B50446FFF7F2FFE7 +:10503000A04205D0012201A900200194FFF7C4FF7E +:1050400002B010BD704700007047000070470000BC +:10505000074B45F255521A6002225A6040F6FF7221 +:105060009A604CF6CC421A60024B01221A707047CB +:105070000030004040550020034B1B781BB1034B10 +:105080004AF6AA221A6070474055002000300040BE +:10509000034B1A681AB9034AD2F874281A60704789 +:1050A0003C55002000300240024B4FF08072C3F8A4 +:1050B000742870470030024008B5FFF7E9FF024B43 +:1050C0001868C0F3407008BD3C55002008B5FFF7D4 +:1050D000DFFF024B1868C0F3007008BD3C5500208C +:1050E00070470000FEE700000A4B0B480B4A904255 +:1050F0000BD30B4BDA1C121AC11E22F003028B4297 +:1051000038BF00220021FCF79BBB53F8041B40F87A +:10511000041BECE790690008445600204456002028 +:105120004456002070B5D0E915439E6800224FF028 +:10513000FF3504EB42135101D3F800090028BEBF2C +:10514000D3F8000940F08040C3F80009D3F8000B01 +:105150000028BEBFD3F8000B40F08040C3F8000B1E +:10516000013263189642C3F80859C3F8085BE0D2CD +:105170004FF00113C4F81C3870BD0000890141F0E4 +:105180002001016103699B06FCD41220FFF76CBA71 +:1051900010B5054C2046FEF72BFF4FF0A04363658A +:1051A000024BA36510BD00BF44550020C86700082E +:1051B00070B50378012B054650D12A4B446D9842B7 +:1051C0001BD1294B5A6B42F080025A635A6D42F050 +:1051D00080025A655A6D5A6942F080025A615A69D2 +:1051E00022F080025A610E2143205B69FEF74AFDDE +:1051F0001E4BE3601E4BC4F800380023C4F8003E89 +:10520000C02323606E6D4FF40413A3633369002B36 +:10521000FCDA012333610C20FFF726FA3369DB0740 +:10522000FCD41220FFF720FA3369002BFCDA0026A9 +:10523000A6602846FFF776FF6B68C4F81068DB6845 +:10524000C4F81468C4F81C684BB90A4BA3614FF04A +:10525000FF336361A36843F00103A36070BD064B95 +:10526000F4E700BF445500200038024040140040DD +:1052700003002002003C30C0083C30C0F8B5446D4B +:10528000054600212046FFF779FFA96D00234FF066 +:1052900001128F68C4F834384FF00066C4F81C2837 +:1052A0004FF0FF3004EB431201339F42C2F8006914 +:1052B000C2F8006BC2F80809C2F8080BF2D20B68FA +:1052C0006A6DEB65636210231361166916F01006B0 +:1052D000FBD11220FFF7C8F9D4F8003823F4FE639D +:1052E000C4F80038A36943F4402343F01003A361DA +:1052F0000923C4F81038C4F814380A4BEB604FF097 +:10530000C043C4F8103B084BC4F8003BC4F8106914 +:10531000C4F80039EB6D03F1100243F48013EA6521 +:10532000A362F8BDA467000840800010426D90F8A9 +:105330004E10D2F8003823F4FE6343EA0113C2F89A +:10534000003870472DE9F84300EB8103456DDA68BA +:10535000166806F00306731E022B05EB41130C467C +:1053600080460FFA81F94FEA41104FF00001C3F86F +:10537000101B4FF0010104F1100398BFB60401FAAD +:1053800003F391698EBF334E06F1805606F5004651 +:1053900000293AD0578A04F15801490137436F5028 +:1053A000D5F81C180B43C5F81C382B180021C3F87E +:1053B000101953690127611EA7409BB3138A928B72 +:1053C0009B08012A88BF5343D8F85C20981842EA0A +:1053D000034301F1400205EB8202C8F85C0021465C +:1053E00053602846FFF7CAFE08EB8900C3681B8A92 +:1053F00043EA8453483464011E432E51D5F81C38C7 +:105400001F43C5F81C78BDE8F88305EB4917D7F8AA +:10541000001B21F40041C7F8001BD5F81C1821EA35 +:105420000303C0E704F13F0305EB83030A4A5A6014 +:1054300028462146FFF7A2FE05EB4910D0F80039B7 +:1054400023F40043C0F80039D5F81C3823EA0707D5 +:10545000D7E700BF0080001000040002826D1268D0 +:10546000C265FFF75FBE00005831436D49015B58CC +:1054700013F4004004D013F4001F0CBF02200120DD +:10548000704700004831436D49015B5813F40040F8 +:1054900004D013F4001F0CBF02200120704700004D +:1054A00000EB8101CB68196A0B6813604B6853608D +:1054B0007047000000EB810330B5DD68AA6913680E +:1054C000D36019B9402B84BF402313606B8A1468E2 +:1054D000426D1C44013CB4FBF3F46343033323F0FB +:1054E000030302EB411043EAC44343F0C043C0F856 +:1054F000103B2B6803F00303012B09B20ED1D2F845 +:10550000083802EB411013F4807FD0F8003B14BF41 +:1055100043F0805343F00053C0F8003B02EB4112CC +:10552000D2F8003B43F00443C2F8003B30BD00001A +:105530002DE9F041244D6E6D06EB40130446D3F87F +:10554000087BC3F8087B38070AD5D6F81438190742 +:1055500006D505EB84032146DB6828465B6898473F +:10556000FA071FD5D6F81438DB071BD505EB8403E3 +:10557000D968CCB98B69488A5A68B2FBF0F600FB4F +:1055800016228AB91868DA6890420DD2121AC3E955 +:105590000024302383F311880B482146FFF78AFF4C +:1055A00084F31188BDE8F081012303FA04F26B89CA +:1055B00023EA02036B81CB68002BF3D0214602481B +:1055C000BDE8F041184700BF4455002000EB8103BF +:1055D00070B5DD68436D6C692668E6604A0156BBAC +:1055E0001A444FF40020C2F810092A6802F003029E +:1055F000012A0AB20ED1D3F8080803EB421410F4C2 +:10560000807FD4F8000914BF40F0805040F0005073 +:10561000C4F8000903EB4212D2F8000940F004403C +:10562000C2F80009D3F83408012202FA01F101435B +:10563000C3F8341870BD19B9402E84BF40202060D3 +:1056400020682E8A8419013CB4FBF6F440EAC44079 +:1056500040F000501A44C6E72DE9F8433B4D6E6D0B +:1056600006EB40130446D3F80889C3F8088918F0FC +:10567000010F4FEA40171AD0D6F81038DB0716D5BD +:1056800005EB8003D9684B691868DA68904230D21C +:10569000121A4FF000091A60C3F80490302383F304 +:1056A000118821462846FFF791FF89F3118818F0E9 +:1056B000800F1CD0D6F834380126A640334216D0CD +:1056C00005EB84036D6DD3F80CC0DCF814200134B5 +:1056D000E4B2D2F800E005EB04342F445168714580 +:1056E00015D3D5F8343823EA0606C5F83468BDE882 +:1056F000F883012303FA04F22B8923EA02032B81A6 +:105700008B68002BD3D0214628469847CFE7BCF8BA +:105710001000AEEB0103834228BF0346D7F81809F7 +:1057200080B2B3EB800FE2D89068A0F1040959F879 +:10573000048FC4F80080A0EB09089844B8F1040F66 +:10574000F5D818440B4490605360C7E744550020D7 +:105750002DE9F74FA24C656D6E69AB691E4016F4DA +:1057600080586E6107D02046FEF7AAFC03B0BDE862 +:10577000F04FFEF75DBA002E12DAD5F8003E9848D9 +:105780009B071EBFD5F8003E23F00303C5F8003E7B +:10579000D5F8043823F00103C5F80438FEF7BAFC45 +:1057A000370505D58E48FFF7BDFC8D48FEF7A0FCF8 +:1057B000B0040CD5D5F8083813F0060FEB6823F4C5 +:1057C00070530CBF43F4105343F4A053EB60310704 +:1057D0001BD56368DB681BB9AB6923F00803AB61B9 +:1057E0002378052B0CD1D5F8003E7D489A071EBFC3 +:1057F000D5F8003E23F00303C5F8003EFEF78AFC0F +:105800006368DB680BB176489847F30274D4B7023B +:1058100027D5D4F85490DFF8C8B100274FF0010A1B +:1058200009EB4712D2F8003B03F44023B3F5802F75 +:1058300011D1D2F8003B002B0DDA62890AFA07F386 +:1058400022EA0303638104EB8703DB68DB6813B19F +:10585000394658469847A36D01379B68FFB29F426F +:10586000DED9F00617D5676D3A6AC2F30A1002F066 +:105870000F0302F4F012B2F5802F00F08580B2F52C +:10588000402F08D104EB83030022DB681B6A07F575 +:10589000805790426AD13003D5F8184813D5E103F8 +:1058A00002D50020FFF744FEA20302D50120FFF736 +:1058B0003FFE630302D50220FFF73AFE270302D51D +:1058C0000320FFF735FE75037FF550AFE00702D5E3 +:1058D0000020FFF7C1FEA10702D50120FFF7BCFEA3 +:1058E000620702D50220FFF7B7FE23077FF53EAF20 +:1058F0000320FFF7B1FE39E7636DDFF8E4A0019301 +:1059000000274FF00109A36D9B685FFA87FB9B4559 +:105910003FF67DAF019B03EB4B13D3F8001901F465 +:105920004021B1F5802F1FD1D3F8001900291BDACF +:10593000D3F8001941F09041C3F80019D3F80019C9 +:105940000029FBDB5946606DFFF718FC218909FA35 +:105950000BF321EA0303238104EB8B03DB689B68D1 +:1059600013B15946504698470137CCE7910708BF15 +:10597000D7F80080072A98BF03F8018B02F10102D3 +:1059800098BF4FEA182884E7023304EB830207F537 +:1059900080575268D2F818C0DCF80820DCE9001CF7 +:1059A000A1EB0C0C002188420AD104EB830463684C +:1059B0009B699A6802449A605A6802445A606AE78E +:1059C00011F0030F08BFD7F800808C4588BF02F89C +:1059D000018B01F1010188BF4FEA1828E3E700BFFE +:1059E00044550020436D03EB4111D1F8003B43F4D3 +:1059F0000013C1F8003B7047436D03EB4111D1F830 +:105A0000003943F40013C1F800397047436D03EBCC +:105A10004111D1F8003B23F40013C1F8003B70475B +:105A2000436D03EB4111D1F8003923F40013C1F8A1 +:105A30000039704730B5039C0172043304FB032521 +:105A4000C0E90653049B03630021059BC160C0E9C4 +:105A50000000C0E90422C0E90842C0E90A1143631A +:105A600030BD0000416A0022C0E90411C0E90A22E9 +:105A7000C2606FF00101FEF767BE0000D0E904329A +:105A8000934201D1C2680AB9181D704700207047BF +:105A900003691960C2680132C260C2691344826935 +:105AA0000361934224BF436A03610021FEF740BEB5 +:105AB00038B504460D46E3683BB16269131D1268B0 +:105AC000A3621344E362002007E0237A33B9294636 +:105AD0002046FEF71DFE0028EDDA38BD6FF001000C +:105AE000FBE70000C368C269013BC360436913441C +:105AF00082694361934224BF436A43610023836206 +:105B0000036B03B11847704770B53023044683F325 +:105B10001188866A3EB9FFF7CBFF054618B186F3B8 +:105B20001188284670BDA36AE26A13F8015BA3627C +:105B3000934202D32046FFF7D5FF002383F3118859 +:105B4000EFE700002DE9F84F04460E461746984649 +:105B50004FF0300989F311880025AA46D4F828B0FF +:105B6000BBF1000F09D141462046FFF7A1FF20B14C +:105B70008BF311882846BDE8F88FD4E90A12A7EB09 +:105B8000050B521A934528BF9346BBF1400F1BD912 +:105B9000334601F1400251F8040B43F8040B9142E3 +:105BA000F9D1A36A40334036A3624035D4E90A23D1 +:105BB0009A4202D32046FFF795FF8AF31188BD422F +:105BC000D8D289F31188C9E730465A46FBF712FE4E +:105BD000A36A5B445E44A3625D44E7E710B5029CA0 +:105BE0000172043303FB0421C0E906130023C0E95A +:105BF0000A33039B0363049BC460C0E90000C0E94F +:105C00000422C0E90842436310BD0000026AC2607A +:105C1000426AC0E904220022C0E90A226FF00101B1 +:105C2000FEF792BDD0E904239A4201D1C26822B99D +:105C3000184650F8043B0B60704700231846FAE7FB +:105C4000C368C2690133C360436913448269436115 +:105C5000934224BF436A43610021FEF769BD0000FF +:105C600038B504460D46E3683BB123691A1DA262AC +:105C7000E2691344E362002007E0237A33B929463E +:105C80002046FEF745FD0028EDDA38BD6FF0010033 +:105C9000FBE7000003691960C268013AC260C2698B +:105CA000134482690361934224BF436A0361002362 +:105CB0008362036B03B118477047000070B530234F +:105CC0000D460446114683F31188866A2EB9FFF704 +:105CD000C7FF10B186F3118870BDA36A1D70A36A57 +:105CE000E26A01339342A36204D3E1692046043996 +:105CF000FFF7D0FF002080F31188EDE72DE9F84F82 +:105D000004460D46904699464FF0300A8AF31188B2 +:105D10000026B346A76A4FB949462046FFF7A0FFC1 +:105D200020B187F311883046BDE8F88FD4E90A071F +:105D30003A1AA8EB0607974228BF1746402F1BD9EF +:105D400005F1400355F8042B40F8042B9D42F9D18E +:105D5000A36A4033A3624036D4E90A239A4204D3AB +:105D6000E16920460439FFF795FF8BF3118846451A +:105D7000D9D28AF31188CDE729463A46FBF73AFD96 +:105D8000A36A3B443D44A3623E44E5E7D0E90423D3 +:105D90009A4217D1C3689BB1836A8BB1043B9B1AAB +:105DA0000ED01360C368013BC360C3691A448369A2 +:105DB00002619A4224BF436A036100238362012384 +:105DC000184670470023FBE700F0D2B84FF080433D +:105DD000586A70474FF08043002258631A610222CC +:105DE000DA6070474FF080430022DA6070470000AD +:105DF0004FF0804358637047FEE7000070B51B4BBF +:105E000001630025044686B0586085620E46FDF7A2 +:105E1000EBFE04F11003C4E904334FF0FF33C4E98F +:105E20000635C4E90044A560E562FFF7CFFF2B46C5 +:105E30000246C4E9082304F134010D4A2565802394 +:105E40002046FEF71BFC0123E0600A4A037500921E +:105E500072680192B268CDE90223074B6846CDE92A +:105E60000435FEF733FC06B070BD00BFD84D0020EE +:105E7000D4670008D9670008F95D0008024AD36AB0 +:105E80001843D062704700BF704B00204B684360DE +:105E90008B688360CB68C3600B6943614B690362A5 +:105EA0008B6943620B6803607047000008B5264B9E +:105EB00026481A6940F2FF110A431A611A6922F44E +:105EC000FF7222F001021A611A691A6B0A431A63FF +:105ED0001A6D0A431A651E4A1B6D1146FFF7D6FF5D +:105EE00002F11C0100F58060FFF7D0FF02F13801DC +:105EF00000F58060FFF7CAFF02F1540100F58060F1 +:105F0000FFF7C4FF02F1700100F58060FFF7BEFFEC +:105F100002F18C0100F58060FFF7B8FF02F1A801E3 +:105F200000F58060FFF7B2FF02F1C40100F5806068 +:105F3000FFF7ACFF02F1E00100F58060FFF7A6FF7C +:105F4000BDE8084000F090B8003802400000024070 +:105F5000E067000808B500F0FBF9FEF75DFBFFF70E +:105F600097F8BDE80840FEF7EBBD00007047000061 +:105F70000F4B1A6C42F001021A641A6E42F00102D1 +:105F80001A660C4A1B6E936843F0010393604FF04E +:105F9000804353229A624FF0FF32DA6200229A6104 +:105FA0005A63DA605A6001225A611A60704700BF72 +:105FB00000380240002004E04FF0804208B511692B +:105FC000D3680B40D9B2C9439B07116107D5302371 +:105FD00083F31188FEF746FB002383F3118808BD85 +:105FE0001F4B1A696FEAC2526FEAD2521A611A69DC +:105FF000C2F308021A614FF0FF301A695A695861FA +:1060000000215A6959615A691A6A62F080521A620B +:106010001A6A02F080521A621A6A5A6A58625A6AF6 +:1060200059625A6A1A6C42F080521A641A6E42F02F +:1060300080521A661A6E0B4A106840F48070106025 +:10604000186F00F44070B0F5007F1EBF4FF4803031 +:1060500018671967536823F40073536000F054B94C +:106060000038024000700040334B4FF080521A64F9 +:10607000324A4FF4404111601A6842F001021A603E +:106080001A689107FCD59A6822F003029A602A4B9D +:106090009A6812F00C02FBD1196801F0F90119603D +:1060A0009A601A6842F480321A601A689203FCD52A +:1060B0005A6F42F001025A671F4B5A6F9007FCD586 +:1060C0001F4A5A601A6842F080721A601B4A53686D +:1060D0005904FCD5184B1A689201FCD5194A9A60EC +:1060E000194B1A68194B9A42194B21D1194A116858 +:1060F000194A91421CD140F205121A60144A1368E1 +:1061000003F00F03052BFAD10B4B9A6842F0020201 +:106110009A609A6802F00C02082AFAD15A6C42F48A +:1061200080425A645A6E42F480425A665B6E7047EF +:1061300040F20572E1E700BF003802400070004005 +:106140000854400700948838002004E011640020BF +:10615000003C024000ED00E041C20F41074A08B593 +:10616000536903F00103536123B1054A13680BB16E +:1061700050689847BDE80840FDF75ABD003C014013 +:10618000BC550020074A08B5536903F00203536168 +:1061900023B1054A93680BB1D0689847BDE8084021 +:1061A000FDF746BD003C0140BC550020074A08B53C +:1061B000536903F00403536123B1054A13690BB11A +:1061C00050699847BDE80840FDF732BD003C0140EA +:1061D000BC550020074A08B5536903F00803536112 +:1061E00023B1054A93690BB1D0699847BDE80840CF +:1061F000FDF71EBD003C0140BC550020074A08B514 +:10620000536903F01003536123B1054A136A0BB1BC +:10621000506A9847BDE80840FDF70ABD003C0140C0 +:10622000BC550020164B10B55C6904F478725A61B5 +:10623000A30604D5134A936A0BB1D06A9847600647 +:1062400004D5104A136B0BB1506B9847210604D547 +:106250000C4A936B0BB1D06B9847E20504D5094A01 +:10626000136C0BB1506C9847A30504D5054A936C89 +:106270000BB1D06C9847BDE81040FDF7D9BC00BF0A +:10628000003C0140BC550020194B10B55C6904F47A +:106290007C425A61620504D5164A136D0BB1506DEC +:1062A0009847230504D5134A936D0BB1D06D9847D9 +:1062B000E00404D50F4A136E0BB1506E9847A10449 +:1062C00004D50C4A936E0BB1D06E9847620404D586 +:1062D000084A136F0BB1506F9847230404D5054A41 +:1062E000936F0BB1D06F9847BDE81040FDF7A0BC8D +:1062F000003C0140BC55002008B5FFF75DFEBDE83D +:106300000840FDF795BC0000062108B50846FDF7DA +:10631000B9FC06210720FDF7B5FC06210820FDF792 +:10632000B1FC06210920FDF7ADFC06210A20FDF78E +:10633000A9FC06211720FDF7A5FC06212820FDF762 +:10634000A1FCBDE8084007211C20FDF79BBC000014 +:1063500008B5FFF745FE00F00BF8FDF747FEFDF727 +:106360001FFDFFF703FEBDE80840FFF72DBD00004D +:106370000023054A19460133102BC2E9001102F12E +:106380000802F8D1704700BFBC5500200B460146FB +:10639000184600F02DB8000000F040B8012838BFC2 +:1063A000012010B50446204600F030F830B900F066 +:1063B00007F808B900F00CF88047F4E710BD0000BA +:1063C000024B1868BFF35B8F704700BF3C5600203C +:1063D00008B5062000F084F80120FEF7FFFA00005F +:1063E000024B0A4601461868FEF78ABD4C2300207E +:1063F00010B5054C13462CB10A4601460220AFF3F6 +:10640000008010BD2046FCE700000000024B014662 +:106410001868FEF779BD00BF4C230020024B0146EF +:106420001868FEF775BD00BF4C23002010B5013978 +:106430000244904201D1002005E0037811F8014F99 +:10644000A34201D0181B10BD0130F2E72DE9F04145 +:10645000A3B1C91A17780144044603F1FF3C8C42EA +:10646000204601D9002009E00578BD4204F101046D +:10647000F5D10CEB0405D618A54201D1BDE8F08199 +:1064800015F8018D16F801EDF045F5D0E7E70000AD +:106490001F2938B504460D4604D9162303604FF072 +:1064A000FF3038BD426C12B152F821304BB9204652 +:1064B00000F030F82A4601462046BDE8384000F09A +:1064C00017B8012B0AD0591C03D1162303600120F1 +:1064D000E7E7002442F82540284698470020E0E7F7 +:1064E000024B01461868FFF7D3BF00BF4C230020C2 +:1064F00038B5074D00230446084611462B60FEF7C9 +:1065000071FA431C02D12B6803B1236038BD00BF70 +:1065100040560020FEF760BA034611F8012B03F83D +:10652000012B002AF9D170476F72672E6172647572 +:1065300070696C6F742E663430352D4D6174656BE7 +:1065400041697273706565640000000053544D33F7 +:1065500032463F3F3F0053544D333246343078008B +:1065600053544D3332463432780053544D3332460F +:106570003434365858000000012033000010410028 +:1065800001105A00031059000710310000000000EC +:106590004C6500081304000056650008190400004B +:1065A00060650008210400006A65000840A2E4F16B +:1065B000646891060041A3E5F26569920700000056 +:1065C0004261642043414E496661636520696E649F +:1065D00065782E0080000000008000000000800030 +:1065E0000000000000000000FD2000081D29000838 +:1065F000792800083D2100084921000849230008A6 +:106600000D2100081D210008112100081921000892 +:10661000152100086D22000821210008ED2B00083B +:106620003121000841220008000000001D3D000843 +:10663000093D0008453D0008313D00083D3D00088A +:10664000293D0008153D0008013D0008513D0008A6 +:1066500000000000010000000000000063300000A6 +:106660005C660008C84B0020D84D0020417264755C +:1066700050696C6F740025424F415244252D424CA5 +:10668000002553455249414C2500000002000000FE +:1066900000000000393F0008A53F0008400040000E +:1066A0007852002088520020020000000000000004 +:1066B0000300000000000000E93F000800000000A7 +:1066C00010000000985200200000000001000000AF +:1066D000000000004455002001010200DD4A0008CE +:1066E000ED490008894A00086D4A0008430000008F +:1066F000F466000809024300020100C032090400E8 +:10670000000102020100052400100105240100011E +:10671000042402020524060001070582030800FF85 +:1067200009040100020A0000000705010240000000 +:1067300007058102400000001200000040670008C9 +:10674000120110010200004009124157000201022B +:10675000030100000403090425424F41524425006F +:106760003031323334353637383941424344454687 +:106770000000000000400000004000000040000059 +:1067800000400000000001000000020000000200C4 +:1067900000000200000002000000020000000200F1 +:1067A00000000200000000002D410008E543000841 +:1067B0009144000840004000A4550020A45500204A +:1067C00001000000B45500208000000040010000DE +:1067D000030000006D61696E0069646C6500000073 +:1067E000AA01A81200000000AAAAAAAA5501140032 +:1067F000FFBF00008877000070A70A0000000A01B0 +:1068000000000000AAAAAAAA00000001FFFF0000E1 +:1068100000000000990000000000A0160000000029 +:10682000AAAAAAA600005011FFDF00000000000085 +:10683000007708002000000000000000AAAAAAAA11 +:1068400010000000FFFF0000000800000000000032 +:106850000000000000000000AAAAAAAA0000000090 +:10686000FFFF00000000000000000000000000002A +:1068700000000000AAAAAAAA00000000FFFF000072 +:106880000000000000000000000000000000000008 +:10689000AAAAAAAA00000000FFFF00000000000052 +:1068A0000000000000000000000000000A000000DE +:1068B00000000000030000000000000000000000D5 +:1068C00000000000000000000000000000000000C8 +:1068D00000000000000000000000000000000000B8 +:1068E000F60300000000000000000F0000000000A0 +:1068F00040420F00FE2A0100D2040000FF00960073 +:1069000000000008009600000000080004000000DD +:1069100054670008000000000000000000000000B4 +:1069200000000000000000000000000050230020D4 +:106930000000000000000000000000000000000057 +:106940000000000000000000000000000000000047 +:106950000000000000000000000000000000000037 +:106960000000000000000000000000000000000027 +:106970000000000000000000000000000000000017 +:106980000000000000000000000000000000000007 :00000001FF diff --git a/Tools/bootloaders/f405-MatekGPS_bl.bin b/Tools/bootloaders/f405-MatekGPS_bl.bin index 723de4f8963b14..14bb6d4f64f464 100755 Binary files a/Tools/bootloaders/f405-MatekGPS_bl.bin and b/Tools/bootloaders/f405-MatekGPS_bl.bin differ diff --git a/Tools/bootloaders/f405-MatekGPS_bl.hex b/Tools/bootloaders/f405-MatekGPS_bl.hex index 68e31533fbae0b..41122bf1ad2bde 100644 --- a/Tools/bootloaders/f405-MatekGPS_bl.hex +++ b/Tools/bootloaders/f405-MatekGPS_bl.hex @@ -1,1741 +1,1691 @@ :020000040800F2 -:1000000000070020F5040008B12E0008692E000842 -:10001000912E0008692E0008892E0008F7040008B8 -:10002000F7040008F7040008F7040008A53E0008DC -:10003000F7040008F7040008F7040008F7040008B4 -:10004000F7040008F7040008F7040008F7040008A4 -:10005000F7040008F7040008756400089D640008B0 -:10006000C5640008ED64000815650008F704000881 -:10007000F7040008F7040008F7040008F704000874 -:10008000F7040008F7040008F70400081D2E000814 -:10009000492E0008592E0008F70400083D650008A5 -:1000A000F7040008F7040008F7040008F704000844 -:1000B00011660008F7040008F7040008F7040008B8 -:1000C000F7040008F7040008F7040008F704000824 -:1000D000F7040008F7040008F7040008F704000814 -:1000E000A1650008F7040008F7040008F7040008F9 -:1000F000F7040008F7040008F7040008F7040008F4 -:10010000F7040008F7040008F7040008F7040008E3 -:10011000F7040008F7040008F7040008F7040008D3 -:10012000F7040008F7040008F7040008F7040008C3 -:10013000F7040008F7040008F7040008F7040008B3 -:10014000F7040008F7040008F7040008695A0008DB -:10015000F7040008F7040008F7040008F704000893 -:10016000F7040008F7040008F7040008F704000883 -:10017000F7040008F7040008F7040008F704000873 -:10018000F7040008F7040008F7040008F704000863 -:10019000F7040008F7040008F7040008F704000853 -:1001A000F7040008F7040008F7040008F704000843 -:1001B000F7040008F7040008F7040008F704000833 -:1001C000F7040008F7040008F7040008F704000823 -:1001D000F7040008F7040008F7040008F704000813 -:1001E000651800080000000000000000000000008A -:1001F00053B94AB9002908BF00281CBF4FF0FF318E -:100200004FF0FF3000F074B9ADF1080C6DE904CE89 -:1002100000F006F8DDF804E0DDE9022304B07047E1 -:100220002DE9F047089D04468E46002B4DD18A42A9 -:10023000944669D9B2FA82F252B101FA02F3C2F1DC -:10024000200120FA01F10CFA02FC41EA030E94406D -:100250004FEA1C48210CBEFBF8F61FFA8CF708FB8E -:1002600016E341EA034306FB07F199420AD91CEB66 -:10027000030306F1FF3080F01F81994240F21C8198 -:10028000023E63445B1AA4B2B3FBF8F008FB1033E0 -:1002900044EA034400FB07F7A7420AD91CEB040415 -:1002A00000F1FF3380F00A81A74240F207816444E5 -:1002B000023840EA0640E41B00261DB1D44000236A -:1002C000C5E900433146BDE8F0878B4209D9002DCE -:1002D00000F0EF800026C5E9000130463146BDE858 -:1002E000F087B3FA83F6002E4AD18B4202D38242C2 -:1002F00000F2F980841A61EB030301209E46002D71 -:10030000E0D0C5E9004EDDE702B9FFDEB2FA82F2C5 -:10031000002A40F09280A1EB0C014FEA1C471FFA23 -:100320008CFE0126200CB1FBF7F307FB131140EA0A -:1003300001410EFB03F0884208D91CEB010103F1D7 -:10034000FF3802D2884200F2CB804346091AA4B299 -:10035000B1FBF7F007FB101144EA01440EFB00FE6D -:10036000A64508D91CEB040400F1FF3102D2A645D2 -:1003700000F2BB800846A4EB0E0440EA03409CE771 -:10038000C6F12007B34022FA07FC4CEA030C20FA1E -:1003900007F401FA06F31C43F9404FEA1C4900FA3E -:1003A00006F3B1FBF9F8200C1FFA8CFE09FB1811BB -:1003B00040EA014108FB0EF0884202FA06F20BD92E -:1003C0001CEB010108F1FF3A80F08880884240F27E -:1003D0008580A8F102086144091AA4B2B1FBF9F0C2 -:1003E00009FB101144EA014100FB0EFE8E4508D9BD -:1003F0001CEB010100F1FF346CD28E456AD9023842 -:10040000614440EA0840A0FB0294A1EB0E01A14226 -:10041000C846A64656D353D05DB1B3EB080261EB94 -:100420000E0101FA07F722FA06F3F1401F43C5E96E -:10043000007100263146BDE8F087C2F12003D840A4 -:100440000CFA02FC21FA03F3914001434FEA1C47E6 -:100450001FFA8CFEB3FBF7F007FB10360B0C43EAD8 -:10046000064300FB0EF69E4204FA02F408D91CEB88 -:10047000030300F1FF382FD29E422DD90238634486 -:100480009B1B89B2B3FBF7F607FB163341EA034126 -:1004900006FB0EF38B4208D91CEB010106F1FF3875 -:1004A00016D28B4214D9023E6144C91A46EA00466C -:1004B00038E72E46284605E70646E3E61846F8E6FE -:1004C0004B45A9D2B9EB020864EB0C0E0138A3E747 -:1004D0004646EAE7204694E74046D1E7D0467BE728 -:1004E000023B614432E7304609E76444023842E7A0 -:1004F000704700BF02E000F000F8FEE772B6374830 -:1005000080F30888364880F3098836483649086001 -:1005100040F20000CCF200004EF63471CEF2000141 -:100520000860BFF34F8FBFF36F8F40F20000C0F23F -:10053000F0004EF68851CEF200010860BFF34F8FF5 -:10054000BFF36F8F4FF00000E1EE100A4EF63C71E2 -:10055000CEF200010860062080F31488BFF36F8F8D -:1005600004F04AFF05F02EFE4FF055301F491B4A9C -:1005700091423CBF41F8040BFAE71D49184A9142E9 -:100580003CBF41F8040BFAE71A491B4A1B4B9A423D -:100590003EBF51F8040B42F8040BF8E7002018495D -:1005A000184A91423CBF41F8040BFAE704F028FFD7 -:1005B00005F05CFE144C154DAC4203DA54F8041BF4 -:1005C0008847F9E700F042F8114C124DAC4203DACB -:1005D00054F8041B8847F9E704F010BF0007002017 -:1005E000002300200000000808ED00E000010020CA -:1005F00000070020F86B000800230020B023002033 -:10060000B023002048560020E0010008E401000863 -:10061000E4010008E40100082DE9F04F2DED108AF7 -:10062000C1F80CD0C3689D46BDEC108ABDE8F08FC0 -:10063000002383F311882846A047002004F0EAF93C -:10064000FEE704F043F900DFFEE70000F8B501F033 -:100650001BF904F06BFE074604F0BAFE0546B8BB72 -:10066000204B9F4234D001339F4234D01E4B27F0A1 -:10067000FF029A4232D1F8B200F012FF2E4642F247 -:10068000107400F013FF08B10024264601F0FEFCB0 -:1006900020B1032000F07CF80024264635B1134B2E -:1006A0009F4203D004F08CFE00242646002004F074 -:1006B00047FE0EB100F082F801F098FA00F062FFF8 -:1006C00001F048F9204600F0D5F800F077F8F9E796 -:1006D0002E460024D5E704460126D2E7064641F21D -:1006E0008834CEE7010007B0000008B0263A09B010 -:1006F00008B501F001F9A0F120035842584108BDA6 -:1007000007B541F21203022101A8ADF8043001F04F -:1007100011F903B05DF804FB38B5302383F3118879 -:10072000174803680BB104F041FA164A1448002335 -:100730004FF47A7104F030FA002383F31188124CDD -:10074000236813B12368013B2360636813B16368B6 -:10075000013B63600D4D2B7833B963687BB9022090 -:1007600001F0BEF9322363602B78032B07D1636855 -:100770002BB9022001F0B4F94FF47A73636038BDED -:10078000B023002019070008D0240020C82300202F -:10079000084B187003280CD8DFE800F008050208A1 -:1007A000022001F093B9022001F086B9024B002229 -:1007B0005A607047C8230020D024002010B501F0F3 -:1007C00065FC30B1244B03221A70244B00225A607E -:1007D00010BD234B234A1C4619680131F8D004335D -:1007E0009342F9D16268204B9A42F1D91F4B9B6822 -:1007F00003F1006303F580339A42E9D204F0B4FDBB -:1008000004F0C6FD002001F0BFF80220FFF7C0FF92 -:10081000174B1A6C00221A64196E1A66196E596CFD -:100820005A64596E5A665A6E1A6942F000521A6139 -:100830001A6922F000521A611B6972B64FF0E02368 -:100840003021C3F8084DD4E9003281F311889D4668 -:1008500083F308881047BBE7C8230020D02400207A -:100860000000010820000108FFFF0008002300200D -:10087000003802402DE9F04F93B0AC4B009020229D -:10088000FF210AA89D6801F05BF9A94A1378A3B972 -:10089000A848012103601170302383F31188036895 -:1008A0000BB104F083F9A44AA24800234FF47A71F3 -:1008B00004F072F9002383F31188009B13B19F4B5E -:1008C000009A1A609E4A009C1378032B1EBF0023D7 -:1008D00013709A4A4FF0000A18BF5360D346564629 -:1008E000D146012001F0F2F824B1944B1B68002B93 -:1008F00000F01582002000F0FFFF0390039B002B07 -:1009000001DA00F087FE039B002BEDDB012001F0F4 -:10091000D3F8039B213B162BE3D801A252F823F016 -:100920007D090008A5090008390A0008E308000845 -:10093000E3080008E3080008C30A0008930C000855 -:10094000AD0B00080F0C0008370C00085D0C000808 -:10095000E30800086F0C0008E3080008E10C000839 -:100960001D0A0008E3080008250D00088909000891 -:100970001D0A0008E30800080F0C00080220FFF71A -:10098000B7FE002840F0F581009B0221BAF1000F6C -:1009900008BF1C4605A841F21233ADF8143000F030 -:1009A000C9FF9EE74FF47A7000F0A6FF071EEBDB4D -:1009B0000220FFF79DFE0028E6D0013F052F00F240 -:1009C000DA81DFE807F0030A0D10133605230593DB -:1009D000042105A800F0AEFF17E054480421F9E710 -:1009E00058480421F6E758480421F3E74FF01C0863 -:1009F000404600F0CBFF08F104080590042105A84B -:100A000000F098FFB8F12C0FF2D1012000FA07F79F -:100A100047EA0B0B5FFA8BFB4FF0000901F0DCF8A3 -:100A200026B10BF00B030B2B08BF0024FFF768FE69 -:100A300057E746480421CDE7002EA5D00BF00B0365 -:100A40000B2BA1D10220FFF753FE074600289BD0B5 -:100A5000012000F099FF0220FFF79AFE00261FFAFE -:100A600086F8404600F0A0FF044690B100214046C1 -:100A700000F0B2FF01360028F1D1BA46044641F237 -:100A80001213022105A8ADF814303E4600F052FFC3 -:100A900027E70120FFF77CFE2546244B9B68AB42ED -:100AA00007D9284600F072FF013040F06781043515 -:100AB000F3E7234B00251D70204BBA465D603E4690 -:100AC000ACE7002E3FF460AF0BF00B030B2B7FF471 -:100AD0005BAF0220FFF75CFE322000F00DFFB0F1AB -:100AE0000008FFF651AF18F003077FF44DAF0F4A2F -:100AF000926808EB050393423FF646AFB8F5807F56 -:100B00003FF742AF124B0193B84523DD4FF47A70A3 -:100B100000F0F2FE0390039A002AFFF635AF019B26 -:100B2000039A03F8012B0137EDE700BF00230020F3 -:100B3000CC240020B023002019070008D024002076 -:100B4000C823002004230020082300200C230020B9 -:100B5000CC230020C820FFF7CBFD074600283FF438 -:100B600013AF1F2D11D8C5F1200242450AAB25F065 -:100B7000030028BF424683490192184400F0BAFF9F -:100B8000019A8048FF2100F0DBFF4FEAA8037D496E -:100B90000193C8F38702284600F0DAFF06460028D2 -:100BA0003FF46DAF019B05EB830537E70220FFF7AC -:100BB0009FFD00283FF4E8AE00F02EFF00283FF430 -:100BC000E3AE0027B846704B9B68BB4218D91F2F75 -:100BD00011D80A9B01330ED027F0030312AA134445 -:100BE00053F8203C05934046042205A901F006FA7B -:100BF00004378046E7E7384600F0C8FE0590F2E784 -:100C0000CDF81480042105A800F094FE06E7002327 -:100C1000642104A8049300F083FE00287FF4B4AE9E -:100C20000220FFF765FD00283FF4AEAE049800F007 -:100C3000DBFE0590E6E70023642104A8049300F09E -:100C40006FFE00287FF4A0AE0220FFF751FD0028C0 -:100C50003FF49AAE049800F0D7FEEAE70220FFF7CF -:100C600047FD00283FF490AE00F0E6FEE1E70220E9 -:100C7000FFF73EFD00283FF487AE05A9142000F0E1 -:100C8000E1FE04210746049004A800F053FE394613 -:100C9000B9E7322000F030FE071EFFF675AEBB0745 -:100CA0007FF472AE384A926807EB090393423FF62D -:100CB0006BAE0220FFF71CFD00283FF465AE27F065 -:100CC00003074F44B9453FF4A9AE484600F05EFE25 -:100CD0000421059005A800F02DFE09F10409F1E7B3 -:100CE0004FF47A70FFF704FD00283FF44DAE00F09A -:100CF00093FE002844D00A9B01330BD008220AA996 -:100D0000002000F025FF00283AD02022FF210AA869 -:100D100000F016FFFFF7F4FC1C4803F081FE13B04F -:100D2000BDE8F08F002E3FF42FAE0BF00B030B2B22 -:100D30007FF42AAE0023642105A8059300F0F0FD9E -:100D4000074600287FF420AE0220FFF7D1FC804642 -:100D500000283FF419AEFFF7D3FC41F2883003F0CE -:100D60005FFE059800F06AFF464600F035FF3C46FE -:100D7000B7E5064652E64FF0000905E6BA467EE6BC -:100D800037467CE6CC23002000230020A08601000B -:100D9000094A136849F2690099B21B0C00FB013340 -:100DA0001360064B186844F2506182B2000C01FBDC -:100DB0000200186080B2704718230020142300201E -:100DC00010B500211022044600F0BAFE034B03CBFD -:100DD000206061601868A06010BD00BF107AFF1F1E -:100DE0002DE9F041ADF54E7D0DF134086CAC40F2CB -:100DF000751207460D460EA80021C8F8001000F035 -:100E00009FFE4FF4C4720021204600F099FE02F0CC -:100E100057F8274B4FF47A72B0FBF2F0186093E862 -:100E20000700022384E807000DF5E9702382FFF72D -:100E3000C7FF4FF203631F49238406A805F0F8FC9F -:100E40001B2384F832310DF2E32206AB0DF1300C96 -:100E50001E4603CE664510605160334602F108021B -:100E6000F6D13188B3789370118020464146012233 -:100E700000F0E6FE00230393AB7E029305F1190315 -:100E8000019380B20123CDE904800093E97E06A39B -:100E9000D3E90023384602F0DBFB0DF54E7DBDE8BB -:100EA000F08100BFAFF300809E6AC421818A46EEC4 -:100EB000D8240020406800082DE9F0412C4C237A0A -:100EC000DAB080460D465BBB27A9284600F0C8FF74 -:100ED0000746002842D19DF89D60C82E3ED80146A5 -:100EE0004FF4A662204600F02BFE4FF48073C4F846 -:100EF000F8314FF40073C4F80C334FF44073C4F866 -:100F0000203432460DF19E0104F1090000F0F2FD9B -:100F100026449DF89C30777223720BB9EB7E2372C6 -:100F20008122002106AC27A800F00AFE01222146FA -:100F300027A800F0D1FF00230393AB7E029305F1B5 -:100F4000190380B201932823CDE904400093E97E80 -:100F500005A3D3E90023404602F07AFB5AB0BDE86E -:100F6000F08100BFAFF3008026417272DF25D7B752 -:100F7000F0450020F0B5254E4FF48A7505FB00655D -:100F8000F1B096F8D83085F8DC300024D82221461C -:100F900085F8E8403AA800F0D3FD06F1090000F01A -:100FA000C7FDD5F8E4308DF8F000C2B206AF06F107 -:100FB00009010DF1F100CDE93A3400F09BFD39460D -:100FC00001223AA800F0B4FF80B2CDE904700823F2 -:100FD0000127CDE9023706F1D803019330230093AE -:100FE000317A0B4807A3D3E9002302F031FBA0427A -:100FF00006DD01F065FFC5F8E000384671B0F0BDD0 -:101000002046FBE778F6339F93CACD8DF04500204C -:10101000F03400202DE9F0411D4D1E4E1E4F86B0CC -:10102000284602F041FB034658B30024CDE90344AF -:10103000ADF81440027B8DF8142099684068029442 -:1010400003AA03C21B68DFF8548043F000430293F5 -:1010500001F038FF821941F10003009402A93846DB -:1010600001F0FAF9A04205DD284602F021FB88F8DC -:101070000040D5E798F80030072B05D8013388F8F1 -:10108000003006B0BDE8F081014802F011FBF8E73E -:10109000F034002040420F0020350020254B002076 -:1010A00070B50D4614461E4602F02EFA50B9022EB7 -:1010B00010D1012C0ED112A3D3E90023C5E90023DE -:1010C000012007E0282C10D005D8012C09D0052CD0 -:1010D0000FD0002070BD302CFBD10BA3D3E900232F -:1010E000ECE70BA3D3E90023E8E70BA3D3E9002344 -:1010F000E4E70BA3D3E90023E0E700BFAFF30080F0 -:10110000401DA12026812A0B78F6339F93CACD8DEE -:101110009E6AC421818A46EE26417272DF25D7B7C6 -:10112000F017304A39059E5638B505460E4C002159 -:10113000013500F051FCA4F82C55B4F82C0500F052 -:1011400033FC78B1B4F82C0500F03EFC014648B9F8 -:10115000B4F82C0500F040FCB4F82C350133A4F8A9 -:101160002C35EAE738BD00BFF045002010B50A4B2A -:101170000A4A1A6003F5805393F860203AB9DC6D8F -:101180002CB1204601F000F8204605F091FABDE8A8 -:101190001040034800F0F8BF20350020F868000830 -:1011A000684500202DE9F04F8FB000AF05460C4692 -:1011B00002F0AAF9002849D1237E022B1BD1E38A31 -:1011C000012B18D101F07CFE0646FFF7E1FD034636 -:1011D0004FF4C870DFF8C482B3FBF0F206F5167660 -:1011E00002FB103316FA83F3C8F80030E37E33B9FC -:1011F000A34B00221A703C37BD46BDE8F08F07F1C3 -:101200002401204600F0EAFD0028F4D107F1140083 -:10121000FFF7D6FD97F8264007F11401224607F1A3 -:10122000270005F08FFA0028E2D10F2C08D8944B44 -:101230001C70D8F80030A3F51673C8F80030DAE750 -:1012400097F82410284602F057F9D4E7E38A282BB0 -:101250002BD010D8012B23D0052BCCD1BFF34F8F2F -:101260008849894BCA6802F4E0621343CB60BFF33C -:101270004F8F00BFFDE7302BBDD1844EE17E327A27 -:101280009142B8D1607E3146002291F8DC5085420F -:1012900000F0A5800132042A01F58A71F5D1AAE790 -:1012A00021462846FFF79CFDA5E721462846FFF783 -:1012B00003FEA0E7B2F8EC507B6005F103094FEAAA -:1012C00099094FEA8902D11DC908A8EBC1039D46BF -:1012D000EB460021584600F033FC04F1EE012A46AB -:1012E0003144584600F006FC7B6813B9012000F039 -:1012F0004BFB96F8D20000F057FB044630B9307231 -:1013000000F08AFB204600F03FFBB1E0D6F8D42085 -:101310003AB996F8D200B6F82C25824201D8FFF7E8 -:1013200003FFD6F8D4202A44944208D296F8D2007B -:10133000B6F82C250130824201D8FFF7F5FE70681F -:101340005FFA89F2594600F003FC08B9C54679E016 -:10135000726896F8D2002A447260D6F8D42005EB61 -:101360000209C6F8D49000F01FFB814509D396F816 -:10137000D220D6F8D4000132001B86F8D220C6F85D -:10138000D400FF2D0FD80024347200F045FB204616 -:1013900000F0FAFA00F07AFE3D4B188108B9FFF729 -:1013A0000DFAC54627E7BB6896F8D9000AFB036229 -:1013B000FB68D2F8E41082F8E83001F58061C2F8E9 -:1013C000E030C2F8E410FFF7D5FDFFF723FE96F8F2 -:1013D000D920013202F0030286F8D920B6E74FF493 -:1013E0008A7A0AFB02F505F1EA013144204600F051 -:1013F000CBFDF86000287FF4FEAE3544012285F86D -:10140000E82001F05DFDD5F8E020D6ED007ADFEDB3 -:10141000216A801A192838BF192040F6B832904244 -:1014200028BF1046B8EE677A07EE900AF8EEE77A22 -:1014300067EEA67ADFED186AE7EE267AFCEEE77A29 -:10144000C6ED007A96F8D930BB60BA6873680AFBBB -:1014500002F4321992F8E81059B1D2F8E4108B4234 -:10146000E8463FF427AF002182F8E810C2F8E01008 -:10147000C5467368064A9B0A01331381BBE600BF69 -:10148000E934002000ED00E00400FA05F0450020FA -:10149000D8240020CDCCCC3D6666663FEC340020DD -:1014A000014B1870704700BFE424002030B54FF0A6 -:1014B00000542B4B22689A4285B007D003F092FF6C -:1014C000044620BB0024204605B030BD254B627D7C -:1014D00025481A70237D03724FF48073C0F8F831E9 -:1014E0004FF40073C0F80C3300254FF44073C0F87C -:1014F00020341E49C0F8E450C922093000F0FAFA3D -:101500002046E022294600F01BFB0124DBE7184AB5 -:10151000184D136C43F000731364AA6D164B9A4276 -:10152000D0D12B6E013B7E2BCCD8144A07CA01AB1D -:1015300083E807001846032100F076FD6B6D8342B7 -:101540004FF00003BED12A6D8A4201BFAB65054B47 -:101550002A6E1A7003BF0A4BEA6D1A601C46B2E786 -:101560009AAD44C5E4240020F04500201600002078 -:1015700000380240006600405041A0B0586600406C -:101580001023002037B51A4D00F080FD02236B7147 -:10159000184B288119681848012201F02FFB0023FD -:1015A0000193164B164900931648174B4FF480527F -:1015B00001F07AFF154B197811B1124801F09CFF28 -:1015C00001F07EFC0446FFF7E3FB4FF4C873B0FB69 -:1015D000F3F202FB130304F5167010FA83F00C4BC0 -:1015E000186003F0F5FE08B10F232B8103B030BD66 -:1015F000D82400201023002020350020A11000084E -:10160000E8240020F0340020A5110008E424002084 -:10161000EC3400202DE9F04F2DED028B0FF238292C -:10162000D9E90089834C93B00BAE9FED7E8BFFF719 -:10163000F1FC814FDFF828A200230A93ADF8343083 -:101640000B9373604FF0000B5B468DED008B012513 -:101650000DF11D0207A938468DF81C508DF81DB0FC -:1016600001F07CFA9DF81C30002B40F0A58020464C -:1016700001F04AFF0646002845D1704F01F020FCDA -:101680003B6898423FD301F01BFC8246FFF780FB8A -:101690004FF4C873B0FBF3F202FB13030AF51670A4 -:1016A00010FA83F03860664F97F800B0CBF1100A5B -:1016B000BBF1000F14BF33462B465FFA8AFA0EA81F -:1016C0008DF82830FFF77CFBBAF1060F28BF4FF0EA -:1016D000060A0EAB03EB0B0152460DF1290000F098 -:1016E00009FA0AAB0393182302930AF10102554B3E -:1016F000D2B2CDE90053049220464CA3D3E9002393 -:1017000001F048FF3E7001F0DBFB4F4A4F4D13687C -:10171000C31AB3F57A7F2ED3106001F0D3FB0246D3 -:101720000B46204601F0CEFF204601F0EDFE10B33F -:101730002B7A474E002B14BF03230223737101F051 -:10174000BFFB0EAF4FF47A730122B0FBF3F03946C2 -:101750003060304600F01AFB182302933D4B019392 -:1017600080B240F25513CDE90370009342464B46D8 -:10177000204601F00FFF2B7A93B101F0A1FB002668 -:1017800007464FF48A7A95F8D900304400F00300F8 -:101790000AFB005393F8E82092B30136042EF2D1ED -:1017A000C82003F03DF92B7A002B7FF43DAF13B036 -:1017B000BDEC028BBDE8F08FDAF8143083F480437F -:1017C000CAF81430594610220EA800F0B9F90DF1EC -:1017D0001E0308AA0AA9384600F03CFF96E8030059 -:1017E0000FAB83E803009DF834308DF844300A9B3A -:1017F0000E930EA9DDE90823204602F037F921E710 -:10180000D3F8E02042B12B68FA2B38BFFA23BA1A7A -:101810000533B2EB430FC0D3FFF7ACFB0028BCD1BC -:10182000BEE700BF0000000000000000401DA12036 -:1018300026812A0BF034002020350020EC340020D3 -:10184000E9340020E8340020204B0020F04500203F -:10185000D8240020244B0020F1C6A7C1D068080F6F -:101860000000024008B5054800F08EFFBDE80840C2 -:10187000034A0449002004F015BF00BF20350020B2 -:10188000604B00206D1100087047000070B50F4BD1 -:101890001B780133DBB2012B0C4611D80C4D2968A3 -:1018A0004FF47A730E6AA2FB0332014622462846A1 -:1018B000B047844204D1074B00221A70012070BD4A -:1018C0004FF4FA7003F0ACF80020F8E71C23002076 -:1018D000D84D0020544B002070B504464FF47A7662 -:1018E000412C254628BF412506FB05F003F098F85A -:1018F000641BF5D170BD000007B50023024601212D -:101900000DF107008DF80730FFF7C0FF20B19DF8FB -:10191000070003B05DF804FB4FF0FF30F9E700006B -:101920000A4608B50421FFF7B1FF80F00100C0B2FC -:10193000404208BD30B4054C2368DD69044B0A46BB -:10194000AC460146204630BC604700BFD84D002061 -:10195000A086010070B503F083FB094E094D30806D -:10196000002428683388834208D903F073FB2B686E -:1019700004440133B4F5803F2B60F2D370BD00BF47 -:10198000564B0020284B002003F018BC00F10060EB -:1019900000F580300068704700F10060920000F5AB -:1019A000803003F0A3BB0000054B1A68054B1B8871 -:1019B0009B1A834202D9104403F04CBB00207047AD -:1019C000284B0020564B0020024B1B68184403F0A4 -:1019D00049BB00BF284B0020024B1B68184403F092 -:1019E00059BB00BF284B002010F003030AD1B0F50B -:1019F000047F05D200F10050A0F51040D0F8003867 -:101A0000184670470023FBE700F10050A0F5104096 -:101A1000D0F8100A70470000064991F8243033B11D -:101A20000023086A81F824300822FFF7B5BF01209F -:101A3000704700BF2C4B0020014B1868704700BF57 -:101A4000002004E070B5194B1D68194B0138C5F32F -:101A50000B0408442D0C04221E88A6420BD15C689E -:101A60000A46013C824213460FD214F9016F4EB16F -:101A700002F8016BF6E7013A03F10803ECD1814269 -:101A80000B4602D22C2203F8012B0A4A05241688A1 -:101A9000AE4204D1984284BF967803F8016B013CB2 -:101AA00002F10402F3D1581A70BD00BF002004E017 -:101AB0009C68000888680008022802BF024B4FF0AB -:101AC00080429A61704700BF00000240022802BFB6 -:101AD000024B4FF480429A61704700BF0000024001 -:101AE000022801BF024A536983F48043536170475F -:101AF0000000024010B50023934203D0CC5CC454D4 -:101B00000133F9E710BD000010B5013810F9013FAD -:101B10003BB191F900409C4203D11AB10131013A25 -:101B2000F4E71AB191F90020981A10BD1046FCE7AD -:101B300003460246D01A12F9011B0029FAD1704758 -:101B400002440346934202D003F8011BFAE77047B0 -:101B50002DE9F8431F4D144695F824200746884682 -:101B600052BBDFF870909CB395F824302BB920223B -:101B7000FF2148462F62FFF7E3FF95F82400C0F1EC -:101B80000802A24228BF2246D6B24146920005EB87 -:101B90008000FFF7AFFF95F82430A41B1E44F6B277 -:101BA000082E17449044E4B285F82460DBD1FFF797 -:101BB00033FF0028D7D108E02B6A03EB820383426E -:101BC000CFD0FFF729FF0028CBD10020BDE8F88354 -:101BD0000120FBE72C4B0020024B1A78024B1A70B5 -:101BE000704700BF544B00201C23002010B5104C40 -:101BF000104802F045FA21460E4802F06DFA2468BA -:101C0000626DD2F8043843F00203C2F804384FF48E -:101C10007A70FFF761FE0849204602F063FB626DAF -:101C2000D2F8043823F00203C2F8043810BD00BF14 -:101C3000E4690008D84D0020EC69000870470000F6 -:101C40002DE9F0470D46044600219046284640F213 -:101C50007912FFF775FF234620220021284601F064 -:101C6000A7FE231D02222021284601F0A1FE631DAC -:101C700003222221284601F09BFEA31D03222521D9 -:101C8000284601F095FE04F1080310222821284679 -:101C900001F08EFE04F1100308223821284601F0DD -:101CA00087FE04F1110308224021284601F080FE3E -:101CB00004F1120308224821284601F079FE04F1BC -:101CC000140320225021284601F072FE04F118036B -:101CD00040227021284601F06BFE04F12003082207 -:101CE000B021284601F064FE04F121030822B82146 -:101CF000284601F05DFE04F12207C0263B4631462E -:101D000008222846083601F053FEB6F5A07F07F1F9 -:101D10000107F3D104F1320308223146284601F0CD -:101D200047FE002704F1330A94F832304FEAC7091E -:101D30009F4209F5A47615D3B8F1000F08D13146BA -:101D400004F599730722284601F032FE09F24F1676 -:101D5000274694F832213B1B93420CD3F01DC00858 -:101D6000BDE8F0870AEB070308223146284601F058 -:101D70001FFE0137D8E707F2331331460822284601 -:101D800001F016FE08360137E3E7000013B50446FC -:101D90000846002101602346C0F80310202201906C -:101DA00001F006FE0198231D0222202101F000FE11 -:101DB0000198631D0322222101F0FAFD0198A31D61 -:101DC0000322252101F0F4FD019804F108031022FB -:101DD000282101F0EDFD072002B010BDF7B500236A -:101DE000047F00910E4607221946054601F0A4FC27 -:101DF000731C0093012200230721284601F09CFC5C -:101E0000C4B9B31C0093052223460821284601F0DB -:101E100093FC0D243746B278BB1B934211D32B7F22 -:101E2000A88A0734E408BBB9844294BF002001208B -:101E300003B0F0BDAB8ADB00083BDB08B3700824BD -:101E4000E8E7FB1C0093214600230822284601F006 -:101E500073FC08340137DEE7201A18BF0120E7E7DA -:101E6000F7B50023047F00910E4608221946054667 -:101E700001F062FC731CC4B908220093114623468A -:101E8000284601F059FC1024012372785F1C013BA5 -:101E9000934211D32B7FA88A0734E408BBB984424C -:101EA00094BF0020012003B0F0BDAB8ADB00083BEB -:101EB000DB0873700824E7E7F31900932146002339 -:101EC0000822284601F038FC08343B46DDE7201A9A -:101ED00018BF0120E7E70000F8B50E460546144696 -:101EE000002181223046FFF72BFE2B4608220021DD -:101EF000304601F05DFD7CB96B1C0722082130469D -:101F000001F056FD0F2401236A785F1C013B9342C8 -:101F100004D3E01DC008F8BD0824F4E7EB192146FE -:101F20000822304601F044FD08343B46ECE700004F -:101F3000F8B50E46054614460021CE223046FFF77E -:101F4000FFFD2B4628220021304601F031FD7CB9EF -:101F500005F1080308222821304601F029FD30242C -:101F60002F462A7A7B1B934204D3E01DC008F8BD9C -:101F70002824F5E707F1090321460822304601F03D -:101F800017FD08340137ECE7F7B5047F00910E46E2 -:101F9000012310220021054601F0CEFBC4B9B31C79 -:101FA0000093092223461021284601F0C5FB19247D -:101FB00037467288BB1B9A4211D82B7FA88A0734F8 -:101FC000E408BBB9844294BF0020012003B0F0BDF7 -:101FD000AB8ADB00103BDB0873801024E8E73B1D75 -:101FE0000093214600230822284601F0A5FB08346F -:101FF0000137DEE7201A18BF0120E7E730B5094DA9 -:102000000A4491420DD011F8013B5840082340F397 -:102010000004013B2C4013F0FF0384EA5000F6D18A -:10202000EFE730BD2083B8EDF7B54FF0FF33DFF8B1 -:1020300054C0DFF854E000EB81011A4688421CD0FE -:1020400050F8044B019401AF042417F8015B82EAB5 -:1020500005620825DB18164605F1FF355241002EB2 -:10206000BCBF83EA0C0382EA0E0215F0FF05F1D132 -:10207000013C14F0FF04E8D1E0E7D843D14303B0BA -:10208000F0BD00BF9336EAA9EBE1F042F7B5384A5C -:10209000106851686B4603C36A46364936480823C0 -:1020A00004F060FB0446002833D10A25334A106847 -:1020B00051686B4603C36A4631492F48082304F030 -:1020C00051FB0446002849D00369B3F5702F45D869 -:1020D000B0F8661040F2F63291423FD1294A0244EC -:1020E00002F15C018B4239D35C3B234900209E1AEC -:1020F000FFF784FF3246074604F164010020FFF732 -:102100007DFFA3689F4229D1E368984208BF00255C -:1021100024E00369B3F5702F27D8418B40F2F632E3 -:10212000914220D1174A024402F110018B4218D388 -:10213000103B114900209D1AFFF760FF2A46064612 -:1021400004F118010020FFF759FFA3689E4202D155 -:10215000E368984201D00D25A8E70025284603B082 -:10216000F0BD1025A2E70C25A0E70B259EE700BFD8 -:10217000BC680008DCFF0E0000000108C56800080C -:1021800090FF0E000800FFF710B5037C044613B95A -:10219000006804F0CFFA204610BD00000023BFF312 -:1021A0005B8FC360BFF35B8FBFF35B8F8360BFF355 -:1021B0005B8F7047BFF35B8F0068BFF35B8F704727 -:1021C00070B505460C30FFF7F5FF05F1080604462B -:1021D0003046FFF7EFFFA04206D930466D68FFF7A3 -:1021E000E9FF2544281A70BD3046FFF7E3FF201AA7 -:1021F000F9E7000070B50546406898B105F10800A0 -:10220000FFF7D8FF05F10C0604463046FFF7D2FF72 -:102210008442304694BF6D680025FFF7CBFF013C38 -:102220002C44201A70BD000038B50C460546FFF757 -:10223000C7FFA04210D305F10800FFF7BBFF04441D -:102240006868B4FBF0F100FB1144BFF35B8F012021 -:10225000AC60BFF35B8F38BD0020FCE72DE9F04197 -:10226000144607460D46FFF7C5FF844228BF0446C3 -:10227000D4B1B84658F80C6B4046FFF79BFF30448A -:10228000286040467E68FFF795FF331A9C4203D8CA -:102290006C600120BDE8F0816B60A41B3B68AB6003 -:1022A0002044E8600220F5E72046F3E738B50C4605 -:1022B0000546FFF79FFFA04210D305F10C00FFF782 -:1022C00079FF04446868B4FBF0F100FB1144BFF3EC -:1022D0005B8F0120EC60BFF35B8F38BD0020FCE713 -:1022E0002DE9FF41884669460746FFF7B7FF6C4670 -:1022F00006B204EBC6060025B44209D06268206825 -:1023000008EB0501FFF7F6FB636808341D44F3E7AB -:1023100029463846FFF7CAFF284604B0BDE8F081D9 -:10232000F8B505460C300F46FFF744FF05F10806E7 -:1023300004463046FFF73EFFA042304688BF6C6837 -:10234000FFF738FF201A386020B130462C68FFF7BD -:1023500031FF2044F8BD000073B5144606460D4613 -:10236000FFF72EFF844228BF04460190DCB101A98B -:102370003046FFF7D5FF019B33B93268C5E9023318 -:10238000C5E9002401200CE09C4238BF019428607C -:10239000019868608442F5D93368AB60241AEC6018 -:1023A000022002B070BD2046FBE700002DE9FF418E -:1023B0000F466946FFF7D0FF6C4600B204EBC0053C -:1023C0000026AC4209D0D4F8048054F8081BB81990 -:1023D0004246FFF78FFB4644F3E7304604B0BDE8C2 -:1023E000F081000038B50546FFF7E0FF04460146DE -:1023F0002846FFF719FF204638BD0000302383F33D -:10240000118862B670470000002383F3118862B61A -:102410007047000010B4026854681A4623465DF8FD -:10242000044B184701207047002070470020704778 -:1024300070470000002070470E20704700F5805064 -:1024400090F8C800C0F340007047000000F58050CD -:1024500090F9C90070470000F7B50C68BDF820700E -:1024600014F000541E466FD10B7B082B6CD8FFF77D -:10247000C5FF4569AB685B010CD4AB681B0108D490 -:10248000AC6814F080545DD1FFF7BEFF204603B066 -:10249000F0BD01240B6804F1180C002BB8BFDB0061 -:1024A0004FEA0C1CB4BF43F004035B0545F80C3045 -:1024B0000B680FFA84FC13F0804F18BF05EB0C1E5D -:1024C00005EB0C1C1EBFDEF8803143F00203CEF892 -:1024D00080310B7BCCF8843105EB04158B68C5F893 -:1024E0008C314B68C5F88831DCF8803143F001034A -:1024F000CCF8803100EB441541F268031D4403EB36 -:1025000044130344C5E9002608330D4601F10C0CC1 -:1025100055F804EB43F804EB6545F9D184342D8874 -:102520001D8000EB441407F00303257925F00B050B -:102530002B432371FFF768FF0097334600F0E2FC5E -:102540000120A4E70224A5E74FF0FF309FE7000039 -:1025500013B500F580540191E06DFFF74BFE1F2885 -:102560000AD90199E06D2022FFF7BAFEA0F12003FD -:102570005842584102B010BD0020FBE708B500F5F5 -:102580008050FFF73BFFC06DFFF708FEBDE8084035 -:10259000FFF73ABF0022026082814260826070478A -:1025A00010B500220023C0E9002300230446038164 -:1025B0000C30FFF7EFFF204610BD0000F0B50546D8 -:1025C00000F580500C4690F8C83013F0040FC3F3A8 -:1025D000800108BF114661F3820304F1840680F88C -:1025E000C83005EB461389B01B79D8072ED57AB3CE -:1025F00019072DD46846FFF7D3FF05EB441303F505 -:10260000835303F1180703AA103318685968144656 -:1026100003C40833BB422246F7D1186820609B8868 -:10262000A380DDE90E23CDE900230123ADF80830B6 -:102630002B686946DB6B2846984705EB46152B79D6 -:102640001A075CBF43F008032B7101E0002AF4D1A4 -:1026500009B0F0BD2DE9F047074688B007F5805472 -:1026600068469A468846FFF7C9FE9146FFF798FFED -:10267000E06DFFF7A5FD1F2829D9E06D20226946EE -:10268000FFF7B0FE202822D103AD444605AB2E460D -:1026900003CE9E4220606160354604F10804F6D105 -:1026A00030682060B388A380DDE90023C9E90023F6 -:1026B000BDF80830AAF80030FFF7A6FE4A46534698 -:1026C0004146384608B0BDE8F04700F009BCFFF7C6 -:1026D0009BFE002008B0BDE8F08700002DE9F84F10 -:1026E0000023C0E90133254B044640F8183B0F4650 -:1026F000FFF750FF04F12800FFF752FF04F14808EC -:1027000004F582554646083530462036FFF748FF27 -:10271000AE42F9D104F580554FF480534FF00009D3 -:10272000C5E91339C5F848800123EE6504F58758DB -:1027300004F58456C5F8549085F8583085F8603013 -:10274000083608F108084FF0000A4FF0000B46E980 -:1027500008ABA6F11800FFF71DFF203646F8289CAD -:102760004645F4D185F8C97017B1054800F0A2FBC1 -:10277000044B63612046BDE8F88F00BFF86800088D -:10278000D06800080064004010B5044B1978044676 -:102790004A1C1A70FFF7A2FF204610BD5C4B0020B8 -:1027A0002DE9F047002950D0294B2A4FB7FBF1F50E -:1027B00099428CBF0A231123581EB5FBF3FC03FB7F -:1027C0001C53C4B22BB102280346F5D80020BDE843 -:1027D000F0870CF1FF36B6F5806FF7D2C4EBC40E6C -:1027E0000EF103034FEAE309C3F3C703A4EB0308A5 -:1027F00009F1010A4FF47A755FFA88F009FB055573 -:102800005AFA88F8B5FBF8F5B5F5617FC1BF0EF14E -:10281000FF33C3F3C703E01AC0B25C1C50FA84F460 -:102820000CFB04F4B7FBF4F4A142CFD1013BDBB2C3 -:102830000F2BCBD80138C0B20728C7D800211071A0 -:1028400016809170D3700120C1E70846BFE700BF32 -:102850003F420F0080DE800270B505460E464FF401 -:102860007A746B695B6803F00103B34207D04FF4DD -:102870007A7002F0D5F8013CF3D1204670BD0120FA -:10288000FCE7000030B54269936913F0700F16D071 -:1028900000230B4C936103F1840200EB4212117987 -:1028A0004D0709D5890707D5416954F823508D6034 -:1028B000117941F0040111710133032BEBD130BDCB -:1028C000E468000873B51D46436916469A68D20746 -:1028D000044609D59A6801219960C2F34002CDE906 -:1028E00000650021FFF76AFE63699A68D1050BD580 -:1028F0009A684FF480719960C2F34022CDE9006577 -:1029000001212046FFF75AFE63699A68D2030BD56E -:102910009A684FF480319960C2F34042CDE9006576 -:1029200002212046FFF74AFE204602B0BDE8704073 -:10293000FFF7A8BFF8B50446466900296CD106F137 -:102940000C07386880076AD006EB01153868D5F89F -:10295000B00110F0040FD5F8B0011ABFC00840F064 -:102960000040400DA061D5F8B0C11CF0020F1CBFA3 -:1029700040F08040A061D5F8B40106EB011100F0F1 -:102980000F0084F82400D1F8B8012077D1F8B801FD -:10299000000A6077D1F8B801000CA077D1F8B8012F -:1029A000000EE077D1F8BC0184F82000D1F8BC011A -:1029B000000A84F82100D1F8BC01000C84F8220040 -:1029C000D1F8BC11090E84F823103821396004F1C4 -:1029D000340004F1180104F1240551F8046B40F8A7 -:1029E000046BA942F9D109880180C4E90A23214670 -:1029F0000023238651F8283B2046DB6B984704F5DB -:102A00008052204692F8C83043F0040382F8C83060 -:102A1000BDE8F840FFF736BF06F1100791E7F8BDB3 -:102A200010B5044600F04EFA02460B4652EA030186 -:102A300002D0013A63F100030449086820B121463D -:102A4000BDE81040FFF776BF10BD00BF584B002017 -:102A5000F8B500F583511E46FFF7D0FCDFF844C0FF -:102A60000831002404F1840500EB45152B795F073C -:102A70000ED4DB060CD5D1E900739742B34107D2DF -:102A800043695CF824709F602B7943F004032B7139 -:102A90000134032C01F12001E4D1BDE8F840FFF737 -:102AA000B3BC00BFE468000808B5FFF7A7FCFFF758 -:102AB000E9FEBDE80840FFF7A7BC0000F8B5436990 -:102AC0000546986800F0E050B0F1E05F0F461FD077 -:102AD000E8B1FFF793FC05F583541034002606F1A6 -:102AE000840305EB43131B791A0706D50136032E21 -:102AF00004F12004F3D1012007E05B07F6D421465E -:102B0000384600F039FA0028F0D1FFF77DFCF8BD17 -:102B10000120FCE700F5805008B5FFF76FFCC06DA1 -:102B2000FFF74EFBFFF770FC43090CBF01200020AC -:102B300008BD0000F8B51D46002313700F46064679 -:102B40001446FFF7E7FF80F00100387025B12946F1 -:102B50003046FFF7B3FF2070F8BD00002DE9B84103 -:102B60000C4615461F46804600F0ACF90B4621780E -:102B7000024609B9287850B14046FFF769FFFFF7D0 -:102B800093FF3B462A462146FFF7D4FF0120BDE8CC -:102B9000B881000010B5FFF731FC174B1A6C42F0FA -:102BA00000721A641A6A42F000721A621A6A00F518 -:102BB000805422F000721A62FFF726FC94F8C830A5 -:102BC000DB0718D4B9B103211320FFF717FC01F07C -:102BD000C7F90321142001F0C3F90321152001F0E6 -:102BE000BFF994F8C83043F0010384F8C830BDE859 -:102BF0001040FFF709BC10BD003802402DE9F04736 -:102C000000F5805588B095F8C930012B04468846F8 -:102C100016467FD8804F57F823200AB947F823007B -:102C2000D7F800A0C4F80C802674BAF1000F63D066 -:102C300095F8C930012B6FD001212046FFF7AAFF7C -:102C4000FFF7DCFB6269136823F00203136062691B -:102C5000136843F001031360636900275F6101217A -:102C60002046FFF7D1FBFFF7F7FD002800F0958025 -:102C7000E86DFFF793FA04F58359BA4609F108099C -:102C8000202200216846FEF75BFF02A8FFF782FCC6 -:102C9000CDF818A06A4609EB07030DF1180E94460B -:102CA000BCE80300F44518605960624603F108036C -:102CB000F5D1DCF80000186020379CF804201A7168 -:102CC000602FDDD195F8C8306FF38203002785F8B7 -:102CD000C8306A4641462046ADF80070ADF8027033 -:102CE0008DF80470FFF75CFD636948BB4FF4004248 -:102CF0001A6008B0BDE8F08741F2D00003F0DAFCBA -:102D0000814610B15146FFF7E9FCC7F80090B9F1D0 -:102D1000000F8DD10020ECE7386803681B6B9847E3 -:102D20000146002888D13868FFF734FF3868036807 -:102D300032465B684146984700287FF47DAFE9E75B -:102D400061221A609DF802309DF803201B061204D0 -:102D500002F4702203F040731343BDF80020C2F365 -:102D6000090213439DF804201205022E02F4E0022A -:102D70000CBF4FF000410021134362690B43D36144 -:102D8000636913225A616269136823F001031360B7 -:102D900039462046FFF760FD08B96369A6E795F854 -:102DA000C93093BB6169D1F8002242F00102C1F839 -:102DB00000226169D1F8002222F47C5222F00E0236 -:102DC000C1F800226169D1F8002242F46062C1F8C2 -:102DD00000226269C2F814326269C2F80432626980 -:102DE00041F6FF71C2F80C126269C2F840326269A2 -:102DF000C2F8443263690122C3F81C226269D2F826 -:102E0000003223F00103C2F8003295F8C83043F0D5 -:102E1000020385F8C8306CE7584B002008B500F075 -:102E200051F850EA0103024602D0421E61F100014E -:102E3000044B186810B10B46FFF744FDBDE808408D -:102E400001F064B8584B002008B50020FFF7E8FDFA -:102E5000BDE8084001F05AB808B50120FFF7E0FDD1 -:102E6000BDE8084001F052B800B59BB0EFF309810E -:102E700068226846FEF73EFEEFF30583014B9B6B2D -:102E8000FEE700BF00ED00E008B5FFF7EDFF000032 -:102E900000B59BB0EFF3098168226846FEF72AFE71 -:102EA000EFF30583014B5B6BFEE700BF00ED00E035 -:102EB000FEE700000FB408B5029801F03DFDFEE703 -:102EC00002F0D2B902F0AAB913B56C4684E8060044 -:102ED000031D94E8030083E80500012002B010BD43 -:102EE00073B58568019155B11B885B0707D4D0E99C -:102EF00000369B6B9847019AC1B23046A847012023 -:102F000002B070BDF0B5866889B005460C465EB16A -:102F1000BDF838305B070AD4D0E900379B6B98477F -:102F20002246C1B23846B047012009B0F0BD0022A8 -:102F30000023CDE900230023ADF808300A4603AB97 -:102F400001F10806106851681C4603C40832B242F9 -:102F50002346F7D1106820609288A280FFF7B2FF65 -:102F60000423ADF808302B68CDE90001DB6B69461E -:102F700028469847D8E7000030B503680968DD0F98 -:102F8000B5EBD17F23F0604421F060424FEAD1706D -:102F90000BD0002BB8BFA40C0029B8BF920C9442F0 -:102FA00002D034BF0120002030BD944205D1C1F3CE -:102FB0008070C3F380738342F6D194422CBF00200B -:102FC0000120F1E72DE9F041456A15B94162BDE8FC -:102FD000F0814B6823F06047C3F38A464FEAD37E03 -:102FE000C3F3807816EA230638BF3E46AC462B462C -:102FF0005A68BEEBD27F22F060440AD0002A18DA69 -:10300000A40CB44217D19D420FD10D60DEE71346E8 -:10301000EEE7A74207D102F08044C2F38072424536 -:103020000BD054B1EFE708D2EDE7CCF800100B60FD -:10303000CDE7B44201D0B442E5D81A689C46002AD4 -:10304000E5D11960C3E700002DE9F047089D01F0C4 -:1030500007044FEAD508224405F0070500EBD1002C -:103060004FF47F49944201D1BDE8F08704F007078F -:1030700005F0070A57453E4638BF5646C6F10806D2 -:10308000111B8E4228BF0E46E10808EBD50E415CAD -:1030900013F80EC0B94029FA06F721FA0AF1FFB277 -:1030A0008CEA010147FA0AF739408CEA010C03F86F -:1030B0000EC034443544D5E780EA0120082341F2AC -:1030C000210201B24000002980B203F1FF33B8BFF2 -:1030D000504013F0FF03F4D17047000038B50C46A0 -:1030E0008D18A54200D138BD14F8011BFFF7E4FF8D -:1030F000F7E7000042684AB1136843604389818959 -:1031000001339BB29942438138BF83811046704797 -:1031100070B588B0202204460D4668460021FEF7AF -:103120000FFD20460495FFF7E5FF024658B16B46B8 -:10313000054608AE1C4603CCB442286069602346AD -:1031400005F10805F6D1104608B070BD082817D95A -:1031500009280CD00A280CD00B280CD00C280CD035 -:103160000D280CD00E2814BF4020302070470C20B2 -:103170007047102070471420704718207047202097 -:1031800070470000082817D90C280CD910280CD932 -:1031900014280CD918280CD920280CD930288CBF19 -:1031A0000F200E207047092070470A2070470B201F -:1031B00070470C2070470D20704700002DE9F84340 -:1031C000078C072F04461ED9D0E9029800254FF638 -:1031D000FF73C5F12006A5F1200029FA05F108FAD0 -:1031E00006F628FA00F031430143C9B21846FFF74A -:1031F00063FF0835402D0346EBD1E1693A46BDE84F -:10320000F843FFF76BBF4FF6FF70BDE8F88300008F -:1032100010B54B6823B9CA8A63F30902CA8210BD8C -:1032200004691A681C600361C38A013BC3824A6057 -:10323000EFE700002DE9F84F1D46CB8A0F46C3F398 -:1032400009010529814692460B4630D00020AAB2DA -:1032500007F11A049EB2042E1FFA80F80FD8904589 -:1032600003F1010306D3FB8A0A4462F30903FB82DC -:1032700001201AE01AF80060E6540130EAE79045B0 -:10328000F1D2A1F1050B1C237C68BBFBF3F203FB1D -:1032900012BB1FFA8BF6002C45D14846FFF72AFFD8 -:1032A000044638B978606FF00200BDE8F88F4FF03F -:1032B0000008E6E7002606607860ADB24FF0000B2C -:1032C000454510D90AEB0803221D13F8011B91553F -:1032D000B1B208F101081B291FFA88F82BD0454527 -:1032E00006F10106F1D8FB8AC3F30902154465F320 -:1032F0000903BCE7013292B21C462368002BF9D1C6 -:103300006B1F0B441C21B3FBF1F301339BB29A42B8 -:10331000D3D2BBF1000FD0D14846FFF7EBFE20B966 -:10332000C4F800B0BFE70122E7E7C0F800B05E468E -:1033300020600446C1E74545D5D94846FFF7DAFE87 -:1033400008B92060AFE7C0F800B00026206004464E -:10335000B6E700002DE9F04F2DED028B1C4683B03F -:103360005B69019207468846002B00F09A80238C07 -:103370002BB1E269002A00F09480072B35D807F1C1 -:103380000C00FFF7B7FE054638B96FF00205284676 -:1033900003B0BDEC028BBDE8F08F14220021FEF7D4 -:1033A000CFFB228CE16905F10800FEF7A3FB208C1E -:1033B000013080B2FFF7E6FEFFF7C8FE013880B2A9 -:1033C0002084013028746369228C1B782A4403F01E -:1033D0001F0363F03F0348F00041137238466960F1 -:1033E0002946FFF7EFFD0125D1E700F10C034FF06F -:1033F000000908EE103A4FF0800A4E464D4618EE8E -:10340000100AFFF777FE83460028BED01422002161 -:10341000FEF796FB002E3AD1019BABF80830022252 -:103420000BF1080E1FFA82FC0CF10100BCF1060F33 -:10343000218C80B201D88E422BD3FFF7A3FEFFF779 -:1034400085FE62691278013802F01F028E4208BFC1 -:103450004FF0400A42EA49121BFA80F14AEA020A96 -:10346000013048F0004281F808A08BF81000CBF83A -:10347000042059463846FFF7A5FD238C0135B34299 -:103480002DB289F001094FF0000AB8D17FE7002280 -:10349000C6E7E169895D0EF802100136B6B2013265 -:1034A000C0E76FF0010572E7F8B515460E46302209 -:1034B000002104461F46FEF743FB069B6360B5F5FB -:1034C000001F079BA76034BF6A094FF6FF72A36213 -:1034D00097B2E66104F1100000239A4206D8002357 -:1034E0000360A782E3822383E360F8BD06600133B3 -:1034F00030462036F1E7000003781BB94BB2002BB1 -:10350000C8BF01707047000000787047F8B50C46DE -:10351000C969074611B9238C002B37D1257E1F2D91 -:1035200034D8387828BB228C072A2CD8268A36F043 -:1035300003032BD14FF6FF70FFF7D0FD20F0010001 -:103540003102400441EA0561400C41EA40254FF652 -:10355000FF72234629463846FFF7FCFE002807DDA8 -:10356000626913780133DBB21F2B88BF002313700D -:10357000F8BD218A2D0645EA012505432046FFF7BF -:103580001DFE0246E5E76FF00300F1E76FF0010072 -:10359000EEE7000070B58AB00446164600212822E6 -:1035A00068461D46FEF7CCFABDF83830ADF810304D -:1035B0000F9B05939DF840308DF81830119B0793B1 -:1035C0006946BDF84830ADF820302046CDE90265A7 -:1035D000FFF79CFF0AB070BD2DE9F041D3690546A5 -:1035E0000C4616460BB9138C5BBB377E1F2F28D8B1 -:1035F00095F80080B8F1000F26D03046FFF7DEFDC9 -:103600003378210241EAC33141EA0801338A41EAB1 -:10361000076141EA03410246334641F080012846F2 -:10362000FFF798FE00280ADD3378012B07D1726975 -:1036300013780133DBB21F2B88BF00231370BDE862 -:10364000F0816FF00100FAE76FF00300F7E7000088 -:10365000F0B58BB004460D46174600212822684677 -:103660001E46FEF76DFA9DF84C305A1E53425341E8 -:103670008DF800309DF84030ADF81030119B059367 -:103680009DF848308DF81830149B07936A46BDF8B2 -:103690005430ADF8203029462046CDE90276FFF7B8 -:1036A0009BFF0BB0F0BD0000406A00B104307047D2 -:1036B000436A1A68426202691A600361C38A013B65 -:1036C000C38270472DE9F041D0F82080194E14468E -:1036D0001D464146002709B9BDE8F081D1E9022322 -:1036E000A21A65EB0303964277EB03031ED2036A2B -:1036F0008B420DD1FFF78CFD036A1B6803620369DF -:103700000B60C38A0161016A013BC3828846E2E71C -:10371000FFF77EFD0B68C8F8003003690B60C38AB1 -:103720000161013BC382D8F80010D4E788460968DC -:10373000D1E700BF80841E002DE9F04F8BB00D460D -:10374000DDF8509014469B468046002800F0198111 -:10375000B9F1000F00F01581531E3F2B00F21181CB -:10376000012A03D1BBF1000F40F00B810023CDE90A -:103770000833B8F81430B5EBC30F4FEAC30703D3CF -:1037800000200BB0BDE8F08F2B199F42D8F80C3009 -:103790003ABF7F1BFFB227461BB9D8F81030002B69 -:1037A0007AD0272D4ED8C5F12806B7424FF0000336 -:1037B0002CBFF6B23E4600932946D8F8080008AB65 -:1037C0003246FFF741FCA7EB060A35445FFA8AFA56 -:1037D000B8F8143003F10053053BDB000493D8F82C -:1037E0000C3003932821039B13B1BAF1000F2CD1A5 -:1037F000D8F8100040B1BAF1000F05D0009608AB20 -:103800005246691AFFF720FC38B2002FB8D066077D -:103810000AD00AAB03EBD401624211F8083C02F073 -:103820000702134101F8083C082C3CD9102C40F247 -:10383000B580202C40F2B780BBF1000F00F09C80D7 -:10384000082334E0BA460026C2E7049BE02B28BFD9 -:10385000E02306930B44AB42059314D95A1B0398FB -:103860000096924534BF5246D2B2691A08AB043072 -:103870000792FFF7E9FB079A1644AAEB020A1544E0 -:10388000F6B25FFA8AFA049B069A05999B1A04938A -:10389000039B1B680393A6E70093D8F8080008ABC6 -:1038A0003A462946AEE7BBF1000F13D00123B4EB33 -:1038B000C30F6CD0082C12D89DF82030621E23FA5A -:1038C00002F2D50706D54FF0FF3202FA04F4234383 -:1038D0008DF820309DF8203089F8003051E7102C09 -:1038E00012D8BDF82030621E23FA02F2D10706D5A5 -:1038F0004FF0FF3202FA04F42343ADF82030BDF854 -:103900002030A9F800303CE7202C0FD80899631E1E -:1039100021FA03F3DA0705D54FF0FF3202FA04F477 -:103920000C430894089BC9F800302AE7402C2BD0A0 -:10393000DDE90865611EC4F12102A4F1210326FA24 -:1039400001F105FA02F225FA03F311431943CB07FB -:1039500012D50122A4F12003C4F1200102FA03F3DD -:1039600022FA01F1A240524243EA010363EB43030E -:1039700032432B43CDE90823DDE90823C9E90023BD -:10398000FFE66FF00100FCE66FF00800F9E6082C96 -:10399000A0D9102CB3D9202CEED8C3E7BBF1000F6F -:1039A000ADD0022383E7BBF1000FBBD004237EE739 -:1039B00030B5012A144638BF0124402C85B028BFF9 -:1039C00040240025012ACDE9025518D81B788DF82E -:1039D000083063070AD004AB03EBD405624215F844 -:1039E000083C02F00702934005F8083C00910346AA -:1039F0002246002102A8FFF727FB05B030BD082AA8 -:103A0000E4D9102A03D81B88ADF80830E1E7202A52 -:103A10008DBFD3E900231B680293CDE90223D8E7C9 -:103A200010B5CB681BB98B600B618B8210BD04692C -:103A30001A681C600361C38A013BC382CA60F0E755 -:103A400003064CBFC0F3C0300220704708B50246E1 -:103A5000FFF7F6FF022806D15306C2F30F2001D16B -:103A600000F0030008BDC2F30740FBE72DE9F04F6B -:103A700093B0CDE903230A6804461046FFF7E0FF40 -:103A8000022814BFC2F306260026002A0D468246ED -:103A900080F2F28112F0C04940F0EE81097B0029EA -:103AA00000F0EA81022803D02378B34240F0E78196 -:103AB000C2F304630693104602F07F030593FFF7F9 -:103AC000C5FF059B29444FEA834848EA0A4848EA6B -:103AD0004668CE7800230022CDE90823F309834607 -:103AE00048EA0008029367D0059B00930246676886 -:103AF000534608A92046B847002800F0C381276A2A -:103B00004FB9414604F10C00FFF702FB074690B99C -:103B10006FF0020054E03B6998450DD03F68002FDC -:103B2000F9D1414604F10C00FFF7F2FA07460028EC -:103B3000EED0236A3B60276297F817C006F01F0893 -:103B4000CCF3840CACEB08001FFA80FE0028B8BF51 -:103B50000EF12000A8EB0C031FFA83FED7E9022127 -:103B6000B8BF00B2002B0793BEBF0EF120031BB2FB -:103B7000079352EA010338D0039BDFF824E39A1A33 -:103B8000049B4FF0000C63EB010196457CEB0103B5 -:103B90002BD36B7B97F81AE0734519D1029B002B4E -:103BA00078D0012821DC7868F8B9DFF8F0C29445B4 -:103BB00070EB010316D337E0276A27B96FF00C00CA -:103BC00013B0BDE8F08F3B699845B5D03F68F4E786 -:103BD000B24890427CEB010301D30020F0E7029B46 -:103BE000002BFAD0079B0F2B17DCFA7DB30002F0F5 -:103BF000030203F07C031343FB7539462046FFF7AD -:103C000007FB6B7BBB76029B3BB9FB7DC3F3840256 -:103C1000013262F38603FB75D0E76A7BBB7E9A4272 -:103C2000DBD1029B002B35D0B309022B32D0039B92 -:103C3000BB60049BFB60142200210DA8FDF780FFF0 -:103C4000039B0A93049B0B932B1D0C932B7BADF8CA -:103C50003EB0013BDBB2ADF83C30069B8DF8423004 -:103C6000059B8DF8433094F82C308DF840A083F0FC -:103C700001038DF844308DF84180A3680AA92046DD -:103C80009847FB7DC3F38403013303F01F039B02BA -:103C9000FB82A2E7FB7DC6F34012B2EBD31F40F0DC -:103CA000F480C3F38403434540F0F280029A2B7BF7 -:103CB000B609002A4DD0F2075DD4032B40F2EB8009 -:103CC000039BBB60049BFB602B7BAE1D033BDBB205 -:103CD0003246394604F10C00FFF7ACFA00280CDA42 -:103CE00039462046FFF794FAFB7DC3F38403013382 -:103CF00003F01F039B02FB820AE7DDE90884AB881F -:103D00003B834FF6FF73C9F12000A9F1200228FA86 -:103D100009F104FA00F0014324FA02F211431846B3 -:103D2000C9B2FFF7C9F909F10809B9F1400F034613 -:103D3000E9D1B8822A7B033AD2B23146FFF7CEF9F5 -:103D4000FB7DB882DA43C2F3C01262F3C713FB757E -:103D500043E786B92E1D013BDBB23246394604F1FA -:103D60000C00FFF767FA0028BADB2A7BB88A013A11 -:103D7000D2B23146E2E7F98AC1F30901013B0429D5 -:103D8000DAB25BD8281D002307F11B069A4208D936 -:103D900010F801CB06F801C0013101330529DBB26F -:103DA000F4D103990A9104990B91934207F11B01F5 -:103DB0000C9138BF043379680D9134BF55FA83F301 -:103DC00000230E93FB8AADF83EB0C3F309031A44F7 -:103DD000069B8DF84230059B8DF8433094F82C30CB -:103DE000ADF83C2083F001038DF8443000238DF8BA -:103DF00040A08DF841807B602A7BB88A013A291D5A -:103E0000FFF76CF93B8BB882834203D1A3680AA900 -:103E10002046984720460AA9FFF702FEFB7DBA8A92 -:103E2000C3F38403013303F01F039B02FB823B8B2C -:103E30009A420CBF00206FF01000C1E67B68002B97 -:103E4000AFD0052001E01C3033461E68002EFAD1A9 -:103E5000091A081D2E1D184401EB090CBCF11B0F9B -:103E60005FFA89F39DD89A429BD916F8013B00F876 -:103E7000013B09F10109EFE76FF00900A0E66FF0DF -:103E80000A009DE66FF00B009AE66FF00D0097E6D2 -:103E90006FF00E0094E66FF00F0091E640420F00C5 -:103EA00080841E00EFF3098305494A6B22F001026A -:103EB0004A63683383F30988002383F311887047CA -:103EC00000EF00E0302080F3118862B60C4B0D4A01 -:103ED000D96821F4E0610904090C0A43DA60D3F8D7 -:103EE000FC20094942F08072C3F8FC200A6842F0C5 -:103EF00001020A602022DA7783F82200704700BFAF -:103F000000ED00E00003FA05001000E010B53023DA -:103F100083F311880E4B5B6813F4006314D0F1EE49 -:103F2000103AEFF30984683C4FF08073E361094B6A -:103F3000DB6B236684F3098800F0BCFC10B1064BF0 -:103F4000A36110BD054BFBE783F31188F9E700BFC0 -:103F500000ED00E000EF00E0430600084606000820 -:103F600000F1604303F561430901C9B283F800130E -:103F7000012200F01F039A4043099B0003F16043B4 -:103F800003F56143C3F880211A60704702684368F3 -:103F90001143016003B118477047000013B5446B2B -:103FA000D4F894341A681178042915D1217C022997 -:103FB00012D11979128901238B4013420CD101A926 -:103FC00004F14C0001F0BAFFD4F89444019B21792C -:103FD0000246206800F0D0F902B010BD143001F0A4 -:103FE0003DBF00004FF0FF33143001F037BF000039 -:103FF0004C3002F00FB800004FF0FF334C3002F0AD -:1040000009B80000143001F00BBF00004FF0FF3181 -:10401000143001F005BF00004C3001F0DBBF0000A0 -:104020004FF0FF324C3001F0D5BF00000020704748 -:1040300010B5D0F894341A6811780429044617D1C1 -:10404000017C022914D15979528901238B401342F2 -:104050000ED1143001F09EFE024648B1D4F89444CB -:104060004FF4807361792068BDE8104000F072B9A8 -:1040700010BD0000406BFFF7DBBF00007047000081 -:104080007FB5124B036000234360C0E90233012572 -:1040900002260F4B057404460290019300F184023E -:1040A000294600964FF48073143001F04FFE094BFF -:1040B0000294CDE9006304F523724FF4807329461E -:1040C00004F14C0001F016FF04B070BD386900081F -:1040D000754000089D3F00080B68302282F311886C -:1040E0000A7903EB820290614A79093243F822008F -:1040F0008A7912B103EB820398610223C0F8941409 -:104100000374002080F311887047000038B5037FE6 -:10411000044613B190F85430ABB9201D012502219B -:10412000FFF734FF04F1140025776FF0010100F070 -:104130009FFC84F8545004F14C006FF00101BDE87D -:10414000384000F095BC38BD10B50121044604305C -:10415000FFF71CFF0023237784F8543010BD0000C4 -:1041600038B504460025143001F008FE04F14C0077 -:10417000257701F0D7FE201D84F854500121FFF768 -:1041800005FF2046BDE83840FFF752BF90F84430A5 -:1041900003F06003202B07D190F84520212A4FF02F -:1041A000000303D81F2A06D800207047222AFBD11B -:1041B000C0E90E3303E0034A82630722C26303644B -:1041C000012070471D23002037B5D0F894341A68B9 -:1041D0001178042904461AD1017C022917D11979D2 -:1041E000128901238B40134211D100F14C0528465E -:1041F00001F058FF58B101A9284601F09FFED4F8FC -:104200009444019B21790246206800F0B5F803B080 -:1042100030BD0000F0B500EB810385B09E69044617 -:104220000D46FEB1302383F3118804EB8507301D62 -:104230000821FFF7ABFEFB685B691B6806F14C00C9 -:104240001BB1019001F088FE019803A901F076FEF0 -:10425000024648B1039B2946204600F08DF8002312 -:1042600083F3118805B0F0BDFB685A691268002A13 -:10427000F5D01B8A013B1340F1D104F14402EAE777 -:10428000093138B550F82140DCB1302383F311886F -:10429000D4F894241368527903EB8203DB689B699A -:1042A0005D6845B104216018FFF770FE294604F1EE -:1042B000140001F079FD2046FFF7BAFE002383F3D6 -:1042C000118838BD7047000001F0EEB8012303707B -:1042D0000023C0E90133C36183620362C3624362A6 -:1042E0000363704738B50446302383F311880025F3 -:1042F000C0E90355C0E90555416001F0E5F8022326 -:10430000237085F31188284638BD000070B500EB96 -:10431000810305465069DA600E46144618B1102232 -:104320000021FDF70DFCA06918B110220021FDF756 -:1043300007FC31462846BDE8704001F08FB9000007 -:10434000826802F0011282600022C0E904228261C8 -:1043500001F010BAF0B400EB81044789E46801254C -:10436000A4698D403D43458123600023A2606360C2 -:10437000F0BC01F02BBA0000F0B400EB8104078917 -:10438000E468012564698D403D4305812360002375 -:10439000A2606360F0BC01F0A5BA000070B5022312 -:1043A000002504460370C0E90255C0E90455C56400 -:1043B000856180F8345001F0EDF863681B6823B123 -:1043C00029462046BDE87040184770BD0378052B8C -:1043D00010B504460AD080F85030052303704368B6 -:1043E0001B680BB1042198470023A36010BD000097 -:1043F0000178052906D190F85020436802701B68A7 -:1044000003B118477047000070B590F83430044687 -:1044100013B1002380F8343004F14402204601F047 -:10442000CBF963689B68B3B994F8443013F0600526 -:1044300035D00021204601F06BFC0021204601F020 -:104440005DFC63681B6813B106212046984706236C -:1044500084F8343070BD204698470028E4D0B4F882 -:104460004A30E26B9A4288BFE36394F94430E56BCB -:10447000002B4FF0300380F20381002D00F0F2801A -:10448000092284F8342083F311880021D4E90E2313 -:104490002046FFF771FF002383F31188DAE794F8D1 -:1044A000452003F07F0343EA022340F202329342A5 -:1044B00000F0C58021D8B3F5807F48D00DD8012BFE -:1044C0003FD0022B00F09380002BB2D104F14C02BC -:1044D000A2630222E2632364C1E7B3F5817F00F0A7 -:1044E0009B80B3F5407FA4D194F84630012BA0D136 -:1044F000B4F84C3043F0020332E0B3F5006F4DD016 -:1045000017D8B3F5A06F31D0A3F5C063012B90D8B5 -:10451000636894F846205E6894F84710B4F8483011 -:104520002046B047002884D04368A3630368E36350 -:104530001AE0B3F5106F36D040F6024293427FF492 -:1045400078AF5C4BA3630223E3630023C3E794F8D3 -:104550004630012B7FF46DAFB4F84C3023F00203EA -:10456000C4E90E55A4F84C30256478E7B4F844301B -:10457000B3F5A06F0ED194F8463084F84E30204643 -:1045800001F060F863681B6813B101212046984769 -:10459000032323700023C4E90E339CE704F14F0387 -:1045A000A3630123C3E72378042B10D1302383F3C3 -:1045B00011882046FFF7C4FE85F311880321636844 -:1045C00084F84F5021701B680BB12046984794F82F -:1045D0004630002BDED084F84F300423237063680C -:1045E0001B68002BD6D0022120469847D2E794F8CA -:1045F00048301D0603F00F0120460AD501F0CEF821 -:10460000012804D002287FF414AF2B4B9AE72B4BE0 -:1046100098E701F0B5F8F3E794F84630002B7FF403 -:1046200008AF94F8483013F00F01B3D01A062046B3 -:1046300002D501F081FBADE701F074FBAAE794F825 -:104640004630002B7FF4F5AE94F8483013F00F019C -:10465000A0D01B06204602D501F05AFB9AE701F0D4 -:104660004DFB97E7142284F8342083F311882B46FE -:104670002A4629462046FFF76DFE85F31188E9E6B4 -:104680005DB1152284F8342083F311880021D4E928 -:104690000E232046FFF75EFEFDE60B2284F8342051 -:1046A00083F311882B462A4629462046FFF764FEED -:1046B000E3E700BF686900086069000864690008F2 -:1046C00038B590F834300446002B3ED0063BDAB2C1 -:1046D0000F2A34D80F2B32D8DFE803F037313108F6 -:1046E000223231313131313131313737C56BB0F8A8 -:1046F0004A309D4214D2C3681B8AB5FBF3F203FB18 -:1047000012556DB9302383F311882B462A4629466A -:10471000FFF732FE85F311880A2384F834300EE067 -:10472000142384F83430302383F3118800231A468D -:1047300019462046FFF70EFE002383F3118838BD8B -:10474000036C03B198470023E7E70021204601F0FE -:10475000DFFA0021204601F0D1FA63681B6813B12B -:104760000621204698470623D7E7000010B590F8A9 -:104770003430142B044629D017D8062B05D001D885 -:104780001BB110BD093B022BFBD80021204601F0D4 -:10479000BFFA0021204601F0B1FA63681B6813B12B -:1047A000062120469847062319E0152BE9D10B2353 -:1047B00080F83430302383F3118800231A461946D9 -:1047C000FFF7DAFD002383F31188DAE7C3689B69FA -:1047D0005B68002BD5D1036C03B19847002384F8A4 -:1047E0003430CEE700230375826803691B6899683B -:1047F0009142FBD25A680360426010605860704773 -:1048000000230375826803691B6899689142FBD88D -:104810005A680360426010605860704708B50846E7 -:10482000302383F311880B7D032B05D0042B0DD08F -:104830002BB983F3118808BD8B6900221A604FF0F1 -:10484000FF338361FFF7CEFF0023F2E7D1E90032A7 -:1048500013605A60F3E70000FFF7C4BF054BD96847 -:104860000875186802681A60536001220275D860E2 -:10487000FBF7D2BE684B002030B50C4BDD684B1CFB -:1048800087B004460FD02B46094A684600F084F9E9 -:104890002046FFF7E3FF009B13B1684600F086F95E -:1048A000A86907B030BDFFF7D9FFF9E7684B0020D2 -:1048B0001D480008044B1A68DB6890689B689842A2 -:1048C00094BF002001207047684B0020084B10B5B2 -:1048D0001C68D86822681A60536001222275DC6067 -:1048E000FFF78EFF01462046BDE81040FBF794BE5F -:1048F000684B0020044B1A68DB6892689B689A42F8 -:1049000001D9FFF7E3BF7047684B002038B5074C6B -:1049100007490848012300252370656001F0FAFB70 -:104920000223237085F3118838BD00BFD04D0020CD -:1049300070690008684B002008B572B6044B186512 -:1049400000F050FC00F00EFD024B03221A70FEE74F -:10495000684B0020D04D002000F05EB9EFF31180CD -:1049600020B9EFF30583302282F3118870470000ED -:1049700010B530B9EFF30584C4F3080414B180F323 -:10498000118810BDFFF7B6FF84F31188F9E7000026 -:10499000034A516853685B1A9842FBD8704700BFBE -:1049A000001000E08B60022308618B82084670478C -:1049B0008368A3F1840243F8142C026943F8442C61 -:1049C000426943F8402C094A43F8242CC26843F852 -:1049D000182C022203F80C2C002203F80B2C044A9A -:1049E00043F8102CA3F12000704700BF31060008E7 -:1049F000684B002008B5FFF7DBFFBDE80840FFF774 -:104A00002BBF0000024BDB6898610F20FFF726BF29 -:104A1000684B0020302383F31188FFF7F3BF0000B9 -:104A200008B50146302383F311880820FFF724FFDF -:104A3000002383F3118808BD064BDB6839B1426857 -:104A400018605A60136043600420FFF715BF4FF0F1 -:104A5000FF307047684B00200368984206D01A6800 -:104A60000260506099611846FFF7F6BE704700007B -:104A700038B504460D462068844200D138BD03682D -:104A800023605C608561FFF7E7FEF4E710B503681B -:104A90009C68A2420CD85C688A600B604C60216004 -:104AA000596099688A1A9A604FF0FF33836010BD8D -:104AB0001B68121BECE700000A2938BF0A2170B5F9 -:104AC00004460D460A26601901F01EFB01F00AFBA0 -:104AD000041BA54203D8751C2E460446F3E70A2E94 -:104AE00004D9BDE87040012001F054BB70BD000046 -:104AF000F8B5144B0D46D96103F1100141600A2A43 -:104B00001969826038BF0A22016048601861A818DC -:104B1000144601F0EBFA0A2701F0E4FA431BA34222 -:104B2000064606D37C1C281901F0EEFA27463546C6 -:104B3000F2E70A2F04D9BDE8F840012001F02ABBB2 -:104B4000F8BD00BF684B0020F8B506460D4601F0E1 -:104B5000C9FA0F4A134653F8107F9F4206D12A46DE -:104B600001463046BDE8F840FFF7C2BFD169BB68D7 -:104B7000441A2C1928BF2C46A34202D92946FFF714 -:104B80009BFF224631460348BDE8F840FFF77EBF51 -:104B9000684B0020784B002010B4C0E903230023A9 -:104BA0005DF8044B4361FFF7CFBF000010B5194C0F -:104BB000236998420DD0D0E90032816813605A60B1 -:104BC0009A680A449A60002303604FF0FF33A361A0 -:104BD00010BD2346026843F8102F53600022026084 -:104BE00022699A4203D1BDE8104001F087BA936868 -:104BF00081680B44936001F075FA2269E16992685B -:104C0000441AA242E4D91144BDE81040091AFFF742 -:104C100053BF00BF684B00202DE9F047DFF8BC8090 -:104C200008F110072C4ED8F8105001F05BFAD8F8B4 -:104C30001C40AA68031B9A423ED81444D5E90032AE -:104C40004FF00009C8F81C4013605A60C5F8009086 -:104C5000D8F81030B34201D101F050FA89F311882D -:104C6000D5E9033128469847302383F311886B69CF -:104C7000002BD8D001F036FA6A69A0EB04094A4546 -:104C800082460DD2022001F085FA0022D8F81030B9 -:104C9000B34208D151462846BDE8F047FFF728BF88 -:104CA000121A2244F2E712EB090938BF4A46294694 -:104CB0003846FFF7EBFEB5E7D8F81030B34208D01E -:104CC0001444211AC8F81C00A960BDE8F047FFF79A -:104CD000F3BEBDE8F08700BF784B0020684B002092 -:104CE00000207047FEE70000704700004FF0FF30E3 -:104CF0007047000002290CD0032904D0012907487D -:104D000018BF00207047032A05D8054800EBC200F1 -:104D10007047044870470020704700BF486A000889 -:104D20002C230020FC69000870B59AB0054608469F -:104D300001A9144600F0C2F801A8FCF7F9FE431CD3 -:104D40005B00C5E900340022237003236370C6B200 -:104D500001AB02341046D1B28E4204F1020401D8F4 -:104D60001AB070BD13F8011B04F8021C04F8010C02 -:104D70000132F0E708B5302383F311880348FFF7C9 -:104D800023FA002383F3118808BD00BFD84D00200B -:104D900090F8443003F01F02012A07D190F8452013 -:104DA0000B2A03D10023C0E90E3315E003F06003A2 -:104DB000202B08D1B0F848302BB990F84520212A93 -:104DC00003D81F2A04D8FFF7E1B9222AEBD0FAE76B -:104DD000034A82630722C26303640120704700BF55 -:104DE0002423002007B5052917D8DFE801F019169C -:104DF00003191920302383F31188104A01900121EF -:104E0000FFF784FA01980E4A0221FFF77FFA0D4856 -:104E1000FFF7A6F9002383F3118803B05DF804FBC4 -:104E2000302383F311880748FFF770F9F2E7302346 -:104E300083F311880348FFF787F9EBE79C690008C3 -:104E4000C0690008D84D002038B50C4D0C4C0D49F8 -:104E50002A4604F10800FFF767FF05F1CA0204F1D2 -:104E600010000949FFF760FF05F5CA7204F1180048 -:104E70000649BDE83840FFF757BF00BFA0520020E9 -:104E80002C2300207C6900088669000891690008CD -:104E900070B5044608460D46FCF74AFEC6B22046E9 -:104EA000013403780BB9184670BD32462946FCF729 -:104EB0002BFE0028F3D10120F6E700002DE9F04792 -:104EC00005460C46FCF734FE2B49C6B22846FFF7D0 -:104ED000DFFF08B10636F6B228492846FFF7D8FFAB -:104EE00008B11036F6B2632E0BD8DFF88C80DFF8ED -:104EF0008C90234FDFF894A02E7846B92670BDE839 -:104F0000F08729462046BDE8F04701F091BC252EE8 -:104F10002ED1072241462846FCF7F6FD70B9194B01 -:104F2000224603F10C0153F8040B42F8040B8B42A8 -:104F3000F9D11B78137007350D34DDE70822494697 -:104F40002846FCF7E1FD98B90F4BA21C1978090916 -:104F50000232C95D02F8041C13F8011B01F00F01B5 -:104F60005345C95D02F8031CF0D118340835C3E776 -:104F700004F8016B0135BFE7686A00089169000811 -:104F8000706A00084E680008107AFF1F1C7AFF1F25 -:104F9000BFF34F8F024AD368DB03FCD4704700BFD6 -:104FA000003C024008B5094B1B7873B9FFF7F0FFCE -:104FB000074B1A69002ABFBF064A5A6002F18832BD -:104FC0005A601A6822F480621A6008BDFE540020FC -:104FD000003C02402301674508B50B4B1B7893B991 -:104FE000FFF7D6FF094B1A6942F000421A611A68AE -:104FF00042F480521A601A6822F480521A601A68C9 -:1050000042F480621A6008BDFE540020003C024059 -:105010000B28F0B516D80C4C0C4923787BB90C4DF5 -:105020000E460C234FF0006255F8047B46F8042B23 -:10503000013B13F0FF033A44F6D10123237051F8EA -:105040002000F0BD0020FCE7305500200055002076 -:10505000846A0008014B53F820007047846A0008F6 -:105060000C2070470B2810B5044601D9002010BD54 -:10507000FFF7CEFF064B53F824301844C21A0BB981 -:105080000120F4E712680132F0D1043BF6E700BFDB -:10509000846A00080B2810B5044621D8FFF778FF72 -:1050A000FFF780FF0F4AF323D360C300DBB243F462 -:1050B000007343F002031361136943F480331361F7 -:1050C000FFF766FFFFF7A4FF074B53F8241000F02B -:1050D00045F9FFF781FF2046BDE81040FFF7C2BF4A -:1050E000002010BD003C0240846A0008F8B512F0B0 -:1050F0000103144642D18218B2F1016F57D82D4BEB -:105100001B6813F0010352D02B4DFFF74BFFF32325 -:10511000EB60FFF73DFF40F20127032C15D824F088 -:1051200001046618244C401A40F20117B142236969 -:1051300000EB010524D123F001032361FFF74CFFAD -:105140000120F8BD043C0430E7E78307E7D12B6971 -:1051500023F440732B612B693B432B6151F8046BA3 -:105160000660BFF34F8FFFF713FF03689E42E9D03D -:105170002B6923F001032B61FFF72EFF0020E0E7EE -:1051800023F44073236123693B4323610B882B8005 -:10519000BFF34F8FFFF7FCFE2D8831F8023BADB215 -:1051A000AB42C3D0236923F001032361E4E718462F -:1051B000C7E700BF00380240003C0240084908B57C -:1051C0000B7828B11BB9FFF7EDFE01230B7008BD6A -:1051D000002BFCD0BDE808400870FFF7FDBE00BF03 -:1051E000FE54002008B54FF400314FF0005000F09D -:1051F000B7F8BDE808404FF480314FF0805000F020 -:10520000AFB800000846114601F076BA012001F05F -:1052100073BA0000084601F08DBA000070B582B084 -:10522000FFF79CFB0E4E054600F05CFF3268904293 -:1052300037BF0C4A0B49516814682EBFD1E90041B1 -:10524000013151600419034641F1000128460191E2 -:105250003360FFF78DFB0199204602B070BD00BF9F -:10526000345500203855002070B582B0FFF776FB2A -:10527000104E054600F036FF3268904237BF0E4AA6 -:105280000D49516814682EBFD1E9004101315160C8 -:10529000041941F100010346284601913360FFF7EC -:1052A00067FB01994FF47A7200232046FAF7A0FFBA -:1052B00002B070BD345500203855002010B50244AE -:1052C000064BD2B2904200D110BD441C00B253F83C -:1052D000200041F8040BE0B2F4E700BF5028004082 -:1052E0000F4B30B51C6F240407D41C6F44F40074BA -:1052F0001C671C6F44F400441C670A4C236843F489 -:10530000807323600244084BD2B2904200D130BD7A -:10531000441C00B251F8045B43F82050E0B2F4E7BB -:1053200000380240007000405028004007B50122BC -:1053300001A90020FFF7C2FF019803B05DF804FB4C -:1053400013B50446FFF7F2FFA04205D0012201A9E0 -:1053500000200194FFF7C4FF02B010BD70470000A9 -:105360007047000070470000074B45F255521A6025 -:1053700002225A6040F6FF729A604CF6CC421A60E4 -:10538000024B01221A707047003000404455002043 -:10539000034B1B781BB1034B4AF6AA221A607047D5 -:1053A0004455002000300040034B1A681AB9034AE4 -:1053B000D2F874281A60704740550020003002402F -:1053C000024B4FF08072C3F87428704700300240DF -:1053D00008B5FFF7E9FF024B1868C0F3407008BD3D -:1053E0004055002008B5FFF7DFFF024B1868C0F3F7 -:1053F000007008BD4055002070470000FEE7000027 -:105400000A4B0B480B4A90420BD30B4BDA1C121A77 -:10541000C11E22F003028B4238BF00220021FCF79C -:105420008FBB53F8041B40F8041BECE7A86C000882 -:1054300048560020485600204856002070B5D0E954 -:1054400015439E6800224FF0FF3504EB42135101D3 -:10545000D3F800090028BEBFD3F8000940F080400F -:10546000C3F80009D3F8000B0028BEBFD3F8000B27 -:1054700040F08040C3F8000B013263189642C3F835 -:105480000859C3F8085BE0D24FF00113C4F81C3888 -:1054900070BD0000890141F02001016103699B0694 -:1054A000FCD41220FFF774BA10B5054C2046FEF765 -:1054B0000DFF4FF0A0436365024BA36510BD00BF15 -:1054C00048550020D86A000870B50378012B0546BE -:1054D00050D12A4B446D98421BD1294B5A6B42F054 -:1054E00080025A635A6D42F080025A655A6D5A69B9 -:1054F00042F080025A615A6922F080025A610E21FC -:1055000043205B69FEF72CFD1E4BE3601E4BC4F885 -:1055100000380023C4F8003EC02323606E6D4FF4B2 -:105520000413A3633369002BFCDA012333610C20DD -:10553000FFF72EFA3369DB07FCD41220FFF728FAB5 -:105540003369002BFCDA0026A6602846FFF776FFB9 -:105550006B68C4F81068DB68C4F81468C4F81C6889 -:105560004BB90A4BA3614FF0FF336361A36843F06B -:105570000103A36070BD064BF4E700BF485500204F -:10558000003802404014004003002002003C30C0BC -:10559000083C30C0F8B5446D054600212046FFF7B1 -:1055A00079FFA96D00234FF001128F68C4F83438D9 -:1055B0004FF00066C4F81C284FF0FF3004EB431294 -:1055C00001339F42C2F80069C2F8006BC2F80809B3 -:1055D000C2F8080BF2D20B686A6DEB6563621023A8 -:1055E0001361166916F01006FBD11220FFF7D0F9EF -:1055F000D4F8003823F4FE63C4F80038A36943F4F8 -:10560000402343F01003A3610923C4F81038C4F801 -:1056100014380A4BEB604FF0C043C4F8103B084B02 -:10562000C4F8003BC4F81069C4F80039EB6D03F10D -:10563000100243F48013EA65A362F8BDB46A00085F -:1056400040800010426D90F84E10D2F8003823F4DC -:10565000FE6343EA0113C2F8003870472DE9F843AE -:1056600000EB8103456DDA68166806F00306731EC9 -:10567000022B05EB41130C4680460FFA81F94FEAE5 -:1056800041104FF00001C3F8101B4FF0010104F16D -:10569000100398BFB60401FA03F391698EBF334E2D -:1056A00006F1805606F5004600293AD0578A04F1E3 -:1056B0005801490137436F50D5F81C180B43C5F802 -:1056C0001C382B180021C3F8101953690127611EDB -:1056D000A7409BB3138A928B9B08012A88BF534330 -:1056E000D8F85C20981842EA034301F1400205EB28 -:1056F0008202C8F85C00214653602846FFF7CAFEC4 -:1057000008EB8900C3681B8A43EA84534834640168 -:105710001E432E51D5F81C381F43C5F81C78BDE830 -:10572000F88305EB4917D7F8001B21F40041C7F8AF -:10573000001BD5F81C1821EA0303C0E704F13F035E -:1057400005EB83030A4A5A6028462146FFF7A2FE6A -:1057500005EB4910D0F8003923F40043C0F80039B4 -:10576000D5F81C3823EA0707D7E700BF00800010F0 -:1057700000040002826D1268C265FFF75FBE000080 -:105780005831436D49015B5813F4004004D013F4C1 -:10579000001F0CBF02200120704700004831436DFC -:1057A00049015B5813F4004004D013F4001F0CBFF0 -:1057B000022001207047000000EB8101CB68196ACC -:1057C0000B6813604B6853607047000000EB810367 -:1057D00030B5DD68AA691368D36019B9402B84BF5E -:1057E000402313606B8A1468426D1C44013CB4FB77 -:1057F000F3F46343033323F0030302EB411043EA62 -:10580000C44343F0C043C0F8103B2B6803F00303CC -:10581000012B09B20ED1D2F8083802EB411013F473 -:10582000807FD0F8003B14BF43F0805343F0005317 -:10583000C0F8003B02EB4112D2F8003B43F00443B6 -:10584000C2F8003B30BD00002DE9F041244D6E6DE3 -:1058500006EB40130446D3F8087BC3F8087B3807EF -:105860000AD5D6F81438190706D505EB8403214666 -:10587000DB6828465B689847FA071FD5D6F81438C6 -:10588000DB071BD505EB8403D968CCB98B69488A43 -:105890005A68B2FBF0F600FB16228AB91868DA687B -:1058A00090420DD2121AC3E90024302383F31188E9 -:1058B0000B482146FFF78AFF84F31188BDE8F08189 -:1058C000012303FA04F26B8923EA02036B81CB689C -:1058D000002BF3D021460248BDE8F041184700BF35 -:1058E0004855002000EB810370B5DD68436D6C699D -:1058F0002668E6604A0156BB1A444FF40020C2F8FD -:1059000010092A6802F00302012A0AB20ED1D3F864 -:10591000080803EB421410F4807FD4F8000914BF88 -:1059200040F0805040F00050C4F8000903EB4212F0 -:10593000D2F8000940F00440C2F80009D3F8340856 -:10594000012202FA01F10143C3F8341870BD19B9FC -:10595000402E84BF4020206020682E8A8419013C9C -:10596000B4FBF6F440EAC44040F000501A44C6E7E5 -:105970002DE9F8433B4D6E6D06EB40130446D3F81A -:105980000889C3F8088918F0010F4FEA40171AD0A8 -:10599000D6F81038DB0716D505EB8003D9684B69BC -:1059A0001868DA68904230D2121A4FF000091A6073 -:1059B000C3F80490302383F3118821462846FFF76B -:1059C00091FF89F3118818F0800F1CD0D6F8343875 -:1059D0000126A640334216D005EB84036D6DD3F843 -:1059E0000CC0DCF814200134E4B2D2F800E005EB7E -:1059F00004342F445168714515D3D5F8343823EA5F -:105A00000606C5F83468BDE8F883012303FA04F2FA -:105A10002B8923EA02032B818B68002BD3D02146EC -:105A200028469847CFE7BCF81000AEEB010383424D -:105A300028BF0346D7F8180980B2B3EB800FE2D82D -:105A40009068A0F1040959F8048FC4F80080A0EB15 -:105A500009089844B8F1040FF5D818440B44906035 -:105A60005360C7E7485500202DE9F74FA24C656DFC -:105A70006E69AB691E4016F480586E6107D02046EF -:105A8000FEF78CFC03B0BDE8F04FFEF73FBA002EE6 -:105A900012DAD5F8003E98489B071EBFD5F8003EA5 -:105AA00023F00303C5F8003ED5F8043823F00103C2 -:105AB000C5F80438FEF79CFC370505D58E48FFF77E -:105AC000BDFC8D48FEF782FCB0040CD5D5F8083833 -:105AD00013F0060FEB6823F470530CBF43F410531C -:105AE00043F4A053EB6031071BD56368DB681BB937 -:105AF000AB6923F00803AB612378052B0CD1D5F8F3 -:105B0000003E7D489A071EBFD5F8003E23F00303F0 -:105B1000C5F8003EFEF76CFC6368DB680BB17648A5 -:105B20009847F30274D4B70227D5D4F85490DFF81D -:105B3000C8B100274FF0010A09EB4712D2F8003B29 -:105B400003F44023B3F5802F11D1D2F8003B002B92 -:105B50000DDA62890AFA07F322EA0303638104EB90 -:105B60008703DB68DB6813B1394658469847A36D55 -:105B700001379B68FFB29F42DED9F00617D5676DEB -:105B80003A6AC2F30A1002F00F0302F4F012B2F5FF -:105B9000802F00F08580B2F5402F08D104EB8303FD -:105BA0000022DB681B6A07F5805790426AD13003F8 -:105BB000D5F8184813D5E10302D50020FFF744FEBD -:105BC000A20302D50120FFF73FFE630302D50220A6 -:105BD000FFF73AFE270302D50320FFF735FE7503D2 -:105BE0007FF550AFE00702D50020FFF7C1FEA10707 -:105BF00002D50120FFF7BCFE620702D50220FFF7A5 -:105C0000B7FE23077FF53EAF0320FFF7B1FE39E76C -:105C1000636DDFF8E4A0019300274FF00109A36D45 -:105C20009B685FFA87FB9B453FF67DAF019B03EBCB -:105C30004B13D3F8001901F44021B1F5802F1FD187 -:105C4000D3F8001900291BDAD3F8001941F090416C -:105C5000C3F80019D3F800190029FBDB5946606D21 -:105C6000FFF718FC218909FA0BF321EA03032381CA -:105C700004EB8B03DB689B6813B159465046984789 -:105C80000137CCE7910708BFD7F80080072A98BFF3 -:105C900003F8018B02F1010298BF4FEA182884E74C -:105CA000023304EB830207F580575268D2F818C01C -:105CB000DCF80820DCE9001CA1EB0C0C0021884278 -:105CC0000AD104EB830463689B699A6802449A6072 -:105CD0005A6802445A606AE711F0030F08BFD7F808 -:105CE00000808C4588BF02F8018B01F1010188BF5B -:105CF0004FEA1828E3E700BF48550020436D03EB47 -:105D00004111D1F8003B43F40013C1F8003B704748 -:105D1000436D03EB4111D1F8003943F40013C1F88E -:105D200000397047436D03EB4111D1F8003B23F478 -:105D30000013C1F8003B7047436D03EB4111D1F8EC -:105D4000003923F40013C1F80039704730B5039CC3 -:105D50000172043304FB0325C0E90653049B03636B -:105D60000021059BC160C0E90000C0E90422C0E930 -:105D70000842C0E90A11436330BD0000416A0022B5 -:105D8000C0E90411C0E90A22C2606FF00101FEF708 -:105D90006FBE0000D0E90432934201D1C2680AB953 -:105DA000181D70470020704703691960C2680132EE -:105DB000C260C269134482690361934224BF436A8B -:105DC00003610021FEF748BE38B504460D46E3687E -:105DD0003BB16269131D1268A3621344E3620020A1 -:105DE00007E0237A33B929462046FEF725FE00282E -:105DF000EDDA38BD6FF00100FBE70000C368C2694F -:105E0000013BC3604369134482694361934224BFE9 -:105E1000436A436100238362036B03B118477047F1 -:105E200070B53023044683F31188866A3EB9FFF7C4 -:105E3000CBFF054618B186F31188284670BDA36ACA -:105E4000E26A13F8015BA362934202D32046FFF794 -:105E5000D5FF002383F31188EFE700002DE9F84F09 -:105E600004460E46174698464FF0300989F31188CC -:105E70000025AA46D4F828B0BBF1000F09D141464D -:105E80002046FFF7A1FF20B18BF311882846BDE81B -:105E9000F88FD4E90A12A7EB050B521A934528BFD5 -:105EA0009346BBF1400F1BD9334601F1400251F834 -:105EB000040B43F8040B9142F9D1A36A40334036F6 -:105EC000A3624035D4E90A239A4202D32046FFF761 -:105ED00095FF8AF31188BD42D8D289F31188C9E7AA -:105EE00030465A46FBF706FEA36A5B445E44A36253 -:105EF0005D44E7E710B5029C0172043303FB042103 -:105F0000C0E906130023C0E90A33039B0363049B23 -:105F1000C460C0E90000C0E90422C0E9084243634C -:105F200010BD0000026AC260426AC0E90422002279 -:105F3000C0E90A226FF00101FEF79ABDD0E90423FF -:105F40009A4201D1C26822B9184650F8043B0B604E -:105F5000704700231846FAE7C368C2690133C3607B -:105F60004369134482694361934224BF436A436196 -:105F70000021FEF771BD000038B504460D46E36808 -:105F80003BB123691A1DA262E2691344E362002057 -:105F900007E0237A33B929462046FEF74DFD002855 -:105FA000EDDA38BD6FF00100FBE70000036919600E -:105FB000C268013AC260C2691344826903619342B4 -:105FC00024BF436A036100238362036B03B1184754 -:105FD0007047000070B530230D460446114683F328 -:105FE0001188866A2EB9FFF7C7FF10B186F31188B2 -:105FF00070BDA36A1D70A36AE26A01339342A36273 -:1060000004D3E16920460439FFF7D0FF002080F374 -:106010001188EDE72DE9F84F04460D469046994664 -:106020004FF0300A8AF311880026B346A76A4FB9A9 -:1060300049462046FFF7A0FF20B187F3118830467C -:10604000BDE8F88FD4E90A073A1AA8EB0607974289 -:1060500028BF1746402F1BD905F1400355F8042BE4 -:1060600040F8042B9D42F9D1A36A4033A362403625 -:10607000D4E90A239A4204D3E16920460439FFF7A0 -:1060800095FF8BF311884645D9D28AF31188CDE765 -:1060900029463A46FBF72EFDA36A3B443D44A362E2 -:1060A0003E44E5E7D0E904239A4217D1C3689BB187 -:1060B000836A8BB1043B9B1A0ED01360C368013B0B -:1060C000C360C3691A44836902619A4224BF436A68 -:1060D0000361002383620123184670470023FBE716 -:1060E00000F0D2B84FF08043586A70474FF08043B9 -:1060F000002258631A610222DA6070474FF0804331 -:106100000022DA60704700004FF080435863704708 -:10611000FEE7000070B51B4B01630025044686B006 -:10612000586085620E46FDF7CDFE04F11003C4E908 -:1061300004334FF0FF33C4E90635C4E90044A560D9 -:10614000E562FFF7CFFF2B460246C4E9082304F1BE -:1061500034010D4A256580232046FEF723FC0123E8 -:10616000E0600A4A0375009272680192B268CDE954 -:106170000223074B6846CDE90435FEF73BFC06B029 -:1061800070BD00BFD04D0020E46A0008E96A000835 -:1061900011610008024AD36A1843D062704700BFF9 -:1061A000684B00204B6843608B688360CB68C3609A -:1061B0000B6943614B6903628B6943620B6803603F -:1061C0007047000008B5264B26481A6940F2FF11B7 -:1061D0000A431A611A6922F4FF7222F001021A615D -:1061E0001A691A6B0A431A631A6D0A431A651E4A22 -:1061F0001B6D1146FFF7D6FF02F11C0100F5806010 -:10620000FFF7D0FF02F1380100F58060FFF7CAFF09 -:1062100002F1540100F58060FFF7C4FF02F1700144 -:1062200000F58060FFF7BEFF02F18C0100F5806091 -:10623000FFF7B8FF02F1A80100F58060FFF7B2FF99 -:1062400002F1C40100F58060FFF7ACFF02F1E0014C -:1062500000F58060FFF7A6FFBDE8084000F090B8A9 -:106260000038024000000240F06A000808B500F063 -:10627000FBF9FEF74BFBFFF797F8BDE80840FEF788 -:10628000E3BD0000704700000F4B1A6C42F00102A2 -:106290001A641A6E42F001021A660C4A1B6E936869 -:1062A00043F0010393604FF0804353229A624FF012 -:1062B000FF32DA6200229A615A63DA605A60012280 -:1062C0005A611A60704700BF00380240002004E0A5 -:1062D0004FF0804208B51169D3680B40D9B2C94369 -:1062E0009B07116107D5302383F31188FEF734FB38 -:1062F000002383F3118808BD1F4B1A696FEAC2524D -:106300006FEAD2521A611A69C2F308021A614FF099 -:10631000FF301A695A69586100215A6959615A69EE -:106320001A6A62F080521A621A6A02F080521A6285 -:106330001A6A5A6A58625A6A59625A6A1A6C42F060 -:1063400080521A641A6E42F080521A661A6E0B4A14 -:10635000106840F480701060186F00F44070B0F561 -:10636000007F1EBF4FF4803018671967536823F40D -:106370000073536000F054B90038024000700040D0 -:10638000334B4FF080521A64324A4FF4404111604F -:106390001A6842F001021A601A689107FCD59A68DF -:1063A00022F003029A602A4B9A6812F00C02FBD189 -:1063B000196801F0F90119609A601A6842F4803294 -:1063C0001A601A689203FCD55A6F42F001025A67AC -:1063D0001F4B5A6F9007FCD51F4A5A601A6842F04B -:1063E00080721A601B4A53685904FCD5184B1A680E -:1063F0009201FCD5194A9A60194B1A68194B9A42B6 -:10640000194B21D1194A1168194A91421CD140F205 -:1064100005121A60144A136803F00F03052BFAD112 -:106420000B4B9A6842F002029A609A6802F00C02E2 -:10643000082AFAD15A6C42F480425A645A6E42F4E5 -:1064400080425A665B6E704740F20572E1E700BF1A -:10645000003802400070004008544007009488381B -:10646000002004E011640020003C024000ED00E048 -:1064700041C20F41074A08B5536903F00103536154 -:1064800023B1054A13680BB150689847BDE808402E -:10649000FDF73CBD003C0140C0550020074A08B54F -:1064A000536903F00203536123B1054A93680BB1AA -:1064B000D0689847BDE80840FDF728BD003C014082 -:1064C000C0550020074A08B5536903F0040353611F -:1064D00023B1054A13690BB150699847BDE80840DC -:1064E000FDF714BD003C0140C0550020074A08B527 -:1064F000536903F00803536123B1054A93690BB153 -:10650000D0699847BDE80840FDF700BD003C014058 -:10651000C0550020074A08B5536903F010035361C2 -:1065200023B1054A136A0BB1506A9847BDE8084089 -:10653000FDF7ECBC003C0140C0550020164B10B5E7 -:106540005C6904F478725A61A30604D5134A936A0D -:106550000BB1D06A9847600604D5104A136B0BB193 -:10656000506B9847210604D50C4A936B0BB1D06B46 -:106570009847E20504D5094A136C0BB1506C984753 -:10658000A30504D5054A936C0BB1D06C9847BDE8C0 -:106590001040FDF7BBBC00BF003C0140C0550020CF -:1065A000194B10B55C6904F47C425A61620504D54C -:1065B000164A136D0BB1506D9847230504D5134A45 -:1065C000936D0BB1D06D9847E00404D50F4A136E5C -:1065D0000BB1506E9847A10404D50C4A936E0BB1D1 -:1065E000D06E9847620404D5084A136F0BB1506F00 -:1065F0009847230404D5054A936F0BB1D06F984791 -:10660000BDE81040FDF782BC003C0140C0550020B1 -:1066100008B5FFF75DFEBDE80840FDF777BC000058 -:10662000062108B50846FDF79BFC06210720FDF76B -:1066300097FC06210820FDF793FC06210920FDF7B1 -:106640008FFC06210A20FDF78BFC06211720FDF7A1 -:1066500087FC06212820FDF783FCBDE808400721C0 -:106660001C20FDF77DBC000008B5FFF745FE00F0DB -:106670000BF8FDF729FEFDF701FDFFF703FEBDE86E -:106680000840FFF72DBD00000023054A19460133DD -:10669000102BC2E9001102F10802F8D1704700BFC7 -:1066A000C05500200B460146184600F02DB80000EA -:1066B00000F040B8012838BF012010B5044620463C -:1066C00000F030F830B900F007F808B900F00CF825 -:1066D0008047F4E710BD0000024B1868BFF35B8FE2 -:1066E000704700BF4056002008B5062000F084F82F -:1066F0000120FEF7F7FA0000024B0A46014618682F -:10670000FEF780BD4C23002010B5054C13462CB17C -:106710000A4601460220AFF3008010BD2046FCE788 -:1067200000000000024B01461868FEF76FBD00BF75 -:106730004C230020024B01461868FEF76BBD00BFDA -:106740004C23002010B501390244904201D10020B1 -:1067500005E0037811F8014FA34201D0181B10BDCA -:106760000130F2E72DE9F041A3B1C91A17780144CD -:10677000044603F1FF3C8C42204601D9002009E089 -:106780000578BD4204F10104F5D10CEB0405D618DF -:10679000A54201D1BDE8F08115F8018D16F801ED93 -:1067A000F045F5D0E7E700001F2938B504460D464F -:1067B00004D9162303604FF0FF3038BD426C12B18C -:1067C00052F821304BB9204600F030F82A460146F5 -:1067D0002046BDE8384000F017B8012B0AD0591CFC -:1067E00003D1162303600120E7E7002442F8254087 -:1067F000284698470020E0E7024B01461868FFF75B -:10680000D3BF00BF4C23002038B5074D00230446FA -:10681000084611462B60FEF769FA431C02D12B682B -:1068200003B1236038BD00BF44560020FEF758BABC -:10683000034611F8012B03F8012B002AF9D1704708 -:106840006F72672E6172647570696C6F742E663436 -:1068500030352D4D6174656B4750530053544D33A3 -:1068600032463F3F3F0053544D3332463430780078 -:1068700053544D3332463432780053544D333246FC -:106880003434365858000000012033000010410015 -:1068900001105A00031059000710310000000000D9 -:1068A0005C68000813040000666800081904000012 -:1068B00070680008210400007A68000840A2E4F132 -:1068C000646891060041A3E5F26569920700000043 -:1068D0004261642043414E496661636520696E648C -:1068E00065782E008000000000800000000080001D -:1068F000000000000000000015240008FD2B000827 -:106900005D2B00082524000859240008552600089E -:1069100029240008392400082D2400083524000803 -:10692000312400087D2500083D240008C92E0008F8 -:106930004D2400085125000800000000F93F000820 -:10694000E53F0008214000080D40000819400008FC -:1069500005400008F13F0008DD3F00082D40000819 -:106960000000000001000000000000006330000093 -:106970006C690008C04B0020D04D00204172647546 -:1069800050696C6F740025424F415244252D424C92 -:10699000002553455249414C2500000002000000EB -:1069A000000000001542000881420008400040003D -:1069B0007052002080520020020000000000000001 -:1069C0000300000000000000C542000800000000B5 -:1069D00010000000905200200000000001000000A4 -:1069E000000000004855002001010200E54D0008AC -:1069F000F54C0008914D0008754D0008430000005B -:106A0000046A000809024300020100C032090400C0 -:106A1000000102020100052400100105240100010B -:106A2000042402020524060001070582030800FF72 -:106A300009040100020A00000007050102400000ED -:106A4000070581024000000012000000506A0008A3 -:106A50001201100102000040091241570002010218 -:106A6000030100000403090425424F41524425005C -:106A70003031323334353637383941424344454674 -:106A80000000000000400000004000000040000046 -:106A900000400000000001000000020000000200B1 -:106AA00000000200000002000000020000000200DE -:106AB000000002000000000009440008C146000870 -:106AC0006D47000840004000A8550020A855002050 -:106AD00001000000B85500208000000040010000C7 -:106AE000030000006D61696E0069646C6500000060 -:106AF000AA01A81200000000AAAAAAAA550114001F -:106B0000FFBF00008877000070A70A0000000A019C -:106B100000000000AAAAAAAA00000001FFFF0000CE -:106B200000000000990000000000A0160000000016 -:106B3000AAAAAAA600005011FFDF00000000000072 -:106B4000007708002000000000000000AAAAAAAAFE -:106B500010000000FFFF000000080000000000001F -:106B60000000000000000000AAAAAAAA000000007D -:106B7000FFFF000000000000000000000000000017 -:106B800000000000AAAAAAAA00000000FFFF00005F -:106B900000000000000000000000000000000000F5 -:106BA000AAAAAAAA00000000FFFF0000000000003F -:106BB0000000000000000000000000000A000000CB -:106BC00000000000030000000000000000000000C2 -:106BD00000000000000000000000000000000000B5 -:106BE0000000000000000000000000003496FF7F5D -:106BF0000100000000000000F6030000000000009B -:106C000000000F000000000040420F00FE2A0100BB -:106C1000D2040000FF00960000000008009600006B -:106C20000000080004000000646A00080000000082 -:106C30000000000000000000000000000000000054 -:106C400000000000502300200000000000000000B1 -:106C50000000000000000000000000000000000034 -:106C60000000000000000000000000000000000024 -:106C70000000000000000000000000000000000014 -:106C80000000000000000000000000000000000004 -:106C900000000000000000000000000000000000F4 -:086CA0000000000000000000EC +:1000000000070020F1010008DD2B0008952B0008F7 +:10001000BD2B0008952B0008B52B0008F301000844 +:10002000F3010008F3010008F3010008D13B0008C8 +:10003000F3010008F3010008F3010008F3010008D0 +:10004000F3010008F3010008F3010008F3010008C0 +:10005000F3010008F3010008656100088D610008E4 +:10006000B5610008DD61000805620008F3010008C1 +:10007000F3010008F3010008F3010008F301000890 +:10008000F3010008F3010008F3010008492B000800 +:10009000752B0008852B0008F30100082D6200086D +:1000A000F3010008F3010008F3010008F301000860 +:1000B00001630008F3010008F3010008F3010008E0 +:1000C000F3010008F3010008F3010008F301000840 +:1000D000F3010008F3010008F3010008F301000830 +:1000E00091620008F3010008F3010008F301000821 +:1000F000F3010008F3010008F3010008F301000810 +:10010000F3010008F3010008F3010008F3010008FF +:10011000F3010008F3010008F3010008F3010008EF +:10012000F3010008F3010008F3010008F3010008DF +:10013000F3010008F3010008F3010008F3010008CF +:10014000F3010008F3010008F30100085957000803 +:10015000F3010008F3010008F3010008F3010008AF +:10016000F3010008F3010008F3010008F30100089F +:10017000F3010008F3010008F3010008F30100088F +:10018000F3010008F3010008F3010008F30100087F +:10019000F3010008F3010008F3010008F30100086F +:1001A000F3010008F3010008F3010008F30100085F +:1001B000F3010008F3010008F3010008F30100084F +:1001C000F3010008F3010008F3010008F30100083F +:1001D000F3010008F3010008F3010008F30100082F +:1001E0007115000800000000000000000000000081 +:1001F00002E000F000F8FEE772B6374880F30888A6 +:10020000364880F3098836483649086040F20000D5 +:10021000CCF200004EF63471CEF200010860BFF35C +:100220004F8FBFF36F8F40F20000C0F2F0004EF628 +:100230008851CEF200010860BFF34F8FBFF36F8F7C +:100240004FF00000E1EE100A4EF63C71CEF20001D4 +:100250000860062080F31488BFF36F8F04F044FF1A +:1002600005F028FE4FF055301F491B4A91423CBF14 +:1002700041F8040BFAE71D49184A91423CBF41F886 +:10028000040BFAE71A491B4A1B4B9A423EBF51F82E +:10029000040B42F8040BF8E700201849184A914271 +:1002A0003CBF41F8040BFAE704F022FF05F056FECC +:1002B000144C154DAC4203DA54F8041B8847F9E797 +:1002C00000F042F8114C124DAC4203DA54F8041B12 +:1002D0008847F9E704F00ABF000700200023002048 +:1002E0000000000808ED00E00001002000070020E9 +:1002F000E068000800230020B0230020B023002085 +:1003000044560020E0010008E4010008E401000870 +:10031000E40100082DE9F04F2DED108AC1F80CD052 +:10032000C3689D46BDEC108ABDE8F08F002383F3BF +:1003300011882846A047002004F0DCF9FEE704F00D +:100340005BF900DFFEE70000F8B501F077F904F093 +:1003500065FE074604F0B4FE0546A8BB1F4B9F424E +:1003600032D001339F4232D01D4B27F0FF029A4218 +:1003700030D1F8B200F01AFF2E4642F2107400F0AD +:100380001BFF08B10024264601F004FD20B1032024 +:1003900000F07AF80024264635B1124B9F4203D074 +:1003A00004F086FE00242646002004F041FE0EB133 +:1003B00000F080F801F09EFA00F06AFF204600F09D +:1003C000DFF800F077F8F9E72E460024D7E7044677 +:1003D0000126D4E7064641F28834D0E7010007B091 +:1003E000000008B0263A09B008B501F0F9F8A0F10C +:1003F00020035842584108BD07B541F212030221BB +:1004000001A8ADF8043001F009F903B05DF804FB70 +:1004100038B5302383F31188174803680BB104F013 +:1004200035FA164A144800234FF47A7104F024FA7E +:10043000002383F31188124C236813B12368013B16 +:100440002360636813B16368013B63600D4D2B78D3 +:1004500033B963687BB9022001F0B6F932236360D7 +:100460002B78032B07D163682BB9022001F0ACF97C +:100470004FF47A73636038BDB02300201104000884 +:10048000D0240020C8230020084B187003280CD863 +:10049000DFE800F008050208022001F08BB9022015 +:1004A00001F07EB9024B00225A607047C823002039 +:1004B000D024002010B501F06DFC30B1294B03228F +:1004C0001A70294B00225A6010BD284B284A1C463E +:1004D00019680131F8D004339342F9D16268254B91 +:1004E0009A42F1D9244B9B6803F1006303F58033F2 +:1004F0009A42E9D204F0B0FD04F0C2FD002001F000 +:10050000B7F80220FFF7C0FF1C4B1A6C00221A64D8 +:10051000196E1A66196E596C5A64596E5A665A6E7B +:100520005A6942F080025A615A6922F080025A6187 +:100530005A691A6942F000521A611A6922F000528F +:100540001A611B6972B64FF0E0233021C3F8084DE1 +:10055000D4E9003281F311889D4683F3088810475F +:10056000B2E700BFC8230020D0240020000001080B +:1005700020000108FFFF000800230020003802408F +:100580002DE9F04F93B0AC4B00902022FF210AA838 +:100590009D6801F059F9A94A1378A3B9A848012127 +:1005A00003601170302383F3118803680BB104F0EA +:1005B0006DF9A44AA24800234FF47A7104F05CF963 +:1005C000002383F31188009B13B19F4B009A1A609C +:1005D0009E4A009C1378032B1EBF002313709A4A77 +:1005E0004FF0000A18BF5360D3465646D14601204B +:1005F00001F0E0F824B1944B1B68002B00F0158249 +:10060000002000F0EDFF0390039B002B01DA00F0C7 +:1006100087FE039B002BEDDB012001F0C1F8039B5B +:10062000213B162BE3D801A252F823F089060008DB +:10063000B106000845070008EF050008EF050008AF +:10064000EF050008CF0700089F090008B908000857 +:100650001B0900084309000869090008EF050008A4 +:100660007B090008EF050008ED09000829070008CC +:10067000EF050008310A0008950600082907000860 +:10068000EF0500081B0900080220FFF7ADFE002857 +:1006900040F0F581009B0221BAF1000F08BF1C4613 +:1006A00005A841F21233ADF8143000F0B7FF9EE711 +:1006B0004FF47A7000F094FF071EEBDB0220FFF787 +:1006C00093FE0028E6D0013F052F00F2DA81DFE833 +:1006D00007F0030A0D10133605230593042105A81E +:1006E00000F09CFF17E054480421F9E75848042122 +:1006F000F6E758480421F3E74FF01C08404600F0A5 +:10070000B9FF08F104080590042105A800F086FF50 +:10071000B8F12C0FF2D1012000FA07F747EA0B0BD2 +:100720005FFA8BFB4FF0000901F0DAF826B10BF00D +:100730000B030B2B08BF0024FFF75EFE57E746486C +:100740000421CDE7002EA5D00BF00B030B2BA1D17C +:100750000220FFF749FE074600289BD0012000F049 +:1007600087FF0220FFF790FE00261FFA86F840461A +:1007700000F08EFF044690B10021404600F0A0FF3B +:1007800001360028F1D1BA46044641F21213022183 +:1007900005A8ADF814303E4600F040FF27E70120E1 +:1007A000FFF772FE2546244B9B68AB4207D92846CB +:1007B00000F060FF013040F067810435F3E7234B20 +:1007C00000251D70204BBA465D603E46ACE7002E0A +:1007D0003FF460AF0BF00B030B2B7FF45BAF0220F9 +:1007E000FFF752FE322000F0FBFEB0F10008FFF6EA +:1007F00051AF18F003077FF44DAF0F4A926808EB32 +:10080000050393423FF646AFB8F5807F3FF742AF0E +:10081000124B0193B84523DD4FF47A7000F0E0FEEF +:100820000390039A002AFFF635AF019B039A03F861 +:10083000012B0137EDE700BF00230020CC2400206E +:10084000B023002011040008D0240020C823002079 +:1008500004230020082300200C230020CC230020A8 +:10086000C820FFF7C1FD074600283FF413AF1F2D36 +:1008700011D8C5F1200242450AAB25F0030028BF7C +:10088000424683490192184400F0B8FF019A80481B +:10089000FF2100F0D9FF4FEAA8037D490193C8F377 +:1008A0008702284600F0D8FF064600283FF46DAFC7 +:1008B000019B05EB830537E70220FFF795FD002834 +:1008C0003FF4E8AE00F01CFF00283FF4E3AE002741 +:1008D000B846704B9B68BB4218D91F2F11D80A9B92 +:1008E00001330ED027F0030312AA134453F8203C1F +:1008F00005934046042205A901F004FA0437804616 +:10090000E7E7384600F0B6FE0590F2E7CDF8148030 +:10091000042105A800F082FE06E70023642104A854 +:10092000049300F071FE00287FF4B4AE0220FFF7BC +:100930005BFD00283FF4AEAE049800F0C9FE0590C0 +:10094000E6E70023642104A8049300F05DFE00287C +:100950007FF4A0AE0220FFF747FD00283FF49AAED7 +:10096000049800F0C5FEEAE70220FFF73DFD0028ED +:100970003FF490AE00F0D4FEE1E70220FFF734FD33 +:1009800000283FF487AE05A9142000F0CFFE042113 +:100990000746049004A800F041FE3946B9E732202A +:1009A00000F01EFE071EFFF675AEBB077FF472AEA9 +:1009B000384A926807EB090393423FF66BAE022078 +:1009C000FFF712FD00283FF465AE27F003074F4400 +:1009D000B9453FF4A9AE484600F04CFE042105900D +:1009E00005A800F01BFE09F10409F1E74FF47A7045 +:1009F000FFF7FAFC00283FF44DAE00F081FE00281E +:100A000044D00A9B01330BD008220AA9002000F031 +:100A100023FF00283AD02022FF210AA800F014FF6B +:100A2000FFF7EAFC1C4803F06BFE13B0BDE8F08F43 +:100A3000002E3FF42FAE0BF00B030B2B7FF42AAEEE +:100A40000023642105A8059300F0DEFD0746002879 +:100A50007FF420AE0220FFF7C7FC804600283FF459 +:100A600019AEFFF7C9FC41F2883003F049FE059842 +:100A700000F068FF464600F033FF3C46B7E5064607 +:100A800052E64FF0000905E6BA467EE637467CE6B8 +:100A9000CC23002000230020A0860100094A13680F +:100AA00049F2690099B21B0C00FB01331360064B3D +:100AB000186844F2506182B2000C01FB0200186019 +:100AC00080B27047182300201423002010B50021A5 +:100AD0001022044600F0B8FE034B03CB2060616097 +:100AE0001868A06010BD00BF107AFF1F2DE9F0410B +:100AF000ADF54E7D0DF134086CAC40F27512074631 +:100B00000D460EA80021C8F8001000F09DFE4FF41D +:100B1000C4720021204600F097FE02F067F8274BD0 +:100B20004FF47A72B0FBF2F0186093E807000223EA +:100B300084E807000DF5E9702382FFF7C7FF4FF245 +:100B400003631F49238406A805F0EAFC1B2384F8ED +:100B500032310DF2E32206AB0DF1300C1E4603CE0E +:100B6000664510605160334602F10802F6D13188C3 +:100B7000B3789370118020464146012200F0E4FED4 +:100B800000230393AB7E029305F11903019380B216 +:100B90000123CDE904800093E97E06A3D3E9002375 +:100BA000384602F0EBFB0DF54E7DBDE8F08100BF4D +:100BB000AFF300809E6AC421818A46EED8240020CB +:100BC000306500082DE9F0412C4C237ADAB08046DC +:100BD0000D465BBB27A9284600F0C6FF0746002844 +:100BE00042D19DF89D60C82E3ED801464FF4A662C2 +:100BF000204600F029FE4FF48073C4F8F8314FF41A +:100C00000073C4F80C334FF44073C4F820343246F8 +:100C10000DF19E0104F1090000F0F0FD26449DF85D +:100C20009C30777223720BB9EB7E237281220021F4 +:100C300006AC27A800F008FE0122214627A800F0F4 +:100C4000CFFF00230393AB7E029305F1190380B21B +:100C500001932823CDE904400093E97E05A3D3E95D +:100C60000023404602F08AFB5AB0BDE8F08100BF85 +:100C7000AFF3008026417272DF25D7B7F845002018 +:100C8000F0B5254E4FF48A7505FB0065F1B096F876 +:100C9000D83085F8DC300024D822214685F8E84099 +:100CA0003AA800F0D1FD06F1090000F0C5FDD5F825 +:100CB000E4308DF8F000C2B206AF06F109010DF183 +:100CC000F100CDE93A3400F099FD394601223AA805 +:100CD00000F0B2FF80B2CDE9047008230127CDE90E +:100CE000023706F1D803019330230093317A0B4881 +:100CF00007A3D3E9002302F041FBA04206DD01F087 +:100D000075FFC5F8E000384671B0F0BD2046FBE73E +:100D100078F6339F93CACD8DF8450020F03400203B +:100D20002DE9F0411D4D1E4E1E4F86B0284602F0A3 +:100D300051FB034658B30024CDE90344ADF81440F9 +:100D4000027B8DF8142099684068029403AA03C2BC +:100D50001B68DFF8548043F00043029301F048FF22 +:100D6000821941F10003009402A9384601F0F0F91C +:100D7000A04205DD284602F031FB88F80040D5E7A7 +:100D800098F80030072B05D8013388F8003006B0FA +:100D9000BDE8F081014802F021FBF8E7F0340020C3 +:100DA00040420F00203500202D4B002070B50D462D +:100DB00014461E4602F03EFA50B9022E10D1012C04 +:100DC0000ED112A3D3E90023C5E90023012007E0D7 +:100DD000282C10D005D8012C09D0052C0FD00020CC +:100DE00070BD302CFBD10BA3D3E90023ECE70BA3A0 +:100DF000D3E90023E8E70BA3D3E90023E4E70BA33F +:100E0000D3E90023E0E700BFAFF30080401DA1203D +:100E100026812A0B78F6339F93CACD8D9E6AC42112 +:100E2000818A46EE26417272DF25D7B7F017304A25 +:100E300039059E5638B505460E4C0021013500F0A7 +:100E40003FFCA4F82C55B4F82C0500F021FC78B137 +:100E5000B4F82C0500F02CFC014648B9B4F82C0578 +:100E600000F02EFCB4F82C350133A4F82C35EAE759 +:100E700038BD00BFF845002010B50A4B0A4A1A6079 +:100E800003F5805393F860203AB9DC6D2CB120460D +:100E900000F0FEFF204605F083FABDE8104003484D +:100EA00000F0F6BF20350020E86500086845002006 +:100EB0002DE9F04F8FB000AF05460C4602F0BAF9AD +:100EC000002849D1237E022B1BD1E38A012B18D1A4 +:100ED00001F08CFE0646FFF7E1FD03464FF4C870B3 +:100EE000DFF8C482B3FBF0F206F5167602FB10338E +:100EF00016FA83F3C8F80030E37E33B9A34B00221F +:100F00001A703C37BD46BDE8F08F07F1240120463A +:100F100000F0E8FD0028F4D107F11400FFF7D6FD3A +:100F200097F8264007F11401224607F1270005F043 +:100F300081FA0028E2D10F2C08D8944B1C70D8F805 +:100F40000030A3F51673C8F80030DAE797F82410DC +:100F5000284602F067F9D4E7E38A282B2BD010D873 +:100F6000012B23D0052BCCD1BFF34F8F8849894B60 +:100F7000CA6802F4E0621343CB60BFF34F8F00BF37 +:100F8000FDE7302BBDD1844EE17E327A9142B8D15B +:100F9000607E3146002291F8DC50854200F0A58049 +:100FA0000132042A01F58A71F5D1AAE721462846C3 +:100FB000FFF79CFDA5E721462846FFF703FEA0E7C3 +:100FC000B2F8EC507B6005F103094FEA99094FEA4A +:100FD0008902D11DC908A8EBC1039D46EB4600213B +:100FE000584600F031FC04F1EE012A4631445846DF +:100FF00000F004FC7B6813B9012000F039FB96F87F +:10100000D20000F045FB044630B9307200F078FBA6 +:10101000204600F02DFBB1E0D6F8D4203AB996F87E +:10102000D200B6F82C25824201D8FFF703FFD6F88C +:10103000D4202A44944208D296F8D200B6F82C253F +:101040000130824201D8FFF7F5FE70685FFA89F23D +:10105000594600F001FC08B9C54679E0726896F877 +:10106000D2002A447260D6F8D42005EB0209C6F8F3 +:10107000D49000F00DFB814509D396F8D220D6F824 +:10108000D4000132001B86F8D220C6F8D400FF2D10 +:101090000FD80024347200F033FB204600F0E8FA49 +:1010A00000F078FE3D4B188108B9FFF703FAC546FA +:1010B00027E7BB6896F8D9000AFB0362FB68D2F801 +:1010C000E41082F8E83001F58061C2F8E030C2F83F +:1010D000E410FFF7D5FDFFF723FE96F8D920013283 +:1010E00002F0030286F8D920B6E74FF48A7A0AFBA9 +:1010F00002F505F1EA013144204600F0C9FDF8602F +:1011000000287FF4FEAE3544012285F8E82001F086 +:101110006DFDD5F8E020D6ED007ADFED216A801A6A +:10112000192838BF192040F6B832904228BF10461F +:10113000B8EE677A07EE900AF8EEE77A67EEA67ADD +:10114000DFED186AE7EE267AFCEEE77AC6ED007A64 +:1011500096F8D930BB60BA6873680AFB02F432199A +:1011600092F8E81059B1D2F8E4108B42E8463FF407 +:1011700027AF002182F8E810C2F8E010C546736876 +:10118000064A9B0A01331381BBE600BFE934002005 +:1011900000ED00E00400FA05F8450020D824002006 +:1011A000CDCCCC3D6666663FEC340020014B187018 +:1011B000704700BFE424002030B54FF000542B4BA3 +:1011C00022689A4285B007D003F084FF044620BB12 +:1011D0000024204605B030BD254B627D25481A709D +:1011E000237D03724FF48073C0F8F8314FF400731D +:1011F000C0F80C3300254FF44073C0F820341E496A +:10120000C0F8E450C922093000F0F8FA2046E02284 +:10121000294600F019FB0124DBE7184A184D136C2E +:1012200043F000731364AA6D164B9A42D0D12B6E13 +:10123000013B7E2BCCD8144A07CA01AB83E80700D8 +:101240001846032100F074FD6B6D83424FF00003DC +:10125000BED12A6D8A4201BFAB65054B2A6E1A705A +:1012600003BF0A4BEA6D1A601C46B2E79AAD44C54B +:10127000E4240020F8450020160000200038024039 +:10128000006600405041A0B0586600401023002086 +:1012900037B51A4D00F07EFD02236B71184B288183 +:1012A00019681848012201F03DFB00230193164BF9 +:1012B000164900931648174B4FF4805201F08AFFED +:1012C000154B197811B1124801F0ACFF01F08EFCFA +:1012D0000446FFF7E3FB4FF4C873B0FBF3F202FBE5 +:1012E000130304F5167010FA83F00C4B186003F02A +:1012F000E7FE08B10F232B8103B030BDD8240020B6 +:101300001023002020350020AD0D0008E824002027 +:10131000F0340020B10E0008E4240020EC3400205A +:101320002DE9F04F2DED028B0FF23829D9E9008914 +:10133000834C93B00BAE9FED7E8BFFF7F1FC814F9A +:10134000DFF828A200230A93ADF834300B937360C2 +:101350004FF0000B5B468DED008B01250DF11D025A +:1013600007A938468DF81C508DF81DB001F088FA99 +:101370009DF81C30002B40F0A580204601F05AFF5C +:101380000646002845D1704F01F030FC3B6898427A +:101390003FD301F02BFC8246FFF780FB4FF4C8736C +:1013A000B0FBF3F202FB13030AF5167010FA83F098 +:1013B0003860664F97F800B0CBF1100ABBF1000F10 +:1013C00014BF33462B465FFA8AFA0EA88DF82830F0 +:1013D000FFF77CFBBAF1060F28BF4FF0060A0EABF1 +:1013E00003EB0B0152460DF1290000F007FA0AAB9E +:1013F0000393182302930AF10102554BD2B2CDE9AF +:101400000053049220464CA3D3E9002301F058FF77 +:101410003E7001F0EBFB4F4A4F4D1368C31AB3F512 +:101420007A7F2ED3106001F0E3FB02460B46204684 +:1014300001F0DEFF204601F0FDFE10B32B7A474E8F +:10144000002B14BF03230223737101F0CFFB0EAFF7 +:101450004FF47A730122B0FBF3F039463060304626 +:1014600000F018FB182302933D4B019380B240F229 +:101470005513CDE90370009342464B46204601F0D8 +:101480001FFF2B7A93B101F0B1FB002607464FF402 +:101490008A7A95F8D900304400F003000AFB005323 +:1014A00093F8E82092B30136042EF2D1C82003F05D +:1014B00027F92B7A002B7FF43DAF13B0BDEC028BE4 +:1014C000BDE8F08FDAF8143083F48043CAF81430A2 +:1014D000594610220EA800F0B7F90DF11E0308AA14 +:1014E0000AA9384600F034FF96E803000FAB83E802 +:1014F00003009DF834308DF844300A9B0E930EA9FA +:10150000DDE90823204602F047F921E7D3F8E0207F +:1015100042B12B68FA2B38BFFA23BA1A0533B2EB63 +:10152000430FC0D3FFF7ACFB0028BCD1BEE700BF20 +:101530000000000000000000401DA12026812A0BB1 +:10154000F034002020350020EC340020E934002065 +:10155000E8340020284B0020F8450020D824002043 +:101560002C4B0020F1C6A7C1D068080F0000024034 +:1015700008B5054800F088FFBDE80840034A044963 +:10158000002004F007BF00BF20350020684B00207A +:10159000790E000870B50F4B1B780133DBB2012BBD +:1015A0000C4611D80C4D29684FF47A730E6AA2FBD1 +:1015B0000332014622462846B047844204D1074BF5 +:1015C00000221A70012070BD4FF4FA7003F098F8F1 +:1015D0000020F8E71C230020E04D00205C4B002099 +:1015E00007B50023024601210DF107008DF80730F1 +:1015F000FFF7D0FF20B19DF8070003B05DF804FBB2 +:101600004FF0FF30F9E700000A4608B50421FFF764 +:10161000C1FF80F00100C0B2404208BD30B4054CAB +:101620002368DD69044B0A46AC460146204630BCBF +:10163000604700BFE04D0020A086010070B503F0B8 +:101640008FFB094E094D308000242868338883427F +:1016500008D903F07FFB2B6804440133B4F5803FC5 +:101660002B60F2D370BD00BF5E4B0020304B0020DA +:1016700003F024BC00F1006000F580300068704782 +:1016800000F10060920000F5803003F0AFBB000075 +:10169000054B1A68054B1B889B1A834202D91044DC +:1016A00003F058BB00207047304B00205E4B0020F9 +:1016B000024B1B68184403F055BB00BF304B0020A1 +:1016C000024B1B68184403F065BB00BF304B002081 +:1016D00010F003030AD1B0F5047F05D200F10050E9 +:1016E000A0F51040D0F80038184670470023FBE7FB +:1016F00000F10050A0F51040D0F8100A704700002B +:10170000064991F8243033B10023086A81F8243067 +:101710000822FFF7B5BF0120704700BF344B0020FF +:10172000014B1868704700BF002004E070B5194BEA +:101730001D68194B0138C5F30B0408442D0C042215 +:101740001E88A6420BD15C680A46013C82421346C1 +:101750000FD214F9016F4EB102F8016BF6E7013AAE +:1017600003F10803ECD181420B4602D22C2203F88C +:10177000012B0A4A05241688AE4204D1984284BF40 +:10178000967803F8016B013C02F10402F3D1581A78 +:1017900070BD00BF002004E08C650008786500087B +:1017A000022802BF024B4FF080429A61704700BF8F +:1017B00000000240022802BF024B4FF480429A61AF +:1017C000704700BF00000240022801BF024A53696F +:1017D00083F48043536170470000024070B50446B3 +:1017E0004FF47A764CB1412C254628BF412506FBA3 +:1017F00005F002F085FF641BF4E770BD10B500230F +:10180000934203D0CC5CC4540133F9E710BD00000F +:1018100010B5013810F9013F3BB191F900409C42ED +:1018200003D11AB10131013AF4E71AB191F900205C +:10183000981A10BD1046FCE703460246D01A12F96A +:10184000011B0029FAD1704702440346934202D09B +:1018500003F8011BFAE770472DE9F8431F4D1446C2 +:1018600095F824200746884652BBDFF870909CB359 +:1018700095F824302BB92022FF2148462F62FFF72C +:10188000E3FF95F82400C0F10802A24228BF2246D7 +:10189000D6B24146920005EB8000FFF7AFFF95F806 +:1018A0002430A41B1E44F6B2082E17449044E4B220 +:1018B00085F82460DBD1FFF723FF0028D7D108E0AB +:1018C0002B6A03EB82038342CFD0FFF719FF002876 +:1018D000CBD10020BDE8F8830120FBE7344B00208A +:1018E000024B1A78024B1A70704700BF5C4B002005 +:1018F0001C23002010B5104C104802F057FA214666 +:101900000E4802F07FFA2468626DD2F8043843F082 +:101910000203C2F804384FF47A70FFF75FFF0849FA +:10192000204602F075FB626DD2F8043823F0020302 +:10193000C2F8043810BD00BFD4660008E04D002096 +:10194000DC660008704700002DE9F0470D460446AC +:1019500000219046284640F27912FFF775FF234692 +:1019600020220021284601F0B9FE231D0222202159 +:10197000284601F0B3FE631D03222221284601F010 +:10198000ADFEA31D03222521284601F0A7FE04F188 +:10199000080310222821284601F0A0FE04F11003BC +:1019A00008223821284601F099FE04F1110308228B +:1019B0004021284601F092FE04F11203082248213A +:1019C000284601F08BFE04F1140320225021284602 +:1019D00001F084FE04F1180340227021284601F032 +:1019E0007DFE04F120030822B021284601F076FE96 +:1019F00004F121030822B821284601F06FFE04F10A +:101A00002207C0263B46314608222846083601F008 +:101A100065FEB6F5A07F07F10107F3D104F13203AB +:101A200008223146284601F059FE002704F1330A06 +:101A300094F832304FEAC7099F4209F5A47615D3CE +:101A4000B8F1000F08D1314604F5997307222846F2 +:101A500001F044FE09F24F16274694F832213B1B51 +:101A600093420CD3F01DC008BDE8F0870AEB0703D2 +:101A700008223146284601F031FE0137D8E707F247 +:101A8000331331460822284601F028FE0836013774 +:101A9000E3E7000013B50446084600210160234631 +:101AA000C0F803102022019001F018FE0198231DB8 +:101AB0000222202101F012FE0198631D032222213F +:101AC00001F00CFE0198A31D0322252101F006FE62 +:101AD000019804F108031022282101F0FFFD0720DE +:101AE00002B010BDF7B50023047F00910E46072217 +:101AF0001946054601F0B6FC731C00930122002331 +:101B00000721284601F0AEFCC4B9B31C009305229E +:101B100023460821284601F0A5FC0D243746B2785B +:101B2000BB1B934211D32B7FA88A0734E408BBB9AF +:101B3000844294BF0020012003B0F0BDAB8ADB00DB +:101B4000083BDB08B3700824E8E7FB1C0093214640 +:101B500000230822284601F085FC08340137DEE71F +:101B6000201A18BF0120E7E7F7B50023047F009192 +:101B70000E4608221946054601F074FC731CC4B9D0 +:101B80000822009311462346284601F06BFC1024DE +:101B9000012372785F1C013B934211D32B7FA88AEB +:101BA0000734E408BBB9844294BF0020012003B08D +:101BB000F0BDAB8ADB00083BDB0873700824E7E765 +:101BC000F3190093214600230822284601F04AFC1D +:101BD00008343B46DDE7201A18BF0120E7E7000084 +:101BE000F8B50E4605461446002181223046FFF71F +:101BF0002BFE2B4608220021304601F06FFD7CB9F8 +:101C00006B1C07220821304601F068FD0F240123D8 +:101C10006A785F1C013B934204D3E01DC008F8BD05 +:101C20000824F4E7EB1921460822304601F056FD5E +:101C300008343B46ECE70000F8B50E46054614466E +:101C40000021CE223046FFF7FFFD2B46282200213F +:101C5000304601F043FD7CB905F108030822282134 +:101C6000304601F03BFD30242F462A7A7B1B9342FD +:101C700004D3E01DC008F8BD2824F5E707F10903E7 +:101C800021460822304601F029FD08340137ECE7EF +:101C9000F7B5047F00910E4601231022002105466E +:101CA00001F0E0FBC4B9B31C0093092223461021C4 +:101CB000284601F0D7FB192437467288BB1B9A428D +:101CC00011D82B7FA88A0734E408BBB9844294BF9B +:101CD0000020012003B0F0BDAB8ADB00103BDB0825 +:101CE00073801024E8E73B1D00932146002308225F +:101CF000284601F0B7FB08340137DEE7201A18BF89 +:101D00000120E7E730B5094D0A4491420DD011F8A2 +:101D1000013B5840082340F30004013B2C4013F0E2 +:101D2000FF0384EA5000F6D1EFE730BD2083B8ED21 +:101D3000F7B54FF0FF33DFF854C0DFF854E000EBA5 +:101D400081011A4688421CD050F8044B019401AF1F +:101D5000042417F8015B82EA05620825DB181646A1 +:101D600005F1FF355241002EBCBF83EA0C0382EA25 +:101D70000E0215F0FF05F1D1013C14F0FF04E8D18B +:101D8000E0E7D843D14303B0F0BD00BF9336EAA9E2 +:101D9000EBE1F042F7B5384A106851686B4603C36F +:101DA0006A4636493648082304F054FB04460028A6 +:101DB00033D10A25334A106851686B4603C36A461B +:101DC00031492F48082304F045FB0446002849D038 +:101DD0000369B3F5702F45D8B0F8661040F2F632BB +:101DE00091423FD1294A024402F15C018B4239D32E +:101DF0005C3B234900209E1AFFF784FF32460746CA +:101E000004F164010020FFF77DFFA3689F4229D100 +:101E1000E368984208BF002524E00369B3F5702FFA +:101E200027D8418B40F2F632914220D1174A024422 +:101E300002F110018B4218D3103B114900209D1A6A +:101E4000FFF760FF2A46064604F118010020FFF75D +:101E500059FFA3689E4202D1E368984201D00D2544 +:101E6000A8E70025284603B0F0BD1025A2E70C2501 +:101E7000A0E70B259EE700BFAC650008DCFF0E0065 +:101E800000000108B565000890FF0E000800FFF78C +:101E900010B5037C044613B9006804F0C3FA204669 +:101EA00010BD00000023BFF35B8FC360BFF35B8FE7 +:101EB000BFF35B8F8360BFF35B8F7047BFF35B8FB4 +:101EC0000068BFF35B8F704770B505460C30FFF7B5 +:101ED000F5FF05F1080604463046FFF7EFFFA04284 +:101EE00006D930466D68FFF7E9FF2544281A70BD12 +:101EF0003046FFF7E3FF201AF9E7000070B505460A +:101F0000406898B105F10800FFF7D8FF05F10C060D +:101F100004463046FFF7D2FF8442304694BF6D68D6 +:101F20000025FFF7CBFF013C2C44201A70BD0000B8 +:101F300038B50C460546FFF7C7FFA04210D305F1A0 +:101F40000800FFF7BBFF04446868B4FBF0F100FB36 +:101F50001144BFF35B8F0120AC60BFF35B8F38BDD2 +:101F60000020FCE72DE9F041144607460D46FFF737 +:101F7000C5FF844228BF0446D4B1B84658F80C6B5C +:101F80004046FFF79BFF3044286040467E68FFF7DD +:101F900095FF331A9C4203D86C600120BDE8F081A4 +:101FA0006B60A41B3B68AB602044E8600220F5E74F +:101FB0002046F3E738B50C460546FFF79FFFA042E1 +:101FC00010D305F10C00FFF779FF04446868B4FBF7 +:101FD000F0F100FB1144BFF35B8F0120EC60BFF315 +:101FE0005B8F38BD0020FCE72DE9FF41884669463C +:101FF0000746FFF7B7FF6C4606B204EBC60600259E +:10200000B44209D06268206808EB0501FFF7F6FBCF +:10201000636808341D44F3E729463846FFF7CAFFD2 +:10202000284604B0BDE8F081F8B505460C300F46EF +:10203000FFF744FF05F1080604463046FFF73EFF70 +:10204000A042304688BF6C68FFF738FF201A38601E +:1020500020B130462C68FFF731FF2044F8BD000066 +:1020600073B5144606460D46FFF72EFF844228BF7F +:1020700004460190DCB101A93046FFF7D5FF019B72 +:1020800033B93268C5E90233C5E9002401200CE008 +:102090009C4238BF01942860019868608442F5D959 +:1020A0003368AB60241AEC60022002B070BD204699 +:1020B000FBE700002DE9FF410F466946FFF7D0FF1F +:1020C0006C4600B204EBC0050026AC4209D0D4F83F +:1020D000048054F8081BB8194246FFF78FFB4644AA +:1020E000F3E7304604B0BDE8F081000038B505469E +:1020F000FFF7E0FF044601462846FFF719FF204698 +:1021000038BD000010B4026854681A4623465DF8D2 +:10211000044B1847002070470020704770470000AC +:10212000002070470E20704700F5805090F8C800DE +:10213000C0F340007047000000F5805090F9D000D7 +:102140007047000000F58050C0F8CC1001207047A7 +:10215000F7B50C68BDF8207014F0005470D10D7BF9 +:10216000082D6DD8302585F311884569AE68760154 +:102170000CD4AC68240108D4AC6814F080545DD150 +:1021800084F31188204603B0F0BD01240E6804F1E9 +:10219000180C002EB8BFF6004FEA0C1CB4BF46F076 +:1021A0000406760545F80C600E680FFA84FC16F0FC +:1021B000804F18BF05EB0C1E05EB0C1C1EBFDEF894 +:1021C000806146F00206CEF880610E7BCCF8846117 +:1021D00005EB04158E68C5F88C614E68C5F88861FA +:1021E000DCF8805145F00105CCF8805100EB441635 +:1021F00041F268052E4405EB44150544C6E9002369 +:1022000008350E4601F10C0C56F804EB45F804EBCA +:102210006645F9D1843436882E8000EB441407F0EB +:102220000305267926F00B0635432571002484F337 +:102230001188009700F0FCFC0120A4E70224A5E728 +:102240004FF0FF309FE7000013B500F58054019177 +:10225000E06DFFF753FE1F280AD90199E06D202297 +:10226000FFF7C2FEA0F120035842584102B010BD52 +:102270000020FBE708B5302383F3118800F5805078 +:10228000C06DFFF70FFE002383F3118808BD000027 +:1022900000220260828142608260704710B5002295 +:1022A0000023C0E900230023044603810C30FFF71C +:1022B000EFFF204610BD0000F0B5054600F5805048 +:1022C0000C4690F8C83013F0040FC3F3800108BF28 +:1022D000114661F3820304F1840680F8C83005EBEF +:1022E000461389B01B79D8072ED57AB319072DD498 +:1022F0006846FFF7D3FF05EB441303F5835303F15F +:10230000180703AA103318685968144603C4083321 +:10231000BB422246F7D1186820609B88A380DDE984 +:102320000E23CDE900230123ADF808302B68694660 +:10233000DB6B2846984705EB46152B791A075CBFDF +:1023400043F008032B7101E0002AF4D109B0F0BD7D +:102350002DE9F0479A4688B00746884691463023D3 +:1023600083F3118807F580546846FFF797FFE06D07 +:10237000FFF7AAFD1F282AD9E06D20226946FFF742 +:10238000B5FE202823D103AD444605AB2E4603CE2F +:102390009E4220606160354604F10804F6D1306841 +:1023A0002060B388A380DDE90023C9E90023BDF8DC +:1023B0000830AAF80030002383F3118853464A46B8 +:1023C0004146384608B0BDE8F04700F01FBC002089 +:1023D00080F3118808B0BDE8F08700002DE9F84FC0 +:1023E0000023C0E90133254B044640F8183B0F4653 +:1023F000FFF74EFF04F12800FFF750FF04F14808F3 +:1024000004F582554646083530462036FFF746FF2C +:10241000AE42F9D104F580554FF480534FF00009D6 +:10242000C5E91339C5F848800123EE6504F58758DE +:1024300004F58456C5F8549085F8583085F8603016 +:10244000083608F108084FF0000A4FF0000B46E983 +:1024500008ABA6F11800FFF71BFF203646F8289CB2 +:102460004645F4D185F8D07017B1054800F0B8FBA7 +:10247000044B63612046BDE8F88F00BFE8650008A3 +:10248000C06500080064004010B5044B197804468C +:102490004A1C1A70FFF7A2FF204610BD644B0020B3 +:1024A0002DE9F047002950D0294B2A4FB7FBF1F511 +:1024B00099428CBF0A231123581EB5FBF3FC03FB82 +:1024C0001C53C4B22BB102280346F5D80020BDE846 +:1024D000F0870CF1FF36B6F5806FF7D2C4EBC40E6F +:1024E0000EF103034FEAE309C3F3C703A4EB0308A8 +:1024F00009F1010A4FF47A755FFA88F009FB055576 +:102500005AFA88F8B5FBF8F5B5F5617FC1BF0EF151 +:10251000FF33C3F3C703E01AC0B25C1C50FA84F463 +:102520000CFB04F4B7FBF4F4A142CFD1013BDBB2C6 +:102530000F2BCBD80138C0B20728C7D800211071A3 +:1025400016809170D3700120C1E70846BFE700BF35 +:102550003F420F0080DE800270B505460E464FF404 +:102560007A746B695B6803F00103B34207D04FF4E0 +:102570007A7002F0C5F8013CF3D1204670BD01200D +:10258000FCE7000030B54269936913F0700F16D074 +:1025900000230B4C936103F1840200EB421211798A +:1025A0004D0709D5890707D5416954F823508D6037 +:1025B000117941F0040111710133032BEBD130BDCE +:1025C000D465000873B51D46436916469A68D2075C +:1025D000044609D59A6801219960C2F34002CDE909 +:1025E00000650021FFF768FE63699A68D1050BD585 +:1025F0009A684FF480719960C2F34022CDE900657A +:1026000001212046FFF758FE63699A68D2030BD573 +:102610009A684FF480319960C2F34042CDE9006579 +:1026200002212046FFF748FE04F58053D3F8CC0082 +:1026300010B103681B699847204602B0BDE870409E +:10264000FFF7A0BFF8B504464669002972D106F12C +:102650000C073868800770D006EB01153868D5F88C +:10266000B00110F0040FD5F8B0011ABFC00840F057 +:102670000040400DA061D5F8B0C11CF0020F1CBF96 +:1026800040F08040A061D5F8B40106EB011100F0E4 +:102690000F0084F82400D1F8B8012077D1F8B801F0 +:1026A000000A6077D1F8B801000CA077D1F8B80122 +:1026B000000EE077D1F8BC0184F82000D1F8BC010D +:1026C000000A84F82100D1F8BC01000C84F8220033 +:1026D000D1F8BC11090E84F823103821396004F1B7 +:1026E000340004F1180104F1240551F8046B40F89A +:1026F000046BA942F9D109880180C4E90A23214663 +:102700000023238651F8283B2046DB6B984704F5CD +:10271000805393F8C820D3F8CC0042F0040283F829 +:10272000C82010B103681B6998472046BDE8F840EF +:10273000FFF728BF06F110078BE7F8BD10B5044678 +:1027400000F056FA02460B4652EA030102D0013A63 +:1027500063F100030449086820B12146BDE8104038 +:10276000FFF770BF10BD00BF604B0020F0B53021F7 +:1027700081F31188DFF848C000F583510831002447 +:1027800004F1840500EB45152E7977070ED4F60683 +:102790000CD5D1E9007697429E4107D246695CF894 +:1027A0002470B7602E7946F004062E710134032C94 +:1027B00001F12001E4D1002383F31188F0BD00BFB3 +:1027C000D465000808B5302383F31188FFF7DAFEDB +:1027D000002383F3118808BDF8B54369054698685E +:1027E00000F0E050B0F1E05F0F4621D0F8B13023A7 +:1027F00083F3118805F583541034002606F1840311 +:1028000005EB43131B791A0706D50136032E04F195 +:102810002004F3D1012007E05B07F6D421463846B7 +:1028200000F040FA0028F0D1002383F31188F8BDAE +:102830000120FCE708B5302383F3118800F58050B0 +:10284000C06DFFF741FB002383F3118843090CBFE0 +:102850000120002008BD0000F8B51D4600231370BC +:102860000F4606461446FFF7E5FF80F0010038707A +:1028700025B129463046FFF7AFFF2070F8BD0000B4 +:102880002DE9B8410C4615461F46804600F0B0F9C8 +:102890000B462178024609B9287850B14046FFF727 +:1028A00065FFFFF78FFF3B462A462146FFF7D4FF1F +:1028B0000120BDE8B881000070B5302686F311888C +:1028C000174B1A6C42F000721A641A6A42F00072D6 +:1028D0001A621A6A22F000721A62002383F31188C6 +:1028E00000F5805494F8C83013F0010516D1A9B151 +:1028F00086F311880321132001F0C8F90321142065 +:1029000001F0C4F90321152001F0C0F994F8C83092 +:1029100043F0010384F8C83085F3118870BD00BF0F +:10292000003802402DE9F04700F5805588B095F851 +:10293000D030012B04468846164600F28180814F34 +:1029400057F823200AB947F82300D7F800A0C4F8A5 +:102950000C802674BAF1000F64D095F8D030012BAA +:1029600070D001212046FFF7A7FF302383F31188A1 +:102970006269136823F0020313606269136843F00D +:1029800001031360636900275F6187F311880121E8 +:102990002046FFF7E1FD002800F09580E86DFFF785 +:1029A00081FA04F58359BA4609F108092022002169 +:1029B0006846FEF749FF02A8FFF76AFCCDF818A0A9 +:1029C0006A4609EB07030DF1180E9446BCE80300B4 +:1029D000F44518605960624603F10803F5D1DCF84C +:1029E0000000186020379CF804201A71602FDDD198 +:1029F00095F8C8306FF38203002785F8C8306A461F +:102A000041462046ADF80070ADF802708DF80470B4 +:102A1000FFF746FD636948BB4FF400421A6008B0F7 +:102A2000BDE8F08741F2D80003F0BCFC814610B14C +:102A30005146FFF7D3FCC7F80090B9F1000F8CD1D5 +:102A40000020ECE7386803681B6B984701460028B4 +:102A500087D13868FFF730FF3868036832465B6813 +:102A60004146984700287FF47CAFE9E761221A606D +:102A70009DF802309DF803201B06120402F4702218 +:102A800003F040731343BDF80020C2F3090213435F +:102A90009DF804201205022E02F4E0020CBF4FF054 +:102AA00000410021134362690B43D3616369132220 +:102AB0005A616269136823F00103136039462046A6 +:102AC000FFF74AFD08B96369A6E795F8D03093BBD4 +:102AD0006169D1F8002242F00102C1F80022616967 +:102AE000D1F8002222F47C5222F00E02C1F800221A +:102AF0006169D1F8002242F46062C1F80022626983 +:102B0000C2F814326269C2F80432626941F6FF7198 +:102B1000C2F80C126269C2F840326269C2F84432EB +:102B200063690122C3F81C226269D2F8003223F0E3 +:102B30000103C2F8003295F8C83043F0020385F86B +:102B4000C8306CE7604B002008B500F051F850EA3F +:102B50000103024602D0421E61F10001044B1868D5 +:102B600010B10B46FFF72EFDBDE8084001F064B838 +:102B7000604B002008B50020FFF7E0FDBDE80840ED +:102B800001F05AB808B50120FFF7D8FDBDE80840AC +:102B900001F052B800B59BB0EFF309816822684696 +:102BA000FEF72CFEEFF30583014B9B6BFEE700BFA6 +:102BB00000ED00E008B5FFF7EDFF000000B59BB0A9 +:102BC000EFF3098168226846FEF718FEEFF30583EC +:102BD000014B5B6BFEE700BF00ED00E0FEE700008D +:102BE0000FB408B5029801F031FDFEE702F0B4B968 +:102BF00002F096B913B56C4684E80600031D94E80C +:102C0000030083E80500012002B010BD73B585689C +:102C1000019155B11B885B0707D4D0E900369B6B47 +:102C20009847019AC1B23046A847012002B070BD52 +:102C3000F0B5866889B005460C465EB1BDF83830FF +:102C40005B070AD4D0E900379B6B98472246C1B294 +:102C50003846B047012009B0F0BD00220023CDE97D +:102C600000230023ADF808300A4603AB01F1080643 +:102C7000106851681C4603C40832B2422346F7D19B +:102C8000106820609288A280FFF7B2FF0423ADF89D +:102C900008302B68CDE90001DB6B69462846984770 +:102CA000D8E7000030B503680968DD0FB5EBD17FC8 +:102CB00023F0604421F060424FEAD1700BD0002B2A +:102CC000B8BFA40C0029B8BF920C944202D034BF04 +:102CD0000120002030BD944205D1C1F38070C3F3C0 +:102CE00080738342F6D194422CBF00200120F1E78B +:102CF0002DE9F041456A15B94162BDE8F0814B68A4 +:102D000023F06047C3F38A464FEAD37EC3F380784B +:102D100016EA230638BF3E46AC462B465A68BEEB41 +:102D2000D27F22F060440AD0002A18DAA40CB44200 +:102D300017D19D420FD10D60DEE71346EEE7A742A3 +:102D400007D102F08044C2F3807242450BD054B1E7 +:102D5000EFE708D2EDE7CCF800100B60CDE7B44206 +:102D600001D0B442E5D81A689C46002AE5D1196022 +:102D7000C3E700002DE9F047089D01F007044FEA82 +:102D8000D508224405F0070500EBD1004FF47F4938 +:102D9000944201D1BDE8F08704F0070705F0070A67 +:102DA00057453E4638BF5646C6F10806111B8E42AF +:102DB00028BF0E46E10808EBD50E415C13F80EC0A3 +:102DC000B94029FA06F721FA0AF1FFB28CEA0101AB +:102DD00047FA0AF739408CEA010C03F80EC0344474 +:102DE0003544D5E780EA0120082341F2210201B2EF +:102DF0004000002980B203F1FF33B8BF504013F008 +:102E0000FF03F4D17047000038B50C468D18A54279 +:102E100000D138BD14F8011BFFF7E4FFF7E700000D +:102E200042684AB1136843604389818901339BB288 +:102E30009942438138BF83811046704770B588B08E +:102E4000202204460D4668460021FEF7FDFC204680 +:102E50000495FFF7E5FF024658B16B46054608AEFC +:102E60001C4603CCB44228606960234605F108057E +:102E7000F6D1104608B070BD082817D909280CD023 +:102E80000A280CD00B280CD00C280CD00D280CD004 +:102E90000E2814BF4020302070470C2070471020AF +:102EA000704714207047182070472020704700009A +:102EB000082817D90C280CD910280CD914280CD99B +:102EC00018280CD920280CD930288CBF0F200E20B0 +:102ED0007047092070470A2070470B2070470C206C +:102EE00070470D20704700002DE9F843078C072F2D +:102EF00004461ED9D0E9029800254FF6FF73C5F1AC +:102F00002006A5F1200029FA05F108FA06F628FAAC +:102F100000F031430143C9B21846FFF763FF08359B +:102F2000402D0346EBD1E1693A46BDE8F843FFF78F +:102F30006BBF4FF6FF70BDE8F883000010B54B681B +:102F400023B9CA8A63F30902CA8210BD04691A68E8 +:102F50001C600361C38A013BC3824A60EFE7000043 +:102F60002DE9F84F1D46CB8A0F46C3F30901052909 +:102F7000814692460B4630D00020AAB207F11A04CF +:102F80009EB2042E1FFA80F80FD8904503F101037A +:102F900006D3FB8A0A4462F30903FB8201201AE08C +:102FA0001AF80060E6540130EAE79045F1D2A1F149 +:102FB000050B1C237C68BBFBF3F203FB12BB1FFA5F +:102FC0008BF6002C45D14846FFF72AFF044638B956 +:102FD00078606FF00200BDE8F88F4FF00008E6E778 +:102FE000002606607860ADB24FF0000B454510D961 +:102FF0000AEB0803221D13F8011B9155B1B208F129 +:1030000001081B291FFA88F82BD0454506F1010657 +:10301000F1D8FB8AC3F30902154465F30903BCE741 +:10302000013292B21C462368002BF9D16B1F0B446E +:103030001C21B3FBF1F301339BB29A42D3D2BBF113 +:10304000000FD0D14846FFF7EBFE20B9C4F800B01E +:10305000BFE70122E7E7C0F800B05E462060044603 +:10306000C1E74545D5D94846FFF7DAFE08B92060E3 +:10307000AFE7C0F800B0002620600446B6E70000C5 +:103080002DE9F04F2DED028B1C4683B05B69019258 +:1030900007468846002B00F09A80238C2BB1E2690A +:1030A000002A00F09480072B35D807F10C00FFF7B9 +:1030B000B7FE054638B96FF00205284603B0BDECEF +:1030C000028BBDE8F08F14220021FEF7BDFB228C9D +:1030D000E16905F10800FEF791FB208C013080B218 +:1030E000FFF7E6FEFFF7C8FE013880B2208401300A +:1030F00028746369228C1B782A4403F01F0363F051 +:103100003F0348F000411372384669602946FFF7D3 +:10311000EFFD0125D1E700F10C034FF0000908EEA7 +:10312000103A4FF0800A4E464D4618EE100AFFF74F +:1031300077FE83460028BED014220021FEF784FBD0 +:10314000002E3AD1019BABF8083002220BF1080E99 +:103150001FFA82FC0CF10100BCF1060F218C80B239 +:1031600001D88E422BD3FFF7A3FEFFF785FE6269DD +:103170001278013802F01F028E4208BF4FF0400A59 +:1031800042EA49121BFA80F14AEA020A013048F089 +:10319000004281F808A08BF81000CBF804205946B3 +:1031A0003846FFF7A5FD238C0135B3422DB289F0D7 +:1031B00001094FF0000AB8D17FE70022C6E7E169B4 +:1031C000895D0EF802100136B6B20132C0E76FF029 +:1031D000010572E7F8B515460E4630220021044677 +:1031E0001F46FEF731FB069B6360B5F5001F079B8A +:1031F000A76034BF6A094FF6FF72A36297B2E66117 +:1032000004F1100000239A4206D800230360A7822D +:10321000E3822383E360F8BD066001333046203645 +:10322000F1E7000003781BB94BB2002BC8BF017057 +:103230007047000000787047F8B50C46C96907462A +:1032400011B9238C002B37D1257E1F2D34D8387827 +:1032500028BB228C072A2CD8268A36F003032BD1D0 +:103260004FF6FF70FFF7D0FD20F00100310240045F +:1032700041EA0561400C41EA40254FF6FF722346C2 +:1032800029463846FFF7FCFE002807DD62691378FF +:103290000133DBB21F2B88BF00231370F8BD218AD6 +:1032A0002D0645EA012505432046FFF71DFE02468F +:1032B000E5E76FF00300F1E76FF00100EEE70000D3 +:1032C00070B58AB0044616460021282268461D467D +:1032D000FEF7BAFABDF83830ADF810300F9B059301 +:1032E0009DF840308DF81830119B07936946BDF862 +:1032F0004830ADF820302046CDE90265FFF79CFF4D +:103300000AB070BD2DE9F041D36905460C4616465A +:103310000BB9138C5BBB377E1F2F28D895F8008024 +:10332000B8F1000F26D03046FFF7DEFD33782102DA +:1033300041EAC33141EA0801338A41EA076141EABF +:1033400003410246334641F080012846FFF798FECC +:1033500000280ADD3378012B07D172691378013315 +:10336000DBB21F2B88BF00231370BDE8F0816FF024 +:103370000100FAE76FF00300F7E70000F0B58BB04B +:1033800004460D4617460021282268461E46FEF7D1 +:103390005BFA9DF84C305A1E534253418DF8003071 +:1033A0009DF84030ADF81030119B05939DF84830E2 +:1033B0008DF81830149B07936A46BDF85430ADF869 +:1033C000203029462046CDE90276FFF79BFF0BB05F +:1033D000F0BD0000406A00B104307047436A1A68CB +:1033E000426202691A600361C38A013BC38270476B +:1033F0002DE9F041D0F82080194E14461D46414673 +:10340000002709B9BDE8F081D1E90223A21A65EBD2 +:103410000303964277EB03031ED2036A8B420DD15E +:10342000FFF78CFD036A1B68036203690B60C38AA4 +:103430000161016A013BC3828846E2E7FFF77EFD36 +:103440000B68C8F8003003690B60C38A0161013B57 +:10345000C382D8F80010D4E788460968D1E700BFD6 +:1034600080841E002DE9F04F8BB00D46DDF85090A2 +:1034700014469B468046002800F01981B9F1000FE0 +:1034800000F01581531E3F2B00F21181012A03D158 +:10349000BBF1000F40F00B810023CDE90833B8F8F1 +:1034A0001430B5EBC30F4FEAC30703D300200BB0B2 +:1034B000BDE8F08F2B199F42D8F80C303ABF7F1B24 +:1034C000FFB227461BB9D8F81030002B7AD0272D31 +:1034D0004ED8C5F12806B7424FF000032CBFF6B214 +:1034E0003E4600932946D8F8080008AB3246FFF75D +:1034F00041FCA7EB060A35445FFA8AFAB8F81430A3 +:1035000003F10053053BDB000493D8F80C30039320 +:103510002821039B13B1BAF1000F2CD1D8F8100069 +:1035200040B1BAF1000F05D0009608AB5246691AB7 +:10353000FFF720FC38B2002FB8D066070AD00AABDC +:1035400003EBD401624211F8083C02F00702134178 +:1035500001F8083C082C3CD9102C40F2B580202CF6 +:1035600040F2B780BBF1000F00F09C80082334E0EC +:10357000BA460026C2E7049BE02B28BFE02306934F +:103580000B44AB42059314D95A1B039800969245FD +:1035900034BF5246D2B2691A08AB04300792FFF723 +:1035A000E9FB079A1644AAEB020A1544F6B25FFA41 +:1035B0008AFA049B069A05999B1A0493039B1B683D +:1035C0000393A6E70093D8F8080008AB3A462946CB +:1035D000AEE7BBF1000F13D00123B4EBC30F6CD0E7 +:1035E000082C12D89DF82030621E23FA02F2D5076B +:1035F00006D54FF0FF3202FA04F423438DF8203051 +:103600009DF8203089F8003051E7102C12D8BDF811 +:103610002030621E23FA02F2D10706D54FF0FF32A6 +:1036200002FA04F42343ADF82030BDF82030A9F8A5 +:1036300000303CE7202C0FD80899631E21FA03F3D1 +:10364000DA0705D54FF0FF3202FA04F40C43089470 +:10365000089BC9F800302AE7402C2BD0DDE908652B +:10366000611EC4F12102A4F1210326FA01F105FA39 +:1036700002F225FA03F311431943CB0712D50122B5 +:10368000A4F12003C4F1200102FA03F322FA01F1AC +:10369000A240524243EA010363EB430332432B430C +:1036A000CDE90823DDE90823C9E90023FFE66FF02F +:1036B0000100FCE66FF00800F9E6082CA0D9102CF8 +:1036C000B3D9202CEED8C3E7BBF1000FADD0022355 +:1036D00083E7BBF1000FBBD004237EE730B5012A9E +:1036E000144638BF0124402C85B028BF4024002553 +:1036F000012ACDE9025518D81B788DF808306307E8 +:103700000AD004AB03EBD405624215F8083C02F082 +:103710000702934005F8083C009103462246002129 +:1037200002A8FFF727FB05B030BD082AE4D9102A0C +:1037300003D81B88ADF80830E1E7202A8DBFD3E914 +:1037400000231B680293CDE90223D8E710B5CB68AC +:103750001BB98B600B618B8210BD04691A681C60F9 +:103760000361C38A013BC382CA60F0E703064CBF12 +:10377000C0F3C0300220704708B50246FFF7F6FFDD +:10378000022806D15306C2F30F2001D100F0030036 +:1037900008BDC2F30740FBE72DE9F04F93B0CDE938 +:1037A00003230A6804461046FFF7E0FF022814BF0F +:1037B000C2F306260026002A0D46824680F2F281D8 +:1037C00012F0C04940F0EE81097B002900F0EA8147 +:1037D000022803D02378B34240F0E781C2F30463A8 +:1037E0000693104602F07F030593FFF7C5FF059B84 +:1037F00029444FEA834848EA0A4848EA4668CE78AE +:1038000000230022CDE90823F309834648EA000893 +:10381000029367D0059B009302466768534608A948 +:103820002046B847002800F0C381276A4FB94146B7 +:1038300004F10C00FFF702FB074690B96FF002009D +:1038400054E03B6998450DD03F68002FF9D14146BF +:1038500004F10C00FFF7F2FA07460028EED0236AC5 +:103860003B60276297F817C006F01F08CCF3840C62 +:10387000ACEB08001FFA80FE0028B8BF0EF1200054 +:10388000A8EB0C031FFA83FED7E90221B8BF00B2F0 +:10389000002B0793BEBF0EF120031BB2079352EA21 +:1038A000010338D0039BDFF824E39A1A049B4FF0FE +:1038B000000C63EB010196457CEB01032BD36B7B82 +:1038C00097F81AE0734519D1029B002B78D0012894 +:1038D00021DC7868F8B9DFF8F0C2944570EB010399 +:1038E00016D337E0276A27B96FF00C0013B0BDE894 +:1038F000F08F3B699845B5D03F68F4E7B2489042F5 +:103900007CEB010301D30020F0E7029B002BFAD0EF +:10391000079B0F2B17DCFA7DB30002F0030203F0C4 +:103920007C031343FB7539462046FFF707FB6B7B8F +:10393000BB76029B3BB9FB7DC3F38402013262F389 +:103940008603FB75D0E76A7BBB7E9A42DBD1029B84 +:10395000002B35D0B309022B32D0039BBB60049BF4 +:10396000FB60142200210DA8FDF76EFF039B0A9354 +:10397000049B0B932B1D0C932B7BADF83EB0013BAE +:10398000DBB2ADF83C30069B8DF84230059B8DF8DC +:10399000433094F82C308DF840A083F001038DF86B +:1039A00044308DF84180A3680AA920469847FB7DE2 +:1039B000C3F38403013303F01F039B02FB82A2E7DE +:1039C000FB7DC6F34012B2EBD31F40F0F480C3F38B +:1039D0008403434540F0F280029A2B7BB609002A0B +:1039E0004DD0F2075DD4032B40F2EB80039BBB600C +:1039F000049BFB602B7BAE1D033BDBB2324639469A +:103A000004F10C00FFF7ACFA00280CDA3946204626 +:103A1000FFF794FAFB7DC3F38403013303F01F0324 +:103A20009B02FB820AE7DDE90884AB883B834FF603 +:103A3000FF73C9F12000A9F1200228FA09F104FA64 +:103A400000F0014324FA02F211431846C9B2FFF70D +:103A5000C9F909F10809B9F1400F0346E9D1B88263 +:103A60002A7B033AD2B23146FFF7CEF9FB7DB8820A +:103A7000DA43C2F3C01262F3C713FB7543E786B99A +:103A80002E1D013BDBB23246394604F10C00FFF734 +:103A900067FA0028BADB2A7BB88A013AD2B23146EB +:103AA000E2E7F98AC1F30901013B0429DAB25BD8E4 +:103AB000281D002307F11B069A4208D910F801CBF4 +:103AC00006F801C0013101330529DBB2F4D10399B5 +:103AD0000A9104990B91934207F11B010C9138BF95 +:103AE000043379680D9134BF55FA83F300230E93A4 +:103AF000FB8AADF83EB0C3F309031A44069B8DF868 +:103B00004230059B8DF8433094F82C30ADF83C20C2 +:103B100083F001038DF8443000238DF840A08DF828 +:103B200041807B602A7BB88A013A291DFFF76CF936 +:103B30003B8BB882834203D1A3680AA920469847E9 +:103B400020460AA9FFF702FEFB7DBA8AC3F384036D +:103B5000013303F01F039B02FB823B8B9A420CBF95 +:103B600000206FF01000C1E67B68002BAFD005206D +:103B700001E01C3033461E68002EFAD1091A081DD8 +:103B80002E1D184401EB090CBCF11B0F5FFA89F3E1 +:103B90009DD89A429BD916F8013B00F8013B09F1E8 +:103BA0000109EFE76FF00900A0E66FF00A009DE65B +:103BB0006FF00B009AE66FF00D0097E66FF00E00C5 +:103BC00094E66FF00F0091E640420F0080841E00E3 +:103BD000EFF3098305494A6B22F001024A63683317 +:103BE00083F30988002383F31188704700EF00E016 +:103BF000302080F3118862B60C4B0D4AD96821F44D +:103C0000E0610904090C0A43DA60D3F8FC20094991 +:103C100042F08072C3F8FC200A6842F001020A6098 +:103C20002022DA7783F82200704700BF00ED00E021 +:103C30000003FA05001000E010B5302383F311886B +:103C40000E4B5B6813F4006314D0F1EE103AEFF3FF +:103C50000984683C4FF08073E361094BDB6B23669A +:103C600084F3098800F0BCFC10B1064BA36110BDC1 +:103C7000054BFBE783F31188F9E700BF00ED00E097 +:103C800000EF00E03F0300084203000800F160433A +:103C900003F561430901C9B283F80013012200F062 +:103CA0001F039A4043099B0003F1604303F56143FE +:103CB000C3F880211A6070470268436811430160AD +:103CC00003B118477047000013B5446BD4F894341F +:103CD0001A681178042915D1217C022912D1197989 +:103CE000128901238B4013420CD101A904F14C002D +:103CF00001F09CFFD4F89444019B2179024620688E +:103D000000F0D0F902B010BD143001F01FBF000068 +:103D10004FF0FF33143001F019BF00004C3001F0B8 +:103D2000F1BF00004FF0FF334C3001F0EBBF00005B +:103D3000143001F0EDBE00004FF0FF31143001F0FF +:103D4000E7BE00004C3001F0BDBF00004FF0FF3275 +:103D50004C3001F0B7BF00000020704710B5D0F81C +:103D600094341A6811780429044617D1017C022979 +:103D700014D15979528901238B4013420ED114304A +:103D800001F080FE024648B1D4F894444FF48073A9 +:103D900061792068BDE8104000F072B910BD0000E4 +:103DA000406BFFF7DBBF0000704700007FB5124B90 +:103DB000036000234360C0E90233012502260F4B54 +:103DC000057404460290019300F18402294600968E +:103DD0004FF48073143001F031FE094B0294CDE9A9 +:103DE000006304F523724FF48073294604F14C00FC +:103DF00001F0F8FE04B070BD28660008A13D00087F +:103E0000C93C00080B68302282F311880A7903EB61 +:103E1000820290614A79093243F822008A7912B10C +:103E200003EB820398610223C0F89414037400200A +:103E300080F311887047000038B5037F044613B142 +:103E400090F85430ABB9201D01250221FFF734FF53 +:103E500004F1140025776FF0010100F079FC84F87B +:103E6000545004F14C006FF00101BDE8384000F0FF +:103E70006FBC38BD10B5012104460430FFF71CFFAC +:103E80000023237784F8543010BD000038B5044671 +:103E90000025143001F0EAFD04F14C00257701F013 +:103EA000B9FE201D84F854500121FFF705FF20467C +:103EB000BDE83840FFF752BF90F8443003F060038C +:103EC000202B07D190F84520212A4FF0000303D87A +:103ED0001F2A06D800207047222AFBD1C0E90E33E2 +:103EE00003E0034A82630722C26303640120704730 +:103EF0001D23002037B5D0F894341A6811780429AE +:103F000004461AD1017C022917D11979128901239B +:103F10008B40134211D100F14C05284601F03AFFC5 +:103F200058B101A9284601F081FED4F89444019BC0 +:103F300021790246206800F0B5F803B030BD0000DA +:103F4000F0B500EB810385B09E6904460D46FEB1D5 +:103F5000302383F3118804EB8507301D0821FFF718 +:103F6000ABFEFB685B691B6806F14C001BB101905E +:103F700001F06AFE019803A901F058FE024648B11B +:103F8000039B2946204600F08DF8002383F3118817 +:103F900005B0F0BDFB685A691268002AF5D01B8A8B +:103FA000013B1340F1D104F14402EAE7093138B58D +:103FB00050F82140DCB1302383F31188D4F89424E5 +:103FC0001368527903EB8203DB689B695D6845B136 +:103FD00004216018FFF770FE294604F1140001F077 +:103FE0005BFD2046FFF7BAFE002383F3118838BD3E +:103FF0007047000001F0D0B8012303700023C0E92E +:104000000133C36183620362C36243620363704727 +:1040100038B50446302383F311880025C0E90355E1 +:10402000C0E90555416001F0C7F80223237085F30C +:104030001188284638BD000070B500EB81030546A5 +:104040005069DA600E46144618B110220021FDF7BF +:10405000FBFBA06918B110220021FDF7F5FB3146EA +:104060002846BDE8704001F071B90000826802F096 +:10407000011282600022C0E90422826101F0F2B9DB +:10408000F0B400EB81044789E4680125A4698D4000 +:104090003D43458123600023A2606360F0BC01F0D2 +:1040A0000DBA0000F0B400EB81040789E468012533 +:1040B00064698D403D43058123600023A2606360F5 +:1040C000F0BC01F087BA000070B502230025044659 +:1040D0000370C0E90255C0E90455C564856180F8E4 +:1040E000345001F0CFF863681B6823B1294620469D +:1040F000BDE87040184770BD0378052B10B5044625 +:104100000AD080F850300523037043681B680BB158 +:10411000042198470023A36010BD00000178052901 +:1041200006D190F85020436802701B6803B118470D +:104130007047000070B590F83430044613B1002386 +:1041400080F8343004F14402204601F0ADF9636890 +:104150009B68B3B994F8443013F0600535D0002162 +:10416000204601F04DFC0021204601F03FFC636831 +:104170001B6813B1062120469847062384F8343083 +:1041800070BD204698470028E4D0B4F84A30E26B6E +:104190009A4288BFE36394F94430E56B002B4FF0FB +:1041A000300380F20381002D00F0F280092284F8B0 +:1041B000342083F311880021D4E90E232046FFF731 +:1041C00071FF002383F31188DAE794F8452003F0A8 +:1041D0007F0343EA022340F20232934200F0C5809B +:1041E00021D8B3F5807F48D00DD8012B3FD0022BCA +:1041F00000F09380002BB2D104F14C02A2630222A2 +:10420000E2632364C1E7B3F5817F00F09B80B3F5DF +:10421000407FA4D194F84630012BA0D1B4F84C30A3 +:1042200043F0020332E0B3F5006F4DD017D8B3F579 +:10423000A06F31D0A3F5C063012B90D8636894F8C8 +:1042400046205E6894F84710B4F848302046B047DE +:10425000002884D04368A3630368E3631AE0B3F5DE +:10426000106F36D040F6024293427FF478AF5C4B39 +:10427000A3630223E3630023C3E794F84630012BD2 +:104280007FF46DAFB4F84C3023F00203C4E90E554F +:10429000A4F84C30256478E7B4F84430B3F5A06F47 +:1042A0000ED194F8463084F84E30204601F042F8A2 +:1042B00063681B6813B101212046984703232370CC +:1042C0000023C4E90E339CE704F14F03A3630123E9 +:1042D000C3E72378042B10D1302383F311882046C1 +:1042E000FFF7C4FE85F311880321636884F84F50FB +:1042F00021701B680BB12046984794F84630002B7C +:10430000DED084F84F300423237063681B68002BD1 +:10431000D6D0022120469847D2E794F848301D06AF +:1043200003F00F0120460AD501F0B0F8012804D0AF +:1043300002287FF414AF2B4B9AE72B4B98E701F040 +:1043400097F8F3E794F84630002B7FF408AF94F821 +:10435000483013F00F01B3D01A06204602D501F001 +:1043600063FBADE701F056FBAAE794F84630002B5B +:104370007FF4F5AE94F8483013F00F01A0D01B067F +:10438000204602D501F03CFB9AE701F02FFB97E7AE +:10439000142284F8342083F311882B462A462946B8 +:1043A0002046FFF76DFE85F31188E9E65DB1152221 +:1043B00084F8342083F311880021D4E90E232046A9 +:1043C000FFF75EFEFDE60B2284F8342083F31188AC +:1043D0002B462A4629462046FFF764FEE3E700BF46 +:1043E00058660008506600085466000838B590F812 +:1043F00034300446002B3ED0063BDAB20F2A34D8C4 +:104400000F2B32D8DFE803F0373131082232313157 +:104410003131313131313737C56BB0F84A309D42D7 +:1044200014D2C3681B8AB5FBF3F203FB12556DB9B6 +:10443000302383F311882B462A462946FFF732FEA4 +:1044400085F311880A2384F834300EE0142384F8AD +:104450003430302383F3118800231A46194620464E +:10446000FFF70EFE002383F3118838BD036C03B100 +:1044700098470023E7E70021204601F0C1FA002118 +:10448000204601F0B3FA63681B6813B10621204689 +:1044900098470623D7E7000010B590F83430142B66 +:1044A000044629D017D8062B05D001D81BB110BD62 +:1044B000093B022BFBD80021204601F0A1FA002184 +:1044C000204601F093FA63681B6813B10621204669 +:1044D0009847062319E0152BE9D10B2380F83430D7 +:1044E000302383F3118800231A461946FFF7DAFDBB +:1044F000002383F31188DAE7C3689B695B68002BAC +:10450000D5D1036C03B19847002384F83430CEE74B +:1045100000230375826803691B6899689142FBD286 +:104520005A6803604260106058607047002303754A +:10453000826803691B6899689142FBD85A680360D6 +:10454000426010605860704708B50846302383F316 +:1045500011880B7D032B05D0042B0DD02BB983F3D1 +:10456000118808BD8B6900221A604FF0FF33836108 +:10457000FFF7CEFF0023F2E7D1E9003213605A6063 +:10458000F3E70000FFF7C4BF054BD968087518684A +:1045900002681A60536001220275D860FBF7BABE48 +:1045A000704B002030B50C4BDD684B1C87B00446C7 +:1045B0000FD02B46094A684600F05EF92046FFF707 +:1045C000E3FF009B13B1684600F060F9A86907B0EB +:1045D00030BDFFF7D9FFF9E7704B002049450008CF +:1045E000044B1A68DB6890689B68984294BF00206F +:1045F00001207047704B0020084B10B51C68D8682C +:1046000022681A60536001222275DC60FFF78EFF7A +:1046100001462046BDE81040FBF77CBE704B0020F1 +:1046200038B5074C07490848012300252370656009 +:1046300001F0E8FB0223237085F3118838BD00BF29 +:10464000D84D002060660008704B002008B572B697 +:10465000044B186500F046FC00F0FCFC024B032202 +:104660001A70FEE7704B0020D84D002000F044B9CE +:10467000034A516853685B1A9842FBD8704700BFE1 +:10468000001000E08B60022308618B8208467047AF +:104690008368A3F1840243F8142C026943F8442C84 +:1046A000426943F8402C094A43F8242CC26843F875 +:1046B000182C022203F80C2C002203F80B2C044ABD +:1046C00043F8102CA3F12000704700BF2D03000811 +:1046D000704B002008B5FFF7DBFFBDE80840FFF78F +:1046E00051BF0000024BDB6898610F20FFF74CBF01 +:1046F000704B0020302383F31188FFF7F3BF0000D5 +:1047000008B50146302383F311880820FFF74AFFDC +:10471000002383F3118808BD064BDB6839B142687A +:1047200018605A60136043600420FFF73BBF4FF0EE +:10473000FF307047704B00200368984206D01A681B +:104740000260506099611846FFF71CBF7047000077 +:1047500038B504460D462068844200D138BD036850 +:1047600023605C608561FFF70DFFF4E710B5036817 +:104770009C68A2420CD85C688A600B604C60216027 +:10478000596099688A1A9A604FF0FF33836010BDB0 +:104790001B68121BECE700000A2938BF0A2170B51C +:1047A00004460D460A26601901F026FB01F012FBB3 +:1047B000041BA54203D8751C2E460446F3E70A2EB7 +:1047C00004D9BDE87040012001F05CBB70BD000061 +:1047D000F8B5144B0D46D96103F1100141600A2A66 +:1047E0001969826038BF0A22016048601861A81800 +:1047F000144601F0F3FA0A2701F0ECFA431BA34236 +:10480000064606D37C1C281901F0F6FA27463546E1 +:10481000F2E70A2F04D9BDE8F840012001F032BBCD +:10482000F8BD00BF704B0020F8B506460D4601F0FC +:10483000D1FA0F4A134653F8107F9F4206D12A46F9 +:1048400001463046BDE8F840FFF7C2BFD169BB68FA +:10485000441A2C1928BF2C46A34202D92946FFF737 +:104860009BFF224631460348BDE8F840FFF77EBF74 +:10487000704B0020804B002010B4C0E903230023BC +:104880005DF8044B4361FFF7CFBF000010B5194C32 +:10489000236998420DD0D0E90032816813605A60D4 +:1048A0009A680A449A60002303604FF0FF33A361C3 +:1048B00010BD2346026843F8102F536000220260A7 +:1048C00022699A4203D1BDE8104001F08FBA936883 +:1048D00081680B44936001F07DFA2269E169926876 +:1048E000441AA242E4D91144BDE81040091AFFF766 +:1048F00053BF00BF704B00202DE9F047DFF8BC80AC +:1049000008F110072C4ED8F8105001F063FAD8F8CF +:104910001C40AA68031B9A423ED81444D5E90032D1 +:104920004FF00009C8F81C4013605A60C5F80090A9 +:10493000D8F81030B34201D101F058FA89F3118848 +:10494000D5E9033128469847302383F311886B69F2 +:10495000002BD8D001F03EFA6A69A0EB04094A4561 +:1049600082460DD2022001F08DFA0022D8F81030D4 +:10497000B34208D151462846BDE8F047FFF728BFAB +:10498000121A2244F2E712EB090938BF4A462946B7 +:104990003846FFF7EBFEB5E7D8F81030B34208D041 +:1049A0001444211AC8F81C00A960BDE8F047FFF7BD +:1049B000F3BEBDE8F08700BF804B0020704B0020A5 +:1049C00038B501F007FA054AD2E90845031B181962 +:1049D00045F10001C2E9080138BD00BF704B00205D +:1049E00000207047FEE70000704700004FF0FF30E6 +:1049F0007047000002290CD0032904D00129074880 +:104A000018BF00207047032A05D8054800EBC200F4 +:104A10007047044870470020704700BF386700089F +:104A20002C230020EC66000870B59AB005460846B5 +:104A300001A9144600F0C2F801A8FCF7FDFE431CD2 +:104A40005B00C5E900340022237003236370C6B203 +:104A500001AB02341046D1B28E4204F1020401D8F7 +:104A60001AB070BD13F8011B04F8021C04F8010C05 +:104A70000132F0E708B5302383F311880348FFF7CC +:104A800039FA002383F3118808BD00BFE04D0020F0 +:104A900090F8443003F01F02012A07D190F8452016 +:104AA0000B2A03D10023C0E90E3315E003F06003A5 +:104AB000202B08D1B0F848302BB990F84520212A96 +:104AC00003D81F2A04D8FFF7F7B9222AEBD0FAE758 +:104AD000034A82630722C26303640120704700BF58 +:104AE0002423002007B5052917D8DFE801F019169F +:104AF00003191920302383F31188104A01900121F2 +:104B0000FFF79AFA01980E4A0221FFF795FA0D482D +:104B1000FFF7BCF9002383F3118803B05DF804FBB1 +:104B2000302383F311880748FFF786F9F2E7302333 +:104B300083F311880348FFF79DF9EBE78C660008C3 +:104B4000B0660008E04D002038B50C4D0C4C0D4906 +:104B50002A4604F10800FFF767FF05F1CA0204F1D5 +:104B600010000949FFF760FF05F5CA7204F118004B +:104B70000649BDE83840FFF757BF00BFA8520020E4 +:104B80002C2300206C660008766600088166000809 +:104B900070B5044608460D46FCF74EFEC6B22046E8 +:104BA000013403780BB9184670BD32462946FCF72C +:104BB0002FFE0028F3D10120F6E700002DE9F04791 +:104BC00005460C46FCF738FE2B49C6B22846FFF7CF +:104BD000DFFF08B10636F6B228492846FFF7D8FFAE +:104BE00008B11036F6B2632E0BD8DFF88C80DFF8F0 +:104BF0008C90234FDFF894A02E7846B92670BDE83C +:104C0000F08729462046BDE8F04701F089BC252EF3 +:104C10002ED1072241462846FCF7FAFD70B9194B00 +:104C2000224603F10C0153F8040B42F8040B8B42AB +:104C3000F9D11B78137007350D34DDE7082249469A +:104C40002846FCF7E5FD98B90F4BA21C1978090915 +:104C50000232C95D02F8041C13F8011B01F00F01B8 +:104C60005345C95D02F8031CF0D118340835C3E779 +:104C700004F8016B0135BFE758670008816600083A +:104C8000606700083E650008107AFF1F1C7AFF1F4E +:104C9000BFF34F8F024AD368DB03FCD4704700BFD9 +:104CA000003C024008B5094B1B7873B9FFF7F0FFD1 +:104CB000074B1A69002ABFBF064A5A6002F18832C0 +:104CC0005A601A6822F480621A6008BD06550020F6 +:104CD000003C02402301674508B50B4B1B7893B994 +:104CE000FFF7D6FF094B1A6942F000421A611A68B1 +:104CF00042F480521A601A6822F480521A601A68CC +:104D000042F480621A6008BD06550020003C024053 +:104D10000B28F0B516D80C4C0C4923787BB90C4DF8 +:104D20000E460C234FF0006255F8047B46F8042B26 +:104D3000013B13F0FF033A44F6D10123237051F8ED +:104D40002000F0BD0020FCE7385500200855002069 +:104D500074670008014B53F820007047746700081F +:104D60000C2070470B2810B5044601D9002010BD57 +:104D7000FFF7CEFF064B53F824301844C21A0BB984 +:104D80000120F4E712680132F0D1043BF6E700BFDE +:104D9000746700080B2810B5044621D8FFF778FF88 +:104DA000FFF780FF0F4AF323D360C300DBB243F465 +:104DB000007343F002031361136943F480331361FA +:104DC000FFF766FFFFF7A4FF074B53F8241000F02E +:104DD0003DF9FFF781FF2046BDE81040FFF7C2BF55 +:104DE000002010BD003C024074670008F8B512F0C6 +:104DF0000103144642D18218B2F1016F57D82D4BEE +:104E00001B6813F0010352D02B4DFFF74BFFF32328 +:104E1000EB60FFF73DFF40F20127032C15D824F08B +:104E200001046618244C401A40F20117B14223696C +:104E300000EB010524D123F001032361FFF74CFFB0 +:104E40000120F8BD043C0430E7E78307E7D12B6974 +:104E500023F440732B612B693B432B6151F8046BA6 +:104E60000660BFF34F8FFFF713FF03689E42E9D040 +:104E70002B6923F001032B61FFF72EFF0020E0E7F1 +:104E800023F44073236123693B4323610B882B8008 +:104E9000BFF34F8FFFF7FCFE2D8831F8023BADB218 +:104EA000AB42C3D0236923F001032361E4E7184632 +:104EB000C7E700BF00380240003C0240084908B57F +:104EC0000B7828B11BB9FFF7EDFE01230B7008BD6D +:104ED000002BFCD0BDE808400870FFF7FDBE00BF06 +:104EE0000655002008B50649064800F0B1F8BDE8AF +:104EF00008404FF480314FF0805000F0A9B800BF57 +:104F000000FF0100000100200846114601F06CBAC4 +:104F1000012001F069BA0000084601F083BA0000E0 +:104F200038B5EFF311859DB9EFF30584C4F3080498 +:104F3000302334B183F31188FFF742FD85F31188E4 +:104F400038BD83F31188FFF73BFD84F3118838BD2A +:104F5000BDE83840FFF734BD38B5FFF7E1FF114C2D +:104F6000114AC00840EA4170A0FB025EC908A0FBDC +:104F7000040C1CEB050CA1FB04404FF000035B414B +:104F8000A1FB02121CEB040C43EB000011EB0E0121 +:104F900042F10002411842F10000090941EA0070A3 +:104FA00038BD00BFCFF753E3A59BC42010B5024422 +:104FB000064BD2B2904200D110BD441C00B253F84F +:104FC000200041F8040BE0B2F4E700BF5028004095 +:104FD0000F4B30B51C6F240407D41C6F44F40074CD +:104FE0001C671C6F44F400441C670A4C236843F49C +:104FF000807323600244084BD2B2904200D130BD8E +:10500000441C00B251F8045B43F82050E0B2F4E7CE +:1050100000380240007000405028004007B50122CF +:1050200001A90020FFF7C2FF019803B05DF804FB5F +:1050300013B50446FFF7F2FFA04205D0012201A9F3 +:1050400000200194FFF7C4FF02B010BD70470000BC +:105050007047000070470000074B45F255521A6038 +:1050600002225A6040F6FF729A604CF6CC421A60F7 +:10507000024B01221A70704700300040405500205A +:10508000034B1B781BB1034B4AF6AA221A607047E8 +:105090004055002000300040034B1A681AB9034AFB +:1050A000D2F874281A6070473C5500200030024046 +:1050B000024B4FF08072C3F87428704700300240F2 +:1050C00008B5FFF7E9FF024B1868C0F3407008BD50 +:1050D0003C55002008B5FFF7DFFF024B1868C0F30E +:1050E000007008BD3C55002070470000FEE700003E +:1050F0000A4B0B480B4A90420BD30B4BDA1C121A8B +:10510000C11E22F003028B4238BF00220021FCF7AF +:105110009BBB53F8041B40F8041BECE790690008A4 +:1051200044560020445600204456002070B5D0E973 +:1051300015439E6800224FF0FF3504EB42135101E6 +:10514000D3F800090028BEBFD3F8000940F0804022 +:10515000C3F80009D3F8000B0028BEBFD3F8000B3A +:1051600040F08040C3F8000B013263189642C3F848 +:105170000859C3F8085BE0D24FF00113C4F81C389B +:1051800070BD0000890141F02001016103699B06A7 +:10519000FCD41220FFF76CBA10B5054C2046FEF780 +:1051A0002BFF4FF0A0436365024BA36510BD00BF0A +:1051B00044550020C867000870B50378012B0546E8 +:1051C00050D12A4B446D98421BD1294B5A6B42F067 +:1051D00080025A635A6D42F080025A655A6D5A69CC +:1051E00042F080025A615A6922F080025A610E210F +:1051F00043205B69FEF74AFD1E4BE3601E4BC4F87B +:1052000000380023C4F8003EC02323606E6D4FF4C5 +:105210000413A3633369002BFCDA012333610C20F0 +:10522000FFF726FA3369DB07FCD41220FFF720FAD8 +:105230003369002BFCDA0026A6602846FFF776FFCC +:105240006B68C4F81068DB68C4F81468C4F81C689C +:105250004BB90A4BA3614FF0FF336361A36843F07E +:105260000103A36070BD064BF4E700BF4455002066 +:10527000003802404014004003002002003C30C0CF +:10528000083C30C0F8B5446D054600212046FFF7C4 +:1052900079FFA96D00234FF001128F68C4F83438EC +:1052A0004FF00066C4F81C284FF0FF3004EB4312A7 +:1052B00001339F42C2F80069C2F8006BC2F80809C6 +:1052C000C2F8080BF2D20B686A6DEB6563621023BB +:1052D0001361166916F01006FBD11220FFF7C8F90A +:1052E000D4F8003823F4FE63C4F80038A36943F40B +:1052F000402343F01003A3610923C4F81038C4F815 +:1053000014380A4BEB604FF0C043C4F8103B084B15 +:10531000C4F8003BC4F81069C4F80039EB6D03F120 +:10532000100243F48013EA65A362F8BDA467000885 +:1053300040800010426D90F84E10D2F8003823F4EF +:10534000FE6343EA0113C2F8003870472DE9F843C1 +:1053500000EB8103456DDA68166806F00306731EDC +:10536000022B05EB41130C4680460FFA81F94FEAF8 +:1053700041104FF00001C3F8101B4FF0010104F180 +:10538000100398BFB60401FA03F391698EBF334E40 +:1053900006F1805606F5004600293AD0578A04F1F6 +:1053A0005801490137436F50D5F81C180B43C5F815 +:1053B0001C382B180021C3F8101953690127611EEE +:1053C000A7409BB3138A928B9B08012A88BF534343 +:1053D000D8F85C20981842EA034301F1400205EB3B +:1053E0008202C8F85C00214653602846FFF7CAFED7 +:1053F00008EB8900C3681B8A43EA8453483464017C +:105400001E432E51D5F81C381F43C5F81C78BDE843 +:10541000F88305EB4917D7F8001B21F40041C7F8C2 +:10542000001BD5F81C1821EA0303C0E704F13F0371 +:1054300005EB83030A4A5A6028462146FFF7A2FE7D +:1054400005EB4910D0F8003923F40043C0F80039C7 +:10545000D5F81C3823EA0707D7E700BF0080001003 +:1054600000040002826D1268C265FFF75FBE000093 +:105470005831436D49015B5813F4004004D013F4D4 +:10548000001F0CBF02200120704700004831436D0F +:1054900049015B5813F4004004D013F4001F0CBF03 +:1054A000022001207047000000EB8101CB68196ADF +:1054B0000B6813604B6853607047000000EB81037A +:1054C00030B5DD68AA691368D36019B9402B84BF71 +:1054D000402313606B8A1468426D1C44013CB4FB8A +:1054E000F3F46343033323F0030302EB411043EA75 +:1054F000C44343F0C043C0F8103B2B6803F00303E0 +:10550000012B09B20ED1D2F8083802EB411013F486 +:10551000807FD0F8003B14BF43F0805343F000532A +:10552000C0F8003B02EB4112D2F8003B43F00443C9 +:10553000C2F8003B30BD00002DE9F041244D6E6DF6 +:1055400006EB40130446D3F8087BC3F8087B380702 +:105550000AD5D6F81438190706D505EB8403214679 +:10556000DB6828465B689847FA071FD5D6F81438D9 +:10557000DB071BD505EB8403D968CCB98B69488A56 +:105580005A68B2FBF0F600FB16228AB91868DA688E +:1055900090420DD2121AC3E90024302383F31188FC +:1055A0000B482146FFF78AFF84F31188BDE8F0819C +:1055B000012303FA04F26B8923EA02036B81CB68AF +:1055C000002BF3D021460248BDE8F041184700BF48 +:1055D0004455002000EB810370B5DD68436D6C69B4 +:1055E0002668E6604A0156BB1A444FF40020C2F810 +:1055F00010092A6802F00302012A0AB20ED1D3F878 +:10560000080803EB421410F4807FD4F8000914BF9B +:1056100040F0805040F00050C4F8000903EB421203 +:10562000D2F8000940F00440C2F80009D3F8340869 +:10563000012202FA01F10143C3F8341870BD19B90F +:10564000402E84BF4020206020682E8A8419013CAF +:10565000B4FBF6F440EAC44040F000501A44C6E7F8 +:105660002DE9F8433B4D6E6D06EB40130446D3F82D +:105670000889C3F8088918F0010F4FEA40171AD0BB +:10568000D6F81038DB0716D505EB8003D9684B69CF +:105690001868DA68904230D2121A4FF000091A6086 +:1056A000C3F80490302383F3118821462846FFF77E +:1056B00091FF89F3118818F0800F1CD0D6F8343888 +:1056C0000126A640334216D005EB84036D6DD3F856 +:1056D0000CC0DCF814200134E4B2D2F800E005EB91 +:1056E00004342F445168714515D3D5F8343823EA72 +:1056F0000606C5F83468BDE8F883012303FA04F20E +:105700002B8923EA02032B818B68002BD3D02146FF +:1057100028469847CFE7BCF81000AEEB0103834260 +:1057200028BF0346D7F8180980B2B3EB800FE2D840 +:105730009068A0F1040959F8048FC4F80080A0EB28 +:1057400009089844B8F1040FF5D818440B44906048 +:105750005360C7E7445500202DE9F74FA24C656D13 +:105760006E69AB691E4016F480586E6107D0204602 +:10577000FEF7AAFC03B0BDE8F04FFEF75DBA002EBD +:1057800012DAD5F8003E98489B071EBFD5F8003EB8 +:1057900023F00303C5F8003ED5F8043823F00103D5 +:1057A000C5F80438FEF7BAFC370505D58E48FFF773 +:1057B000BDFC8D48FEF7A0FCB0040CD5D5F8083828 +:1057C00013F0060FEB6823F470530CBF43F410532F +:1057D00043F4A053EB6031071BD56368DB681BB94A +:1057E000AB6923F00803AB612378052B0CD1D5F806 +:1057F000003E7D489A071EBFD5F8003E23F0030304 +:10580000C5F8003EFEF78AFC6368DB680BB176489A +:105810009847F30274D4B70227D5D4F85490DFF830 +:10582000C8B100274FF0010A09EB4712D2F8003B3C +:1058300003F44023B3F5802F11D1D2F8003B002BA5 +:105840000DDA62890AFA07F322EA0303638104EBA3 +:105850008703DB68DB6813B1394658469847A36D68 +:1058600001379B68FFB29F42DED9F00617D5676DFE +:105870003A6AC2F30A1002F00F0302F4F012B2F512 +:10588000802F00F08580B2F5402F08D104EB830310 +:105890000022DB681B6A07F5805790426AD130030B +:1058A000D5F8184813D5E10302D50020FFF744FED0 +:1058B000A20302D50120FFF73FFE630302D50220B9 +:1058C000FFF73AFE270302D50320FFF735FE7503E5 +:1058D0007FF550AFE00702D50020FFF7C1FEA1071A +:1058E00002D50120FFF7BCFE620702D50220FFF7B8 +:1058F000B7FE23077FF53EAF0320FFF7B1FE39E780 +:10590000636DDFF8E4A0019300274FF00109A36D58 +:105910009B685FFA87FB9B453FF67DAF019B03EBDE +:105920004B13D3F8001901F44021B1F5802F1FD19A +:10593000D3F8001900291BDAD3F8001941F090417F +:10594000C3F80019D3F800190029FBDB5946606D34 +:10595000FFF718FC218909FA0BF321EA03032381DD +:1059600004EB8B03DB689B6813B15946504698479C +:105970000137CCE7910708BFD7F80080072A98BF06 +:1059800003F8018B02F1010298BF4FEA182884E75F +:10599000023304EB830207F580575268D2F818C02F +:1059A000DCF80820DCE9001CA1EB0C0C002188428B +:1059B0000AD104EB830463689B699A6802449A6085 +:1059C0005A6802445A606AE711F0030F08BFD7F81B +:1059D00000808C4588BF02F8018B01F1010188BF6E +:1059E0004FEA1828E3E700BF44550020436D03EB5E +:1059F0004111D1F8003B43F40013C1F8003B70475C +:105A0000436D03EB4111D1F8003943F40013C1F8A1 +:105A100000397047436D03EB4111D1F8003B23F48B +:105A20000013C1F8003B7047436D03EB4111D1F8FF +:105A3000003923F40013C1F80039704730B5039CD6 +:105A40000172043304FB0325C0E90653049B03637E +:105A50000021059BC160C0E90000C0E90422C0E943 +:105A60000842C0E90A11436330BD0000416A0022C8 +:105A7000C0E90411C0E90A22C2606FF00101FEF71B +:105A800067BE0000D0E90432934201D1C2680AB96E +:105A9000181D70470020704703691960C268013201 +:105AA000C260C269134482690361934224BF436A9E +:105AB00003610021FEF740BE38B504460D46E36899 +:105AC0003BB16269131D1268A3621344E3620020B4 +:105AD00007E0237A33B929462046FEF71DFE002849 +:105AE000EDDA38BD6FF00100FBE70000C368C26962 +:105AF000013BC3604369134482694361934224BFFD +:105B0000436A436100238362036B03B11847704704 +:105B100070B53023044683F31188866A3EB9FFF7D7 +:105B2000CBFF054618B186F31188284670BDA36ADD +:105B3000E26A13F8015BA362934202D32046FFF7A7 +:105B4000D5FF002383F31188EFE700002DE9F84F1C +:105B500004460E46174698464FF0300989F31188DF +:105B60000025AA46D4F828B0BBF1000F09D1414660 +:105B70002046FFF7A1FF20B18BF311882846BDE82E +:105B8000F88FD4E90A12A7EB050B521A934528BFE8 +:105B90009346BBF1400F1BD9334601F1400251F847 +:105BA000040B43F8040B9142F9D1A36A4033403609 +:105BB000A3624035D4E90A239A4202D32046FFF774 +:105BC00095FF8AF31188BD42D8D289F31188C9E7BD +:105BD00030465A46FBF712FEA36A5B445E44A3625A +:105BE0005D44E7E710B5029C0172043303FB042116 +:105BF000C0E906130023C0E90A33039B0363049B37 +:105C0000C460C0E90000C0E90422C0E9084243635F +:105C100010BD0000026AC260426AC0E9042200228C +:105C2000C0E90A226FF00101FEF792BDD0E904231A +:105C30009A4201D1C26822B9184650F8043B0B6061 +:105C4000704700231846FAE7C368C2690133C3608E +:105C50004369134482694361934224BF436A4361A9 +:105C60000021FEF769BD000038B504460D46E36823 +:105C70003BB123691A1DA262E2691344E36200206A +:105C800007E0237A33B929462046FEF745FD002870 +:105C9000EDDA38BD6FF00100FBE700000369196021 +:105CA000C268013AC260C2691344826903619342C7 +:105CB00024BF436A036100238362036B03B1184767 +:105CC0007047000070B530230D460446114683F33B +:105CD0001188866A2EB9FFF7C7FF10B186F31188C5 +:105CE00070BDA36A1D70A36AE26A01339342A36286 +:105CF00004D3E16920460439FFF7D0FF002080F388 +:105D00001188EDE72DE9F84F04460D469046994677 +:105D10004FF0300A8AF311880026B346A76A4FB9BC +:105D200049462046FFF7A0FF20B187F3118830468F +:105D3000BDE8F88FD4E90A073A1AA8EB060797429C +:105D400028BF1746402F1BD905F1400355F8042BF7 +:105D500040F8042B9D42F9D1A36A4033A362403638 +:105D6000D4E90A239A4204D3E16920460439FFF7B3 +:105D700095FF8BF311884645D9D28AF31188CDE778 +:105D800029463A46FBF73AFDA36A3B443D44A362E9 +:105D90003E44E5E7D0E904239A4217D1C3689BB19A +:105DA000836A8BB1043B9B1A0ED01360C368013B1E +:105DB000C360C3691A44836902619A4224BF436A7B +:105DC0000361002383620123184670470023FBE729 +:105DD00000F0D2B84FF08043586A70474FF08043CC +:105DE000002258631A610222DA6070474FF0804344 +:105DF0000022DA60704700004FF08043586370471C +:105E0000FEE7000070B51B4B01630025044686B019 +:105E1000586085620E46FDF7EBFE04F11003C4E9FD +:105E200004334FF0FF33C4E90635C4E90044A560EC +:105E3000E562FFF7CFFF2B460246C4E9082304F1D1 +:105E400034010D4A256580232046FEF71BFC012303 +:105E5000E0600A4A0375009272680192B268CDE967 +:105E60000223074B6846CDE90435FEF733FC06B044 +:105E700070BD00BFD84D0020D4670008D967000866 +:105E8000015E0008024AD36A1843D062704700BF1F +:105E9000704B00204B6843608B688360CB68C360A5 +:105EA0000B6943614B6903628B6943620B68036052 +:105EB0007047000008B5264B26481A6940F2FF11CA +:105EC0000A431A611A6922F4FF7222F001021A6170 +:105ED0001A691A6B0A431A631A6D0A431A651E4A35 +:105EE0001B6D1146FFF7D6FF02F11C0100F5806023 +:105EF000FFF7D0FF02F1380100F58060FFF7CAFF1D +:105F000002F1540100F58060FFF7C4FF02F1700157 +:105F100000F58060FFF7BEFF02F18C0100F58060A4 +:105F2000FFF7B8FF02F1A80100F58060FFF7B2FFAC +:105F300002F1C40100F58060FFF7ACFF02F1E0015F +:105F400000F58060FFF7A6FFBDE8084000F090B8BC +:105F50000038024000000240E067000808B500F089 +:105F6000FBF9FEF75DFBFFF797F8BDE80840FEF789 +:105F7000EBBD0000704700000F4B1A6C42F00102AD +:105F80001A641A6E42F001021A660C4A1B6E93687C +:105F900043F0010393604FF0804353229A624FF025 +:105FA000FF32DA6200229A615A63DA605A60012293 +:105FB0005A611A60704700BF00380240002004E0B8 +:105FC0004FF0804208B51169D3680B40D9B2C9437C +:105FD0009B07116107D5302383F31188FEF746FB39 +:105FE000002383F3118808BD1F4B1A696FEAC25260 +:105FF0006FEAD2521A611A69C2F308021A614FF0AD +:10600000FF301A695A69586100215A6959615A6901 +:106010001A6A62F080521A621A6A02F080521A6298 +:106020001A6A5A6A58625A6A59625A6A1A6C42F073 +:1060300080521A641A6E42F080521A661A6E0B4A27 +:10604000106840F480701060186F00F44070B0F574 +:10605000007F1EBF4FF4803018671967536823F420 +:106060000073536000F054B90038024000700040E3 +:10607000334B4FF080521A64324A4FF44041116062 +:106080001A6842F001021A601A689107FCD59A68F2 +:1060900022F003029A602A4B9A6812F00C02FBD19C +:1060A000196801F0F90119609A601A6842F48032A7 +:1060B0001A601A689203FCD55A6F42F001025A67BF +:1060C0001F4B5A6F9007FCD51F4A5A601A6842F05E +:1060D00080721A601B4A53685904FCD5184B1A6821 +:1060E0009201FCD5194A9A60194B1A68194B9A42C9 +:1060F000194B21D1194A1168194A91421CD140F219 +:1061000005121A60144A136803F00F03052BFAD125 +:106110000B4B9A6842F002029A609A6802F00C02F5 +:10612000082AFAD15A6C42F480425A645A6E42F4F8 +:1061300080425A665B6E704740F20572E1E700BF2D +:10614000003802400070004008544007009488382E +:10615000002004E011640020003C024000ED00E05B +:1061600041C20F41074A08B5536903F00103536167 +:1061700023B1054A13680BB150689847BDE8084041 +:10618000FDF75ABD003C0140BC550020074A08B548 +:10619000536903F00203536123B1054A93680BB1BD +:1061A000D0689847BDE80840FDF746BD003C014077 +:1061B000BC550020074A08B5536903F00403536136 +:1061C00023B1054A13690BB150699847BDE80840EF +:1061D000FDF732BD003C0140BC550020074A08B520 +:1061E000536903F00803536123B1054A93690BB166 +:1061F000D0699847BDE80840FDF71EBD003C01404E +:10620000BC550020074A08B5536903F010035361D9 +:1062100023B1054A136A0BB1506A9847BDE808409C +:10622000FDF70ABD003C0140BC550020164B10B5DF +:106230005C6904F478725A61A30604D5134A936A20 +:106240000BB1D06A9847600604D5104A136B0BB1A6 +:10625000506B9847210604D50C4A936B0BB1D06B59 +:106260009847E20504D5094A136C0BB1506C984766 +:10627000A30504D5054A936C0BB1D06C9847BDE8D3 +:106280001040FDF7D9BC00BF003C0140BC550020C8 +:10629000194B10B55C6904F47C425A61620504D55F +:1062A000164A136D0BB1506D9847230504D5134A58 +:1062B000936D0BB1D06D9847E00404D50F4A136E6F +:1062C0000BB1506E9847A10404D50C4A936E0BB1E4 +:1062D000D06E9847620404D5084A136F0BB1506F13 +:1062E0009847230404D5054A936F0BB1D06F9847A4 +:1062F000BDE81040FDF7A0BC003C0140BC550020AB +:1063000008B5FFF75DFEBDE80840FDF795BC00004D +:10631000062108B50846FDF7B9FC06210720FDF760 +:10632000B5FC06210820FDF7B1FC06210920FDF788 +:10633000ADFC06210A20FDF7A9FC06211720FDF778 +:10634000A5FC06212820FDF7A1FCBDE80840072197 +:106350001C20FDF79BBC000008B5FFF745FE00F0D0 +:106360000BF8FDF747FEFDF71FFDFFF703FEBDE845 +:106370000840FFF72DBD00000023054A19460133F0 +:10638000102BC2E9001102F10802F8D1704700BFDA +:10639000BC5500200B460146184600F02DB8000001 +:1063A00000F040B8012838BF012010B5044620464F +:1063B00000F030F830B900F007F808B900F00CF838 +:1063C0008047F4E710BD0000024B1868BFF35B8FF5 +:1063D000704700BF3C56002008B5062000F084F846 +:1063E0000120FEF7FFFA0000024B0A46014618683A +:1063F000FEF78ABD4C23002010B5054C13462CB186 +:106400000A4601460220AFF3008010BD2046FCE79B +:1064100000000000024B01461868FEF779BD00BF7E +:106420004C230020024B01461868FEF775BD00BFE3 +:106430004C23002010B501390244904201D10020C4 +:1064400005E0037811F8014FA34201D0181B10BDDD +:106450000130F2E72DE9F041A3B1C91A17780144E0 +:10646000044603F1FF3C8C42204601D9002009E09C +:106470000578BD4204F10104F5D10CEB0405D618F2 +:10648000A54201D1BDE8F08115F8018D16F801EDA6 +:10649000F045F5D0E7E700001F2938B504460D4662 +:1064A00004D9162303604FF0FF3038BD426C12B19F +:1064B00052F821304BB9204600F030F82A46014608 +:1064C0002046BDE8384000F017B8012B0AD0591C0F +:1064D00003D1162303600120E7E7002442F825409A +:1064E000284698470020E0E7024B01461868FFF76E +:1064F000D3BF00BF4C23002038B5074D002304460E +:10650000084611462B60FEF771FA431C02D12B6836 +:1065100003B1236038BD00BF40560020FEF760BACB +:10652000034611F8012B03F8012B002AF9D170471B +:106530006F72672E6172647570696C6F742E663449 +:1065400030352D4D6174656B4750530053544D33B6 +:1065500032463F3F3F0053544D333246343078008B +:1065600053544D3332463432780053544D3332460F +:106570003434365858000000012033000010410028 +:1065800001105A00031059000710310000000000EC +:106590004C6500081304000056650008190400004B +:1065A00060650008210400006A65000840A2E4F16B +:1065B000646891060041A3E5F26569920700000056 +:1065C0004261642043414E496661636520696E649F +:1065D00065782E0080000000008000000000800030 +:1065E0000000000000000000052100082529000827 +:1065F0008128000845210008512100085123000886 +:106600001521000825210008192100082121000872 +:106610001D2100087522000829210008F52B00081B +:10662000392100084922000800000000253D00082B +:10663000113D00084D3D0008393D0008453D00086A +:10664000313D00081D3D0008093D0008593D000886 +:1066500000000000010000000000000063300000A6 +:106660005C660008C84B0020D84D0020417264755C +:1066700050696C6F740025424F415244252D424CA5 +:10668000002553455249414C2500000002000000FE +:1066900000000000413F0008AD3F000840004000FE +:1066A0007852002088520020020000000000000004 +:1066B0000300000000000000F13F0008000000009F +:1066C00010000000985200200000000001000000AF +:1066D000000000004455002001010200E54A0008C6 +:1066E000F5490008914A0008754A00084300000077 +:1066F000F466000809024300020100C032090400E8 +:10670000000102020100052400100105240100011E +:10671000042402020524060001070582030800FF85 +:1067200009040100020A0000000705010240000000 +:1067300007058102400000001200000040670008C9 +:10674000120110010200004009124157000201022B +:10675000030100000403090425424F41524425006F +:106760003031323334353637383941424344454687 +:106770000000000000400000004000000040000059 +:1067800000400000000001000000020000000200C4 +:1067900000000200000002000000020000000200F1 +:1067A000000002000000000035410008ED43000831 +:1067B0009944000840004000A4550020A455002042 +:1067C00001000000B45500208000000040010000DE +:1067D000030000006D61696E0069646C6500000073 +:1067E000AA01A81200000000AAAAAAAA5501140032 +:1067F000FFBF00008877000070A70A0000000A01B0 +:1068000000000000AAAAAAAA00000001FFFF0000E1 +:1068100000000000990000000000A0160000000029 +:10682000AAAAAAA600005011FFDF00000000000085 +:10683000007708002000000000000000AAAAAAAA11 +:1068400010000000FFFF0000000800000000000032 +:106850000000000000000000AAAAAAAA0000000090 +:10686000FFFF00000000000000000000000000002A +:1068700000000000AAAAAAAA00000000FFFF000072 +:106880000000000000000000000000000000000008 +:10689000AAAAAAAA00000000FFFF00000000000052 +:1068A0000000000000000000000000000A000000DE +:1068B00000000000030000000000000000000000D5 +:1068C00000000000000000000000000000000000C8 +:1068D00000000000000000000000000000000000B8 +:1068E000F60300000000000000000F0000000000A0 +:1068F00040420F00FE2A0100D2040000FF00960073 +:1069000000000008009600000000080004000000DD +:1069100054670008000000000000000000000000B4 +:1069200000000000000000000000000050230020D4 +:106930000000000000000000000000000000000057 +:106940000000000000000000000000000000000047 +:106950000000000000000000000000000000000037 +:106960000000000000000000000000000000000027 +:106970000000000000000000000000000000000017 +:106980000000000000000000000000000000000007 :00000001FF diff --git a/Tools/bootloaders/mRo-M10095_bl.bin b/Tools/bootloaders/mRo-M10095_bl.bin index d6e9552de9d889..f5b9703b3b6552 100755 Binary files a/Tools/bootloaders/mRo-M10095_bl.bin and b/Tools/bootloaders/mRo-M10095_bl.bin differ diff --git a/Tools/bootloaders/mRo-M10095_bl.elf b/Tools/bootloaders/mRo-M10095_bl.elf index f516a144bc382b..d2ac1fbe762720 100755 Binary files a/Tools/bootloaders/mRo-M10095_bl.elf and b/Tools/bootloaders/mRo-M10095_bl.elf differ diff --git a/Tools/bootloaders/mRo-M10095_bl.hex b/Tools/bootloaders/mRo-M10095_bl.hex index 097fbdc19b25cd..6787419734ba19 100644 --- a/Tools/bootloaders/mRo-M10095_bl.hex +++ b/Tools/bootloaders/mRo-M10095_bl.hex @@ -1,1412 +1,1389 @@ :020000040800F2 -:1000000000070020F5040008A52F00085D2F000858 -:10001000852F00085D2F00087D2F0008F7040008D9 -:10002000F7040008F7040008F7040008853F0008FB -:10003000F7040008F7040008F7040008F7040008B4 -:10004000F7040008F7040008F7040008F7040008A4 -:10005000F7040008F7040008D9520008015300080B -:10006000295300085153000879530008F704000889 -:10007000F7040008F7040008F7040008F704000874 -:10008000F7040008F7040008F7040008F704000864 -:10009000F70400083D2F00084D2F0008A153000869 -:1000A000F7040008F7040008F7040008F704000844 -:1000B00089540008F7040008F7040008F704000852 -:1000C000F7040008F7040008F7040008F704000824 -:1000D000F704000875540008F7040008F704000846 -:1000E00005540008F7040008F7040008F7040008A6 -:1000F000F7040008F7040008F7040008F7040008F4 -:10010000F7040008F7040008F7040008F7040008E3 -:10011000F7040008F7040008F7040008F7040008D3 -:10012000F7040008F7040008F7040008F7040008C3 -:10013000F7040008F7040008F7040008F7040008B3 -:10014000F7040008F7040008F7040008F7040008A3 -:10015000F7040008F7040008F7040008F704000893 -:10016000F7040008F7040008F7040008F704000883 -:10017000F7040008F7040008F7040008F704000873 -:10018000F7040008F7040008F7040008F704000863 -:10019000F7040008F7040008F7040008F704000853 -:1001A000F7040008F7040008F7040008F704000843 -:1001B000F7040008F7040008F7040008F704000833 -:1001C000F7040008F7040008F7040008F704000823 -:1001D000F7040008F7040008F7040008F704000813 -:1001E00009180008000000000000000000000000E6 -:1001F00053B94AB9002908BF00281CBF4FF0FF318E -:100200004FF0FF3000F074B9ADF1080C6DE904CE89 -:1002100000F006F8DDF804E0DDE9022304B07047E1 -:100220002DE9F047089D04468E46002B4DD18A42A9 -:10023000944669D9B2FA82F252B101FA02F3C2F1DC -:10024000200120FA01F10CFA02FC41EA030E94406D -:100250004FEA1C48210CBEFBF8F61FFA8CF708FB8E -:1002600016E341EA034306FB07F199420AD91CEB66 -:10027000030306F1FF3080F01F81994240F21C8198 -:10028000023E63445B1AA4B2B3FBF8F008FB1033E0 -:1002900044EA034400FB07F7A7420AD91CEB040415 -:1002A00000F1FF3380F00A81A74240F207816444E5 -:1002B000023840EA0640E41B00261DB1D44000236A -:1002C000C5E900433146BDE8F0878B4209D9002DCE -:1002D00000F0EF800026C5E9000130463146BDE858 -:1002E000F087B3FA83F6002E4AD18B4202D38242C2 -:1002F00000F2F980841A61EB030301209E46002D71 -:10030000E0D0C5E9004EDDE702B9FFDEB2FA82F2C5 -:10031000002A40F09280A1EB0C014FEA1C471FFA23 -:100320008CFE0126200CB1FBF7F307FB131140EA0A -:1003300001410EFB03F0884208D91CEB010103F1D7 -:10034000FF3802D2884200F2CB804346091AA4B299 -:10035000B1FBF7F007FB101144EA01440EFB00FE6D -:10036000A64508D91CEB040400F1FF3102D2A645D2 -:1003700000F2BB800846A4EB0E0440EA03409CE771 -:10038000C6F12007B34022FA07FC4CEA030C20FA1E -:1003900007F401FA06F31C43F9404FEA1C4900FA3E -:1003A00006F3B1FBF9F8200C1FFA8CFE09FB1811BB -:1003B00040EA014108FB0EF0884202FA06F20BD92E -:1003C0001CEB010108F1FF3A80F08880884240F27E -:1003D0008580A8F102086144091AA4B2B1FBF9F0C2 -:1003E00009FB101144EA014100FB0EFE8E4508D9BD -:1003F0001CEB010100F1FF346CD28E456AD9023842 -:10040000614440EA0840A0FB0294A1EB0E01A14226 -:10041000C846A64656D353D05DB1B3EB080261EB94 -:100420000E0101FA07F722FA06F3F1401F43C5E96E -:10043000007100263146BDE8F087C2F12003D840A4 -:100440000CFA02FC21FA03F3914001434FEA1C47E6 -:100450001FFA8CFEB3FBF7F007FB10360B0C43EAD8 -:10046000064300FB0EF69E4204FA02F408D91CEB88 -:10047000030300F1FF382FD29E422DD90238634486 -:100480009B1B89B2B3FBF7F607FB163341EA034126 -:1004900006FB0EF38B4208D91CEB010106F1FF3875 -:1004A00016D28B4214D9023E6144C91A46EA00466C -:1004B00038E72E46284605E70646E3E61846F8E6FE -:1004C0004B45A9D2B9EB020864EB0C0E0138A3E747 -:1004D0004646EAE7204694E74046D1E7D0467BE728 -:1004E000023B614432E7304609E76444023842E7A0 -:1004F000704700BF02E000F000F8FEE772B6374830 -:1005000080F30888364880F3098836483649086001 -:1005100040F20000CCF200004EF63471CEF2000141 -:100520000860BFF34F8FBFF36F8F40F20000C0F23F -:10053000F0004EF68851CEF200010860BFF34F8FF5 -:10054000BFF36F8F4FF00000E1EE100A4EF63C71E2 -:10055000CEF200010860062080F31488BFF36F8F8D -:1005600004F0EAFC04F07CFD4FF055301F491B4AB3 -:1005700091423CBF41F8040BFAE71D49184A9142E9 -:100580003CBF41F8040BFAE71A491B4A1B4B9A423D -:100590003EBF51F8040B42F8040BF8E7002018495D -:1005A000184A91423CBF41F8040BFAE704F0C8FC3A -:1005B00004F09CFD144C154DAC4203DA54F8041BB6 -:1005C0008847F9E700F042F8114C124DAC4203DACB -:1005D00054F8041B8847F9E704F0B0BC000700207A -:1005E000002300200000000808ED00E000010020CA -:1005F0000007002090570008002300208C230020D3 -:1006000090230020C0540020E0010008E40100080D -:10061000E4010008E40100082DE9F04F2DED108AF7 -:10062000C1F80CD0C3689D46BDEC108ABDE8F08FC0 -:10063000002383F311882846A047002004F00CF91A -:10064000FEE704F06FF800DFFEE70000F8B501F008 -:10065000EDF804F013FC074604F064FC0546B8BB53 -:10066000204B9F4234D001339F4234D01E4B27F0A1 -:10067000FF029A4232D1F8B200F010FF2E4642F249 -:10068000107400F011FF08B10024264601F058FC58 -:1006900020B1032000F07CF80024264635B1134B2E -:1006A0009F4203D004F036FC00242646002004F0CC -:1006B000EFFB0EB100F082F801F028FA00F026FFFF -:1006C00001F012F9204600F0D7F800F077F8F9E7CA -:1006D0002E460024D5E704460126D2E706464FF40D -:1006E0007A74CEE7010007B0000008B0263A09B0DE -:1006F00008B501F0C5F8A0F120035842584108BDE3 -:1007000007B541F21203022101A8ADF8043001F04F -:10071000D5F803B05DF804FB38B5302383F31188B6 -:10072000174803680BB104F055F9164A1448002322 -:100730004FF47A7104F044F9002383F31188124CCA -:10074000236813B12368013B2360636813B16368B6 -:10075000013B63600D4D2B7833B963687BB9022090 -:1007600001F062F9322363602B78032B07D16368B1 -:100770002BB9022001F058F94FF47A73636038BD49 -:100780009023002019070008B0240020A82300208F -:10079000084B187003280CD8DFE800F008050208A1 -:1007A000022001F039B9022001F02EB9024B0022DB -:1007B0005A607047A8230020B024002038B501F00B -:1007C000BFFB30B1254B03221A70254B00225A6023 -:1007D00038BD244B244A19680131F9D004339342BF -:1007E000F9D1224C1F4DD4F80428AA42F0D3204B53 -:1007F0009B6803F1006303F5F0439A42E8D204F0EA -:100800005BFB04F06DFB002001F088F80220FFF78D -:10081000BFFF184B9A6D00229A65996F9A67996F7E -:10082000D96DDA65D96FDA67D96F196E1A66D3F8A0 -:100830008010C3F88020D3F8803072B64FF0E023E8 -:100840003021C3F8085DD4F80038D4F8042881F3C7 -:1008500011889D4683F308881047B9E7A823002034 -:10086000B0240020007800082078000800700008FC -:1008700000230020001002402DE9F04F93B0AC4B54 -:1008800000902022FF210AA89D6801F0E9F8A94AFA -:100890001378A3B9A848012103601170302383F3B2 -:1008A000118803680BB104F095F8A44AA24800230C -:1008B0004FF47A7104F084F8002383F31188009BCD -:1008C00013B19F4B009A1A609E4A009C1378032B29 -:1008D0001EBF002313709A4A4FF0000A18BF5360DE -:1008E000D3465646D146012001F096F824B1944BE8 -:1008F0001B68002B00F01582002000F0C1FF039060 -:10090000039B002B01DA00F049FE039B002BEDDB7B -:10091000012001F079F8039B213B162BE3D801A2BB -:1009200052F823F081090008A90900083D0A0008CF -:10093000E7080008E7080008E7080008C70A0008F9 -:10094000970C0008B10B0008130C00083B0C0008C2 -:10095000610C0008E7080008730C0008E7080008AD -:10096000E50C0008210A0008E7080008290D000826 -:100970008D090008210A0008E7080008130C000888 -:100980000220FFF7B5FE002840F0F581009B022110 -:10099000BAF1000F08BF1C4605A841F21233ADF8AA -:1009A000143000F08BFF9EE74FF47A7000F068FF80 -:1009B000071EEBDB0220FFF79BFE0028E6D0013F7D -:1009C000052F00F2DA81DFE807F0030A0D10133675 -:1009D00005230593042105A800F070FF17E0544893 -:1009E0000421F9E758480421F6E758480421F3E7C1 -:1009F0004FF01C08404600F093FF08F104080590F2 -:100A0000042105A800F05AFFB8F12C0FF2D1012003 -:100A100000FA07F747EA0B0B5FFA8BFB4FF0000970 -:100A200001F06AF826B10BF00B030B2B08BF002472 -:100A3000FFF766FE57E746480421CDE7002EA5D014 -:100A40000BF00B030B2BA1D10220FFF751FE074641 -:100A500000289BD0012000F061FF0220FFF798FEE4 -:100A600000261FFA86F8404600F06AFF044690B15F -:100A70000021404600F07CFF01360028F1D1BA4643 -:100A8000044641F21213022105A8ADF814303E4687 -:100A900000F014FF27E70120FFF77AFE2546244BDC -:100AA0009B68AB4207D9284600F03AFF013040F07E -:100AB00067810435F3E7234B00251D70204BBA46B0 -:100AC0005D603E46ACE7002E3FF460AF0BF00B03D9 -:100AD0000B2B7FF45BAF0220FFF75AFE322000F0B1 -:100AE000CFFEB0F10008FFF651AF18F003077FF416 -:100AF0004DAF0F4A926808EB050393423FF646AFAD -:100B0000B8F5807F3FF742AF124B0193B84523DD24 -:100B10004FF47A7000F0B4FE0390039A002AFFF6B7 -:100B200035AF019B039A03F8012B0137EDE700BFB6 -:100B300000230020AC240020902300201907000887 -:100B4000B0240020A8230020042300200823002034 -:100B50000C230020AC230020C820FFF7C9FD074666 -:100B600000283FF413AF1F2D11D8C5F120024245D4 -:100B70000AAB25F0030028BF42468349019218447E -:100B800000F05CFF019A8048FF2100F069FF4FEA06 -:100B9000A8037D490193C8F38702284600F068FF47 -:100BA000064600283FF46DAF019B05EB830537E750 -:100BB0000220FFF79DFD00283FF4E8AE00F0EAFEBA -:100BC00000283FF4E3AE0027B846704B9B68BB4259 -:100BD00018D91F2F11D80A9B01330ED027F0030319 -:100BE00012AA134453F8203C05934046042205A959 -:100BF00001F090F904378046E7E7384600F090FEB0 -:100C00000590F2E7CDF81480042105A800F056FE07 -:100C100006E70023642104A8049300F045FE0028A1 -:100C20007FF4B4AE0220FFF763FD00283FF4AEAEC0 -:100C3000049800F0A5FE0590E6E70023642104A8CF -:100C4000049300F031FE00287FF4A0AE0220FFF7ED -:100C50004FFD00283FF49AAE049800F093FEEAE7B7 -:100C60000220FFF745FD00283FF490AE00F0A2FE01 -:100C7000E1E70220FFF73CFD00283FF487AE05A91D -:100C8000142000F09DFE04210746049004A800F003 -:100C900015FE3946B9E7322000F0F2FD071EFFF6D7 -:100CA00075AEBB077FF472AE384A926807EB090352 -:100CB00093423FF66BAE0220FFF71AFD00283FF487 -:100CC00065AE27F003074F44B9453FF4A9AE484647 -:100CD00000F026FE0421059005A800F0EFFD09F1C3 -:100CE0000409F1E74FF47A70FFF702FD00283FF4A2 -:100CF0004DAE00F04FFE002844D00A9B01330BD0CC -:100D000008220AA9002000F0B3FE00283AD02022D1 -:100D1000FF210AA800F0A4FEFFF7F2FC1C4803F034 -:100D2000A1FD13B0BDE8F08F002E3FF42FAE0BF005 -:100D30000B030B2B7FF42AAE0023642105A8059337 -:100D400000F0B2FD074600287FF420AE0220FFF736 -:100D5000CFFC804600283FF419AEFFF7D1FC41F2EA -:100D6000883003F07FFD059800F0DCFE464600F079 -:100D7000C3FE3C46B7E5064652E64FF0000905E6DD -:100D8000BA467EE637467CE6AC23002000230020EE -:100D9000A0860100094A136849F2690099B21B0C48 -:100DA00000FB01331360064B186844F2506182B2B5 -:100DB000000C01FB0200186080B270471423002071 -:100DC0001023002010B500211022044600F048FE38 -:100DD000034B03CB206061601868A06010BD00BFAA -:100DE0009075FF1F2DE9F041ADF54E7D0DF13408F2 -:100DF0006CAC40F2751207460D460EA80021C8F8EB -:100E0000001000F02DFE4FF4C4720021204600F0C7 -:100E100027FE02F0CFF8254B4FF47A72B0FBF2F0C8 -:100E2000186093E80700022384E807000DF5E970D5 -:100E30002382FFF7C7FF41F204131D49238406A84C -:100E400004F0BEFB182384F832310DF2E3266B4424 -:100E50000DF1300C1A4603CA6245306071601346CA -:100E600006F10806F6D141460122204600F074FE44 -:100E700000230393AB7E029305F11903019380B223 -:100E80000123CDE904800093E97E06A3D3E9002382 -:100E9000384602F04DFC0DF54E7DBDE8F08100BFF7 -:100EA000AFF300809E6AC421818A46EEB8240020F8 -:100EB000D05500082DE9F0412C4C237ADAB0804659 -:100EC0000D465BBB27A9284600F056FF07460028C1 -:100ED00042D19DF89D60C82E3ED801464FF4A662CF -:100EE000204600F0BDFD4FF48073C4F8F8314FF494 -:100EF0000073C4F80C334FF44073C4F82034324606 -:100F00000DF19E0104F1090000F098FD26449DF8C2 -:100F10009C30777223720BB9EB7E23728122002101 -:100F200006AC27A800F09CFD0122214627A800F06E -:100F30005FFF00230393AB7E029305F1190380B298 -:100F400001932823CDE904400093E97E05A3D3E96A -:100F50000023404602F0ECFB5AB0BDE8F08100BF30 -:100F6000AFF3008026417272DF25D7B7B049002069 -:100F7000F0B5254E4FF48A7505FB0065F1B096F883 -:100F8000D83085F8DC300024D822214685F8E840A6 -:100F90003AA800F065FD06F1090000F059FDD5F80A -:100FA000E4308DF8F000C2B206AF06F109010DF190 -:100FB000F100CDE93A3400F041FD394601223AA86A -:100FC00000F042FF80B2CDE9047008230127CDE98B -:100FD000023706F1D803019330230093317A0B488E -:100FE00007A3D3E9002302F0A3FBA04206DD01F032 -:100FF000E1FFC5F8E000384671B0F0BD2046FBE7E0 -:1010000078F6339F93CACD8DB0490020D0340020AC -:101010002DE9F0411D4D1E4E1E4F86B0284602F0B0 -:10102000B3FB034658B30024CDE90344ADF81440A4 -:10103000027B8DF8142099684068029403AA03C2C9 -:101040001B68DFF8548043F00043029301F0B4FFC3 -:10105000821941F10003009402A9384601F08CF98D -:10106000A04205DD284602F093FB88F80040D5E752 -:1010700098F80030072B05D8013388F8003006B007 -:10108000BDE8F081014802F083FBF8E7D03400208E -:1010900040420F0000350020E54E002070B50D469F -:1010A00014461E4602F0A0FA50B9022E10D1012CAF -:1010B0000ED112A3D3E90023C5E90023012007E0E4 -:1010C000282C10D005D8012C09D0052C0FD00020D9 -:1010D00070BD302CFBD10BA3D3E90023ECE70BA3AD -:1010E000D3E90023E8E70BA3D3E90023E4E70BA34C -:1010F000D3E90023E0E700BFAFF30080401DA1204B -:1011000026812A0B78F6339F93CACD8D9E6AC4211F -:10111000818A46EE26417272DF25D7B7F017304A32 -:1011200039059E5638B505460E4C0021013500F0B4 -:101130001FFCA4F82C55B4F82C0500F001FC78B184 -:10114000B4F82C0500F00CFC014648B9B4F82C05A5 -:1011500000F00EFCB4F82C350133A4F82C35EAE786 -:1011600038BD00BFB049002010B50A4B0A4A1A60CA -:1011700003F5805393F848203AB95C6C2CB12046B3 -:1011800000F05CFF204604F0D1F9BDE810400348B0 -:1011900000F054BF003500202856000830450020DC -:1011A0002DE9F04F8FB000AF05460C4602F01CFA57 -:1011B000002849D1237E022B1BD1E38A012B18D1B1 -:1011C00001F0F8FE0646FFF7E5FD03464FF4C87050 -:1011D000DFF8C482B3FBF0F206F5167602FB10339B -:1011E00016FA83F3C8F80030E37E33B9A34B00222C -:1011F0001A703C37BD46BDE8F08F07F12401204648 -:1012000000F078FD0028F4D107F11400FFF7DAFDB3 -:1012100097F8264007F11401224607F1270004F051 -:101220009DF90028E2D10F2C08D8944B1C70D8F8F7 -:101230000030A3F51673C8F80030DAE797F82410E9 -:10124000284602F0C9F9D4E7E38A282B2BD010D81E -:10125000012B23D0052BCCD1BFF34F8F8849894B6D -:10126000CA6802F4E0621343CB60BFF34F8F00BF44 -:10127000FDE7302BBDD1844EE17E327A9142B8D168 -:10128000607E3146002291F8DC50854200F0A58056 -:101290000132042A01F58A71F5D1AAE721462846D0 -:1012A000FFF7A0FDA5E721462846FFF703FEA0E7CC -:1012B000B2F8EC507B6005F103094FEA99094FEA57 -:1012C0008902D11DC908A8EBC1039D46EB46002148 -:1012D000584600F0C5FB04F1EE012A463144584659 -:1012E00000F0ACFB7B6813B9012000F017FB96F807 -:1012F000D20000F025FB044630B9307200F04AFB02 -:10130000204600F00BFBB1E0D6F8D4203AB996F8AD -:10131000D200B6F82C25824201D8FFF703FFD6F899 -:10132000D4202A44944208D296F8D200B6F82C254C -:101330000130824201D8FFF7F5FE70685FFA89F24A -:10134000594600F095FB08B9C54679E0726896F8F1 -:10135000D2002A447260D6F8D42005EB0209C6F800 -:10136000D49000F0EDFA814509D396F8D220D6F852 -:10137000D4000132001B86F8D220C6F8D400FF2D1D -:101380000FD80024347200F005FB204600F0C6FAA6 -:1013900000F0D6FD3D4B188108B9FFF70FFAC5469E -:1013A00027E7BB6896F8D9000AFB0362FB68D2F80E -:1013B000E41082F8E83001F58061C2F8E030C2F84C -:1013C000E410FFF7D5FDFFF723FE96F8D920013290 -:1013D00002F0030286F8D920B6E74FF48A7A0AFBB6 -:1013E00002F505F1EA013144204600F059FDF860AC -:1013F00000287FF4FEAE3544012285F8E82001F094 -:10140000D9FDD5F8E020D6ED007ADFED216A801A0B -:10141000192838BF192040F6B832904228BF10462C -:10142000B8EE677A07EE900AF8EEE77A67EEA67AEA -:10143000DFED186AE7EE267AFCEEE77AC6ED007A71 -:1014400096F8D930BB60BA6873680AFB02F43219A7 -:1014500092F8E81059B1D2F8E4108B42E8463FF414 -:1014600027AF002182F8E810C2F8E010C546736883 -:10147000064A9B0A01331381BBE600BFC934002032 -:1014800000ED00E00400FA05B0490020B824002077 -:10149000CDCCCC3D6666663FCC340020014B187045 -:1014A000704700BFC424002038B54FF00054134BE0 -:1014B00022689A4220D1124B627D12481A70237D15 -:1014C00003724FF48073C0F8F8314FF40073C0F822 -:1014D0000C3300254FF44073C0F820340A49C0F89B -:1014E000E450C922093000F0A9FAE022294620463A -:1014F00000F0B6FA012038BD0020FCE79AAD44C5E3 -:10150000C4240020B04900201600002037B500F0A8 -:1015100017FD194D1949288102236B7100220123FF -:10152000174801F051F900230193164B1649009317 -:101530001648174B4FF4805202F026F8154B1978D5 -:1015400011B1124802F048F801F034FD0446FFF7EB -:1015500021FC4FF4C873B0FBF3F202FB130304F554 -:10156000167010FA83F00C4B186003F0DBFC08B126 -:101570000F232B8103B030BDB824002040420F0060 -:10158000003500209D100008C8240020D034002021 -:10159000A1110008C4240020CC3400202DE9F04F14 -:1015A0002DED028B90A7D7E900670FF24429D9E906 -:1015B0000089884C95B00DAD9FED848BFFF728FD19 -:1015C000DFF834B200230C93ADF83C300D936B6020 -:1015D00000230DF125028DED008B4FF0010A09A9C2 -:1015E00058468DF825308DF824A001F04BFC9DF86D -:1015F00024200023002A40F0AF80204601F0F4FFB1 -:101600000546002847D1DFF8F4B101F0D3FCDBF840 -:10161000003098423FD301F0CDFC0790FFF7BAFBB2 -:10162000079A4FF4C873B0FBF3F101FB130302F503 -:10163000167010FA83F0CBF80000DFF8C4B19BF805 -:1016400000100791002914BF2B46534610A88DF8AF -:101650003030FFF7B7FB0799C1F11002D2B2062A6A -:1016600010AB28BF062219440DF13100079200F09B -:10167000E5F9079A0CAB0393182302930132564BFA -:10168000D2B2CDE900A304923B463246204601F097 -:10169000F1FF8BF8005001F08DFC504A504D13685B -:1016A000C31AB3F57A7F32D3106001F085FC02468D -:1016B0000B46204602F076F8204601F095FF30B345 -:1016C0002B7ADFF840A1002B14BF032302238AF8F2 -:1016D000053001F06FFC0DF1400B4FF47A730122DD -:1016E000B0FBF3F05946CAF80000504600F0DAFAB1 -:1016F000182302933B4B019380B240F25513CDE97E -:1017000003B0009342464B46204601F0B3FF2B7ACC -:10171000B3B101F04FFC4FF0000A83464FF48A72D8 -:1017200095F8D900504400F0030002FB005393F8F1 -:10173000E810002934D00AF1010ABAF1040FEFD100 -:10174000C82003F08FF82B7A002B7FF434AF15B04C -:10175000BDEC028BBDE8F08F4FF0904110A84A69B4 -:1017600082F010024A611946102200F079F90DF159 -:1017700026030AAA0CA9584600F0F0FE95E80300DB -:1017800011AB83E803009DF83C308DF84C300C9B86 -:10179000109310A9DDE90A23204602F0D7F917E7D4 -:1017A000D3F8E01049B12B68FA2B38BFFA23ABEB22 -:1017B00001010533B1EB430FBDD3FFF7D9FB4FF464 -:1017C0008A720028B7D1BBE7AFF3008000000000A9 -:1017D00000000000D0340020C8340020E04E00207B -:1017E000B0490020E44E0020401DA12026812A0B94 -:1017F000F1C6A7C1D068080F00350020CC34002006 -:10180000C9340020B824002008B5054800F04AFF7C -:10181000BDE80840034A0449002003F081BE00BF30 -:1018200000350020384F0020691100087047000083 -:1018300070B5104B1B780133DBB2012B0C4612D86C -:101840000D4B1D6829684FF47A730E6AA2FB0332B0 -:10185000014622462846B047844204D1074B002265 -:101860001A70012070BD4FF4FA7002F0FBFF0020E7 -:10187000F8E700BF182300201C2300202C4F002075 -:1018800007B50023024601210DF107008DF807304E -:10189000FFF7CEFF20B19DF8070003B05DF804FB11 -:1018A0004FF0FF30F9E700000A4608B50421FFF7C2 -:1018B000BFFF80F00100C0B2404208BD30B4074B0A -:1018C0000A461978064B53F821402368DD69054B19 -:1018D0000146AC46204630BC604700BF2C4F00207C -:1018E0001C230020A086010070B503F063F9094EA7 -:1018F000094D3080002428683388834208D903F0DA -:1019000055F92B6804440133B4F5F04F2B60F2D342 -:1019100070BD00BF2E4F0020E84E002003F0FCB940 -:1019200000F1006000F5E040D0F8000870470000CA -:1019300000F10060920000F5F04003F077B900007C -:10194000054B1A68054B1B889B1A834202D9104429 -:1019500003F02CB900207047E84E00202E4F0020E5 -:10196000024B1B68184403F027B900BFE84E002063 -:10197000024B1B68184403F031B900BFE84E002049 -:101980000020704700F10050A0F51040D0F89005FD -:1019900070470000064991F8243033B10023086AEB -:1019A00081F824300822FFF7C3BF0120704700BF31 -:1019B000EC4E0020014B1868704700BF002004E087 -:1019C00030B50F4B0F4C1B682288C3F30B03013853 -:1019D000934208440BD164680A46013C8242134694 -:1019E0000BD214F9015F2DB102F8015BF6E78142D9 -:1019F0000B4602D22C2203F8012B581A30BD00BF2F -:101A0000002004E020230020022802BF4FF0904372 -:101A100010229A6170470000022802BF4FF09043E5 -:101A20004FF480129A617047022801BF4FF0904234 -:101A3000536983F0100353617047000010B5002311 -:101A4000934203D0CC5CC4540133F9E710BD0000CD -:101A500003460246D01A12F9011B0029FAD1704739 -:101A600002440346934202D003F8011BFAE7704791 -:101A70002DE9F8431F4D144695F824200746884663 -:101A800052BBDFF870909CB395F824302BB920221C -:101A9000FF2148462F62FFF7E3FF95F82400C0F1CD -:101AA0000802A24228BF2246D6B24146920005EB68 -:101AB0008000FFF7C3FF95F82430A41B1E44F6B244 -:101AC000082E17449044E4B285F82460DBD1FFF778 -:101AD00061FF0028D7D108E02B6A03EB8203834221 -:101AE000CFD0FFF757FF0028CBD10020BDE8F88307 -:101AF0000120FBE7EC4E0020024B1A78024B1A70D3 -:101B0000704700BF2C4F00201823002003494FF4DA -:101B1000E1330B60024B186802F06ABD144F0020DD -:101B20001C230020094B10B518220446002118463A -:101B3000FFF796FF064A074B127804600146BDE89E -:101B4000104053F8220002F053BD00BF144F002094 -:101B50002C4F00201C2300202DE9F0470D460446A1 -:101B600000219046284640F27912FFF779FF23467C -:101B700020220021284601F08BFF231D0222202174 -:101B8000284601F085FF631D03222221284601F02B -:101B90007FFFA31D03222521284601F079FF04F1D0 -:101BA000080310222821284601F072FF04F11003D7 -:101BB00008223821284601F06BFF04F111030822A6 -:101BC0004021284601F064FF04F112030822482155 -:101BD000284601F05DFF04F114032022502128461D -:101BE00001F056FF04F1180340227021284601F04D -:101BF0004FFF04F120030822B021284601F048FFDE -:101C000004F121030822B821284601F041FF04F124 -:101C10002207C0263B46314608222846083601F0F6 -:101C200037FFB6F5A07F07F10107F3D104F13203C6 -:101C300008223146284601F02BFF002704F1330A21 -:101C400094F832304FEAC7099F4209F5A47615D3BC -:101C5000B8F1000F08D1314604F5997307222846E0 -:101C600001F016FF09F24F16274694F832213B1B6C -:101C700093420CD3F01DC008BDE8F0870AEB0703C0 -:101C800008223146284601F003FF0137D8E707F262 -:101C9000331331460822284601F0FAFE0836013790 -:101CA000E3E7000013B5044608460021016023461F -:101CB000C0F803102022019001F0EAFE0198231DD4 -:101CC0000222202101F0E4FE0198631D032222215B -:101CD00001F0DEFE0198A31D0322252101F0D8FEAC -:101CE000019804F108031022282101F0D1FE0720F9 -:101CF00002B010BDF7B50023047F00910E46072205 -:101D00001946054601F088FD731C0093012200234B -:101D10000721284601F080FDC4B9B31C00930522B9 -:101D200023460821284601F077FD0D243746B27876 -:101D3000BB1B934211D32B7FA88A0734E408BBB99D -:101D4000844294BF0020012003B0F0BDAB8ADB00C9 -:101D5000083BDB08B3700824E8E7FB1C009321462E -:101D600000230822284601F057FD08340137DEE73A -:101D7000201A18BF0120E7E7F7B50023047F009180 -:101D80000E4608221946054601F046FD731CC4B9EB -:101D90000822009311462346284601F03DFD1024F9 -:101DA000012372785F1C013B934211D32B7FA88AD9 -:101DB0000734E408BBB9844294BF0020012003B07B -:101DC000F0BDAB8ADB00083BDB0873700824E7E753 -:101DD000F3190093214600230822284601F01CFD38 -:101DE00008343B46DDE7201A18BF0120E7E7000072 -:101DF000F8B50E4605461446002181223046FFF70D -:101E00002FFE2B4608220021304601F041FE7CB90E -:101E10006B1C07220821304601F03AFE0F240123F3 -:101E20006A785F1C013B934204D3E01DC008F8BDF3 -:101E30000824F4E7EB1921460822304601F028FE79 -:101E400008343B46ECE70000F8B50E46054614465C -:101E50000021CE223046FFF703FE2B462822002128 -:101E6000304601F015FE7CB905F10803082228214F -:101E7000304601F00DFE30242F462A7A7B1B934218 -:101E800004D3E01DC008F8BD2824F5E707F10903D5 -:101E900021460822304601F0FBFD08340137ECE70B -:101EA000F7B5047F00910E4601231022002105465C -:101EB00001F0B2FCC4B9B31C0093092223461021DF -:101EC000284601F0A9FC192437467288BB1B9A42A8 -:101ED00011D82B7FA88A0734E408BBB9844294BF89 -:101EE0000020012003B0F0BDAB8ADB00103BDB0813 -:101EF00073801024E8E73B1D00932146002308224D -:101F0000284601F089FC08340137DEE7201A18BFA3 -:101F10000120E7E730B5094D0A4491420DD011F890 -:101F2000013B5840082340F30004013B2C4013F0D0 -:101F3000FF0384EA5000F6D1EFE730BD2083B8ED0F -:101F4000F7B5384A106851686B4603C36A4636498C -:101F50003648082303F012FB0446002833D10A2533 -:101F6000334A106851686B4603C36A4631492F48AB -:101F7000082303F003FB0446002849D00369B3F5A6 -:101F8000623F45D8B0F8661040F2114291423FD10D -:101F9000294A024402F15C018B4239D35C3B23495C -:101FA00000209E1AFFF7B6FF3246074604F164018F -:101FB0000020FFF7AFFFA3689F4229D1E368984252 -:101FC00008BF002524E00369B3F5623F27D8418BA1 -:101FD00040F21142914220D1174A024402F110010D -:101FE0008B4218D3103B114900209D1AFFF792FF36 -:101FF0002A46064604F118010020FFF78BFFA3686C -:102000009E4202D1E368984201D00D25A8E7002541 -:10201000284603B0F0BD1025A2E70C25A0E70B254C -:102020009EE700BFF8550008DC8703000078000831 -:1020300001560008908703000888FFF710B5037C5D -:10204000044613B9006803F081FA204610BD000071 -:102050000023BFF35B8FC360BFF35B8FBFF35B8F66 -:102060008360BFF35B8F7047BFF35B8F0068BFF384 -:102070005B8F704770B505460C30FFF7F5FF05F133 -:10208000080604463046FFF7EFFFA04206D9304667 -:102090006D68FFF7E9FF2544281A70BD3046FFF749 -:1020A000E3FF201AF9E7000070B50546406898B1D3 -:1020B00005F10800FFF7D8FF05F10C06044630468D -:1020C000FFF7D2FF8442304694BF6D680025FFF7CA -:1020D000CBFF013C2C44201A70BD000038B50C46E3 -:1020E0000546FFF7C7FFA04210D305F10800FFF730 -:1020F000BBFF04446868B4FBF0F100FB1144BFF37C -:102100005B8F0120AC60BFF35B8F38BD0020FCE724 -:102110002DE9F041144607460D46FFF7C5FF8442FE -:1021200028BF0446D4B1B84658F80C6B4046FFF7B8 -:102130009BFF3044286040467E68FFF795FF331AC6 -:102140009C4203D86C600120BDE8F0816B60A41B49 -:102150003B68AB602044E8600220F5E72046F3E7E7 -:1021600038B50C460546FFF79FFFA04210D305F196 -:102170000C00FFF779FF04446868B4FBF0F100FB42 -:102180001144BFF35B8F0120EC60BFF35B8F38BD60 -:102190000020FCE72DE9FF41884669460746FFF726 -:1021A000B7FF6C4606B204EBC6060025B44209D060 -:1021B0006268206808EB0501FFF740FC636808349B -:1021C0001D44F3E729463846FFF7CAFF284604B006 -:1021D000BDE8F081F8B505460C300F46FFF744FF27 -:1021E00005F1080604463046FFF73EFFA0423046A0 -:1021F00088BF6C68FFF738FF201A386020B130467E -:102200002C68FFF731FF2044F8BD000073B5144679 -:1022100006460D46FFF72EFF844228BF0446019074 -:10222000DCB101A93046FFF7D5FF019B33B9326815 -:10223000C5E90233C5E9002401200CE09C4238BF07 -:1022400001942860019868608442F5D93368AB60D6 -:10225000241AEC60022002B070BD2046FBE70000AB -:102260002DE9FF410F466946FFF7D0FF6C4600B2EB -:1022700004EBC0050026AC4209D0D4F8048054F821 -:10228000081BB8194246FFF7D9FB4644F3E730462E -:1022900004B0BDE8F081000038B50546FFF7E0FF67 -:1022A000044601462846FFF719FF204638BD0000C6 -:1022B000302383F3118862B670470000002383F354 -:1022C000118862B670470000012070477047000017 -:1022D00010B41346026814680022A4465DF8044B4B -:1022E0006047000000F5805090F8590470470000E6 -:1022F00000F5805090F852047047000000F58050BF -:1023000090F95804704700005020704700F5805243 -:1023100008B5FFF7CDFFD2F89834D2F894041844EA -:10232000D2F890341844D2F878341844D2F888346B -:102330001844D2F884341844FFF7C0FF08BD0000E9 -:1023400038B5C26A936923F001039361044600F033 -:1023500031FE0546E36A9B69DB0706D500F02AFEDD -:10236000431BFA2BF6D9002004E004F58054012029 -:1023700084F8520438BD00002DE9F04F0C4600F5FA -:10238000805185B01F4691F85234BDF8389005460B -:1023900090469BB1D1F874340133C1F8743423688A -:1023A0009A0006D4237B082B0BD9627B0AB10F2B32 -:1023B00007D9D1F878340133C1F878344FF0FF30C1 -:1023C0000FE0FFF775FFEB6AD3F8C42012F4001A90 -:1023D0000AD0D1F87C340133C1F87C34FFF76EFFAA -:1023E000002005B0BDE8F08FD3F8C46022686B6AA6 -:1023F000C6F301464FF0480B002A1BFB063BB4BF57 -:1024000042F080429204CBF8002023685B0044BF76 -:1024100042F00052CBF80020227B330643EA02430D -:10242000CBF80430607B720118B343F44013CBF84F -:102430000430D1F8A4340133C1F8A434AB1803F547 -:102440008353197B41F020011973207B039200F024 -:102450000DFE039A033080105FFA8AF383420AF17B -:10246000010A0DDA04EB83010BEB830349689960E1 -:10247000F2E7AB1803F58353197B60F34511E3E7EB -:10248000EB6A0121B140C3F8CC10AB1803F58253BD -:10249000C3E9048705EB461303F58253214618333D -:1024A00004F10C0051F804CB43F804CB8142F9D17C -:1024B000098819802A4441F268032846D65002F55B -:1024C000805209F0030392F86C1043F0100321F0DE -:1024D0001F010B4382F86C30FFF7F0FE4246CDF847 -:1024E00000903B46214600F087FD012079E700007F -:1024F00013B500F580540191606CFFF7D5FD1F28DE -:102500000AD90199606C2022FFF744FEA0F1200354 -:102510005842584102B010BD0020FBE708B500F555 -:102520008050FFF7C5FE406CFFF792FDBDE8084004 -:10253000FFF7C4BE00220260828142608260704761 -:1025400010B500220023C0E90023002304460381C4 -:102550000C30FFF7EFFF204610BD00002DE9F047DB -:10256000074688B007F5805468469A468846FFF7C4 -:102570009FFE9146FFF7E4FF606CFFF77BFD1F288D -:102580002CD9606C20226946FFF786FE202825D1D1 -:1025900094F8523413B303AD444605AB2E4603CE34 -:1025A0009E4220606160354604F10804F6D130682F -:1025B0002060B388A380DDE90023C9E90023BDF8CA -:1025C0000830AAF80030FFF779FE4A4653464146E4 -:1025D000384608B0BDE8F04700F0FCBCFFF76EFEDF -:1025E000002008B0BDE8F0872DE9F84F002306462B -:1025F000C0E90133284B46F8303B00F581540546CD -:1026000088463746103438462037FFF799FFA742EF -:10261000F9D105F580544FF4805326630026C4E9B0 -:102620000D366764012305F5835705F5A359E66365 -:1026300084F8403084F84830103709F110094FF021 -:10264000000A4FF0000B47E908ABA7F11800FFF7AD -:1026500071FF203747F8286C4F45F4D184F858842F -:10266000A4F85A64A4F85C64A4F85E6484F8606416 -:10267000A4F86264A4F86464A4F8666484F86864E6 -:10268000B8F1000F02D0054800F08EFC044BEB625D -:102690002846BDE8F88F00BF285600080C560008F1 -:1026A0000064004010B5044B197804464A1C1A70A7 -:1026B000FFF79AFF204610BD354F00202DE9F0436B -:1026C00000295FD03048314BB3FBF1F381428CBF1E -:1026D0000A201120451EB3FBF0F700FB1730ECB2C7 -:1026E00020B1022D2846F5D8002037E07D1EB5F533 -:1026F000806F33D2C4EBC40808F103034FEAE30E42 -:10270000C3F3C703A4EB030C0EF101094FF47A7075 -:102710005FFA8CF60EFB000E59FA8CFCBEFBFCFC3B -:10272000BCF5617F1CDC1FFA8CF4581C56FA80F053 -:1027300047431648B0FBF7F7B942D5D1013BDBB2AE -:102740000F2BD1D8711EC9B207294FF0000005D850 -:10275000107114805580537191710120BDE8F08390 -:1027600008F1FF334FEAE30CC3F3C703E41A0CF19B -:10277000010EE6B20CFB00005EFA84F4B0FBF4F448 -:10278000A4B2D2E70846E9E73F420F0000127A0000 -:102790000B4B10B54FF45472044600211846FFF756 -:1027A0005FF9084BA3614033E361D8332362F03310 -:1027B0006362E36A60610022C3F8C02010BD00BFFD -:1027C00000A4004070A400402DE9F04F00F58055B2 -:1027D000994695F85834012B89B004468A469046AC -:1027E00004D90027384609B0BDE8F08F8D4A52F869 -:1027F000231009B942F823008B49C4F80CA00B78C8 -:1028000084F8109093B9FFF753FD884B9A6D42F00E -:1028100000729A659A6B42F000729A639A6B22F08A -:1028200000729A6301230B70FFF748FD95F851344D -:1028300073B903211520FFF73BFD01F023FD0321B0 -:10284000162001F01FFD012385F85134FFF736FDF6 -:10285000FFF72EFDE26A936923F01003936100F005 -:10286000A9FB0746E36A9E6916F0080607D000F048 -:10287000A1FBC31BFA2BF5D9FFF720FDB1E79A693D -:1028800042F001029A6100F095FB0746E36A9A69FB -:10289000D00705D400F08EFBC31BFA2BF6D9EBE76B -:1028A0009A6942F002029A61E36A00275F65FFF7C6 -:1028B00005FD686CFFF7CCFB04F5825B0BF1100B98 -:1028C000202200216846FFF7CBF802A8FFF732FE6E -:1028D00006976A460BEB06030DF1180E9446BCE80A -:1028E0000300F44518605960624603F10803F5D10E -:1028F000DCF80000186020369CF804201A71B6F548 -:10290000806FDDD1002304F5A25285F8503485F89C -:1029100053341A3251462046FFF7D0FE074690B98D -:10292000E26A936923F00103936100F043FB0546DB -:10293000E36A9B69D9077FF554AF00F03BFB431B6B -:10294000FA2BF5D94DE795F85F6495F85E24C5F844 -:102950006CA4360246EA426695F86024E36A1643A0 -:10296000B5F85C2446EA0246DE61B8F1000F29D0D2 -:1029700004F5A352023241462046FFF79FFE90B96C -:10298000E26A936923F00103936100F013FB0546AB -:10299000E36A9B69DA077FF524AF00F00BFB431B6A -:1029A000FA2BF5D91DE795F8683495F86714C5F842 -:1029B00070841B0143EA0123B5F86414E26A43EA18 -:1029C0000143D3602046FFF7E3FE002385F8593426 -:1029D000E36A6FF040421A65E36A154A5A65E36A92 -:1029E00044229A65E36A0722C3F8DC20E36A0322E3 -:1029F0009145DA653FF4F6AEE26A936923F001038C -:102A0000936100F0D7FA0646E36A9B69DB0705D5B8 -:102A100000F0D0FA831BFA2BF6D9E2E6012385F801 -:102A20005234DFE6304F0020344F002000100240C7 -:102A30009B0008002DE9F04F054689B09046994665 -:102A4000002741F2680A00F58056EB6AD3F8D430CB -:102A5000FB40D8074AD505EB471252444FEA471BC3 -:102A60001379190742D4D6F880340133C6F880347C -:102A700013799A0648BFD6F8A83405EB0B0248BF75 -:102A80000133524448BFC6F8A834137943F0080311 -:102A90001371DB0722D596F85334FBB105F5825448 -:102AA000183468465C44FFF74BFD03AB04F1080C97 -:102AB000206861681A4603C2083464451346F7D19A -:102AC00020681060A2889A800123ADF808302B6836 -:102AD000CDE90089DB6B694628469847D6F854341F -:102AE00023B1D6F89C340133C6F89C340137202F2B -:102AF000ABD109B0BDE8F08F2DE9F04F8DB00446A1 -:102B00000F4600F059FA82468946002F56D1E36AF3 -:102B1000D3F89020920141BF04F58051D1F894245C -:102B20000132C1F89424D3F89020160703D1002075 -:102B30000DB0BDE8F08FD3F89050E669C5F30125DC -:102B4000482303FB0566E8464046FFF7F3FC32687E -:102B500051004ABF22F06043C2F38A4343F000436E -:102B6000920048BF43F080430093736813F400134E -:102B70001FBF04F5805201238DF80D30D2F8AC341C -:102B80000EBF8DF80D300133C2F8AC34F38803F07A -:102B90000F038DF80C304FF0000B9DF80C0000F087 -:102BA00065FA5FFA8BF3984220D9F2180CA90B440E -:102BB000127A03F82C2C0BF1010BEEE7012FB6D1A2 -:102BC000E36AD3F89820950141BF04F58051D1F80C -:102BD00094240132C1F89424D3F898201007A6D089 -:102BE000D3F89850266AC5F30125A9E7EFB9E36A3F -:102BF000C3F8945004A8FFF7A3FC98E80F0007ADB2 -:102C000007C52B800023ADF8183023682046CDE996 -:102C100004A9DB6B04A9984704F5805458B1D4F893 -:102C20008C340133C4F88C3482E7012F04BFE36A8B -:102C3000C3F89C50DEE7D4F890340133C4F89034E4 -:102C4000012075E7F8B505460F4600F580540126CA -:102C500039462846FFF750FF10B184F85364F7E770 -:102C6000D4F8543423B1D4F89C340133C4F89C34E0 -:102C7000F8BD0000F0B5C36A1A6C12F47F0F2BD0B8 -:102C800000F580541B6CC4F8A03441F268050023A1 -:102C900047194FF0010C00EB43122A445E011179F1 -:102CA00011F0020F15D0490713D4B959C66AD6F8E6 -:102CB000C8E00CFA01F111EA0E0F0AD0C6F8D010E4 -:102CC000117941F004011171D4F888240132C4F85B -:102CD00088240133202BDED1F0BD000010B5254C37 -:102CE000254B226802B338B31A6D12060ED5802226 -:102CF0001A6500F061F950EA01020B4602D0013872 -:102D000061F1000302462068FFF794FE1A4A136D32 -:102D10001B032AD523684FF4002103F58053116566 -:102D2000012283F8592420E001221A6508221A653D -:102D30004FF480621A6510BD196DC80702D4196D71 -:102D4000890705D50321196510460021FFF77AFF91 -:102D5000094B1A6D100702D41A6DD10605D5182239 -:102D60001A6520680121FFF76DFF2068BDE810405B -:102D7000FFF780BF304F00200064004008B5FFF728 -:102D800097FAFFF777FFBDE80840FFF797BA000012 -:102D9000C36AD3F8C40080F40010C0F340507047F9 -:102DA00000F5805008B5FFF783FA406CFFF762F931 -:102DB000FFF784FA43090CBF0120002008BD000082 -:102DC00000F5805393F8592462B1C16A8A6922F0F0 -:102DD00001028A61D3F898240132C3F898240022B2 -:102DE00083F85924704700002DE9F74300F582511C -:102DF00098461031FFF75CFA002541F2680E4FF05B -:102E0000010900F5805C00EB4514744423795E07EA -:102E10001CD4DB061AD5C36A8E69D3F8C87009FAC8 -:102E200006F63E4212D04F6801970F689742019F05 -:102E300077EB08070AD2C3F8D060237943F0040384 -:102E40002371DCF884340133CCF884340135202D2F -:102E500001F12001D7D103B0BDE8F043FFF72EBA4E -:102E6000F8B51E46002313700F4605461446FFF7BB -:102E700097FF80F0010038701EB12846FFF788FFE9 -:102E80002070F8BD2DE9F04F85B09946DDE90EA31D -:102E90000D4602931378019391F800B080461646D0 -:102EA00000F08AF82B7804460F4613B93378002BCC -:102EB00042D022463B464046FFF796FFFFF75EFFB3 -:102EC000FFF77EFF4B4632462946FFF7C9FF2B78B6 -:102ED00033B1BBF1000F03D0012005B0BDE8F08F86 -:102EE000337813B1019B002BF6D108F5805303937F -:102EF000029B544577EB03031ED2039BD3F8540483 -:102F0000D0B10368AAEB0401DB6889B298474B464D -:102F1000324629464046FFF7A3FF2B7813B1BBF199 -:102F2000000FD9D1337813B1019B002BD4D100F01D -:102F300043F804460F46DBE70020CEE708B5002043 -:102F4000FFF7CCFEBDE8084001F050B808B50120FD -:102F5000FFF7C4FEBDE8084001F048B800B59BB0DB -:102F6000EFF3098168226846FEF768FDEFF30583F9 -:102F7000014B9B6BFEE700BF00ED00E008B5FFF7DB -:102F8000EDFF000000B59BB0EFF3098168226846B1 -:102F9000FEF754FDEFF30583014B5B6BFEE700BFCB -:102FA00000ED00E0FEE700000FB408B5029801F064 -:102FB000EFFBFEE701F0FEBE01F0D6BE13B56C4696 -:102FC00084E80600031D94E8030083E8050001205F -:102FD00002B010BD73B58568019155B11B885B07C0 -:102FE00007D4D0E900369B6B9847019AC1B23046AE -:102FF000A847012002B070BDF0B5866889B00546CB -:103000000C465EB1BDF838305B070AD4D0E9003712 -:103010009B6B98472246C1B23846B047012009B0A1 -:10302000F0BD00220023CDE900230023ADF80830D5 -:103030000A4603AB01F10806106851681C4603C438 -:103040000832B2422346F7D1106820609288A280ED -:10305000FFF7B2FF0423ADF808302B68CDE900017B -:10306000DB6B694628469847D8E70000082817D93F -:1030700009280CD00A280CD00B280CD00C280CD016 -:103080000D280CD00E2814BF4020302070470C2093 -:103090007047102070471420704718207047202078 -:1030A000704700002DE9F041456A15B94162BDE85D -:1030B000F0814B6823F06047C3F38A464FEAD37E22 -:1030C000C3F3807816EA230638BF3E46AC462B464B -:1030D0005A68BEEBD27F22F060440AD0002A18DA88 -:1030E000A40CB44217D19D420FD10D60DEE7134608 -:1030F000EEE7A74207D102F08044C2F38072424556 -:103100000BD054B1EFE708D2EDE7CCF800100B601C -:10311000CDE7B44201D0B442E5D81A689C46002AF3 -:10312000E5D11960C3E700002DE9F047089D01F0E3 -:1031300007044FEAD508224405F0070500EBD1004B -:103140004FF47F49944201D1BDE8F08704F00707AE -:1031500005F0070A57453E4638BF5646C6F10806F1 -:10316000111B8E4228BF0E46E10808EBD50E415CCC -:1031700013F80EC0B94029FA06F721FA0AF1FFB296 -:103180008CEA010147FA0AF739408CEA010C03F88E -:103190000EC034443544D5E780EA0120082341F2CB -:1031A000210201B24000002980B203F1FF33B8BF11 -:1031B000504013F0FF03F4D17047000038B50C46BF -:1031C0008D18A54200D138BD14F8011BFFF7E4FFAC -:1031D000F7E7000042684AB1136843604389818978 -:1031E00001339BB29942438138BF838110467047B7 -:1031F00070B588B0202204460D4668460021FEF7CF -:103200002FFC20460495FFF7E5FF024658B16B46B8 -:10321000054608AE1C4603CCB442286069602346CC -:1032200005F10805F6D1104608B070BD082817D979 -:1032300009280CD00A280CD00B280CD00C280CD054 -:103240000D280CD00E2814BF4020302070470C20D1 -:1032500070471020704714207047182070472020B6 -:1032600070470000082817D90C280CD910280CD951 -:1032700014280CD918280CD920280CD930288CBF38 -:103280000F200E207047092070470A2070470B203E -:1032900070470C2070470D20704700002DE9F8435F -:1032A000078C072F04461ED9D0E9029800254FF657 -:1032B000FF73C5F12006A5F1200029FA05F108FAEF -:1032C00006F628FA00F031430143C9B21846FFF769 -:1032D00063FF0835402D0346EBD1E1693A46BDE86E -:1032E000F843FFF76BBF4FF6FF70BDE8F8830000AF -:1032F00010B54B6823B9CA8A63F30902CA8210BDAC -:1033000004691A681C600361C38A013BC3824A6076 -:10331000EFE700002DE9F84F1D46CB8A0F46C3F3B7 -:1033200009010529814692460B4630D00020AAB2F9 -:1033300007F11A049EB2042E1FFA80F80FD89045A8 -:1033400003F1010306D3FB8A0A4462F30903FB82FB -:1033500001201AE01AF80060E6540130EAE79045CF -:10336000F1D2A1F1050B1C237C68BBFBF3F203FB3C -:1033700012BB1FFA8BF6002C45D14846FFF72AFFF7 -:10338000044638B978606FF00200BDE8F88F4FF05E -:103390000008E6E7002606607860ADB24FF0000B4B -:1033A000454510D90AEB0803221D13F8011B91555E -:1033B000B1B208F101081B291FFA88F82BD0454546 -:1033C00006F10106F1D8FB8AC3F30902154465F33F -:1033D0000903BCE7013292B21C462368002BF9D1E5 -:1033E0006B1F0B441C21B3FBF1F301339BB29A42D8 -:1033F000D3D2BBF1000FD0D14846FFF7EBFE20B986 -:10340000C4F800B0BFE70122E7E7C0F800B05E46AD -:1034100020600446C1E74545D5D94846FFF7DAFEA6 -:1034200008B92060AFE7C0F800B00026206004466D -:10343000B6E700002DE9F04F2DED028B1C4683B05E -:103440005B69019207468846002B00F09A80238C26 -:103450002BB1E269002A00F09480072B35D807F1E0 -:103460000C00FFF7B7FE054638B96FF00205284695 -:1034700003B0BDEC028BBDE8F08F14220021FEF7F3 -:10348000EFFA228CE16905F10800FEF7D7FA208CEB -:10349000013080B2FFF7E6FEFFF7C8FE013880B2C8 -:1034A0002084013028746369228C1B782A4403F03D -:1034B0001F0363F03F0348F0004113723846696010 -:1034C0002946FFF7EFFD0125D1E700F10C034FF08E -:1034D000000908EE103A4FF0800A4E464D4618EEAD -:1034E000100AFFF777FE83460028BED01422002181 -:1034F000FEF7B6FA002E3AD1019BABF80830022253 -:103500000BF1080E1FFA82FC0CF10100BCF1060F52 -:10351000218C80B201D88E422BD3FFF7A3FEFFF798 -:1035200085FE62691278013802F01F028E4208BFE0 -:103530004FF0400A42EA49121BFA80F14AEA020AB5 -:10354000013048F0004281F808A08BF81000CBF859 -:10355000042059463846FFF7A5FD238C0135B342B8 -:103560002DB289F001094FF0000AB8D17FE700229F -:10357000C6E7E169895D0EF802100136B6B2013284 -:10358000C0E76FF0010572E7F8B515460E46302228 -:10359000002104461F46FEF763FA069B6360B5F5FB -:1035A000001F079BA76034BF6A094FF6FF72A36232 -:1035B00097B2E66104F1100000239A4206D8002376 -:1035C0000360A782E3822383E360F8BD06600133D2 -:1035D00030462036F1E7000003781BB94BB2002BD0 -:1035E000C8BF01707047000000787047F8B50C46FE -:1035F000C969074611B9238C002B37D1257E1F2DB1 -:1036000034D8387828BB228C072A2CD8268A36F062 -:1036100003032BD14FF6FF70FFF7D0FD20F0010020 -:103620003102400441EA0561400C41EA40254FF671 -:10363000FF72234629463846FFF7FCFE002807DDC7 -:10364000626913780133DBB21F2B88BF002313702C -:10365000F8BD218A2D0645EA012505432046FFF7DE -:103660001DFE0246E5E76FF00300F1E76FF0010091 -:10367000EEE7000070B58AB0044616460021282205 -:1036800068461D46FEF7ECF9BDF83830ADF810304D -:103690000F9B05939DF840308DF81830119B0793D0 -:1036A0006946BDF84830ADF820302046CDE90265C6 -:1036B000FFF79CFF0AB070BD2DE9F041D3690546C4 -:1036C0000C4616460BB9138C5BBB377E1F2F28D8D0 -:1036D00095F80080B8F1000F26D03046FFF7DEFDE8 -:1036E0003378210241EAC33141EA0801338A41EAD1 -:1036F000076141EA03410246334641F08001284612 -:10370000FFF798FE00280ADD3378012B07D1726994 -:1037100013780133DBB21F2B88BF00231370BDE881 -:10372000F0816FF00100FAE76FF00300F7E70000A7 -:10373000F0B58BB004460D46174600212822684696 -:103740001E46FEF78DF99DF84C305A1E53425341E8 -:103750008DF800309DF84030ADF81030119B059386 -:103760009DF848308DF81830149B07936A46BDF8D1 -:103770005430ADF8203029462046CDE90276FFF7D7 -:103780009BFF0BB0F0BD0000406A00B104307047F1 -:10379000436A1A68426202691A600361C38A013B84 -:1037A000C38270472DE9F041D0F82080194E1446AD -:1037B0001D464146002709B9BDE8F081D1E9022341 -:1037C000A21A65EB0303964277EB03031ED2036A4A -:1037D0008B420DD1FFF78CFD036A1B6803620369FE -:1037E0000B60C38A0161016A013BC3828846E2E73C -:1037F000FFF77EFD0B68C8F8003003690B60C38AD1 -:103800000161013BC382D8F80010D4E788460968FB -:10381000D1E700BF80841E002DE9F04F8BB00D462C -:10382000DDF8509014469B468046002800F0198130 -:10383000B9F1000F00F01581531E3F2B00F21181EA -:10384000012A03D1BBF1000F40F00B810023CDE929 -:103850000833B8F81430B5EBC30F4FEAC30703D3EE -:1038600000200BB0BDE8F08F2B199F42D8F80C3028 -:103870003ABF7F1BFFB227461BB9D8F81030002B88 -:103880007AD0272D4ED8C5F12806B7424FF0000355 -:103890002CBFF6B23E4600932946D8F8080008AB84 -:1038A0003246FFF741FCA7EB060A35445FFA8AFA75 -:1038B000B8F8143003F10053053BDB000493D8F84B -:1038C0000C3003932821039B13B1BAF1000F2CD1C4 -:1038D000D8F8100040B1BAF1000F05D0009608AB3F -:1038E0005246691AFFF720FC38B2002FB8D066079D -:1038F0000AD00AAB03EBD401624211F8083C02F093 -:103900000702134101F8083C082C3CD9102C40F266 -:10391000B580202C40F2B780BBF1000F00F09C80F6 -:10392000082334E0BA460026C2E7049BE02B28BFF8 -:10393000E02306930B44AB42059314D95A1B03981A -:103940000096924534BF5246D2B2691A08AB043091 -:103950000792FFF7E9FB079A1644AAEB020A1544FF -:10396000F6B25FFA8AFA049B069A05999B1A0493A9 -:10397000039B1B680393A6E70093D8F8080008ABE5 -:103980003A462946AEE7BBF1000F13D00123B4EB52 -:10399000C30F6CD0082C12D89DF82030621E23FA79 -:1039A00002F2D50706D54FF0FF3202FA04F42343A2 -:1039B0008DF820309DF8203089F8003051E7102C28 -:1039C00012D8BDF82030621E23FA02F2D10706D5C4 -:1039D0004FF0FF3202FA04F42343ADF82030BDF873 -:1039E0002030A9F800303CE7202C0FD80899631E3E -:1039F00021FA03F3DA0705D54FF0FF3202FA04F497 -:103A00000C430894089BC9F800302AE7402C2BD0BF -:103A1000DDE90865611EC4F12102A4F1210326FA43 -:103A200001F105FA02F225FA03F311431943CB071A -:103A300012D50122A4F12003C4F1200102FA03F3FC -:103A400022FA01F1A240524243EA010363EB43032D -:103A500032432B43CDE90823DDE90823C9E90023DC -:103A6000FFE66FF00100FCE66FF00800F9E6082CB5 -:103A7000A0D9102CB3D9202CEED8C3E7BBF1000F8E -:103A8000ADD0022383E7BBF1000FBBD004237EE758 -:103A900030B5012A144638BF0124402C85B028BF18 -:103AA00040240025012ACDE9025518D81B788DF84D -:103AB000083063070AD004AB03EBD405624215F863 -:103AC000083C02F00702934005F8083C00910346C9 -:103AD0002246002102A8FFF727FB05B030BD082AC7 -:103AE000E4D9102A03D81B88ADF80830E1E7202A72 -:103AF0008DBFD3E900231B680293CDE90223D8E7E9 -:103B000010B5CB681BB98B600B618B8210BD04694B -:103B10001A681C600361C38A013BC382CA60F0E774 -:103B200003064CBFC0F3C0300220704708B5024600 -:103B3000FFF7F6FF022806D15306C2F30F2001D18A -:103B400000F0030008BDC2F30740FBE72DE9F04F8A -:103B500093B0CDE903230A6804461046FFF7E0FF5F -:103B6000022814BFC2F306260026002A0D4682460C -:103B700080F2F28112F0C04940F0EE81097B002909 -:103B800000F0EA81022803D02378B34240F0E781B5 -:103B9000C2F304630693104602F07F030593FFF718 -:103BA000C5FF059B29444FEA834848EA0A4848EA8A -:103BB0004668CE7800230022CDE90823F309834626 -:103BC00048EA0008029367D0059B009302466768A5 -:103BD000534608A92046B847002800F0C381276A49 -:103BE0004FB9414604F10C00FFF702FB074690B9BC -:103BF0006FF0020054E03B6998450DD03F68002FFC -:103C0000F9D1414604F10C00FFF7F2FA074600280B -:103C1000EED0236A3B60276297F817C006F01F08B2 -:103C2000CCF3840CACEB08001FFA80FE0028B8BF70 -:103C30000EF12000A8EB0C031FFA83FED7E9022146 -:103C4000B8BF00B2002B0793BEBF0EF120031BB21A -:103C5000079352EA010338D0039BDFF824E39A1A52 -:103C6000049B4FF0000C63EB010196457CEB0103D4 -:103C70002BD36B7B97F81AE0734519D1029B002B6D -:103C800078D0012821DC7868F8B9DFF8F0C29445D3 -:103C900070EB010316D337E0276A27B96FF00C00E9 -:103CA00013B0BDE8F08F3B699845B5D03F68F4E7A5 -:103CB000B24890427CEB010301D30020F0E7029B65 -:103CC000002BFAD0079B0F2B17DCFA7DB30002F014 -:103CD000030203F07C031343FB7539462046FFF7CC -:103CE00007FB6B7BBB76029B3BB9FB7DC3F3840276 -:103CF000013262F38603FB75D0E76A7BBB7E9A4292 -:103D0000DBD1029B002B35D0B309022B32D0039BB1 -:103D1000BB60049BFB60142200210DA8FDF7A0FEF0 -:103D2000039B0A93049B0B932B1D0C932B7BADF8E9 -:103D30003EB0013BDBB2ADF83C30069B8DF8423023 -:103D4000059B8DF8433094F82C308DF840A083F01B -:103D500001038DF844308DF84180A3680AA92046FC -:103D60009847FB7DC3F38403013303F01F039B02D9 -:103D7000FB82A2E7FB7DC6F34012B2EBD31F40F0FB -:103D8000F480C3F38403434540F0F280029A2B7B16 -:103D9000B609002A4DD0F2075DD4032B40F2EB8028 -:103DA000039BBB60049BFB602B7BAE1D033BDBB224 -:103DB0003246394604F10C00FFF7ACFA00280CDA61 -:103DC00039462046FFF794FAFB7DC3F384030133A1 -:103DD00003F01F039B02FB820AE7DDE90884AB883E -:103DE0003B834FF6FF73C9F12000A9F1200228FAA6 -:103DF00009F104FA00F0014324FA02F211431846D3 -:103E0000C9B2FFF7C9F909F10809B9F1400F034632 -:103E1000E9D1B8822A7B033AD2B23146FFF7CEF914 -:103E2000FB7DB882DA43C2F3C01262F3C713FB759D -:103E300043E786B92E1D013BDBB23246394604F119 -:103E40000C00FFF767FA0028BADB2A7BB88A013A30 -:103E5000D2B23146E2E7F98AC1F30901013B0429F4 -:103E6000DAB25BD8281D002307F11B069A4208D955 -:103E700010F801CB06F801C0013101330529DBB28E -:103E8000F4D103990A9104990B91934207F11B0114 -:103E90000C9138BF043379680D9134BF55FA83F320 -:103EA00000230E93FB8AADF83EB0C3F309031A4416 -:103EB000069B8DF84230059B8DF8433094F82C30EA -:103EC000ADF83C2083F001038DF8443000238DF8D9 -:103ED00040A08DF841807B602A7BB88A013A291D79 -:103EE000FFF76CF93B8BB882834203D1A3680AA920 -:103EF0002046984720460AA9FFF702FEFB7DBA8AB2 -:103F0000C3F38403013303F01F039B02FB823B8B4B -:103F10009A420CBF00206FF01000C1E67B68002BB6 -:103F2000AFD0052001E01C3033461E68002EFAD1C8 -:103F3000091A081D2E1D184401EB090CBCF11B0FBA -:103F40005FFA89F39DD89A429BD916F8013B00F895 -:103F5000013B09F10109EFE76FF00900A0E66FF0FE -:103F60000A009DE66FF00B009AE66FF00D0097E6F1 -:103F70006FF00E0094E66FF00F0091E640420F00E4 -:103F800080841E00EFF3098305494A6B22F0010289 -:103F90004A63683383F30988002383F311887047E9 -:103FA00000EF00E0302080F3118862B60C4B0D4A20 -:103FB000D96821F4E0610904090C0A43DA60D3F8F6 -:103FC000FC20094942F08072C3F8FC200A6842F0E4 -:103FD00001020A602022DA7783F82200704700BFCE -:103FE00000ED00E00003FA05001000E010B53023FA -:103FF00083F311880E4B5B6813F4006314D0F1EE69 -:10400000103AEFF30984683C4FF08073E361094B89 -:10401000DB6B236684F3098800F078FB10B1064B54 -:10402000A36110BD054BFBE783F31188F9E700BFDF -:1040300000ED00E000EF00E043060008460600083F -:10404000026843681143016003B1184770470000DC -:10405000024A136843F0C003136070470038014000 -:1040600013B50E4C204600F0B7FA04F114000C49C9 -:10407000009400234FF4807200F074F9094B0A4950 -:1040800000944FF4807204F1380000F0EDF9074A13 -:10409000074BC4E9172302B010BD00BF3C4F0020FE -:1040A000A84F002051400008A850002000380140CF -:1040B000007A030A30B5037C234C002918BF0C4654 -:1040C000012B0FD1214B98420CD1214B1A6E42F497 -:1040D00080421A66D3F8802042F48042C3F88020E0 -:1040E000D3F880302268036EC16D846603EB5203FF -:1040F000B3FBF2F36268150442BF23F0070503F037 -:10410000070343EA4503CB60A36843F040034B60D9 -:10411000E36843F001038B6042F4967343F00103BC -:104120000B604FF0FF330B62510505D512F01022E2 -:1041300005D0B2F1805F04D080F8643030BD7F23B9 -:10414000FAE73F23F8E700BF685600083C4F00201D -:10415000001002402DE9F047C66D3768F4693462FB -:104160002107054619D014F0080118BF4FF48071DB -:10417000E20748BF41F02001A30748BF41F04001DA -:10418000600748BF41F08001302383F31188281D68 -:10419000FFF756FF002383F31188E2050AD5302389 -:1041A00083F311884FF48061281DFFF749FF002336 -:1041B00083F311884FF030094FF0000A14F0200803 -:1041C00038D13B0616D54FF0300905F1380A2006E4 -:1041D00010D589F31188504600F07AF9002836DAB4 -:1041E0000821281DFFF72CFF27F0800333600023F0 -:1041F00083F31188790614D5620612D5302383F330 -:104200001188D5E913239A4208D12B6C33B11021C0 -:10421000281D27F04007FFF713FF3760002383F3C3 -:104220001188E30618D5AA6E1369ABB1BDE8F04753 -:104230005069184789F31188736A95F86410284605 -:10424000194000F0E3F98AF31188F469B6E7B06227 -:1042500088F31188F469BAE7BDE8F0874FF0E023EE -:10426000002258684FF0FF31930003F1604303F5DB -:10427000614301329042C3F88010C3F88011F3D239 -:104280007047000000F1604303F561430901C9B2C2 -:1042900083F80013012200F01F039A4043099B009A -:1042A00003F1604303F56143C3F880211A6070474E -:1042B000F8B5154682680669AA420B46816938BF7F -:1042C0008568761AB54204460BD218462A46FDF791 -:1042D000B5FBA3692B44A361A3685B1BA3602846BD -:1042E000F8BD0CD918463246FDF7A8FBAF1BE168B4 -:1042F0003A463044FDF7A2FBE3683B44EBE718463F -:104300002A46FDF79BFBE368E5E7000083689342DC -:10431000F7B51546044638BF8568D0E90460361AFB -:10432000B5420BD22A46FDF789FB63692B446361D2 -:10433000A36828465B1BA36003B0F0BD0DD93246CD -:104340000191FDF77BFB0199E068AF1B3A463144D0 -:10435000FDF774FBE3683B44E9E72A46FDF76EFB93 -:10436000E368E4E710B50A440024C361029B84605B -:10437000C0E90000C0E90511C1600261036210BD1F -:1043800008B5D0E90532934201D1826882B98268CA -:10439000013282605A1C42611970D0E904329A429B -:1043A00024BFC3684361002100F078FA002008BDF3 -:1043B0004FF0FF30FBE7000070B5302304460E4697 -:1043C00083F31188A568A5B1A368A269013BA36026 -:1043D000531CA36115782269934224BFE368A3614B -:1043E000E3690BB120469847002383F311882846E0 -:1043F00007E03146204600F041FA0028E2DA85F372 -:10440000118870BD2DE9F74F04460E4617469846B1 -:10441000D0F81C904FF0300A8AF311884FF0000B4F -:10442000154665B12A4631462046FFF741FF03464F -:1044300060B94146204600F021FA0028F1D000235F -:1044400083F31188781B03B0BDE8F08FB9F1000F3A -:1044500003D001902046C847019B8BF31188ED1AC9 -:104460001E448AF31188DCE7C0E90511C160C3610D -:104470001144009B8260C0E9000001610362704743 -:10448000F8B504460D461646302383F31188A76815 -:10449000A7B1A368013BA36063695A1C62611D70E8 -:1044A000D4E904329A4224BFE3686361E3690BB143 -:1044B00020469847002080F3118807E031462046C7 -:1044C00000F0DCF90028E2DA87F31188F8BD00007B -:1044D000D0E905239A4210B501D182687AB9826881 -:1044E000013282605A1C82611C7803699A4224BF9F -:1044F000C3688361002100F0D1F9204610BD4FF060 -:10450000FF30FBE72DE9F74F04460E461746984665 -:10451000D0F81C904FF0300A8AF311884FF0000B4E -:10452000154665B12A4631462046FFF7EFFE0346A1 -:1045300060B94146204600F0A1F90028F1D00023DF -:1045400083F31188781B03B0BDE8F08FB9F1000F39 -:1045500003D001902046C847019B8BF31188ED1AC8 -:104560001E448AF31188DCE7026843681143016046 -:1045700003B11847704700001430FFF743BF000035 -:104580004FF0FF331430FFF73DBF00003830FFF726 -:10459000B9BF00004FF0FF333830FFF7B3BF000062 -:1045A0001430FFF709BF00004FF0FF311430FFF760 -:1045B00003BF00003830FFF763BF00004FF0FF3249 -:1045C0003830FFF75DBF0000012914BF6FF0130002 -:1045D00000207047FFF744BD044B03600023C0E98F -:1045E0000233436001230374704700BF8056000804 -:1045F00010B53023044683F31188FFF75BFD0223D7 -:104600002374002080F3118810BD000038B5C36901 -:1046100004460D461BB904210844FFF7A5FF2946AF -:1046200004F11400FFF7ACFE002806DA201D4FF459 -:104630000061BDE83840FFF797BF38BD0023037520 -:10464000826803691B6899689142FBD25A680360CB -:1046500042601060586070470023037582680369E8 -:104660001B6899689142FBD85A68036042601060E9 -:104670005860704708B50846302383F311880B7DD6 -:10468000032B05D0042B0DD02BB983F3118808BD63 -:104690008B6900221A604FF0FF338361FFF7CEFF72 -:1046A0000023F2E7D1E9003213605A60F3E700001B -:1046B000FFF7C4BF054BD9680875186802681A600F -:1046C000536001220275D860FBF7A6BFA8510020F5 -:1046D00030B50C4BDD684B1C87B004460FD02B4621 -:1046E000094A684600F06CF92046FFF7E3FF009B9B -:1046F00013B1684600F06EF9A86907B030BDFFF746 -:10470000D9FFF9E7A851002075460008044B1A6844 -:10471000DB6890689B68984294BF00200120704736 -:10472000A8510020084B10B51C68D86822681A6090 -:10473000536001222275DC60FFF78EFF01462046A0 -:10474000BDE81040FBF768BFA8510020044B1A6871 -:10475000DB6892689B689A4201D9FFF7E3BF704714 -:10476000A851002038B5074C074908480123002507 -:104770002370656000F01CFC0223237085F3118810 -:1047800038BD00BF10540020AC560008A8510020CE -:1047900008B572B6044B186500F0D2FA00F08AFB37 -:1047A000024B03221A70FEE7A8510020105400208B -:1047B00000F046B9EFF3118020B9EFF30583302202 -:1047C00082F311887047000010B530B9EFF305840B -:1047D000C4F3080414B180F3118810BDFFF7B6FFCD -:1047E00084F31188F9E700008B60022308618B8253 -:1047F000084670478368A3F1840243F8142C0269C9 -:1048000043F8442C426943F8402C094A43F8242CCD -:10481000C26843F8182C022203F80C2C002203F87B -:104820000B2C044A43F8102CA3F12000704700BF62 -:1048300031060008A851002008B5FFF7DBFFBDE8EE -:104840000840FFF735BF0000024BDB6898610F207E -:10485000FFF730BFA8510020302383F31188FFF702 -:10486000F3BF000008B50146302383F31188082008 -:10487000FFF72EFF002383F3118808BD064BDB688A -:1048800039B1426818605A60136043600420FFF732 -:104890001FBF4FF0FF307047A851002003689842B7 -:1048A00006D01A680260506099611846FFF700BF91 -:1048B0007047000010B503689C68A2420CD85C6881 -:1048C0008A600B604C602160596099688A1A9A600E -:1048D0004FF0FF33836010BD1B68121BECE7000034 -:1048E0000A2938BF0A2170B504460D460A26601908 -:1048F00000F058FB00F044FB041BA54203D8751CD4 -:104900002E460446F3E70A2E04D9BDE87040012084 -:1049100000F08EBB70BD0000F8B5144B0D46D96198 -:1049200003F1100141600A2A1969826038BF0A2226 -:10493000016048601861A818144600F025FB0A279A -:1049400000F01EFB431BA342064606D37C1C28191D -:1049500000F028FB27463546F2E70A2F04D9BDE8C8 -:10496000F840012000F064BBF8BD00BFA851002052 -:10497000F8B506460D4600F003FB0F4A134653F800 -:10498000107F9F4206D12A4601463046BDE8F840D6 -:10499000FFF7C2BFD169BB68441A2C1928BF2C4647 -:1049A000A34202D92946FFF79BFF2246314603481E -:1049B000BDE8F840FFF77EBFA8510020B8510020A5 -:1049C00010B4C0E9032300235DF8044B4361FFF7F3 -:1049D000CFBF000010B5194C236998420DD0D0E923 -:1049E0000032816813605A609A680A449A60002312 -:1049F00003604FF0FF33A36110BD2346026843F804 -:104A0000102F53600022026022699A4203D1BDE850 -:104A1000104000F0C1BA936881680B44936000F0C5 -:104A2000AFFA2269E1699268441AA242E4D91144BA -:104A3000BDE81040091AFFF753BF00BFA85100207E -:104A40002DE9F047DFF8BC8008F110072C4ED8F8AC -:104A5000105000F095FAD8F81C40AA68031B9A423F -:104A60003ED81444D5E900324FF00009C8F81C4084 -:104A700013605A60C5F80090D8F81030B34201D1E5 -:104A800000F08AFA89F31188D5E90331284698475E -:104A9000302383F311886B69002BD8D000F070FAB3 -:104AA0006A69A0EB04094A4582460DD2022000F053 -:104AB000BFFA0022D8F81030B34208D15146284638 -:104AC000BDE8F047FFF728BF121A2244F2E712EBC5 -:104AD000090938BF4A4629463846FFF7EBFEB5E7D5 -:104AE000D8F81030B34208D01444211AC8F81C007A -:104AF000A960BDE8F047FFF7F3BEBDE8F08700BF4F -:104B0000B8510020A851002000207047FEE70000A7 -:104B1000704700004FF0FF3070470000BFF34F8F29 -:104B2000024A1369DB03FCD4704700BF0020024037 -:104B300008B5094B1B7873B9FFF7F0FF074B5A69AB -:104B4000002ABFBF064A9A6002F188329A601A684A -:104B500022F480621A6008BD285400200020024020 -:104B60002301674508B50B4B1B7893B9FFF7D6FFB8 -:104B7000094B5A6942F000425A611A6842F4805265 -:104B80001A601A6822F480521A601A6842F480622D -:104B90001A6008BD28540020002002407F289ABFD8 -:104BA00000F58030C0020020704700004FF4006024 -:104BB00070470000802070477F2808B50BD8FFF7AA -:104BC000EDFF00F500630268013204D10430834236 -:104BD000F9D1012008BD0020FCE700007F2810B5B6 -:104BE00004461FD8FFF79AFFFFF7A2FF0E4BF322F0 -:104BF0001A6102225A615A6942EAC0025A615A692C -:104C000042F480325A61FFF789FF4FF40061FFF7E9 -:104C1000C5FF00F04BF9FFF7A5FF2046BDE81040A7 -:104C2000FFF7CABF002010BD002002402DE9F84365 -:104C300040EA020313F00703144606D0304B40F25B -:104C400031321A600020BDE8F88385182D4A95425C -:104C50000CD92B4A40F236311160F3E7031D1B6873 -:104C60004A68934208D1083C08300831072C14D90F -:104C700002680B689A42F1D0FFF75AFFFFF74EFF28 -:104C8000214E08314FF001084FF00009012CA1F12D -:104C9000080706D8FFF766FF01E0002CECD10120E1 -:104CA000D1E7C6F81480054651F8083C45F8043BA6 -:104CB00051F8043C4360FFF731FF336943F00103CF -:104CC0003361C6F81490026851F8083C9A420CD03F -:104CD0000B4B40F25E321A600C4B18600C4B1C60A0 -:104CE0000C4B1F60FFF73EFFACE72D6851F8043C0A -:104CF0009D4201F10801EBD1083C0830C6E700BF36 -:104D00002454002000000408002002401854002011 -:104D1000205400201C540020084908B50B7828B105 -:104D20001BB9FFF705FF01230B7008BD002BFCD05A -:104D3000BDE808400870FFF715BF00BF28540020E9 -:104D400008B54FF4C0314FF0005000F0B1F8BDE8A5 -:104D500008404FF480414FF0805000F0A9B80000A7 -:104D6000084600F0F3BB000070B582B0FFF722FDEB -:104D70000E4E054600F004F93268904237BF0C4AE7 -:104D80000B49516814682EBFD1E9004101315160CF -:104D90000419034641F10001284601913360FFF7F1 -:104DA00013FD0199204602B070BD00BF2C540020B5 -:104DB0003054002070B582B0FFF7FCFC104E054661 -:104DC00000F0DEF83268904237BF0E4A0D49516854 -:104DD00014682EBFD1E9004101315160041941F13D -:104DE00000010346284601913360FFF7EDFC01996D -:104DF0004FF47A7200232046FBF7FAF902B070BD37 -:104E00002C540020305400200244D2B2904200D1F1 -:104E10007047431C800000F1804000F5145000688A -:104E200041F8040BD8B2F1E7124B10B5D3F890401B -:104E3000240409D4D3F89040C3F89040D3F89040AC -:104E400044F40044C3F890400B4C2368024443F4FC -:104E500080732360D2B2904200D110BD431C800009 -:104E600000F1804000F5145051F8044B0460D8B2B2 -:104E7000F1E700BF001002400070004007B50122BA -:104E800001A90020FFF7C0FF019803B05DF804FB03 -:104E900013B50446FFF7F2FFA04205D0012201A995 -:104EA00000200194FFF7C0FF02B010BD7047000062 -:104EB0007047000070470000074B45F255521A60DA -:104EC00002225A6040F6FF729A604CF6CC421A6099 -:104ED000024B01221A707047003000403C54002001 -:104EE000034B1B781BB1034B4AF6AA221A6070478A -:104EF0003C54002000300040054B1A6832B902F1E2 -:104F0000804202F50432D2F894201A60704700BF44 -:104F100038540020024B4FF40002C3F8942070472D -:104F20000010024008B5FFF7E7FF024B1868C0F316 -:104F3000407008BD3854002070470000FEE70000B4 -:104F40000A4B0B480B4A90420BD30B4BDA1C121A3C -:104F5000C11E22F003028B4238BF00220021FCF761 -:104F60007FBD53F8041B40F8041BECE71C580008F5 -:104F7000C0540020C0540020C054002000F0C2B82B -:104F80004FF08043586A70474FF0804300225863C7 -:104F90001A610222DA6070474FF080430022DA6023 -:104FA000704700004FF0804358637047FEE70000F1 -:104FB00070B51B4B01630025044686B058608562BE -:104FC0000E46FEF7EFFF04F11003C4E904334FF07F -:104FD000FF33C4E90635C4E90044A560E562FFF784 -:104FE000CFFF2B460246C4E9082304F134010D4AE1 -:104FF000256580232046FFF7F7FB0123E0600A4A7E -:105000000375009272680192B268CDE90223074BE2 -:105010006846CDE90435FFF70FFC06B070BD00BF50 -:1050200010540020B8560008BD560008AD4F0008C7 -:10503000024AD36A1843D062704700BFA8510020CB -:105040004B6843608B688360CB68C3600B694361C6 -:105050004B6903628B6943620B6803607047000011 -:1050600008B5204BDA6A42F07F02DA62DA6A22F08F -:105070007F02DA62DA6ADA6C42F07F02DA64DA6EB0 -:1050800042F07F02DA66184ADB6E11464FF090401C -:10509000FFF7D6FF02F11C0100F58060FFF7D0FF9B -:1050A00002F1380100F58060FFF7CAFF02F15401F8 -:1050B00000F58060FFF7C4FF02F1700100F5806029 -:1050C000FFF7BEFF02F18C0100F58060FFF7B8FF2B -:1050D00002F1A80100F58060FFF7B2FFBDE80840CB -:1050E00000F050B800100240C456000808B500F0A7 -:1050F000FBF9FFF737FBBDE80840FFF7FDBE0000F6 -:10510000704700000F4B9A6D42F001029A659A6F4A -:1051100042F001029A670C4A9B6F936843F00103C7 -:1051200093604FF08043A7229A624FF0FF32DA6219 -:1051300000229A615A63DA605A6001225A611A6049 -:10514000704700BF00100240002004E04FF0804292 -:1051500008B51169D3680B40D9B2C9439B071161E7 -:1051600007D5302383F31188FFF722FB002383F355 -:10517000118808BD08B5FFF771F8BDE8084000F0D8 -:105180008BB900004E4B4FF0FF319A6A99629A6AD0 -:1051900000229A62986AD86A60F07F00D862D86A62 -:1051A00000F07F00D862D86A186B1963186B1A6315 -:1051B000186B986B9963986B9A63986BD86BD963EB -:1051C000D86BDA63D86B186C1964196C1A64196C93 -:1051D000196E41F001011966D3F8801021F0010128 -:1051E000C3F88010D3F88010996D41F08051996513 -:1051F000996F21F080519967996F32494FF40040BF -:105200008860CA600A624A628A62CA620A634A6342 -:105210008A63CA630A644A648A64CA640A654A651E -:105220004A604FF48072C1F880204FF440720A60E7 -:105230004A6912F48062FBD1D3F8901011F4407FD8 -:105240001EBF4FF48031C3F89010C3F89020D3F8FC -:10525000982042F00102C3F89820D3F898209207D2 -:10526000FBD51A6842F480321A601A689003FCD5A4 -:10527000D3F8902022F00322C3F89020124ADA607B -:105280001A6842F080721A601A689101FCD50F49C1 -:105290000F4800229A60C3F888100E49C3F89C207A -:1052A000016002684A401207FBD19A6842F003028B -:1052B0009A609A6802F00C020C2AFAD1704700BF7B -:1052C0000010024000700040032A610155010050A7 -:1052D0000020024004070400074A08B5536903F0A0 -:1052E0000103536123B1054A13680BB15068984715 -:1052F000BDE80840FEF77ABE00040140405400209B -:10530000074A08B5536903F00203536123B1054A04 -:1053100093680BB1D0689847BDE80840FEF766BEB9 -:105320000004014040540020074A08B5536903F0C7 -:105330000403536123B1054A13690BB150699847BF -:10534000BDE80840FEF752BE000401404054002072 -:10535000074A08B5536903F00803536123B1054AAE -:1053600093690BB1D0699847BDE80840FEF73EBE8F -:105370000004014040540020074A08B5536903F077 -:105380001003536123B1054A136A0BB1506A984761 -:10539000BDE80840FEF72ABE00040140405400204A -:1053A000164B10B55C6904F478725A61A30604D5F3 -:1053B000134A936A0BB1D06A9847600604D5104A25 -:1053C000136B0BB1506B9847210604D50C4A936BB5 -:1053D0000BB1D06B9847E20504D5094A136C0BB1A9 -:1053E000506C9847A30504D5054A936C0BB1D06C5B -:1053F0009847BDE81040FEF7F9BD00BF000401402A -:1054000040540020194B10B55C6904F47C425A6189 -:10541000620504D5164A136D0BB1506D98472305EC -:1054200004D5134A936D0BB1D06D9847E00404D5B1 -:105430000F4A136E0BB1506E9847A10404D50C4A65 -:10544000936E0BB1D06E9847620404D5084A136F6F -:105450000BB1506F9847230404D5054A936F0BB1E5 -:10546000D06F9847BDE81040FEF7C0BD0004014072 -:105470004054002008B50348FEF76CFEBDE8084024 -:10548000FEF7B4BD3C4F002008B5FFF75FFEBDE856 -:105490000840FEF7ABBD0000062108B50846FEF740 -:1054A000F1FE06210720FEF7EDFE06210820FEF79B -:1054B000E9FE06210920FEF7E5FE06210A20FEF797 -:1054C000E1FE06211720FEF7DDFE06212820FEF76B -:1054D000D9FE07211C20FEF7D5FEBDE808400C21AF -:1054E0002520FEF7CFBE000008B5FFF743FE00F011 -:1054F00009F8FFF76FF8FFF703FEBDE80840FFF774 -:105500003DBD00000023054A19460133102BC2E9B6 -:10551000001102F10802F8D1704700BF405400208A -:105520000B460146184600F003B8000000F00EB824 -:1055300010B5054C13462CB10A4601460220AFF3C4 -:10554000008010BD2046FCE700000000024B014631 -:105550001868FFF705BC00BF2823002010B50139EB -:105560000244904201D1002005E0037811F8014F78 -:10557000A34201D0181B10BD0130F2E72DE9F04124 -:10558000A3B1C91A17780144044603F1FF3C8C42C9 -:10559000204601D9002009E00578BD4204F101044C -:1055A000F5D10CEB0405D618A54201D1BDE8F08178 -:1055B00015F8018D16F801EDF045F5D0E7E700008C -:1055C000034611F8012B03F8012B002AF9D170478B -:1055D0006F72672E6172647570696C6F742E6D5294 -:1055E0006F2D4D31303039350000000053544D33AC -:1055F0003247343F3F00000040A2E4F16468910666 -:105600000041A3E5F2656992070000004261642051 -:1056100043414E496661636520696E6465782E007A -:105620000000000000000000C9270008D122000887 -:10563000852E0008C9220008792300085D2500088E -:1056400041230008092300080D230008E522000873 -:10565000CD2200081D250008F1220008BD2F0008FA -:10566000FD220008F1240008009600000000000060 +:1000000000070020F1010008252D0008DD2C000864 +:10001000052D0008DD2C0008FD2C0008F301000868 +:10002000F3010008F3010008F3010008053D000892 +:10003000F3010008F3010008F3010008F3010008D0 +:10004000F3010008F3010008F3010008F3010008C0 +:10005000F3010008F3010008154200083D420008C2 +:10006000654200088D420008B5420008F30100080F +:10007000F3010008F3010008F3010008F301000890 +:10008000F3010008F3010008F3010008F301000880 +:10009000F3010008BD2C0008CD2C0008DD4200084B +:1000A000F3010008F3010008F3010008F301000860 +:1000B000C5430008F3010008F3010008F30100083C +:1000C000F3010008F3010008F3010008F301000840 +:1000D000F3010008B1430008F3010008F301000830 +:1000E00041430008F3010008F3010008F301000890 +:1000F000F3010008F3010008F3010008F301000810 +:10010000F3010008F3010008F3010008F3010008FF +:10011000F3010008F3010008F3010008F3010008EF +:10012000F3010008F3010008F3010008F3010008DF +:10013000F3010008F3010008F3010008F3010008CF +:10014000F3010008F3010008F3010008F3010008BF +:10015000F3010008F3010008F3010008F3010008AF +:10016000F3010008F3010008F3010008F30100089F +:10017000F3010008F3010008F3010008F30100088F +:10018000F3010008F3010008F3010008F30100087F +:10019000F3010008F3010008F3010008F30100086F +:1001A000F3010008F3010008F3010008F30100085F +:1001B000F3010008F3010008F3010008F30100084F +:1001C000F3010008F3010008F3010008F30100083F +:1001D000F3010008F3010008F3010008F30100082F +:1001E00001150008000000000000000000000000F1 +:1001F00002E000F000F8FEE772B6374880F30888A6 +:10020000364880F3098836483649086040F20000D5 +:10021000CCF200004EF63471CEF200010860BFF35C +:100220004F8FBFF36F8F40F20000C0F2F0004EF628 +:100230008851CEF200010860BFF34F8FBFF36F8F7C +:100240004FF00000E1EE100A4EF63C71CEF20001D4 +:100250000860062080F31488BFF36F8F04F032FF2C +:1002600005F012F84FF055301F491B4A91423CBF30 +:1002700041F8040BFAE71D49184A91423CBF41F886 +:10028000040BFAE71A491B4A1B4B9A423EBF51F82E +:10029000040B42F8040BF8E700201849184A914271 +:1002A0003CBF41F8040BFAE704F010FF05F032F808 +:1002B000144C154DAC4203DA54F8041B8847F9E797 +:1002C00000F042F8114C124DAC4203DA54F8041B12 +:1002D0008847F9E704F0F8BE00070020002300205B +:1002E0000000000808ED00E00001002000070020E9 +:1002F000F855000800230020B4230020B823002074 +:10030000EC540020E0010008E4010008E4010008CA +:10031000E40100082DE9F04F2DED108AC1F80CD052 +:10032000C3689D46BDEC108ABDE8F08F002383F3BF +:1003300011882846A047002004F04CFBFEE704F09B +:10034000D5FA00DFFEE70000F8B501F047F904F048 +:100350005BFE074604F0ACFE0546A8BB1F4B9F4260 +:1003600032D001339F4232D01D4B27F0FF029A4218 +:1003700030D1F8B200F00EFF2E4642F2107400F0B9 +:100380000FFF08B10024264601F054FC20B10320E1 +:1003900000F07AF80024264635B1124B9F4203D074 +:1003A00004F07EFE00242646002004F037FE0EB145 +:1003B00000F080F801F024FA00F024FF204600F05D +:1003C000D7F800F077F8F9E72E460024D7E704467F +:1003D0000126D4E706464FF47A74D0E7010007B04F +:1003E000000008B0263A09B008B501F0C3F8A0F142 +:1003F00020035842584108BD07B541F212030221BB +:1004000001A8ADF8043001F0D3F803B05DF804FBA7 +:1004100038B5302383F31188174803680BB104F013 +:1004200097FB164A144800234FF47A7104F086FBB8 +:10043000002383F31188124C236813B12368013B16 +:100440002360636813B16368013B63600D4D2B78D3 +:1004500033B963687BB9022001F060F9322363602D +:100460002B78032B07D163682BB9022001F056F9D2 +:100470004FF47A73636038BDB8230020110400087C +:10048000D8240020D0230020084B187003280CD853 +:10049000DFE800F008050208022001F037B9022069 +:1004A00001F02CB9024B00225A607047D023002083 +:1004B000D824002038B501F0BDFB30B1254B032214 +:1004C0001A70254B00225A6038BD244B244A196803 +:1004D0000131F9D004339342F9D1224C1F4DD4F8A5 +:1004E0000428AA42F0D3204B9B6803F1006303F574 +:1004F000F0439A42E8D204F0A5FD04F0B7FD0020D5 +:1005000001F086F80220FFF7BFFF184B9A6D00221A +:100510009A65996F9A67996FD96DDA65D96FDA67BD +:10052000D96F196E1A66D3F88010C3F88020D3F8FB +:10053000803072B64FF0E0233021C3F8085DD4F864 +:100540000038D4F8042881F311889D4683F3088885 +:100550001047B9E7D0230020D824002000780008F5 +:1005600020780008007000080023002000100240DE +:100570002DE9F04F93B0AC4B00902022FF210AA848 +:100580009D6801F0E7F8A94A1378A3B9A8480121AA +:1005900003601170302383F3118803680BB104F0FA +:1005A000D7FAA44AA24800234FF47A7104F0C6FA9D +:1005B000002383F31188009B13B19F4B009A1A60AC +:1005C0009E4A009C1378032B1EBF002313709A4A87 +:1005D0004FF0000A18BF5360D3465646D14601205B +:1005E00001F094F824B1944B1B68002B00F01582A5 +:1005F000002000F0BFFF0390039B002B01DA00F006 +:1006000049FE039B002BEDDB012001F077F8039BF3 +:10061000213B162BE3D801A252F823F079060008FB +:10062000A106000835070008DF050008DF050008FF +:10063000DF050008BF0700088F090008A9080008A7 +:100640000B0900083309000859090008DF050008F4 +:100650006B090008DF050008DD090008190700081C +:10066000DF050008210A00088506000819070008B0 +:10067000DF0500080B0900080220FFF7B5FE00287F +:1006800040F0F581009B0221BAF1000F08BF1C4623 +:1006900005A841F21233ADF8143000F089FF9EE74F +:1006A0004FF47A7000F066FF071EEBDB0220FFF7C5 +:1006B0009BFE0028E6D0013F052F00F2DA81DFE83B +:1006C00007F0030A0D10133605230593042105A82E +:1006D00000F06EFF17E054480421F9E75848042160 +:1006E000F6E758480421F3E74FF01C08404600F0B5 +:1006F00091FF08F104080590042105A800F058FFB7 +:10070000B8F12C0FF2D1012000FA07F747EA0B0BE2 +:100710005FFA8BFB4FF0000901F068F826B10BF08F +:100720000B030B2B08BF0024FFF766FE57E7464874 +:100730000421CDE7002EA5D00BF00B030B2BA1D18C +:100740000220FFF751FE074600289BD0012000F051 +:100750005FFF0220FFF798FE00261FFA86F840464A +:1007600000F068FF044690B10021404600F07AFF97 +:1007700001360028F1D1BA46044641F21213022193 +:1007800005A8ADF814303E4600F012FF27E701201F +:10079000FFF77AFE2546244B9B68AB4207D92846D3 +:1007A00000F038FF013040F067810435F3E7234B58 +:1007B00000251D70204BBA465D603E46ACE7002E1A +:1007C0003FF460AF0BF00B030B2B7FF45BAF022009 +:1007D000FFF75AFE322000F0CDFEB0F10008FFF620 +:1007E00051AF18F003077FF44DAF0F4A926808EB42 +:1007F000050393423FF646AFB8F5807F3FF742AF1F +:10080000124B0193B84523DD4FF47A7000F0B2FE2D +:100810000390039A002AFFF635AF019B039A03F871 +:10082000012B0137EDE700BF00230020D424002076 +:10083000B823002011040008D8240020D023002071 +:1008400004230020082300200C230020D4230020B0 +:10085000C820FFF7C9FD074600283FF413AF1F2D3E +:1008600011D8C5F1200242450AAB25F0030028BF8C +:10087000424683490192184400F05AFF019A804889 +:10088000FF2100F067FF4FEAA8037D490193C8F3F9 +:100890008702284600F066FF064600283FF46DAF49 +:1008A000019B05EB830537E70220FFF79DFD00283C +:1008B0003FF4E8AE00F0E8FE00283FF4E3AE002786 +:1008C000B846704B9B68BB4218D91F2F11D80A9BA2 +:1008D00001330ED027F0030312AA134453F8203C2F +:1008E00005934046042205A901F08EF9043780469D +:1008F000E7E7384600F08EFE0590F2E7CDF8148069 +:10090000042105A800F054FE06E70023642104A892 +:10091000049300F043FE00287FF4B4AE0220FFF7FA +:1009200063FD00283FF4AEAE049800F0A3FE0590EE +:10093000E6E70023642104A8049300F02FFE0028BA +:100940007FF4A0AE0220FFF74FFD00283FF49AAEDF +:10095000049800F091FEEAE70220FFF745FD002829 +:100960003FF490AE00F0A0FEE1E70220FFF73CFD6F +:1009700000283FF487AE05A9142000F09BFE042157 +:100980000746049004A800F013FE3946B9E7322068 +:1009900000F0F0FD071EFFF675AEBB077FF472AEE8 +:1009A000384A926807EB090393423FF66BAE022088 +:1009B000FFF71AFD00283FF465AE27F003074F4408 +:1009C000B9453FF4A9AE484600F024FE0421059045 +:1009D00005A800F0EDFD09F10409F1E74FF47A7084 +:1009E000FFF702FD00283FF44DAE00F04DFE002859 +:1009F00044D00A9B01330BD008220AA9002000F042 +:100A0000B1FE00283AD02022FF210AA800F0A2FE61 +:100A1000FFF7F2FC1C4803F0E3FF13B0BDE8F08FD2 +:100A2000002E3FF42FAE0BF00B030B2B7FF42AAEFE +:100A30000023642105A8059300F0B0FD07460028B7 +:100A40007FF420AE0220FFF7CFFC804600283FF461 +:100A500019AEFFF7D1FC41F2883003F0C1FF0598D1 +:100A600000F0DAFE464600F0C1FE3C46B7E5064619 +:100A700052E64FF0000905E6BA467EE637467CE6C8 +:100A8000D423002000230020A0860100094A136817 +:100A900049F2690099B21B0C00FB01331360064B4D +:100AA000186844F2506182B2000C01FB0200186029 +:100AB00080B27047142300201023002010B50021BD +:100AC0001022044600F046FE034B03CB2060616019 +:100AD0001868A06010BD00BF9075FF1F2DE9F041A0 +:100AE000ADF54E7D0DF134086CAC40F27512074641 +:100AF0000D460EA80021C8F8001000F02BFE4FF4A0 +:100B0000C4720021204600F025FE02F013F9254BA7 +:100B10004FF47A72B0FBF2F0186093E807000223FA +:100B200084E807000DF5E9702382FFF7C7FF41F263 +:100B300004131D49238406A804F056FC182384F8E6 +:100B400032310DF2E3266B440DF1300C1A4603CA24 +:100B5000624530607160134606F10806F6D14146E1 +:100B60000122204600F072FE00230393AB7E029325 +:100B700005F11903019380B20123CDE904800093AC +:100B8000E97E06A3D3E90023384602F091FC0DF577 +:100B90004E7DBDE8F08100BFAFF300809E6AC421A6 +:100BA000818A46EEE0240020F85300082DE9F04148 +:100BB0002C4C237ADAB080460D465BBB27A9284629 +:100BC00000F054FF0746002842D19DF89D60C82ED2 +:100BD0003ED801464FF4A662204600F0BBFD4FF41C +:100BE0008073C4F8F8314FF40073C4F80C334FF439 +:100BF0004073C4F8203432460DF19E0104F109001F +:100C000000F096FD26449DF89C30777223720BB954 +:100C1000EB7E23728122002106AC27A800F09AFD0A +:100C20000122214627A800F05DFF00230393AB7E3D +:100C3000029305F1190380B201932823CDE9044002 +:100C40000093E97E05A3D3E90023404602F030FC7F +:100C50005AB0BDE8F08100BFAFF300802641727248 +:100C6000DF25D7B7E8490020F0B5254E4FF48A7547 +:100C700005FB0065F1B096F8D83085F8DC3000242B +:100C8000D822214685F8E8403AA800F063FD06F135 +:100C9000090000F057FDD5F8E4308DF8F000C2B23D +:100CA00006AF06F109010DF1F100CDE93A3400F08B +:100CB0003FFD394601223AA800F040FF80B2CDE95D +:100CC000047008230127CDE9023706F1D803019308 +:100CD00030230093317A0B4807A3D3E9002302F0B5 +:100CE000E7FBA04206DD02F025F8C5F8E000384633 +:100CF00071B0F0BD2046FBE778F6339F93CACD8DE7 +:100D0000E8490020F83400202DE9F0411D4D1E4E29 +:100D10001E4F86B0284602F0F7FB034658B3002466 +:100D2000CDE90344ADF81440027B8DF81420996896 +:100D30004068029403AA03C21B68DFF8548043F0A2 +:100D40000043029301F0F8FF821941F1000300947F +:100D500002A9384601F082F9A04205DD284602F0DA +:100D6000D7FB88F80040D5E798F80030072B05D866 +:100D7000013388F8003006B0BDE8F081014802F088 +:100D8000C7FBF8E7F834002040420F002835002068 +:100D90001D4F002070B50D4614461E4602F0E4FAC1 +:100DA00050B9022E10D1012C0ED112A3D3E9002389 +:100DB000C5E90023012007E0282C10D005D8012C1C +:100DC00009D0052C0FD0002070BD302CFBD10BA317 +:100DD000D3E90023ECE70BA3D3E90023E8E70BA357 +:100DE000D3E90023E4E70BA3D3E90023E0E700BF46 +:100DF000AFF30080401DA12026812A0B78F6339F97 +:100E000093CACD8D9E6AC421818A46EE26417272B4 +:100E1000DF25D7B7F017304A39059E5638B5054655 +:100E20000E4C0021013500F01DFCA4F82C55B4F83F +:100E30002C0500F0FFFB78B1B4F82C0500F00AFC9B +:100E4000014648B9B4F82C0500F00CFCB4F82C3578 +:100E50000133A4F82C35EAE738BD00BFE84900208B +:100E600010B50A4B0A4A1A6003F5805393F84820DC +:100E70003AB95C6C2CB1204600F05AFF204604F0D1 +:100E800069FABDE81040034800F052BF2835002041 +:100E900050540008584500202DE9F04F8FB000AFA6 +:100EA00005460C4602F060FA002849D1237E022B49 +:100EB0001BD1E38A012B18D101F03CFF0646FFF756 +:100EC000E5FD03464FF4C870DFF8C482B3FBF0F2CF +:100ED00006F5167602FB103316FA83F3C8F80030D5 +:100EE000E37E33B9A34B00221A703C37BD46BDE800 +:100EF000F08F07F12401204600F076FD0028F4D1A0 +:100F000007F11400FFF7DAFD97F8264007F1140106 +:100F1000224607F1270004F035FA0028E2D10F2C11 +:100F200008D8944B1C70D8F80030A3F51673C8F895 +:100F30000030DAE797F82410284602F00DFAD4E7DB +:100F4000E38A282B2BD010D8012B23D0052BCCD112 +:100F5000BFF34F8F8849894BCA6802F4E06213439C +:100F6000CB60BFF34F8F00BFFDE7302BBDD1844E68 +:100F7000E17E327A9142B8D1607E3146002291F80A +:100F8000DC50854200F0A5800132042A01F58A7107 +:100F9000F5D1AAE721462846FFF7A0FDA5E721469F +:100FA0002846FFF703FEA0E7B2F8EC507B6005F19E +:100FB00003094FEA99094FEA8902D11DC908A8EB34 +:100FC000C1039D46EB460021584600F0C3FB04F1E7 +:100FD000EE012A463144584600F0AAFB7B6813B95B +:100FE000012000F015FB96F8D20000F023FB044628 +:100FF00030B9307200F048FB204600F009FBB1E048 +:10100000D6F8D4203AB996F8D200B6F82C25824208 +:1010100001D8FFF703FFD6F8D4202A44944208D21F +:1010200096F8D200B6F82C250130824201D8FFF79D +:10103000F5FE70685FFA89F2594600F093FB08B933 +:10104000C54679E0726896F8D2002A447260D6F8F4 +:10105000D42005EB0209C6F8D49000F0EBFA8145E4 +:1010600009D396F8D220D6F8D4000132001B86F8B6 +:10107000D220C6F8D400FF2D0FD80024347200F01F +:1010800003FB204600F0C4FA00F0D4FD3D4B18816C +:1010900008B9FFF70FFAC54627E7BB6896F8D900ED +:1010A0000AFB0362FB68D2F8E41082F8E83001F52D +:1010B0008061C2F8E030C2F8E410FFF7D5FDFFF719 +:1010C00023FE96F8D920013202F0030286F8D920D7 +:1010D000B6E74FF48A7A0AFB02F505F1EA013144DA +:1010E000204600F057FDF86000287FF4FEAE35443E +:1010F000012285F8E82001F01DFED5F8E020D6EDAC +:10110000007ADFED216A801A192838BF192040F6CD +:10111000B832904228BF1046B8EE677A07EE900AC0 +:10112000F8EEE77A67EEA67ADFED186AE7EE267A40 +:10113000FCEEE77AC6ED007A96F8D930BB60BA6863 +:1011400073680AFB02F4321992F8E81059B1D2F828 +:10115000E4108B42E8463FF427AF002182F8E81004 +:10116000C2F8E010C5467368064A9B0A0133138132 +:10117000BBE600BFF134002000ED00E00400FA05FA +:10118000E8490020E0240020CDCCCC3D6666663FD7 +:10119000F4340020014B1870704700BFEC2400208D +:1011A00038B54FF00054134B22689A4220D1124BAD +:1011B000627D12481A70237D03724FF48073C0F869 +:1011C000F8314FF40073C0F80C3300254FF440732E +:1011D000C0F820340A49C0F8E450C922093000F0B0 +:1011E000A7FAE0222946204600F0B4FA012038BDD3 +:1011F0000020FCE79AAD44C5EC240020E84900201B +:101200001600002037B500F015FD194D1949288149 +:1012100002236B7100220123174801F069F90023B2 +:101220000193164B164900931648174B4FF4805202 +:1012300002F06AF8154B197811B1124802F08CF8D7 +:1012400001F078FD0446FFF721FC4FF4C873B0FBB2 +:10125000F3F202FB130304F5167010FA83F00C4B43 +:10126000186003F025FF08B10F232B8103B030BDB8 +:10127000E024002040420F0028350020950D000892 +:10128000F0240020F8340020990E0008EC240020FF +:10129000F43400202DE9F04F2DED028B90A7D7E913 +:1012A00000670FF24429D9E90089884C95B00DAD4B +:1012B0009FED848BFFF728FDDFF834B200230C93F9 +:1012C000ADF83C300D936B6000230DF125028DEDE0 +:1012D000008B4FF0010A09A958468DF825308DF88A +:1012E00024A001F08FFC9DF824200023002A40F068 +:1012F000AF80204602F038F80546002847D1DFF8D5 +:10130000F4B101F017FDDBF8003098423FD301F053 +:1013100011FD0790FFF7BAFB079A4FF4C873B0FBB3 +:10132000F3F101FB130302F5167010FA83F0CBF80A +:101330000000DFF8C4B19BF800100791002914BF2A +:101340002B46534610A88DF83030FFF7B7FB0799AE +:10135000C1F11002D2B2062A10AB28BF06221944EE +:101360000DF13100079200F0E3F9079A0CAB0393FB +:10137000182302930132564BD2B2CDE900A3049256 +:101380003B463246204602F035F88BF8005001F01B +:10139000D1FC504A504D1368C31AB3F57A7F32D34B +:1013A000106001F0C9FC02460B46204602F0BAF874 +:1013B000204601F0D9FF30B32B7ADFF840A1002B93 +:1013C00014BF032302238AF8053001F0B3FC0DF1AA +:1013D000400B4FF47A730122B0FBF3F05946CAF880 +:1013E0000000504600F0D8FA182302933B4B0193BB +:1013F00080B240F25513CDE903B0009342464B460C +:10140000204601F0F7FF2B7AB3B101F093FC4FF0C7 +:10141000000A83464FF48A7295F8D900504400F0D0 +:10142000030002FB005393F8E810002934D00AF1BE +:10143000010ABAF1040FEFD1C82003F0D1FA2B7AD8 +:10144000002B7FF434AF15B0BDEC028BBDE8F08FFC +:101450004FF0904110A84A6982F010024A61194683 +:10146000102200F077F90DF126030AAA0CA95846BC +:1014700000F0E8FE95E8030011AB83E803009DF857 +:101480003C308DF84C300C9B109310A9DDE90A23F9 +:10149000204602F01BFA17E7D3F8E01049B12B6899 +:1014A000FA2B38BFFA23ABEB01010533B1EB430F45 +:1014B000BDD3FFF7D9FB4FF48A720028B7D1BBE741 +:1014C000AFF300800000000000000000F8340020AE +:1014D000F0340020184F0020E84900201C4F002065 +:1014E000401DA12026812A0BF1C6A7C1D068080F94 +:1014F00028350020F4340020F1340020E0240020BE +:1015000008B5054800F044FFBDE80840034A044917 +:10151000002003F019BF00BF28350020704F0020C5 +:10152000610E000870B5104B1B780133DBB2012B44 +:101530000C4612D80D4B1D6829684FF47A730E6A59 +:10154000A2FB0332014622462846B047844204D11A +:10155000074B00221A70012070BD4FF4FA7003F09F +:101560003FFA0020F8E700BF182300201C230020CA +:10157000644F002007B50023024601210DF107004A +:101580008DF80730FFF7CEFF20B19DF8070003B0BC +:101590005DF804FB4FF0FF30F9E700000A4608B59C +:1015A0000421FFF7BFFF80F00100C0B2404208BD38 +:1015B00030B4074B0A461978064B53F8214023688C +:1015C000DD69054B0146AC46204630BC604700BF94 +:1015D000644F00201C230020A086010070B503F09A +:1015E000B7FB094E094D30800024286833888342B8 +:1015F00008D903F0A9FB2B6804440133B4F5F04F7C +:101600002B60F2D370BD00BF664F0020204F00203A +:1016100003F050BC00F1006000F5E040D0F8000895 +:101620007047000000F10060920000F5F04003F008 +:10163000CBBB0000054B1A68054B1B889B1A8342E5 +:1016400002D9104403F080BB00207047204F0020D7 +:10165000664F0020024B1B68184403F07BBB00BFA1 +:10166000204F0020024B1B68184403F085BB00BFCD +:10167000204F00200020704700F10050A0F51040DE +:10168000D0F8900570470000064991F8243033B136 +:101690000023086A81F824300822FFF7C3BF012025 +:1016A000704700BF244F0020014B1868704700BFEF +:1016B000002004E030B50F4B0F4C1B682288C3F3A9 +:1016C0000B030138934208440BD164680A46013C7D +:1016D000824213460BD214F9015F2DB102F8015B6F +:1016E000F6E781420B4602D22C2203F8012B581A4E +:1016F00030BD00BF002004E020230020022802BFEC +:101700004FF0904310229A6170470000022802BFF8 +:101710004FF090434FF480129A617047022801BF46 +:101720004FF09042536983F01003536170470000FB +:1017300010B50023934203D0CC5CC4540133F9E7C5 +:1017400010BD000003460246D01A12F9011B002901 +:10175000FAD1704702440346934202D003F8011BBA +:10176000FAE770472DE9F8431F4D144695F82420F9 +:101770000746884652BBDFF870909CB395F824303A +:101780002BB92022FF2148462F62FFF7E3FF95F88F +:101790002400C0F10802A24228BF2246D6B2414628 +:1017A000920005EB8000FFF7C3FF95F82430A41BDF +:1017B0001E44F6B2082E17449044E4B285F8246023 +:1017C000DBD1FFF761FF0028D7D108E02B6A03EBDC +:1017D00082038342CFD0FFF757FF0028CBD10020F0 +:1017E000BDE8F8830120FBE7244F0020024B1A7864 +:1017F000024B1A70704700BF644F0020182300206E +:1018000003494FF4E1330B60024B186802F0D4BF78 +:101810004C4F00201C230020094B10B51822044611 +:1018200000211846FFF796FF064A074B127804601E +:101830000146BDE8104053F8220002F0BDBF00BFD2 +:101840004C4F0020644F00201C2300202DE9F0475E +:101850000D46044600219046284640F27912FFF7D3 +:1018600079FF234620220021284601F0D1FF231DC5 +:1018700002222021284601F0CBFF631D03222221F2 +:10188000284601F0C5FFA31D03222521284601F0AB +:10189000BFFF04F1080310222821284601F0B8FFF9 +:1018A00004F1100308223821284601F0B1FF04F1A9 +:1018B000110308224021284601F0AAFF04F1120377 +:1018C00008224821284601F0A3FF04F11403202236 +:1018D0005021284601F09CFF04F11803402270219A +:1018E000284601F095FF04F120030822B021284684 +:1018F00001F08EFF04F121030822B821284601F0EF +:1019000087FF04F12207C0263B46314608222846BD +:10191000083601F07DFFB6F5A07F07F10107F3D18E +:1019200004F1320308223146284601F071FF0027F6 +:1019300004F1330A94F832304FEAC7099F4209F59F +:10194000A47615D3B8F1000F08D1314604F5997388 +:101950000722284601F05CFF09F24F16274694F84B +:1019600032213B1B93420CD3F01DC008BDE8F08729 +:101970000AEB070308223146284601F049FF0137E8 +:10198000D8E707F2331331460822284601F040FF1A +:1019900008360137E3E7000013B504460846002186 +:1019A00001602346C0F803102022019001F030FFAF +:1019B0000198231D0222202101F02AFF0198631DB6 +:1019C0000322222101F024FF0198A31D03222521D7 +:1019D00001F01EFF019804F108031022282101F0F4 +:1019E00017FF072002B010BDF7B50023047F009158 +:1019F0000E4607221946054601F0CEFD731C0093E2 +:101A0000012200230721284601F0C6FDC4B9B31CFA +:101A10000093052223460821284601F0BDFD0D2430 +:101A20003746B278BB1B934211D32B7FA88A073469 +:101A3000E408BBB9844294BF0020012003B0F0BD8C +:101A4000AB8ADB00083BDB08B3700824E8E7FB1C2B +:101A50000093214600230822284601F09DFD08340A +:101A60000137DEE7201A18BF0120E7E7F7B50023AA +:101A7000047F00910E4608221946054601F08CFDB0 +:101A8000731CC4B90822009311462346284601F06E +:101A900083FD1024012372785F1C013B934211D314 +:101AA0002B7FA88A0734E408BBB9844294BF002086 +:101AB000012003B0F0BDAB8ADB00083BDB0873708C +:101AC0000824E7E7F319009321460023082228465B +:101AD00001F062FD08343B46DDE7201A18BF012003 +:101AE000E7E70000F8B50E460546144600218122BE +:101AF0003046FFF72FFE2B4608220021304601F02A +:101B000087FE7CB96B1C07220821304601F080FE5D +:101B10000F2401236A785F1C013B934204D3E01D2C +:101B2000C008F8BD0824F4E7EB1921460822304626 +:101B300001F06EFE08343B46ECE70000F8B50E46B7 +:101B4000054614460021CE223046FFF703FE2B4601 +:101B500028220021304601F05BFE7CB905F1080324 +:101B600008222821304601F053FE30242F462A7ADD +:101B70007B1B934204D3E01DC008F8BD2824F5E781 +:101B800007F1090321460822304601F041FE0834DE +:101B90000137ECE7F7B5047F00910E4601231022D0 +:101BA0000021054601F0F8FCC4B9B31C00930922DA +:101BB00023461021284601F0EFFC1924374672888D +:101BC000BB1B9A4211D82B7FA88A0734E408BBB903 +:101BD000844294BF0020012003B0F0BDAB8ADB003B +:101BE000103BDB0873801024E8E73B1D009321467F +:101BF00000230822284601F0CFFC08340137DEE735 +:101C0000201A18BF0120E7E730B5094D0A44914278 +:101C10000DD011F8013B5840082340F30004013B6C +:101C20002C4013F0FF0384EA5000F6D1EFE730BDFB +:101C30002083B8EDF7B5384A106851686B4603C386 +:101C40006A4636493648082303F0ACFB04460028B0 +:101C500033D10A25334A106851686B4603C36A467C +:101C600031492F48082303F09DFB0446002849D042 +:101C70000369B3F5623F45D8B0F8661040F21142EF +:101C800091423FD1294A024402F15C018B4239D38F +:101C90005C3B234900209E1AFFF7B6FF32460746F9 +:101CA00004F164010020FFF7AFFFA3689F4229D130 +:101CB000E368984208BF002524E00369B3F5623F5A +:101CC00027D8418B40F21142914220D1174A024459 +:101CD00002F110018B4218D3103B114900209D1ACC +:101CE000FFF792FF2A46064604F118010020FFF78D +:101CF0008BFFA3689E4202D1E368984201D00D2574 +:101D0000A8E70025284603B0F0BD1025A2E70C2562 +:101D1000A0E70B259EE700BF20540008DC870300E6 +:101D20000078000829540008908703000888FFF70E +:101D300010B5037C044613B9006803F01BFB204672 +:101D400010BD00000023BFF35B8FC360BFF35B8F48 +:101D5000BFF35B8F8360BFF35B8F7047BFF35B8F15 +:101D60000068BFF35B8F704770B505460C30FFF716 +:101D7000F5FF05F1080604463046FFF7EFFFA042E5 +:101D800006D930466D68FFF7E9FF2544281A70BD73 +:101D90003046FFF7E3FF201AF9E7000070B505466B +:101DA000406898B105F10800FFF7D8FF05F10C066F +:101DB00004463046FFF7D2FF8442304694BF6D6838 +:101DC0000025FFF7CBFF013C2C44201A70BD00001A +:101DD00038B50C460546FFF7C7FFA04210D305F102 +:101DE0000800FFF7BBFF04446868B4FBF0F100FB98 +:101DF0001144BFF35B8F0120AC60BFF35B8F38BD34 +:101E00000020FCE72DE9F041144607460D46FFF798 +:101E1000C5FF844228BF0446D4B1B84658F80C6BBD +:101E20004046FFF79BFF3044286040467E68FFF73E +:101E300095FF331A9C4203D86C600120BDE8F08105 +:101E40006B60A41B3B68AB602044E8600220F5E7B0 +:101E50002046F3E738B50C460546FFF79FFFA04242 +:101E600010D305F10C00FFF779FF04446868B4FB58 +:101E7000F0F100FB1144BFF35B8F0120EC60BFF376 +:101E80005B8F38BD0020FCE72DE9FF41884669469D +:101E90000746FFF7B7FF6C4606B204EBC6060025FF +:101EA000B44209D06268206808EB0501FFF740FCE6 +:101EB000636808341D44F3E729463846FFF7CAFF34 +:101EC000284604B0BDE8F081F8B505460C300F4651 +:101ED000FFF744FF05F1080604463046FFF73EFFD2 +:101EE000A042304688BF6C68FFF738FF201A386080 +:101EF00020B130462C68FFF731FF2044F8BD0000C8 +:101F000073B5144606460D46FFF72EFF844228BFE0 +:101F100004460190DCB101A93046FFF7D5FF019BD3 +:101F200033B93268C5E90233C5E9002401200CE069 +:101F30009C4238BF01942860019868608442F5D9BA +:101F40003368AB60241AEC60022002B070BD2046FA +:101F5000FBE700002DE9FF410F466946FFF7D0FF80 +:101F60006C4600B204EBC0050026AC4209D0D4F8A0 +:101F7000048054F8081BB8194246FFF7D9FB4644C1 +:101F8000F3E7304604B0BDE8F081000038B50546FF +:101F9000FFF7E0FF044601462846FFF719FF2046F9 +:101FA00038BD00007047000010B413460268146882 +:101FB0000022A4465DF8044B6047000000F5805005 +:101FC00090F859047047000000F5805090F85204D2 +:101FD0007047000000F5805090F9580470470000E9 +:101FE00050207047302383F3118800F58052D2F8D7 +:101FF0009C34D2F898041844D2F894341844D2F897 +:102000007C341844D2F88C341844D2F888341844FC +:10201000002383F31188704700F58050C0F85414F2 +:102020000120704738B5C26A936923F001039361B8 +:10203000044600F07FFE0546E36A9B69DB0706D590 +:1020400000F078FE431BFA2BF6D9002004E004F5DB +:102050008054012084F8520438BD00002DE9F04F6F +:102060000C4600F5805185B01F4691F85234BDF8FA +:102070003890054690469BB1D1F878340133C1F8C9 +:1020800078342368980006D4237B082B0BD9627B15 +:102090000AB10F2B07D9D1F87C340133C1F87C3455 +:1020A0004FF0FF3010E0302383F31188EB6AD3F850 +:1020B000C42012F4001B0AD0D1F880340133C1F8D7 +:1020C0008034002080F3118805B0BDE8F08FD3F88C +:1020D000C4302068C3F3014A6B6A4822002812FB0F +:1020E0000A33B4BF40F08040800418602268520078 +:1020F00044BF40F000501860207B4FEA0A6242EA79 +:1021000000425A60607B4FEA4A1610B342F4401214 +:102110005A60D1F8B0240132C1F8B024AA1902F5EE +:102120008352117B41F020011173207B039300F057 +:102130005DFE039B033080105FFA8BF282420BF14D +:10214000010B0DDA04EB820103EB82024968916016 +:10215000F2E7AA1902F58352117B60F34511E3E718 +:10216000EB6A012202FA0AF2C3F8CC2005EB4A110D +:10217000AB1903F5825301F58251C3E90487183185 +:10218000234604F10C0253F8040B41F8040B93426C +:10219000F9D11B880B802E4441F2680346F803A056 +:1021A00006F5805609F0030396F86C2043F01003FF +:1021B00022F01F02134386F86C30002383F311884A +:1021C000CDF8009042463B462146284600F0D4FD1B +:1021D000012079E713B500F580540191606CFFF799 +:1021E000DDFD1F280AD90199606C2022FFF74CFE03 +:1021F000A0F120035842584102B010BD0020FBE777 +:1022000008B5302383F3118800F58050406CFFF748 +:1022100099FD002383F3118808BD000000220260AD +:10222000828142608260704710B500220023C0E9BD +:1022300000230023044603810C30FFF7EFFF204604 +:1022400010BD00002DE9F0479A4688B00746884641 +:102250009146302383F3118807F580546846FFF7D1 +:10226000E3FF606CFFF780FD1F282DD9606C2022F2 +:102270006946FFF78BFE202826D194F852341BB311 +:1022800003AD444605AB2E4603CE9E4220606160FE +:10229000354604F10804F6D130682060B388A38085 +:1022A000DDE90023C9E90023BDF80830AAF80030B1 +:1022B000002383F3118853464A464146384608B006 +:1022C000BDE8F04700F046BD002080F3118808B05B +:1022D000BDE8F0872DE9F84F00230646C0E9013339 +:1022E000284B46F8303B00F5815405468846374672 +:1022F000103438462037FFF797FFA742F9D105F58C +:1023000080544FF4805326630026C4E90D36676479 +:10231000012305F5835705F5A359E66384F840309A +:1023200084F84830103709F110094FF0000A4FF0D7 +:10233000000B47E908ABA7F11800FFF76FFF203744 +:1023400047F8286C4F45F4D184F85884A4F85A64AF +:10235000A4F85C64A4F85E6484F86064A4F8626421 +:10236000A4F86464A4F8666484F86864B8F1000FA3 +:1023700002D0054800F0D8FC044BEB622846BDE8CB +:10238000F88F00BF50540008345400080064004027 +:1023900010B5044B197804464A1C1A70FFF79AFFCF +:1023A000204610BD6D4F00202DE9F84315460C4620 +:1023B00000295CD0022001F027FF2E49B0FBF4F782 +:1023C0008C428CBF0A2111214B1EB7FBF1F601FB99 +:1023D0001671DAB221B1022B1946F5D8002032E08D +:1023E000731EB3F5806FF9D2C2EBC20808F1030186 +:1023F0004FEAE10EC1F3C701A2EB010C0EF1010996 +:102400004FF47A735FFA8CF70EFB033E59FA8CFC9B +:10241000BEFBFCFCBCF5617F17DC1FFA8CF34A1C89 +:1024200057FA82F27243B0FBF2F08442D6D14A1ED0 +:102430000F2AD3D87A1E072AD0D801202B806E808D +:1024400028716971AF71BDE8F88308F1FF314FEA77 +:10245000E10CC1F3C701521A0CF1010ED7B20CFB0B +:1024600003335EFA82F2B3FBF2F39BB2D7E708467E +:10247000E9E700BF3F420F0030B50D4B0D4D052081 +:102480001C786C438C420ED15978518099785171E7 +:10249000D9789171197911715B7903EB83035B0032 +:1024A0001380012030BD013803F10603E8D1F9E7BC +:1024B0009054000840420F000B4B10B54FF454727B +:1024C000044600211846FFF745F9084BA361403345 +:1024D000E361D8332362F0336362E36A6061002210 +:1024E000C3F8C02010BD00BF00A4004070A400408D +:1024F0002DE9F04F00F580551F4695F85834012B13 +:1025000089B004468946904604D90026304609B071 +:10251000BDE8F08F9A4A52F8231009B942F8230017 +:102520009848C4F80C900178277499B9302383F344 +:102530001188954B9A6D42F000729A659A6B42F041 +:1025400000729A639A6B22F000729A6301230370FF +:1025500081F3118895F851647EB9302383F3118893 +:102560000321152001F072FF0321162001F06EFFF8 +:10257000012385F8513486F31188302383F31188C1 +:10258000E26A936923F01003936100F0D3FB824663 +:10259000E36A9E6916F0080609D000F0CBFBA0EBB9 +:1025A0000A03FA2BF4D9002686F31188AEE79A695C +:1025B00042F001029A6100F0BDFB8246E36A9A692B +:1025C000D00706D400F0B6FBA0EB0A03FA2BF5D92E +:1025D000E9E79A6942F002029A61E36A4FF0000A61 +:1025E000C3F854A08AF31188686CFFF7ABFB04F5BD +:1025F000825B0BF1100B202200216846FFF7AAF83E +:1026000002A8FFF70BFECDF818A06A460BEB0603F5 +:102610000DF1180E9446BCE80300F44518605960AB +:10262000624603F10803F5D1DCF80000186020369B +:102630009CF804201A71B6F5806FDCD1002304F5F4 +:10264000A25285F8503485F853341A324946204650 +:10265000FFF7AAFE064690B9E26A936923F00103E8 +:10266000936100F067FB0546E36A9B69D9077FF534 +:102670004CAF00F05FFB431BFA2BF5D945E795F80B +:102680005E34C5F86C94591E95F85F34E26A013BDC +:102690001B0243EA416395F8601401390B43B5F816 +:1026A0005C14013943EA0143D361B8F1000F36D01D +:1026B00004F5A352023241462046FFF7DDFE90B9F1 +:1026C000E26A936923F00103936100F033FB05464E +:1026D000E36A9B69DA077FF518AF00F02BFB431B19 +:1026E000FA2BF5D911E795F86724C5F87084511EC7 +:1026F00095F86824E36A013A120142EA012295F84A +:10270000661401390A43B5F86414013942EA0142FA +:1027100042F40002DA60E36A4FF420629A642046D1 +:10272000FFF7CAFE002385F85934E36A6FF0404290 +:102730001A65E36A154A5A65E36A44229A65E36AB0 +:102740000722C3F8DC20E36A03229742DA653FF4EC +:10275000DDAEE26A936923F00103936100F0EAFAC7 +:102760000746E36A9B69DB0705D500F0E3FAC31B64 +:10277000FA2BF6D9C9E6012385F85234C6E600BF24 +:10278000684F00206C4F0020001002409B000800A2 +:102790002DE9F04F054689B090469946002741F251 +:1027A000680A00F58056EB6AD3F8D430FB40D807AE +:1027B00051D505EB471252444FEA471B13791907CD +:1027C00049D4D6F884340133C6F8843405F5A553CA +:1027D000C3E9008913799A0648BFD6F8B43405EBEB +:1027E0000B0248BF0133524448BFC6F8B4341379D2 +:1027F00043F008031371DB0722D596F85334FBB17D +:1028000005F58254183468465C44FFF70DFD03ABB0 +:1028100004F1080C206861681A4603C20834644554 +:102820001346F7D120681060A2889A800123ADF882 +:1028300008302B68CDE90089DB6B6946284698474C +:10284000D6F8A834D6F854040133C6F8A83410B129 +:1028500003681B6998470137202FA4D109B0BDE850 +:10286000F08F00002DE9F04F8DB004460F4600F0C8 +:1028700063FA82468946002F56D1E36AD3F8902046 +:10288000920141BF04F58051D1F898240132C1F87A +:102890009824D3F89020160703D100200DB0BDE88E +:1028A000F08FD3F89050E669C5F30125482303FB68 +:1028B0000566E8464046FFF7B1FC326851004ABF62 +:1028C00022F06043C2F38A4343F00043920048BFC2 +:1028D00043F080430093736813F400131FBF04F5A3 +:1028E000805201238DF80D30D2F8B8340EBF8DF828 +:1028F0000D300133C2F8B834F38803F00F038DF8BC +:102900000C304FF0000B9DF80C0000F06FFA5FFAEE +:102910008BF3984220D9F2180CA90B44127A03F8D1 +:102920002C2C0BF1010BEEE7012FB6D1E36AD3F8A3 +:102930009820950141BF04F58051D1F898240132C7 +:10294000C1F89824D3F898201007A6D0D3F898504F +:10295000266AC5F30125A9E7EFB9E36AC3F89450E5 +:1029600004A8FFF761FC98E80F0007AD07C52B80AE +:102970000023ADF8183023682046CDE904A9DB6BAD +:1029800004A9984704F5805458B1D4F89034013321 +:10299000C4F8903482E7012F04BFE36AC3F89C5067 +:1029A000DEE7D4F894340133C4F89434012075E799 +:1029B0002DE9F04105460F4600F5805401263946C1 +:1029C0002846FFF74FFF10B184F85364F7E7D4F8B7 +:1029D000A834D4F854040133C4F8A83420B10368EF +:1029E000BDE8F0411B691847BDE8F081F0B5C36A46 +:1029F0001A6C12F47F0F2BD000F580541B6CC4F8B6 +:102A0000AC3441F26805002347194FF0010C00EB8C +:102A100043122A445E01117911F0020F15D04907C3 +:102A200013D4B959C66AD6F8C8E00CFA01F111EA14 +:102A30000E0F0AD0C6F8D010117941F004011171BF +:102A4000D4F88C240132C4F88C240133202BDED13D +:102A5000F0BD000010B5254C254B226802B338B3F9 +:102A60001A6D12060ED580221A6500F065F950EA3B +:102A700001020B4602D0013861F1000302462068D2 +:102A8000FFF786FE1A4A136D1B032AD523684FF4FD +:102A9000002103F580531165012283F8592420E0B9 +:102AA00001221A6508221A654FF480621A6510BD6A +:102AB000196DC80702D4196D890705D50321196559 +:102AC00010460021FFF774FF094B1A6D100702D45E +:102AD0001A6DD10605D518221A6520680121FFF765 +:102AE00067FF2068BDE81040FFF780BF684F0020F7 +:102AF0000064004008B5302383F31188FFF776FFA8 +:102B0000002383F3118808BDC36AD3F8C40080F49E +:102B10000010C0F34050704708B5302383F311888C +:102B200000F58050406CFFF71FF9002383F31188F4 +:102B300043090CBF0120002008BD000000F58053B0 +:102B400093F8592462B1C16A8A6922F001028A614C +:102B5000D3F89C240132C3F89C24002283F8592422 +:102B6000704700002DE9F743302181F3118800F50B +:102B700082511031002541F2680E4FF0010800F536 +:102B8000805C00EB45147444267977071CD4F60664 +:102B90001AD5D0F82C908E69D9F8C87008FA06F6C4 +:102BA0003E4211D04F6801970F689742019F9F41A5 +:102BB0000AD2C9F8D060267946F004062671DCF8FE +:102BC00088440134CCF888440135202D01F12001DE +:102BD000D7D1002383F3118803B0BDE8F083000050 +:102BE000F8B51E46002313700F4605461446FFF73E +:102BF00093FF80F0010038701EB12846FFF784FF74 +:102C00002070F8BD2DE9F04F85B09946DDE90EA39F +:102C10000D4602931378019391F800B08046164652 +:102C200000F08AF82B7804460F4613B93378002B4E +:102C300041D022463B464046FFF794FFFFF75AFF3C +:102C4000FFF77CFF4B4632462946FFF7C9FF2B783A +:102C500033B1BBF1000F03D0012005B0BDE8F08F08 +:102C6000337813B1019B002BF6D108F58053039301 +:102C7000029B544577EB03031DD2039BD3F8540406 +:102C8000C8B10368AAEB04011B6898474B4632465B +:102C900029464046FFF7A4FF2B7813B1BBF1000F84 +:102CA000DAD1337813B1019B002BD5D100F044F871 +:102CB00004460F46DCE70020CFE7000008B50020FF +:102CC000FFF7C8FEBDE8084001F050B808B5012084 +:102CD000FFF7C0FEBDE8084001F048B800B59BB062 +:102CE000EFF3098168226846FEF722FDEFF30583C2 +:102CF000014B9B6BFEE700BF00ED00E008B5FFF75E +:102D0000EDFF000000B59BB0EFF309816822684633 +:102D1000FEF70EFDEFF30583014B5B6BFEE700BF93 +:102D200000ED00E0FEE700000FB408B5029801F0E6 +:102D300007FEFEE702F004B902F0E6B813B56C46F0 +:102D400084E80600031D94E8030083E805000120E1 +:102D500002B010BD73B58568019155B11B885B0742 +:102D600007D4D0E900369B6B9847019AC1B2304630 +:102D7000A847012002B070BDF0B5866889B005464D +:102D80000C465EB1BDF838305B070AD4D0E9003795 +:102D90009B6B98472246C1B23846B047012009B024 +:102DA000F0BD00220023CDE900230023ADF8083058 +:102DB0000A4603AB01F10806106851681C4603C4BB +:102DC0000832B2422346F7D1106820609288A28070 +:102DD000FFF7B2FF0423ADF808302B68CDE90001FE +:102DE000DB6B694628469847D8E70000082817D9C2 +:102DF00009280CD00A280CD00B280CD00C280CD099 +:102E00000D280CD00E2814BF4020302070470C2015 +:102E100070471020704714207047182070472020FA +:102E2000704700002DE9F041456A15B94162BDE8DF +:102E3000F0814B6823F06047C3F38A464FEAD37EA4 +:102E4000C3F3807816EA230638BF3E46AC462B46CD +:102E50005A68BEEBD27F22F060440AD0002A18DA0A +:102E6000A40CB44217D19D420FD10D60DEE713468A +:102E7000EEE7A74207D102F08044C2F380724245D8 +:102E80000BD054B1EFE708D2EDE7CCF800100B609F +:102E9000CDE7B44201D0B442E5D81A689C46002A76 +:102EA000E5D11960C3E700002DE9F047089D01F066 +:102EB00007044FEAD508224405F0070500EBD100CE +:102EC0004FF47F49944201D1BDE8F08704F0070731 +:102ED00005F0070A57453E4638BF5646C6F1080674 +:102EE000111B8E4228BF0E46E10808EBD50E415C4F +:102EF00013F80EC0B94029FA06F721FA0AF1FFB219 +:102F00008CEA010147FA0AF739408CEA010C03F810 +:102F10000EC034443544D5E780EA0120082341F24D +:102F2000210201B24000002980B203F1FF33B8BF93 +:102F3000504013F0FF03F4D17047000038B50C4641 +:102F40008D18A54200D138BD14F8011BFFF7E4FF2E +:102F5000F7E7000042684AB11368436043898189FA +:102F600001339BB29942438138BF83811046704739 +:102F700070B588B0202204460D4668460021FEF751 +:102F8000E9FB20460495FFF7E5FF024658B16B4682 +:102F9000054608AE1C4603CCB4422860696023464F +:102FA00005F10805F6D1104608B070BD082817D9FC +:102FB00009280CD00A280CD00B280CD00C280CD0D7 +:102FC0000D280CD00E2814BF4020302070470C2054 +:102FD0007047102070471420704718207047202039 +:102FE00070470000082817D90C280CD910280CD9D4 +:102FF00014280CD918280CD920280CD930288CBFBB +:103000000F200E207047092070470A2070470B20C0 +:1030100070470C2070470D20704700002DE9F843E1 +:10302000078C072F04461ED9D0E9029800254FF6D9 +:10303000FF73C5F12006A5F1200029FA05F108FA71 +:1030400006F628FA00F031430143C9B21846FFF7EB +:1030500063FF0835402D0346EBD1E1693A46BDE8F0 +:10306000F843FFF76BBF4FF6FF70BDE8F883000031 +:1030700010B54B6823B9CA8A63F30902CA8210BD2E +:1030800004691A681C600361C38A013BC3824A60F9 +:10309000EFE700002DE9F84F1D46CB8A0F46C3F33A +:1030A00009010529814692460B4630D00020AAB27C +:1030B00007F11A049EB2042E1FFA80F80FD890452B +:1030C00003F1010306D3FB8A0A4462F30903FB827E +:1030D00001201AE01AF80060E6540130EAE7904552 +:1030E000F1D2A1F1050B1C237C68BBFBF3F203FBBF +:1030F00012BB1FFA8BF6002C45D14846FFF72AFF7A +:10310000044638B978606FF00200BDE8F88F4FF0E0 +:103110000008E6E7002606607860ADB24FF0000BCD +:10312000454510D90AEB0803221D13F8011B9155E0 +:10313000B1B208F101081B291FFA88F82BD04545C8 +:1031400006F10106F1D8FB8AC3F30902154465F3C1 +:103150000903BCE7013292B21C462368002BF9D167 +:103160006B1F0B441C21B3FBF1F301339BB29A425A +:10317000D3D2BBF1000FD0D14846FFF7EBFE20B908 +:10318000C4F800B0BFE70122E7E7C0F800B05E4630 +:1031900020600446C1E74545D5D94846FFF7DAFE29 +:1031A00008B92060AFE7C0F800B0002620600446F0 +:1031B000B6E700002DE9F04F2DED028B1C4683B0E1 +:1031C0005B69019207468846002B00F09A80238CA9 +:1031D0002BB1E269002A00F09480072B35D807F163 +:1031E0000C00FFF7B7FE054638B96FF00205284618 +:1031F00003B0BDEC028BBDE8F08F14220021FEF776 +:10320000A9FA228CE16905F10800FEF791FA208CF9 +:10321000013080B2FFF7E6FEFFF7C8FE013880B24A +:103220002084013028746369228C1B782A4403F0BF +:103230001F0363F03F0348F0004113723846696092 +:103240002946FFF7EFFD0125D1E700F10C034FF010 +:10325000000908EE103A4FF0800A4E464D4618EE2F +:10326000100AFFF777FE83460028BED01422002103 +:10327000FEF770FA002E3AD1019BABF8083002221B +:103280000BF1080E1FFA82FC0CF10100BCF1060FD5 +:10329000218C80B201D88E422BD3FFF7A3FEFFF71B +:1032A00085FE62691278013802F01F028E4208BF63 +:1032B0004FF0400A42EA49121BFA80F14AEA020A38 +:1032C000013048F0004281F808A08BF81000CBF8DC +:1032D000042059463846FFF7A5FD238C0135B3423B +:1032E0002DB289F001094FF0000AB8D17FE7002222 +:1032F000C6E7E169895D0EF802100136B6B2013207 +:10330000C0E76FF0010572E7F8B515460E463022AA +:10331000002104461F46FEF71DFA069B6360B5F5C3 +:10332000001F079BA76034BF6A094FF6FF72A362B4 +:1033300097B2E66104F1100000239A4206D80023F8 +:103340000360A782E3822383E360F8BD0660013354 +:1033500030462036F1E7000003781BB94BB2002B52 +:10336000C8BF01707047000000787047F8B50C4680 +:10337000C969074611B9238C002B37D1257E1F2D33 +:1033800034D8387828BB228C072A2CD8268A36F0E5 +:1033900003032BD14FF6FF70FFF7D0FD20F00100A3 +:1033A0003102400441EA0561400C41EA40254FF6F4 +:1033B000FF72234629463846FFF7FCFE002807DD4A +:1033C000626913780133DBB21F2B88BF00231370AF +:1033D000F8BD218A2D0645EA012505432046FFF761 +:1033E0001DFE0246E5E76FF00300F1E76FF0010014 +:1033F000EEE7000070B58AB0044616460021282288 +:1034000068461D46FEF7A6F9BDF83830ADF8103015 +:103410000F9B05939DF840308DF81830119B079352 +:103420006946BDF84830ADF820302046CDE9026548 +:10343000FFF79CFF0AB070BD2DE9F041D369054646 +:103440000C4616460BB9138C5BBB377E1F2F28D852 +:1034500095F80080B8F1000F26D03046FFF7DEFD6A +:103460003378210241EAC33141EA0801338A41EA53 +:10347000076141EA03410246334641F08001284694 +:10348000FFF798FE00280ADD3378012B07D1726917 +:1034900013780133DBB21F2B88BF00231370BDE804 +:1034A000F0816FF00100FAE76FF00300F7E700002A +:1034B000F0B58BB004460D46174600212822684619 +:1034C0001E46FEF747F99DF84C305A1E53425341B1 +:1034D0008DF800309DF84030ADF81030119B059309 +:1034E0009DF848308DF81830149B07936A46BDF854 +:1034F0005430ADF8203029462046CDE90276FFF75A +:103500009BFF0BB0F0BD0000406A00B10430704773 +:10351000436A1A68426202691A600361C38A013B06 +:10352000C38270472DE9F041D0F82080194E14462F +:103530001D464146002709B9BDE8F081D1E90223C3 +:10354000A21A65EB0303964277EB03031ED2036ACC +:103550008B420DD1FFF78CFD036A1B680362036980 +:103560000B60C38A0161016A013BC3828846E2E7BE +:10357000FFF77EFD0B68C8F8003003690B60C38A53 +:103580000161013BC382D8F80010D4E7884609687E +:10359000D1E700BF80841E002DE9F04F8BB00D46AF +:1035A000DDF8509014469B468046002800F01981B3 +:1035B000B9F1000F00F01581531E3F2B00F211816D +:1035C000012A03D1BBF1000F40F00B810023CDE9AC +:1035D0000833B8F81430B5EBC30F4FEAC30703D371 +:1035E00000200BB0BDE8F08F2B199F42D8F80C30AB +:1035F0003ABF7F1BFFB227461BB9D8F81030002B0B +:103600007AD0272D4ED8C5F12806B7424FF00003D7 +:103610002CBFF6B23E4600932946D8F8080008AB06 +:103620003246FFF741FCA7EB060A35445FFA8AFAF7 +:10363000B8F8143003F10053053BDB000493D8F8CD +:103640000C3003932821039B13B1BAF1000F2CD146 +:10365000D8F8100040B1BAF1000F05D0009608ABC1 +:103660005246691AFFF720FC38B2002FB8D066071F +:103670000AD00AAB03EBD401624211F8083C02F015 +:103680000702134101F8083C082C3CD9102C40F2E9 +:10369000B580202C40F2B780BBF1000F00F09C8079 +:1036A000082334E0BA460026C2E7049BE02B28BF7B +:1036B000E02306930B44AB42059314D95A1B03989D +:1036C0000096924534BF5246D2B2691A08AB043014 +:1036D0000792FFF7E9FB079A1644AAEB020A154482 +:1036E000F6B25FFA8AFA049B069A05999B1A04932C +:1036F000039B1B680393A6E70093D8F8080008AB68 +:103700003A462946AEE7BBF1000F13D00123B4EBD4 +:10371000C30F6CD0082C12D89DF82030621E23FAFB +:1037200002F2D50706D54FF0FF3202FA04F4234324 +:103730008DF820309DF8203089F8003051E7102CAA +:1037400012D8BDF82030621E23FA02F2D10706D546 +:103750004FF0FF3202FA04F42343ADF82030BDF8F5 +:103760002030A9F800303CE7202C0FD80899631EC0 +:1037700021FA03F3DA0705D54FF0FF3202FA04F419 +:103780000C430894089BC9F800302AE7402C2BD042 +:10379000DDE90865611EC4F12102A4F1210326FAC6 +:1037A00001F105FA02F225FA03F311431943CB079D +:1037B00012D50122A4F12003C4F1200102FA03F37F +:1037C00022FA01F1A240524243EA010363EB4303B0 +:1037D00032432B43CDE90823DDE90823C9E900235F +:1037E000FFE66FF00100FCE66FF00800F9E6082C38 +:1037F000A0D9102CB3D9202CEED8C3E7BBF1000F11 +:10380000ADD0022383E7BBF1000FBBD004237EE7DA +:1038100030B5012A144638BF0124402C85B028BF9A +:1038200040240025012ACDE9025518D81B788DF8CF +:10383000083063070AD004AB03EBD405624215F8E5 +:10384000083C02F00702934005F8083C009103464B +:103850002246002102A8FFF727FB05B030BD082A49 +:10386000E4D9102A03D81B88ADF80830E1E7202AF4 +:103870008DBFD3E900231B680293CDE90223D8E76B +:1038800010B5CB681BB98B600B618B8210BD0469CE +:103890001A681C600361C38A013BC382CA60F0E7F7 +:1038A00003064CBFC0F3C0300220704708B5024683 +:1038B000FFF7F6FF022806D15306C2F30F2001D10D +:1038C00000F0030008BDC2F30740FBE72DE9F04F0D +:1038D00093B0CDE903230A6804461046FFF7E0FFE2 +:1038E000022814BFC2F306260026002A0D4682468F +:1038F00080F2F28112F0C04940F0EE81097B00298C +:1039000000F0EA81022803D02378B34240F0E78137 +:10391000C2F304630693104602F07F030593FFF79A +:10392000C5FF059B29444FEA834848EA0A4848EA0C +:103930004668CE7800230022CDE90823F3098346A8 +:1039400048EA0008029367D0059B00930246676827 +:10395000534608A92046B847002800F0C381276ACB +:103960004FB9414604F10C00FFF702FB074690B93E +:103970006FF0020054E03B6998450DD03F68002F7E +:10398000F9D1414604F10C00FFF7F2FA074600288E +:10399000EED0236A3B60276297F817C006F01F0835 +:1039A000CCF3840CACEB08001FFA80FE0028B8BFF3 +:1039B0000EF12000A8EB0C031FFA83FED7E90221C9 +:1039C000B8BF00B2002B0793BEBF0EF120031BB29D +:1039D000079352EA010338D0039BDFF824E39A1AD5 +:1039E000049B4FF0000C63EB010196457CEB010357 +:1039F0002BD36B7B97F81AE0734519D1029B002BF0 +:103A000078D0012821DC7868F8B9DFF8F0C2944555 +:103A100070EB010316D337E0276A27B96FF00C006B +:103A200013B0BDE8F08F3B699845B5D03F68F4E727 +:103A3000B24890427CEB010301D30020F0E7029BE7 +:103A4000002BFAD0079B0F2B17DCFA7DB30002F096 +:103A5000030203F07C031343FB7539462046FFF74E +:103A600007FB6B7BBB76029B3BB9FB7DC3F38402F8 +:103A7000013262F38603FB75D0E76A7BBB7E9A4214 +:103A8000DBD1029B002B35D0B309022B32D0039B34 +:103A9000BB60049BFB60142200210DA8FDF75AFEB9 +:103AA000039B0A93049B0B932B1D0C932B7BADF86C +:103AB0003EB0013BDBB2ADF83C30069B8DF84230A6 +:103AC000059B8DF8433094F82C308DF840A083F09E +:103AD00001038DF844308DF84180A3680AA920467F +:103AE0009847FB7DC3F38403013303F01F039B025C +:103AF000FB82A2E7FB7DC6F34012B2EBD31F40F07E +:103B0000F480C3F38403434540F0F280029A2B7B98 +:103B1000B609002A4DD0F2075DD4032B40F2EB80AA +:103B2000039BBB60049BFB602B7BAE1D033BDBB2A6 +:103B30003246394604F10C00FFF7ACFA00280CDAE3 +:103B400039462046FFF794FAFB7DC3F38403013323 +:103B500003F01F039B02FB820AE7DDE90884AB88C0 +:103B60003B834FF6FF73C9F12000A9F1200228FA28 +:103B700009F104FA00F0014324FA02F21143184655 +:103B8000C9B2FFF7C9F909F10809B9F1400F0346B5 +:103B9000E9D1B8822A7B033AD2B23146FFF7CEF997 +:103BA000FB7DB882DA43C2F3C01262F3C713FB7520 +:103BB00043E786B92E1D013BDBB23246394604F19C +:103BC0000C00FFF767FA0028BADB2A7BB88A013AB3 +:103BD000D2B23146E2E7F98AC1F30901013B042977 +:103BE000DAB25BD8281D002307F11B069A4208D9D8 +:103BF00010F801CB06F801C0013101330529DBB211 +:103C0000F4D103990A9104990B91934207F11B0196 +:103C10000C9138BF043379680D9134BF55FA83F3A2 +:103C200000230E93FB8AADF83EB0C3F309031A4498 +:103C3000069B8DF84230059B8DF8433094F82C306C +:103C4000ADF83C2083F001038DF8443000238DF85B +:103C500040A08DF841807B602A7BB88A013A291DFB +:103C6000FFF76CF93B8BB882834203D1A3680AA9A2 +:103C70002046984720460AA9FFF702FEFB7DBA8A34 +:103C8000C3F38403013303F01F039B02FB823B8BCE +:103C90009A420CBF00206FF01000C1E67B68002B39 +:103CA000AFD0052001E01C3033461E68002EFAD14B +:103CB000091A081D2E1D184401EB090CBCF11B0F3D +:103CC0005FFA89F39DD89A429BD916F8013B00F818 +:103CD000013B09F10109EFE76FF00900A0E66FF081 +:103CE0000A009DE66FF00B009AE66FF00D0097E674 +:103CF0006FF00E0094E66FF00F0091E640420F0067 +:103D000080841E00EFF3098305494A6B22F001020B +:103D10004A63683383F30988002383F3118870476B +:103D200000EF00E0302080F3118862B60C4B0D4AA2 +:103D3000D96821F4E0610904090C0A43DA60D3F878 +:103D4000FC20094942F08072C3F8FC200A6842F066 +:103D500001020A602022DA7783F82200704700BF50 +:103D600000ED00E00003FA05001000E010B530237C +:103D700083F311880E4B5B6813F4006314D0F1EEEB +:103D8000103AEFF30984683C4FF08073E361094B0C +:103D9000DB6B236684F3098800F09CFD10B1064BB1 +:103DA000A36110BD054BFBE783F31188F9E700BF62 +:103DB00000ED00E000EF00E03F03000842030008D0 +:103DC000026843681143016003B11847704700005F +:103DD000024A136843F0C003136070470038014083 +:103DE00013B50F4C204600F0DBFC04F114000D4924 +:103DF000009400234FF4807200F098FB0A490B4BAB +:103E000000944FF4807204F1380000F011FC084B6C +:103E1000E365002000F0F8F9206602B010BD00BF95 +:103E2000744F0020E04F0020E0500020D13D0008FA +:103E30000038014030B5037C234C002918BF0C46E4 +:103E4000012B0FD1214B98420CD1214B1A6E42F419 +:103E500080421A66D3F8802042F48042C3F8802062 +:103E6000D3F880302268036EC16D846603EB520381 +:103E7000B3FBF2F36268150442BF23F0070503F0B9 +:103E8000070343EA4503CB60A36843F040034B605C +:103E9000E36843F001038B6042F4967343F001033F +:103EA0000B604FF0FF330B62510505D512F0102265 +:103EB00005D0B2F1805F04D080F8643030BD7F233C +:103EC000FAE73F23F8E700BFB0540008744F002022 +:103ED000001002402DE9F047C66D3768F46934627E +:103EE0002107054619D014F0080118BF4FF480715E +:103EF000E20748BF41F02001A30748BF41F040015D +:103F0000600748BF41F08001302383F31188281DEA +:103F1000FFF756FF002383F31188E2050AD530230B +:103F200083F311884FF48061281DFFF749FF0023B8 +:103F300083F311884FF030094FF0000A14F0200885 +:103F400038D13B0616D54FF0300905F1380A200666 +:103F500010D589F31188504600F09EFB002836DA10 +:103F60000821281DFFF72CFF27F080033360002372 +:103F700083F31188790614D5620612D5302383F3B2 +:103F80001188D5E913239A4208D12B6C33B1102143 +:103F9000281D27F04007FFF713FF3760002383F346 +:103FA0001188E30618D5AA6E1369ABB1BDE8F047D6 +:103FB0005069184789F31188736A95F86410284688 +:103FC000194000F007FC8AF31188F469B6E7B06283 +:103FD00088F31188F469BAE7BDE8F087434B4FF4E2 +:103FE000007270B51A605A6912F4C06FFBD1404B71 +:103FF0009A6802F00C02042A20D01A6842F48072F7 +:104000001A601A685205FCD501229A609A6802F07B +:104010000C02042AFAD13749374A0A600A6812F0BA +:104020000F02FBD1C3F8982063221A601A68960326 +:10403000FCD42E4A4FF48071C2F88010C468E503A6 +:1040400006D51A6842F480321A601A689103FCD5CA +:10405000C269D20709D5D3F8982042F00102C3F80B +:104060009820D3F898209607FBD54269DA6044F48B +:1040700080721A6004F0807111B11A689501FBD545 +:10408000996802691B4E22F0030501F003012943E0 +:10409000996085693560316869400907FBD113492A +:1040A00005680D6046684E608068C1F880006E0447 +:1040B00017D448698505FCD4996802F0030021F003 +:1040C00003010143996092009968514011F00C0F6F +:1040D000FAD1E2055EBF1A6822F480721A600020ED +:1040E00070BD48698005FCD5E6E700BF0070004060 +:1040F00000100240002002400006040008B500F055 +:1041000091F9BDE8084000F065B9000010B5394CE0 +:104110003948A36A4FF0FF32A262A36A0023A36268 +:10412000A16AE16A61F07F01E162E16A01F07F0169 +:10413000E162E16A216B2263216B2363216BA16B36 +:10414000A263A16BA363A16BE16BE263E16BE36329 +:10415000E16B216C2264226C2364226C226E42F09B +:1041600001022266D4F8802022F00102C4F88020E7 +:10417000D4F88020A26D42F08052A265A26F22F096 +:104180008052A267A26F1D4A4FF400419160D36034 +:10419000136253629362D362136353639363D36373 +:1041A000136453649364D36413655365116841F4D5 +:1041B00080711160D4F8902012F4407F1EBF4FF43C +:1041C0008032C4F89020C4F890300D4A0023A360D8 +:1041D000C4F88820C4F89C30FFF700FF10B10948EC +:1041E00000F0AEFBD4F8903023F00323C4F89030F5 +:1041F00010BD00BF00100240D05400080070004005 +:1042000055010051C8540008014B53F82000704775 +:1042100028230020074A08B5536903F001035361BE +:1042200023B1054A13680BB150689847BDE80840B0 +:10423000FFF79CBD000401406C540020074A08B5FC +:10424000536903F00203536123B1054A93680BB12C +:10425000D0689847BDE80840FFF788BD00040140DA +:104260006C540020074A08B5536903F004035361F6 +:1042700023B1054A13690BB150699847BDE808405E +:10428000FFF774BD000401406C540020074A08B5D4 +:10429000536903F00803536123B1054A93690BB1D5 +:1042A000D0699847BDE80840FFF760BD00040140B1 +:1042B0006C540020074A08B5536903F0100353619A +:1042C00023B1054A136A0BB1506A9847BDE808400C +:1042D000FFF74CBD000401406C540020164B10B594 +:1042E0005C6904F478725A61A30604D5134A936A90 +:1042F0000BB1D06A9847600604D5104A136B0BB116 +:10430000506B9847210604D50C4A936B0BB1D06BC8 +:104310009847E20504D5094A136C0BB1506C9847D5 +:10432000A30504D5054A936C0BB1D06C9847BDE842 +:104330001040FFF71BBD00BF000401406C5400207B +:10434000194B10B55C6904F47C425A61620504D5CE +:10435000164A136D0BB1506D9847230504D5134AC7 +:10436000936D0BB1D06D9847E00404D50F4A136EDE +:104370000BB1506E9847A10404D50C4A936E0BB153 +:10438000D06E9847620404D5084A136F0BB1506F82 +:104390009847230404D5054A936F0BB1D06F984713 +:1043A000BDE81040FFF7E2BC000401406C5400205F +:1043B00008B50348FFF78EFDBDE80840FFF7D6BCFF +:1043C000744F002008B500F0D9FEBDE80840FFF7A3 +:1043D000CDBC0000062108B5084600F037F80621DC +:1043E000072000F033F80621082000F02FF80621FE +:1043F000092000F02BF806210A2000F027F80621FA +:10440000172000F023F80621282000F01FF80721CC +:104410001C2000F01BF8BDE808400C21252000F00E +:1044200015B800004FF0E023002258684FF0FF312C +:10443000930003F1604303F5614301329042C3F8F6 +:104440008010C3F88011F3D27047000000F1604380 +:1044500003F561430901C9B283F80013012200F09A +:104460001F039A4043099B0003F1604303F5614336 +:10447000C3F880211A607047F8B51546826806694E +:10448000AA420B46816938BF8568761AB542044650 +:104490000BD218462A46FDF74BF9A3692B44A361BA +:1044A000A3685B1BA3602846F8BD0CD918463246AA +:1044B000FDF73EF9AF1BE1683A463044FDF738F9A5 +:1044C000E3683B44EBE718462A46FDF731F9E36819 +:1044D000E5E7000083689342F7B51546044638BF08 +:1044E0008568D0E90460361AB5420BD22A46FDF73A +:1044F0001FF963692B446361A36828465B1BA360B3 +:1045000003B0F0BD0DD932460191FDF711F90199C3 +:10451000E068AF1B3A463144FDF70AF9E3683B44D3 +:10452000E9E72A46FDF704F9E368E4E710B50A4431 +:104530000024C361029B8460C0E90000C0E905114A +:10454000C1600261036210BD08B5D0E90532934233 +:1045500001D1826882B98268013282605A1C42614C +:104560001970D0E904329A4224BFC3684361002124 +:1045700000F052FA002008BD4FF0FF30FBE70000CA +:1045800070B5302304460E4683F31188A568A5B1A3 +:10459000A368A269013BA360531CA361157822693B +:1045A000934224BFE368A361E3690BB120469847B7 +:1045B000002383F31188284607E03146204600F0A7 +:1045C0001BFA0028E2DA85F3118870BD2DE9F74F58 +:1045D00004460E4617469846D0F81C904FF0300A15 +:1045E0008AF311884FF0000B154665B12A46314613 +:1045F0002046FFF741FF034660B94146204600F0E0 +:10460000FBF90028F1D0002383F31188781B03B055 +:10461000BDE8F08FB9F1000F03D001902046C847E4 +:10462000019B8BF31188ED1A1E448AF31188DCE795 +:10463000C0E90511C160C3611144009B8260C0E9FB +:104640000000016103627047F8B504460D46164646 +:10465000302383F31188A768A7B1A368013BA36047 +:1046600063695A1C62611D70D4E904329A4224BF06 +:10467000E3686361E3690BB120469847002080F34B +:10468000118807E03146204600F0B6F90028E2DA4A +:1046900087F31188F8BD0000D0E905239A4210B5D0 +:1046A00001D182687AB98268013282605A1C8261C3 +:1046B0001C7803699A4224BFC3688361002100F01B +:1046C000ABF9204610BD4FF0FF30FBE72DE9F74F67 +:1046D00004460E4617469846D0F81C904FF0300A14 +:1046E0008AF311884FF0000B154665B12A46314612 +:1046F0002046FFF7EFFE034660B94146204600F032 +:104700007BF90028F1D0002383F31188781B03B0D4 +:10471000BDE8F08FB9F1000F03D001902046C847E3 +:10472000019B8BF31188ED1A1E448AF31188DCE794 +:10473000026843681143016003B1184770470000E5 +:104740001430FFF743BF00004FF0FF331430FFF782 +:104750003DBF00003830FFF7B9BF00004FF0FF3316 +:104760003830FFF7B3BF00001430FFF709BF000077 +:104770004FF0FF311430FFF703BF00003830FFF770 +:1047800063BF00004FF0FF323830FFF75DBF00001D +:10479000012914BF6FF0130000207047FFF720BB02 +:1047A000044B03600023C0E9023343600123037418 +:1047B000704700BFF054000810B53023044683F35F +:1047C0001188FFF737FB02232374002080F3118840 +:1047D00010BD000038B5C36904460D461BB904215D +:1047E0000844FFF7A5FF294604F11400FFF7ACFECB +:1047F000002806DA201D4FF40061BDE83840FFF7BD +:1048000097BF38BD00230375826803691B689968E8 +:104810009142FBD25A680360426010605860704752 +:1048200000230375826803691B6899689142FBD86D +:104830005A680360426010605860704708B50846C7 +:10484000302383F311880B7D032B05D0042B0DD06F +:104850002BB983F3118808BD8B6900221A604FF0D1 +:10486000FF338361FFF7CEFF0023F2E7D1E9003287 +:1048700013605A60F3E70000FFF7C4BF054BD96827 +:104880000875186802681A60536001220275D860C2 +:10489000FBF740BDE051002030B50C4BDD684B1CF0 +:1048A00087B004460FD02B46094A684600F046F907 +:1048B0002046FFF7E3FF009B13B1684600F048F97C +:1048C000A86907B030BDFFF7D9FFF9E7E051002034 +:1048D0003D480008044B1A68DB6890689B68984262 +:1048E00094BF002001207047E0510020084B10B514 +:1048F0001C68D86822681A60536001222275DC6047 +:10490000FFF78EFF01462046BDE81040FBF702BDD1 +:10491000E051002038B5074C07490848012300251D +:104920002370656000F058FC0223237085F3118822 +:1049300038BD00BF485400201C550008E05100203D +:1049400008B572B6044B186500F0C8FA00F078FBA1 +:10495000024B03221A70FEE7E05100204854002069 +:1049600000F02CB98B60022308618B8208467047E7 +:104970008368A3F1840243F8142C026943F8442CA1 +:10498000426943F8402C094A43F8242CC26843F892 +:10499000182C022203F80C2C002203F80B2C044ADA +:1049A00043F8102CA3F12000704700BF2D0300082E +:1049B000E051002008B5FFF7DBFFBDE80840FFF736 +:1049C0005BBF0000024BDB6898610F20FFF756BF0A +:1049D000E0510020302383F31188FFF7F3BF00007C +:1049E00008B50146302383F311880820FFF754FFF0 +:1049F000002383F3118808BD064BDB6839B1426898 +:104A000018605A60136043600420FFF745BF4FF001 +:104A1000FF307047E05100200368984206D01A68C2 +:104A20000260506099611846FFF726BF704700008A +:104A300010B503689C68A2420CD85C688A600B6061 +:104A40004C602160596099688A1A9A604FF0FF3370 +:104A5000836010BD1B68121BECE700000A2938BFF9 +:104A60000A2170B504460D460A26601900F0AEFB17 +:104A700000F09AFB041BA54203D8751C2E46044681 +:104A8000F3E70A2E04D9BDE87040012000F0E4BB32 +:104A900070BD0000F8B5144B0D46D96103F110014B +:104AA00041600A2A1969826038BF0A2201604860A1 +:104AB0001861A818144600F07BFB0A2700F074FB6D +:104AC000431BA342064606D37C1C281900F07EFB3C +:104AD00027463546F2E70A2F04D9BDE8F840012001 +:104AE00000F0BABBF8BD00BFE0510020F8B50646A3 +:104AF0000D4600F059FB0F4A134653F8107F9F42B2 +:104B000006D12A4601463046BDE8F840FFF7C2BF4D +:104B1000D169BB68441A2C1928BF2C46A34202D97C +:104B20002946FFF79BFF224631460348BDE8F8407F +:104B3000FFF77EBFE0510020F051002010B4C0E923 +:104B4000032300235DF8044B4361FFF7CFBF000050 +:104B500010B5194C236998420DD0D0E90032816814 +:104B600013605A609A680A449A60002303604FF009 +:104B7000FF33A36110BD2346026843F8102F536032 +:104B80000022026022699A4203D1BDE8104000F081 +:104B900017BB936881680B44936000F005FB2269A2 +:104BA000E1699268441AA242E4D91144BDE8104078 +:104BB000091AFFF753BF00BFE05100202DE9F0476D +:104BC000DFF8BC8008F110072C4ED8F8105000F028 +:104BD000EBFAD8F81C40AA68031B9A423ED814444A +:104BE000D5E900324FF00009C8F81C4013605A6044 +:104BF000C5F80090D8F81030B34201D100F0E0FAC7 +:104C000089F31188D5E9033128469847302383F387 +:104C100011886B69002BD8D000F0C6FA6A69A0EB46 +:104C200004094A4582460DD2022000F015FB0022FD +:104C3000D8F81030B34208D151462846BDE8F047B5 +:104C4000FFF728BF121A2244F2E712EB090938BF16 +:104C50004A4629463846FFF7EBFEB5E7D8F810304C +:104C6000B34208D01444211AC8F81C00A960BDE85A +:104C7000F047FFF7F3BEBDE8F08700BFF05100201A +:104C8000E051002038B500F08FFA054AD2E9084516 +:104C9000031B181945F10001C2E9080138BD00BF26 +:104CA000E051002000207047FEE700007047000040 +:104CB0004FF0FF3070470000BFF34F8F024A136977 +:104CC000DB03FCD4704700BF0020024008B5094B4D +:104CD0001B7873B9FFF7F0FF074B5A69002ABFBF73 +:104CE000064A9A6002F188329A601A6822F4806259 +:104CF0001A6008BD6054002000200240230167456F +:104D000008B50B4B1B7893B9FFF7D6FF094B5A69CF +:104D100042F000425A611A6842F480521A601A68DE +:104D200022F480521A601A6842F480621A6008BD48 +:104D300060540020002002407F289ABF00F5803098 +:104D4000C0020020704700004FF400607047000070 +:104D5000802070477F2808B50BD8FFF7EDFF00F5DE +:104D600000630268013204D104308342F9D101208A +:104D700008BD0020FCE700007F2810B504461FD8BE +:104D8000FFF79AFFFFF7A2FF0E4BF3221A610222F0 +:104D90005A615A6942EAC0025A615A6942F4803241 +:104DA0005A61FFF789FF4FF40061FFF7C5FF00F07C +:104DB00043F9FFF7A5FF2046BDE81040FFF7CABF43 +:104DC000002010BD002002402DE9F84340EA020314 +:104DD00013F00703144606D0304B40F241321A60FC +:104DE0000020BDE8F88385182D4A95420CD92B4A3E +:104DF00040F246311160F3E7031D1B684A68934295 +:104E000008D1083C08300831072C14D902680B6817 +:104E10009A42F1D0FFF75AFFFFF74EFF214E0831BB +:104E20004FF001084FF00009012CA1F1080706D846 +:104E3000FFF766FF01E0002CECD10120D1E7C6F8B6 +:104E40001480054651F8083C45F8043B51F8043CF1 +:104E50004360FFF731FF336943F001033361C6F864 +:104E60001490026851F8083C9A420CD00B4B40F267 +:104E70006E321A600C4B18600C4B1C600C4B1F60A0 +:104E8000FFF73EFFACE72D6851F8043C9D4201F16D +:104E90000801EBD1083C0830C6E700BF5C54002095 +:104EA0000000040800200240505400205854002004 +:104EB00054540020084908B50B7828B11BB9FFF7F6 +:104EC00005FF01230B7008BD002BFCD0BDE8084096 +:104ED0000870FFF715BF00BF6054002008B50649F1 +:104EE000064800F0ABF8BDE808404FF480414FF0B1 +:104EF000805000F0A3B800BF007F01000001002037 +:104F0000084600F037BA000038B5EFF311859DB9B7 +:104F1000EFF30584C4F30804302334B183F311881C +:104F2000FFF7B0FE85F3118838BD83F31188FFF7D2 +:104F3000A9FE84F3118838BDBDE83840FFF7A2BE52 +:104F400038B5FFF7E1FF114C114AC00840EA417043 +:104F5000A0FB025EC908A0FB040C1CEB050CA1FB26 +:104F600004404FF000035B41A1FB02121CEB040C58 +:104F700043EB000011EB0E0142F10002411842F137 +:104F80000000090941EA007038BD00BFCFF753E3C4 +:104F9000A59BC4200244D2B2904200D17047431C6A +:104FA000800000F1804000F51450006841F8040BC7 +:104FB000D8B2F1E7124B10B5D3F89040240409D4CD +:104FC000D3F89040C3F89040D3F8904044F40044A4 +:104FD000C3F890400B4C2368024443F48073236071 +:104FE000D2B2904200D110BD431C800000F180403D +:104FF00000F5145051F8044B0460D8B2F1E700BF3B +:10500000001002400070004007B5012201A90020F5 +:10501000FFF7C0FF019803B05DF804FB13B5044629 +:10502000FFF7F2FFA04205D0012201A90020019460 +:10503000FFF7C0FF02B010BD7047000070470000CE +:1050400070470000074B45F255521A6002225A6021 +:1050500040F6FF729A604CF6CC421A60024B012275 +:105060001A7070470030004068540020034B1B78D2 +:105070001BB1034B4AF6AA221A60704768540020FD +:1050800000300040054B1A6832B902F1804202F547 +:105090000432D2F894201A60704700BF6454002094 +:1050A000024B4FF40002C3F89420704700100240F6 +:1050B00008B5FFF7E7FF024B1868C0F3407008BD62 +:1050C0006454002070470000FEE700000A4B0B48C4 +:1050D0000B4A90420BD30B4BDA1C121AC11E22F062 +:1050E00003028B4238BF00220021FCF733BB53F888 +:1050F000041B40F8041BECE7AC560008EC540020FD +:10510000EC540020EC5400200023054A19460133DA +:10511000102BC2E9001102F10802F8D1704700BF5C +:105120006C54002008B5124B9A6D42F001029A654A +:105130009A6F42F001029A670E4A9B6F936843F0A0 +:10514000010393600620FFF75FF80B4BB0FBF3F011 +:105150004FF080434FF0FF3201389862DA6200224C +:105160009A615A63DA605A6001225A611A6008BD76 +:1051700000100240002004E040420F004FF0804247 +:1051800008B51169D3680B40D9B2C9439B071161B7 +:1051900007D5302383F31188FFF7E2FB002383F365 +:1051A000118808BDFFF7BEBF4FF08043586A7047B3 +:1051B0004FF08043002258631A610222DA60704780 +:1051C0004FF080430022DA60704700004FF08043C8 +:1051D00058637047FEE7000070B51B4B0163002564 +:1051E000044686B0586085620E46FEF79BFD04F1CA +:1051F0001003C4E904334FF0FF33C4E90635C4E9B2 +:105200000044A560E562FFF7CFFF2B460246C4E9E4 +:10521000082304F134010D4A256580232046FFF759 +:10522000A1FB0123E0600A4A0375009272680192B3 +:10523000B268CDE90223074B6846CDE90435FFF794 +:10524000B9FB06B070BD00BF4854002028550008C7 +:105250002D550008D5510008024AD36A1843D06280 +:10526000704700BFE05100204B6843608B6883604B +:10527000CB68C3600B6943614B6903628B6943620E +:105280000B6803607047000008B5204BDA6A42F0F3 +:105290007F02DA62DA6A22F07F02DA62DA6ADA6CB4 +:1052A00042F07F02DA64DA6E42F07F02DA66184A70 +:1052B000DB6E11464FF09040FFF7D6FF02F11C0164 +:1052C00000F58060FFF7D0FF02F1380100F5806043 +:1052D000FFF7CAFF02F1540100F58060FFF7C4FF39 +:1052E00002F1700100F58060FFF7BEFF02F18C0152 +:1052F00000F58060FFF7B8FF02F1A80100F58060BB +:10530000FFF7B2FFBDE80840FEF700BF0010024003 +:105310003455000808B500F009F8FFF7FBFABDE8BE +:105320000840FFF7AFBE00007047000008B5FEF769 +:10533000E5FEFFF7E9FEFFF731FAFFF7F5FFBDE8FD +:105340000840FFF72FBF00000B460146184600F04B +:1053500003B8000000F00EB810B5054C13462CB190 +:105360000A4601460220AFF3008010BD2046FCE74C +:1053700000000000024B01461868FFF7C1BD00BFE6 +:105380005023002010B501390244904201D1002081 +:1053900005E0037811F8014FA34201D0181B10BD9E +:1053A0000130F2E72DE9F041A3B1C91A17780144A1 +:1053B000044603F1FF3C8C42204601D9002009E05D +:1053C0000578BD4204F10104F5D10CEB0405D618B3 +:1053D000A54201D1BDE8F08115F8018D16F801ED67 +:1053E000F045F5D0E7E70000034611F8012B03F87C +:1053F000012B002AF9D170476F72672E61726475B4 +:1054000070696C6F742E6D526F2D4D31303039359F +:105410000000000053544D333247343F3F0000003A +:1054200040A2E4F1646891060041A3E5F265699247 +:10543000070000004261642043414E496661636594 +:1054400020696E6465782E000000000000000000F6 +:10545000F1240008A91F0008052C000819200008E5 +:105460005D2000084522000825200008E11F0008F3 +:10547000E51F0008BD1F0008A51F00080122000845 +:10548000C91F00083D2D0008D51F0008D5210008C0 +:1054900001040E05054B02020E05054B04010E0525 +:1054A000054B05010B04044B0801060303460000ED +:1054B0000096000000000000000000000000000056 +:1054C0000000000000000000636C6B737763000055 +:1054D00000030000000000000001000000000101C6 +:1054E000030000000328310104070400010000004C +:1054F000000000005D470008494700088547000894 +:10550000714700087D4700086947000855470008B3 +:105510004147000891470008633000001855000813 +:1055200038520020485400206D61696E0069646C37 +:10553000650000000001A82A00000000AAAABEAA77 +:1055400000001424EFFF0000000000007097090025 +:105550000000000000000000AAAAAAAA00000000A3 +:10556000FFFF00000000000000000000000000003D +:1055700000000000AAAAAAAA00000000FFFF000085 +:10558000000000000000000000000000000000001B +:10559000AAAAAAAA00000000FFFF00000000000065 +:1055A000000000000000000000000000AAAAAAAA53 +:1055B00000000000FFFF00000000000000000000ED +:1055C0000000000000000000AAAAAAAA0000000033 +:1055D000FFFF0000000000000000000000000000CD +:1055E00000000000AAAAAAAA00000000FFFF000015 +:1055F0000000000000000000110400000000000096 +:105600000088030000000000FE2A0100D204000010 +:10561000FF000000744F0020000000001454000838 +:10562000006889096D8BB90200B4C4040068890957 +:105630000068890900688909006889090068890982 +:1056400000688909000000005423002000000000C9 +:10565000000000000000000000000000000000004A +:10566000000000000000000000000000000000003A :10567000000000000000000000000000000000002A -:10568000000000009545000881450008BD45000860 -:10569000A9450008B5450008A14500088D4500084A -:1056A00079450008C945000863300000A856000885 -:1056B00000520020105400206D61696E0069646C16 -:1056C000650000000001A82A00000000AAAABEAAE6 -:1056D00000001424EFFF0000000000007097090094 -:1056E0000000000000000000AAAAAAAA0000000012 -:1056F000FFFF0000000000000000000000000000AC -:1057000000000000AAAAAAAA00000000FFFF0000F3 -:105710000000000000000000000000000000000089 -:10572000AAAAAAAA00000000FFFF000000000000D3 -:10573000000000000000000000000000AAAAAAAAC1 -:1057400000000000FFFF000000000000000000005B -:105750000000000000000000AAAAAAAA00000000A1 -:10576000FFFF00000000000000000000000000003B -:1057700000000000AAAAAAAA00000000FFFF000083 -:10578000000000000000000098AAFF7F0100000058 -:105790001104000000000000008803000000000069 -:1057A000FE2A0100D2040000FF0000003C4F002050 -:1057B00000000000EC5500082C2300200000000031 -:1057C00000000000000000000000000000000000D9 -:1057D00000000000000000000000000000000000C9 -:1057E00000000000000000000000000000000000B9 -:1057F00000000000000000000000000000000000A9 -:105800000000000000000000000000000000000098 -:0C5810000000000000000000000000008C +:10568000000000000000000000000000000000001A +:10569000000000000000000000000000000000000A +:0C56A000000000000000000000000000FE :00000001FF diff --git a/Tools/bootloaders/mRoCANPWM-M10126_bl.bin b/Tools/bootloaders/mRoCANPWM-M10126_bl.bin index 96fd236045c79e..c18c58f06953e0 100755 Binary files a/Tools/bootloaders/mRoCANPWM-M10126_bl.bin and b/Tools/bootloaders/mRoCANPWM-M10126_bl.bin differ diff --git a/Tools/bootloaders/mRoKitCANrevC_bl.bin b/Tools/bootloaders/mRoKitCANrevC_bl.bin index de138c355e8415..e7841c82b9a5eb 100755 Binary files a/Tools/bootloaders/mRoKitCANrevC_bl.bin and b/Tools/bootloaders/mRoKitCANrevC_bl.bin differ diff --git a/Tools/bootloaders/mRoKitCANrevC_bl.hex b/Tools/bootloaders/mRoKitCANrevC_bl.hex index 3ba95d12767dcc..2cfa28e9fc55a5 100644 --- a/Tools/bootloaders/mRoKitCANrevC_bl.hex +++ b/Tools/bootloaders/mRoKitCANrevC_bl.hex @@ -25,7 +25,7 @@ :10017000B3010008B3010008B3010008B30100088F :10018000B3010008B3010008B3010008B30100087F :10019000B3010008B3010008B3010008B30100086F -:1001A0001D0F00080000000000000000000000001B +:1001A000210F000800000000000000000000000017 :1001B00002E000F000F8FEE772B6374880F30888E6 :1001C000364880F3098836483649086040F2000016 :1001D000CCF200004EF63471CEF200010860BFF39D @@ -42,208 +42,208 @@ :1002800000F042F8114C124DAC4203DA54F8041B52 :100290008847F9E703F038BC00090020001100206E :1002A0000000000808ED00E0000100200009002027 -:1002B000B0480008001100207C11002080110020AF +:1002B000A8480008001100207C11002080110020B7 :1002C000543C0020A0010008A4010008A40100087B :1002D000A40100082DE9F04F2DED108AC1F80CD0D3 :1002E000C3689D46BDEC108ABDE8F08F002383F300 :1002F00011882846A047002003F05AF9FEE703F0D2 -:10030000E3F800DFFEE70000F8B500F019FE03F0A7 -:100310009DFB074603F0ECFB0546002840D12C4B23 -:100320009F423DD001339F423DD02A4B27F0FF0230 -:100330009A423BD1F8B200F03FFC2E4642F21074D4 -:1003400000F040FC08B10024264601F0B1F888B363 -:10035000032000F045F80024264635B11E4B9F428D -:1003600003D003F0BDFB00242646002003F078FBF9 -:100370001A4B1B6913F0400322D00EB100F046F86F -:1003800000F052FC00F0DEFD01F0BCFF0546CCB1F0 -:1003900001F0B8FF401BA04214D900F037F8F3E792 -:1003A0002E460024CCE704460126C9E706464FF452 -:1003B0007A74C5E7002CD0D04FF47A740126CCE7CC -:1003C0001C46DDE700F078FC012003F0F7F8DEE7DB -:1003D000010007B0000008B0263A09B00004004848 -:1003E000084B187003280CD8DFE800F00805020855 -:1003F000022000F003BE022000F0F8BD024B0022F4 -:100400005A607047801100208411002038B501F037 -:100410004FF830B11F4B03221A701F4B00225A6055 -:1004200038BD1E4B1E4A19680131F9D0043393427E -:10043000F9D11C4C194DD4F80428AA42F0D31A4B18 -:100440009B6803F1006303F5D0439A42E8D203F0BE -:100450001BFB03F02DFB002000F08EFD0220FFF7B8 -:10046000BFFF124BDA690022DA61D96999699A6192 -:100470009B6972B64FF0E0233021C3F8085DD4F8D1 -:100480000038D4F8042881F311889D4683F3088846 -:100490001047C5E780110020841100200068000883 -:1004A00020680008006000080011002000100240D1 -:1004B000094A136849F2690099B21B0C00FB013329 -:1004C0001360064B186844F2506182B2000C01FBC5 -:1004D0000200186080B27047141100201011002033 -:1004E00010B500211022044600F0A2FD034B03CBFF -:1004F000206061601868A06010BD00BFACF7FF1FEE -:100500002DE9F041ADF5507D0DF13C086EAC40F2A7 -:10051000751207460D4610A80021C8F8001000F01B -:1005200087FD4FF4C4720021204600F081FD01F0E8 -:10053000E9FE254B4FF47A72B0FBF2F0186093E8B5 -:100540000700022384E807000DF5ED702382FFF712 -:10055000C7FF47F604131D49238407A804F0DAF8FF -:100560001C2384F832310DF2EB226B440DF1340C74 -:100570001E4603CE664510605160334602F1080204 -:10058000F6D13068106041460122204600F09CFD03 +:10030000E3F800DFFEE70000F8B500F01BFE03F0A5 +:100310009DFB074603F0ECFB064600283ED12B4B25 +:100320009F423BD001339F423BD0294B27F0FF0235 +:100330009A4239D1F8B200F041FC354642F21074CD +:1003400000F042FC08B10024254601F0B1F878B372 +:10035000032000F043F80024254636B11D4B9F4290 +:1003600003D003F0BDFB00242546002003F078FBFA +:10037000194B1B6913F040031FD00DB100F044F876 +:1003800000F054FC01F0BEFF0546C4B101F0BAFF15 +:10039000401BA04213D900F037F8F3E7354600249C +:1003A000CEE704460125CBE705464FF47A74C7E74C +:1003B000B4F57A7F08BF0125CFE71C46E0E700F0DF +:1003C0007DFC012003F0FAF8DFE700BF010007B071 +:1003D000000008B0263A09B000040048084B187025 +:1003E00003280CD8DFE800F008050208022000F01E +:1003F00005BE022000F0FABD024B00225A60704791 +:10040000801100208411002038B501F051F830B17E +:100410001F4B03221A701F4B00225A6038BD1E4B1F +:100420001E4A19680131F9D004339342F9D11C4CAA +:10043000194DD4F80428AA42F0D31A4B9B6803F153 +:10044000006303F5D0439A42E8D203F01DFB03F0AA +:100450002FFB002000F090FD0220FFF7BFFF124BA2 +:10046000DA690022DA61D96999699A619B6972B681 +:100470004FF0E0233021C3F8085DD4F80038D4F8F9 +:10048000042881F311889D4683F308881047C5E747 +:1004900080110020841100200068000820680008F6 +:1004A000006000080011002000100240094A136893 +:1004B00049F2690099B21B0C00FB01331360064B33 +:1004C000186844F2506182B2000C01FB020018600F +:1004D00080B27047141100201011002010B50021C7 +:1004E0001022044600F0A4FD034B03CB20606160A2 +:1004F0001868A06010BD00BFACF7FF1F2DE9F041E8 +:10050000ADF54E7D0DF134086CAC40F27512074626 +:100510000D460EA80021C8F8001000F089FD4FF428 +:10052000C4720021204600F083FD01F0EBFE274B52 +:100530004FF47A72B0FBF2F0186093E807000223E0 +:1005400084E807000DF5E9702382FFF7C7FF47F63F +:1005500004131F49238406A804F0DCF81B2384F845 +:1005600032310DF2E32206AB0DF1300C1E4603CE04 +:10057000664510605160334602F10802F6D13188B9 +:10058000B3789370118020464146012200F09CFD13 :1005900000230393AB7E029305F11903019380B20C -:1005A0000123CDE904800093E97E05A3D3E900236C -:1005B000384602F06FFA0DF5507DBDE8F08100BFBE -:1005C0009E6AC421818A46EE8C11002024470008CF -:1005D0002DE9F0412C4C237ADAB080460D465BBB06 -:1005E00027A9284600F080FE0746002842D19DF842 -:1005F0009D60C82E3ED801464FF4A662204600F00A -:1006000017FD4FF48073C4F8F8314FF40073C4F849 -:100610000C334FF44073C4F8203432460DF19E0180 -:1006200004F1090000F0F2FC26449DF89C3077723A -:1006300023720BB9EB7E23728122002106AC27A81E -:1006400000F0F6FC0122214627A800F089FE0023D5 -:100650000393AB7E029305F1190380B20193282323 -:10066000CDE904400093E97E05A3D3E90023404689 -:1006700002F010FA5AB0BDE8F08100BFAFF300807D -:1006800026417272DF25D7B7B0320020F0B5254E73 -:100690004FF48A7505FB0065F1B096F8D83085F8FF -:1006A000DC300024D822214685F8E8403AA800F042 -:1006B000BFFC06F1090000F0B3FCD5F8E4308DF87A -:1006C000F000C2B206AF06F109010DF1F100CDE96B -:1006D0003A3400F09BFC394601223AA800F06CFE47 -:1006E00080B2CDE9047008230127CDE9023706F175 -:1006F000D803019330230093317A0B4807A3D3E941 -:10070000002302F0C7F9A04206DD01F0FBFDC5F8A9 -:10071000E000384671B0F0BD2046FBE778F6339F25 -:1007200093CACD8DB0320020A42100202DE9F041E4 -:100730001D4D1E4E1E4F86B0284602F0D7F90346C7 -:1007400058B30024CDE90344ADF81440027B8DF882 -:10075000142099684068029403AA03C21B68DFF85A -:10076000548043F00043029301F0CEFD821941F121 -:100770000003009402A9384601F078F8A04205DD94 -:10078000284602F0B7F988F80040D5E798F800301D -:10079000072B05D8013388F8003006B0BDE8F0819A -:1007A000014802F0A7F9F8E7A421002040420F0019 -:1007B000D8210020E537002070B50D4614461E46AE -:1007C00002F0C4F850B9022E10D1012C0ED112A3A0 -:1007D000D3E90023C5E90023012007E0282C10D02D -:1007E00005D8012C09D0052C0FD0002070BD302C6D -:1007F000FBD10BA3D3E90023ECE70BA3D3E9002340 -:10080000E8E70BA3D3E90023E4E70BA3D3E9002334 -:10081000E0E700BFAFF30080401DA12026812A0B36 -:1008200078F6339F93CACD8D9E6AC421818A46EEA5 -:1008300026417272DF25D7B7F017304A39059E5628 -:1008400038B505460E4C0021013500F0B7FBA4F881 -:100850002C55B4F82C0500F099FB78B1B4F82C05B0 -:1008600000F0A4FB014648B9B4F82C0500F0A6FB43 -:10087000B4F82C350133A4F82C35EAE738BD00BFB5 -:10088000B032002010B50A4B0A4A1A6003F58053B3 -:1008900093F860203AB9DC6D2CB1204600F086FE5A -:1008A000204603F077FEBDE81040034800F07EBE0E -:1008B000D821002080470008203200202DE9F04F89 -:1008C0008FB000AF05460C4602F040F8002849D131 -:1008D000237E022B1BD1E38A012B18D101F012FDDC -:1008E0000646FFF7E5FD03464FF4C870DFF8C48203 -:1008F000B3FBF0F206F5167602FB103316FA83F31B -:10090000C8F80030E37E33B9A34B00221A703C379D -:10091000BD46BDE8F08F07F12401204600F0A2FC9F -:100920000028F4D107F11400FFF7DAFD97F826400C -:1009300007F11401224607F1270003F075FE002895 -:10094000E2D10F2C08D8944B1C70D8F80030A3F5D6 -:100950001673C8F80030DAE797F82410284601F03B -:10096000EDFFD4E7E38A282B2BD010D8012B23D01E -:10097000052BCCD1BFF34F8F8849894BCA6802F44D -:10098000E0621343CB60BFF34F8F00BFFDE7302B16 -:10099000BDD1844EE17E327A9142B8D1607E31463B -:1009A000002291F8DC50854200F0A5800132042A33 -:1009B00001F58A71F5D1AAE721462846FFF7A0FD87 -:1009C000A5E721462846FFF703FEA0E7B2F8EC5062 -:1009D0007B6005F103094FEA99094FEA8902D11DAD -:1009E000C908A8EBC1039D46EB460021584600F01C -:1009F0001FFB04F1EE012A463144584600F006FB85 -:100A00007B6813B9012000F0B7FA96F8D20000F025 -:100A1000BDFA044630B9307200F0D8FA204600F032 -:100A2000ABFAB1E0D6F8D4203AB996F8D200B6F8CD -:100A30002C25824201D8FFF703FFD6F8D4202A44A0 -:100A4000944208D296F8D200B6F82C2501308242A2 -:100A500001D8FFF7F5FE70685FFA89F2594600F099 -:100A6000EFFA08B9C54679E0726896F8D2002A44D0 -:100A70007260D6F8D42005EB0209C6F8D49000F0D5 -:100A800085FA814509D396F8D220D6F8D4000132F0 -:100A9000001B86F8D220C6F8D400FF2D0FD8002402 -:100AA000347200F093FA204600F066FA00F000FD80 -:100AB0003D4B188108B9FFF7A9FCC54627E7BB687D -:100AC00096F8D9000AFB0362FB68D2F8E41082F8BA -:100AD000E83001F58061C2F8E030C2F8E410FFF7B9 -:100AE000D5FDFFF723FE96F8D920013202F003026C -:100AF00086F8D920B6E74FF48A7A0AFB02F505F1A9 -:100B0000EA013144204600F083FCF86000287FF4BD -:100B1000FEAE3544012285F8E82001F0F3FBD5F85C -:100B2000E020D6ED007ADFED216A801A192838BF5F -:100B3000192040F6B832904228BF1046B8EE677AC6 -:100B400007EE900AF8EEE77A67EEA67ADFED186A0C -:100B5000E7EE267AFCEEE77AC6ED007A96F8D93011 -:100B6000BB60BA6873680AFB02F4321992F8E810A5 -:100B700059B1D2F8E4108B42E8463FF427AF002188 -:100B800082F8E810C2F8E010C5467368064A9B0A6E -:100B900001331381BBE600BF9D21002000ED00E082 -:100BA0000400FA05B03200208C110020CDCCCC3DE1 -:100BB0006666663FA0210020014B1870704700BF99 -:100BC0009811002038B54FF00054134B22689A4218 -:100BD00020D1124B627D12481A70237D03724FF4AC -:100BE0008073C0F8F8314FF40073C0F80C3300255F -:100BF0004FF44073C0F820340A49C0F8E450C922C9 -:100C0000093000F003FAE0222946204600F010FAED -:100C1000012038BD0020FCE79AAD44C598110020A2 -:100C2000B03200201600002037B500F041FC194D0D -:100C3000194928810223012218486B7101F0FEF93D -:100C400000230193164B174900931748174B4FF495 -:100C5000805201F04BFE164B197811B1124801F089 -:100C60006DFE01F04FFB0446FFF722FC4FF4C87302 -:100C7000B0FBF3F202FB130304F5167010FA83F0D5 -:100C80000C4B186002F034FF08B10F232B8103B026 -:100C900030BD00BF8C11002040420F00D821002041 -:100CA000B90700089C110020A4210020BD080008FD -:100CB00098110020A02100202DE9F04F2DED028B8E -:100CC0008EA7D7E900670FF23C29D9E90089864C45 -:100CD00095B00DAD9FED828BFFF728FDDFF82CB2AC -:100CE00000230C93ADF83C300D936B6000230DF1A5 -:100CF00025028DED008B4FF0010A09A958468DF8A9 -:100D000025308DF824A001F047F99DF82420002318 -:100D1000002A40F0AB80204601F018FE054600286E -:100D200047D1DFF8ECB101F0EDFADBF80030984282 -:100D30003FD301F0E7FA0790FFF7BAFB079A4FF4A9 -:100D4000C873B0FBF3F101FB130302F5167010FA40 -:100D500083F0CBF80000DFF8BCB19BF800100791DE -:100D6000002914BF2B46534610A88DF83030FFF7EA -:100D7000B7FB0799C1F11002D2B2062A10AB28BF07 -:100D8000062219440DF13100079200F03FF9079A4D -:100D90000CAB0393182302930132544BD2B2CDE92A -:100DA00000A304923B463246204601F015FE8BF824 -:100DB000005001F0A7FA4E4A4E4D1368C31AB3F51E -:100DC0007A7F32D3106001F09FFA02460B4620462C -:100DD00001F09AFE204601F0B9FD30B32B7ADFF81E -:100DE00038A1002B14BF032302238AF8053001F039 -:100DF00089FA0DF1400B4FF47A730122B0FBF3F046 -:100E00005946CAF80000504600F004FA182302932D -:100E1000394B019380B240F25513CDE903B00093F2 -:100E200042464B46204601F0D7FD2B7ACBB101F06C -:100E300069FA4FF0000A83464FF48A7295F8D90098 -:100E4000504400F0030002FB005393F8E81089B30C -:100E50000AF1010ABAF1040FF0D12B7A002B7FF4CA -:100E600038AF15B0BDEC028BBDE8F08F4FF090416C -:100E700010A84A6982F010024A611946102200F057 -:100E8000D7F80DF126030AAA0CA9584600F0EEFD8A -:100E900095E8030011AB83E803009DF83C308DF822 -:100EA0004C300C9B109310A9DDE90A23204601F079 -:100EB000FFFF1BE7D3F8E01049B12B68FA2B38BFCE -:100EC000FA23ABEB01010533B1EB430FC0D3FFF7BE -:100ED000DDFB4FF48A720028BAD1BEE7AFF3008081 -:100EE0000000000000000000A42100209C21002040 -:100EF000E0370020B0320020E4370020401DA12060 -:100F000026812A0BF1C6A7C1D068080FD82100207E -:100F1000A02100209D2100208C11002008B505484B -:100F200000F040FEBDE80840034A0449002003F0F9 -:100F30002BBB00BFD82100202038002085080008E6 -:100F40007047000070B502F011FC094E094D308069 +:1005A0000123CDE904800093E97E06A3D3E900236B +:1005B000384602F06FFA0DF54E7DBDE8F08100BFC0 +:1005C000AFF300809E6AC421818A46EE8C11002020 +:1005D000244700082DE9F0412C4C237ADAB08046FC +:1005E0000D465BBB27A9284600F07EFE0746002883 +:1005F00042D19DF89D60C82E3ED801464FF4A662B8 +:10060000204600F015FD4FF48073C4F8F8314FF424 +:100610000073C4F80C334FF44073C4F820343246EE +:100620000DF19E0104F1090000F0F0FC26449DF854 +:100630009C30777223720BB9EB7E237281220021EA +:1006400006AC27A800F0F4FC0122214627A800F000 +:1006500087FE00230393AB7E029305F1190380B25A +:1006600001932823CDE904400093E97E05A3D3E953 +:100670000023404602F00EFA5AB0BDE8F08100BFF8 +:10068000AFF3008026417272DF25D7B7B032002069 +:10069000F0B5254E4FF48A7505FB0065F1B096F86C +:1006A000D83085F8DC300024D822214685F8E8408F +:1006B0003AA800F0BDFC06F1090000F0B1FCD5F845 +:1006C000E4308DF8F000C2B206AF06F109010DF179 +:1006D000F100CDE93A3400F099FC394601223AA8FC +:1006E00000F06AFE80B2CDE9047008230127CDE94D +:1006F000023706F1D803019330230093317A0B4877 +:1007000007A3D3E9002302F0C5F9A04206DD01F0FA +:10071000F9FDC5F8E000384671B0F0BD2046FBE7B2 +:1007200078F6339F93CACD8DB0320020A4210020EB +:100730002DE9F0411D4D1E4E1E4F86B0284602F099 +:10074000D5F9034658B30024CDE90344ADF814406D +:10075000027B8DF8142099684068029403AA03C2B2 +:100760001B68DFF8548043F00043029301F0CCFD96 +:10077000821941F10003009402A9384601F076F88D +:10078000A04205DD284602F0B5F988F80040D5E71B +:1007900098F80030072B05D8013388F8003006B0F0 +:1007A000BDE8F081014802F0A5F9F8E7A421002096 +:1007B00040420F00D8210020E537002070B50D46DB +:1007C00014461E4602F0C2F850B9022E10D1012C78 +:1007D0000ED112A3D3E90023C5E90023012007E0CD +:1007E000282C10D005D8012C09D0052C0FD00020C2 +:1007F00070BD302CFBD10BA3D3E90023ECE70BA396 +:10080000D3E90023E8E70BA3D3E90023E4E70BA334 +:10081000D3E90023E0E700BFAFF30080401DA12033 +:1008200026812A0B78F6339F93CACD8D9E6AC42108 +:10083000818A46EE26417272DF25D7B7F017304A1B +:1008400039059E5638B505460E4C0021013500F09D +:10085000B5FBA4F82C55B4F82C0500F097FB78B143 +:10086000B4F82C0500F0A2FB014648B9B4F82C05F9 +:1008700000F0A4FBB4F82C350133A4F82C35EAE7DA +:1008800038BD00BFB032002010B50A4B0A4A1A60CA +:1008900003F5805393F860203AB9DC6D2CB1204603 +:1008A00000F084FE204603F075FEBDE810400348CA +:1008B00000F07CBED82100207C47000820320020B8 +:1008C0002DE9F04F8FB000AF05460C4602F03EF820 +:1008D000002849D1237E022B1BD1E38A012B18D19A +:1008E00001F010FD0646FFF7E1FD03464FF4C87026 +:1008F000DFF8C482B3FBF0F206F5167602FB103384 +:1009000016FA83F3C8F80030E37E33B9A34B002214 +:100910001A703C37BD46BDE8F08F07F12401204630 +:1009200000F0A0FC0028F4D107F11400FFF7D6FD79 +:1009300097F8264007F11401224607F1270003F03B +:1009400073FE0028E2D10F2C08D8944B1C70D8F805 +:100950000030A3F51673C8F80030DAE797F82410D2 +:10096000284601F0EBFFD4E7E38A282B2BD010D8E0 +:10097000012B23D0052BCCD1BFF34F8F8849894B56 +:10098000CA6802F4E0621343CB60BFF34F8F00BF2D +:10099000FDE7302BBDD1844EE17E327A9142B8D151 +:1009A000607E3146002291F8DC50854200F0A5803F +:1009B0000132042A01F58A71F5D1AAE721462846B9 +:1009C000FFF79CFDA5E721462846FFF703FEA0E7B9 +:1009D000B2F8EC507B6005F103094FEA99094FEA40 +:1009E0008902D11DC908A8EBC1039D46EB46002131 +:1009F000584600F01DFB04F1EE012A4631445846EA +:100A000000F004FB7B6813B9012000F0B5FA96F8FA +:100A1000D20000F0BBFA044630B9307200F0D6FACA +:100A2000204600F0A9FAB1E0D6F8D4203AB996F8F9 +:100A3000D200B6F82C25824201D8FFF703FFD6F882 +:100A4000D4202A44944208D296F8D200B6F82C2535 +:100A50000130824201D8FFF7F5FE70685FFA89F233 +:100A6000594600F0EDFA08B9C54679E0726896F883 +:100A7000D2002A447260D6F8D42005EB0209C6F8E9 +:100A8000D49000F083FA814509D396F8D220D6F8A5 +:100A9000D4000132001B86F8D220C6F8D400FF2D06 +:100AA0000FD80024347200F091FA204600F064FA66 +:100AB00000F0FEFC3D4B188108B9FFF7A5FCC546C8 +:100AC00027E7BB6896F8D9000AFB0362FB68D2F8F7 +:100AD000E41082F8E83001F58061C2F8E030C2F835 +:100AE000E410FFF7D5FDFFF723FE96F8D920013279 +:100AF00002F0030286F8D920B6E74FF48A7A0AFB9F +:100B000002F505F1EA013144204600F081FCF8606D +:100B100000287FF4FEAE3544012285F8E82001F07C +:100B2000F1FBD5F8E020D6ED007ADFED216A801ADE +:100B3000192838BF192040F6B832904228BF104615 +:100B4000B8EE677A07EE900AF8EEE77A67EEA67AD3 +:100B5000DFED186AE7EE267AFCEEE77AC6ED007A5A +:100B600096F8D930BB60BA6873680AFB02F4321990 +:100B700092F8E81059B1D2F8E4108B42E8463FF4FD +:100B800027AF002182F8E810C2F8E010C54673686C +:100B9000064A9B0A01331381BBE600BF9D2100205A +:100BA00000ED00E00400FA05B03200208C110020B6 +:100BB000CDCCCC3D6666663FA0210020014B18706D +:100BC000704700BF9811002038B54FF00054134B08 +:100BD00022689A4220D1124B627D12481A70237DFE +:100BE00003724FF48073C0F8F8314FF40073C0F80B +:100BF0000C3300254FF44073C0F820340A49C0F884 +:100C0000E450C922093000F001FAE02229462046CA +:100C100000F00EFA012038BD0020FCE79AAD44C573 +:100C200098110020B03200201600002037B500F0E7 +:100C30003FFC194D194928810223012218486B7184 +:100C400001F0FCF900230193164B17490093174854 +:100C5000174B4FF4805201F049FE164B197811B131 +:100C6000124801F06BFE01F04DFB0446FFF71EFC3D +:100C70004FF4C873B0FBF3F202FB130304F51670D4 +:100C800010FA83F00C4B186002F032FF08B10F230A +:100C90002B8103B030BD00BF8C11002040420F00FB +:100CA000D8210020BD0700089C110020A4210020AD +:100CB000C108000898110020A02100202DE9F04F64 +:100CC0002DED028B8EA7D7E900670FF23C29D9E9F9 +:100CD0000089864C95B00DAD9FED828BFFF728FD06 +:100CE000DFF82CB200230C93ADF83C300D936B6011 +:100CF00000230DF125028DED008B4FF0010A09A9AB +:100D000058468DF825308DF824A001F045F99DF85E +:100D100024200023002A40F0AB80204601F016FE7C +:100D20000546002847D1DFF8ECB101F0EBFADBF81B +:100D3000003098423FD301F0E5FA0790FFF7B6FB89 +:100D4000079A4FF4C873B0FBF3F101FB130302F5EC +:100D5000167010FA83F0CBF80000DFF8BCB19BF8F6 +:100D600000100791002914BF2B46534610A88DF898 +:100D70003030FFF7B3FB0799C1F11002D2B2062A57 +:100D800010AB28BF062219440DF13100079200F084 +:100D90003DF9079A0CAB0393182302930132544B8D +:100DA000D2B2CDE900A304923B463246204601F080 +:100DB00013FE8BF8005001F0A5FA4E4A4E4D136811 +:100DC000C31AB3F57A7F32D3106001F09DFA024660 +:100DD0000B46204601F098FE204601F0B7FD30B3E7 +:100DE0002B7ADFF838A1002B14BF032302238AF8E3 +:100DF000053001F087FA0DF1400B4FF47A730122B0 +:100E0000B0FBF3F05946CAF80000504600F002FA71 +:100E100018230293394B019380B240F25513CDE968 +:100E200003B0009342464B46204601F0D5FD2B7A95 +:100E3000CBB101F067FA4FF0000A83464FF48A7293 +:100E400095F8D900504400F0030002FB005393F8DA +:100E5000E81089B30AF1010ABAF1040FF0D12B7A34 +:100E6000002B7FF438AF15B0BDEC028BBDE8F08FDE +:100E70004FF0904110A84A6982F010024A61194669 +:100E8000102200F0D5F80DF126030AAA0CA9584645 +:100E900000F0ECFD95E8030011AB83E803009DF83A +:100EA0003C308DF84C300C9B109310A9DDE90A23DF +:100EB000204601F0FDFF1BE7D3F8E01049B12B6895 +:100EC000FA2B38BFFA23ABEB01010533B1EB430F2B +:100ED000C0D3FFF7DDFB4FF48A720028BAD1BEE71A +:100EE000AFF300800000000000000000A4210020FB +:100EF0009C210020E0370020B0320020E4370020A1 +:100F0000401DA12026812A0BF1C6A7C1D068080F79 +:100F1000D8210020A02100209D2100208C1100203C +:100F200008B5054800F03EFEBDE80840034A044904 +:100F3000002003F029BB00BFD8210020203800206A +:100F40008908000870B502F011FC094E094D308087 :100F5000002428683388834208D902F003FC2B68F8 :100F600004440133B4F5D04F2B60F2D370BD00BF01 :100F700014380020E837002002F084BC00F1006043 @@ -344,8 +344,8 @@ :101560002A46064604F118010020FFF78BFFA36806 :101570009E4202D1E368984201D00D25A8E70025DC :10158000284603B0F0BD1025A2E70C25A0E70B25E7 -:101590009EE700BF44470008DC970300006800088E -:1015A0004D470008909703000898FFF710B5037C9B +:101590009EE700BF40470008DC9703000068000892 +:1015A00049470008909703000898FFF710B5037C9F :1015B000044613B9006803F02FF8204610BD000060 :1015C0000023BFF35B8FC360BFF35B8FBFF35B8F01 :1015D0008360BFF35B8F7047BFF35B8F0068BFF31F @@ -440,7 +440,7 @@ :101B600008084FF0000A4FF0000B46E908ABA6F159 :101B70001800FFF71BFF203646F8289C4645F4D195 :101B800085F8D07017B1054800F0B6FB044B6361CF -:101B90002046BDE8F88F00BF80470008584700087E +:101B90002046BDE8F88F00BF7C4700085447000886 :101BA0000064004010B5044B197804464A1C1A70B2 :101BB000FFF7A2FF204610BD1C3800202DE9F0479A :101BC000002950D0294B2A4FB7FBF1F599428CBF21 @@ -460,7 +460,7 @@ :101CA000936913F0700F16D000230B4C936103F16E :101CB000840200EB421211794D0709D5890707D537 :101CC000416954F823508D60117941F0040111717C -:101CD0000133032BEBD130BD6C47000873B51D46B3 +:101CD0000133032BEBD130BD6847000873B51D46B7 :101CE000436916469A68D207044609D59A680121C5 :101CF0009960C2F34002CDE900650021FFF76AFE5A :101D000063699A68D1050BD59A684FF48071996020 @@ -492,7 +492,7 @@ :101EA0002E7977070ED4F6060CD5D1E90076974245 :101EB0009E4107D246695CF82470B7602E7946F0DF :101EC00004062E710134032C01F12001E4D100231A -:101ED00083F31188F0BD00BF6C47000808B53023BC +:101ED00083F31188F0BD00BF6847000808B53023C0 :101EE00083F31188FFF7DAFE002383F3118808BD1E :101EF000F8B543690546986800F0E050B0F1E05F3E :101F00000F4621D0F8B1302383F3118805F58354AF @@ -848,7 +848,7 @@ :1034E00001462046BDE81040FCF7F4BE2838002015 :1034F00038B5074C0749084801230025237065604B :1035000000F024FB0223237085F3118838BD00BF2F -:10351000503A0020C44700082838002008B572B689 +:10351000503A0020C04700082838002008B572B68D :10352000044B186500F0C2F900F0ACFA024B03221C :103530001A70FEE728380020503A002000F09AB8B0 :103540008B60022308618B82084670478368A3F171 @@ -894,20 +894,20 @@ :1037C000FFF798FF00F05AF9FFF7B4FF2046BDE875 :1037D0001040FFF7CDBF002010BD00BF0020024009 :1037E0002DE9F84312F00103144606D01F4B40F2B6 -:1037F000F5221A600020BDE8F88385181C4A95421E -:1038000004D91A4A40F2FA211160F3E7FFF77CFF6E +:1037F00003321A600020BDE8F88385181C4A954200 +:1038000004D91A4A4FF442711160F3E7FFF77CFFC5 :10381000FFF770FFDFF86880451A4FF00109012CAF :1038200005EB01060F4603D8FFF784FF0120E2E70E :103830003B88C8F8109033800020FFF75BFFC8F882 :103840001000338831F8022B9BB29A420CD0074B00 -:1038500040F211321A60074B1E60074B1C60074B89 +:1038500040F21F321A60074B1E60074B1C60074B7B :103860001F60FFF767FFC6E7023CD8E7643A002015 :1038700000000408583A0020603A00205C3A00201A :1038800000200240084908B50B7828B11BB9FFF7A2 :103890003BFF01230B7008BD002BFCD0BDE80840A6 -:1038A0000870FFF747BF00BF683A002008B54FF423 -:1038B00020414FF0005000F0E3F8BDE808404FF41D -:1038C00000514FF0805000F0DBB800000846114670 +:1038A0000870FFF747BF00BF683A002008B5064818 +:1038B0004FF41F4100F0E4F8BDE808404FF4005118 +:1038C0004FF0805000F0DCB800010020084611469F :1038D00000F084BE012000F081BE0000084600F028 :1038E0009BBE000038B5EFF31185BDBBEFF3058437 :1038F000C4F308043023C4B183F31188FFF7E2FE58 @@ -946,7 +946,7 @@ :103B00006C3A002070470000FEE700000A4B0B48AB :103B10000B4A90420BD30B4BDA1C121AC11E22F037 :103B200003028B4238BF00220021FDF781BA53F80F -:103B3000041B40F8041BECE72C490008543C00200F +:103B3000041B40F8041BECE724490008543C002017 :103B4000543C0020543C0020FEE7000070B51B4BA5 :103B500001630025044686B0586085620E46FFF773 :103B6000D3FB04F11003C4E904334FF0FF33A36126 @@ -955,7 +955,7 @@ :103B90002046FFF7D5FC0123E0600B4A0375009235 :103BA00072680192B268CDE90223084B6846CDE9FC :103BB0000435FFF7EDFC06B070BD00BF503A0020A1 -:103BC00028380020D0470008D5470008493B0008A6 +:103BC00028380020CC470008D1470008493B0008AE :103BD0004B6843608B688360CB68C3600B6943614B :103BE0004B6903628B6943620B6803607047000096 :103BF00008B51B4B9A6A42F4FC029A629A6A22F454 @@ -965,7 +965,7 @@ :103C3000FFF7CEFF02F1540100F58060FFF7C8FFE7 :103C400002F1700100F58060FFF7C2FF02F18C0104 :103C500000F58060FFF7BCFFBDE8084000F05AB8EF -:103C600000100240DC47000808B500F093F9FFF7A8 +:103C600000100240D847000808B500F093F9FFF7AC :103C70003FFCBDE80840FFF727BF00007047000089 :103C800010B5214CA36A63F4FC03A362A36A03F496 :103C9000FC03A3624FF0FF32A36A23692261236908 @@ -1026,7 +1026,7 @@ :104000004FBA00004FF0FF32383000F049BA0000DC :10401000012914BF6FF013000020704700F06CB846 :10402000044B03600023C0E902334360012303749F -:10403000704700BF8448000838B5C36904460D4680 +:10403000704700BF8048000838B5C36904460D4684 :104040001BB904210844FFF7B3FF294604F114000B :1040500000F0A6F9002806DA201D4FF40061BDE843 :104060003840FFF7A5BF38BD00F00EB80023054A61 @@ -1138,36 +1138,36 @@ :1047000002D12B6803B1236038BD00BF503C0020AC :10471000FEF7E6BF034611F8012B03F8012B002A30 :10472000F9D170476F72672E6172647570696C6F32 -:10473000742E6D726F5F6D31303032357265764335 -:104740000000000040A2E4F1646891060041A3E586 -:10475000F2656992070000004261642043414E49BE -:104760006661636520696E6465782E0080000000D4 -:104770000080000000008000000000000000000039 -:10478000211800083D200008991F00086118000842 -:104790006D1800086D1A000831180008411800084B -:1047A000351800083D18000839180008911900084C -:1047B000451800080D230008551800086519000861 -:1047C00063300000C047000880380020503A0020C5 -:1047D0006D61696E0069646C65000000A001A82A23 -:1047E00000000000FAAABEAA50001424EFFF000047 -:1047F0000077000070970900010000000000000031 -:10480000AAAAAAAA01000000FFFF00000000000001 -:10481000000000000000000000000000AAAAAAAAF0 -:1048200000000000FFFF000000000000000000008A -:104830000000000000000000AAAAAAAA00000000D0 -:10484000FFFF00000000000000000000000000006A -:1048500000000000AAAAAAAA00000000FFFF0000B2 -:104860000000000000000000000000000000000048 -:10487000AAAAAAAA00000000FFFF00000000000092 -:104880000000000000000000DD3F0008C93F0008F4 -:1048900005400008F13F0008FD3F0008E93F00081F -:1048A000D53F0008C13F000811400008000000008B -:1048B00079040000000000000098030000000000E0 -:1048C000FE2A0100D20400001C110020000000009C +:10473000742E6D526F4B697443414E72657643001F +:1047400040A2E4F1646891060041A3E5F265699234 +:10475000070000004261642043414E496661636581 +:1047600020696E6465782E008000000000800000E3 +:104770000000800000000000000000002118000878 +:104780003D200008991F0008611800086D180008F6 +:104790006D1A000831180008411800083518000883 +:1047A0003D1800083918000891190008451800083C +:1047B0000D23000855180008651900086330000033 +:1047C000BC47000880380020503A00206D61696EB7 +:1047D0000069646C65000000A001A82A00000000C8 +:1047E000FAAABEAA50001424EFFF000000770000D0 +:1047F000709709000100000000000000AAAAAAAA00 +:1048000001000000FFFF00000000000000000000A9 +:104810000000000000000000AAAAAAAA00000000F0 +:10482000FFFF00000000000000000000000000008A +:1048300000000000AAAAAAAA00000000FFFF0000D2 +:104840000000000000000000000000000000000068 +:10485000AAAAAAAA00000000FFFF000000000000B2 +:10486000000000000000000000000000AAAAAAAAA0 +:1048700000000000FFFF000000000000000000003A +:1048800000000000DD3F0008C93F000805400008A7 +:10489000F13F0008FD3F0008E93F0008D53F000850 +:1048A000C13F00081140000879040000000000002A +:1048B0000098030000000000FE2A0100D20400005E +:1048C0001C1100200000000000000000000000009B :1048D00000000000000000000000000000000000D8 :1048E00000000000000000000000000000000000C8 :1048F00000000000000000000000000000000000B8 :1049000000000000000000000000000000000000A7 :104910000000000000000000000000000000000097 -:0C4920000000000000000000000000008B +:044920000000000093 :00000001FF diff --git a/Tools/bootloaders/rGNSS_bl.bin b/Tools/bootloaders/rGNSS_bl.bin index 11593c73e2fd52..81055c357beb36 100755 Binary files a/Tools/bootloaders/rGNSS_bl.bin and b/Tools/bootloaders/rGNSS_bl.bin differ diff --git a/Tools/bootloaders/sw-nav-f405_bl.bin b/Tools/bootloaders/sw-nav-f405_bl.bin index 308f76f1fb5f45..e4bcac19c24eaf 100755 Binary files a/Tools/bootloaders/sw-nav-f405_bl.bin and b/Tools/bootloaders/sw-nav-f405_bl.bin differ diff --git a/Tools/bootloaders/sw-nav-f405_bl.hex b/Tools/bootloaders/sw-nav-f405_bl.hex index cb588d700be370..2b27b817de76df 100644 --- a/Tools/bootloaders/sw-nav-f405_bl.hex +++ b/Tools/bootloaders/sw-nav-f405_bl.hex @@ -1,1198 +1,1148 @@ :020000040800F2 -:1000000000070020F5040008DD26000895260008FA -:10001000BD26000895260008B5260008F70400084C -:10002000F7040008F7040008F7040008D1360008B8 -:10003000F7040008F7040008F7040008F7040008B4 -:10004000F7040008F7040008F7040008F7040008A4 -:10005000F7040008F70400089D440008C5440008A0 -:10006000ED440008154500083D450008F704000868 -:10007000F7040008F7040008F7040008F704000874 -:10008000F7040008F7040008F704000849260008F0 -:100090007526000885260008F70400086545000855 -:1000A000F7040008F7040008F7040008F704000844 -:1000B00039460008F7040008F7040008F7040008B0 -:1000C000F7040008F7040008F7040008F704000824 -:1000D000F7040008F7040008F7040008F704000814 -:1000E000C9450008F7040008F7040008F7040008F1 -:1000F000F7040008F7040008F7040008F7040008F4 -:10010000F7040008F7040008F7040008F7040008E3 -:10011000F7040008F7040008F7040008F7040008D3 -:10012000F7040008F7040008F7040008F7040008C3 -:10013000F7040008F7040008F7040008F7040008B3 -:10014000F7040008F7040008F7040008F7040008A3 -:10015000F7040008F7040008F7040008F704000893 -:10016000F7040008F7040008F7040008F704000883 -:10017000F7040008F7040008F7040008F704000873 -:10018000F7040008F7040008F7040008F704000863 -:10019000F7040008F7040008F7040008F704000853 -:1001A000F7040008F7040008F7040008F704000843 -:1001B000F7040008F7040008F7040008F704000833 -:1001C000F7040008F7040008F7040008F704000823 -:1001D000F7040008F7040008F7040008F704000813 -:1001E000BD12000800000000000000000000000038 -:1001F00053B94AB9002908BF00281CBF4FF0FF318E -:100200004FF0FF3000F074B9ADF1080C6DE904CE89 -:1002100000F006F8DDF804E0DDE9022304B07047E1 -:100220002DE9F047089D04468E46002B4DD18A42A9 -:10023000944669D9B2FA82F252B101FA02F3C2F1DC -:10024000200120FA01F10CFA02FC41EA030E94406D -:100250004FEA1C48210CBEFBF8F61FFA8CF708FB8E -:1002600016E341EA034306FB07F199420AD91CEB66 -:10027000030306F1FF3080F01F81994240F21C8198 -:10028000023E63445B1AA4B2B3FBF8F008FB1033E0 -:1002900044EA034400FB07F7A7420AD91CEB040415 -:1002A00000F1FF3380F00A81A74240F207816444E5 -:1002B000023840EA0640E41B00261DB1D44000236A -:1002C000C5E900433146BDE8F0878B4209D9002DCE -:1002D00000F0EF800026C5E9000130463146BDE858 -:1002E000F087B3FA83F6002E4AD18B4202D38242C2 -:1002F00000F2F980841A61EB030301209E46002D71 -:10030000E0D0C5E9004EDDE702B9FFDEB2FA82F2C5 -:10031000002A40F09280A1EB0C014FEA1C471FFA23 -:100320008CFE0126200CB1FBF7F307FB131140EA0A -:1003300001410EFB03F0884208D91CEB010103F1D7 -:10034000FF3802D2884200F2CB804346091AA4B299 -:10035000B1FBF7F007FB101144EA01440EFB00FE6D -:10036000A64508D91CEB040400F1FF3102D2A645D2 -:1003700000F2BB800846A4EB0E0440EA03409CE771 -:10038000C6F12007B34022FA07FC4CEA030C20FA1E -:1003900007F401FA06F31C43F9404FEA1C4900FA3E -:1003A00006F3B1FBF9F8200C1FFA8CFE09FB1811BB -:1003B00040EA014108FB0EF0884202FA06F20BD92E -:1003C0001CEB010108F1FF3A80F08880884240F27E -:1003D0008580A8F102086144091AA4B2B1FBF9F0C2 -:1003E00009FB101144EA014100FB0EFE8E4508D9BD -:1003F0001CEB010100F1FF346CD28E456AD9023842 -:10040000614440EA0840A0FB0294A1EB0E01A14226 -:10041000C846A64656D353D05DB1B3EB080261EB94 -:100420000E0101FA07F722FA06F3F1401F43C5E96E -:10043000007100263146BDE8F087C2F12003D840A4 -:100440000CFA02FC21FA03F3914001434FEA1C47E6 -:100450001FFA8CFEB3FBF7F007FB10360B0C43EAD8 -:10046000064300FB0EF69E4204FA02F408D91CEB88 -:10047000030300F1FF382FD29E422DD90238634486 -:100480009B1B89B2B3FBF7F607FB163341EA034126 -:1004900006FB0EF38B4208D91CEB010106F1FF3875 -:1004A00016D28B4214D9023E6144C91A46EA00466C -:1004B00038E72E46284605E70646E3E61846F8E6FE -:1004C0004B45A9D2B9EB020864EB0C0E0138A3E747 -:1004D0004646EAE7204694E74046D1E7D0467BE728 -:1004E000023B614432E7304609E76444023842E7A0 -:1004F000704700BF02E000F000F8FEE772B6374830 -:1005000080F30888364880F3098836483649086001 -:1005100040F20000CCF200004EF63471CEF2000141 -:100520000860BFF34F8FBFF36F8F40F20000C0F23F -:10053000F0004EF68851CEF200010860BFF34F8FF5 -:10054000BFF36F8F4FF00000E1EE100A4EF63C71E2 -:10055000CEF200010860062080F31488BFF36F8F8D -:1005600003F0B2FD03F044FE4FF055301F491B4A23 -:1005700091423CBF41F8040BFAE71D49184A9142E9 -:100580003CBF41F8040BFAE71A491B4A1B4B9A423D -:100590003EBF51F8040B42F8040BF8E7002018495D -:1005A000184A91423CBF41F8040BFAE703F090FD72 -:1005B00003F072FE144C154DAC4203DA54F8041BE0 -:1005C0008847F9E700F042F8114C124DAC4203DACB -:1005D00054F8041B8847F9E703F078BD00070020B2 -:1005E000002300200000000808ED00E000010020CA -:1005F00000070020404A000800230020802300203C -:1006000080230020684D0020E0010008E40100087C -:10061000E4010008E40100082DE9F04F2DED108AF7 -:10062000C1F80CD0C3689D46BDEC108ABDE8F08FC0 -:10063000002383F311882846A047002003F0CAF95D -:10064000FEE703F02DF900DFFEE70000F8B500F04B -:1006500047FE03F0D3FC074603F022FD0546D0BB5E -:10066000294B9F4237D001339F4237D0274B27F089 -:10067000FF029A4235D1F8B200F03EFC2E4642F21B -:10068000107400F03FFC08B10024264601F014F974 -:1006900058B3032000F03EF80024264635B11C4B29 -:1006A0009F4203D003F0F4FC00242646002003F010 -:1006B000AFFC0EB100F044F800F090FC00F012FE28 -:1006C00002F014F80546B4B900F0D0FC4FF47A708B -:1006D00003F086F9F7E72E460024D2E70446012608 -:1006E000CFE7064641F28834CBE7002CD6D04FF452 -:1006F0007A740126D2E701F0F9FF431BA342E3D944 -:1007000000F01EF8DCE700BF010007B0000008B0F1 -:10071000263A09B0084B187003280CD8DFE800F01F -:1007200008050208022000F039BE022000F02EBEAB -:10073000024B00225A60704780230020842300204F -:1007400010B501F0B9F830B1204B03221A70204BDC -:1007500000225A6010BD1F4B1F4A1C461968013108 -:10076000F8D004339342F9D162681C4B9A42F1D914 -:100770001B4B9B6803F1006303F580339A42E9D277 -:1007800003F05AFC03F06CFC002000F0C5FD0220D1 -:10079000FFF7C0FF134B1A6C00221A64196E1A6619 -:1007A000196E596C5A64596E5A665B6E72B64FF088 -:1007B000E0233021C3F8084DD4E9003281F31188D9 -:1007C0009D4683F308881047C4E700BF80230020BC -:1007D000842300200000010820000108FFFF00081A -:1007E0000023002000380240094A136849F26900DA -:1007F00099B21B0C00FB01331360064B186844F2DE -:10080000506182B2000C01FB0200186080B2704798 -:10081000182300201423002010B5002110220446C4 -:1008200000F0D8FD034B03CB206061601868A06026 -:1008300010BD00BF107AFF1F2DE9F041ADF54C7DD2 -:100840000DF12C086AAC40F2751207460D460CA853 -:100850000021C8F8001000F0BDFD4FF4C472002163 -:10086000204600F0B7FD01F041FF274B4FF47A72AC -:10087000B0FBF2F0186093E80700022384E8070059 -:100880000DF5E5702382FFF7C7FF47F217231F49D5 -:10089000238407A803F0DCFF0E2384F832310DF225 -:1008A000DB2207AB0DF1240C1E4603CE664510601B -:1008B0005160334602F10802F6D130681060B38807 -:1008C000938041460122204600F0D0FD002303938F -:1008D000AB7E029305F11903019380B20123CDE9A8 -:1008E00004800093E97E06A3D3E90023384602F092 -:1008F000C5FA0DF54C7DBDE8F08100BFAFF3008077 -:100900009E6AC421818A46EE8C230020604800083C -:100910002DE9F0412C4C237ADAB080460D465BBBC2 -:1009200027A9284600F0B2FE0746002842D19DF8CC -:100930009D60C82E3ED801464FF4A662204600F0C6 -:1009400049FD4FF48073C4F8F8314FF40073C4F8D4 -:100950000C334FF44073C4F8203432460DF19E013D -:1009600004F1090000F024FD26449DF89C307772C4 -:1009700023720BB9EB7E23728122002106AC27A8DB -:1009800000F028FD0122214627A800F0BBFE00232D -:100990000393AB7E029305F1190380B201932823E0 -:1009A000CDE904400093E97E05A3D3E90023404646 -:1009B00002F064FA5AB0BDE8F08100BFAFF30080E6 -:1009C00026417272DF25D7B7A8440020F0B5254E26 -:1009D0004FF48A7505FB0065F1B096F8D83085F8BC -:1009E000DC300024D822214685F8E8403AA800F0FF -:1009F000F1FC06F1090000F0E5FCD5F8E4308DF8D3 -:100A0000F000C2B206AF06F109010DF1F100CDE927 -:100A10003A3400F0CDFC394601223AA800F09EFE9F -:100A200080B2CDE9047008230127CDE9023706F131 -:100A3000D803019330230093317A0B4807A3D3E9FD -:100A4000002302F01BFAA04206DD01F04FFEC5F8BC -:100A5000E000384671B0F0BD2046FBE778F6339FE2 -:100A600093CACD8DA8440020A43300202DE9F04185 -:100A70001D4D1E4E1E4F86B0284602F02BFA03462F -:100A800058B30024CDE90344ADF81440027B8DF83F -:100A9000142099684068029403AA03C21B68DFF817 -:100AA000548043F00043029301F022FE821941F189 -:100AB0000003009402A9384601F0E4F8A04205DDE5 -:100AC000284602F00BFA88F80040D5E798F8003085 -:100AD000072B05D8013388F8003006B0BDE8F08157 -:100AE000014802F0FBF9F8E7A433002040420F0070 -:100AF000D8330020DD49002070B50D4614461E464F -:100B000002F018F950B9022E10D1012C0ED112A307 -:100B1000D3E90023C5E90023012007E0282C10D0E9 -:100B200005D8012C09D0052C0FD0002070BD302C29 -:100B3000FBD10BA3D3E90023ECE70BA3D3E90023FC -:100B4000E8E70BA3D3E90023E4E70BA3D3E90023F1 -:100B5000E0E700BFAFF30080401DA12026812A0BF3 -:100B600078F6339F93CACD8D9E6AC421818A46EE62 -:100B700026417272DF25D7B7F017304A39059E56E5 -:100B800038B505460E4C0021013500F0E7FBA4F80E -:100B90002C55B4F82C0500F0C9FB78B1B4F82C053D -:100BA00000F0D4FB014648B9B4F82C0500F0D6FBA0 -:100BB000B4F82C350133A4F82C35EAE738BD00BF72 -:100BC000A844002010B50A4B0A4A1A6003F5805366 -:100BD00093F860203AB9DC6D2CB1204600F0EAFEB3 -:100BE000204603F075FDBDE81040034800F0E2BE6A -:100BF000D8330020AC480008204400202DE9F04FF5 -:100C00008FB000AF05460C4602F094F8002849D199 -:100C1000237E022B1BD1E38A012B18D101F066FD44 -:100C20000646FFF7E1FD03464FF4C870DFF8C482C3 -:100C3000B3FBF0F206F5167602FB103316FA83F3D7 -:100C4000C8F80030E37E33B9A34B00221A703C375A -:100C5000BD46BDE8F08F07F12401204600F0D4FC2A -:100C60000028F4D107F11400FFF7D6FD97F82640CD -:100C700007F11401224607F1270003F073FD002855 -:100C8000E2D10F2C08D8944B1C70D8F80030A3F593 -:100C90001673C8F80030DAE797F82410284602F0F7 -:100CA00041F8D4E7E38A282B2BD010D8012B23D08E -:100CB000052BCCD1BFF34F8F8849894BCA6802F40A -:100CC000E0621343CB60BFF34F8F00BFFDE7302BD3 -:100CD000BDD1844EE17E327A9142B8D1607E3146F8 -:100CE000002291F8DC50854200F0A5800132042AF0 -:100CF00001F58A71F5D1AAE721462846FFF79CFD48 -:100D0000A5E721462846FFF703FEA0E7B2F8EC501E -:100D10007B6005F103094FEA99094FEA8902D11D69 -:100D2000C908A8EBC1039D46EB460021584600F0D8 -:100D300051FB04F1EE012A463144584600F038FBDD -:100D40007B6813B9012000F0E7FA96F8D20000F0B2 -:100D5000EDFA044630B9307200F008FB204600F08E -:100D6000DBFAB1E0D6F8D4203AB996F8D200B6F85A -:100D70002C25824201D8FFF703FFD6F8D4202A445D -:100D8000944208D296F8D200B6F82C25013082425F -:100D900001D8FFF7F5FE70685FFA89F2594600F056 -:100DA00021FB08B9C54679E0726896F8D2002A445A -:100DB0007260D6F8D42005EB0209C6F8D49000F092 -:100DC000B5FA814509D396F8D220D6F8D40001327D -:100DD000001B86F8D220C6F8D400FF2D0FD80024BF -:100DE000347200F0C3FA204600F096FA00F064FD79 -:100DF0003D4B188108B9FFF7A3FCC54627E7BB6840 -:100E000096F8D9000AFB0362FB68D2F8E41082F876 -:100E1000E83001F58061C2F8E030C2F8E410FFF775 -:100E2000D5FDFFF723FE96F8D920013202F0030228 -:100E300086F8D920B6E74FF48A7A0AFB02F505F165 -:100E4000EA013144204600F0B5FCF86000287FF448 -:100E5000FEAE3544012285F8E82001F047FCD5F8C4 -:100E6000E020D6ED007ADFED216A801A192838BF1C -:100E7000192040F6B832904228BF1046B8EE677A83 -:100E800007EE900AF8EEE77A67EEA67ADFED186AC9 -:100E9000E7EE267AFCEEE77AC6ED007A96F8D930CE -:100EA000BB60BA6873680AFB02F4321992F8E81062 -:100EB00059B1D2F8E4108B42E8463FF427AF002145 -:100EC00082F8E810C2F8E010C5467368064A9B0A2B -:100ED00001331381BBE600BF9D33002000ED00E02D -:100EE0000400FA05A84400208C230020CDCCCC3D82 -:100EF0006666663FA0330020014B1870704700BF44 -:100F00009823002030B54FF000542B4B22689A42B2 -:100F100085B007D003F0CEF8044620BB002420465D -:100F200005B030BD254B627D25481A70237D0372C4 -:100F30004FF48073C0F8F8314FF40073C0F80C33ED -:100F400000254FF44073C0F820341E49C0F8E45027 -:100F5000C922093000F02CFA2046E022294600F090 -:100F600039FA0124DBE7184A184D136C43F000737B -:100F70001364AA6D164B9A42D0D12B6E013B7E2B87 -:100F8000CCD8144A07CA01AB83E8070018460321EE -:100F900000F060FC6B6D83424FF00003BED12A6D00 -:100FA0008A4201BFAB65054B2A6E1A7003BF0A4B1C -:100FB000EA6D1A601C46B2E79AAD44C5982300203A -:100FC000A8440020160000200038024000660040BF -:100FD0005041A0B0586600401023002037B51A4D8C -:100FE00000F06AFC02236B71184B288119681848BD -:100FF000012201F019FA00230193164B16490093C0 -:101000001648174B4FF4805201F064FE154B1978C7 -:1010100011B1124801F086FE01F068FB0446FFF7AB -:10102000E3FB4FF4C873B0FBF3F202FB130304F5C8 -:10103000167010FA83F00C4B186003F031F808B109 -:101040000F232B8103B030BD8C2300201023002000 -:10105000D8330020F90A00089C230020A433002084 -:10106000FD0B000898230020A03300202DE9F04F4D -:101070002DED028B0FF23829D9E90089834C93B00A -:101080000BAE9FED7E8BFFF7F1FC814FDFF828A2BE -:1010900000230A93ADF834300B9373604FF0000BCC -:1010A0005B468DED008B01250DF11D0207A9384629 -:1010B0008DF81C508DF81DB001F066F99DF81C30BC -:1010C000002B40F0A580204601F034FE06460028A3 -:1010D00045D1704F01F00AFB3B6898423FD301F0C5 -:1010E00005FB8246FFF780FB4FF4C873B0FBF3F2B9 -:1010F00002FB13030AF5167010FA83F03860664F8E -:1011000097F800B0CBF1100ABBF1000F14BF3346C3 -:101110002B465FFA8AFA0EA88DF82830FFF77CFB81 -:10112000BAF1060F28BF4FF0060A0EAB03EB0B0116 -:1011300052460DF1290000F03BF90AAB0393182346 -:1011400002930AF10102554BD2B2CDE90053049249 -:1011500020464CA3D3E9002301F032FE3E7001F09B -:10116000C5FA4F4A4F4D1368C31AB3F57A7F2ED391 -:10117000106001F0BDFA02460B46204601F0B8FEB1 -:10118000204601F0D7FD10B32B7A474E002B14BF39 -:1011900003230223737101F0A9FA0EAF4FF47A739F -:1011A0000122B0FBF3F039463060304600F004FA1B -:1011B000182302933D4B019380B240F25513CDE9C1 -:1011C0000370009342464B46204601F0F9FD2B7A0E -:1011D00093B101F08BFA002607464FF48A7A95F80E -:1011E000D900304400F003000AFB005393F8E820D4 -:1011F00092B30136042EF2D1C82002F0F1FB2B7A13 -:10120000002B7FF43DAF13B0BDEC028BBDE8F08F37 -:10121000DAF8143083F01003CAF81430594610225B -:101220000EA800F0D7F80DF11E0308AA0AA9384647 -:1012300000F026FE96E803000FAB83E803009DF85C -:1012400034308DF844300A9B0E930EA9DDE9082353 -:10125000204602F021F821E7D3F8E02042B12B68C4 -:10126000FA2B38BFFA23BA1A0533B2EB430FC0D3B7 -:10127000FFF7ACFB0028BCD1BEE700BF00000000B8 -:1012800000000000401DA12026812A0BA43300206D -:10129000D8330020A03300209D3300209C33002051 -:1012A000D8490020A84400208C230020DC490020DD -:1012B000F1C6A7C1D068080F0008024008B505486C -:1012C00000F078FEBDE80840034A0449002003F01E -:1012D000F9B900BFD8330020184A0020C50B000818 -:1012E0007047000070B502F023FD094E094D3080B3 -:1012F000002428683388834208D902F013FD2B6844 -:1013000004440133B4F5803F2B60F2D370BD00BFBD -:101310000C4A0020E049002002F0B8BD00F1006056 -:10132000920000F5803002F049BD0000054B1A68BC -:10133000054B1B889B1A834202D9104402F0F2BC71 -:1013400000207047E04900200C4A0020024B1B6837 -:10135000184402F0EFBC00BFE0490020024B1B68BC -:10136000184402F0FFBC00BFE0490020064991F894 -:10137000243033B10023086A81F824300822FFF7B3 -:10138000CDBF0120704700BFE4490020022802BF02 -:10139000014B10229A61704700080240022802BFE8 -:1013A000024B4FF480129A61704700BF0008024060 -:1013B00010B50023934203D0CC5CC4540133F9E749 -:1013C00010BD000003460246D01A12F9011B002985 -:1013D000FAD1704702440346934202D003F8011B3E -:1013E000FAE770472DE9F8431F4D144695F824207D -:1013F0000746884652BBDFF870909CB395F82430BE -:101400002BB92022FF2148462F62FFF7E3FF95F812 -:101410002400C0F10802A24228BF2246D6B24146AB -:10142000920005EB8000FFF7C3FF95F82430A41B62 -:101430001E44F6B2082E17449044E4B285F82460A6 -:10144000DBD1FFF793FF0028D7D108E02B6A03EB2D -:1014500082038342CFD0FFF789FF0028CBD1002041 -:10146000BDE8F8830120FBE7E44900202DE9F047BF -:101470000D46044600219046284640F27912FFF7B7 -:10148000A9FF234620220021284601F0A7FE231DA4 -:1014900002222021284601F0A1FE631D0322222101 -:1014A000284601F09BFEA31D03222521284601F0BA -:1014B00095FE04F1080310222821284601F08EFE33 -:1014C00004F1100308223821284601F087FE04F1B8 -:1014D000110308224021284601F080FE04F1120386 -:1014E00008224821284601F079FE04F11403202245 -:1014F0005021284601F072FE04F1180340227021A9 -:10150000284601F06BFE04F120030822B021284692 -:1015100001F064FE04F121030822B821284601F0FD -:101520005DFE04F12207C0263B46314608222846CC -:10153000083601F053FEB6F5A07F07F10107F3D19D -:1015400004F1320308223146284601F047FE002705 -:1015500004F1330A94F832304FEAC7099F4209F583 -:10156000A47615D3B8F1000F08D1314604F599736C -:101570000722284601F032FE09F24F16274694F85A -:1015800032213B1B93420CD3F01DC008BDE8F0870D -:101590000AEB070308223146284601F01FFE0137F7 -:1015A000D8E707F2331331460822284601F016FE29 -:1015B00008360137E3E7000013B50446084600216A -:1015C00001602346C0F803102022019001F006FEBE -:1015D0000198231D0222202101F000FE0198631DC5 -:1015E0000322222101F0FAFD0198A31D03222521E7 -:1015F00001F0F4FD019804F108031022282101F004 -:10160000EDFD072002B010BDF7B50023047F009167 -:101610000E4607221946054601F0A4FC731C0093F0 -:10162000012200230721284601F09CFCC4B9B31C09 -:101630000093052223460821284601F093FC0D243F -:101640003746B278BB1B934211D32B7FA88A07344D -:10165000E408BBB9844294BF0020012003B0F0BD70 -:10166000AB8ADB00083BDB08B3700824E8E7FB1C0F -:101670000093214600230822284601F073FC083419 -:101680000137DEE7201A18BF0120E7E7F7B500238E -:10169000047F00910E4608221946054601F062FCBF -:1016A000731CC4B90822009311462346284601F052 -:1016B00059FC1024012372785F1C013B934211D323 -:1016C0002B7FA88A0734E408BBB9844294BF00206A -:1016D000012003B0F0BDAB8ADB00083BDB08737070 -:1016E0000824E7E7F319009321460023082228463F -:1016F00001F038FC08343B46DDE7201A18BF012012 -:10170000E7E70000F8B50E460546144600218122A1 -:101710003046FFF75FFE2B4608220021304601F0DD -:101720005DFD7CB96B1C07220821304601F056FD97 -:101730000F2401236A785F1C013B934204D3E01D10 -:10174000C008F8BD0824F4E7EB192146082230460A -:1017500001F044FD08343B46ECE70000F8B50E46C6 -:10176000054614460021CE223046FFF733FE2B46B5 -:1017700028220021304601F031FD7CB905F1080333 -:1017800008222821304601F029FD30242F462A7AEC -:101790007B1B934204D3E01DC008F8BD2824F5E765 -:1017A00007F1090321460822304601F017FD0834ED -:1017B0000137ECE7F7B5047F00910E4601231022B4 -:1017C0000021054601F0CEFBC4B9B31C00930922E9 -:1017D00023461021284601F0C5FB1924374672889C -:1017E000BB1B9A4211D82B7FA88A0734E408BBB9E7 -:1017F000844294BF0020012003B0F0BDAB8ADB001F -:10180000103BDB0873801024E8E73B1D0093214662 -:1018100000230822284601F0A5FB08340137DEE743 -:10182000201A18BF0120E7E730B5094D0A4491425C -:101830000DD011F8013B5840082340F30004013B50 -:101840002C4013F0FF0384EA5000F6D1EFE730BDDF -:101850002083B8EDF7B54FF0FF33DFF854C0DFF861 -:1018600054E000EB81011A4688421CD050F8044B2A -:10187000019401AF042417F8015B82EA0562082590 -:10188000DB18164605F1FF355241002EBCBF83EA36 -:101890000C0382EA0E0215F0FF05F1D1013C14F0B1 -:1018A000FF04E8D1E0E7D843D14303B0F0BD00BF67 -:1018B0009336EAA9EBE1F042F7B5384A106851686F -:1018C0006B4603C36A4636493648082302F05AFF7E -:1018D0000446002833D10A25334A106851686B4604 -:1018E00003C36A4631492F48082302F04BFF0446E0 -:1018F000002849D00369B3F5702F45D8B0F86610B9 -:1019000041F2727291423FD1294A024402F15C01D4 -:101910008B4239D35C3B234900209E1AFFF784FF9A -:101920003246074604F164010020FFF77DFFA368FB -:101930009F4229D1E368984208BF002524E003694B -:10194000B3F5702F27D8418B41F27272914220D1AA -:10195000174A024402F110018B4218D3103B11497F -:1019600000209D1AFFF760FF2A46064604F1180181 -:101970000020FFF759FFA3689E4202D1E368984216 -:1019800001D00D25A8E70025284603B0F0BD10259D -:10199000A2E70C25A0E70B259EE700BF70480008D2 -:1019A000DCFF0E00000001087948000890FF0E00DF -:1019B0000800FFF710B5037C044613B9006802F075 -:1019C000C9FE204610BD00000023BFF35B8FC3603B -:1019D000BFF35B8FBFF35B8F8360BFF35B8F704799 -:1019E000BFF35B8F0068BFF35B8F704770B5054630 -:1019F0000C30FFF7F5FF05F1080604463046FFF707 -:101A0000EFFFA04206D930466D68FFF7E9FF254495 -:101A1000281A70BD3046FFF7E3FF201AF9E70000EF -:101A200070B50546406898B105F10800FFF7D8FF8A -:101A300005F10C0604463046FFF7D2FF84423046DB -:101A400094BF6D680025FFF7CBFF013C2C44201AA2 -:101A500070BD000038B50C460546FFF7C7FFA04231 -:101A600010D305F10800FFF7BBFF04446868B4FB1E -:101A7000F0F100FB1144BFF35B8F0120AC60BFF3BA -:101A80005B8F38BD0020FCE72DE9F0411446074686 -:101A90000D46FFF7C5FF844228BF0446D4B1B846BF -:101AA00058F80C6B4046FFF79BFF304428604046D7 -:101AB0007E68FFF795FF331A9C4203D86C600120C3 -:101AC000BDE8F0816B60A41B3B68AB602044E8601C -:101AD0000220F5E72046F3E738B50C460546FFF748 -:101AE0009FFFA04210D305F10C00FFF779FF0444DB -:101AF0006868B4FBF0F100FB1144BFF35B8F012079 -:101B0000EC60BFF35B8F38BD0020FCE72DE9FF419F -:101B1000884669460746FFF7B7FF6C4606B204EBF6 -:101B2000C6060025B44209D06268206808EB0501AA -:101B3000FFF73EFC636808341D44F3E72946384646 -:101B4000FFF7CAFF284604B0BDE8F081F8B50546A6 -:101B50000C300F46FFF744FF05F1080604463046F7 -:101B6000FFF73EFFA042304688BF6C68FFF738FFA2 -:101B7000201A386020B130462C68FFF731FF20442E -:101B8000F8BD000073B5144606460D46FFF72EFF5C -:101B9000844228BF04460190DCB101A93046FFF71A -:101BA000D5FF019B33B93268C5E90233C5E900248A -:101BB00001200CE09C4238BF0194286001986860C5 -:101BC0008442F5D93368AB60241AEC60022002B07D -:101BD00070BD2046FBE700002DE9FF410F46694636 -:101BE000FFF7D0FF6C4600B204EBC0050026AC4204 -:101BF00009D0D4F8048054F8081BB8194246FFF7FE -:101C0000D7FB4644F3E7304604B0BDE8F08100005E -:101C100038B50546FFF7E0FF044601462846FFF7C2 -:101C200019FF204638BD0000302383F3118862B6C7 -:101C300070470000002383F3118862B670470000EC -:101C400010B4026854681A4623465DF8044B1847DE -:101C50000120704700207047002070477047000047 -:101C6000002070470E20704700F5805090F8C800A3 -:101C7000C0F340007047000000F5805090F9C900A3 -:101C800070470000F7B50C68BDF8207014F00054E0 -:101C90001E466FD10B7B082B6CD8FFF7C5FF45693B -:101CA000AB685B010CD4AB681B0108D4AC6814F0C2 -:101CB00080545DD1FFF7BEFF204603B0F0BD012484 -:101CC0000B6804F1180C002BB8BFDB004FEA0C1CAA -:101CD000B4BF43F004035B0545F80C300B680FFA02 -:101CE00084FC13F0804F18BF05EB0C1E05EB0C1C99 -:101CF0001EBFDEF8803143F00203CEF880310B7B4B -:101D0000CCF8843105EB04158B68C5F88C314B6831 -:101D1000C5F88831DCF8803143F00103CCF880311C -:101D200000EB441541F268031D4403EB44130344E4 -:101D3000C5E9002608330D4601F10C0C55F804EBFB -:101D400043F804EB6545F9D184342D881D8000EB00 -:101D5000441407F00303257925F00B052B43237169 -:101D6000FFF768FF0097334600F0E2FC0120A4E78C -:101D70000224A5E74FF0FF309FE7000013B500F500 -:101D800080540191E06DFFF74BFE1F280AD901999D -:101D9000E06D2022FFF7BAFEA0F12003584258411F -:101DA00002B010BD0020FBE708B500F58050FFF73A -:101DB0003BFFC06DFFF708FEBDE80840FFF73ABFE4 -:101DC00000220260828142608260704710B500226A -:101DD0000023C0E900230023044603810C30FFF7F1 -:101DE000EFFF204610BD0000F0B5054600F580501D -:101DF0000C4690F8C83013F0040FC3F3800108BFFD -:101E0000114661F3820304F1840680F8C83005EBC3 -:101E1000461389B01B79D8072ED57AB319072DD46C -:101E20006846FFF7D3FF05EB441303F5835303F133 -:101E3000180703AA103318685968144603C40833F6 -:101E4000BB422246F7D1186820609B88A380DDE959 -:101E50000E23CDE900230123ADF808302B68694635 -:101E6000DB6B2846984705EB46152B791A075CBFB4 -:101E700043F008032B7101E0002AF4D109B0F0BD52 -:101E80002DE9F047074688B007F5805468469A4622 -:101E90008846FFF7C9FE9146FFF798FFE06DFFF710 -:101EA000A5FD1F2829D9E06D20226946FFF7B0FE65 -:101EB000202822D103AD444605AB2E4603CE9E42D8 -:101EC00020606160354604F10804F6D13068206076 -:101ED000B388A380DDE90023C9E90023BDF80830F9 -:101EE000AAF80030FFF7A6FE4A4653464146384658 -:101EF00008B0BDE8F04700F009BCFFF79BFE0020EA -:101F000008B0BDE8F08700002DE9F84F0023C0E9D4 -:101F10000133254B044640F8183B0F46FFF750FFAE -:101F200004F12800FFF752FF04F1480804F5825538 -:101F30004646083530462036FFF748FFAE42F9D115 -:101F400004F580554FF480534FF00009C5E913396B -:101F5000C5F848800123EE6504F5875804F58456DA -:101F6000C5F8549085F8583085F86030083608F187 -:101F700008084FF0000A4FF0000B46E908ABA6F145 -:101F80001800FFF71DFF203646F8289C4645F4D17F -:101F900085F8C97017B1054800F0A2FB044B6361D6 -:101FA0002046BDE8F88F00BFAC4800088448000810 -:101FB0000064004010B5044B197804464A1C1A709E -:101FC000FFF7A2FF204610BD144A00202DE9F0477C -:101FD000002950D0294B2A4FB7FBF1F599428CBF0D -:101FE0000A231123581EB5FBF3FC03FB1C53C4B298 -:101FF0002BB102280346F5D80020BDE8F0870CF18C -:10200000FF36B6F5806FF7D2C4EBC40E0EF10303B2 -:102010004FEAE309C3F3C703A4EB030809F1010A7C -:102020004FF47A755FFA88F009FB05555AFA88F87B -:10203000B5FBF8F5B5F5617FC1BF0EF1FF33C3F312 -:10204000C703E01AC0B25C1C50FA84F40CFB04F421 -:10205000B7FBF4F4A142CFD1013BDBB20F2BCBD8BD -:102060000138C0B20728C7D80021107116809170BE -:10207000D3700120C1E70846BFE700BF3F420F0011 -:1020800080DE800270B505460E464FF47A746B69A7 -:102090005B6803F00103B34207D04FF47A7001F09C -:1020A0009FFC013CF3D1204670BD0120FCE70000FD -:1020B00030B54269936913F0700F16D000230B4CB2 -:1020C000936103F1840200EB421211794D0709D5A7 -:1020D000890707D5416954F823508D60117941F083 -:1020E000040111710133032BEBD130BD9848000876 -:1020F00073B51D46436916469A68D207044609D54A -:102100009A6801219960C2F34002CDE9006500217F -:10211000FFF76AFE63699A68D1050BD59A684FF498 -:1021200080719960C2F34022CDE90065012120460B -:10213000FFF75AFE63699A68D2030BD59A684FF489 -:1021400080319960C2F34042CDE90065022120460A -:10215000FFF74AFE204602B0BDE87040FFF7A8BF77 -:10216000F8B50446466900296CD106F10C073868B9 -:1021700080076AD006EB01153868D5F8B00110F079 -:10218000040FD5F8B0011ABFC00840F00040400D60 -:10219000A061D5F8B0C11CF0020F1CBF40F0804018 -:1021A000A061D5F8B40106EB011100F00F0084F82E -:1021B0002400D1F8B8012077D1F8B801000A60777F -:1021C000D1F8B801000CA077D1F8B801000EE07783 -:1021D000D1F8BC0184F82000D1F8BC01000A84F8D1 -:1021E0002100D1F8BC01000C84F82200D1F8BC1108 -:1021F000090E84F823103821396004F1340004F109 -:10220000180104F1240551F8046B40F8046BA9424D -:10221000F9D109880180C4E90A23214600232386D5 -:1022200051F8283B2046DB6B984704F58052204646 -:1022300092F8C83043F0040382F8C830BDE8F84093 -:10224000FFF736BF06F1100791E7F8BD10B5044659 -:1022500000F04EFA02460B4652EA030102D0013A60 -:1022600063F100030449086820B12146BDE810402D -:10227000FFF776BF10BD00BF104A0020F8B500F58B -:1022800083511E46FFF7D0FCDFF844C0083100241C -:1022900004F1840500EB45152B795F070ED4DB06AE -:1022A0000CD5D1E900739742B34107D243695CF87A -:1022B00024709F602B7943F004032B710134032CAD -:1022C00001F12001E4D1BDE8F840FFF7B3BC00BF45 -:1022D0009848000808B5FFF7A7FCFFF7E9FEBDE83E -:1022E0000840FFF7A7BC0000F8B5436905469868A9 -:1022F00000F0E050B0F1E05F0F461FD0E8B1FFF70B -:1023000093FC05F583541034002606F1840305EB95 -:1023100043131B791A0706D50136032E04F1200456 -:10232000F3D1012007E05B07F6D42146384600F0E0 -:1023300039FA0028F0D1FFF77DFCF8BD0120FCE759 -:1023400000F5805008B5FFF76FFCC06DFFF74EFB3E -:10235000FFF770FC43090CBF0120002008BD0000FE -:10236000F8B51D46002313700F4606461446FFF7C6 -:10237000E7FF80F00100387025B129463046FFF7AD -:10238000B3FF2070F8BD00002DE9B8410C4615469A -:102390001F46804600F0ACF90B462178024609B989 -:1023A000287850B14046FFF769FFFFF793FF3B469F -:1023B0002A462146FFF7D4FF0120BDE8B88100007E -:1023C00010B5FFF731FC174B1A6C42F000721A641B -:1023D0001A6A42F000721A621A6A00F5805422F0FA -:1023E00000721A62FFF726FC94F8C830DB0718D495 -:1023F000B9B103211320FFF717FC01F0C7F903213E -:10240000142001F0C3F90321152001F0BFF994F85D -:10241000C83043F0010384F8C830BDE81040FFF72E -:1024200009BC10BD003802402DE9F04700F5805589 -:1024300088B095F8C930012B0446884616467FD8E7 -:10244000804F57F823200AB947F82300D7F800A097 -:10245000C4F80C802674BAF1000F63D095F8C93027 -:10246000012B6FD001212046FFF7AAFFFFF7DCFB0D -:102470006269136823F0020313606269136843F012 -:1024800001031360636900275F6101212046FFF7A4 -:10249000D1FBFFF7F7FD002800F09580E86DFFF70E -:1024A00093FA04F58359BA4609F10809202200215C -:1024B0006846FEF78FFF02A8FFF782FCCDF818A050 -:1024C0006A4609EB07030DF1180E9446BCE80300B9 -:1024D000F44518605960624603F10803F5D1DCF851 -:1024E0000000186020379CF804201A71602FDDD19D -:1024F00095F8C8306FF38203002785F8C8306A4624 -:1025000041462046ADF80070ADF802708DF80470B9 -:10251000FFF75CFD636948BB4FF400421A6008B0E6 -:10252000BDE8F08741F2D00002F0D4F8814610B146 -:102530005146FFF7E9FCC7F80090B9F1000F8DD1C3 -:102540000020ECE7386803681B6B984701460028B9 -:1025500088D13868FFF734FF3868036832465B6813 -:102560004146984700287FF47DAFE9E761221A6071 -:102570009DF802309DF803201B06120402F470221D -:1025800003F040731343BDF80020C2F30902134364 -:102590009DF804201205022E02F4E0020CBF4FF059 -:1025A00000410021134362690B43D3616369132225 -:1025B0005A616269136823F00103136039462046AB -:1025C000FFF760FD08B96369A6E795F8C93093BBCA -:1025D0006169D1F8002242F00102C1F8002261696C -:1025E000D1F8002222F47C5222F00E02C1F800221F -:1025F0006169D1F8002242F46062C1F80022626988 -:10260000C2F814326269C2F80432626941F6FF719D -:10261000C2F80C126269C2F840326269C2F84432F0 -:1026200063690122C3F81C226269D2F8003223F0E8 -:102630000103C2F8003295F8C83043F0020385F870 -:10264000C8306CE7104A002008B500F051F850EA95 -:102650000103024602D0421E61F10001044B1868DA -:1026600010B10B46FFF744FDBDE8084001F064B827 -:10267000104A002008B50020FFF7E8FDBDE808403B -:1026800001F05AB808B50120FFF7E0FDBDE80840A9 -:1026900001F052B800B59BB0EFF30981682268469B -:1026A000FEF786FEEFF30583014B9B6BFEE700BF51 -:1026B00000ED00E008B5FFF7EDFF000000B59BB0AE -:1026C000EFF3098168226846FEF772FEEFF3058397 -:1026D000014B5B6BFEE700BF00ED00E0FEE7000092 -:1026E0000FB408B5029801F011F9FEE701F024BC1F -:1026F00001F0FCBB13B56C4684E80600031D94E8AA -:10270000030083E80500012002B010BD73B58568A1 -:10271000019155B11B885B0707D4D0E900369B6B4C -:102720009847019AC1B23046A847012002B070BD57 -:10273000F0B5866889B005460C465EB1BDF8383004 -:102740005B070AD4D0E900379B6B98472246C1B299 -:102750003846B047012009B0F0BD00220023CDE982 -:1027600000230023ADF808300A4603AB01F1080648 -:10277000106851681C4603C40832B2422346F7D1A0 -:10278000106820609288A280FFF7B2FF0423ADF8A2 -:1027900008302B68CDE90001DB6B69462846984775 -:1027A000D8E7000030B503680968DD0FB5EBD17FCD -:1027B00023F0604421F060424FEAD1700BD0002B2F -:1027C000B8BFA40C0029B8BF920C944202D034BF09 -:1027D0000120002030BD944205D1C1F38070C3F3C5 -:1027E00080738342F6D194422CBF00200120F1E790 -:1027F0002DE9F041456A15B94162BDE8F0814B68A9 -:1028000023F06047C3F38A464FEAD37EC3F3807850 -:1028100016EA230638BF3E46AC462B465A68BEEB46 -:10282000D27F22F060440AD0002A18DAA40CB44205 -:1028300017D19D420FD10D60DEE71346EEE7A742A8 -:1028400007D102F08044C2F3807242450BD054B1EC -:10285000EFE708D2EDE7CCF800100B60CDE7B4420B -:1028600001D0B442E5D81A689C46002AE5D1196027 -:10287000C3E700002DE9F047089D01F007044FEA87 -:10288000D508224405F0070500EBD1004FF47F493D -:10289000944201D1BDE8F08704F0070705F0070A6C -:1028A00057453E4638BF5646C6F10806111B8E42B4 -:1028B00028BF0E46E10808EBD50E415C13F80EC0A8 -:1028C000B94029FA06F721FA0AF1FFB28CEA0101B0 -:1028D00047FA0AF739408CEA010C03F80EC0344479 -:1028E0003544D5E780EA0120082341F2210201B2F4 -:1028F0004000002980B203F1FF33B8BF504013F00D -:10290000FF03F4D17047000038B50C468D18A5427E -:1029100000D138BD14F8011BFFF7E4FFF7E7000012 -:1029200042684AB1136843604389818901339BB28D -:102930009942438138BF83811046704770B588B093 -:10294000202204460D4668460021FEF743FD20463E -:102950000495FFF7E5FF024658B16B46054608AE01 -:102960001C4603CCB44228606960234605F1080583 -:10297000F6D1104608B070BD082817D909280CD028 -:102980000A280CD00B280CD00C280CD00D280CD009 -:102990000E2814BF4020302070470C2070471020B4 -:1029A000704714207047182070472020704700009F -:1029B000082817D90C280CD910280CD914280CD9A0 -:1029C00018280CD920280CD930288CBF0F200E20B5 -:1029D0007047092070470A2070470B2070470C2071 -:1029E00070470D20704700002DE9F843078C072F32 -:1029F00004461ED9D0E9029800254FF6FF73C5F1B1 -:102A00002006A5F1200029FA05F108FA06F628FAB1 -:102A100000F031430143C9B21846FFF763FF0835A0 -:102A2000402D0346EBD1E1693A46BDE8F843FFF794 -:102A30006BBF4FF6FF70BDE8F883000010B54B6820 -:102A400023B9CA8A63F30902CA8210BD04691A68ED -:102A50001C600361C38A013BC3824A60EFE7000048 -:102A60002DE9F84F1D46CB8A0F46C3F3090105290E -:102A7000814692460B4630D00020AAB207F11A04D4 -:102A80009EB2042E1FFA80F80FD8904503F101037F -:102A900006D3FB8A0A4462F30903FB8201201AE091 -:102AA0001AF80060E6540130EAE79045F1D2A1F14E -:102AB000050B1C237C68BBFBF3F203FB12BB1FFA64 -:102AC0008BF6002C45D14846FFF72AFF044638B95B -:102AD00078606FF00200BDE8F88F4FF00008E6E77D -:102AE000002606607860ADB24FF0000B454510D966 -:102AF0000AEB0803221D13F8011B9155B1B208F12E -:102B000001081B291FFA88F82BD0454506F101065C -:102B1000F1D8FB8AC3F30902154465F30903BCE746 -:102B2000013292B21C462368002BF9D16B1F0B4473 -:102B30001C21B3FBF1F301339BB29A42D3D2BBF118 -:102B4000000FD0D14846FFF7EBFE20B9C4F800B023 -:102B5000BFE70122E7E7C0F800B05E462060044608 -:102B6000C1E74545D5D94846FFF7DAFE08B92060E8 -:102B7000AFE7C0F800B0002620600446B6E70000CA -:102B80002DE9F04F2DED028B1C4683B05B6901925D -:102B900007468846002B00F09A80238C2BB1E2690F -:102BA000002A00F09480072B35D807F10C00FFF7BE -:102BB000B7FE054638B96FF00205284603B0BDECF4 -:102BC000028BBDE8F08F14220021FEF703FC228C5B -:102BD000E16905F10800FEF7EBFB208C013080B2C3 -:102BE000FFF7E6FEFFF7C8FE013880B2208401300F -:102BF00028746369228C1B782A4403F01F0363F056 -:102C00003F0348F000411372384669602946FFF7D8 -:102C1000EFFD0125D1E700F10C034FF0000908EEAC -:102C2000103A4FF0800A4E464D4618EE100AFFF754 -:102C300077FE83460028BED014220021FEF7CAFB8F -:102C4000002E3AD1019BABF8083002220BF1080E9E -:102C50001FFA82FC0CF10100BCF1060F218C80B23E -:102C600001D88E422BD3FFF7A3FEFFF785FE6269E2 -:102C70001278013802F01F028E4208BF4FF0400A5E -:102C800042EA49121BFA80F14AEA020A013048F08E -:102C9000004281F808A08BF81000CBF804205946B8 -:102CA0003846FFF7A5FD238C0135B3422DB289F0DC -:102CB00001094FF0000AB8D17FE70022C6E7E169B9 -:102CC000895D0EF802100136B6B20132C0E76FF02E -:102CD000010572E7F8B515460E463022002104467C -:102CE0001F46FEF777FB069B6360B5F5001F079B49 -:102CF000A76034BF6A094FF6FF72A36297B2E6611C -:102D000004F1100000239A4206D800230360A78232 -:102D1000E3822383E360F8BD06600133304620364A -:102D2000F1E7000003781BB94BB2002BC8BF01705C -:102D30007047000000787047F8B50C46C96907462F -:102D400011B9238C002B37D1257E1F2D34D838782C -:102D500028BB228C072A2CD8268A36F003032BD1D5 -:102D60004FF6FF70FFF7D0FD20F001003102400464 -:102D700041EA0561400C41EA40254FF6FF722346C7 -:102D800029463846FFF7FCFE002807DD6269137804 -:102D90000133DBB21F2B88BF00231370F8BD218ADB -:102DA0002D0645EA012505432046FFF71DFE024694 -:102DB000E5E76FF00300F1E76FF00100EEE70000D8 -:102DC00070B58AB0044616460021282268461D4682 -:102DD000FEF700FBBDF83830ADF810300F9B0593BF -:102DE0009DF840308DF81830119B07936946BDF867 -:102DF0004830ADF820302046CDE90265FFF79CFF52 -:102E00000AB070BD2DE9F041D36905460C4616465F -:102E10000BB9138C5BBB377E1F2F28D895F8008029 -:102E2000B8F1000F26D03046FFF7DEFD33782102DF -:102E300041EAC33141EA0801338A41EA076141EAC4 -:102E400003410246334641F080012846FFF798FED1 -:102E500000280ADD3378012B07D17269137801331A -:102E6000DBB21F2B88BF00231370BDE8F0816FF029 -:102E70000100FAE76FF00300F7E70000F0B58BB050 -:102E800004460D4617460021282268461E46FEF7D6 -:102E9000A1FA9DF84C305A1E534253418DF8003030 -:102EA0009DF84030ADF81030119B05939DF84830E7 -:102EB0008DF81830149B07936A46BDF85430ADF86E -:102EC000203029462046CDE90276FFF79BFF0BB064 -:102ED000F0BD0000406A00B104307047436A1A68D0 -:102EE000426202691A600361C38A013BC382704770 -:102EF0002DE9F041D0F82080194E14461D46414678 -:102F0000002709B9BDE8F081D1E90223A21A65EBD7 -:102F10000303964277EB03031ED2036A8B420DD163 -:102F2000FFF78CFD036A1B68036203690B60C38AA9 -:102F30000161016A013BC3828846E2E7FFF77EFD3B -:102F40000B68C8F8003003690B60C38A0161013B5C -:102F5000C382D8F80010D4E788460968D1E700BFDB -:102F600080841E002DE9F04F8BB00D46DDF85090A7 -:102F700014469B468046002800F01981B9F1000FE5 -:102F800000F01581531E3F2B00F21181012A03D15D -:102F9000BBF1000F40F00B810023CDE90833B8F8F6 -:102FA0001430B5EBC30F4FEAC30703D300200BB0B7 -:102FB000BDE8F08F2B199F42D8F80C303ABF7F1B29 -:102FC000FFB227461BB9D8F81030002B7AD0272D36 -:102FD0004ED8C5F12806B7424FF000032CBFF6B219 -:102FE0003E4600932946D8F8080008AB3246FFF762 -:102FF00041FCA7EB060A35445FFA8AFAB8F81430A8 -:1030000003F10053053BDB000493D8F80C30039325 -:103010002821039B13B1BAF1000F2CD1D8F810006E -:1030200040B1BAF1000F05D0009608AB5246691ABC -:10303000FFF720FC38B2002FB8D066070AD00AABE1 -:1030400003EBD401624211F8083C02F0070213417D -:1030500001F8083C082C3CD9102C40F2B580202CFB -:1030600040F2B780BBF1000F00F09C80082334E0F1 -:10307000BA460026C2E7049BE02B28BFE023069354 -:103080000B44AB42059314D95A1B03980096924502 -:1030900034BF5246D2B2691A08AB04300792FFF728 -:1030A000E9FB079A1644AAEB020A1544F6B25FFA46 -:1030B0008AFA049B069A05999B1A0493039B1B6842 -:1030C0000393A6E70093D8F8080008AB3A462946D0 -:1030D000AEE7BBF1000F13D00123B4EBC30F6CD0EC -:1030E000082C12D89DF82030621E23FA02F2D50770 -:1030F00006D54FF0FF3202FA04F423438DF8203056 -:103100009DF8203089F8003051E7102C12D8BDF816 -:103110002030621E23FA02F2D10706D54FF0FF32AB -:1031200002FA04F42343ADF82030BDF82030A9F8AA -:1031300000303CE7202C0FD80899631E21FA03F3D6 -:10314000DA0705D54FF0FF3202FA04F40C43089475 -:10315000089BC9F800302AE7402C2BD0DDE9086530 -:10316000611EC4F12102A4F1210326FA01F105FA3E -:1031700002F225FA03F311431943CB0712D50122BA -:10318000A4F12003C4F1200102FA03F322FA01F1B1 -:10319000A240524243EA010363EB430332432B4311 -:1031A000CDE90823DDE90823C9E90023FFE66FF034 -:1031B0000100FCE66FF00800F9E6082CA0D9102CFD -:1031C000B3D9202CEED8C3E7BBF1000FADD002235A -:1031D00083E7BBF1000FBBD004237EE730B5012AA3 -:1031E000144638BF0124402C85B028BF4024002558 -:1031F000012ACDE9025518D81B788DF808306307ED -:103200000AD004AB03EBD405624215F8083C02F087 -:103210000702934005F8083C00910346224600212E -:1032200002A8FFF727FB05B030BD082AE4D9102A11 -:1032300003D81B88ADF80830E1E7202A8DBFD3E919 -:1032400000231B680293CDE90223D8E710B5CB68B1 -:103250001BB98B600B618B8210BD04691A681C60FE -:103260000361C38A013BC382CA60F0E703064CBF17 -:10327000C0F3C0300220704708B50246FFF7F6FFE2 -:10328000022806D15306C2F30F2001D100F003003B -:1032900008BDC2F30740FBE72DE9F04F93B0CDE93D -:1032A00003230A6804461046FFF7E0FF022814BF14 -:1032B000C2F306260026002A0D46824680F2F281DD -:1032C00012F0C04940F0EE81097B002900F0EA814C -:1032D000022803D02378B34240F0E781C2F30463AD -:1032E0000693104602F07F030593FFF7C5FF059B89 -:1032F00029444FEA834848EA0A4848EA4668CE78B3 -:1033000000230022CDE90823F309834648EA000898 -:10331000029367D0059B009302466768534608A94D -:103320002046B847002800F0C381276A4FB94146BC -:1033300004F10C00FFF702FB074690B96FF00200A2 -:1033400054E03B6998450DD03F68002FF9D14146C4 -:1033500004F10C00FFF7F2FA07460028EED0236ACA -:103360003B60276297F817C006F01F08CCF3840C67 -:10337000ACEB08001FFA80FE0028B8BF0EF1200059 -:10338000A8EB0C031FFA83FED7E90221B8BF00B2F5 -:10339000002B0793BEBF0EF120031BB2079352EA26 -:1033A000010338D0039BDFF824E39A1A049B4FF003 -:1033B000000C63EB010196457CEB01032BD36B7B87 -:1033C00097F81AE0734519D1029B002B78D0012899 -:1033D00021DC7868F8B9DFF8F0C2944570EB01039E -:1033E00016D337E0276A27B96FF00C0013B0BDE899 -:1033F000F08F3B699845B5D03F68F4E7B2489042FA -:103400007CEB010301D30020F0E7029B002BFAD0F4 -:10341000079B0F2B17DCFA7DB30002F0030203F0C9 -:103420007C031343FB7539462046FFF707FB6B7B94 -:10343000BB76029B3BB9FB7DC3F38402013262F38E -:103440008603FB75D0E76A7BBB7E9A42DBD1029B89 -:10345000002B35D0B309022B32D0039BBB60049BF9 -:10346000FB60142200210DA8FDF7B4FF039B0A9313 -:10347000049B0B932B1D0C932B7BADF83EB0013BB3 -:10348000DBB2ADF83C30069B8DF84230059B8DF8E1 -:10349000433094F82C308DF840A083F001038DF870 -:1034A00044308DF84180A3680AA920469847FB7DE7 -:1034B000C3F38403013303F01F039B02FB82A2E7E3 -:1034C000FB7DC6F34012B2EBD31F40F0F480C3F390 -:1034D0008403434540F0F280029A2B7BB609002A10 -:1034E0004DD0F2075DD4032B40F2EB80039BBB6011 -:1034F000049BFB602B7BAE1D033BDBB2324639469F -:1035000004F10C00FFF7ACFA00280CDA394620462B -:10351000FFF794FAFB7DC3F38403013303F01F0329 -:103520009B02FB820AE7DDE90884AB883B834FF608 -:10353000FF73C9F12000A9F1200228FA09F104FA69 -:1035400000F0014324FA02F211431846C9B2FFF712 -:10355000C9F909F10809B9F1400F0346E9D1B88268 -:103560002A7B033AD2B23146FFF7CEF9FB7DB8820F -:10357000DA43C2F3C01262F3C713FB7543E786B99F -:103580002E1D013BDBB23246394604F10C00FFF739 -:1035900067FA0028BADB2A7BB88A013AD2B23146F0 -:1035A000E2E7F98AC1F30901013B0429DAB25BD8E9 -:1035B000281D002307F11B069A4208D910F801CBF9 -:1035C00006F801C0013101330529DBB2F4D10399BA -:1035D0000A9104990B91934207F11B010C9138BF9A -:1035E000043379680D9134BF55FA83F300230E93A9 -:1035F000FB8AADF83EB0C3F309031A44069B8DF86D -:103600004230059B8DF8433094F82C30ADF83C20C7 -:1036100083F001038DF8443000238DF840A08DF82D -:1036200041807B602A7BB88A013A291DFFF76CF93B -:103630003B8BB882834203D1A3680AA920469847EE -:1036400020460AA9FFF702FEFB7DBA8AC3F3840372 -:10365000013303F01F039B02FB823B8B9A420CBF9A -:1036600000206FF01000C1E67B68002BAFD0052072 -:1036700001E01C3033461E68002EFAD1091A081DDD -:103680002E1D184401EB090CBCF11B0F5FFA89F3E6 -:103690009DD89A429BD916F8013B00F8013B09F1ED -:1036A0000109EFE76FF00900A0E66FF00A009DE660 -:1036B0006FF00B009AE66FF00D0097E66FF00E00CA -:1036C00094E66FF00F0091E640420F0080841E00E8 -:1036D000EFF3098305494A6B22F001024A6368331C -:1036E00083F30988002383F31188704700EF00E01B -:1036F000302080F3118862B60C4B0D4AD96821F452 -:10370000E0610904090C0A43DA60D3F8FC20094996 -:1037100042F08072C3F8FC200A6842F001020A609D -:103720002022DA7783F82200704700BF00ED00E026 -:103730000003FA05001000E010B5302383F3118870 -:103740000E4B5B6813F4006314D0F1EE103AEFF304 -:103750000984683C4FF08073E361094BDB6B23669F -:1037600084F3098800F090F810B1064BA36110BDF6 -:10377000054BFBE783F31188F9E700BF00ED00E09C -:1037800000EF00E0430600084606000800F1604331 -:1037900003F561430901C9B283F80013012200F067 -:1037A0001F039A4043099B0003F1604303F5614303 -:1037B000C3F880211A60704700230375826803698B -:1037C0001B6899689142FBD25A680360426010609E -:1037D0005860704700230375826803691B68996805 -:1037E0009142FBD85A68036042601060586070478D -:1037F00008B50846302383F311880B7D032B05D0D1 -:10380000042B0DD02BB983F3118808BD8B690022DE -:103810001A604FF0FF338361FFF7CEFF0023F2E71A -:10382000D1E9003213605A60F3E70000FFF7C4BF2C -:10383000054BD9680875186802681A605360012240 -:103840000275D860FCF7E8BE204A002030B50C4B6A -:10385000DD684B1C87B004460FD02B46094A6846EA -:1038600000F050F92046FFF7E3FF009B13B16846D4 -:1038700000F052F9A86907B030BDFFF7D9FFF9E7AA -:10388000204A0020F1370008044B1A68DB68906872 -:103890009B68984294BF002001207047204A002076 -:1038A000084B10B51C68D86822681A605360012262 -:1038B0002275DC60FFF78EFF01462046BDE8104010 -:1038C000FCF7AABE204A0020044B1A68DB68926805 -:1038D0009B689A4201D9FFF7E3BF7047204A002056 -:1038E00038B5074C07490848012300252370656057 -:1038F00000F026FC0223237085F3118838BD00BF39 -:10390000884C0020F0480008204A002008B572B614 -:10391000044B186500F0CEFA00F08CFB024B03223A -:103920001A70FEE7204A0020884C002000F02AB9D7 -:10393000EFF3118020B9EFF30583302282F3118871 -:103940007047000010B530B9EFF30584C4F30804E4 -:1039500014B180F3118810BDFFF7B6FF84F311880E -:10396000F9E700008B60022308618B8208467047EC -:103970008368A3F1840243F8142C026943F8442CB1 -:10398000426943F8402C094A43F8242CC26843F8A2 -:10399000182C022203F80C2C002203F80B2C044AEA -:1039A00043F8102CA3F12000704700BF3106000837 -:1039B000204A002008B5FFF7DBFFBDE80840FFF70D -:1039C00035BF0000024BDB6898610F20FFF730BF66 -:1039D000204A0020302383F31188FFF7F3BF000053 -:1039E00008B50146302383F311880820FFF72EFF26 -:1039F000002383F3118808BD10B503689C68A242B8 -:103A00000CD85C688A600B604C60216059609968D2 -:103A10008A1A9A604FF0FF33836010BD1B68121B37 -:103A2000ECE700000A2938BF0A2170B504460D46AC -:103A30000A26601900F07EFB00F06AFB041BA54219 -:103A400003D8751C2E460446F3E70A2E04D9BDE8B8 -:103A50007040012000F0B4BB70BD0000F8B5144BFD -:103A60000D46D96103F1100141600A2A196982608B -:103A700038BF0A22016048601861A818144600F097 -:103A80004BFB0A2700F044FB431BA342064606D328 -:103A90007C1C281900F04EFB27463546F2E70A2F1A -:103AA00004D9BDE8F840012000F08ABBF8BD00BF92 -:103AB000204A0020F8B506460D4600F029FB0F4AC3 -:103AC000134653F8107F9F4206D12A4601463046DE -:103AD000BDE8F840FFF7C2BFD169BB68441A2C1992 -:103AE00028BF2C46A34202D92946FFF79BFF224656 -:103AF00031460348BDE8F840FFF77EBF204A00206A -:103B0000304A002010B4C0E9032300235DF8044BC1 -:103B10004361FFF7CFBF000010B5194C23699842ED -:103B20000DD0D0E90032816813605A609A680A4467 -:103B30009A60002303604FF0FF33A36110BD23465A -:103B4000026843F8102F53600022026022699A42F3 -:103B500003D1BDE8104000F0E7BA936881680B44D8 -:103B6000936000F0D5FA2269E1699268441AA24292 -:103B7000E4D91144BDE81040091AFFF753BF00BF54 -:103B8000204A00202DE9F047DFF8BC8008F110073B -:103B90002C4ED8F8105000F0BBFAD8F81C40AA6898 -:103BA000031B9A423ED81444D5E900324FF0000975 -:103BB000C8F81C4013605A60C5F80090D8F810305F -:103BC000B34201D100F0B0FA89F31188D5E903318D -:103BD00028469847302383F311886B69002BD8D08F -:103BE00000F096FA6A69A0EB04094A4582460DD2B4 -:103BF000022000F0E5FA0022D8F81030B34208D1D4 -:103C000051462846BDE8F047FFF728BF121A224464 -:103C1000F2E712EB090938BF4A4629463846FFF752 -:103C2000EBFEB5E7D8F81030B34208D01444211A9F -:103C3000C8F81C00A960BDE8F047FFF7F3BEBDE877 -:103C4000F08700BF304A0020204A00200020704743 -:103C5000FEE70000704700004FF0FF3070470000A3 -:103C6000BFF34F8F024AD368DB03FCD4704700BF19 -:103C7000003C024008B5094B1B7873B9FFF7F0FF11 -:103C8000074B1A69002ABFBF064A5A6002F1883200 -:103C90005A601A6822F480621A6008BD904C0020B5 -:103CA000003C02402301674508B50B4B1B7893B9D4 -:103CB000FFF7D6FF094B1A6942F000421A611A68F1 -:103CC00042F480521A601A6822F480521A601A680C -:103CD00042F480621A6008BD904C0020003C024013 -:103CE0000B28F0B516D80C4C0C4923787BB90C4D39 -:103CF0000E460C234FF0006255F8047B46F8042B67 -:103D0000013B13F0FF033A44F6D10123237051F82D -:103D10002000F0BD0020FCE7C44C0020944C0020A3 -:103D2000FC480008014B53F820007047FC4800088D -:103D30000C2070470B2810B5044601D9002010BD97 -:103D4000FFF7CEFF064B53F824301844C21A0BB9C4 -:103D50000120F4E712680132F0D1043BF6E700BF1E -:103D6000FC4800080B2810B5044621D8FFF778FF5F -:103D7000FFF780FF0F4AF323D360C300DBB243F4A5 -:103D8000007343F002031361136943F4803313613A -:103D9000FFF766FFFFF7A4FF074B53F8241000F06E -:103DA00045F9FFF781FF2046BDE81040FFF7C2BF8D -:103DB000002010BD003C0240FC480008F8B512F09D -:103DC0000103144642D18218B2F1016F57D82D4B2E -:103DD0001B6813F0010352D02B4DFFF74BFFF32369 -:103DE000EB60FFF73DFF40F20127032C15D824F0CC -:103DF00001046618244C401A40F20117B1422369AD -:103E000000EB010524D123F001032361FFF74CFFF0 -:103E10000120F8BD043C0430E7E78307E7D12B69B4 -:103E200023F440732B612B693B432B6151F8046BE6 -:103E30000660BFF34F8FFFF713FF03689E42E9D080 -:103E40002B6923F001032B61FFF72EFF0020E0E731 -:103E500023F44073236123693B4323610B882B8048 -:103E6000BFF34F8FFFF7FCFE2D8831F8023BADB258 -:103E7000AB42C3D0236923F001032361E4E7184672 -:103E8000C7E700BF00380240003C0240084908B5BF -:103E90000B7828B11BB9FFF7EDFE01230B7008BDAD -:103EA000002BFCD0BDE808400870FFF7FDBE00BF46 -:103EB000904C002008B54FF400314FF0005000F056 -:103EC000B7F8BDE808404FF480314FF0805000F063 -:103ED000AFB800000846114600F01EBC012000F0FB -:103EE0001BBC0000084600F035BC000070B582B075 -:103EF000FFF71EFD0E4E054600F00AF932689042AB -:103F000037BF0C4A0B49516814682EBFD1E90041F4 -:103F1000013151600419034641F100012846019125 -:103F20003360FFF70FFD0199204602B070BD00BF5E -:103F3000C84C0020D04C002070B582B0FFF7F8FCD0 -:103F4000104E054600F0E4F83268904237BF0E4A42 -:103F50000D49516814682EBFD1E90041013151600B -:103F6000041941F100010346284601913360FFF72F -:103F7000E9FC01994FF47A7200232046FCF738F9E6 -:103F800002B070BDC84C0020D04C002010B50244D7 -:103F9000064BD2B2904200D110BD441C00B253F87F -:103FA000200041F8040BE0B2F4E700BF50280040C5 -:103FB0000F4B30B51C6F240407D41C6F44F40074FD -:103FC0001C671C6F44F400441C670A4C236843F4CC -:103FD000807323600244084BD2B2904200D130BDBE -:103FE000441C00B251F8045B43F82050E0B2F4E7FF -:103FF00000380240007000405028004007B5012200 -:1040000001A90020FFF7C2FF019803B05DF804FB8F -:1040100013B50446FFF7F2FFA04205D0012201A923 -:1040200000200194FFF7C4FF02B010BD70470000EC -:104030007047000070470000074B45F255521A6068 -:1040400002225A6040F6FF729A604CF6CC421A6027 -:10405000024B01221A70704700300040DC4C0020F7 -:10406000034B1B781BB1034B4AF6AA221A60704718 -:10407000DC4C002000300040034B1A681AB9034A98 -:10408000D2F874281A607047D84C002000300240E3 -:10409000024B4FF08072C3F8742870470030024022 -:1040A00008B5FFF7E9FF024B1868C0F3407008BD80 -:1040B000D84C002008B5FFF7DFFF024B1868C0F3AB -:1040C000007008BDD84C002070470000FEE70000DB -:1040D0000A4B0B480B4A90420BD30B4BDA1C121ABB -:1040E000C11E22F003028B4238BF00220021FDF7DF -:1040F00071B953F8041B40F8041BECE7C04A0008F0 -:10410000684D0020684D0020684D002000F0D0B8B8 -:104110004FF08043586A70474FF080430022586345 -:104120001A610222DA6070474FF080430022DA60A1 -:10413000704700004FF0804358637047FEE700006F -:1041400070B51B4B01630025044686B0586085623C -:104150000E46FFF7CDFA04F11003C4E904334FF023 -:10416000FF33C4E90635C4E90044A560E562FFF702 -:10417000CFFF2B460246C4E9082304F134010D4A5F -:10418000256580232046FFF7EDFB0123E0600A4A06 -:104190000375009272680192B268CDE90223074B61 -:1041A0006846CDE90435FFF705FC06B070BD00BFD9 -:1041B000884C00202C490008314900083D41000886 -:1041C000024AD36A1843D062704700BF204A0020D9 -:1041D0004B6843608B688360CB68C3600B69436145 -:1041E0004B6903628B6943620B6803607047000090 -:1041F00008B5264B26481A6940F2FF110A431A6196 -:104200001A6922F4FF7222F001021A611A691A6B0C -:104210000A431A631A6D0A431A651E4A1B6D11463A -:10422000FFF7D6FF02F11C0100F58060FFF7D0FF19 -:1042300002F1380100F58060FFF7CAFF02F1540176 -:1042400000F58060FFF7C4FF02F1700100F58060A7 -:10425000FFF7BEFF02F18C0100F58060FFF7B8FFA9 -:1042600002F1A80100F58060FFF7B2FF02F1C4017E -:1042700000F58060FFF7ACFF02F1E00100F580601F -:10428000FFF7A6FFBDE8084000F08EB800380240F6 -:10429000000002403849000808B500F0F9F9FFF7BE -:1042A0001FFBBDE80840FFF7E7BE000070470000B5 -:1042B0000F4B1A6C42F001021A641A6E42F00102AE -:1042C0001A660C4A1B6E936843F0010393604FF02B -:1042D000804353229A624FF0FF32DA6200229A61E1 -:1042E0005A63DA605A6001225A611A60704700BF4F -:1042F00000380240002004E04FF0804208B5116908 -:10430000D3680B40D9B2C9439B07116107D530234D -:1043100083F31188FFF70AFB002383F3118808BD9C -:104320001F4B1A696FEAC2526FEAD2521A611A69B8 -:10433000C2F308021A614FF0FF301A695A695861D6 -:1043400000215A6959615A691A6A62F080521A62E8 -:104350001A6A02F080521A621A6A5A6A58625A6AD3 -:1043600059625A6A1A6C42F080521A641A6E42F00C -:1043700080521A661A6E0B4A106840F48070106002 -:10438000186F00F44070B0F5007F1EBF4FF480300E -:1043900018671967536823F40073536000F054B929 -:1043A0000038024000700040334B4FF080521A64D6 -:1043B000324A4FF4404111601A6842F001021A601B -:1043C0001A689107FCD59A6822F003029A602A4B7A -:1043D0009A6812F00C02FBD1196801F0F90119601A -:1043E0009A601A6842F480321A601A689203FCD507 -:1043F0005A6F42F001025A671F4B5A6F9007FCD563 -:104400001F4A5A601A6842F080721A601B4A536849 -:104410005904FCD5184B1A689201FCD5194A9A60C8 -:10442000194B1A68194B9A42194B21D1194A116834 -:10443000194A91421CD140F205121A60144A1368BD -:1044400003F00F03052BFAD10B4B9A6842F00202DE -:104450009A609A6802F00C02082AFAD15A6C42F467 -:1044600080425A645A6E42F480425A665B6E7047CC -:1044700040F20572E1E700BF0038024000700040E2 -:104480000854400700948838002004E0116400209C -:10449000003C024000ED00E041C20F41074A08B570 -:1044A000536903F00103536123B1054A13680BB14B -:1044B00050689847BDE80840FFF73EB9003C01400E -:1044C000E04C0020074A08B5536903F0020353612A -:1044D00023B1054A93680BB1D0689847BDE80840FE -:1044E000FFF72AB9003C0140E04C0020074A08B51C -:1044F000536903F00403536123B1054A13690BB1F7 -:1045000050699847BDE80840FFF716B9003C0140E4 -:10451000E04C0020074A08B5536903F008035361D3 -:1045200023B1054A93690BB1D0699847BDE80840AB -:10453000FFF702B9003C0140E04C0020074A08B5F3 -:10454000536903F01003536123B1054A136A0BB199 -:10455000506A9847BDE80840FFF7EEB8003C0140BC -:10456000E04C0020164B10B55C6904F478725A6177 -:10457000A30604D5134A936A0BB1D06A9847600624 -:1045800004D5104A136B0BB1506B9847210604D524 -:104590000C4A936B0BB1D06B9847E20504D5094ADE -:1045A000136C0BB1506C9847A30504D5054A936C66 -:1045B0000BB1D06C9847BDE81040FFF7BDB800BF05 -:1045C000003C0140E04C0020194B10B55C6904F43C -:1045D0007C425A61620504D5164A136D0BB1506DC9 -:1045E0009847230504D5134A936D0BB1D06D9847B6 -:1045F000E00404D50F4A136E0BB1506E9847A10426 -:1046000004D50C4A936E0BB1D06E9847620404D562 -:10461000084A136F0BB1506F9847230404D5054A1D -:10462000936F0BB1D06F9847BDE81040FFF784B887 -:10463000003C0140E04C002008B5FFF75DFEBDE8FE -:104640000840FFF779B80000062108B50846FFF7D3 -:104650009DF806210720FFF799F806210820FFF7AB -:1046600095F806210920FFF791F806210A20FFF7A7 -:104670008DF806211720FFF789F806212820FFF77B -:1046800085F8BDE8084007211C20FFF77FB800002F -:1046900008B5FFF745FE00F007F8FFF707FEBDE895 -:1046A0000840FFF733BD00000023054A19460133D7 -:1046B000102BC2E9001102F10802F8D1704700BFC7 -:1046C000E04C00200B460146184600F02DB80000D3 -:1046D00000F040B8012838BF012010B5044620463C -:1046E00000F030F830B900F007F808B900F00CF825 -:1046F0008047F4E710BD0000024B1868BFF35B8FE2 -:10470000704700BF604D002008B5062000F084F817 -:104710000120FFF79DFA0000024B0A460146186887 -:10472000FFF7D8BB1C23002010B5054C13462CB155 -:104730000A4601460220AFF3008010BD2046FCE788 -:1047400000000000024B01461868FFF7C7BB00BF1E -:104750001C230020024B01461868FFF7C3BB00BFB3 -:104760001C23002010B501390244904201D10020E1 -:1047700005E0037811F8014FA34201D0181B10BDCA -:104780000130F2E72DE9F041A3B1C91A17780144CD -:10479000044603F1FF3C8C42204601D9002009E089 -:1047A0000578BD4204F10104F5D10CEB0405D618DF -:1047B000A54201D1BDE8F08115F8018D16F801ED93 -:1047C000F045F5D0E7E700001F2938B504460D464F -:1047D00004D9162303604FF0FF3038BD426C12B18C -:1047E00052F821304BB9204600F030F82A460146F5 -:1047F0002046BDE8384000F017B8012B0AD0591CFC -:1048000003D1162303600120E7E7002442F8254086 -:10481000284698470020E0E7024B01461868FFF75A -:10482000D3BF00BF1C23002038B5074D002304462A -:10483000084611462B60FFF70FFA431C02D12B6884 -:1048400003B1236038BD00BF644D0020FFF7FEB9FF -:10485000034611F8012B03F8012B002AF9D1704708 -:1048600073772D6E61762D663430352D626C0000C5 -:1048700040A2E4F1646891060041A3E5F265699203 -:10488000070000004261642043414E496661636550 -:1048900020696E6465782E008000000000800000B2 -:1048A000000080000000000000000000411C000823 -:1048B0002924000889230008511C0008851C0008D1 -:1048C000811E0008551C0008651C0008591C0008C2 -:1048D000611C00085D1C0008A91D0008691C000877 -:1048E000F5260008791C00087D1D000863300000D3 -:1048F000EC480008784A0020884C00200040000066 -:1049000000400000004000000040000000000100E6 -:10491000000002000000020000000200000002008F -:104920000000020000000200000002006D61696EDC -:104930000069646C650000005400806A000000009B -:10494000AAAAAA6A00000024F17F0000000000006B -:10495000009009000100000000000000AAAAAAAA15 -:1049600000000000FEFF000000000000000000004A -:104970000001000000000000AAAAAAAA000000008E -:10498000EFFF000000000000000000000000000039 -:1049900000000000AAAAAAAA00000000FFFF000071 -:1049A0000000000000000000000000000000000007 -:1049B000AAAAAAAA00000000FFFF00000000000051 -:1049C000000000000000000000000000AAAAAAAA3F -:1049D00000000000FFFF00000000000000000000D9 -:1049E0000000000000000000AAAAAAAA000000001F -:1049F000FFFF0000000000000000000000000000B9 -:104A0000000000000A000000000000000300000099 -:104A10000000000000000000000000000000000096 -:104A20000000000000000000000000000000000086 -:104A300000000000ECB7FF7F010000000000000054 -:104A4000721700000000000000000F0000000000CE -:104A500040420F00FE2A0100D20400002023002063 -:104A60000000000000000000000000000000000046 -:104A70000000000000000000000000000000000036 -:104A80000000000000000000000000000000000026 -:104A90000000000000000000000000000000000016 -:104AA0000000000000000000000000000000000006 -:104AB00000000000000000000000000000000000F6 +:1000000000070020F1010008F9230008B1230008CF +:10001000D9230008B1230008D1230008F301000808 +:10002000F3010008F3010008F3010008ED330008B4 +:10003000F3010008F3010008F3010008F3010008D0 +:10004000F3010008F3010008F3010008F3010008C0 +:10005000F3010008F30100087D410008A5410008F4 +:10006000CD410008F54100081D420008F3010008D9 +:10007000F3010008F3010008F3010008F301000890 +:10008000F3010008F3010008F301000865230008EC +:1000900091230008A1230008F3010008454200084D +:1000A000F3010008F3010008F3010008F301000860 +:1000B00019430008F3010008F3010008F3010008E8 +:1000C000F3010008F3010008F3010008F301000840 +:1000D000F3010008F3010008F3010008F301000830 +:1000E000A9420008F3010008F3010008F301000829 +:1000F000F3010008F3010008F3010008F301000810 +:10010000F3010008F3010008F3010008F3010008FF +:10011000F3010008F3010008F3010008F3010008EF +:10012000F3010008F3010008F3010008F3010008DF +:10013000F3010008F3010008F3010008F3010008CF +:10014000F3010008F3010008F3010008F3010008BF +:10015000F3010008F3010008F3010008F3010008AF +:10016000F3010008F3010008F3010008F30100089F +:10017000F3010008F3010008F3010008F30100088F +:10018000F3010008F3010008F3010008F30100087F +:10019000F3010008F3010008F3010008F30100086F +:1001A000F3010008F3010008F3010008F30100085F +:1001B000F3010008F3010008F3010008F30100084F +:1001C000F3010008F3010008F3010008F30100083F +:1001D000F3010008F3010008F3010008F30100082F +:1001E000B90F00080000000000000000000000003F +:1001F00002E000F000F8FEE772B6374880F30888A6 +:10020000364880F3098836483649086040F20000D5 +:10021000CCF200004EF63471CEF200010860BFF35C +:100220004F8FBFF36F8F40F20000C0F2F0004EF628 +:100230008851CEF200010860BFF34F8FBFF36F8F7C +:100240004FF00000E1EE100A4EF63C71CEF20001D4 +:100250000860062080F31488BFF36F8F03F0A4FDBD +:1002600003F036FE4FF055301F491B4A91423CBF08 +:1002700041F8040BFAE71D49184A91423CBF41F886 +:10028000040BFAE71A491B4A1B4B9A423EBF51F82E +:10029000040B42F8040BF8E700201849184A914271 +:1002A0003CBF41F8040BFAE703F082FD03F064FE63 +:1002B000144C154DAC4203DA54F8041B8847F9E797 +:1002C00000F042F8114C124DAC4203DA54F8041B12 +:1002D0008847F9E703F06ABD0007002000230020EB +:1002E0000000000808ED00E00001002000070020E9 +:1002F00018470008002300208023002080230020CE +:10030000604D0020E0010008E4010008E40100085D +:10031000E40100082DE9F04F2DED108AC1F80CD052 +:10032000C3689D46BDEC108ABDE8F08F002383F3BF +:1003300011882846A047002003F0B4F9FEE703F037 +:100340003DF900DFFEE70000F8B500F047FE03F0DE +:10035000C5FC074603F014FD0546C0BB294B9F4270 +:1003600035D001339F4235D0274B27F0FF029A4208 +:1003700033D1F8B200F03EFC2E4642F2107400F089 +:100380003FFC08B10024264601F012F948B30320CF +:1003900000F03EF80024264635B11C4B9F4203D0A6 +:1003A00003F0E6FC00242646002003F0A1FC0EB179 +:1003B00000F044F800F090FC02F026F80546C4B9BD +:1003C00000F0D2FC4FF47A7003F072F9F7E72E4692 +:1003D0000024D4E704460126D1E7064641F28834DA +:1003E000CDE741F288339C4204BF4FF47A74012672 +:1003F000D2E702F009F8431BA342E1D900F01EF84E +:10040000DAE700BF010007B0000008B0263A09B0E3 +:10041000084B187003280CD8DFE800F00805020824 +:10042000022000F037BE022000F02CBE024B00225A +:100430005A607047802300208423002010B501F00B +:10044000B7F830B1204B03221A70204B00225A60BB +:1004500010BD1F4B1F4A1C4619680131F8D00433E8 +:100460009342F9D162681C4B9A42F1D91B4B9B68AD +:1004700003F1006303F580339A42E9D203F04CFCA8 +:1004800003F05EFC002000F0C3FD0220FFF7C0FF78 +:10049000134B1A6C00221A64196E1A66196E596C85 +:1004A0005A64596E5A665B6E72B64FF0E023302183 +:1004B000C3F8084DD4E9003281F311889D4683F3D7 +:1004C00008881047C4E700BF802300208423002051 +:1004D0000000010820000108FFFF000800230020A1 +:1004E00000380240094A136849F2690099B21B0CAE +:1004F00000FB01331360064B186844F2506182B26E +:10050000000C01FB0200186080B270471823002025 +:100510001423002010B500211022044600F0D6FD5F +:10052000034B03CB206061601868A06010BD00BF62 +:10053000107AFF1F2DE9F041ADF54C7D0DF12C082F +:100540006AAC40F2751207460D460CA80021C8F8A7 +:10055000001000F0BBFD4FF4C4720021204600F0F3 +:10056000B5FD01F051FF274B4FF47A72B0FBF2F06A +:10057000186093E80700022384E807000DF5E57092 +:100580002382FFF7C7FF47F217231F49238407A8D9 +:1005900003F0CEFF0E2384F832310DF2DB2207ABDD +:1005A0000DF1240C1E4603CE6645106051603346A3 +:1005B00002F10802F6D130681060B388938041469A +:1005C0000122204600F0CEFD00230393AB7E029370 +:1005D00005F11903019380B20123CDE90480009352 +:1005E000E97E06A3D3E90023384602F0D5FA0DF5DB +:1005F0004C7DBDE8F08100BFAFF300809E6AC4214E +:10060000818A46EE8C230020404500082DE9F04108 +:100610002C4C237ADAB080460D465BBB27A92846CE +:1006200000F0B0FE0746002842D19DF89D60C82E1C +:100630003ED801464FF4A662204600F047FD4FF435 +:100640008073C4F8F8314FF40073C4F80C334FF4DE +:100650004073C4F8203432460DF19E0104F10900C4 +:1006600000F022FD26449DF89C30777223720BB96E +:10067000EB7E23728122002106AC27A800F026FD24 +:100680000122214627A800F0B9FE00230393AB7E88 +:10069000029305F1190380B201932823CDE90440A8 +:1006A0000093E97E05A3D3E90023404602F074FAE3 +:1006B0005AB0BDE8F08100BFAFF3008026417272EE +:1006C000DF25D7B7B0440020F0B5254E4FF48A752A +:1006D00005FB0065F1B096F8D83085F8DC300024D1 +:1006E000D822214685F8E8403AA800F0EFFC06F150 +:1006F000090000F0E3FCD5F8E4308DF8F000C2B258 +:1007000006AF06F109010DF1F100CDE93A3400F030 +:10071000CBFC394601223AA800F09CFE80B2CDE91C +:10072000047008230127CDE9023706F1D8030193AD +:1007300030230093317A0B4807A3D3E9002302F05A +:100740002BFAA04206DD01F05FFEC5F8E000384656 +:1007500071B0F0BD2046FBE778F6339F93CACD8D8C +:10076000B0440020A43300202DE9F0411D4D1E4E61 +:100770001E4F86B0284602F03BFA034658B30024C9 +:10078000CDE90344ADF81440027B8DF8142099683C +:100790004068029403AA03C21B68DFF8548043F048 +:1007A0000043029301F032FE821941F100030094EC +:1007B00002A9384601F0DAF8A04205DD284602F029 +:1007C0001BFA88F80040D5E798F80030072B05D8C9 +:1007D000013388F8003006B0BDE8F081014802F02E +:1007E0000BFAF8E7A433002040420F00D833002072 +:1007F000E549002070B50D4614461E4602F028F962 +:1008000050B9022E10D1012C0ED112A3D3E900232E +:10081000C5E90023012007E0282C10D005D8012CC1 +:1008200009D0052C0FD0002070BD302CFBD10BA3BC +:10083000D3E90023ECE70BA3D3E90023E8E70BA3FC +:10084000D3E90023E4E70BA3D3E90023E0E700BFEB +:10085000AFF30080401DA12026812A0B78F6339F3C +:1008600093CACD8D9E6AC421818A46EE264172725A +:10087000DF25D7B7F017304A39059E5638B50546FB +:100880000E4C0021013500F0E5FBA4F82C55B4F81E +:100890002C0500F0C7FB78B1B4F82C0500F0D2FBB2 +:1008A000014648B9B4F82C0500F0D4FBB4F82C3557 +:1008B0000133A4F82C35EAE738BD00BFB04400206E +:1008C00010B50A4B0A4A1A6003F5805393F860206A +:1008D0003AB9DC6D2CB1204600F0E8FE204603F06A +:1008E00067FDBDE81040034800F0E0BED8330020AB +:1008F0008C450008204400202DE9F04F8FB000AF58 +:1009000005460C4602F0A4F8002849D1237E022BAC +:100910001BD1E38A012B18D101F076FD0646FFF7C3 +:10092000E1FD03464FF4C870DFF8C482B3FBF0F278 +:1009300006F5167602FB103316FA83F3C8F800307A +:10094000E37E33B9A34B00221A703C37BD46BDE8A5 +:10095000F08F07F12401204600F0D2FC0028F4D1EA +:1009600007F11400FFF7D6FD97F8264007F11401B0 +:10097000224607F1270003F065FD0028E2D10F2C85 +:1009800008D8944B1C70D8F80030A3F51673C8F83B +:100990000030DAE797F82410284602F051F8D4E73F +:1009A000E38A282B2BD010D8012B23D0052BCCD1B8 +:1009B000BFF34F8F8849894BCA6802F4E062134342 +:1009C000CB60BFF34F8F00BFFDE7302BBDD1844E0E +:1009D000E17E327A9142B8D1607E3146002291F8B0 +:1009E000DC50854200F0A5800132042A01F58A71AD +:1009F000F5D1AAE721462846FFF79CFDA5E7214649 +:100A00002846FFF703FEA0E7B2F8EC507B6005F143 +:100A100003094FEA99094FEA8902D11DC908A8EBD9 +:100A2000C1039D46EB460021584600F04FFB04F100 +:100A3000EE012A463144584600F036FB7B6813B974 +:100A4000012000F0E5FA96F8D20000F0EBFA044637 +:100A500030B9307200F006FB204600F0D9FAB1E060 +:100A6000D6F8D4203AB996F8D200B6F82C258242AE +:100A700001D8FFF703FFD6F8D4202A44944208D2C5 +:100A800096F8D200B6F82C250130824201D8FFF743 +:100A9000F5FE70685FFA89F2594600F01FFB08B94D +:100AA000C54679E0726896F8D2002A447260D6F89A +:100AB000D42005EB0209C6F8D49000F0B3FA8145C2 +:100AC00009D396F8D220D6F8D4000132001B86F85C +:100AD000D220C6F8D400FF2D0FD80024347200F0C5 +:100AE000C1FA204600F094FA00F062FD3D4B1881F7 +:100AF00008B9FFF7A3FCC54627E7BB6896F8D900FD +:100B00000AFB0362FB68D2F8E41082F8E83001F5D2 +:100B10008061C2F8E030C2F8E410FFF7D5FDFFF7BE +:100B200023FE96F8D920013202F0030286F8D9207C +:100B3000B6E74FF48A7A0AFB02F505F1EA0131447F +:100B4000204600F0B3FCF86000287FF4FEAE354488 +:100B5000012285F8E82001F057FCD5F8E020D6ED19 +:100B6000007ADFED216A801A192838BF192040F673 +:100B7000B832904228BF1046B8EE677A07EE900A66 +:100B8000F8EEE77A67EEA67ADFED186AE7EE267AE6 +:100B9000FCEEE77AC6ED007A96F8D930BB60BA6809 +:100BA00073680AFB02F4321992F8E81059B1D2F8CE +:100BB000E4108B42E8463FF427AF002182F8E810AA +:100BC000C2F8E010C5467368064A9B0A01331381D8 +:100BD000BBE600BF9D33002000ED00E00400FA05F5 +:100BE000B04400208C230020CDCCCC3D6666663F0F +:100BF000A0330020014B1870704700BF98230020DD +:100C000030B54FF000542B4B22689A4285B007D084 +:100C100003F0C0F8044620BB0024204605B030BDD8 +:100C2000254B627D25481A70237D03724FF4807333 +:100C3000C0F8F8314FF40073C0F80C3300254FF4BE +:100C40004073C0F820341E49C0F8E450C92209306E +:100C500000F02AFA2046E022294600F037FA012463 +:100C6000DBE7184A184D136C43F000731364AA6D48 +:100C7000164B9A42D0D12B6E013B7E2BCCD8144A16 +:100C800007CA01AB83E807001846032100F05EFCA9 +:100C90006B6D83424FF00003BED12A6D8A4201BFC3 +:100CA000AB65054B2A6E1A7003BF0A4BEA6D1A60DA +:100CB0001C46B2E79AAD44C598230020B0440020FA +:100CC0001600002000380240006600405041A0B0ED +:100CD000586600401023002037B51A4D00F068FC1C +:100CE00002236B71184B288119681848012201F002 +:100CF00027FA00230193164B164900931648174B09 +:100D00004FF4805201F074FE154B197811B112485E +:100D100001F096FE01F078FB0446FFF7E3FB4FF489 +:100D2000C873B0FBF3F202FB130304F5167010FA5C +:100D300083F00C4B186003F023F808B10F232B81CC +:100D400003B030BD8C23002010230020D8330020B6 +:100D5000F50700089C230020A4330020F9080008B0 +:100D600098230020A03300202DE9F04F2DED028BB9 +:100D70000FF23829D9E90089834C93B00BAE9FED6F +:100D80007E8BFFF7F1FC814FDFF828A200230A9346 +:100D9000ADF834300B9373604FF0000B5B468DED74 +:100DA000008B01250DF11D0207A938468DF81C5056 +:100DB0008DF81DB001F072F99DF81C30002B40F049 +:100DC000A580204601F044FE0646002845D1704F1C +:100DD00001F01AFB3B6898423FD301F015FB8246B5 +:100DE000FFF780FB4FF4C873B0FBF3F202FB130371 +:100DF0000AF5167010FA83F03860664F97F800B065 +:100E0000CBF1100ABBF1000F14BF33462B465FFA3B +:100E10008AFA0EA88DF82830FFF77CFBBAF1060F8E +:100E200028BF4FF0060A0EAB03EB0B0152460DF143 +:100E3000290000F039F90AAB0393182302930AF151 +:100E40000102554BD2B2CDE90053049220464CA387 +:100E5000D3E9002301F042FE3E7001F0D5FA4F4A7B +:100E60004F4D1368C31AB3F57A7F2ED3106001F08B +:100E7000CDFA02460B46204601F0C8FE204601F09E +:100E8000E7FD10B32B7A474E002B14BF0323022338 +:100E9000737101F0B9FA0EAF4FF47A730122B0FB0F +:100EA000F3F039463060304600F002FA182302931E +:100EB0003D4B019380B240F25513CDE9037000938E +:100EC00042464B46204601F009FE2B7A93B101F0D1 +:100ED0009BFA002607464FF48A7A95F8D9003044E9 +:100EE00000F003000AFB005393F8E82092B30136A8 +:100EF000042EF2D1C82002F0DBFB2B7A002B7FF40A +:100F00003DAF13B0BDEC028BBDE8F08FDAF81430C2 +:100F100083F01003CAF81430594610220EA800F0CE +:100F2000D5F80DF11E0308AA0AA9384600F01EFEE6 +:100F300096E803000FAB83E803009DF834308DF88A +:100F400044300A9B0E930EA9DDE90823204602F0E7 +:100F500031F821E7D3F8E02042B12B68FA2B38BFF3 +:100F6000FA23BA1A0533B2EB430FC0D3FFF7ACFB39 +:100F70000028BCD1BEE700BF000000000000000058 +:100F8000401DA12026812A0BA4330020D833002045 +:100F9000A03300209D3300209C330020E049002036 +:100FA000B04400208C230020E4490020F1C6A7C1F2 +:100FB000D068080F0008024008B5054800F072FE2E +:100FC000BDE80840034A0449002003F0EBB900BF24 +:100FD000D8330020204A0020C108000870B502F074 +:100FE0001FFD094E094D3080002428683388834254 +:100FF00008D902F00FFD2B6804440133B4F5803F9B +:101000002B60F2D370BD00BF144A0020E8490020D5 +:1010100002F0B4BD00F10060920000F5803002F0F3 +:1010200045BD0000054B1A68054B1B889B1A83427F +:1010300002D9104402F0EEBC00207047E8490020BD +:10104000144A0020024B1B68184402F0EBBC00BF9E +:10105000E8490020024B1B68184402F0FBBC00BFAB +:10106000E8490020064991F8243033B10023086A8A +:1010700081F824300822FFF7CDBF0120704700BF60 +:10108000EC490020022802BF014B10229A617047F0 +:1010900000080240022802BF024B4FF480129A61FE +:1010A000704700BF0008024010B50023934203D0F0 +:1010B000CC5CC4540133F9E710BD0000034602467E +:1010C000D01A12F9011B0029FAD1704702440346D5 +:1010D000934202D003F8011BFAE770472DE9F84369 +:1010E0001F4D144695F824200746884652BBDFF86A +:1010F00070909CB395F824302BB92022FF214846EC +:101100002F62FFF7E3FF95F82400C0F10802A24226 +:1011100028BF2246D6B24146920005EB8000FFF779 +:10112000C3FF95F82430A41B1E44F6B2082E1744C2 +:101130009044E4B285F82460DBD1FFF793FF0028E8 +:10114000D7D108E02B6A03EB82038342CFD0FFF7AD +:1011500089FF0028CBD10020BDE8F8830120FBE700 +:10116000EC4900202DE9F0470D4604460021904649 +:10117000284640F27912FFF7A9FF234620220021DA +:10118000284601F0B9FE231D02222021284601F045 +:10119000B3FE631D03222221284601F0ADFEA31DEC +:1011A00003222521284601F0A7FE04F1080310229E +:1011B0002821284601F0A0FE04F11003082238215E +:1011C000284601F099FE04F1110308224021284627 +:1011D00001F092FE04F1120308224821284601F092 +:1011E0008BFE04F1140320225021284601F084FED6 +:1011F00004F1180340227021284601F07DFE04F11D +:1012000020030822B021284601F076FE04F12103D4 +:101210000822B821284601F06FFE04F12207C026FB +:101220003B46314608222846083601F065FEB6F5F1 +:10123000A07F07F10107F3D104F132030822314600 +:10124000284601F059FE002704F1330A94F83230A1 +:101250004FEAC7099F4209F5A47615D3B8F1000FEC +:1012600008D1314604F599730722284601F044FE5F +:1012700009F24F16274694F832213B1B93420CD3B8 +:10128000F01DC008BDE8F0870AEB070308223146CD +:10129000284601F031FE0137D8E707F23313314613 +:1012A0000822284601F028FE08360137E3E700004F +:1012B00013B504460846002101602346C0F8031018 +:1012C0002022019001F018FE0198231D0222202106 +:1012D00001F012FE0198631D0322222101F00CFE91 +:1012E0000198A31D0322252101F006FE019804F1B7 +:1012F00008031022282101F0FFFD072002B010BDD5 +:10130000F7B50023047F00910E46072219460546D3 +:1013100001F0B6FC731C009301220023072128462C +:1013200001F0AEFCC4B9B31C00930522234608218A +:10133000284601F0A5FC0D243746B278BB1B93422A +:1013400011D32B7FA88A0734E408BBB9844294BF29 +:101350000020012003B0F0BDAB8ADB00083BDB08B6 +:10136000B3700824E8E7FB1C009321460023082201 +:10137000284601F085FC08340137DEE7201A18BF43 +:101380000120E7E7F7B50023047F00910E4608220D +:101390001946054601F074FC731CC4B90822009379 +:1013A00011462346284601F06BFC10240123727875 +:1013B0005F1C013B934211D32B7FA88A0734E408BA +:1013C000BBB9844294BF0020012003B0F0BDAB8ABA +:1013D000DB00083BDB0873700824E7E7F319009390 +:1013E000214600230822284601F04AFC08343B46E7 +:1013F000DDE7201A18BF0120E7E70000F8B50E4628 +:1014000005461446002181223046FFF75FFE2B4639 +:1014100008220021304601F06FFD7CB96B1C0722C9 +:101420000821304601F068FD0F2401236A785F1C13 +:10143000013B934204D3E01DC008F8BD0824F4E743 +:10144000EB1921460822304601F056FD08343B4690 +:10145000ECE70000F8B50E46054614460021CE2202 +:101460003046FFF733FE2B4628220021304601F09C +:1014700043FD7CB905F1080308222821304601F01C +:101480003BFD30242F462A7A7B1B934204D3E01D78 +:10149000C008F8BD2824F5E707F109032146082212 +:1014A000304601F029FD08340137ECE7F7B5047F39 +:1014B00000910E46012310220021054601F0E0FBB9 +:1014C000C4B9B31C0093092223461021284601F019 +:1014D000D7FB192437467288BB1B9A4211D82B7F41 +:1014E000A88A0734E408BBB9844294BF00200120D5 +:1014F00003B0F0BDAB8ADB00103BDB087380102427 +:10150000E8E73B1D0093214600230822284601F00E +:10151000B7FB08340137DEE7201A18BF0120E7E7E0 +:1015200030B5094D0A4491420DD011F8013B5840A5 +:10153000082340F30004013B2C4013F0FF0384EA2E +:101540005000F6D1EFE730BD2083B8EDF7B54FF08E +:10155000FF33DFF854C0DFF854E000EB81011A4696 +:1015600088421CD050F8044B019401AF042417F8B2 +:10157000015B82EA05620825DB18164605F1FF3596 +:101580005241002EBCBF83EA0C0382EA0E0215F022 +:10159000FF05F1D1013C14F0FF04E8D1E0E7D843A6 +:1015A000D14303B0F0BD00BF9336EAA9EBE1F042AE +:1015B000F7B5384A106851686B4603C36A46364926 +:1015C0003648082302F04EFF0446002833D10A258E +:1015D000334A106851686B4603C36A4631492F4845 +:1015E000082302F03FFF0446002849D00369B3F501 +:1015F000702F45D8B0F8661041F2727291423FD117 +:10160000294A024402F15C018B4239D35C3B2349F5 +:1016100000209E1AFFF784FF3246074604F164015A +:101620000020FFF77DFFA3689F4229D1E36898421D +:1016300008BF002524E00369B3F5702F27D8418B3C +:1016400041F27272914220D1174A024402F1100114 +:101650008B4218D3103B114900209D1AFFF760FF01 +:101660002A46064604F118010020FFF759FFA36837 +:101670009E4202D1E368984201D00D25A8E70025DB +:10168000284603B0F0BD1025A2E70C25A0E70B25E6 +:101690009EE700BF50450008DCFF0E000000010877 +:1016A0005945000890FF0E000800FFF710B5037CB5 +:1016B000044613B9006802F0BDFE204610BD0000CC +:1016C0000023BFF35B8FC360BFF35B8FBFF35B8F00 +:1016D0008360BFF35B8F7047BFF35B8F0068BFF31E +:1016E0005B8F704770B505460C30FFF7F5FF05F1CD +:1016F000080604463046FFF7EFFFA04206D9304601 +:101700006D68FFF7E9FF2544281A70BD3046FFF7E2 +:10171000E3FF201AF9E7000070B50546406898B16C +:1017200005F10800FFF7D8FF05F10C060446304626 +:10173000FFF7D2FF8442304694BF6D680025FFF763 +:10174000CBFF013C2C44201A70BD000038B50C467C +:101750000546FFF7C7FFA04210D305F10800FFF7C9 +:10176000BBFF04446868B4FBF0F100FB1144BFF315 +:101770005B8F0120AC60BFF35B8F38BD0020FCE7BE +:101780002DE9F041144607460D46FFF7C5FF844298 +:1017900028BF0446D4B1B84658F80C6B4046FFF752 +:1017A0009BFF3044286040467E68FFF795FF331A60 +:1017B0009C4203D86C600120BDE8F0816B60A41BE3 +:1017C0003B68AB602044E8600220F5E72046F3E781 +:1017D00038B50C460546FFF79FFFA04210D305F130 +:1017E0000C00FFF779FF04446868B4FBF0F100FBDC +:1017F0001144BFF35B8F0120EC60BFF35B8F38BDFA +:101800000020FCE72DE9FF41884669460746FFF7BF +:10181000B7FF6C4606B204EBC6060025B44209D0F9 +:101820006268206808EB0501FFF73EFC6368083436 +:101830001D44F3E729463846FFF7CAFF284604B09F +:10184000BDE8F081F8B505460C300F46FFF744FFC0 +:1018500005F1080604463046FFF73EFFA042304639 +:1018600088BF6C68FFF738FF201A386020B1304617 +:101870002C68FFF731FF2044F8BD000073B5144613 +:1018800006460D46FFF72EFF844228BF044601900E +:10189000DCB101A93046FFF7D5FF019B33B93268AF +:1018A000C5E90233C5E9002401200CE09C4238BFA1 +:1018B00001942860019868608442F5D93368AB6070 +:1018C000241AEC60022002B070BD2046FBE7000045 +:1018D0002DE9FF410F466946FFF7D0FF6C4600B285 +:1018E00004EBC0050026AC4209D0D4F8048054F8BB +:1018F000081BB8194246FFF7D7FB4644F3E73046CA +:1019000004B0BDE8F081000038B50546FFF7E0FF00 +:10191000044601462846FFF719FF204638BD00005F +:1019200010B4026854681A4623465DF8044B184701 +:10193000002070470020704770470000002070476B +:101940000E20704700F5805090F8C800C0F34000AA +:101950007047000000F5805090F9D00070470000FB +:1019600000F58050C0F8CC1001207047F7B50C6826 +:10197000BDF8207014F0005470D10D7B082D6DD887 +:10198000302585F311884569AE6876010CD4AC68C2 +:10199000240108D4AC6814F080545DD184F311881C +:1019A000204603B0F0BD01240E6804F1180C002E8F +:1019B000B8BFF6004FEA0C1CB4BF46F0040676052B +:1019C00045F80C600E680FFA84FC16F0804F18BFC3 +:1019D00005EB0C1E05EB0C1C1EBFDEF8806146F00B +:1019E0000206CEF880610E7BCCF8846105EB04150D +:1019F0008E68C5F88C614E68C5F88861DCF8805146 +:101A000045F00105CCF8805100EB441641F2680521 +:101A10002E4405EB44150544C6E9002308350E465F +:101A200001F10C0C56F804EB45F804EB6645F9D1CE +:101A3000843436882E8000EB441407F003052679A1 +:101A400026F00B0635432571002484F31188009796 +:101A500000F0FCFC0120A4E70224A5E74FF0FF30D2 +:101A60009FE7000013B500F580540191E06DFFF78A +:101A700053FE1F280AD90199E06D2022FFF7C2FE0C +:101A8000A0F120035842584102B010BD0020FBE7EE +:101A900008B5302383F3118800F58050C06DFFF73F +:101AA0000FFE002383F3118808BD000000220260AE +:101AB000828142608260704710B500220023C0E935 +:101AC00000230023044603810C30FFF7EFFF20467C +:101AD00010BD0000F0B5054600F580500C4690F8AA +:101AE000C83013F0040FC3F3800108BF114661F33F +:101AF000820304F1840680F8C83005EB461389B0F0 +:101B00001B79D8072ED57AB319072DD46846FFF76D +:101B1000D3FF05EB441303F5835303F1180703AA1E +:101B2000103318685968144603C40833BB42224670 +:101B3000F7D1186820609B88A380DDE90E23CDE9EA +:101B400000230123ADF808302B686946DB6B28467B +:101B5000984705EB46152B791A075CBF43F008033D +:101B60002B7101E0002AF4D109B0F0BD2DE9F04756 +:101B70009A4688B0074688469146302383F31188F9 +:101B800007F580546846FFF797FFE06DFFF7AAFD61 +:101B90001F282AD9E06D20226946FFF7B5FE2028CC +:101BA00023D103AD444605AB2E4603CE9E422060B2 +:101BB0006160354604F10804F6D130682060B388CE +:101BC000A380DDE90023C9E90023BDF80830AAF8A5 +:101BD0000030002383F3118853464A464146384675 +:101BE00008B0BDE8F04700F01FBC002080F311886A +:101BF00008B0BDE8F08700002DE9F84F0023C0E9E8 +:101C00000133254B044640F8183B0F46FFF74EFFC3 +:101C100004F12800FFF750FF04F1480804F582554D +:101C20004646083530462036FFF746FFAE42F9D12A +:101C300004F580554FF480534FF00009C5E913397E +:101C4000C5F848800123EE6504F5875804F58456ED +:101C5000C5F8549085F8583085F86030083608F19A +:101C600008084FF0000A4FF0000B46E908ABA6F158 +:101C70001800FFF71BFF203646F8289C4645F4D194 +:101C800085F8D07017B1054800F0B8FB044B6361CC +:101C90002046BDE8F88F00BF8C4500086445000869 +:101CA0000064004010B5044B197804464A1C1A70B1 +:101CB000FFF7A2FF204610BD1C4A00202DE9F04787 +:101CC000002950D0294B2A4FB7FBF1F599428CBF20 +:101CD0000A231123581EB5FBF3FC03FB1C53C4B2AB +:101CE0002BB102280346F5D80020BDE8F0870CF19F +:101CF000FF36B6F5806FF7D2C4EBC40E0EF10303C6 +:101D00004FEAE309C3F3C703A4EB030809F1010A8F +:101D10004FF47A755FFA88F009FB05555AFA88F88E +:101D2000B5FBF8F5B5F5617FC1BF0EF1FF33C3F325 +:101D3000C703E01AC0B25C1C50FA84F40CFB04F434 +:101D4000B7FBF4F4A142CFD1013BDBB20F2BCBD8D0 +:101D50000138C0B20728C7D80021107116809170D1 +:101D6000D3700120C1E70846BFE700BF3F420F0024 +:101D700080DE800270B505460E464FF47A746B69BA +:101D80005B6803F00103B34207D04FF47A7001F0AF +:101D90008FFC013CF3D1204670BD0120FCE7000020 +:101DA00030B54269936913F0700F16D000230B4CC5 +:101DB000936103F1840200EB421211794D0709D5BA +:101DC000890707D5416954F823508D60117941F096 +:101DD000040111710133032BEBD130BD78450008AC +:101DE00073B51D46436916469A68D207044609D55D +:101DF0009A6801219960C2F34002CDE90065002193 +:101E0000FFF768FE63699A68D1050BD59A684FF4AD +:101E100080719960C2F34022CDE90065012120461E +:101E2000FFF758FE63699A68D2030BD59A684FF49E +:101E300080319960C2F34042CDE90065022120461D +:101E4000FFF748FE04F58053D3F8CC0010B10368C7 +:101E50001B699847204602B0BDE87040FFF7A0BF5D +:101E6000F8B504464669002972D106F10C073868B6 +:101E7000800770D006EB01153868D5F8B00110F076 +:101E8000040FD5F8B0011ABFC00840F00040400D63 +:101E9000A061D5F8B0C11CF0020F1CBF40F080401B +:101EA000A061D5F8B40106EB011100F00F0084F831 +:101EB0002400D1F8B8012077D1F8B801000A607782 +:101EC000D1F8B801000CA077D1F8B801000EE07786 +:101ED000D1F8BC0184F82000D1F8BC01000A84F8D4 +:101EE0002100D1F8BC01000C84F82200D1F8BC110B +:101EF000090E84F823103821396004F1340004F10C +:101F0000180104F1240551F8046B40F8046BA94250 +:101F1000F9D109880180C4E90A23214600232386D8 +:101F200051F8283B2046DB6B984704F5805393F823 +:101F3000C820D3F8CC0042F0040283F8C82010B1C6 +:101F400003681B6998472046BDE8F840FFF728BFA3 +:101F500006F110078BE7F8BD10B5044600F056FAFD +:101F600002460B4652EA030102D0013A63F1000334 +:101F70000449086820B12146BDE81040FFF770BF52 +:101F800010BD00BF184A0020F0B5302181F3118840 +:101F9000DFF848C000F583510831002404F18405BE +:101FA00000EB45152E7977070ED4F6060CD5D1E94E +:101FB000007697429E4107D246695CF82470B7606C +:101FC0002E7946F004062E710134032C01F1200114 +:101FD000E4D1002383F31188F0BD00BF78450008E9 +:101FE00008B5302383F31188FFF7DAFE002383F36B +:101FF000118808BDF8B543690546986800F0E050BF +:10200000B0F1E05F0F4621D0F8B1302383F311889F +:1020100005F583541034002606F1840305EB4313C1 +:102020001B791A0706D50136032E04F12004F3D1DB +:10203000012007E05B07F6D42146384600F040FA5D +:102040000028F0D1002383F31188F8BD0120FCE7BC +:1020500008B5302383F3118800F58050C06DFFF779 +:1020600041FB002383F3118843090CBF01200020AA +:1020700008BD0000F8B51D46002313700F46064644 +:102080001446FFF7E5FF80F00100387025B12946BE +:102090003046FFF7AFFF2070F8BD00002DE9B841D2 +:1020A0000C4615461F46804600F0B0F90B462178D5 +:1020B000024609B9287850B14046FFF765FFFFF79F +:1020C0008FFF3B462A462146FFF7D4FF0120BDE89B +:1020D000B881000070B5302686F31188174B1A6C52 +:1020E00042F000721A641A6A42F000721A621A6AA6 +:1020F00022F000721A62002383F3118800F58054E5 +:1021000094F8C83013F0010516D1A9B186F31188EF +:102110000321132001F0C8F90321142001F0C4F9B0 +:102120000321152001F0C0F994F8C83043F00103F1 +:1021300084F8C83085F3118870BD00BF00380240B4 +:102140002DE9F04700F5805588B095F8D030012B87 +:1021500004468846164600F28180814F57F82320B6 +:102160000AB947F82300D7F800A0C4F80C802674F9 +:10217000BAF1000F64D095F8D030012B70D0012156 +:102180002046FFF7A7FF302383F3118862691368A5 +:1021900023F0020313606269136843F001031360C4 +:1021A000636900275F6187F3118801212046FFF7EB +:1021B000E1FD002800F09580E86DFFF781FA04F555 +:1021C0008359BA4609F10809202200216846FEF722 +:1021D0007DFF02A8FFF76AFCCDF818A06A4609EB5C +:1021E00007030DF1180E9446BCE80300F44518608F +:1021F0005960624603F10803F5D1DCF8000018606D +:1022000020379CF804201A71602FDDD195F8C83072 +:102210006FF38203002785F8C8306A46414620469E +:10222000ADF80070ADF802708DF80470FFF746FD50 +:10223000636948BB4FF400421A6008B0BDE8F087FC +:1022400041F2D80002F0B6F8814610B15146FFF7CE +:10225000D3FCC7F80090B9F1000F8CD10020ECE757 +:10226000386803681B6B98470146002887D1386897 +:10227000FFF730FF3868036832465B68414698478D +:1022800000287FF47CAFE9E761221A609DF80230F4 +:102290009DF803201B06120402F4702203F0407321 +:1022A0001343BDF80020C2F3090213439DF8042034 +:1022B0001205022E02F4E0020CBF4FF00041002193 +:1022C000134362690B43D361636913225A616269E4 +:1022D000136823F00103136039462046FFF74AFDD7 +:1022E00008B96369A6E795F8D03093BB6169D1F866 +:1022F000002242F00102C1F800226169D1F80022F7 +:1023000022F47C5222F00E02C1F800226169D1F859 +:10231000002242F46062C1F800226269C2F81432FD +:102320006269C2F80432626941F6FF71C2F80C12A8 +:102330006269C2F840326269C2F8443263690122BC +:10234000C3F81C226269D2F8003223F00103C2F8FC +:10235000003295F8C83043F0020385F8C8306CE7C6 +:10236000184A002008B500F051F850EA010302466F +:1023700002D0421E61F10001044B186810B10B46F7 +:10238000FFF72EFDBDE8084001F064B8184A0020B0 +:1023900008B50020FFF7E0FDBDE8084001F05AB89D +:1023A00008B50120FFF7D8FDBDE8084001F052B89C +:1023B00000B59BB0EFF3098168226846FEF774FE12 +:1023C000EFF30583014B9B6BFEE700BF00ED00E0E0 +:1023D00008B5FFF7EDFF000000B59BB0EFF30981F2 +:1023E00068226846FEF760FEEFF30583014B5B6BE6 +:1023F000FEE700BF00ED00E0FEE700000FB408B507 +:10240000029801F005F9FEE701F006BC01F0E8BB17 +:1024100013B56C4684E80600031D94E8030083E8C6 +:102420000500012002B010BD73B58568019155B15A +:102430001B885B0707D4D0E900369B6B9847019A4D +:10244000C1B23046A847012002B070BDF0B5866821 +:1024500089B005460C465EB1BDF838305B070AD43A +:10246000D0E900379B6B98472246C1B23846B04747 +:10247000012009B0F0BD00220023CDE90023002394 +:10248000ADF808300A4603AB01F108061068516840 +:102490001C4603C40832B2422346F7D110682060BC +:1024A0009288A280FFF7B2FF0423ADF808302B68B2 +:1024B000CDE90001DB6B694628469847D8E7000064 +:1024C00030B503680968DD0FB5EBD17F23F06044B8 +:1024D00021F060424FEAD1700BD0002BB8BFA40CA2 +:1024E0000029B8BF920C944202D034BF01200020D2 +:1024F00030BD944205D1C1F38070C3F38073834231 +:10250000F6D194422CBF00200120F1E72DE9F041E3 +:10251000456A15B94162BDE8F0814B6823F0604718 +:10252000C3F38A464FEAD37EC3F3807816EA2306C4 +:1025300038BF3E46AC462B465A68BEEBD27F22F0EF +:1025400060440AD0002A18DAA40CB44217D19D4284 +:102550000FD10D60DEE71346EEE7A74207D102F088 +:102560008044C2F3807242450BD054B1EFE708D2E9 +:10257000EDE7CCF800100B60CDE7B44201D0B442D7 +:10258000E5D81A689C46002AE5D11960C3E7000027 +:102590002DE9F047089D01F007044FEAD5082244D1 +:1025A00005F0070500EBD1004FF47F49944201D1BB +:1025B000BDE8F08704F0070705F0070A57453E46D7 +:1025C00038BF5646C6F10806111B8E4228BF0E467C +:1025D000E10808EBD50E415C13F80EC0B94029FAAA +:1025E00006F721FA0AF1FFB28CEA010147FA0AF76D +:1025F00039408CEA010C03F80EC034443544D5E769 +:1026000080EA0120082341F2210201B240000029A2 +:1026100080B203F1FF33B8BF504013F0FF03F4D191 +:102620007047000038B50C468D18A54200D138BD62 +:1026300014F8011BFFF7E4FFF7E7000042684AB116 +:10264000136843604389818901339BB29942438176 +:1026500038BF83811046704770B588B02022044689 +:102660000D4668460021FEF731FD20460495FFF730 +:10267000E5FF024658B16B46054608AE1C4603CC42 +:10268000B44228606960234605F10805F6D110467A +:1026900008B070BD082817D909280CD00A280CD01A +:1026A0000B280CD00C280CD00D280CD00E2814BFF1 +:1026B0004020302070470C207047102070471420B5 +:1026C000704718207047202070470000082817D94D +:1026D0000C280CD910280CD914280CD918280CD97E +:1026E00020280CD930288CBF0F200E2070470920DD +:1026F00070470A2070470B2070470C2070470D2050 +:10270000704700002DE9F843078C072F04461ED9B7 +:10271000D0E9029800254FF6FF73C5F12006A5F118 +:10272000200029FA05F108FA06F628FA00F03143EC +:102730000143C9B21846FFF763FF0835402D034631 +:10274000EBD1E1693A46BDE8F843FFF76BBF4FF6BE +:10275000FF70BDE8F883000010B54B6823B9CA8A42 +:1027600063F30902CA8210BD04691A681C60036120 +:10277000C38A013BC3824A60EFE700002DE9F84FAE +:102780001D46CB8A0F46C3F30901052981469246AF +:102790000B4630D00020AAB207F11A049EB2042ED4 +:1027A0001FFA80F80FD8904503F1010306D3FB8A86 +:1027B0000A4462F30903FB8201201AE01AF8006060 +:1027C000E6540130EAE79045F1D2A1F1050B1C2354 +:1027D0007C68BBFBF3F203FB12BB1FFA8BF6002CE9 +:1027E00045D14846FFF72AFF044638B978606FF0B4 +:1027F0000200BDE8F88F4FF00008E6E7002606600B +:102800007860ADB24FF0000B454510D90AEB0803D4 +:10281000221D13F8011B9155B1B208F101081B29C3 +:102820001FFA88F82BD0454506F10106F1D8FB8A3E +:10283000C3F30902154465F30903BCE7013292B200 +:102840001C462368002BF9D16B1F0B441C21B3FBE2 +:10285000F1F301339BB29A42D3D2BBF1000FD0D136 +:102860004846FFF7EBFE20B9C4F800B0BFE70122ED +:10287000E7E7C0F800B05E4620600446C1E7454582 +:10288000D5D94846FFF7DAFE08B92060AFE7C0F8AF +:1028900000B0002620600446B6E700002DE9F04FA6 +:1028A0002DED028B1C4683B05B690192074688467A +:1028B000002B00F09A80238C2BB1E269002A00F0F3 +:1028C0009480072B35D807F10C00FFF7B7FE0546BB +:1028D00038B96FF00205284603B0BDEC028BBDE8A5 +:1028E000F08F14220021FEF7F1FB228CE16905F143 +:1028F0000800FEF7D9FB208C013080B2FFF7E6FE1E +:10290000FFF7C8FE013880B2208401302874636963 +:10291000228C1B782A4403F01F0363F03F0348F026 +:1029200000411372384669602946FFF7EFFD012523 +:10293000D1E700F10C034FF0000908EE103A4FF018 +:10294000800A4E464D4618EE100AFFF777FE834682 +:102950000028BED014220021FEF7B8FB002E3AD189 +:10296000019BABF8083002220BF1080E1FFA82FC23 +:102970000CF10100BCF1060F218C80B201D88E420F +:102980002BD3FFF7A3FEFFF785FE626912780138AB +:1029900002F01F028E4208BF4FF0400A42EA49127D +:1029A0001BFA80F14AEA020A013048F0004281F83D +:1029B00008A08BF81000CBF8042059463846FFF7E2 +:1029C000A5FD238C0135B3422DB289F001094FF0EA +:1029D000000AB8D17FE70022C6E7E169895D0EF8F9 +:1029E00002100136B6B20132C0E76FF0010572E79E +:1029F000F8B515460E463022002104461F46FEF764 +:102A000065FB069B6360B5F5001F079BA76034BF9D +:102A10006A094FF6FF72A36297B2E66104F11000F3 +:102A200000239A4206D800230360A782E38223830F +:102A3000E360F8BD0660013330462036F1E7000060 +:102A400003781BB94BB2002BC8BF01707047000060 +:102A500000787047F8B50C46C969074611B9238C50 +:102A6000002B37D1257E1F2D34D8387828BB228CF7 +:102A7000072A2CD8268A36F003032BD14FF6FF7095 +:102A8000FFF7D0FD20F001003102400441EA05616A +:102A9000400C41EA40254FF6FF722346294638464E +:102AA000FFF7FCFE002807DD626913780133DBB213 +:102AB0001F2B88BF00231370F8BD218A2D0645EA1D +:102AC000012505432046FFF71DFE0246E5E76FF0AE +:102AD0000300F1E76FF00100EEE7000070B58AB087 +:102AE000044616460021282268461D46FEF7EEFAE7 +:102AF000BDF83830ADF810300F9B05939DF840308D +:102B00008DF81830119B07936946BDF84830ADF831 +:102B100020302046CDE90265FFF79CFF0AB070BD6A +:102B20002DE9F041D36905460C4616460BB9138CC6 +:102B30005BBB377E1F2F28D895F80080B8F1000FB7 +:102B400026D03046FFF7DEFD3378210241EAC3315B +:102B500041EA0801338A41EA076141EA034102463A +:102B6000334641F080012846FFF798FE00280ADD31 +:102B70003378012B07D1726913780133DBB21F2B35 +:102B800088BF00231370BDE8F0816FF00100FAE701 +:102B90006FF00300F7E70000F0B58BB004460D4678 +:102BA00017460021282268461E46FEF78FFA9DF838 +:102BB0004C305A1E534253418DF800309DF840303E +:102BC000ADF81030119B05939DF848308DF8183002 +:102BD000149B07936A46BDF85430ADF8203029465F +:102BE0002046CDE90276FFF79BFF0BB0F0BD000059 +:102BF000406A00B104307047436A1A684262026951 +:102C00001A600361C38A013BC38270472DE9F0411A +:102C1000D0F82080194E14461D464146002709B9B8 +:102C2000BDE8F081D1E90223A21A65EB03039642C5 +:102C300077EB03031ED2036A8B420DD1FFF78CFDA5 +:102C4000036A1B68036203690B60C38A0161016A3E +:102C5000013BC3828846E2E7FFF77EFD0B68C8F8B8 +:102C6000003003690B60C38A0161013BC382D8F85D +:102C70000010D4E788460968D1E700BF80841E00B1 +:102C80002DE9F04F8BB00D46DDF8509014469B4671 +:102C90008046002800F01981B9F1000F00F015817D +:102CA000531E3F2B00F21181012A03D1BBF1000F0B +:102CB00040F00B810023CDE90833B8F81430B5EBB0 +:102CC000C30F4FEAC30703D300200BB0BDE8F08F5A +:102CD0002B199F42D8F80C303ABF7F1BFFB2274612 +:102CE0001BB9D8F81030002B7AD0272D4ED8C5F15B +:102CF0002806B7424FF000032CBFF6B23E460093C1 +:102D00002946D8F8080008AB3246FFF741FCA7EB8C +:102D1000060A35445FFA8AFAB8F8143003F1005312 +:102D2000053BDB000493D8F80C3003932821039B68 +:102D300013B1BAF1000F2CD1D8F8100040B1BAF19C +:102D4000000F05D0009608AB5246691AFFF720FC29 +:102D500038B2002FB8D066070AD00AAB03EBD40113 +:102D6000624211F8083C02F00702134101F8083CE6 +:102D7000082C3CD9102C40F2B580202C40F2B780B2 +:102D8000BBF1000F00F09C80082334E0BA46002617 +:102D9000C2E7049BE02B28BFE02306930B44AB4221 +:102DA000059314D95A1B03980096924534BF524696 +:102DB000D2B2691A08AB04300792FFF7E9FB079A11 +:102DC0001644AAEB020A1544F6B25FFA8AFA049B8B +:102DD000069A05999B1A0493039B1B680393A6E725 +:102DE0000093D8F8080008AB3A462946AEE7BBF195 +:102DF000000F13D00123B4EBC30F6CD0082C12D8F2 +:102E00009DF82030621E23FA02F2D50706D54FF056 +:102E1000FF3202FA04F423438DF820309DF820306D +:102E200089F8003051E7102C12D8BDF82030621E0E +:102E300023FA02F2D10706D54FF0FF3202FA04F46A +:102E40002343ADF82030BDF82030A9F800303CE72E +:102E5000202C0FD80899631E21FA03F3DA0705D551 +:102E60004FF0FF3202FA04F40C430894089BC9F8AF +:102E700000302AE7402C2BD0DDE90865611EC4F143 +:102E80002102A4F1210326FA01F105FA02F225FA42 +:102E900003F311431943CB0712D50122A4F12003F8 +:102EA000C4F1200102FA03F322FA01F1A2405242D6 +:102EB00043EA010363EB430332432B43CDE9082389 +:102EC000DDE90823C9E90023FFE66FF00100FCE615 +:102ED0006FF00800F9E6082CA0D9102CB3D9202CEB +:102EE000EED8C3E7BBF1000FADD0022383E7BBF1FF +:102EF000000FBBD004237EE730B5012A144638BF4B +:102F00000124402C85B028BF40240025012ACDE9AA +:102F1000025518D81B788DF8083063070AD004AB27 +:102F200003EBD405624215F8083C02F00702934017 +:102F300005F8083C009103462246002102A8FFF74D +:102F400027FB05B030BD082AE4D9102A03D81B8816 +:102F5000ADF80830E1E7202A8DBFD3E900231B68D4 +:102F60000293CDE90223D8E710B5CB681BB98B607B +:102F70000B618B8210BD04691A681C600361C38AEF +:102F8000013BC382CA60F0E703064CBFC0F3C03008 +:102F90000220704708B50246FFF7F6FF022806D167 +:102FA0005306C2F30F2001D100F0030008BDC2F3A5 +:102FB0000740FBE72DE9F04F93B0CDE903230A6802 +:102FC00004461046FFF7E0FF022814BFC2F30626AE +:102FD0000026002A0D46824680F2F28112F0C04996 +:102FE00040F0EE81097B002900F0EA81022803D03D +:102FF0002378B34240F0E781C2F30463069310469E +:1030000002F07F030593FFF7C5FF059B29444FEAB4 +:10301000834848EA0A4848EA4668CE7800230022F6 +:10302000CDE90823F309834648EA0008029367D0F4 +:10303000059B009302466768534608A92046B84797 +:10304000002800F0C381276A4FB9414604F10C0003 +:10305000FFF702FB074690B96FF0020054E03B69AE +:1030600098450DD03F68002FF9D1414604F10C007E +:10307000FFF7F2FA07460028EED0236A3B6027628A +:1030800097F817C006F01F08CCF3840CACEB0800CF +:103090001FFA80FE0028B8BF0EF12000A8EB0C0339 +:1030A0001FFA83FED7E90221B8BF00B2002B0793B5 +:1030B000BEBF0EF120031BB2079352EA010338D0C2 +:1030C000039BDFF824E39A1A049B4FF0000C63EB98 +:1030D000010196457CEB01032BD36B7B97F81AE03B +:1030E000734519D1029B002B78D0012821DC786828 +:1030F000F8B9DFF8F0C2944570EB010316D337E05E +:10310000276A27B96FF00C0013B0BDE8F08F3B6958 +:103110009845B5D03F68F4E7B24890427CEB010394 +:1031200001D30020F0E7029B002BFAD0079B0F2B66 +:1031300017DCFA7DB30002F0030203F07C031343B3 +:10314000FB7539462046FFF707FB6B7BBB76029B7E +:103150003BB9FB7DC3F38402013262F38603FB7546 +:10316000D0E76A7BBB7E9A42DBD1029B002B35D035 +:10317000B309022B32D0039BBB60049BFB6014227B +:1031800000210DA8FDF7A2FF039B0A93049B0B935C +:103190002B1D0C932B7BADF83EB0013BDBB2ADF8A1 +:1031A0003C30069B8DF84230059B8DF8433094F8F7 +:1031B0002C308DF840A083F001038DF844308DF859 +:1031C0004180A3680AA920469847FB7DC3F3840386 +:1031D000013303F01F039B02FB82A2E7FB7DC6F3D2 +:1031E0004012B2EBD31F40F0F480C3F38403434595 +:1031F00040F0F280029A2B7BB609002A4DD0F207EC +:103200005DD4032B40F2EB80039BBB60049BFB600F +:103210002B7BAE1D033BDBB23246394604F10C007A +:10322000FFF7ACFA00280CDA39462046FFF794FA8B +:10323000FB7DC3F38403013303F01F039B02FB8276 +:103240000AE7DDE90884AB883B834FF6FF73C9F1D9 +:103250002000A9F1200228FA09F104FA00F0014344 +:1032600024FA02F211431846C9B2FFF7C9F909F16D +:103270000809B9F1400F0346E9D1B8822A7B033A25 +:10328000D2B23146FFF7CEF9FB7DB882DA43C2F302 +:10329000C01262F3C713FB7543E786B92E1D013BCD +:1032A000DBB23246394604F10C00FFF767FA00281A +:1032B000BADB2A7BB88A013AD2B23146E2E7F98A10 +:1032C000C1F30901013B0429DAB25BD8281D0023B0 +:1032D00007F11B069A4208D910F801CB06F801C085 +:1032E000013101330529DBB2F4D103990A91049924 +:1032F0000B91934207F11B010C9138BF043379689D +:103300000D9134BF55FA83F300230E93FB8AADF879 +:103310003EB0C3F309031A44069B8DF84230059B67 +:103320008DF8433094F82C30ADF83C2083F0010345 +:103330008DF8443000238DF840A08DF841807B60EB +:103340002A7BB88A013A291DFFF76CF93B8BB882BA +:10335000834203D1A3680AA92046984720460AA9B8 +:10336000FFF702FEFB7DBA8AC3F38403013303F047 +:103370001F039B02FB823B8B9A420CBF00206FF025 +:103380001000C1E67B68002BAFD0052001E01C30A7 +:1033900033461E68002EFAD1091A081D2E1D184446 +:1033A00001EB090CBCF11B0F5FFA89F39DD89A421F +:1033B0009BD916F8013B00F8013B09F10109EFE741 +:1033C0006FF00900A0E66FF00A009DE66FF00B00B9 +:1033D0009AE66FF00D0097E66FF00E0094E66FF03E +:1033E0000F0091E640420F0080841E00EFF3098336 +:1033F00005494A6B22F001024A63683383F3098866 +:10340000002383F31188704700EF00E0302080F341 +:10341000118862B60C4B0D4AD96821F4E0610904A9 +:10342000090C0A43DA60D3F8FC20094942F08072A3 +:10343000C3F8FC200A6842F001020A602022DA7711 +:1034400083F82200704700BF00ED00E00003FA059A +:10345000001000E010B5302383F311880E4B5B6839 +:1034600013F4006314D0F1EE103AEFF30984683CD2 +:103470004FF08073E361094BDB6B236684F30988AB +:1034800000F090F810B1064BA36110BD054BFBE7AF +:1034900083F31188F9E700BF00ED00E000EF00E0E2 +:1034A0003F0300084203000800F1604303F5614355 +:1034B0000901C9B283F80013012200F01F039A40EA +:1034C00043099B0003F1604303F56143C3F8802186 +:1034D0001A60704700230375826803691B68996846 +:1034E0009142FBD25A680360426010605860704796 +:1034F00000230375826803691B6899689142FBD8B1 +:103500005A680360426010605860704708B508460A +:10351000302383F311880B7D032B05D0042B0DD0B2 +:103520002BB983F3118808BD8B6900221A604FF014 +:10353000FF338361FFF7CEFF0023F2E7D1E90032CA +:1035400013605A60F3E70000FFF7C4BF054BD9686A +:103550000875186802681A60536001220275D86005 +:10356000FCF7D8BE284A002030B50C4BDD684B1C58 +:1035700087B004460FD02B46094A684600F02AF966 +:103580002046FFF7E3FF009B13B1684600F02CF9DB +:10359000A86907B030BDFFF7D9FFF9E7284A002036 +:1035A0000D350008044B1A68DB6890689B689842E8 +:1035B00094BF002001207047284A0020084B10B516 +:1035C0001C68D86822681A60536001222275DC608A +:1035D000FFF78EFF01462046BDE81040FCF79ABE7B +:1035E000284A002038B5074C074908480123002520 +:1035F0002370656000F014FC0223237085F31188AA +:1036000038BD00BF904C0020D0450008284A00205B +:1036100008B572B6044B186500F0C4FA00F07AFBE6 +:10362000024B03221A70FEE7284A0020904C00202B +:1036300000F010B98B60022308618B820846704746 +:103640008368A3F1840243F8142C026943F8442CE4 +:10365000426943F8402C094A43F8242CC26843F8D5 +:10366000182C022203F80C2C002203F80B2C044A1D +:1036700043F8102CA3F12000704700BF2D03000871 +:10368000284A002008B5FFF7DBFFBDE80840FFF738 +:103690005BBF0000024BDB6898610F20FFF756BF4D +:1036A000284A0020302383F31188FFF7F3BF00007E +:1036B00008B50146302383F311880820FFF754FF33 +:1036C000002383F3118808BD10B503689C68A242EB +:1036D0000CD85C688A600B604C6021605960996806 +:1036E0008A1A9A604FF0FF33836010BD1B68121B6B +:1036F000ECE700000A2938BF0A2170B504460D46E0 +:103700000A26601900F086FB00F072FB041BA5423C +:1037100003D8751C2E460446F3E70A2E04D9BDE8EB +:103720007040012000F0BCBB70BD0000F8B5144B28 +:103730000D46D96103F1100141600A2A19698260BE +:1037400038BF0A22016048601861A818144600F0CA +:1037500053FB0A2700F04CFB431BA342064606D34B +:103760007C1C281900F056FB27463546F2E70A2F45 +:1037700004D9BDE8F840012000F092BBF8BD00BFBD +:10378000284A0020F8B506460D4600F031FB0F4AE6 +:10379000134653F8107F9F4206D12A460146304611 +:1037A000BDE8F840FFF7C2BFD169BB68441A2C19C5 +:1037B00028BF2C46A34202D92946FFF79BFF224689 +:1037C00031460348BDE8F840FFF77EBF284A002095 +:1037D000384A002010B4C0E9032300235DF8044BED +:1037E0004361FFF7CFBF000010B5194C2369984221 +:1037F0000DD0D0E90032816813605A609A680A449B +:103800009A60002303604FF0FF33A36110BD23468D +:10381000026843F8102F53600022026022699A4226 +:1038200003D1BDE8104000F0EFBA936881680B4403 +:10383000936000F0DDFA2269E1699268441AA242BD +:10384000E4D91144BDE81040091AFFF753BF00BF87 +:10385000284A00202DE9F047DFF8BC8008F1100766 +:103860002C4ED8F8105000F0C3FAD8F81C40AA68C3 +:10387000031B9A423ED81444D5E900324FF00009A8 +:10388000C8F81C4013605A60C5F80090D8F8103092 +:10389000B34201D100F0B8FA89F31188D5E90331B8 +:1038A00028469847302383F311886B69002BD8D0C2 +:1038B00000F09EFA6A69A0EB04094A4582460DD2DF +:1038C000022000F0EDFA0022D8F81030B34208D1FF +:1038D00051462846BDE8F047FFF728BF121A224498 +:1038E000F2E712EB090938BF4A4629463846FFF786 +:1038F000EBFEB5E7D8F81030B34208D01444211AD3 +:10390000C8F81C00A960BDE8F047FFF7F3BEBDE8AA +:10391000F08700BF384A0020284A002038B500F060 +:1039200067FA054AD2E90845031B181945F1000159 +:10393000C2E9080138BD00BF284A002000207047B6 +:10394000FEE70000704700004FF0FF3070470000B6 +:10395000BFF34F8F024AD368DB03FCD4704700BF2C +:10396000003C024008B5094B1B7873B9FFF7F0FF24 +:10397000074B1A69002ABFBF064A5A6002F1883213 +:103980005A601A6822F480621A6008BD984C0020C0 +:10399000003C02402301674508B50B4B1B7893B9E7 +:1039A000FFF7D6FF094B1A6942F000421A611A6804 +:1039B00042F480521A601A6822F480521A601A681F +:1039C00042F480621A6008BD984C0020003C02401E +:1039D0000B28F0B516D80C4C0C4923787BB90C4D4C +:1039E0000E460C234FF0006255F8047B46F8042B7A +:1039F000013B13F0FF033A44F6D10123237051F841 +:103A00002000F0BD0020FCE7CC4C00209C4C0020A6 +:103A1000DC450008014B53F820007047DC450008E6 +:103A20000C2070470B2810B5044601D9002010BDAA +:103A3000FFF7CEFF064B53F824301844C21A0BB9D7 +:103A40000120F4E712680132F0D1043BF6E700BF31 +:103A5000DC4500080B2810B5044621D8FFF778FF95 +:103A6000FFF780FF0F4AF323D360C300DBB243F4B8 +:103A7000007343F002031361136943F4803313614D +:103A8000FFF766FFFFF7A4FF074B53F8241000F081 +:103A90003DF9FFF781FF2046BDE81040FFF7C2BFA8 +:103AA000002010BD003C0240DC450008F8B512F0D3 +:103AB0000103144642D18218B2F1016F57D82D4B41 +:103AC0001B6813F0010352D02B4DFFF74BFFF3237C +:103AD000EB60FFF73DFF40F20127032C15D824F0DF +:103AE00001046618244C401A40F20117B1422369C0 +:103AF00000EB010524D123F001032361FFF74CFF04 +:103B00000120F8BD043C0430E7E78307E7D12B69C7 +:103B100023F440732B612B693B432B6151F8046BF9 +:103B20000660BFF34F8FFFF713FF03689E42E9D093 +:103B30002B6923F001032B61FFF72EFF0020E0E744 +:103B400023F44073236123693B4323610B882B805B +:103B5000BFF34F8FFFF7FCFE2D8831F8023BADB26B +:103B6000AB42C3D0236923F001032361E4E7184685 +:103B7000C7E700BF00380240003C0240084908B5D2 +:103B80000B7828B11BB9FFF7EDFE01230B7008BDC0 +:103B9000002BFCD0BDE808400870FFF7FDBE00BF59 +:103BA000984C002008B50649064800F0B1F8BDE879 +:103BB00008404FF480314FF0805000F0A9B800BFAA +:103BC00000FF0100000100200846114600F014BC6F +:103BD000012000F011BC0000084600F02BBC0000E2 +:103BE00038B5EFF311859DB9EFF30584C4F30804EC +:103BF000302334B183F31188FFF790FE85F31188E9 +:103C000038BD83F31188FFF789FE84F3118838BD2E +:103C1000BDE83840FFF782BE38B5FFF7E1FF114C31 +:103C2000114AC00840EA4170A0FB025EC908A0FB2F +:103C3000040C1CEB050CA1FB04404FF000035B419E +:103C4000A1FB02121CEB040C43EB000011EB0E0174 +:103C500042F10002411842F10000090941EA0070F6 +:103C600038BD00BFCFF753E3A59BC42010B5024475 +:103C7000064BD2B2904200D110BD441C00B253F8A2 +:103C8000200041F8040BE0B2F4E700BF50280040E8 +:103C90000F4B30B51C6F240407D41C6F44F4007420 +:103CA0001C671C6F44F400441C670A4C236843F4EF +:103CB000807323600244084BD2B2904200D130BDE1 +:103CC000441C00B251F8045B43F82050E0B2F4E722 +:103CD00000380240007000405028004007B5012223 +:103CE00001A90020FFF7C2FF019803B05DF804FBB3 +:103CF00013B50446FFF7F2FFA04205D0012201A947 +:103D000000200194FFF7C4FF02B010BD704700000F +:103D10007047000070470000074B45F255521A608B +:103D200002225A6040F6FF729A604CF6CC421A604A +:103D3000024B01221A70704700300040D44C002022 +:103D4000034B1B781BB1034B4AF6AA221A6070473B +:103D5000D44C002000300040034B1A681AB9034AC3 +:103D6000D2F874281A607047D04C0020003002400E +:103D7000024B4FF08072C3F8742870470030024045 +:103D800008B5FFF7E9FF024B1868C0F3407008BDA3 +:103D9000D04C002008B5FFF7DFFF024B1868C0F3D6 +:103DA000007008BDD04C002070470000FEE7000006 +:103DB0000A4B0B480B4A90420BD30B4BDA1C121ADE +:103DC000C11E22F003028B4238BF00220021FDF702 +:103DD0007DB953F8041B40F8041BECE79847000832 +:103DE000604D0020604D0020604D002000F0D0B8F4 +:103DF0004FF08043586A70474FF080430022586369 +:103E00001A610222DA6070474FF080430022DA60C4 +:103E1000704700004FF0804358637047FEE7000092 +:103E200070B51B4B01630025044686B0586085625F +:103E30000E46FFF7EBFA04F11003C4E904334FF028 +:103E4000FF33C4E90635C4E90044A560E562FFF725 +:103E5000CFFF2B460246C4E9082304F134010D4A82 +:103E6000256580232046FFF7E5FB0123E0600A4A31 +:103E70000375009272680192B268CDE90223074B84 +:103E80006846CDE90435FFF7FDFB06B070BD00BF05 +:103E9000904C00200C460008114600081D3E00080A +:103EA000024AD36A1843D062704700BF284A0020F4 +:103EB0004B6843608B688360CB68C3600B69436168 +:103EC0004B6903628B6943620B68036070470000B3 +:103ED00008B5264B26481A6940F2FF110A431A61B9 +:103EE0001A6922F4FF7222F001021A611A691A6B30 +:103EF0000A431A631A6D0A431A651E4A1B6D11465E +:103F0000FFF7D6FF02F11C0100F58060FFF7D0FF3C +:103F100002F1380100F58060FFF7CAFF02F1540199 +:103F200000F58060FFF7C4FF02F1700100F58060CA +:103F3000FFF7BEFF02F18C0100F58060FFF7B8FFCC +:103F400002F1A80100F58060FFF7B2FF02F1C401A1 +:103F500000F58060FFF7ACFF02F1E00100F5806042 +:103F6000FFF7A6FFBDE8084000F08EB80038024019 +:103F7000000002401846000808B500F0F9F9FFF704 +:103F800031FBBDE80840FFF7E7BE000070470000C6 +:103F90000F4B1A6C42F001021A641A6E42F00102D1 +:103FA0001A660C4A1B6E936843F0010393604FF04E +:103FB000804353229A624FF0FF32DA6200229A6104 +:103FC0005A63DA605A6001225A611A60704700BF72 +:103FD00000380240002004E04FF0804208B511692B +:103FE000D3680B40D9B2C9439B07116107D5302371 +:103FF00083F31188FFF71CFB002383F3118808BDAE +:104000001F4B1A696FEAC2526FEAD2521A611A69DB +:10401000C2F308021A614FF0FF301A695A695861F9 +:1040200000215A6959615A691A6A62F080521A620B +:104030001A6A02F080521A621A6A5A6A58625A6AF6 +:1040400059625A6A1A6C42F080521A641A6E42F02F +:1040500080521A661A6E0B4A106840F48070106025 +:10406000186F00F44070B0F5007F1EBF4FF4803031 +:1040700018671967536823F40073536000F054B94C +:104080000038024000700040334B4FF080521A64F9 +:10409000324A4FF4404111601A6842F001021A603E +:1040A0001A689107FCD59A6822F003029A602A4B9D +:1040B0009A6812F00C02FBD1196801F0F90119603D +:1040C0009A601A6842F480321A601A689203FCD52A +:1040D0005A6F42F001025A671F4B5A6F9007FCD586 +:1040E0001F4A5A601A6842F080721A601B4A53686D +:1040F0005904FCD5184B1A689201FCD5194A9A60EC +:10410000194B1A68194B9A42194B21D1194A116857 +:10411000194A91421CD140F205121A60144A1368E0 +:1041200003F00F03052BFAD10B4B9A6842F0020201 +:104130009A609A6802F00C02082AFAD15A6C42F48A +:1041400080425A645A6E42F480425A665B6E7047EF +:1041500040F20572E1E700BF003802400070004005 +:104160000854400700948838002004E011640020BF +:10417000003C024000ED00E041C20F41074A08B593 +:10418000536903F00103536123B1054A13680BB16E +:1041900050689847BDE80840FFF75CB9003C014013 +:1041A000D84C0020074A08B5536903F00203536155 +:1041B00023B1054A93680BB1D0689847BDE8084021 +:1041C000FFF748B9003C0140D84C0020074A08B529 +:1041D000536903F00403536123B1054A13690BB11A +:1041E00050699847BDE80840FFF734B9003C0140EA +:1041F000D84C0020074A08B5536903F008035361FF +:1042000023B1054A93690BB1D0699847BDE80840CE +:10421000FFF720B9003C0140D84C0020074A08B500 +:10422000536903F01003536123B1054A136A0BB1BC +:10423000506A9847BDE80840FFF70CB9003C0140C0 +:10424000D84C0020164B10B55C6904F478725A61A2 +:10425000A30604D5134A936A0BB1D06A9847600647 +:1042600004D5104A136B0BB1506B9847210604D547 +:104270000C4A936B0BB1D06B9847E20504D5094A01 +:10428000136C0BB1506C9847A30504D5054A936C89 +:104290000BB1D06C9847BDE81040FFF7DBB800BF0A +:1042A000003C0140D84C0020194B10B55C6904F467 +:1042B0007C425A61620504D5164A136D0BB1506DEC +:1042C0009847230504D5134A936D0BB1D06D9847D9 +:1042D000E00404D50F4A136E0BB1506E9847A10449 +:1042E00004D50C4A936E0BB1D06E9847620404D586 +:1042F000084A136F0BB1506F9847230404D5054A41 +:10430000936F0BB1D06F9847BDE81040FFF7A2B88C +:10431000003C0140D84C002008B5FFF75DFEBDE829 +:104320000840FFF797B80000062108B50846FFF7D8 +:10433000BBF806210720FFF7B7F806210820FFF792 +:10434000B3F806210920FFF7AFF806210A20FFF78E +:10435000ABF806211720FFF7A7F806212820FFF762 +:10436000A3F8BDE8084007211C20FFF79DB8000016 +:1043700008B5FFF745FE00F007F8FFF707FEBDE8B8 +:104380000840FFF733BD00000023054A19460133FA +:10439000102BC2E9001102F10802F8D1704700BFEA +:1043A000D84C00200B460146184600F02DB80000FE +:1043B00000F040B8012838BF012010B5044620465F +:1043C00000F030F830B900F007F808B900F00CF848 +:1043D0008047F4E710BD0000024B1868BFF35B8F05 +:1043E000704700BF584D002008B5062000F084F843 +:1043F0000120FFF7A5FA0000024B0A4601461868A3 +:10440000FFF7E2BB1C23002010B5054C13462CB16E +:104410000A4601460220AFF3008010BD2046FCE7AB +:1044200000000000024B01461868FFF7D1BB00BF37 +:104430001C230020024B01461868FFF7CDBB00BFCC +:104440001C23002010B501390244904201D1002004 +:1044500005E0037811F8014FA34201D0181B10BDED +:104460000130F2E72DE9F041A3B1C91A17780144F0 +:10447000044603F1FF3C8C42204601D9002009E0AC +:104480000578BD4204F10104F5D10CEB0405D61802 +:10449000A54201D1BDE8F08115F8018D16F801EDB6 +:1044A000F045F5D0E7E700001F2938B504460D4672 +:1044B00004D9162303604FF0FF3038BD426C12B1AF +:1044C00052F821304BB9204600F030F82A46014618 +:1044D0002046BDE8384000F017B8012B0AD0591C1F +:1044E00003D1162303600120E7E7002442F82540AA +:1044F000284698470020E0E7024B01461868FFF77E +:10450000D3BF00BF1C23002038B5074D002304464D +:10451000084611462B60FFF717FA431C02D12B689F +:1045200003B1236038BD00BF5C4D0020FFF706BA21 +:10453000034611F8012B03F8012B002AF9D170472B +:1045400073772D6E61762D663430352D626C0000E8 +:1045500040A2E4F1646891060041A3E5F265699226 +:10456000070000004261642043414E496661636573 +:1045700020696E6465782E008000000000800000D5 +:104580000000800000000000000000002119000869 +:10459000412100089D200008611900086D190008DC +:1045A0006D1B000831190008411900083519000871 +:1045B0003D19000839190008911A0008451900082A +:1045C0001124000855190008651A0008633000001E +:1045D000CC450008804A0020904C0020004000009C +:1045E000004000000040000000400000000001000A +:1045F00000000200000002000000020000000200B3 +:104600000000020000000200000002006D61696EFF +:104610000069646C650000005400806A00000000BE +:10462000AAAAAA6A00000024F17F0000000000008E +:10463000009009000100000000000000AAAAAAAA38 +:1046400000000000FEFF000000000000000000006D +:104650000001000000000000AAAAAAAA00000000B1 +:10466000EFFF00000000000000000000000000005C +:1046700000000000AAAAAAAA00000000FFFF000094 +:10468000000000000000000000000000000000002A +:10469000AAAAAAAA00000000FFFF00000000000074 +:1046A000000000000000000000000000AAAAAAAA62 +:1046B00000000000FFFF00000000000000000000FC +:1046C0000000000000000000AAAAAAAA0000000042 +:1046D000FFFF0000000000000000000000000000DC +:1046E000000000000A0000000000000003000000BD +:1046F00000000000000000000000000000000000BA +:1047000000000000000000000000000000000000A9 +:104710000000000000000000721700000000000010 +:1047200000000F000000000040420F00FE2A0100C0 +:10473000D204000020230020000000000000000040 +:104740000000000000000000000000000000000069 +:104750000000000000000000000000000000000059 +:104760000000000000000000000000000000000049 +:104770000000000000000000000000000000000039 +:104780000000000000000000000000000000000029 +:08479000000000000000000021 :00000001FF diff --git a/Tools/bootloaders/sw-spar-f407_bl.bin b/Tools/bootloaders/sw-spar-f407_bl.bin index 813ec86ab8932a..0cfbdef808fa61 100755 Binary files a/Tools/bootloaders/sw-spar-f407_bl.bin and b/Tools/bootloaders/sw-spar-f407_bl.bin differ diff --git a/Tools/bootloaders/sw-spar-f407_bl.hex b/Tools/bootloaders/sw-spar-f407_bl.hex index 88c60c7a045d44..5e0a9fabd55e0f 100644 --- a/Tools/bootloaders/sw-spar-f407_bl.hex +++ b/Tools/bootloaders/sw-spar-f407_bl.hex @@ -1,1762 +1,1711 @@ :020000040800F2 -:1000000000070020F5040008FD2F0008B52F0008A8 -:10001000DD2F0008B52F0008D52F0008F7040008D1 -:10002000F7040008F7040008F7040008F13F00088F -:10003000F7040008F7040008F7040008F7040008B4 -:10004000F7040008F7040008F7040008F7040008A4 -:10005000F7040008F7040008C5650008ED6500080E -:10006000156600083D66000865660008F70400088C -:10007000F7040008F7040008F7040008F704000874 -:10008000F7040008F7040008F7040008452F0008EB -:10009000552F0008692F0008F70400088D66000836 -:1000A000F7040008F7040008F7040008F704000844 -:1000B00061670008F7040008F7040008F704000867 -:1000C000F7040008F7040008F7040008F704000824 -:1000D000F7040008F7040008F7040008F704000814 -:1000E000F1660008F7040008F7040008F7040008A8 -:1000F000F7040008F7040008F7040008F7040008F4 -:10010000F7040008F7040008F7040008F7040008E3 -:10011000F7040008F7040008F7040008F7040008D3 -:10012000F7040008F7040008F7040008F7040008C3 -:10013000F7040008F7040008F70400087D2F000802 -:100140008D2F0008A12F0008F7040008B95B0008F4 -:10015000F7040008F7040008F7040008F704000893 -:10016000F7040008F7040008F7040008F704000883 -:10017000F7040008F7040008F7040008F704000873 -:10018000F7040008F7040008F7040008F704000863 -:10019000F7040008F7040008F7040008F704000853 -:1001A000F7040008F7040008F7040008F704000843 -:1001B000F7040008F7040008F7040008F704000833 -:1001C000F7040008F7040008F7040008F704000823 -:1001D000F7040008F7040008F7040008F704000813 -:1001E000D11800080000000000000000000000001E -:1001F00053B94AB9002908BF00281CBF4FF0FF318E -:100200004FF0FF3000F074B9ADF1080C6DE904CE89 -:1002100000F006F8DDF804E0DDE9022304B07047E1 -:100220002DE9F047089D04468E46002B4DD18A42A9 -:10023000944669D9B2FA82F252B101FA02F3C2F1DC -:10024000200120FA01F10CFA02FC41EA030E94406D -:100250004FEA1C48210CBEFBF8F61FFA8CF708FB8E -:1002600016E341EA034306FB07F199420AD91CEB66 -:10027000030306F1FF3080F01F81994240F21C8198 -:10028000023E63445B1AA4B2B3FBF8F008FB1033E0 -:1002900044EA034400FB07F7A7420AD91CEB040415 -:1002A00000F1FF3380F00A81A74240F207816444E5 -:1002B000023840EA0640E41B00261DB1D44000236A -:1002C000C5E900433146BDE8F0878B4209D9002DCE -:1002D00000F0EF800026C5E9000130463146BDE858 -:1002E000F087B3FA83F6002E4AD18B4202D38242C2 -:1002F00000F2F980841A61EB030301209E46002D71 -:10030000E0D0C5E9004EDDE702B9FFDEB2FA82F2C5 -:10031000002A40F09280A1EB0C014FEA1C471FFA23 -:100320008CFE0126200CB1FBF7F307FB131140EA0A -:1003300001410EFB03F0884208D91CEB010103F1D7 -:10034000FF3802D2884200F2CB804346091AA4B299 -:10035000B1FBF7F007FB101144EA01440EFB00FE6D -:10036000A64508D91CEB040400F1FF3102D2A645D2 -:1003700000F2BB800846A4EB0E0440EA03409CE771 -:10038000C6F12007B34022FA07FC4CEA030C20FA1E -:1003900007F401FA06F31C43F9404FEA1C4900FA3E -:1003A00006F3B1FBF9F8200C1FFA8CFE09FB1811BB -:1003B00040EA014108FB0EF0884202FA06F20BD92E -:1003C0001CEB010108F1FF3A80F08880884240F27E -:1003D0008580A8F102086144091AA4B2B1FBF9F0C2 -:1003E00009FB101144EA014100FB0EFE8E4508D9BD -:1003F0001CEB010100F1FF346CD28E456AD9023842 -:10040000614440EA0840A0FB0294A1EB0E01A14226 -:10041000C846A64656D353D05DB1B3EB080261EB94 -:100420000E0101FA07F722FA06F3F1401F43C5E96E -:10043000007100263146BDE8F087C2F12003D840A4 -:100440000CFA02FC21FA03F3914001434FEA1C47E6 -:100450001FFA8CFEB3FBF7F007FB10360B0C43EAD8 -:10046000064300FB0EF69E4204FA02F408D91CEB88 -:10047000030300F1FF382FD29E422DD90238634486 -:100480009B1B89B2B3FBF7F607FB163341EA034126 -:1004900006FB0EF38B4208D91CEB010106F1FF3875 -:1004A00016D28B4214D9023E6144C91A46EA00466C -:1004B00038E72E46284605E70646E3E61846F8E6FE -:1004C0004B45A9D2B9EB020864EB0C0E0138A3E747 -:1004D0004646EAE7204694E74046D1E7D0467BE728 -:1004E000023B614432E7304609E76444023842E7A0 -:1004F000704700BF02E000F000F8FEE772B6374830 -:1005000080F30888364880F3098836483649086001 -:1005100040F20000CCF200004EF63471CEF2000141 -:100520000860BFF34F8FBFF36F8F40F20000C0F23F -:10053000F0004EF68851CEF200010860BFF34F8FF5 -:10054000BFF36F8F4FF00000E1EE100A4EF63C71E2 -:10055000CEF200010860062080F31488BFF36F8F8D -:1005600004F0F2FF05F0D6FE4FF055301F491B4A4C -:1005700091423CBF41F8040BFAE71D49184A9142E9 -:100580003CBF41F8040BFAE71A491B4A1B4B9A423D -:100590003EBF51F8040B42F8040BF8E7002018495D -:1005A000184A91423CBF41F8040BFAE704F0D0FF2F -:1005B00005F004FF144C154DAC4203DA54F8041B4B -:1005C0008847F9E700F042F8114C124DAC4203DACB -:1005D00054F8041B8847F9E704F0B8BF000700206F -:1005E000002300200000000808ED00E000010020CA -:1005F00000070020486D000800230020B0230020E1 -:10060000B023002008670020E0010008E401000892 -:10061000E4010008E40100082DE9F04F2DED108AF7 -:10062000C1F80CD0C3689D46BDEC108ABDE8F08FC0 -:10063000002383F311882846A047002004F090FA95 -:10064000FEE704F0E9F900DFFEE70000F8B501F08D -:1006500055F904F013FF074604F062FF0546B8BBE6 -:10066000204B9F4234D001339F4234D01E4B27F0A1 -:10067000FF029A4232D1F8B200F036FF2E4642F223 -:10068000107400F037FF08B10024264601F038FD51 -:1006900020B1032000F07CF80024264635B1134B2E -:1006A0009F4203D004F034FF00242646002004F0CB -:1006B000EFFE0EB100F082F801F0D2FA00F086FFF2 -:1006C00001F082F9204600F0DFF800F077F8F9E752 -:1006D0002E460024D5E704460126D2E7064641F21D -:1006E0008834CEE7010007B0000008B0263A09B010 -:1006F00008B501F03BF9A0F120035842584108BD6C -:1007000007B541F21203022101A8ADF8043001F04F -:100710004BF903B05DF804FB38B5302383F311883F -:10072000174803680BB104F0E7FA164A144800238F -:100730004FF47A7104F0D6FA002383F31188124C37 -:10074000236813B12368013B2360636813B16368B6 -:10075000013B63600D4D2B7833B963687BB9022090 -:1007600001F0F8F9322363602B78032B07D163681B -:100770002BB9022001F0EEF94FF47A73636038BDB3 -:10078000B023002019070008D0240020C82300202F -:10079000084B187003280CD8DFE800F008050208A1 -:1007A000022001F0CDB9022001F0C0B9024B0022B5 -:1007B0005A607047C8230020D024002010B501F0F3 -:1007C0009FFC30B1294B03221A70294B00225A603A -:1007D00010BD284B284A1C4619680131F8D0043353 -:1007E0009342F9D16268254B9A42F1D9244B9B6818 -:1007F00003F1006303F580339A42E9D204F05CFE12 -:1008000004F06EFE002001F0F9F80220FFF7C0FFAF -:100810001C4B1A6C00221A64196E1A66196E596CF8 -:100820005A64596E5A665A6E5A6942F080025A6189 -:100830005A6922F080025A615A691A6942F00052DC -:100840001A611A6922F000521A611B6972B64FF0E0 -:10085000E0233021C3F8084DD4E9003281F3118838 -:100860009D4683F308881047B2E700BFC8230020E5 -:10087000D02400200000010820000108FFFF00082C -:1008800000230020003802402DE9F04F93B0AC4B1C -:1008900000902022FF210AA89D6801F08BF9A94A47 -:1008A0001378A3B9A848012103601170302383F3A2 -:1008B000118803680BB104F01FFAA44AA248002370 -:1008C0004FF47A7104F00EFA002383F31188009B31 -:1008D00013B19F4B009A1A609E4A009C1378032B19 -:1008E0001EBF002313709A4A4FF0000A18BF5360CE -:1008F000D3465646D146012001F022F924B1944B4B -:100900001B68002B00F01582002001F02FF80390E7 -:10091000039B002B01DA00F0ABFE039B002BEDDB09 -:10092000012001F003F9039B213B162BE3D801A220 -:1009300052F823F091090008B90900084D0A00088F -:10094000F7080008F7080008F7080008D70A0008A9 -:10095000A70C0008C10B0008230C00084B0C000872 -:10096000710C0008F7080008830C0008F70800085D -:10097000F50C0008310A0008F7080008390D0008D6 -:100980009D090008310A0008F7080008230C000838 -:100990000220FFF7ADFE002840F0F581009B022108 -:1009A000BAF1000F08BF1C4605A841F21233ADF89A -:1009B000143000F0F9FF9EE74FF47A7000F0D6FF94 -:1009C000071EEBDB0220FFF793FE0028E6D0013F75 -:1009D000052F00F2DA81DFE807F0030A0D10133665 -:1009E00005230593042105A800F0DEFF17E0544815 -:1009F0000421F9E758480421F6E758480421F3E7B1 -:100A00004FF01C08404600F0FBFF08F10408059079 -:100A1000042105A800F0C8FFB8F12C0FF2D1012085 -:100A200000FA07F747EA0B0B5FFA8BFB4FF0000960 -:100A300001F00CF926B10BF00B030B2B08BF0024BF -:100A4000FFF75EFE57E746480421CDE7002EA5D00C -:100A50000BF00B030B2BA1D10220FFF749FE074639 -:100A600000289BD0012000F0C9FF0220FFF790FE74 -:100A700000261FFA86F8404600F0D0FF044690B1E9 -:100A80000021404600F0E2FF01360028F1D1BA46CD -:100A9000044641F21213022105A8ADF814303E4677 -:100AA00000F082FF27E70120FFF772FE2546244B66 -:100AB0009B68AB4207D9284600F0A2FF013040F006 -:100AC00067810435F3E7234B00251D70204BBA46A0 -:100AD0005D603E46ACE7002E3FF460AF0BF00B03C9 -:100AE0000B2B7FF45BAF0220FFF752FE322000F0A9 -:100AF0003DFFB0F10008FFF651AF18F003077FF497 -:100B00004DAF0F4A926808EB050393423FF646AF9C -:100B1000B8F5807F3FF742AF124B0193B84523DD14 -:100B20004FF47A7000F022FF0390039A002AFFF638 -:100B300035AF019B039A03F8012B0137EDE700BFA6 -:100B400000230020CC240020B02300201907000837 -:100B5000D0240020C82300200423002008230020E4 -:100B60000C230020CC230020C820FFF7C1FD07463E -:100B700000283FF413AF1F2D11D8C5F120024245C4 -:100B80000AAB25F0030028BF42468349019218446E -:100B900000F0EAFF019A8048FF2101F00BF84FEACC -:100BA000A8037D490193C8F38702284601F00AF89B -:100BB000064600283FF46DAF019B05EB830537E740 -:100BC0000220FFF795FD00283FF4E8AE00F05EFF3D -:100BD00000283FF4E3AE0027B846704B9B68BB4249 -:100BE00018D91F2F11D80A9B01330ED027F0030309 -:100BF00012AA134453F8203C05934046042205A949 -:100C000001F036FA04378046E7E7384600F0F8FE90 -:100C10000590F2E7CDF81480042105A800F0C4FE89 -:100C200006E70023642104A8049300F0B3FE002823 -:100C30007FF4B4AE0220FFF75BFD00283FF4AEAEB8 -:100C4000049800F00BFF0590E6E70023642104A858 -:100C5000049300F09FFE00287FF4A0AE0220FFF76F -:100C600047FD00283FF49AAE049800F007FFEAE73A -:100C70000220FFF73DFD00283FF490AE00F016FF84 -:100C8000E1E70220FFF734FD00283FF487AE05A915 -:100C9000142000F011FF04210746049004A800F07E -:100CA00083FE3946B9E7322000F060FE071EFFF6EA -:100CB00075AEBB077FF472AE384A926807EB090342 -:100CC00093423FF66BAE0220FFF712FD00283FF47F -:100CD00065AE27F003074F44B9453FF4A9AE484637 -:100CE00000F08EFE0421059005A800F05DFE09F1DC -:100CF0000409F1E74FF47A70FFF7FAFC00283FF49B -:100D00004DAE00F0C3FE002844D00A9B01330BD047 -:100D100008220AA9002000F055FF00283AD020221E -:100D2000FF210AA800F046FFFFF7EAFC1C4803F089 -:100D30001DFF13B0BDE8F08F002E3FF42FAE0BF077 -:100D40000B030B2B7FF42AAE0023642105A8059327 -:100D500000F020FE074600287FF420AE0220FFF7B7 -:100D6000C7FC804600283FF419AEFFF7C9FC41F2EA -:100D7000883003F0FBFE059800F09AFF464600F02D -:100D800065FF3C46B7E5064652E64FF0000905E62A -:100D9000BA467EE637467CE6CC23002000230020BE -:100DA000A0860100094A136849F2690099B21B0C38 -:100DB00000FB01331360064B186844F2506182B2A5 -:100DC000000C01FB0200186080B27047182300205D -:100DD0001423002010B500211022044600F0EAFE82 -:100DE000034B03CB206061601868A06010BD00BF9A -:100DF000107AFF1F2DE9F041ADF54C7D0DF12C0867 -:100E00006AAC40F2751207460D460CA80021C8F8DE -:100E1000001000F0CFFE4FF4C4720021204600F015 -:100E2000C9FE02F0F3F8274B4FF47A72B0FBF2F0F0 -:100E3000186093E80700022384E807000DF5E570C9 -:100E40002382FFF7C7FF47F217031F49238407A830 -:100E500005F096FD0F2384F832310DF2DB2207AB4B -:100E60000DF1240C1E4603CE6645106051603346DA -:100E700002F10802F6D130681060B188B37993713D -:100E8000918020464146012200F014FF0023039385 -:100E9000AB7E029305F11903019380B20123CDE9E2 -:100EA00004800093E97E05A3D3E90023384602F0CD -:100EB00075FC0DF54C7DBDE8F08100BF9E6AC42134 -:100EC000818A46EED8240020906900082DE9F0417F -:100ED0002C4C237ADAB080460D465BBB27A9284606 -:100EE00000F0F8FF0746002842D19DF89D60C82E0B -:100EF0003ED801464FF4A662204600F05BFE4FF458 -:100F00008073C4F8F8314FF40073C4F80C334FF415 -:100F10004073C4F8203432460DF19E0104F10900FB -:100F200000F022FE26449DF89C30777223720BB9A4 -:100F3000EB7E23728122002106AC27A800F03AFE46 -:100F40000122214627A801F001F800230393AB7E7C -:100F5000029305F1190380B201932823CDE90440DF -:100F60000093E97E05A3D3E90023404602F016FC76 -:100F70005AB0BDE8F08100BFAFF300802641727225 -:100F8000DF25D7B7C0560020F0B5254E4FF48A753F -:100F900005FB0065F1B096F8D83085F8DC30002408 -:100FA000D822214685F8E8403AA800F003FE06F171 -:100FB000090000F0F7FDD5F8E4308DF8F000C2B27A -:100FC00006AF06F109010DF1F100CDE93A3400F068 -:100FD000CBFD394601223AA800F0E4FF80B2CDE90A -:100FE000047008230127CDE9023706F1D8030193E5 -:100FF00030230093317A0B4807A3D3E9002302F092 -:10100000CDFBA04206DD02F001F8C5F8E00038464D -:1010100071B0F0BD2046FBE778F6339F93CACD8DC3 -:10102000C0560020F03400202DE9F04F274FDFF8A4 -:10103000A880274E87B0384602F0DCFB0346002824 -:101040003DD00024CDE90344ADF81440027B8DF877 -:10105000142099684068029403AA03C21B681D4DBE -:1010600043F000430293A146A2462B68D3F810B088 -:1010700001F0CEFF10EB080241F100032846CDF845 -:1010800000A002A9D84704F2344440F668030028BF -:10109000C8BF49F0010905F586559C4205F11005C8 -:1010A000E3D1B9F1000F05D0384602F0A7FB86F86E -:1010B00000A0C0E73378072B04D80133337007B0A2 -:1010C000BDE8F08F014802F099FBF8E7F03400200A -:1010D000F55B00202035002040420F0070B50D4622 -:1010E00014461E4602F0B6FA50B9022E10D1012C59 -:1010F0000ED112A3D3E90023C5E90023012007E0A4 -:10110000282C10D005D8012C09D0052C0FD0002098 -:1011100070BD302CFBD10BA3D3E90023ECE70BA36C -:10112000D3E90023E8E70BA3D3E90023E4E70BA30B -:10113000D3E90023E0E700BFAFF30080401DA1200A -:1011400026812A0B78F6339F93CACD8D9E6AC421DF -:10115000818A46EE26417272DF25D7B7F017304AF2 -:1011600039059E5638B505460E4C0021013500F074 -:101170006DFCA4F82C55B4F82C0500F04FFC78B1A8 -:10118000B4F82C0500F05AFC014648B9B4F82C0517 -:1011900000F05CFCB4F82C350133A4F82C35EAE7F8 -:1011A00038BD00BFC0560020F8B50E4C0E4F0226C9 -:1011B000A4F5805343F8487C237E3BB965692DB183 -:1011C000284601F01BF8284605F01AFB204601F0DE -:1011D00015F8A4F58654012EA4F1100400D1F8BD31 -:1011E0000126E5E7385600204C6A00082DE9F04F4B -:1011F0008FB000AF05460C4602F02CFA002849D10A -:10120000237E022B1BD1E38A012B18D101F0FEFEB5 -:101210000646FFF7C7FD03464FF4C870DFF8C482E7 -:10122000B3FBF0F206F5167602FB103316FA83F3E1 -:10123000C8F80030E37E33B9A34B00221A703C3764 -:10124000BD46BDE8F08F07F12401204600F000FE06 -:101250000028F4D107F11400FFF7BCFD97F82640F1 -:1012600007F11401224607F1270005F013FB0028BF -:10127000E2D10F2C08D8944B1C70D8F80030A3F59D -:101280001673C8F80030DAE797F82410284602F001 -:10129000D9F9D4E7E38A282B2BD010D8012B23D0FF -:1012A000052BCCD1BFF34F8F8849894BCA6802F414 -:1012B000E0621343CB60BFF34F8F00BFFDE7302BDD -:1012C000BDD1844EE17E327A9142B8D1607E314602 -:1012D000002291F8DC50854200F0A5800132042AFA -:1012E00001F58A71F5D1AAE721462846FFF782FD6C -:1012F000A5E721462846FFF7E9FDA0E7B2F8EC5044 -:101300007B6005F103094FEA99094FEA8902D11D73 -:10131000C908A8EBC1039D46EB460021584600F0E2 -:1013200049FC04F1EE012A463144584600F01CFC09 -:101330007B6813B9012000F061FB96F8D20000F041 -:101340006DFB044630B9307200F0A0FB204600F07F -:1013500055FBB1E0D6F8D4203AB996F8D200B6F8E9 -:101360002C25824201D8FFF7FDFED6F8D4202A446E -:10137000944208D296F8D200B6F82C250130824269 -:1013800001D8FFF7EFFE70685FFA89F2594600F066 -:1013900019FC08B9C54679E0726896F8D2002A446B -:1013A0007260D6F8D42005EB0209C6F8D49000F09C -:1013B00035FB814509D396F8D220D6F8D400013206 -:1013C000001B86F8D220C6F8D400FF2D0FD80024C9 -:1013D000347200F05BFB204600F010FB00F090FE42 -:1013E0003D4B188108B9FFF7E9F9C54627E7BB6807 -:1013F00096F8D9000AFB0362FB68D2F8E41082F881 -:10140000E83001F58061C2F8E030C2F8E410FFF77F -:10141000BBFDFFF709FE96F8D920013202F0030266 -:1014200086F8D920B6E74FF48A7A0AFB02F505F16F -:10143000EA013144204600F0E1FDF86000287FF425 -:10144000FEAE3544012285F8E82001F0DFFDD5F835 -:10145000E020D6ED007ADFED216A801A192838BF26 -:10146000192040F6B832904228BF1046B8EE677A8D -:1014700007EE900AF8EEE77A67EEA67ADFED186AD3 -:10148000E7EE267AFCEEE77AC6ED007A96F8D930D8 -:10149000BB60BA6873680AFB02F4321992F8E8106C -:1014A00059B1D2F8E4108B42E8463FF427AF00214F -:1014B00082F8E810C2F8E010C5467368064A9B0A35 -:1014C00001331381BBE600BFE934002000ED00E0EA -:1014D0000400FA05C0560020D8240020CDCCCC3D15 -:1014E0006666663FEC340020014B1870704700BF01 -:1014F000E424002030B54FF000542B4B22689A4270 -:1015000085B007D004F016F8044620BB002420461E -:1015100005B030BD254B627D25481A70237D0372CE -:101520004FF48073C0F8F8314FF40073C0F80C33F7 -:1015300000254FF44073C0F820341E49C0F8E45031 -:10154000C922093000F010FB2046E022294600F0B5 -:1015500031FB0124DBE7184A184D136C43F000738C -:101560001364AA6D164B9A42D0D12B6E013B7E2B91 -:10157000CCD8144A07CA01AB83E8070018460321F8 -:1015800000F08CFD6B6D83424FF00003BED12A6DDD -:101590008A4201BFAB65054B2A6E1A7003BF0A4B26 -:1015A000EA6D1A601C46B2E79AAD44C5E4240020F7 -:1015B000C05600201600002000380240006600409F -:1015C0005041A0B0586600401023002037B500F00D -:1015D00097FD1D4D1D4C2881022321681C486B710D -:1015E000012201F097FB1B48216850F8D03F0122EF -:1015F0005B68984700230193174B184900931848DC -:10160000184B4FF4805201F0F5FF174B197811B1C8 -:10161000134802F017F801F0F9FC0446FFF7C2FB8B -:101620004FF4C873B0FBF3F202FB130304F516701A -:1016300010FA83F00D4B186003F072FF08B10F230E -:101640002B8103B030BD00BFD82400201023002020 -:101650002035002020450020DD100008E82400206F -:10166000F0340020ED110008E4240020EC340020C8 -:101670002DE9F04F2DED028BDFF8508293B00BAFC8 -:101680009FED838BFFF7D0FC00230A93ADF8343035 -:101690000B937B600025844CDFF810A22E460123BB -:1016A0008DF81C3023688DED008B4FF0000BD3F8C4 -:1016B00008908DF81DB05B460DF11D0207A920466C -:1016C000C8479DF81C90B9F1000F24D0D8F8143009 -:1016D00083F48073C8F81430102259460EA800F025 -:1016E00069FA236808AA5E690AA90DF11E0320465B -:1016F000B04797E803000FAB83E803009DF8343050 -:101700008DF844300A9B0E930EA9DDE9082350465C -:1017100002F052FA4E4605F2344540F6680304F5ED -:1017200086549D4204F11004B9D1002EB2D15F4815 -:1017300001F090FF002840D15D4D01F067FC2B685F -:1017400098423AD301F062FC0446FFF72BFB4FF4BA -:10175000C873B0FBF3F202FB130304F5167010FA22 -:1017600083F02860534D8DF828602E7816B9012338 -:101770008DF82830C6F11004E4B20EA8FFF72AFB5A -:10178000062C28BF06240EAB224699190DF129001C -:1017900000F0EAF90AAB0393182302930134464B95 -:1017A0000193E4B201230093404804943AA3D3E99F -:1017B000002301F095FF00232B7001F027FC3F4A26 -:1017C0003F4C1368C31AB3F57A7F2FD3106001F032 -:1017D0001FFC02460B46354802F01AF8334801F068 -:1017E00039FF18B3237A374D002B14BF032302238C -:1017F0006B7101F00BFC0EAE4FF47A730122B0FB5B -:10180000F3F031462860284600F0FAFA18230293D4 -:101810002D4B019380B240F25513CDE90360009344 -:1018200022481FA3D3E9002301F05AFF237A93B182 -:1018300001F0ECFB002506464FF48A7794F8D900B6 -:10184000284400F0030007FB004393F8E82072B13E -:101850000135042DF2D1C82003F088F9237A002B3A -:101860007FF40DAF13B0BDEC028BBDE8F08FD3F861 -:10187000E02042B12368FA2B38BFFA23B21A0533AD -:10188000B2EB430FE4D3FFF77FFB0028E0D1E2E7A0 -:101890000000000000000000401DA12026812A0B4E -:1018A000F1C6A7C1D068080F20350020F034002011 -:1018B000EC340020E9340020E8340020F05B002004 -:1018C000C0560020D8240020F45B0020000802400D -:1018D00008B5064800F094FF054800F091FFBDE808 -:1018E0000840044A0449002004F084BF2035002049 -:1018F000F0450020345C0020A9110008704700006A -:1019000070B50F4B1B780133DBB2012B0C4611D89D -:101910000C4D29684FF47A730E6AA2FB033201461C -:1019200022462846B047844204D1074B00221A7051 -:10193000012070BD4FF4FA7003F018F90020F8E7A9 -:101940001C230020A85E0020245C002070B5044603 -:101950004FF47A76412C254628BF412506FB05F039 -:1019600003F004F9641BF5D170BD000007B5002336 -:10197000024601210DF107008DF80730FFF7C0FF87 -:1019800020B19DF8070003B05DF804FB4FF0FF3075 -:10199000F9E700000A4608B50421FFF7B1FF80F01F -:1019A0000100C0B2404208BD30B4054C2368DD6977 -:1019B000044B0A46AC460146204630BC604700BF97 -:1019C000A85E0020A086010070B503F0EFFB094E71 -:1019D000094D3080002428683388834208D903F0F9 -:1019E000DFFB2B6804440133B4F5803F2B60F2D356 -:1019F00070BD00BF265C0020F85B002003F086BCB1 -:101A000000F1006000F580300068704700F1006070 -:101A1000920000F5803003F00FBC0000054B1A68FF -:101A2000054B1B889B1A834202D9104403F0B8BBB4 -:101A300000207047F85B0020265C0020024B1B68EA -:101A4000184403F0B5BB00BFF85B0020024B1B68D5 -:101A5000184403F0C5BB00BFF85B002010F003037F -:101A60000AD1B0F5047F05D200F10050A0F5104076 -:101A7000D0F80038184670470023FBE700F100500B -:101A8000A0F51040D0F8100A70470000064991F800 -:101A9000243033B10023086A81F824300822FFF78C -:101AA000B5BF0120704700BFFC5B0020014B1868E8 -:101AB000704700BF002004E070B5194B1D68194B3A -:101AC0000138C5F30B0408442D0C04221E88A642DD -:101AD0000BD15C680A46013C824213460FD214F9CE -:101AE000016F4EB102F8016BF6E7013A03F108030A -:101AF000ECD181420B4602D22C2203F8012B0A4A78 -:101B000005241688AE4204D1984284BF967803F823 -:101B1000016B013C02F10402F3D1581A70BD00BF01 -:101B2000002004E0E0690008CC690008022802BF38 -:101B3000024B4FF480729A61704700BF0008024068 -:101B4000022802BF024B4FF080729A61704700BFBB -:101B500000080240022801BF024A536983F48073DF -:101B6000536170470008024010B50023934203D030 -:101B7000CC5CC4540133F9E710BD000010B5013846 -:101B800010F9013F3BB191F900409C4203D11AB1D9 -:101B90000131013AF4E71AB191F90020981A10BD09 -:101BA0001046FCE703460246D01A12F9011B002931 -:101BB000FAD1704702440346934202D003F8011B56 -:101BC000FAE770472DE9F8431F4D144695F8242095 -:101BD0000746884652BBDFF870909CB395F82430D6 -:101BE0002BB92022FF2148462F62FFF7E3FF95F82B -:101BF0002400C0F10802A24228BF2246D6B24146C4 -:101C0000920005EB8000FFF7AFFF95F82430A41B8E -:101C10001E44F6B2082E17449044E4B285F82460BE -:101C2000DBD1FFF733FF0028D7D108E02B6A03EBA5 -:101C300082038342CFD0FFF729FF0028CBD10020B9 -:101C4000BDE8F8830120FBE7FC5B0020024B1A781B -:101C5000024B1A70704700BF245C00201C23002038 -:101C600010B5104C104802F0B1FA21460E4802F0AF -:101C7000D9FA2468626DD2F8043843F00203C2F83E -:101C800004384FF47A70FFF761FE0849204602F0ED -:101C9000CFFB626DD2F8043823F00203C2F8043897 -:101CA00010BD00BF386B0008A85E0020406B000824 -:101CB000704700002DE9F0470D460446002190468C -:101CC000284640F27912FFF775FF234620220021B3 -:101CD000284601F013FF231D02222021284601F08F -:101CE0000DFF631D03222221284601F007FFA31DDB -:101CF00003222521284601F001FF04F108031022E8 -:101D00002821284601F0FAFE04F1100308223821A8 -:101D1000284601F0F3FE04F1110308224021284671 -:101D200001F0ECFE04F1120308224821284601F0DC -:101D3000E5FE04F1140320225021284601F0DEFEC6 -:101D400004F1180340227021284601F0D7FE04F167 -:101D500020030822B021284601F0D0FE04F121031F -:101D60000822B821284601F0C9FE04F12207C02646 -:101D70003B46314608222846083601F0BFFEB6F53C -:101D8000A07F07F10107F3D104F1320308223146A5 -:101D9000284601F0B3FE002704F1330A94F83230EC -:101DA0004FEAC7099F4209F5A47615D3B8F1000F91 -:101DB00008D1314604F599730722284601F09EFEAA -:101DC00009F24F16274694F832213B1B93420CD35D -:101DD000F01DC008BDE8F0870AEB07030822314672 -:101DE000284601F08BFE0137D8E707F2331331465E -:101DF0000822284601F082FE08360137E3E700009A -:101E000013B504460846002101602346C0F80310BC -:101E10002022019001F072FE0198231D0222202150 -:101E200001F06CFE0198631D0322222101F066FE81 -:101E30000198A31D0322252101F060FE019804F101 -:101E400008031022282101F059FE072002B010BD1E -:101E5000F7B50023047F00910E4607221946054678 -:101E600001F010FD731C0093012200230721284676 -:101E700001F008FDC4B9B31C0093052223460821D4 -:101E8000284601F0FFFC0D243746B278BB1B934275 -:101E900011D32B7FA88A0734E408BBB9844294BFCE -:101EA0000020012003B0F0BDAB8ADB00083BDB085B -:101EB000B3700824E8E7FB1C0093214600230822A6 -:101EC000284601F0DFFC08340137DEE7201A18BF8E -:101ED0000120E7E7F7B50023047F00910E460822B2 -:101EE0001946054601F0CEFC731CC4B908220093C4 -:101EF00011462346284601F0C5FC102401237278C0 -:101F00005F1C013B934211D32B7FA88A0734E4085E -:101F1000BBB9844294BF0020012003B0F0BDAB8A5E -:101F2000DB00083BDB0873700824E7E7F319009334 -:101F3000214600230822284601F0A4FC08343B4631 -:101F4000DDE7201A18BF0120E7E70000F8B50E46CC -:101F500005461446002181223046FFF72BFE2B4612 -:101F600008220021304601F0C9FD7CB96B1C072214 -:101F70000821304601F0C2FD0F2401236A785F1C5E -:101F8000013B934204D3E01DC008F8BD0824F4E7E8 -:101F9000EB1921460822304601F0B0FD08343B46DB -:101FA000ECE70000F8B50E46054614460021CE22A7 -:101FB0003046FFF7FFFD2B4628220021304601F076 -:101FC0009DFD7CB905F1080308222821304601F067 -:101FD00095FD30242F462A7A7B1B934204D3E01DC3 -:101FE000C008F8BD2824F5E707F1090321460822B7 -:101FF000304601F083FD08340137ECE7F7B5047F84 -:1020000000910E46012310220021054601F03AFC02 -:10201000C4B9B31C0093092223461021284601F0BD -:1020200031FC192437467288BB1B9A4211D82B7F8A -:10203000A88A0734E408BBB9844294BF0020012079 -:1020400003B0F0BDAB8ADB00103BDB0873801024CB -:10205000E8E73B1D0093214600230822284601F0B3 -:1020600011FC08340137DEE7201A18BF0120E7E72A -:1020700030B5094D0A4491420DD011F8013B58404A -:10208000082340F30004013B2C4013F0FF0384EAD3 -:102090005000F6D1EFE730BD2083B8EDF7B54FF033 -:1020A000FF33DFF854C0DFF854E000EB81011A463B -:1020B00088421CD050F8044B019401AF042417F857 -:1020C000015B82EA05620825DB18164605F1FF353B -:1020D0005241002EBCBF83EA0C0382EA0E0215F0C7 -:1020E000FF05F1D1013C14F0FF04E8D1E0E7D8434B -:1020F000D14303B0F0BD00BF9336EAA9EBE1F04253 -:10210000F7B5384A106851686B4603C36A463649CA -:102110003648082304F0CEFB0446002833D10A25B4 -:10212000334A106851686B4603C36A4631492F48E9 -:10213000082304F0BFFB0446002849D00369B3F527 -:10214000E02F45D8B0F8661041F2707291423FD14D -:10215000294A024402F15C018B4239D35C3B23499A -:1021600000209E1AFFF784FF3246074604F16401FF -:102170000020FFF77DFFA3689F4229D1E3689842C2 -:1021800008BF002524E00369B3F5E02F27D8418B71 -:1021900041F27072914220D1174A024402F11001BB -:1021A0008B4218D3103B114900209D1AFFF760FFA6 -:1021B0002A46064604F118010020FFF759FFA368DC -:1021C0009E4202D1E368984201D00D25A8E7002580 -:1021D000284603B0F0BD1025A2E70C25A0E70B258B -:1021E0009EE700BF006A0008DCFF0600000001084F -:1021F000096A000890FF06000800FFF710B5037C8D -:10220000044613B9006804F03DFB204610BD0000F1 -:102210000023BFF35B8FC360BFF35B8FBFF35B8FA4 -:102220008360BFF35B8F7047BFF35B8F0068BFF3C2 -:102230005B8F704770B505460C30FFF7F5FF05F171 -:10224000080604463046FFF7EFFFA04206D93046A5 -:102250006D68FFF7E9FF2544281A70BD3046FFF787 -:10226000E3FF201AF9E7000070B50546406898B111 -:1022700005F10800FFF7D8FF05F10C0604463046CB -:10228000FFF7D2FF8442304694BF6D680025FFF708 -:10229000CBFF013C2C44201A70BD000038B50C4621 -:1022A0000546FFF7C7FFA04210D305F10800FFF76E -:1022B000BBFF04446868B4FBF0F100FB1144BFF3BA -:1022C0005B8F0120AC60BFF35B8F38BD0020FCE763 -:1022D0002DE9F041144607460D46FFF7C5FF84423D -:1022E00028BF0446D4B1B84658F80C6B4046FFF7F7 -:1022F0009BFF3044286040467E68FFF795FF331A05 -:102300009C4203D86C600120BDE8F0816B60A41B87 -:102310003B68AB602044E8600220F5E72046F3E725 -:1023200038B50C460546FFF79FFFA04210D305F1D4 -:102330000C00FFF779FF04446868B4FBF0F100FB80 -:102340001144BFF35B8F0120EC60BFF35B8F38BD9E -:102350000020FCE72DE9FF41884669460746FFF764 -:10236000B7FF6C4606B204EBC6060025B44209D09E -:102370006268206808EB0501FFF7F6FB6368083424 -:102380001D44F3E729463846FFF7CAFF284604B044 -:10239000BDE8F081F8B505460C300F46FFF744FF65 -:1023A00005F1080604463046FFF73EFFA0423046DE -:1023B00088BF6C68FFF738FF201A386020B13046BC -:1023C0002C68FFF731FF2044F8BD000073B51446B8 -:1023D00006460D46FFF72EFF844228BF04460190B3 -:1023E000DCB101A93046FFF7D5FF019B33B9326854 -:1023F000C5E90233C5E9002401200CE09C4238BF46 -:1024000001942860019868608442F5D93368AB6014 -:10241000241AEC60022002B070BD2046FBE70000E9 -:102420002DE9FF410F466946FFF7D0FF6C4600B229 -:1024300004EBC0050026AC4209D0D4F8048054F85F -:10244000081BB8194246FFF78FFB4644F3E73046B6 -:1024500004B0BDE8F081000038B50546FFF7E0FFA5 -:10246000044601462846FFF719FF204638BD000004 -:10247000302383F3118862B670470000002383F392 -:10248000118862B67047000010B4026854681A469A -:1024900023465DF8044B1847012070470020704721 -:1024A0000020704770470000002070470E207047E2 -:1024B00000F5805090F8C800C0F34000704700005D -:1024C00000F5805090F9C90070470000F7B50C681E -:1024D000BDF8207014F000541E466FD10B7B082B02 -:1024E0006CD8FFF7C5FF4569AB685B010CD4AB68DE -:1024F0001B0108D4AC6814F080545DD1FFF7BEFF17 -:10250000204603B0F0BD01240B6804F1180C002B29 -:10251000B8BFDB004FEA0C1CB4BF43F004035B05FB -:1025200045F80C300B680FFA84FC13F0804F18BF8D -:1025300005EB0C1E05EB0C1C1EBFDEF8803143F0D2 -:102540000203CEF880310B7BCCF8843105EB041507 -:102550008B68C5F88C314B68C5F88831DCF8803160 -:1025600043F00103CCF8803100EB441541F26803DD -:102570001D4403EB44130344C5E9002608330D460C -:1025800001F10C0C55F804EB43F804EB6545F9D167 -:1025900084342D881D8000EB441407F00303257953 -:1025A00025F00B052B432371FFF768FF0097334697 -:1025B00000F04EFD0120A4E70224A5E74FF0FF3014 -:1025C0009FE7000013B500F580540191E06DFFF71F -:1025D0004BFE1F280AD90199E06D2022FFF7BAFEB1 -:1025E000A0F120035842584102B010BD0020FBE783 -:1025F00008B500F58050FFF73BFFC06DFFF708FE00 -:10260000BDE80840FFF73ABF0022026082814260C5 -:102610008260704710B500220023C0E90023002328 -:10262000044603810C30FFF7EFFF204610BD000089 -:10263000F0B5054600F580500C4690F8C83013F010 -:10264000040FC3F3800108BF114661F3820304F154 -:10265000840680F8C83005EB461389B01B79D8078B -:102660002ED57AB319072DD46846FFF7D3FF05EBB3 -:10267000441303F5835303F1180703AA10331868B2 -:102680005968144603C40833BB422246F7D1186880 -:1026900020609B88A380DDE90E23CDE90023012380 -:1026A000ADF808302B686946DB6B2846984705EB88 -:1026B00046152B791A075CBF43F008032B7101E024 -:1026C000002AF4D109B0F0BD2DE9F047074688B0E3 -:1026D00007F5805468469A468846FFF7C9FE91463A -:1026E000FFF798FFE06DFFF7A5FD1F2829D9E06DE2 -:1026F00020226946FFF7B0FE202822D103AD4446D0 -:1027000005AB2E4603CE9E4220606160354604F143 -:102710000804F6D130682060B388A380DDE9002387 -:10272000C9E90023BDF80830AAF80030FFF7A6FE7B -:102730004A4653464146384608B0BDE8F04700F0E7 -:1027400075BCFFF79BFE002008B0BDE8F0870000D5 -:102750002DE9F84F0023C0E90133264B044640F829 -:10276000183B0F46FFF750FF04F12800FFF752FF18 -:1027700004F1480804F582554646083530462036AF -:10278000FFF748FFAE42F9D104F580554FF480536E -:102790004FF00009C5E91339C5F848800123EE65FB -:1027A00004F5875804F58456C5F8549085F85830D8 -:1027B00085F86030083608F108084FF0000A4FF03D -:1027C000000B46E908ABA6F11800FFF71DFF203605 -:1027D00046F8289C4645F4D1012F85F8C97002D9E6 -:1027E000054800F00DFC054B53F827306361204687 -:1027F000BDE8F88F4C6A0008146A0008306A0008C7 -:1028000010B5044B197804464A1C1A70FFF7A0FF54 -:10281000204610BD305C00202DE9F047002950D043 -:10282000294B2A4FB7FBF1F599428CBF0A2311239C -:10283000581EB5FBF3FC03FB1C53C4B22BB102289A -:102840000346F5D80020BDE8F0870CF1FF36B6F559 -:10285000806FF7D2C4EBC40E0EF103034FEAE30915 -:10286000C3F3C703A4EB030809F1010A4FF47A7517 -:102870005FFA88F009FB05555AFA88F8B5FBF8F5B8 -:10288000B5F5617FC1BF0EF1FF33C3F3C703E01A93 -:10289000C0B25C1C50FA84F40CFB04F4B7FBF4F4F3 -:1028A000A142CFD1013BDBB20F2BCBD80138C0B254 -:1028B0000728C7D80021107116809170D3700120AD -:1028C000C1E70846BFE700BF3F420F0080DE80023D -:1028D00070B505460E464FF47A746B695B6803F079 -:1028E0000103B34207D04FF47A7002F03FF9013C84 -:1028F000F3D1204670BD0120FCE7000030B54269ED -:10290000936913F0700F16D000230B4C936103F101 -:10291000840200EB421211794D0709D5890707D5CA -:10292000416954F823508D60117941F0040111710F -:102930000133032BEBD130BD386A000873B51D4657 -:10294000436916469A68D207044609D59A68012158 -:102950009960C2F34002CDE900650021FFF768FEEF -:1029600063699A68D1050BD59A684FF480719960B4 -:10297000C2F34022CDE9006501212046FFF758FE51 -:1029800063699A68D2030BD59A684FF480319960D5 -:10299000C2F34042CDE9006502212046FFF748FE20 -:1029A000204602B0BDE87040FFF7A8BF0C4B10B541 -:1029B0001C561B5C012B11D800F02AFB50EA0103C6 -:1029C000024602D0421E61F10001064B53F824007A -:1029D00020B1BDE810400B46FFF7B0BF10BD00BFEF -:1029E0002C6A0008285C0020F8B5044646690029D6 -:1029F0006CD106F10C07386880076AD006EB011528 -:102A00003868D5F8B00110F0040FD5F8B0011ABF3E -:102A1000C00840F00040400DA061D5F8B0C11CF0E6 -:102A2000020F1CBF40F08040A061D5F8B40106EB56 -:102A3000011100F00F0084F82400D1F8B8012077CC -:102A4000D1F8B801000A6077D1F8B801000CA0777E -:102A5000D1F8B801000EE077D1F8BC0184F820006D -:102A6000D1F8BC01000A84F82100D1F8BC01000CA7 -:102A700084F82200D1F8BC11090E84F82310382103 -:102A8000396004F1340004F1180104F1240551F80F -:102A9000046B40F8046BA942F9D109880180C4E9AC -:102AA0000A2321460023238651F8283B2046DB6B6E -:102AB000984704F58052204692F8C83043F004034A -:102AC00082F8C830BDE8F840FFF718BF06F11007DC -:102AD00091E7F8BD0D4B70B51D561B5C012B0C46E4 -:102AE00012D800F095FA02460B4652EA030102D0D2 -:102AF000013A63F10003064951F8250020B121464F -:102B0000BDE87040FFF770BF70BD00BF2C6A0008C1 -:102B1000285C0020F8B500F583511E46FFF7A8FC9D -:102B2000DFF844C00831002404F1840500EB4515AA -:102B30002B795F070ED4DB060CD5D1E900739742E1 -:102B4000B34107D243695CF824709F602B7943F04E -:102B500004032B710134032C01F12001E4D1BDE801 -:102B6000F840FFF78BBC00BF386A000808B5FFF7D4 -:102B70007FFCFFF7C3FEBDE80840FFF77FBC000005 -:102B8000F8B543690546986800F0E050B0F1E05FA1 -:102B90000F461FD0E8B1FFF76BFC05F583541034E6 -:102BA000002606F1840305EB43131B791A0706D5AB -:102BB0000136032E04F12004F3D1012007E05B0766 -:102BC000F6D42146384600F07DFA0028F0D1FFF710 -:102BD00055FCF8BD0120FCE700F5805008B5FFF773 -:102BE00047FCC06DFFF726FBFFF748FC43090CBF0D -:102BF0000120002008BD0000F8B51D460023137019 -:102C00000F4606461446FFF7E7FF80F001003870D4 -:102C100025B129463046FFF7B3FF2070F8BD00000C -:102C20002DE9B8410C4615461F46804600F0F0F9E4 -:102C30000B462178024609B9287850B14046FFF783 -:102C400069FFFFF793FF3B462A462146FFF7D4FF73 -:102C50000120BDE8B881000038B500F58054FFF7C9 -:102C600007FC2A4D94F8C930EB5CDBB1012B27D06F -:102C7000FFF704FC94F8C830DB0746D4002944D0A1 -:102C8000FFF7F6FB94F8C930EB5C33B3012B31D07E -:102C900094F8C83043F0010384F8C830BDE83840E8 -:102CA000FFF7ECBB1A4B1A6C42F000721A641A6AF6 -:102CB00042F000721A621A6A22F000721A62D7E7B2 -:102CC000134B1A6C42F080621A641A6A42F08062F6 -:102CD0001A621A6A22F08062F0E70321132001F0E1 -:102CE000E5F90321142001F0E1F90321152001F099 -:102CF000DDF9CDE703213F2001F0D8F90321402081 -:102D000001F0D4F903214120F1E738BD286A000819 -:102D1000003802402DE9F04700F5805588B095F85D -:102D2000C930022B0446884616467FD8844F57F890 -:102D300023200AB947F82300D7F800A0C4F80C8074 -:102D40002674BAF1000F63D095F8C930012B6FD00B -:102D500001212046FFF780FFFFF78AFB62691368B5 -:102D600023F0020313606269136843F001031360E8 -:102D7000636900275F6101212046FFF77FFBFFF7B2 -:102D8000A7FD002800F09580E86DFFF741FA04F5F3 -:102D90008359BA4609F10809202200216846FEF746 -:102DA00009FF02A8FFF730FCCDF818A06A4609EB2E -:102DB00007030DF1180E9446BCE80300F4451860B3 -:102DC0005960624603F10803F5D1DCF80000186091 -:102DD00020379CF804201A71602FDDD195F8C83097 -:102DE0006FF38203002785F8C8306A4641462046C3 -:102DF000ADF80070ADF802708DF80470FFF70CFDAF -:102E0000636948BB4FF400421A6008B0BDE8F08720 -:102E100041F2D00003F0F6FC814610B15146FFF7B5 -:102E200097FCC7F80090B9F1000F8DD10020ECE7B6 -:102E3000386803681B6B98470146002888D13868BA -:102E4000FFF70AFF3868036832465B6841469847D7 -:102E500000287FF47DAFE9E761221A609DF8023017 -:102E60009DF803201B06120402F4702203F0407345 -:102E70001343BDF80020C2F3090213439DF8042058 -:102E80001205022E02F4E0020CBF4FF000410021B7 -:102E9000134362690B43D361636913225A61626908 -:102EA000136823F00103136039462046FFF710FD35 -:102EB00008B96369A6E795F8C930002B39D1616973 -:102EC000D1F8002242F00102C1F800226169D1F874 -:102ED000002222F47C5222F00E02C1F80022616925 -:102EE000D1F8002242F46062C1F800226269C2F89F -:102EF00014326269C2F8043262696FF07841C2F834 -:102F00000C126269C2F840326269C2F844326269E6 -:102F1000C2F8B0326269C2F8B432636944F20102A5 -:102F2000C3F81C226269D2F8003223F00103C2F810 -:102F3000003295F8C83043F0020385F8C83064E7E2 -:102F4000285C002008B50020FFF730FDBDE80840F0 -:102F500001F082B808B500210846FFF7BBFDBDE8C7 -:102F6000084001F079B8000008B501210020FFF702 -:102F7000B1FDBDE8084001F06FB8000008B50120C0 -:102F8000FFF714FDBDE8084001F066B808B5002160 -:102F90000120FFF79FFDBDE8084001F05DB800008B -:102FA00008B501210846FFF795FDBDE8084001F08E -:102FB00053B8000000B59BB0EFF309816822684662 -:102FC000FEF7D2FDEFF30583014B9B6BFEE700BFDD -:102FD00000ED00E008B5FFF7EDFF000000B59BB085 -:102FE000EFF3098168226846FEF7BEFDEFF3058323 -:102FF000014B5B6BFEE700BF00ED00E0FEE7000069 -:103000000FB408B5029801F03DFDFEE702F0D4B917 -:1030100002F0ACB913B56C4684E80600031D94E8D1 -:10302000030083E80500012002B010BD73B5856878 -:10303000019155B11B885B0707D4D0E900369B6B23 -:103040009847019AC1B23046A847012002B070BD2E -:10305000F0B5866889B005460C465EB1BDF83830DB -:103060005B070AD4D0E900379B6B98472246C1B270 -:103070003846B047012009B0F0BD00220023CDE959 -:1030800000230023ADF808300A4603AB01F108061F -:10309000106851681C4603C40832B2422346F7D177 -:1030A000106820609288A280FFF7B2FF0423ADF879 -:1030B00008302B68CDE90001DB6B6946284698474C -:1030C000D8E7000030B503680968DD0FB5EBD17FA4 -:1030D00023F0604421F060424FEAD1700BD0002B06 -:1030E000B8BFA40C0029B8BF920C944202D034BFE0 -:1030F0000120002030BD944205D1C1F38070C3F39C -:1031000080738342F6D194422CBF00200120F1E766 -:103110002DE9F041456A15B94162BDE8F0814B687F -:1031200023F06047C3F38A464FEAD37EC3F3807827 -:1031300016EA230638BF3E46AC462B465A68BEEB1D -:10314000D27F22F060440AD0002A18DAA40CB442DC -:1031500017D19D420FD10D60DEE71346EEE7A7427F -:1031600007D102F08044C2F3807242450BD054B1C3 -:10317000EFE708D2EDE7CCF800100B60CDE7B442E2 -:1031800001D0B442E5D81A689C46002AE5D11960FE -:10319000C3E700002DE9F047089D01F007044FEA5E -:1031A000D508224405F0070500EBD1004FF47F4914 -:1031B000944201D1BDE8F08704F0070705F0070A43 -:1031C00057453E4638BF5646C6F10806111B8E428B -:1031D00028BF0E46E10808EBD50E415C13F80EC07F -:1031E000B94029FA06F721FA0AF1FFB28CEA010187 -:1031F00047FA0AF739408CEA010C03F80EC0344450 -:103200003544D5E780EA0120082341F2210201B2CA -:103210004000002980B203F1FF33B8BF504013F0E3 -:10322000FF03F4D17047000038B50C468D18A54255 -:1032300000D138BD14F8011BFFF7E4FFF7E70000E9 -:1032400042684AB1136843604389818901339BB264 -:103250009942438138BF83811046704770B588B06A -:10326000202204460D4668460021FEF7A3FC2046B6 -:103270000495FFF7E5FF024658B16B46054608AED8 -:103280001C4603CCB44228606960234605F108055A -:10329000F6D1104608B070BD082817D909280CD0FF -:1032A0000A280CD00B280CD00C280CD00D280CD0E0 -:1032B0000E2814BF4020302070470C20704710208B -:1032C0007047142070471820704720207047000076 -:1032D000082817D90C280CD910280CD914280CD977 -:1032E00018280CD920280CD930288CBF0F200E208C -:1032F0007047092070470A2070470B2070470C2048 -:1033000070470D20704700002DE9F843078C072F08 -:1033100004461ED9D0E9029800254FF6FF73C5F187 -:103320002006A5F1200029FA05F108FA06F628FA88 -:1033300000F031430143C9B21846FFF763FF083577 -:10334000402D0346EBD1E1693A46BDE8F843FFF76B -:103350006BBF4FF6FF70BDE8F883000010B54B68F7 -:1033600023B9CA8A63F30902CA8210BD04691A68C4 -:103370001C600361C38A013BC3824A60EFE700001F -:103380002DE9F84F1D46CB8A0F46C3F309010529E5 -:10339000814692460B4630D00020AAB207F11A04AB -:1033A0009EB2042E1FFA80F80FD8904503F1010356 -:1033B00006D3FB8A0A4462F30903FB8201201AE068 -:1033C0001AF80060E6540130EAE79045F1D2A1F125 -:1033D000050B1C237C68BBFBF3F203FB12BB1FFA3B -:1033E0008BF6002C45D14846FFF72AFF044638B932 -:1033F00078606FF00200BDE8F88F4FF00008E6E754 -:10340000002606607860ADB24FF0000B454510D93C -:103410000AEB0803221D13F8011B9155B1B208F104 -:1034200001081B291FFA88F82BD0454506F1010633 -:10343000F1D8FB8AC3F30902154465F30903BCE71D -:10344000013292B21C462368002BF9D16B1F0B444A -:103450001C21B3FBF1F301339BB29A42D3D2BBF1EF -:10346000000FD0D14846FFF7EBFE20B9C4F800B0FA -:10347000BFE70122E7E7C0F800B05E4620600446DF -:10348000C1E74545D5D94846FFF7DAFE08B92060BF -:10349000AFE7C0F800B0002620600446B6E70000A1 -:1034A0002DE9F04F2DED028B1C4683B05B69019234 -:1034B00007468846002B00F09A80238C2BB1E269E6 -:1034C000002A00F09480072B35D807F10C00FFF795 -:1034D000B7FE054638B96FF00205284603B0BDECCB -:1034E000028BBDE8F08F14220021FEF763FB228CD3 -:1034F000E16905F10800FEF737FB208C013080B24E -:10350000FFF7E6FEFFF7C8FE013880B220840130E5 -:1035100028746369228C1B782A4403F01F0363F02C -:103520003F0348F000411372384669602946FFF7AF -:10353000EFFD0125D1E700F10C034FF0000908EE83 -:10354000103A4FF0800A4E464D4618EE100AFFF72B -:1035500077FE83460028BED014220021FEF72AFB06 -:10356000002E3AD1019BABF8083002220BF1080E75 -:103570001FFA82FC0CF10100BCF1060F218C80B215 -:1035800001D88E422BD3FFF7A3FEFFF785FE6269B9 -:103590001278013802F01F028E4208BF4FF0400A35 -:1035A00042EA49121BFA80F14AEA020A013048F065 -:1035B000004281F808A08BF81000CBF8042059468F -:1035C0003846FFF7A5FD238C0135B3422DB289F0B3 -:1035D00001094FF0000AB8D17FE70022C6E7E16990 -:1035E000895D0EF802100136B6B20132C0E76FF005 -:1035F000010572E7F8B515460E4630220021044653 -:103600001F46FEF7D7FA069B6360B5F5001F079BC0 -:10361000A76034BF6A094FF6FF72A36297B2E661F2 -:1036200004F1100000239A4206D800230360A78209 -:10363000E3822383E360F8BD066001333046203621 -:10364000F1E7000003781BB94BB2002BC8BF017033 -:103650007047000000787047F8B50C46C969074606 -:1036600011B9238C002B37D1257E1F2D34D8387803 -:1036700028BB228C072A2CD8268A36F003032BD1AC -:103680004FF6FF70FFF7D0FD20F00100310240043B -:1036900041EA0561400C41EA40254FF6FF7223469E -:1036A00029463846FFF7FCFE002807DD62691378DB -:1036B0000133DBB21F2B88BF00231370F8BD218AB2 -:1036C0002D0645EA012505432046FFF71DFE02466B -:1036D000E5E76FF00300F1E76FF00100EEE70000AF -:1036E00070B58AB0044616460021282268461D4659 -:1036F000FEF760FABDF83830ADF810300F9B059337 -:103700009DF840308DF81830119B07936946BDF83D -:103710004830ADF820302046CDE90265FFF79CFF28 -:103720000AB070BD2DE9F041D36905460C46164636 -:103730000BB9138C5BBB377E1F2F28D895F8008000 -:10374000B8F1000F26D03046FFF7DEFD33782102B6 -:1037500041EAC33141EA0801338A41EA076141EA9B -:1037600003410246334641F080012846FFF798FEA8 -:1037700000280ADD3378012B07D1726913780133F1 -:10378000DBB21F2B88BF00231370BDE8F0816FF000 -:103790000100FAE76FF00300F7E70000F0B58BB027 -:1037A00004460D4617460021282268461E46FEF7AD -:1037B00001FA9DF84C305A1E534253418DF80030A7 -:1037C0009DF84030ADF81030119B05939DF84830BE -:1037D0008DF81830149B07936A46BDF85430ADF845 -:1037E000203029462046CDE90276FFF79BFF0BB03B -:1037F000F0BD0000406A00B104307047436A1A68A7 -:10380000426202691A600361C38A013BC382704746 -:103810002DE9F041D0F82080194E14461D4641464E -:10382000002709B9BDE8F081D1E90223A21A65EBAE -:103830000303964277EB03031ED2036A8B420DD13A -:10384000FFF78CFD036A1B68036203690B60C38A80 -:103850000161016A013BC3828846E2E7FFF77EFD12 -:103860000B68C8F8003003690B60C38A0161013B33 -:10387000C382D8F80010D4E788460968D1E700BFB2 -:1038800080841E002DE9F04F8BB00D46DDF850907E -:1038900014469B468046002800F01981B9F1000FBC -:1038A00000F01581531E3F2B00F21181012A03D134 -:1038B000BBF1000F40F00B810023CDE90833B8F8CD -:1038C0001430B5EBC30F4FEAC30703D300200BB08E -:1038D000BDE8F08F2B199F42D8F80C303ABF7F1B00 -:1038E000FFB227461BB9D8F81030002B7AD0272D0D -:1038F0004ED8C5F12806B7424FF000032CBFF6B2F0 -:103900003E4600932946D8F8080008AB3246FFF738 -:1039100041FCA7EB060A35445FFA8AFAB8F814307E -:1039200003F10053053BDB000493D8F80C300393FC -:103930002821039B13B1BAF1000F2CD1D8F8100045 -:1039400040B1BAF1000F05D0009608AB5246691A93 -:10395000FFF720FC38B2002FB8D066070AD00AABB8 -:1039600003EBD401624211F8083C02F00702134154 -:1039700001F8083C082C3CD9102C40F2B580202CD2 -:1039800040F2B780BBF1000F00F09C80082334E0C8 -:10399000BA460026C2E7049BE02B28BFE02306932B -:1039A0000B44AB42059314D95A1B039800969245D9 -:1039B00034BF5246D2B2691A08AB04300792FFF7FF -:1039C000E9FB079A1644AAEB020A1544F6B25FFA1D -:1039D0008AFA049B069A05999B1A0493039B1B6819 -:1039E0000393A6E70093D8F8080008AB3A462946A7 -:1039F000AEE7BBF1000F13D00123B4EBC30F6CD0C3 -:103A0000082C12D89DF82030621E23FA02F2D50746 -:103A100006D54FF0FF3202FA04F423438DF820302C -:103A20009DF8203089F8003051E7102C12D8BDF8ED -:103A30002030621E23FA02F2D10706D54FF0FF3282 -:103A400002FA04F42343ADF82030BDF82030A9F881 -:103A500000303CE7202C0FD80899631E21FA03F3AD -:103A6000DA0705D54FF0FF3202FA04F40C4308944C -:103A7000089BC9F800302AE7402C2BD0DDE9086507 -:103A8000611EC4F12102A4F1210326FA01F105FA15 -:103A900002F225FA03F311431943CB0712D5012291 -:103AA000A4F12003C4F1200102FA03F322FA01F188 -:103AB000A240524243EA010363EB430332432B43E8 -:103AC000CDE90823DDE90823C9E90023FFE66FF00B -:103AD0000100FCE66FF00800F9E6082CA0D9102CD4 -:103AE000B3D9202CEED8C3E7BBF1000FADD0022331 -:103AF00083E7BBF1000FBBD004237EE730B5012A7A -:103B0000144638BF0124402C85B028BF402400252E -:103B1000012ACDE9025518D81B788DF808306307C3 -:103B20000AD004AB03EBD405624215F8083C02F05E -:103B30000702934005F8083C009103462246002105 -:103B400002A8FFF727FB05B030BD082AE4D9102AE8 -:103B500003D81B88ADF80830E1E7202A8DBFD3E9F0 -:103B600000231B680293CDE90223D8E710B5CB6888 -:103B70001BB98B600B618B8210BD04691A681C60D5 -:103B80000361C38A013BC382CA60F0E703064CBFEE -:103B9000C0F3C0300220704708B50246FFF7F6FFB9 -:103BA000022806D15306C2F30F2001D100F0030012 -:103BB00008BDC2F30740FBE72DE9F04F93B0CDE914 -:103BC00003230A6804461046FFF7E0FF022814BFEB -:103BD000C2F306260026002A0D46824680F2F281B4 -:103BE00012F0C04940F0EE81097B002900F0EA8123 -:103BF000022803D02378B34240F0E781C2F3046384 -:103C00000693104602F07F030593FFF7C5FF059B5F -:103C100029444FEA834848EA0A4848EA4668CE7889 -:103C200000230022CDE90823F309834648EA00086F -:103C3000029367D0059B009302466768534608A924 -:103C40002046B847002800F0C381276A4FB9414693 -:103C500004F10C00FFF702FB074690B96FF0020079 -:103C600054E03B6998450DD03F68002FF9D141469B -:103C700004F10C00FFF7F2FA07460028EED0236AA1 -:103C80003B60276297F817C006F01F08CCF3840C3E -:103C9000ACEB08001FFA80FE0028B8BF0EF1200030 -:103CA000A8EB0C031FFA83FED7E90221B8BF00B2CC -:103CB000002B0793BEBF0EF120031BB2079352EAFD -:103CC000010338D0039BDFF824E39A1A049B4FF0DA -:103CD000000C63EB010196457CEB01032BD36B7B5E -:103CE00097F81AE0734519D1029B002B78D0012870 -:103CF00021DC7868F8B9DFF8F0C2944570EB010375 -:103D000016D337E0276A27B96FF00C0013B0BDE86F -:103D1000F08F3B699845B5D03F68F4E7B2489042D0 -:103D20007CEB010301D30020F0E7029B002BFAD0CB -:103D3000079B0F2B17DCFA7DB30002F0030203F0A0 -:103D40007C031343FB7539462046FFF707FB6B7B6B -:103D5000BB76029B3BB9FB7DC3F38402013262F365 -:103D60008603FB75D0E76A7BBB7E9A42DBD1029B60 -:103D7000002B35D0B309022B32D0039BBB60049BD0 -:103D8000FB60142200210DA8FDF714FF039B0A938A -:103D9000049B0B932B1D0C932B7BADF83EB0013B8A -:103DA000DBB2ADF83C30069B8DF84230059B8DF8B8 -:103DB000433094F82C308DF840A083F001038DF847 -:103DC00044308DF84180A3680AA920469847FB7DBE -:103DD000C3F38403013303F01F039B02FB82A2E7BA -:103DE000FB7DC6F34012B2EBD31F40F0F480C3F367 -:103DF0008403434540F0F280029A2B7BB609002AE7 -:103E00004DD0F2075DD4032B40F2EB80039BBB60E7 -:103E1000049BFB602B7BAE1D033BDBB23246394675 -:103E200004F10C00FFF7ACFA00280CDA3946204602 -:103E3000FFF794FAFB7DC3F38403013303F01F0300 -:103E40009B02FB820AE7DDE90884AB883B834FF6DF -:103E5000FF73C9F12000A9F1200228FA09F104FA40 -:103E600000F0014324FA02F211431846C9B2FFF7E9 -:103E7000C9F909F10809B9F1400F0346E9D1B8823F -:103E80002A7B033AD2B23146FFF7CEF9FB7DB882E6 -:103E9000DA43C2F3C01262F3C713FB7543E786B976 -:103EA0002E1D013BDBB23246394604F10C00FFF710 -:103EB00067FA0028BADB2A7BB88A013AD2B23146C7 -:103EC000E2E7F98AC1F30901013B0429DAB25BD8C0 -:103ED000281D002307F11B069A4208D910F801CBD0 -:103EE00006F801C0013101330529DBB2F4D1039991 -:103EF0000A9104990B91934207F11B010C9138BF71 -:103F0000043379680D9134BF55FA83F300230E937F -:103F1000FB8AADF83EB0C3F309031A44069B8DF843 -:103F20004230059B8DF8433094F82C30ADF83C209E -:103F300083F001038DF8443000238DF840A08DF804 -:103F400041807B602A7BB88A013A291DFFF76CF912 -:103F50003B8BB882834203D1A3680AA920469847C5 -:103F600020460AA9FFF702FEFB7DBA8AC3F3840349 -:103F7000013303F01F039B02FB823B8B9A420CBF71 -:103F800000206FF01000C1E67B68002BAFD0052049 -:103F900001E01C3033461E68002EFAD1091A081DB4 -:103FA0002E1D184401EB090CBCF11B0F5FFA89F3BD -:103FB0009DD89A429BD916F8013B00F8013B09F1C4 -:103FC0000109EFE76FF00900A0E66FF00A009DE637 -:103FD0006FF00B009AE66FF00D0097E66FF00E00A1 -:103FE00094E66FF00F0091E640420F0080841E00BF -:103FF000EFF3098305494A6B22F001024A636833F3 -:1040000083F30988002383F31188704700EF00E0F1 -:10401000302080F3118862B60C4B0D4AD96821F428 -:10402000E0610904090C0A43DA60D3F8FC2009496D -:1040300042F08072C3F8FC200A6842F001020A6074 -:104040002022DA7783F82200704700BF00ED00E0FD -:104050000003FA05001000E010B5302383F3118847 -:104060000E4B5B6813F4006314D0F1EE103AEFF3DB -:104070000984683C4FF08073E361094BDB6B236676 -:1040800084F3098800F0BCFC10B1064BA36110BD9D -:10409000054BFBE783F31188F9E700BF00ED00E073 -:1040A00000EF00E0430600084606000800F1604308 -:1040B00003F561430901C9B283F80013012200F03E -:1040C0001F039A4043099B0003F1604303F56143DA -:1040D000C3F880211A607047026843681143016089 -:1040E00003B118477047000013B5446BD4F89434FB -:1040F0001A681178042915D1217C022912D1197965 -:10410000128901238B4013420CD101A904F14C0008 -:1041100001F0BCFFD4F89444019B21790246206849 -:1041200000F0D0F902B010BD143001F03FBF000024 -:104130004FF0FF33143001F039BF00004C3002F073 -:1041400011B800004FF0FF334C3002F00BB8000004 -:10415000143001F00DBF00004FF0FF31143001F0BA -:1041600007BF00004C3001F0DDBF00004FF0FF3210 -:104170004C3001F0D7BF00000020704710B5D0F8D8 -:1041800094341A6811780429044617D1017C022955 -:1041900014D15979528901238B4013420ED1143026 -:1041A00001F0A0FE024648B1D4F894444FF4807365 -:1041B00061792068BDE8104000F072B910BD0000C0 -:1041C000406BFFF7DBBF0000704700007FB5124B6C -:1041D000036000234360C0E90233012502260F4B30 -:1041E000057404460290019300F18402294600966A -:1041F0004FF48073143001F051FE094B0294CDE965 -:10420000006304F523724FF48073294604F14C00D7 -:1042100001F018FF04B070BD8C6A0008C1410008AD -:10422000E94000080B68302282F311880A7903EB19 -:10423000820290614A79093243F822008A7912B1E8 -:1042400003EB820398610223C0F8941403740020E6 -:1042500080F311887047000038B5037F044613B11E -:1042600090F85430ABB9201D01250221FFF734FF2F -:1042700004F1140025776FF0010100F09FFC84F831 -:10428000545004F14C006FF00101BDE8384000F0DB -:1042900095BC38BD10B5012104460430FFF71CFF62 -:1042A0000023237784F8543010BD000038B504464D -:1042B0000025143001F00AFE04F14C00257701F0CE -:1042C000D9FE201D84F854500121FFF705FF204638 -:1042D000BDE83840FFF752BF90F8443003F0600368 -:1042E000202B07D190F84520212A4FF0000303D856 -:1042F0001F2A06D800207047222AFBD1C0E90E33BE -:1043000003E0034A82630722C2630364012070470B -:104310001D23002037B5D0F894341A681178042989 -:1043200004461AD1017C022917D119791289012377 -:104330008B40134211D100F14C05284601F05AFF81 -:1043400058B101A9284601F0A1FED4F89444019B7C -:1043500021790246206800F0B5F803B030BD0000B6 -:10436000F0B500EB810385B09E6904460D46FEB1B1 -:10437000302383F3118804EB8507301D0821FFF7F4 -:10438000ABFEFB685B691B6806F14C001BB101903A -:1043900001F08AFE019803A901F078FE024648B1B7 -:1043A000039B2946204600F08DF8002383F31188F3 -:1043B00005B0F0BDFB685A691268002AF5D01B8A67 -:1043C000013B1340F1D104F14402EAE7093138B569 -:1043D00050F82140DCB1302383F31188D4F89424C1 -:1043E0001368527903EB8203DB689B695D6845B112 -:1043F00004216018FFF770FE294604F1140001F053 -:104400007BFD2046FFF7BAFE002383F3118838BDF9 -:104410007047000001F0F0B8012303700023C0E9E9 -:104420000133C36183620362C36243620363704703 -:1044300038B50446302383F311880025C0E90355BD -:10444000C0E90555416001F0E7F80223237085F3C8 -:104450001188284638BD000070B500EB8103054681 -:104460005069DA600E46144618B110220021FDF79B -:10447000A1FBA06918B110220021FDF79BFB31467A -:104480002846BDE8704001F091B90000826802F052 -:10449000011282600022C0E90422826101F012BA96 -:1044A000F0B400EB81044789E4680125A4698D40DC -:1044B0003D43458123600023A2606360F0BC01F0AE -:1044C0002DBA0000F0B400EB81040789E4680125EF -:1044D00064698D403D43058123600023A2606360D1 -:1044E000F0BC01F0A7BA000070B502230025044615 -:1044F0000370C0E90255C0E90455C564856180F8C0 -:10450000345001F0EFF863681B6823B12946204658 -:10451000BDE87040184770BD0378052B10B5044600 -:104520000AD080F850300523037043681B680BB134 -:10453000042198470023A36010BD000001780529DD -:1045400006D190F85020436802701B6803B11847E9 -:104550007047000070B590F83430044613B1002362 -:1045600080F8343004F14402204601F0CDF963684C -:104570009B68B3B994F8443013F0600535D000213E -:10458000204601F06DFC0021204601F05FFC6368CD -:104590001B6813B1062120469847062384F834305F -:1045A00070BD204698470028E4D0B4F84A30E26B4A -:1045B0009A4288BFE36394F94430E56B002B4FF0D7 -:1045C000300380F20381002D00F0F280092284F88C -:1045D000342083F311880021D4E90E232046FFF70D -:1045E00071FF002383F31188DAE794F8452003F084 -:1045F0007F0343EA022340F20232934200F0C58077 -:1046000021D8B3F5807F48D00DD8012B3FD0022BA5 -:1046100000F09380002BB2D104F14C02A26302227D -:10462000E2632364C1E7B3F5817F00F09B80B3F5BB -:10463000407FA4D194F84630012BA0D1B4F84C307F -:1046400043F0020332E0B3F5006F4DD017D8B3F555 -:10465000A06F31D0A3F5C063012B90D8636894F8A4 -:1046600046205E6894F84710B4F848302046B047BA -:10467000002884D04368A3630368E3631AE0B3F5BA -:10468000106F36D040F6024293427FF478AF5C4B15 -:10469000A3630223E3630023C3E794F84630012BAE -:1046A0007FF46DAFB4F84C3023F00203C4E90E552B -:1046B000A4F84C30256478E7B4F84430B3F5A06F23 -:1046C0000ED194F8463084F84E30204601F062F85E -:1046D00063681B6813B101212046984703232370A8 -:1046E0000023C4E90E339CE704F14F03A3630123C5 -:1046F000C3E72378042B10D1302383F3118820469D -:10470000FFF7C4FE85F311880321636884F84F50D6 -:1047100021701B680BB12046984794F84630002B57 -:10472000DED084F84F300423237063681B68002BAD -:10473000D6D0022120469847D2E794F848301D068B -:1047400003F00F0120460AD501F0D0F8012804D06B -:1047500002287FF414AF2B4B9AE72B4B98E701F01C -:10476000B7F8F3E794F84630002B7FF408AF94F8DD -:10477000483013F00F01B3D01A06204602D501F0DD -:1047800083FBADE701F076FBAAE794F84630002BF7 -:104790007FF4F5AE94F8483013F00F01A0D01B065B -:1047A000204602D501F05CFB9AE701F04FFB97E74A -:1047B000142284F8342083F311882B462A46294694 -:1047C0002046FFF76DFE85F31188E9E65DB11522FD -:1047D00084F8342083F311880021D4E90E23204685 -:1047E000FFF75EFEFDE60B2284F8342083F3118888 -:1047F0002B462A4629462046FFF764FEE3E700BF22 -:10480000BC6A0008B46A0008B86A000838B590F8B5 -:1048100034300446002B3ED0063BDAB20F2A34D89F -:104820000F2B32D8DFE803F0373131082232313133 -:104830003131313131313737C56BB0F84A309D42B3 -:1048400014D2C3681B8AB5FBF3F203FB12556DB992 -:10485000302383F311882B462A462946FFF732FE80 -:1048600085F311880A2384F834300EE0142384F889 -:104870003430302383F3118800231A46194620462A -:10488000FFF70EFE002383F3118838BD036C03B1DC -:1048900098470023E7E70021204601F0E1FA0021D4 -:1048A000204601F0D3FA63681B6813B10621204645 -:1048B00098470623D7E7000010B590F83430142B42 -:1048C000044629D017D8062B05D001D81BB110BD3E -:1048D000093B022BFBD80021204601F0C1FA002140 -:1048E000204601F0B3FA63681B6813B10621204625 -:1048F0009847062319E0152BE9D10B2380F83430B3 -:10490000302383F3118800231A461946FFF7DAFD96 -:10491000002383F31188DAE7C3689B695B68002B87 -:10492000D5D1036C03B19847002384F83430CEE727 -:1049300000230375826803691B6899689142FBD262 -:104940005A68036042601060586070470023037526 -:10495000826803691B6899689142FBD85A680360B2 -:10496000426010605860704708B50846302383F3F2 -:1049700011880B7D032B05D0042B0DD02BB983F3AD -:10498000118808BD8B6900221A604FF0FF338361E4 -:10499000FFF7CEFF0023F2E7D1E9003213605A603F -:1049A000F3E70000FFF7C4BF054BD9680875186826 -:1049B00002681A60536001220275D860FBF72CBEB2 -:1049C000385C002030B50C4BDD684B1C87B00446CA -:1049D0000FD02B46094A684600F084F92046FFF7BD -:1049E000E3FF009B13B1684600F086F9A86907B0A1 -:1049F00030BDFFF7D9FFF9E7385C002069490008AE -:104A0000044B1A68DB6890689B68984294BF00204A -:104A100001207047385C0020084B10B51C68D8682E -:104A200022681A60536001222275DC60FFF78EFF56 -:104A300001462046BDE81040FBF7EEBD385C002083 -:104A4000044B1A68DB6892689B689A4201D9FFF7A9 -:104A5000E3BF7047385C002038B5074C0749084869 -:104A6000012300252370656001F0FCFB0223237005 -:104A700085F3118838BD00BFA05E0020C46A00081D -:104A8000385C002008B572B6044B186500F052FC83 -:104A900000F010FD024B03221A70FEE7385C002084 -:104AA000A05E002000F05EB9EFF3118020B9EFF3B3 -:104AB0000583302282F311887047000010B530B9A9 -:104AC000EFF30584C4F3080414B180F3118810BD1A -:104AD000FFF7B6FF84F31188F9E70000034A516835 -:104AE00053685B1A9842FBD8704700BF001000E083 -:104AF0008B60022308618B82084670478368A3F1AC -:104B0000840243F8142C026943F8442C426943F8A8 -:104B1000402C094A43F8242CC26843F8182C02227E -:104B200003F80C2C002203F80B2C044A43F8102C39 -:104B3000A3F12000704700BF31060008385C002058 -:104B400008B5FFF7DBFFBDE80840FFF72BBF00000B -:104B5000024BDB6898610F20FFF726BF385C00200E -:104B6000302383F31188FFF7F3BF000008B5014637 -:104B7000302383F311880820FFF724FF002383F3F9 -:104B8000118808BD064BDB6839B1426818605A606D -:104B9000136043600420FFF715BF4FF0FF307047EC -:104BA000385C00200368984206D01A6802605060A2 -:104BB00099611846FFF7F6BE7047000038B5044605 -:104BC0000D462068844200D138BD036823605C60D4 -:104BD0008561FFF7E7FEF4E710B503689C68A24221 -:104BE0000CD85C688A600B604C60216059609968E1 -:104BF0008A1A9A604FF0FF33836010BD1B68121B46 -:104C0000ECE700000A2938BF0A2170B504460D46BA -:104C10000A26601901F020FB01F00CFB041BA542E1 -:104C200003D8751C2E460446F3E70A2E04D9BDE8C6 -:104C30007040012001F056BB70BD0000F8B5144B68 -:104C40000D46D96103F1100141600A2A1969826099 -:104C500038BF0A22016048601861A818144601F0A4 -:104C6000EDFA0A2701F0E6FA431BA342064606D3F3 -:104C70007C1C281901F0F0FA27463546F2E70A2F86 -:104C800004D9BDE8F840012001F02CBBF8BD00BFFD -:104C9000385C0020F8B506460D4601F0CBFA0F4A05 -:104CA000134653F8107F9F4206D12A4601463046EC -:104CB000BDE8F840FFF7C2BFD169BB68441A2C19A0 -:104CC00028BF2C46A34202D92946FFF79BFF224664 -:104CD00031460348BDE8F840FFF77EBF385C00204E -:104CE000485C002010B4C0E9032300235DF8044BA6 -:104CF0004361FFF7CFBF000010B5194C23699842FC -:104D00000DD0D0E90032816813605A609A680A4475 -:104D10009A60002303604FF0FF33A36110BD234668 -:104D2000026843F8102F53600022026022699A4201 -:104D300003D1BDE8104001F089BA936881680B4443 -:104D4000936001F077FA2269E1699268441AA242FD -:104D5000E4D91144BDE81040091AFFF753BF00BF62 -:104D6000385C00202DE9F047DFF8BC8008F110071F -:104D70002C4ED8F8105001F05DFAD8F81C40AA6803 -:104D8000031B9A423ED81444D5E900324FF0000983 -:104D9000C8F81C4013605A60C5F80090D8F810306D -:104DA000B34201D101F052FA89F31188D5E90331F8 -:104DB00028469847302383F311886B69002BD8D09D -:104DC00001F038FA6A69A0EB04094A4582460DD21F -:104DD000022001F087FA0022D8F81030B34208D13F -:104DE00051462846BDE8F047FFF728BF121A224473 -:104DF000F2E712EB090938BF4A4629463846FFF761 -:104E0000EBFEB5E7D8F81030B34208D01444211AAD -:104E1000C8F81C00A960BDE8F047FFF7F3BEBDE885 -:104E2000F08700BF485C0020385C002000207047FD -:104E3000FEE70000704700004FF0FF3070470000B1 -:104E400002290CD0032904D00129074818BF0020EB -:104E50007047032A05D8054800EBC2007047044894 -:104E600070470020704700BF9C6B00082C23002077 -:104E7000506B000870B59AB00546084601A9144663 -:104E800000F0C2F801A8FCF78DFE431C5B00C5E9E9 -:104E900000340022237003236370C6B201AB0234D6 -:104EA0001046D1B28E4204F1020401D81AB070BD8E -:104EB00013F8011B04F8021C04F8010C0132F0E79E -:104EC00008B5302383F311880348FFF723FA002342 -:104ED00083F3118808BD00BFA85E002090F844301D -:104EE00003F01F02012A07D190F845200B2A03D1B5 -:104EF0000023C0E90E3315E003F06003202B08D136 -:104F0000B0F848302BB990F84520212A03D81F2A41 -:104F100004D8FFF7E1B9222AEBD0FAE7034A82630B -:104F20000722C26303640120704700BF24230020CE -:104F300007B5052917D8DFE801F01916031919205C -:104F4000302383F31188104A01900121FFF784FA7E -:104F500001980E4A0221FFF77FFA0D48FFF7A6F9E4 -:104F6000002383F3118803B05DF804FB302383F33F -:104F700011880748FFF770F9F2E7302383F31188AF -:104F80000348FFF787F9EBE7F06A0008146B0008A5 -:104F9000A85E002038B50C4D0C4C0D492A4604F192 -:104FA0000800FFF767FF05F1CA0204F11000094984 -:104FB000FFF760FF05F5CA7204F118000649BDE865 -:104FC0003840FFF757BF00BF706300202C2300203C -:104FD000D06A0008DA6A0008E56A000870B504467D -:104FE00008460D46FCF7DEFDC6B2204601340378C4 -:104FF0000BB9184670BD32462946FCF7BFFD0028A4 -:10500000F3D10120F6E700002DE9F84F05460C46E4 -:10501000FCF7C8FD2B49C6B22846FFF7DFFF08B1F1 -:105020000536F6B228492846FFF7D8FF08B11036F2 -:10503000F6B2632E0DD8DFF88C80DFF88C90234F0A -:10504000DFF890A0DFF890B02E7846B92670BDE862 -:10505000F88F29462046BDE8F84F01F091BC252E77 -:105060002BD1072241462846FCF788FD58B9DBF8CA -:1050700000302360DBF804306360DBF80830A360A5 -:1050800007350C34E0E7082249462846FCF776FD50 -:1050900098B90F4BA21C197809090232C95D02F8B0 -:1050A000041C13F8011B01F00F015345C95D02F800 -:1050B000031CF0D118340835C6E704F8016B01353C -:1050C000C2E700BFBC6B0008E56A0008D16B0008AE -:1050D000107AFF1F1C7AFF1FC46B0008BFF34F8FAD -:1050E000024AD368DB03FCD4704700BF003C024097 -:1050F00008B5094B1B7873B9FFF7F0FF074B1A6926 -:10510000002ABFBF064A5A6002F188325A601A6804 -:1051100022F480621A6008BDCE650020003C024087 -:105120002301674508B50B4B1B7893B9FFF7D6FFF2 -:10513000094B1A6942F000421A611A6842F480521F -:105140001A601A6822F480521A601A6842F4806267 -:105150001A6008BDCE650020003C02400728F0B56B -:1051600016D80C4C0C4923787BB90C4D0E460823FD -:105170004FF0006255F8047B46F8042B013B13F016 -:10518000FF033A44F6D10123237051F82000F0BD0B -:105190000020FCE7F0650020D0650020E46B0008EB -:1051A000014B53F820007047E46B0008082070475B -:1051B000072810B5044601D9002010BDFFF7CEFF27 -:1051C000064B53F824301844C21A0BB90120F4E7F7 -:1051D00012680132F0D1043BF6E700BFE46B00082F -:1051E000072810B5044621D8FFF778FFFFF780FFA6 -:1051F0000F4AF323D360C300DBB243F4007343F0E0 -:1052000002031361136943F480331361FFF766FFF0 -:10521000FFF7A4FF074B53F8241000F047F9FFF7FE -:1052200081FF2046BDE81040FFF7C2BF002010BD3F -:10523000003C0240E46B0008F8B512F0010314468C -:1052400042D185182E4A954257D82E4B1B6813F031 -:10525000010352D02C4DFFF74BFFF323EB60FFF718 -:105260003DFF40F20127032C15D824F001046618F5 -:10527000254C401A40F20117B142236900EB0105A9 -:1052800024D123F001032361FFF74CFF0120F8BD77 -:10529000043C0430E7E78307E7D12B6923F440732C -:1052A0002B612B693B432B6151F8046B0660BFF304 -:1052B0004F8FFFF713FF03689E42E9D02B6923F05D -:1052C00001032B61FFF72EFF0020E0E723F440737A -:1052D000236123693B4323610B882B80BFF34F8FEE -:1052E000FFF7FCFE2D8831F8023BADB2AB42C3D0D4 -:1052F000236923F001032361E4E71846C7E700BFF1 -:105300000000080800380240003C0240084908B587 -:105310000B7828B11BB9FFF7EBFE01230B7008BD1A -:10532000002BFCD0BDE808400870FFF7FBBE00BFB3 -:10533000CE65002008B54FF400314FF0005000F06A -:10534000B7F8BDE808404FF480314FF0805000F0CE -:10535000AFB800000846114601F076BA012001F00E -:1053600073BA0000084601F08DBA000070B582B033 -:10537000FFF79AFB0E4E054600F05CFF3268904244 -:1053800037BF0C4A0B49516814682EBFD1E9004160 -:10539000013151600419034641F100012846019191 -:1053A0003360FFF78BFB0199204602B070BD00BF50 -:1053B000F4650020F865002070B582B0FFF774FB3B -:1053C000104E054600F036FF3268904237BF0E4A55 -:1053D0000D49516814682EBFD1E900410131516077 -:1053E000041941F100010346284601913360FFF79B -:1053F00065FB01994FF47A7200232046FAF7F8FE14 -:1054000002B070BDF4650020F865002010B50244BC -:10541000064BD2B2904200D110BD441C00B253F8EA -:10542000200041F8040BE0B2F4E700BF5028004030 -:105430000F4B30B51C6F240407D41C6F44F4007468 -:105440001C671C6F44F400441C670A4C236843F437 -:10545000807323600244084BD2B2904200D130BD29 -:10546000441C00B251F8045B43F82050E0B2F4E76A -:1054700000380240007000405028004007B501226B -:1054800001A90020FFF7C2FF019803B05DF804FBFB -:1054900013B50446FFF7F2FFA04205D0012201A98F -:1054A00000200194FFF7C4FF02B010BD7047000058 -:1054B0007047000070470000074B45F255521A60D4 -:1054C00002225A6040F6FF729A604CF6CC421A6093 -:1054D000024B01221A707047003000400466002021 -:1054E000034B1B781BB1034B4AF6AA221A60704784 -:1054F0000466002000300040034B1A681AB9034AC2 -:10550000D2F874281A60704700660020003002400C -:10551000024B4FF08072C3F874287047003002408D -:1055200008B5FFF7E9FF024B1868C0F3407008BDEB -:105530000066002008B5FFF7DFFF024B1868C0F3D4 -:10554000007008BD0066002070470000FEE7000004 -:105550000A4B0B480B4A90420BD30B4BDA1C121A26 -:10556000C11E22F003028B4238BF00220021FCF74B -:1055700021BB53F8041B40F8041BECE7F86D00084E -:1055800008670020086700200867002070B5D0E990 -:1055900015439E6800224FF0FF3504EB4213510182 -:1055A000D3F800090028BEBFD3F8000940F08040BE -:1055B000C3F80009D3F8000B0028BEBFD3F8000BD6 -:1055C00040F08040C3F8000B013263189642C3F8E4 -:1055D0000859C3F8085BE0D24FF00113C4F81C3837 -:1055E00070BD0000890141F02001016103699B0643 -:1055F000FCD41220FFF772BA10B5054C2046FEF716 -:105600000BFF4FF0A0436365024BA36510BD00BFC5 -:1056100008660020286C000870B50378012B054649 -:1056200050D12A4B446D98421BD1294B5A6B42F002 -:1056300080025A635A6D42F080025A655A6D5A6967 -:1056400042F080025A615A6922F080025A610E21AA -:1056500043205B69FEF72AFD1E4BE3601E4BC4F836 -:1056600000380023C4F8003EC02323606E6D4FF461 -:105670000413A3633369002BFCDA012333610C208C -:10568000FFF72CFA3369DB07FCD41220FFF726FA68 -:105690003369002BFCDA0026A6602846FFF776FF68 -:1056A0006B68C4F81068DB68C4F81468C4F81C6838 -:1056B0004BB90A4BA3614FF0FF336361A36843F01A -:1056C0000103A36070BD064BF4E700BF086600202D -:1056D000003802404014004003002002003C30C06B -:1056E000083C30C0F8B5446D054600212046FFF760 -:1056F00079FFA96D00234FF001128F68C4F8343888 -:105700004FF00066C4F81C284FF0FF3004EB431242 -:1057100001339F42C2F80069C2F8006BC2F8080961 -:10572000C2F8080BF2D20B686A6DEB656362102356 -:105730001361166916F01006FBD11220FFF7CEF99F -:10574000D4F8003823F4FE63C4F80038A36943F4A6 -:10575000402343F01003A3610923C4F81038C4F8B0 -:1057600014380A4BEB604FF0C043C4F8103B084BB1 -:10577000C4F8003BC4F81069C4F80039EB6D03F1BC -:10578000100243F48013EA65A362F8BD046C0008BC -:1057900040800010426D90F84E10D2F8003823F48B -:1057A000FE6343EA0113C2F8003870472DE9F8435D -:1057B00000EB8103456DDA68166806F00306731E78 -:1057C000022B05EB41130C4680460FFA81F94FEA94 -:1057D00041104FF00001C3F8101B4FF0010104F11C -:1057E000100398BFB60401FA03F391698EBF334EDC -:1057F00006F1805606F5004600293AD0578A04F192 -:105800005801490137436F50D5F81C180B43C5F8B0 -:105810001C382B180021C3F8101953690127611E89 -:10582000A7409BB3138A928B9B08012A88BF5343DE -:10583000D8F85C20981842EA034301F1400205EBD6 -:105840008202C8F85C00214653602846FFF7CAFE72 -:1058500008EB8900C3681B8A43EA84534834640117 -:105860001E432E51D5F81C381F43C5F81C78BDE8DF -:10587000F88305EB4917D7F8001B21F40041C7F85E -:10588000001BD5F81C1821EA0303C0E704F13F030D -:1058900005EB83030A4A5A6028462146FFF7A2FE19 -:1058A00005EB4910D0F8003923F40043C0F8003963 -:1058B000D5F81C3823EA0707D7E700BF008000109F -:1058C00000040002826D1268C265FFF75FBE00002F -:1058D0005831436D49015B5813F4004004D013F470 -:1058E000001F0CBF02200120704700004831436DAB -:1058F00049015B5813F4004004D013F4001F0CBF9F -:10590000022001207047000000EB8101CB68196A7A -:105910000B6813604B6853607047000000EB810315 -:1059200030B5DD68AA691368D36019B9402B84BF0C -:10593000402313606B8A1468426D1C44013CB4FB25 -:10594000F3F46343033323F0030302EB411043EA10 -:10595000C44343F0C043C0F8103B2B6803F003037B -:10596000012B09B20ED1D2F8083802EB411013F422 -:10597000807FD0F8003B14BF43F0805343F00053C6 -:10598000C0F8003B02EB4112D2F8003B43F0044365 -:10599000C2F8003B30BD00002DE9F041244D6E6D92 -:1059A00006EB40130446D3F8087BC3F8087B38079E -:1059B0000AD5D6F81438190706D505EB8403214615 -:1059C000DB6828465B689847FA071FD5D6F8143875 -:1059D000DB071BD505EB8403D968CCB98B69488AF2 -:1059E0005A68B2FBF0F600FB16228AB91868DA682A -:1059F00090420DD2121AC3E90024302383F3118898 -:105A00000B482146FFF78AFF84F31188BDE8F08137 -:105A1000012303FA04F26B8923EA02036B81CB684A -:105A2000002BF3D021460248BDE8F041184700BFE3 -:105A30000866002000EB810370B5DD68436D6C697A -:105A40002668E6604A0156BB1A444FF40020C2F8AB -:105A500010092A6802F00302012A0AB20ED1D3F813 -:105A6000080803EB421410F4807FD4F8000914BF37 -:105A700040F0805040F00050C4F8000903EB42129F -:105A8000D2F8000940F00440C2F80009D3F8340805 -:105A9000012202FA01F10143C3F8341870BD19B9AB -:105AA000402E84BF4020206020682E8A8419013C4B -:105AB000B4FBF6F440EAC44040F000501A44C6E794 -:105AC0002DE9F8433B4D6E6D06EB40130446D3F8C9 -:105AD0000889C3F8088918F0010F4FEA40171AD057 -:105AE000D6F81038DB0716D505EB8003D9684B696B -:105AF0001868DA68904230D2121A4FF000091A6022 -:105B0000C3F80490302383F3118821462846FFF719 -:105B100091FF89F3118818F0800F1CD0D6F8343823 -:105B20000126A640334216D005EB84036D6DD3F8F1 -:105B30000CC0DCF814200134E4B2D2F800E005EB2C -:105B400004342F445168714515D3D5F8343823EA0D -:105B50000606C5F83468BDE8F883012303FA04F2A9 -:105B60002B8923EA02032B818B68002BD3D021469B -:105B700028469847CFE7BCF81000AEEB01038342FC -:105B800028BF0346D7F8180980B2B3EB800FE2D8DC -:105B90009068A0F1040959F8048FC4F80080A0EBC4 -:105BA00009089844B8F1040FF5D818440B449060E4 -:105BB0005360C7E7086600202DE9F74FA24C656DDA -:105BC0006E69AB691E4016F480586E6107D020469E -:105BD000FEF78AFC03B0BDE8F04FFEF73DBA002E99 -:105BE00012DAD5F8003E98489B071EBFD5F8003E54 -:105BF00023F00303C5F8003ED5F8043823F0010371 -:105C0000C5F80438FEF79AFC370505D58E48FFF72E -:105C1000BDFC8D48FEF780FCB0040CD5D5F80838E3 -:105C200013F0060FEB6823F470530CBF43F41053CA -:105C300043F4A053EB6031071BD56368DB681BB9E5 -:105C4000AB6923F00803AB612378052B0CD1D5F8A1 -:105C5000003E7D489A071EBFD5F8003E23F003039F -:105C6000C5F8003EFEF76AFC6368DB680BB1764856 -:105C70009847F30274D4B70227D5D4F85490DFF8CC -:105C8000C8B100274FF0010A09EB4712D2F8003BD8 -:105C900003F44023B3F5802F11D1D2F8003B002B41 -:105CA0000DDA62890AFA07F322EA0303638104EB3F -:105CB0008703DB68DB6813B1394658469847A36D04 -:105CC00001379B68FFB29F42DED9F00617D5676D9A -:105CD0003A6AC2F30A1002F00F0302F4F012B2F5AE -:105CE000802F00F08580B2F5402F08D104EB8303AC -:105CF0000022DB681B6A07F5805790426AD13003A7 -:105D0000D5F8184813D5E10302D50020FFF744FE6B -:105D1000A20302D50120FFF73FFE630302D5022054 -:105D2000FFF73AFE270302D50320FFF735FE750380 -:105D30007FF550AFE00702D50020FFF7C1FEA107B5 -:105D400002D50120FFF7BCFE620702D50220FFF753 -:105D5000B7FE23077FF53EAF0320FFF7B1FE39E71B -:105D6000636DDFF8E4A0019300274FF00109A36DF4 -:105D70009B685FFA87FB9B453FF67DAF019B03EB7A -:105D80004B13D3F8001901F44021B1F5802F1FD136 -:105D9000D3F8001900291BDAD3F8001941F090411B -:105DA000C3F80019D3F800190029FBDB5946606DD0 -:105DB000FFF718FC218909FA0BF321EA0303238179 -:105DC00004EB8B03DB689B6813B159465046984738 -:105DD0000137CCE7910708BFD7F80080072A98BFA2 -:105DE00003F8018B02F1010298BF4FEA182884E7FB -:105DF000023304EB830207F580575268D2F818C0CB -:105E0000DCF80820DCE9001CA1EB0C0C0021884226 -:105E10000AD104EB830463689B699A6802449A6020 -:105E20005A6802445A606AE711F0030F08BFD7F8B6 -:105E300000808C4588BF02F8018B01F1010188BF09 -:105E40004FEA1828E3E700BF08660020436D03EB24 -:105E50004111D1F8003B43F40013C1F8003B7047F7 -:105E6000436D03EB4111D1F8003943F40013C1F83D -:105E700000397047436D03EB4111D1F8003B23F427 -:105E80000013C1F8003B7047436D03EB4111D1F89B -:105E9000003923F40013C1F80039704730B5039C72 -:105EA0000172043304FB0325C0E90653049B03631A -:105EB0000021059BC160C0E90000C0E90422C0E9DF -:105EC0000842C0E90A11436330BD0000416A002264 -:105ED000C0E90411C0E90A22C2606FF00101FEF7B7 -:105EE0006DBE0000D0E90432934201D1C2680AB904 -:105EF000181D70470020704703691960C26801329D -:105F0000C260C269134482690361934224BF436A39 -:105F100003610021FEF746BE38B504460D46E3682E -:105F20003BB16269131D1268A3621344E36200204F -:105F300007E0237A33B929462046FEF723FE0028DE -:105F4000EDDA38BD6FF00100FBE70000C368C269FD -:105F5000013BC3604369134482694361934224BF98 -:105F6000436A436100238362036B03B118477047A0 -:105F700070B53023044683F31188866A3EB9FFF773 -:105F8000CBFF054618B186F31188284670BDA36A79 -:105F9000E26A13F8015BA362934202D32046FFF743 -:105FA000D5FF002383F31188EFE700002DE9F84FB8 -:105FB00004460E46174698464FF0300989F311887B -:105FC0000025AA46D4F828B0BBF1000F09D14146FC -:105FD0002046FFF7A1FF20B18BF311882846BDE8CA -:105FE000F88FD4E90A12A7EB050B521A934528BF84 -:105FF0009346BBF1400F1BD9334601F1400251F8E3 -:10600000040B43F8040B9142F9D1A36A40334036A4 -:10601000A3624035D4E90A239A4202D32046FFF70F -:1060200095FF8AF31188BD42D8D289F31188C9E758 -:1060300030465A46FBF798FDA36A5B445E44A36270 -:106040005D44E7E710B5029C0172043303FB0421B1 -:10605000C0E906130023C0E90A33039B0363049BD2 -:10606000C460C0E90000C0E90422C0E908424363FB -:1060700010BD0000026AC260426AC0E90422002228 -:10608000C0E90A226FF00101FEF798BDD0E90423B0 -:106090009A4201D1C26822B9184650F8043B0B60FD -:1060A000704700231846FAE7C368C2690133C3602A -:1060B0004369134482694361934224BF436A436145 -:1060C0000021FEF76FBD000038B504460D46E368B9 -:1060D0003BB123691A1DA262E2691344E362002006 -:1060E00007E0237A33B929462046FEF74BFD002806 -:1060F000EDDA38BD6FF00100FBE7000003691960BD -:10610000C268013AC260C269134482690361934262 -:1061100024BF436A036100238362036B03B1184702 -:106120007047000070B530230D460446114683F3D6 -:106130001188866A2EB9FFF7C7FF10B186F3118860 -:1061400070BDA36A1D70A36AE26A01339342A36221 -:1061500004D3E16920460439FFF7D0FF002080F323 -:106160001188EDE72DE9F84F04460D469046994613 -:106170004FF0300A8AF311880026B346A76A4FB958 -:1061800049462046FFF7A0FF20B187F3118830462B -:10619000BDE8F88FD4E90A073A1AA8EB0607974238 -:1061A00028BF1746402F1BD905F1400355F8042B93 -:1061B00040F8042B9D42F9D1A36A4033A3624036D4 -:1061C000D4E90A239A4204D3E16920460439FFF74F -:1061D00095FF8BF311884645D9D28AF31188CDE714 -:1061E00029463A46FBF7C0FCA36A3B443D44A36200 -:1061F0003E44E5E7D0E904239A4217D1C3689BB136 -:10620000836A8BB1043B9B1A0ED01360C368013BB9 -:10621000C360C3691A44836902619A4224BF436A16 -:106220000361002383620123184670470023FBE7C4 -:1062300000F0D2B84FF08043586A70474FF0804367 -:10624000002258631A610222DA6070474FF08043DF -:106250000022DA60704700004FF0804358637047B7 -:10626000FEE7000070B51B4B01630025044686B0B5 -:10627000586085620E46FDF7CBFE04F11003C4E9B9 -:1062800004334FF0FF33C4E90635C4E90044A56088 -:10629000E562FFF7CFFF2B460246C4E9082304F16D -:1062A00034010D4A256580232046FEF721FC012399 -:1062B000E0600A4A0375009272680192B268CDE903 -:1062C0000223074B6846CDE90435FEF739FC06B0DA -:1062D00070BD00BFA05E0020346C0008396C00085F -:1062E00061620008024AD36A1843D062704700BF57 -:1062F000385C00204B6843608B688360CB68C36068 -:106300000B6943614B6903628B6943620B680360ED -:106310007047000008B5264B26481A6940F2FF1165 -:106320000A431A611A6922F4FF7222F001021A610B -:106330001A691A6B0A431A631A6D0A431A651E4AD0 -:106340001B6D1146FFF7D6FF02F11C0100F58060BE -:10635000FFF7D0FF02F1380100F58060FFF7CAFFB8 -:1063600002F1540100F58060FFF7C4FF02F17001F3 -:1063700000F58060FFF7BEFF02F18C0100F5806040 -:10638000FFF7B8FF02F1A80100F58060FFF7B2FF48 -:1063900002F1C40100F58060FFF7ACFF02F1E001FB -:1063A00000F58060FFF7A6FFBDE8084000F090B858 -:1063B0000038024000000240406C000808B500F0C0 -:1063C000FBF9FEF749FBFFF797F8BDE80840FEF739 -:1063D000E1BD0000704700000F4B1A6C42F0010253 -:1063E0001A641A6E42F001021A660C4A1B6E936818 -:1063F00043F0010393604FF0804353229A624FF0C1 -:10640000FF32DA6200229A615A63DA605A6001222E -:106410005A611A60704700BF00380240002004E053 -:106420004FF0804208B51169D3680B40D9B2C94317 -:106430009B07116107D5302383F31188FEF732FBE8 -:10644000002383F3118808BD1F4B1A696FEAC252FB -:106450006FEAD2521A611A69C2F308021A614FF048 -:10646000FF301A695A69586100215A6959615A699D -:106470001A6A62F080521A621A6A02F080521A6234 -:106480001A6A5A6A58625A6A59625A6A1A6C42F00F -:1064900080521A641A6E42F080521A661A6E0B4AC3 -:1064A000106840F480701060186F00F44070B0F510 -:1064B000007F1EBF4FF4803018671967536823F4BC -:1064C0000073536000F054B900380240007000407F -:1064D000334B4FF080521A64324A4FF440411160FE -:1064E0001A6842F001021A601A689107FCD59A688E -:1064F00022F003029A602A4B9A6812F00C02FBD138 -:10650000196801F0F90119609A601A6842F4803242 -:106510001A601A689203FCD55A6F42F001025A675A -:106520001F4B5A6F9007FCD51F4A5A601A6842F0F9 -:1065300080721A601B4A53685904FCD5184B1A68BC -:106540009201FCD5194A9A60194B1A68194B9A4264 -:10655000194B21D1194A1168194A91421CD140F2B4 -:1065600005121A60144A136803F00F03052BFAD1C1 -:106570000B4B9A6842F002029A609A6802F00C0291 -:10658000082AFAD15A6C42F480425A645A6E42F494 -:1065900080425A665B6E704740F20572E1E700BFC9 -:1065A00000380240007000400854400700948838CA -:1065B000002004E011640020003C024000ED00E0F7 -:1065C00041C20F41074A08B5536903F00103536103 -:1065D00023B1054A13680BB150689847BDE80840DD -:1065E000FDF73ABD003C014080660020074A08B52F -:1065F000536903F00203536123B1054A93680BB159 -:10660000D0689847BDE80840FDF726BD003C014032 -:1066100080660020074A08B5536903F004035361FC -:1066200023B1054A13690BB150699847BDE808408A -:10663000FDF712BD003C014080660020074A08B506 -:10664000536903F00803536123B1054A93690BB101 -:10665000D0699847BDE80840FDF7FEBC003C01400A -:1066600080660020074A08B5536903F010035361A0 -:1066700023B1054A136A0BB1506A9847BDE8084038 -:10668000FDF7EABC003C014080660020164B10B5C7 -:106690005C6904F478725A61A30604D5134A936ABC -:1066A0000BB1D06A9847600604D5104A136B0BB142 -:1066B000506B9847210604D50C4A936B0BB1D06BF5 -:1066C0009847E20504D5094A136C0BB1506C984702 -:1066D000A30504D5054A936C0BB1D06C9847BDE86F -:1066E0001040FDF7B9BC00BF003C014080660020AF -:1066F000194B10B55C6904F47C425A61620504D5FB -:10670000164A136D0BB1506D9847230504D5134AF3 -:10671000936D0BB1D06D9847E00404D50F4A136E0A -:106720000BB1506E9847A10404D50C4A936E0BB17F -:10673000D06E9847620404D5084A136F0BB1506FAE -:106740009847230404D5054A936F0BB1D06F98473F -:10675000BDE81040FDF780BC003C01408066002091 -:1067600008B5FFF75DFEBDE80840FDF775BC000009 -:10677000062108B50846FDF799FC06210720FDF71C -:1067800095FC06210820FDF791FC06210920FDF764 -:106790008DFC06210A20FDF789FC06211720FDF754 -:1067A00085FC06212820FDF781FCBDE80840072173 -:1067B0001C20FDF77BBC000008B5FFF745FE00F08C -:1067C0000BF8FDF727FEFDF7FFFCFFF703FEBDE822 -:1067D0000840FFF72DBD00000023054A194601338C -:1067E000102BC2E9001102F10802F8D1704700BF76 -:1067F000806600200B460146184600F02DB80000C8 -:1068000000F040B8012838BF012010B504462046EA -:1068100000F030F830B900F007F808B900F00CF8D3 -:106820008047F4E710BD0000024B1868BFF35B8F90 -:10683000704700BF0067002008B5062000F084F80C -:106840000120FEF7F5FA0000024B0A4601461868DF -:10685000FEF780BD4C23002010B5054C13462CB12B -:106860000A4601460220AFF3008010BD2046FCE737 -:1068700000000000024B01461868FEF76FBD00BF24 -:106880004C230020024B01461868FEF76BBD00BF89 -:106890004C23002010B501390244904201D1002060 -:1068A00005E0037811F8014FA34201D0181B10BD79 -:1068B0000130F2E72DE9F041A3B1C91A177801447C -:1068C000044603F1FF3C8C42204601D9002009E038 -:1068D0000578BD4204F10104F5D10CEB0405D6188E -:1068E000A54201D1BDE8F08115F8018D16F801ED42 -:1068F000F045F5D0E7E700001F2938B504460D46FE -:1069000004D9162303604FF0FF3038BD426C12B13A -:1069100052F821304BB9204600F030F82A460146A3 -:106920002046BDE8384000F017B8012B0AD0591CAA -:1069300003D1162303600120E7E7002442F8254035 -:10694000284698470020E0E7024B01461868FFF709 -:10695000D3BF00BF4C23002038B5074D00230446A9 -:10696000084611462B60FEF767FA431C02D12B68DC -:1069700003B1236038BD00BF04670020FEF756BA9C -:10698000034611F8012B03F8012B002AF9D17047B7 -:1069900073772D737061722D663430372D626C0001 -:1069A00053544D3332463F3F3F0053544D333246EC -:1069B0003430780053544D333246343278005354D7 -:1069C0004D3332463434365858000000012033002D -:1069D0000010410001105A00031059000710310047 -:1069E00000000000A069000813040000AA69000864 -:1069F00019040000B469000821040000BE69000801 -:106A000040A2E4F1646891060041A3E5F265699251 -:106A1000070000004261642043414E49666163659E -:106A200020696E6465782E00000100000001FF00FF -:106A3000006400400068004080000000008000000A -:106A40000000800000000000000000008924000811 -:106A5000152D0008212C000899240008CD240008D9 -:106A6000C92600089D240008AD240008A1240008C0 -:106A7000A9240008A5240008F1250008B124000875 -:106A800015300008C1240008C525000800000000DA -:106A900045410008314100086D4100085941000896 -:106AA00065410008514100083D41000829410008A6 -:106AB0007941000800000000010000000000000013 -:106AC00063300000C06A0008905C0020A05E0020D7 -:106AD0004172647550696C6F740025424F41524495 -:106AE000252D424C002553455249414C25000000BC -:106AF000020000000000000061430008CD430008D0 -:106B0000400040004063002050630020020000006D -:106B10000000000003000000000000001144000815 -:106B20000000000010000000606300200000000072 -:106B300001000000000000000866002001010200C2 -:106B4000314F0008414E0008DD4E0008C14E0008DC -:106B500043000000586B000809024300020100C016 -:106B600032090400000102020100052400100105A1 -:106B70002401000104240202052406000107058205 -:106B8000030800FF09040100020A000000070501D4 -:106B900002400000070581024000000012000000D2 -:106BA000A46B0008120110010200004009124157B5 -:106BB00000020102030100000403090425424F41C1 -:106BC0005244250073772D737061722D663430370F -:106BD0000030313233343536373839414243444559 -:106BE000460000000040000000400000004000009F -:106BF0000040000000000100000002000000020050 -:106C00000000020000000000554500080D48000883 -:106C1000B94800084000400068660020686600200F -:106C200001000000786600208000000040010000A4 -:106C3000030000006D61696E0069646C650000000E -:106C40000000802A00000000AAAAAAAA00000024CE -:106C5000FFFF00000000000000A00A000068000024 -:106C600000000000AA6AAAAA000000007FFF00003E -:106C7000000090090000000000000100000000007A -:106C8000AAAAAAAA00000000FFFE0000000000005F -:106C9000000000001A000000000000009AAAAAAA42 -:106CA00000000000FFFF000099000000000000004D -:106CB0000000000000000000AAAAAAAA000000002C -:106CC000FFFF0000000000000000000000000000C6 -:106CD00000000000AAAAAAAA00000000FFFF00000E -:106CE00000000000000000000000000000000000A4 -:106CF000AAAAAAAA00000000FFFF000000000000EE -:106D00000000000000000000000000000A00000079 -:106D10000000000003000000000000000000000070 -:106D20000000000000000000000000000000000063 -:106D3000000000000000000000000000E494FF7F5D -:106D400001000000000000007017000000000000BB -:106D5000000007000000000040420F00FE2A010072 -:106D6000D2040000FF00960000000008009600001A -:106D70000000080004000000B86B000800000000DC -:106D80000000000000000000000000000000000003 -:106D90000000000050230020000000000000000060 -:106DA00000000000000000000000000000000000E3 -:106DB00000000000000000000000000000000000D3 -:106DC00000000000000000000000000000000000C3 -:106DD00000000000000000000000000000000000B3 -:106DE00000000000000000000000000000000000A3 -:086DF00000000000000000009B +:1000000000070020F1010008152D0008CD2C000884 +:10001000F52C0008CD2C0008ED2C0008F301000899 +:10002000F3010008F3010008F3010008093D00088E +:10003000F3010008F3010008F3010008F3010008D0 +:10004000F3010008F3010008F3010008F3010008C0 +:10005000F3010008F3010008A1620008C96200086A +:10006000F16200081963000841630008F301000809 +:10007000F3010008F3010008F3010008F301000890 +:10008000F3010008F3010008F30100085D2C0008EB +:100090006D2C0008812C0008F3010008696300083A +:1000A000F3010008F3010008F3010008F301000860 +:1000B0003D640008F3010008F3010008F3010008A3 +:1000C000F3010008F3010008F3010008F301000840 +:1000D000F3010008F3010008F3010008F301000830 +:1000E000CD630008F3010008F3010008F3010008E4 +:1000F000F3010008F3010008F3010008F301000810 +:10010000F3010008F3010008F3010008F3010008FF +:10011000F3010008F3010008F3010008F3010008EF +:10012000F3010008F3010008F3010008F3010008DF +:10013000F3010008F3010008F3010008952C000802 +:10014000A52C0008B92C0008F301000895580008F8 +:10015000F3010008F3010008F3010008F3010008AF +:10016000F3010008F3010008F3010008F30100089F +:10017000F3010008F3010008F3010008F30100088F +:10018000F3010008F3010008F3010008F30100087F +:10019000F3010008F3010008F3010008F30100086F +:1001A000F3010008F3010008F3010008F30100085F +:1001B000F3010008F3010008F3010008F30100084F +:1001C000F3010008F3010008F3010008F30100083F +:1001D000F3010008F3010008F3010008F30100082F +:1001E000C915000800000000000000000000000029 +:1001F00002E000F000F8FEE772B6374880F30888A6 +:10020000364880F3098836483649086040F20000D5 +:10021000CCF200004EF63471CEF200010860BFF35C +:100220004F8FBFF36F8F40F20000C0F2F0004EF628 +:100230008851CEF200010860BFF34F8FBFF36F8F7C +:100240004FF00000E1EE100A4EF63C71CEF20001D4 +:100250000860062080F31488BFF36F8F04F0E2FF7C +:1002600005F0C6FE4FF055301F491B4A91423CBF76 +:1002700041F8040BFAE71D49184A91423CBF41F886 +:10028000040BFAE71A491B4A1B4B9A423EBF51F82E +:10029000040B42F8040BF8E700201849184A914271 +:1002A0003CBF41F8040BFAE704F0C0FF05F0F4FE90 +:1002B000144C154DAC4203DA54F8041B8847F9E797 +:1002C00000F042F8114C124DAC4203DA54F8041B12 +:1002D0008847F9E704F0A8BF0007002000230020AA +:1002E0000000000808ED00E00001002000070020E9 +:1002F000186A000800230020B0230020B02300204B +:100300000C670020E0010008E4010008E401000897 +:10031000E40100082DE9F04F2DED108AC1F80CD052 +:10032000C3689D46BDEC108ABDE8F08F002383F3BF +:1003300011882846A047002004F078FAFEE704F070 +:10034000F7F900DFFEE70000F8B501F0A7F904F0C7 +:1003500003FF074604F052FF0546A8BB1F4B9F4210 +:1003600032D001339F4232D01D4B27F0FF029A4218 +:1003700030D1F8B200F034FF2E4642F2107400F093 +:1003800035FF08B10024264601F034FD20B10320DA +:1003900000F07AF80024264635B1124B9F4203D074 +:1003A00004F024FF00242646002004F0DFFE0EB1F6 +:1003B00000F080F801F0CEFA00F084FF204600F053 +:1003C000DFF800F077F8F9E72E460024D7E7044677 +:1003D0000126D4E7064641F28834D0E7010007B091 +:1003E000000008B0263A09B008B501F029F9A0F1DB +:1003F00020035842584108BD07B541F212030221BB +:1004000001A8ADF8043001F039F903B05DF804FB40 +:1004100038B5302383F31188174803680BB104F013 +:10042000D1FA164A144800234FF47A7104F0C0FA46 +:10043000002383F31188124C236813B12368013B16 +:100440002360636813B16368013B63600D4D2B78D3 +:1004500033B963687BB9022001F0E6F932236360A7 +:100460002B78032B07D163682BB9022001F0DCF94C +:100470004FF47A73636038BDB02300201104000884 +:10048000D0240020C8230020084B187003280CD863 +:10049000DFE800F008050208022001F0BBB90220E5 +:1004A00001F0AEB9024B00225A607047C823002009 +:1004B000D024002010B501F09DFC30B1294B03225F +:1004C0001A70294B00225A6010BD284B284A1C463E +:1004D00019680131F8D004339342F9D16268254B91 +:1004E0009A42F1D9244B9B6803F1006303F58033F2 +:1004F0009A42E9D204F04EFE04F060FE002001F0C2 +:10050000E7F80220FFF7C0FF1C4B1A6C00221A64A8 +:10051000196E1A66196E596C5A64596E5A665A6E7B +:100520005A6942F080025A615A6922F080025A6187 +:100530005A691A6942F000521A611A6922F000528F +:100540001A611B6972B64FF0E0233021C3F8084DE1 +:10055000D4E9003281F311889D4683F3088810475F +:10056000B2E700BFC8230020D0240020000001080B +:1005700020000108FFFF000800230020003802408F +:100580002DE9F04F93B0AC4B00902022FF210AA838 +:100590009D6801F089F9A94A1378A3B9A8480121F7 +:1005A00003601170302383F3118803680BB104F0EA +:1005B00009FAA44AA24800234FF47A7104F0F8F92A +:1005C000002383F31188009B13B19F4B009A1A609C +:1005D0009E4A009C1378032B1EBF002313709A4A77 +:1005E0004FF0000A18BF5360D3465646D14601204B +:1005F00001F010F924B1944B1B68002B00F0158218 +:10060000002001F01DF80390039B002B01DA00F09D +:10061000ABFE039B002BEDDB012001F0F1F8039B07 +:10062000213B162BE3D801A252F823F089060008DB +:10063000B106000845070008EF050008EF050008AF +:10064000EF050008CF0700089F090008B908000857 +:100650001B0900084309000869090008EF050008A4 +:100660007B090008EF050008ED09000829070008CC +:10067000EF050008310A0008950600082907000860 +:10068000EF0500081B0900080220FFF7ADFE002857 +:1006900040F0F581009B0221BAF1000F08BF1C4613 +:1006A00005A841F21233ADF8143000F0E7FF9EE7E1 +:1006B0004FF47A7000F0C4FF071EEBDB0220FFF757 +:1006C00093FE0028E6D0013F052F00F2DA81DFE833 +:1006D00007F0030A0D10133605230593042105A81E +:1006E00000F0CCFF17E054480421F9E758480421F2 +:1006F000F6E758480421F3E74FF01C08404600F0A5 +:10070000E9FF08F104080590042105A800F0B6FFF0 +:10071000B8F12C0FF2D1012000FA07F747EA0B0BD2 +:100720005FFA8BFB4FF0000901F00AF926B10BF0DC +:100730000B030B2B08BF0024FFF75EFE57E746486C +:100740000421CDE7002EA5D00BF00B030B2BA1D17C +:100750000220FFF749FE074600289BD0012000F049 +:10076000B7FF0220FFF790FE00261FFA86F84046EA +:1007700000F0BEFF044690B10021404600F0D0FFDB +:1007800001360028F1D1BA46044641F21213022183 +:1007900005A8ADF814303E4600F070FF27E70120B1 +:1007A000FFF772FE2546244B9B68AB4207D92846CB +:1007B00000F090FF013040F067810435F3E7234BF0 +:1007C00000251D70204BBA465D603E46ACE7002E0A +:1007D0003FF460AF0BF00B030B2B7FF45BAF0220F9 +:1007E000FFF752FE322000F02BFFB0F10008FFF6B9 +:1007F00051AF18F003077FF44DAF0F4A926808EB32 +:10080000050393423FF646AFB8F5807F3FF742AF0E +:10081000124B0193B84523DD4FF47A7000F010FFBE +:100820000390039A002AFFF635AF019B039A03F861 +:10083000012B0137EDE700BF00230020CC2400206E +:10084000B023002011040008D0240020C823002079 +:1008500004230020082300200C230020CC230020A8 +:10086000C820FFF7C1FD074600283FF413AF1F2D36 +:1008700011D8C5F1200242450AAB25F0030028BF7C +:10088000424683490192184400F0E8FF019A8048EB +:10089000FF2101F009F84FEAA8037D490193C8F34D +:1008A0008702284601F008F8064600283FF46DAF9D +:1008B000019B05EB830537E70220FFF795FD002834 +:1008C0003FF4E8AE00F04CFF00283FF4E3AE002711 +:1008D000B846704B9B68BB4218D91F2F11D80A9B92 +:1008E00001330ED027F0030312AA134453F8203C1F +:1008F00005934046042205A901F034FA04378046E6 +:10090000E7E7384600F0E6FE0590F2E7CDF8148000 +:10091000042105A800F0B2FE06E70023642104A824 +:10092000049300F0A1FE00287FF4B4AE0220FFF78C +:100930005BFD00283FF4AEAE049800F0F9FE059090 +:10094000E6E70023642104A8049300F08DFE00284C +:100950007FF4A0AE0220FFF747FD00283FF49AAED7 +:10096000049800F0F5FEEAE70220FFF73DFD0028BD +:100970003FF490AE00F004FFE1E70220FFF734FD02 +:1009800000283FF487AE05A9142000F0FFFE0421E3 +:100990000746049004A800F071FE3946B9E73220FA +:1009A00000F04EFE071EFFF675AEBB077FF472AE79 +:1009B000384A926807EB090393423FF66BAE022078 +:1009C000FFF712FD00283FF465AE27F003074F4400 +:1009D000B9453FF4A9AE484600F07CFE04210590DD +:1009E00005A800F04BFE09F10409F1E74FF47A7015 +:1009F000FFF7FAFC00283FF44DAE00F0B1FE0028EE +:100A000044D00A9B01330BD008220AA9002000F031 +:100A100053FF00283AD02022FF210AA800F044FF0B +:100A2000FFF7EAFC1C4803F007FF13B0BDE8F08FA6 +:100A3000002E3FF42FAE0BF00B030B2B7FF42AAEEE +:100A40000023642105A8059300F00EFE0746002848 +:100A50007FF420AE0220FFF7C7FC804600283FF459 +:100A600019AEFFF7C9FC41F2883003F0E5FE0598A6 +:100A700000F098FF464600F063FF3C46B7E50646A7 +:100A800052E64FF0000905E6BA467EE637467CE6B8 +:100A9000CC23002000230020A0860100094A13680F +:100AA00049F2690099B21B0C00FB01331360064B3D +:100AB000186844F2506182B2000C01FB0200186019 +:100AC00080B27047182300201423002010B50021A5 +:100AD0001022044600F0E8FE034B03CB2060616067 +:100AE0001868A06010BD00BF107AFF1F2DE9F0410B +:100AF000ADF54C7D0DF12C086AAC40F2751207463D +:100B00000D460CA80021C8F8001000F0CDFE4FF4EF +:100B1000C4720021204600F0C7FE02F003F9274B03 +:100B20004FF47A72B0FBF2F0186093E807000223EA +:100B300084E807000DF5E5702382FFF7C7FF47F251 +:100B400017031F49238407A805F088FD0F2384F8A5 +:100B500032310DF2DB2207AB0DF1240C1E4603CE21 +:100B6000664510605160334602F10802F6D13068E4 +:100B70001060B188B379937191802046414601227B +:100B800000F012FF00230393AB7E029305F11903DB +:100B9000019380B20123CDE904800093E97E05A38F +:100BA000D3E90023384602F085FC0DF54C7DBDE805 +:100BB000F08100BF9E6AC421818A46EED8240020BD +:100BC0006C6600082DE9F0412C4C237ADAB080469F +:100BD0000D465BBB27A9284600F0F6FF0746002814 +:100BE00042D19DF89D60C82E3ED801464FF4A662C2 +:100BF000204600F059FE4FF48073C4F8F8314FF4EA +:100C00000073C4F80C334FF44073C4F820343246F8 +:100C10000DF19E0104F1090000F020FE26449DF82C +:100C20009C30777223720BB9EB7E237281220021F4 +:100C300006AC27A800F038FE0122214627A800F0C4 +:100C4000FFFF00230393AB7E029305F1190380B2EB +:100C500001932823CDE904400093E97E05A3D3E95D +:100C60000023404602F026FC5AB0BDE8F08100BFE8 +:100C7000AFF3008026417272DF25D7B7D05600202F +:100C8000F0B5254E4FF48A7505FB0065F1B096F876 +:100C9000D83085F8DC300024D822214685F8E84099 +:100CA0003AA800F001FE06F1090000F0F5FDD5F8C4 +:100CB000E4308DF8F000C2B206AF06F109010DF183 +:100CC000F100CDE93A3400F0C9FD394601223AA8D5 +:100CD00000F0E2FF80B2CDE9047008230127CDE9DE +:100CE000023706F1D803019330230093317A0B4881 +:100CF00007A3D3E9002302F0DDFBA04206DD02F0EA +:100D000011F8C5F8E000384671B0F0BD2046FBE7A9 +:100D100078F6339F93CACD8DD0560020F034002052 +:100D20002DE9F04F274FDFF8A880274E87B03846CF +:100D300002F0ECFB034600283DD00024CDE903443B +:100D4000ADF81440027B8DF8142099684068029435 +:100D500003AA03C21B681D4D43F000430293A14642 +:100D6000A2462B68D3F810B001F0DEFF10EB0802AA +:100D700041F100032846CDF800A002A9D84704F2AB +:100D8000364440F66C030028C8BF49F0010905F558 +:100D900086559C4205F11805E3D1B9F1000F05D045 +:100DA000384602F0B7FB86F800A0C0E73378072B7F +:100DB00004D80133337007B0BDE8F08F014802F06A +:100DC000A9FBF8E7F0340020055C00202035002066 +:100DD00040420F0070B50D4614461E4602F0C6FA9A +:100DE00050B9022E10D1012C0ED112A3D3E9002349 +:100DF000C5E90023012007E0282C10D005D8012CDC +:100E000009D0052C0FD0002070BD302CFBD10BA3D6 +:100E1000D3E90023ECE70BA3D3E90023E8E70BA316 +:100E2000D3E90023E4E70BA3D3E90023E0E700BF05 +:100E3000AFF30080401DA12026812A0B78F6339F56 +:100E400093CACD8D9E6AC421818A46EE2641727274 +:100E5000DF25D7B7F017304A39059E5638B5054615 +:100E60000E4C0021013500F05BFCA4F82C55B4F8C1 +:100E70002C0500F03DFC78B1B4F82C0500F048FCDE +:100E8000014648B9B4F82C0500F04AFCB4F82C35FA +:100E90000133A4F82C35EAE738BD00BFD056002056 +:100EA000F8B50E4C0E4F0226A4F5805343F8487C4B +:100EB000237E3BB965692DB1284601F019F8284613 +:100EC00005F00CFB204601F013F8A4F58654012E22 +:100ED000A4F1180400D1F8BD0126E5E74056002032 +:100EE000286700082DE9F04F8FB000AF05460C468B +:100EF00002F03CFA002849D1237E022B1BD1E38A61 +:100F0000012B18D101F00EFF0646FFF7C7FD03467F +:100F10004FF4C870DFF8C482B3FBF0F206F5167622 +:100F200002FB103316FA83F3C8F80030E37E33B9BE +:100F3000A34B00221A703C37BD46BDE8F08F07F185 +:100F40002401204600F0FEFD0028F4D107F1140032 +:100F5000FFF7BCFD97F8264007F11401224607F180 +:100F6000270005F005FB0028E2D10F2C08D8944B90 +:100F70001C70D8F80030A3F51673C8F80030DAE713 +:100F800097F82410284602F0E9F9D4E7E38A282BE1 +:100F90002BD010D8012B23D0052BCCD1BFF34F8FF2 +:100FA0008849894BCA6802F4E0621343CB60BFF3FF +:100FB0004F8F00BFFDE7302BBDD1844EE17E327AEA +:100FC0009142B8D1607E3146002291F8DC508542D2 +:100FD00000F0A5800132042A01F58A71F5D1AAE753 +:100FE00021462846FFF782FDA5E721462846FFF760 +:100FF000E9FDA0E7B2F8EC507B6005F103094FEA88 +:1010000099094FEA8902D11DC908A8EBC1039D4681 +:10101000EB460021584600F047FC04F1EE012A4659 +:101020003144584600F01AFC7B6813B9012000F0E7 +:101030004FFB96F8D20000F05BFB044630B93072EB +:1010400000F08EFB204600F043FBB1E0D6F8D42040 +:101050003AB996F8D200B6F82C25824201D8FFF7AB +:10106000FDFED6F8D4202A44944208D296F8D20045 +:10107000B6F82C250130824201D8FFF7EFFE7068E8 +:101080005FFA89F2594600F017FC08B9C54679E0C5 +:10109000726896F8D2002A447260D6F8D42005EB24 +:1010A0000209C6F8D49000F023FB814509D396F8D5 +:1010B000D220D6F8D4000132001B86F8D220C6F820 +:1010C000D400FF2D0FD80024347200F049FB2046D5 +:1010D00000F0FEFA00F08EFE3D4B188108B9FFF7D4 +:1010E000E9F9C54627E7BB6896F8D9000AFB036211 +:1010F000FB68D2F8E41082F8E83001F58061C2F8AC +:10110000E030C2F8E410FFF7BBFDFFF709FE96F8E8 +:10111000D920013202F0030286F8D920B6E74FF455 +:101120008A7A0AFB02F505F1EA013144204600F013 +:10113000DFFDF86000287FF4FEAE3544012285F81B +:10114000E82001F0EFFDD5F8E020D6ED007ADFEDE4 +:10115000216A801A192838BF192040F6B832904207 +:1011600028BF1046B8EE677A07EE900AF8EEE77AE5 +:1011700067EEA67ADFED186AE7EE267AFCEEE77AEC +:10118000C6ED007A96F8D930BB60BA6873680AFB7E +:1011900002F4321992F8E81059B1D2F8E4108B42F7 +:1011A000E8463FF427AF002182F8E810C2F8E010CB +:1011B000C5467368064A9B0A01331381BBE600BF2C +:1011C000E934002000ED00E00400FA05D0560020CC +:1011D000D8240020CDCCCC3D6666663FEC340020A0 +:1011E000014B1870704700BFE424002030B54FF069 +:1011F00000542B4B22689A4285B007D004F008F8BF +:10120000044620BB0024204605B030BD254B627D3E +:1012100025481A70237D03724FF48073C0F8F831AB +:101220004FF40073C0F80C3300254FF44073C0F83E +:1012300020341E49C0F8E450C922093000F00EFBEA +:101240002046E022294600F02FFB0124DBE7184A64 +:10125000184D136C43F000731364AA6D164B9A4239 +:10126000D0D12B6E013B7E2BCCD8144A07CA01ABE0 +:1012700083E807001846032100F08AFD6B6D834266 +:101280004FF00003BED12A6D8A4201BFAB65054B0A +:101290002A6E1A7003BF0A4BEA6D1A601C46B2E749 +:1012A0009AAD44C5E4240020D0560020160000204A +:1012B00000380240006600405041A0B0586600402F +:1012C0001023002037B500F095FD1D4D1D4C2881E1 +:1012D000022321681C486B71012201F0A5FB1B4809 +:1012E000216850F8D83F01225B689847002301939A +:1012F000174B184900931848184B4FF4805202F0CE +:1013000005F8174B197811B1134802F027F801F0CE +:1013100009FD0446FFF7C2FB4FF4C873B0FBF3F2BC +:1013200002FB130304F5167010FA83F00D4B1860DE +:1013300003F064FF08B10F232B8103B030BD00BF61 +:10134000D824002010230020203500202045002034 +:10135000D50D0008E8240020F0340020E50E000838 +:10136000E4240020EC3400202DE9F04F2DED028B19 +:10137000DFF8508293B00BAF9FED838BFFF7D0FC6B +:1013800000230A93ADF834300B937B600025844C26 +:10139000DFF810A22E4601238DF81C3023688DED56 +:1013A000008B4FF0000BD3F808908DF81DB05B4612 +:1013B0000DF11D0207A92046C8479DF81C90B9F100 +:1013C000000F24D0D8F8143083F48073C8F8143098 +:1013D000102259460EA800F067FA236808AA5E6931 +:1013E0000AA90DF11E032046B04797E803000FAB92 +:1013F00083E803009DF834308DF844300A9B0E9347 +:101400000EA9DDE90823504602F062FA4E4605F2C5 +:10141000364540F66C0304F586549D4204F11804E9 +:10142000B9D1002EB2D15F4801F0A0FF002840D111 +:101430005D4D01F077FC2B6898423AD301F072FCC5 +:101440000446FFF72BFB4FF4C873B0FBF3F202FB2B +:10145000130304F5167010FA83F02860534D8DF8CD +:1014600028602E7816B901238DF82830C6F11004B3 +:10147000E4B20EA8FFF72AFB062C28BF06240EAB09 +:10148000224699190DF1290000F0E8F90AAB0393FF +:10149000182302930134464B0193E4B201230093D5 +:1014A000404804943AA3D3E9002301F0A5FF0023A8 +:1014B0002B7001F037FC3F4A3F4C1368C31AB3F559 +:1014C0007A7F2FD3106001F02FFC02460B4635487F +:1014D00002F02AF8334801F049FF18B3237A374D58 +:1014E000002B14BF032302236B7101F01BFC0EAE13 +:1014F0004FF47A730122B0FBF3F03146286028469E +:1015000000F0F8FA182302932D4B019380B240F2B9 +:101510005513CDE90360009322481FA3D3E90023AC +:1015200001F06AFF237A93B101F0FCFB0025064627 +:101530004FF48A7794F8D900284400F0030007FBA1 +:10154000004393F8E82072B10135042DF2D1C82090 +:1015500003F072F9237A002B7FF40DAF13B0BDECCA +:10156000028BBDE8F08FD3F8E02042B12368FA2B5C +:1015700038BFFA23B21A0533B2EB430FE4D3FFF7B7 +:101580007FFB0028E0D1E2E700000000000000003F +:10159000401DA12026812A0BF1C6A7C1D068080FE3 +:1015A00020350020F0340020EC340020E934002005 +:1015B000E8340020005C0020D0560020D824002011 +:1015C000045C00200008024008B5064800F08EFFC9 +:1015D000054800F08BFFBDE80840044A044900209C +:1015E00004F076BF20350020F8450020445C002040 +:1015F000A10E000870B50F4B1B780133DBB2012B35 +:101600000C4611D80C4D29684FF47A730E6AA2FB70 +:101610000332014622462846B047844204D1074B94 +:1016200000221A70012070BD4FF4FA7003F004F923 +:101630000020F8E71C230020B85E0020345C002066 +:1016400007B50023024601210DF107008DF8073090 +:10165000FFF7D0FF20B19DF8070003B05DF804FB51 +:101660004FF0FF30F9E700000A4608B50421FFF704 +:10167000C1FF80F00100C0B2404208BD30B4054C4B +:101680002368DD69044B0A46AC460146204630BC5F +:10169000604700BFB85E0020A086010070B503F06F +:1016A000FBFB094E094D30800024286833888342B3 +:1016B00008D903F0EBFB2B6804440133B4F5803FF9 +:1016C0002B60F2D370BD00BF365C0020085C0020A8 +:1016D00003F092BC00F1006000F5803000687047B4 +:1016E00000F10060920000F5803003F01BBC0000A8 +:1016F000054B1A68054B1B889B1A834202D910447C +:1017000003F0C4BB00207047085C0020365C00205A +:10171000024B1B68184403F0C1BB00BF085C0020EB +:10172000024B1B68184403F0D1BB00BF085C0020CB +:1017300010F003030AD1B0F5047F05D200F1005088 +:10174000A0F51040D0F80038184670470023FBE79A +:1017500000F10050A0F51040D0F8100A70470000CA +:10176000064991F8243033B10023086A81F8243007 +:101770000822FFF7B5BF0120704700BF0C5C0020B6 +:10178000014B1868704700BF002004E070B5194B8A +:101790001D68194B0138C5F30B0408442D0C0422B5 +:1017A0001E88A6420BD15C680A46013C8242134661 +:1017B0000FD214F9016F4EB102F8016BF6E7013A4E +:1017C00003F10803ECD181420B4602D22C2203F82C +:1017D000012B0A4A05241688AE4204D1984284BFE0 +:1017E000967803F8016B013C02F10402F3D1581A18 +:1017F00070BD00BF002004E0BC660008A8660008B9 +:10180000022802BF024B4FF480729A61704700BFFA +:1018100000080240022802BF024B4FF080729A611A +:10182000704700BF00080240022801BF024A536906 +:1018300083F48073536170470008024070B504461A +:101840004FF47A764CB1412C254628BF412506FB42 +:1018500005F002F0F1FF641BF4E770BD10B5002342 +:10186000934203D0CC5CC4540133F9E710BD0000AF +:1018700010B5013810F9013F3BB191F900409C428D +:1018800003D11AB10131013AF4E71AB191F90020FC +:10189000981A10BD1046FCE703460246D01A12F90A +:1018A000011B0029FAD1704702440346934202D03B +:1018B00003F8011BFAE770472DE9F8431F4D144662 +:1018C00095F824200746884652BBDFF870909CB3F9 +:1018D00095F824302BB92022FF2148462F62FFF7CC +:1018E000E3FF95F82400C0F10802A24228BF224677 +:1018F000D6B24146920005EB8000FFF7AFFF95F8A6 +:101900002430A41B1E44F6B2082E17449044E4B2BF +:1019100085F82460DBD1FFF723FF0028D7D108E04A +:101920002B6A03EB82038342CFD0FFF719FF002815 +:10193000CBD10020BDE8F8830120FBE70C5C002040 +:10194000024B1A78024B1A70704700BF345C0020BB +:101950001C23002010B5104C104802F0C3FA214699 +:101960000E4802F0EBFA2468626DD2F8043843F0B6 +:101970000203C2F804384FF47A70FFF75FFF08499A +:10198000204602F0E1FB626DD2F8043823F0020336 +:10199000C2F8043810BD00BF14680008B85E00200B +:1019A0001C680008704700002DE9F0470D4604460A +:1019B00000219046284640F27912FFF775FF234632 +:1019C00020220021284601F025FF231D022220218C +:1019D000284601F01FFF631D03222221284601F043 +:1019E00019FFA31D03222521284601F013FF04F14E +:1019F000080310222821284601F00CFF04F11003EF +:101A000008223821284601F005FF04F111030822BD +:101A10004021284601F0FEFE04F11203082248216D +:101A2000284601F0F7FE04F1140320225021284635 +:101A300001F0F0FE04F1180340227021284601F065 +:101A4000E9FE04F120030822B021284601F0E2FE5D +:101A500004F121030822B821284601F0DBFE04F13D +:101A60002207C0263B46314608222846083601F0A8 +:101A7000D1FEB6F5A07F07F10107F3D104F13203DF +:101A800008223146284601F0C5FE002704F1330A3A +:101A900094F832304FEAC7099F4209F5A47615D36E +:101AA000B8F1000F08D1314604F599730722284692 +:101AB00001F0B0FE09F24F16274694F832213B1B85 +:101AC00093420CD3F01DC008BDE8F0870AEB070372 +:101AD00008223146284601F09DFE0137D8E707F27B +:101AE000331331460822284601F094FE08360137A8 +:101AF000E3E7000013B504460846002101602346D1 +:101B0000C0F803102022019001F084FE0198231DEB +:101B10000222202101F07EFE0198631D0322222172 +:101B200001F078FE0198A31D0322252101F072FE29 +:101B3000019804F108031022282101F06BFE072010 +:101B400002B010BDF7B50023047F00910E460722B6 +:101B50001946054601F022FD731C00930122002363 +:101B60000721284601F01AFDC4B9B31C00930522D1 +:101B700023460821284601F011FD0D243746B2788E +:101B8000BB1B934211D32B7FA88A0734E408BBB94F +:101B9000844294BF0020012003B0F0BDAB8ADB007B +:101BA000083BDB08B3700824E8E7FB1C00932146E0 +:101BB00000230822284601F0F1FC08340137DEE753 +:101BC000201A18BF0120E7E7F7B50023047F009132 +:101BD0000E4608221946054601F0E0FC731CC4B904 +:101BE0000822009311462346284601F0D7FC102412 +:101BF000012372785F1C013B934211D32B7FA88A8B +:101C00000734E408BBB9844294BF0020012003B02C +:101C1000F0BDAB8ADB00083BDB0873700824E7E704 +:101C2000F3190093214600230822284601F0B6FC50 +:101C300008343B46DDE7201A18BF0120E7E7000023 +:101C4000F8B50E4605461446002181223046FFF7BE +:101C50002BFE2B4608220021304601F0DBFD7CB92B +:101C60006B1C07220821304601F0D4FD0F2401230C +:101C70006A785F1C013B934204D3E01DC008F8BDA5 +:101C80000824F4E7EB1921460822304601F0C2FD92 +:101C900008343B46ECE70000F8B50E46054614460E +:101CA0000021CE223046FFF7FFFD2B4628220021DF +:101CB000304601F0AFFD7CB905F108030822282168 +:101CC000304601F0A7FD30242F462A7A7B1B934231 +:101CD00004D3E01DC008F8BD2824F5E707F1090387 +:101CE00021460822304601F095FD08340137ECE723 +:101CF000F7B5047F00910E4601231022002105460E +:101D000001F04CFCC4B9B31C0093092223461021F6 +:101D1000284601F043FC192437467288BB1B9A42BF +:101D200011D82B7FA88A0734E408BBB9844294BF3A +:101D30000020012003B0F0BDAB8ADB00103BDB08C4 +:101D400073801024E8E73B1D0093214600230822FE +:101D5000284601F023FC08340137DEE7201A18BFBB +:101D60000120E7E730B5094D0A4491420DD011F842 +:101D7000013B5840082340F30004013B2C4013F082 +:101D8000FF0384EA5000F6D1EFE730BD2083B8EDC1 +:101D9000F7B54FF0FF33DFF854C0DFF854E000EB45 +:101DA00081011A4688421CD050F8044B019401AFBF +:101DB000042417F8015B82EA05620825DB18164641 +:101DC00005F1FF355241002EBCBF83EA0C0382EAC5 +:101DD0000E0215F0FF05F1D1013C14F0FF04E8D12B +:101DE000E0E7D843D14303B0F0BD00BF9336EAA982 +:101DF000EBE1F042F7B5384A106851686B4603C30F +:101E00006A4636493648082304F0C2FB04460028D7 +:101E100033D10A25334A106851686B4603C36A46BA +:101E200031492F48082304F0B3FB0446002849D069 +:101E30000369B3F5E02F45D8B0F8661041F270722F +:101E400091423FD1294A024402F15C018B4239D3CD +:101E50005C3B234900209E1AFFF784FF3246074669 +:101E600004F164010020FFF77DFFA3689F4229D1A0 +:101E7000E368984208BF002524E00369B3F5E02F2A +:101E800027D8418B41F27072914220D1174A024407 +:101E900002F110018B4218D3103B114900209D1A0A +:101EA000FFF760FF2A46064604F118010020FFF7FD +:101EB00059FFA3689E4202D1E368984201D00D25E4 +:101EC000A8E70025284603B0F0BD1025A2E70C25A1 +:101ED000A0E70B259EE700BFDC660008DCFF0600DC +:101EE00000000108E566000890FF06000800FFF703 +:101EF00010B5037C044613B9006804F031FB20469A +:101F000010BD00000023BFF35B8FC360BFF35B8F86 +:101F1000BFF35B8F8360BFF35B8F7047BFF35B8F53 +:101F20000068BFF35B8F704770B505460C30FFF754 +:101F3000F5FF05F1080604463046FFF7EFFFA04223 +:101F400006D930466D68FFF7E9FF2544281A70BDB1 +:101F50003046FFF7E3FF201AF9E7000070B50546A9 +:101F6000406898B105F10800FFF7D8FF05F10C06AD +:101F700004463046FFF7D2FF8442304694BF6D6876 +:101F80000025FFF7CBFF013C2C44201A70BD000058 +:101F900038B50C460546FFF7C7FFA04210D305F140 +:101FA0000800FFF7BBFF04446868B4FBF0F100FBD6 +:101FB0001144BFF35B8F0120AC60BFF35B8F38BD72 +:101FC0000020FCE72DE9F041144607460D46FFF7D7 +:101FD000C5FF844228BF0446D4B1B84658F80C6BFC +:101FE0004046FFF79BFF3044286040467E68FFF77D +:101FF00095FF331A9C4203D86C600120BDE8F08144 +:102000006B60A41B3B68AB602044E8600220F5E7EE +:102010002046F3E738B50C460546FFF79FFFA04280 +:1020200010D305F10C00FFF779FF04446868B4FB96 +:10203000F0F100FB1144BFF35B8F0120EC60BFF3B4 +:102040005B8F38BD0020FCE72DE9FF4188466946DB +:102050000746FFF7B7FF6C4606B204EBC60600253D +:10206000B44209D06268206808EB0501FFF7F6FB6F +:10207000636808341D44F3E729463846FFF7CAFF72 +:10208000284604B0BDE8F081F8B505460C300F468F +:10209000FFF744FF05F1080604463046FFF73EFF10 +:1020A000A042304688BF6C68FFF738FF201A3860BE +:1020B00020B130462C68FFF731FF2044F8BD000006 +:1020C00073B5144606460D46FFF72EFF844228BF1F +:1020D00004460190DCB101A93046FFF7D5FF019B12 +:1020E00033B93268C5E90233C5E9002401200CE0A8 +:1020F0009C4238BF01942860019868608442F5D9F9 +:102100003368AB60241AEC60022002B070BD204638 +:10211000FBE700002DE9FF410F466946FFF7D0FFBE +:102120006C4600B204EBC0050026AC4209D0D4F8DE +:10213000048054F8081BB8194246FFF78FFB464449 +:10214000F3E7304604B0BDE8F081000038B505463D +:10215000FFF7E0FF044601462846FFF719FF204637 +:1021600038BD000010B4026854681A4623465DF872 +:10217000044B18470020704700207047704700004C +:10218000002070470E20704700F5805090F8C8007E +:10219000C0F340007047000000F5805090F9D00077 +:1021A0007047000000F58050C0F8CC100120704747 +:1021B000F7B50C68BDF8207014F0005470D10D7B99 +:1021C000082D6DD8302585F311884569AE687601F4 +:1021D0000CD4AC68240108D4AC6814F080545DD1F0 +:1021E00084F31188204603B0F0BD01240E6804F189 +:1021F000180C002EB8BFF6004FEA0C1CB4BF46F016 +:102200000406760545F80C600E680FFA84FC16F09B +:10221000804F18BF05EB0C1E05EB0C1C1EBFDEF833 +:10222000806146F00206CEF880610E7BCCF88461B6 +:1022300005EB04158E68C5F88C614E68C5F8886199 +:10224000DCF8805145F00105CCF8805100EB4416D4 +:1022500041F268052E4405EB44150544C6E9002308 +:1022600008350E4601F10C0C56F804EB45F804EB6A +:102270006645F9D1843436882E8000EB441407F08B +:102280000305267926F00B0635432571002484F3D7 +:102290001188009700F068FD0120A4E70224A5E75B +:1022A0004FF0FF309FE7000013B500F58054019117 +:1022B000E06DFFF753FE1F280AD90199E06D202237 +:1022C000FFF7C2FEA0F120035842584102B010BDF2 +:1022D0000020FBE708B5302383F3118800F5805018 +:1022E000C06DFFF70FFE002383F3118808BD0000C7 +:1022F00000220260828142608260704710B5002235 +:102300000023C0E900230023044603810C30FFF7BB +:10231000EFFF204610BD0000F0B5054600F58050E7 +:102320000C4690F8C83013F0040FC3F3800108BFC7 +:10233000114661F3820304F1840680F8C83005EB8E +:10234000461389B01B79D8072ED57AB319072DD437 +:102350006846FFF7D3FF05EB441303F5835303F1FE +:10236000180703AA103318685968144603C40833C1 +:10237000BB422246F7D1186820609B88A380DDE924 +:102380000E23CDE900230123ADF808302B68694600 +:10239000DB6B2846984705EB46152B791A075CBF7F +:1023A00043F008032B7101E0002AF4D109B0F0BD1D +:1023B0002DE9F0479A4688B0074688469146302373 +:1023C00083F3118807F580546846FFF797FFE06DA7 +:1023D000FFF7AAFD1F282AD9E06D20226946FFF7E2 +:1023E000B5FE202823D103AD444605AB2E4603CECF +:1023F0009E4220606160354604F10804F6D13068E1 +:102400002060B388A380DDE90023C9E90023BDF87B +:102410000830AAF80030002383F3118853464A4657 +:102420004146384608B0BDE8F04700F08BBC0020BC +:1024300080F3118808B0BDE8F08700002DE9F84F5F +:102440000023C0E90133264B044640F8183B0F46F1 +:10245000FFF74EFF04F12800FFF750FF04F1480892 +:1024600004F582554646083530462036FFF746FFCC +:10247000AE42F9D104F580554FF480534FF0000976 +:10248000C5E91339C5F848800123EE6504F587587E +:1024900004F58456C5F8549085F8583085F86030B6 +:1024A000083608F108084FF0000A4FF0000B46E923 +:1024B00008ABA6F11800FFF71BFF203646F8289C52 +:1024C0004645F4D1012F85F8D07002D9054800F0B7 +:1024D00023FC054B53F8273063612046BDE8F88F95 +:1024E00028670008F06600080C67000810B5044B68 +:1024F000197804464A1C1A70FFF7A0FF204610BD49 +:10250000405C00202DE9F047002950D0294B2A4F8C +:10251000B7FBF1F599428CBF0A231123581EB5FB76 +:10252000F3FC03FB1C53C4B22BB102280346F5D8BD +:102530000020BDE8F0870CF1FF36B6F5806FF7D2CA +:10254000C4EBC40E0EF103034FEAE309C3F3C70360 +:10255000A4EB030809F1010A4FF47A755FFA88F0D9 +:1025600009FB05555AFA88F8B5FBF8F5B5F5617F12 +:10257000C1BF0EF1FF33C3F3C703E01AC0B25C1C46 +:1025800050FA84F40CFB04F4B7FBF4F4A142CFD16D +:10259000013BDBB20F2BCBD80138C0B20728C7D81C +:1025A0000021107116809170D3700120C1E7084698 +:1025B000BFE700BF3F420F0080DE800270B50546D6 +:1025C0000E464FF47A746B695B6803F00103B34203 +:1025D00007D04FF47A7002F02FF9013CF3D1204676 +:1025E00070BD0120FCE7000030B54269936913F02B +:1025F000700F16D000230B4C936103F1840200EBA3 +:10260000421211794D0709D5890707D5416954F858 +:1026100023508D60117941F0040111710133032BB6 +:10262000EBD130BD1467000873B51D4643691646EB +:102630009A68D207044609D59A6801219960C2F3C5 +:102640004002CDE900650021FFF766FE63699A68E4 +:10265000D1050BD59A684FF480719960C2F340227E +:10266000CDE9006501212046FFF756FE63699A68AF +:10267000D2030BD59A684FF480319960C2F340427F +:10268000CDE9006502212046FFF746FE04F58053A0 +:10269000D3F8CC0010B103681B699847204602B0FC +:1026A000BDE87040FFF7A0BF0C4B10B51C561B5C7B +:1026B000012B11D800F038FB50EA0103024602D08A +:1026C000421E61F10001064B53F8240020B1BDE821 +:1026D00010400B46FFF7A8BF10BD00BF08670008F9 +:1026E000385C0020F8B504464669002972D106F12D +:1026F0000C073868800770D006EB01153868D5F8EC +:10270000B00110F0040FD5F8B0011ABFC00840F0B6 +:102710000040400DA061D5F8B0C11CF0020F1CBFF5 +:1027200040F08040A061D5F8B40106EB011100F043 +:102730000F0084F82400D1F8B8012077D1F8B8014F +:10274000000A6077D1F8B801000CA077D1F8B80181 +:10275000000EE077D1F8BC0184F82000D1F8BC016C +:10276000000A84F82100D1F8BC01000C84F8220092 +:10277000D1F8BC11090E84F823103821396004F116 +:10278000340004F1180104F1240551F8046B40F8F9 +:10279000046BA942F9D109880180C4E90A232146C2 +:1027A0000023238651F8283B2046DB6B984704F52D +:1027B000805393F8C820D3F8CC0042F0040283F889 +:1027C000C82010B103681B6998472046BDE8F8404F +:1027D000FFF70ABF06F110078BE7F8BD0D4B70B588 +:1027E0001D561B5C012B0C4612D800F09DFA0246C8 +:1027F0000B4652EA030102D0013A63F10003064995 +:1028000051F8250020B12146BDE87040FFF76ABFAE +:1028100070BD00BF08670008385C0020F0B53021AB +:1028200081F31188DFF848C000F583510831002496 +:1028300004F1840500EB45152E7977070ED4F606D2 +:102840000CD5D1E9007697429E4107D246695CF8E3 +:102850002470B7602E7946F004062E710134032CE3 +:1028600001F12001E4D1002383F31188F0BD00BF02 +:102870001467000808B5302383F31188FFF7B4FE0E +:10288000002383F3118808BDF8B5436905469868AD +:1028900000F0E050B0F1E05F0F4621D0F8B13023F6 +:1028A00083F3118805F583541034002606F1840360 +:1028B00005EB43131B791A0706D50136032E04F1E5 +:1028C0002004F3D1012007E05B07F6D42146384607 +:1028D00000F084FA0028F0D1002383F31188F8BDBA +:1028E0000120FCE708B5302383F3118800F5805000 +:1028F000C06DFFF719FB002383F3118843090CBF58 +:102900000120002008BD0000F8B51D46002313700B +:102910000F4606461446FFF7E5FF80F001003870C9 +:1029200025B129463046FFF7AFFF2070F8BD000003 +:102930002DE9B8410C4615461F46804600F0F4F9D3 +:102940000B462178024609B9287850B14046FFF776 +:1029500065FFFFF78FFF3B462A462146FFF7D4FF6E +:102960000120BDE8B881000038B5302383F3118819 +:1029700000F580542A4D94F8D030EB5CE3B1012B84 +:1029800028D0002383F3118894F8C830DB0712D4D1 +:1029900089B1302383F3118894F8D030EB5C33B3E2 +:1029A000012B31D094F8C83043F0010384F8C830CB +:1029B000002383F3118838BD1A4B1A6C42F0007261 +:1029C0001A641A6A42F000721A621A6A22F00072DD +:1029D0001A62D6E7134B1A6C42F080621A641A6AC4 +:1029E00042F080621A621A6A22F08062F0E70321E4 +:1029F000132001F0E7F90321142001F0E3F903218A +:102A0000152001F0DFF9CDE703213F2001F0DAF9CD +:102A10000321402001F0D6F903214120F1E700BF56 +:102A200004670008003802402DE9F04700F58055A2 +:102A300088B095F8D030022B04468846164600F23E +:102A40008180854F57F823200AB947F82300D7F82B +:102A500000A0C4F80C802674BAF1000F64D095F879 +:102A6000D030012B70D001212046FFF77DFF3023AD +:102A700083F311886269136823F0020313606269AB +:102A8000136843F001031360636900275F6187F3F4 +:102A9000118801212046FFF791FD002800F0958064 +:102AA000E86DFFF72FFA04F58359BA4609F10809D2 +:102AB000202200216846FEF7F7FE02A8FFF718FC67 +:102AC000CDF818A06A4609EB07030DF1180E9446DD +:102AD000BCE80300F44518605960624603F108033E +:102AE000F5D1DCF80000186020379CF804201A713A +:102AF000602FDDD195F8C8306FF38203002785F889 +:102B0000C8306A4641462046ADF80070ADF8027004 +:102B10008DF80470FFF7F6FC636948BB4FF4004280 +:102B20001A6008B0BDE8F08741F2D80003F0D8FC85 +:102B3000814610B15146FFF781FCC7F80090B9F10A +:102B4000000F8CD10020ECE7386803681B6B9847B6 +:102B50000146002887D13868FFF706FF3868036808 +:102B600032465B684146984700287FF47CAFE9E72E +:102B700061221A609DF802309DF803201B061204A2 +:102B800002F4702203F040731343BDF80020C2F337 +:102B9000090213439DF804201205022E02F4E002FC +:102BA0000CBF4FF000410021134362690B43D36116 +:102BB000636913225A616269136823F00103136089 +:102BC00039462046FFF7FAFC08B96369A6E795F88D +:102BD000D030002B39D16169D1F8002242F00102D6 +:102BE000C1F800226169D1F8002222F47C5222F05F +:102BF0000E02C1F800226169D1F8002242F460623D +:102C0000C1F800226269C2F814326269C2F8043263 +:102C100062696FF07841C2F80C126269C2F8403202 +:102C20006269C2F844326269C2F8B0326269C2F8BD +:102C3000B432636944F20102C3F81C226269D2F81B +:102C4000003223F00103C2F8003295F8C83043F097 +:102C5000020385F8C83064E7385C002008B500201E +:102C6000FFF722FDBDE8084001F082B808B5002159 +:102C70000846FFF7B3FDBDE8084001F079B8000051 +:102C800008B501210020FFF7A9FDBDE8084001F0CB +:102C90006FB8000008B50120FFF706FDBDE8084049 +:102CA00001F066B808B500210120FFF797FDBDE8E7 +:102CB000084001F05DB8000008B501210846FFF7A3 +:102CC0008DFDBDE8084001F053B8000000B59BB091 +:102CD000EFF3098168226846FEF7C0FDEFF3058334 +:102CE000014B9B6BFEE700BF00ED00E008B5FFF76E +:102CF000EDFF000000B59BB0EFF309816822684644 +:102D0000FEF7ACFDEFF30583014B5B6BFEE700BF05 +:102D100000ED00E0FEE700000FB408B5029801F0F6 +:102D200031FDFEE702F0B6B902F098B913B56C4672 +:102D300084E80600031D94E8030083E805000120F1 +:102D400002B010BD73B58568019155B11B885B0752 +:102D500007D4D0E900369B6B9847019AC1B2304640 +:102D6000A847012002B070BDF0B5866889B005465D +:102D70000C465EB1BDF838305B070AD4D0E90037A5 +:102D80009B6B98472246C1B23846B047012009B034 +:102D9000F0BD00220023CDE900230023ADF8083068 +:102DA0000A4603AB01F10806106851681C4603C4CB +:102DB0000832B2422346F7D1106820609288A28080 +:102DC000FFF7B2FF0423ADF808302B68CDE900010E +:102DD000DB6B694628469847D8E7000030B50368A2 +:102DE0000968DD0FB5EBD17F23F0604421F060422C +:102DF0004FEAD1700BD0002BB8BFA40C0029B8BF8C +:102E0000920C944202D034BF0120002030BD944285 +:102E100005D1C1F38070C3F380738342F6D194422D +:102E20002CBF00200120F1E72DE9F041456A15B9DA +:102E30004162BDE8F0814B6823F06047C3F38A46E6 +:102E40004FEAD37EC3F3807816EA230638BF3E46A6 +:102E5000AC462B465A68BEEBD27F22F060440AD0C3 +:102E6000002A18DAA40CB44217D19D420FD10D608C +:102E7000DEE71346EEE7A74207D102F08044C2F333 +:102E8000807242450BD054B1EFE708D2EDE7CCF8A1 +:102E900000100B60CDE7B44201D0B442E5D81A6807 +:102EA0009C46002AE5D11960C3E700002DE9F047F0 +:102EB000089D01F007044FEAD508224405F00705F4 +:102EC00000EBD1004FF47F49944201D1BDE8F08777 +:102ED00004F0070705F0070A57453E4638BF564637 +:102EE000C6F10806111B8E4228BF0E46E10808EB0A +:102EF000D50E415C13F80EC0B94029FA06F721FA45 +:102F00000AF1FFB28CEA010147FA0AF739408CEA6C +:102F1000010C03F80EC034443544D5E780EA0120A3 +:102F2000082341F2210201B24000002980B203F1DE +:102F3000FF33B8BF504013F0FF03F4D170470000D7 +:102F400038B50C468D18A54200D138BD14F8011BC8 +:102F5000FFF7E4FFF7E7000042684AB113684360F7 +:102F60004389818901339BB29942438138BF838170 +:102F70001046704770B588B0202204460D4668465A +:102F80000021FEF791FC20460495FFF7E5FF02467D +:102F900058B16B46054608AE1C4603CCB4422860C7 +:102FA0006960234605F10805F6D1104608B070BDEA +:102FB000082817D909280CD00A280CD00B280CD0C7 +:102FC0000C280CD00D280CD00E2814BF4020302027 +:102FD00070470C207047102070471420704718204D +:102FE0007047202070470000082817D90C280CD9FA +:102FF00010280CD914280CD918280CD920280CD941 +:1030000030288CBF0F200E207047092070470A20FF +:1030100070470B2070470C2070470D207047000050 +:103020002DE9F843078C072F04461ED9D0E90298F2 +:1030300000254FF6FF73C5F12006A5F1200029FAFF +:1030400005F108FA06F628FA00F031430143C9B247 +:103050001846FFF763FF0835402D0346EBD1E169C1 +:103060003A46BDE8F843FFF76BBF4FF6FF70BDE887 +:10307000F883000010B54B6823B9CA8A63F30902CC +:10308000CA8210BD04691A681C600361C38A013BCF +:10309000C3824A60EFE700002DE9F84F1D46CB8A56 +:1030A0000F46C3F309010529814692460B4630D0ED +:1030B0000020AAB207F11A049EB2042E1FFA80F86B +:1030C0000FD8904503F1010306D3FB8A0A4462F34B +:1030D0000903FB8201201AE01AF80060E65401306F +:1030E000EAE79045F1D2A1F1050B1C237C68BBFBFC +:1030F000F3F203FB12BB1FFA8BF6002C45D14846B6 +:10310000FFF72AFF044638B978606FF00200BDE887 +:10311000F88F4FF00008E6E7002606607860ADB251 +:103120004FF0000B454510D90AEB0803221D13F898 +:10313000011B9155B1B208F101081B291FFA88F84B +:103140002BD0454506F10106F1D8FB8AC3F30902ED +:10315000154465F30903BCE7013292B21C462368AB +:10316000002BF9D16B1F0B441C21B3FBF1F301338E +:103170009BB29A42D3D2BBF1000FD0D14846FFF7A1 +:10318000EBFE20B9C4F800B0BFE70122E7E7C0F8C2 +:1031900000B05E4620600446C1E74545D5D94846A3 +:1031A000FFF7DAFE08B92060AFE7C0F800B00026EC +:1031B00020600446B6E700002DE9F04F2DED028BAC +:1031C0001C4683B05B69019207468846002B00F0DD +:1031D0009A80238C2BB1E269002A00F09480072B9F +:1031E00035D807F10C00FFF7B7FE054638B96FF088 +:1031F0000205284603B0BDEC028BBDE8F08F142217 +:103200000021FEF751FB228CE16905F10800FEF771 +:1032100025FB208C013080B2FFF7E6FEFFF7C8FEE9 +:10322000013880B22084013028746369228C1B78B5 +:103230002A4403F01F0363F03F0348F00041137278 +:10324000384669602946FFF7EFFD0125D1E700F117 +:103250000C034FF0000908EE103A4FF0800A4E467A +:103260004D4618EE100AFFF777FE83460028BED0C1 +:1032700014220021FEF718FB002E3AD1019BABF877 +:10328000083002220BF1080E1FFA82FC0CF101003B +:10329000BCF1060F218C80B201D88E422BD3FFF7F0 +:1032A000A3FEFFF785FE62691278013802F01F0263 +:1032B0008E4208BF4FF0400A42EA49121BFA80F1E1 +:1032C0004AEA020A013048F0004281F808A08BF86F +:1032D0001000CBF8042059463846FFF7A5FD238C93 +:1032E0000135B3422DB289F001094FF0000AB8D17F +:1032F0007FE70022C6E7E169895D0EF8021001361A +:10330000B6B20132C0E76FF0010572E7F8B51546B5 +:103310000E463022002104461F46FEF7C5FA069BE2 +:103320006360B5F5001F079BA76034BF6A094FF6BD +:10333000FF72A36297B2E66104F1100000239A4283 +:1033400006D800230360A782E3822383E360F8BDED +:103350000660013330462036F1E7000003781BB9E0 +:103360004BB2002BC8BF0170704700000078704757 +:10337000F8B50C46C969074611B9238C002B37D123 +:10338000257E1F2D34D8387828BB228C072A2CD8CC +:10339000268A36F003032BD14FF6FF70FFF7D0FDDE +:1033A00020F001003102400441EA0561400C41EA8D +:1033B00040254FF6FF72234629463846FFF7FCFEAC +:1033C000002807DD626913780133DBB21F2B88BF49 +:1033D00000231370F8BD218A2D0645EA0125054317 +:1033E0002046FFF71DFE0246E5E76FF00300F1E718 +:1033F0006FF00100EEE7000070B58AB00446164693 +:103400000021282268461D46FEF74EFABDF83830E6 +:10341000ADF810300F9B05939DF840308DF81830B3 +:10342000119B07936946BDF84830ADF8203020461F +:10343000CDE90265FFF79CFF0AB070BD2DE9F041B0 +:10344000D36905460C4616460BB9138C5BBB377E19 +:103450001F2F28D895F80080B8F1000F26D03046ED +:10346000FFF7DEFD3378210241EAC33141EA08016A +:10347000338A41EA076141EA03410246334641F09B +:1034800080012846FFF798FE00280ADD3378012BDB +:1034900007D1726913780133DBB21F2B88BF002379 +:1034A0001370BDE8F0816FF00100FAE76FF00300E0 +:1034B000F7E70000F0B58BB004460D461746002133 +:1034C000282268461E46FEF7EFF99DF84C305A1E3A +:1034D000534253418DF800309DF84030ADF8103024 +:1034E000119B05939DF848308DF81830149B079375 +:1034F0006A46BDF85430ADF8203029462046CDE963 +:103500000276FFF79BFF0BB0F0BD0000406A00B1F0 +:1035100004307047436A1A68426202691A600361A4 +:10352000C38A013BC38270472DE9F041D0F8208067 +:10353000194E14461D464146002709B9BDE8F081E1 +:10354000D1E90223A21A65EB0303964277EB03034A +:103550001ED2036A8B420DD1FFF78CFD036A1B68F4 +:10356000036203690B60C38A0161016A013BC38284 +:103570008846E2E7FFF77EFD0B68C8F80030036974 +:103580000B60C38A0161013BC382D8F80010D4E705 +:1035900088460968D1E700BF80841E002DE9F04FFE +:1035A0008BB00D46DDF8509014469B4680460028AF +:1035B00000F01981B9F1000F00F01581531E3F2B67 +:1035C00000F21181012A03D1BBF1000F40F00B8101 +:1035D0000023CDE90833B8F81430B5EBC30F4FEA38 +:1035E000C30703D300200BB0BDE8F08F2B199F4217 +:1035F000D8F80C303ABF7F1BFFB227461BB9D8F86A +:103600001030002B7AD0272D4ED8C5F12806B742AE +:103610004FF000032CBFF6B23E4600932946D8F87F +:10362000080008AB3246FFF741FCA7EB060A354419 +:103630005FFA8AFAB8F8143003F10053053BDB0057 +:103640000493D8F80C3003932821039B13B1BAF1EB +:10365000000F2CD1D8F8100040B1BAF1000F05D0FE +:10366000009608AB5246691AFFF720FC38B2002FCB +:10367000B8D066070AD00AAB03EBD401624211F856 +:10368000083C02F00702134101F8083C082C3CD921 +:10369000102C40F2B580202C40F2B780BBF1000F17 +:1036A00000F09C80082334E0BA460026C2E7049B61 +:1036B000E02B28BFE02306930B44AB42059314D9BB +:1036C0005A1B03980096924534BF5246D2B2691AEB +:1036D00008AB04300792FFF7E9FB079A1644AAEB00 +:1036E000020A1544F6B25FFA8AFA049B069A059913 +:1036F0009B1A0493039B1B680393A6E70093D8F8D7 +:10370000080008AB3A462946AEE7BBF1000F13D0DC +:103710000123B4EBC30F6CD0082C12D89DF82030D5 +:10372000621E23FA02F2D50706D54FF0FF3202FAE5 +:1037300004F423438DF820309DF8203089F80030C0 +:1037400051E7102C12D8BDF82030621E23FA02F285 +:10375000D10706D54FF0FF3202FA04F42343ADF847 +:103760002030BDF82030A9F800303CE7202C0FD8DD +:103770000899631E21FA03F3DA0705D54FF0FF32EB +:1037800002FA04F40C430894089BC9F800302AE7B5 +:10379000402C2BD0DDE90865611EC4F12102A4F1A3 +:1037A000210326FA01F105FA02F225FA03F3114387 +:1037B0001943CB0712D50122A4F12003C4F1200143 +:1037C00002FA03F322FA01F1A240524243EA010352 +:1037D00063EB430332432B43CDE90823DDE90823A0 +:1037E000C9E90023FFE66FF00100FCE66FF0080076 +:1037F000F9E6082CA0D9102CB3D9202CEED8C3E7B9 +:10380000BBF1000FADD0022383E7BBF1000FBBD0AB +:1038100004237EE730B5012A144638BF0124402C2A +:1038200085B028BF40240025012ACDE9025518D8CB +:103830001B788DF8083063070AD004AB03EBD4057E +:10384000624215F8083C02F00702934005F8083C74 +:10385000009103462246002102A8FFF727FB05B08E +:1038600030BD082AE4D9102A03D81B88ADF80830E7 +:10387000E1E7202A8DBFD3E900231B680293CDE93D +:103880000223D8E710B5CB681BB98B600B618B8224 +:1038900010BD04691A681C600361C38A013BC382BE +:1038A000CA60F0E703064CBFC0F3C0300220704787 +:1038B00008B50246FFF7F6FF022806D15306C2F309 +:1038C0000F2001D100F0030008BDC2F30740FBE761 +:1038D0002DE9F04F93B0CDE903230A680446104662 +:1038E000FFF7E0FF022814BFC2F306260026002AD5 +:1038F0000D46824680F2F28112F0C04940F0EE811E +:10390000097B002900F0EA81022803D02378B34222 +:1039100040F0E781C2F304630693104602F07F0390 +:103920000593FFF7C5FF059B29444FEA834848EA02 +:103930000A4848EA4668CE7800230022CDE90823E9 +:10394000F309834648EA0008029367D0059B009379 +:1039500002466768534608A92046B847002800F089 +:10396000C381276A4FB9414604F10C00FFF702FBFF +:10397000074690B96FF0020054E03B6998450DD0BE +:103980003F68002FF9D1414604F10C00FFF7F2FA2D +:1039900007460028EED0236A3B60276297F817C0DD +:1039A00006F01F08CCF3840CACEB08001FFA80FE75 +:1039B0000028B8BF0EF12000A8EB0C031FFA83FE0D +:1039C000D7E90221B8BF00B2002B0793BEBF0EF1AA +:1039D00020031BB2079352EA010338D0039BDFF8A0 +:1039E00024E39A1A049B4FF0000C63EB0101964507 +:1039F0007CEB01032BD36B7B97F81AE0734519D14D +:103A0000029B002B78D0012821DC7868F8B9DFF818 +:103A1000F0C2944570EB010316D337E0276A27B94B +:103A20006FF00C0013B0BDE8F08F3B699845B5D03E +:103A30003F68F4E7B24890427CEB010301D30020D9 +:103A4000F0E7029B002BFAD0079B0F2B17DCFA7DC7 +:103A5000B30002F0030203F07C031343FB75394605 +:103A60002046FFF707FB6B7BBB76029B3BB9FB7DD8 +:103A7000C3F38402013262F38603FB75D0E76A7BED +:103A8000BB7E9A42DBD1029B002B35D0B309022BBF +:103A900032D0039BBB60049BFB60142200210DA865 +:103AA000FDF702FF039B0A93049B0B932B1D0C93C2 +:103AB0002B7BADF83EB0013BDBB2ADF83C30069B52 +:103AC0008DF84230059B8DF8433094F82C308DF8FA +:103AD00040A083F001038DF844308DF84180A36845 +:103AE0000AA920469847FB7DC3F38403013303F002 +:103AF0001F039B02FB82A2E7FB7DC6F34012B2EBE1 +:103B0000D31F40F0F480C3F38403434540F0F280B8 +:103B1000029A2B7BB609002A4DD0F2075DD4032B05 +:103B200040F2EB80039BBB60049BFB602B7BAE1DD4 +:103B3000033BDBB23246394604F10C00FFF7ACFA26 +:103B400000280CDA39462046FFF794FAFB7DC3F3D0 +:103B50008403013303F01F039B02FB820AE7DDE9C4 +:103B60000884AB883B834FF6FF73C9F12000A9F1AD +:103B7000200228FA09F104FA00F0014324FA02F2C3 +:103B800011431846C9B2FFF7C9F909F10809B9F19B +:103B9000400F0346E9D1B8822A7B033AD2B23146BC +:103BA000FFF7CEF9FB7DB882DA43C2F3C01262F3AD +:103BB000C713FB7543E786B92E1D013BDBB23246C6 +:103BC000394604F10C00FFF767FA0028BADB2A7BBC +:103BD000B88A013AD2B23146E2E7F98AC1F3090163 +:103BE000013B0429DAB25BD8281D002307F11B062C +:103BF0009A4208D910F801CB06F801C0013101330F +:103C00000529DBB2F4D103990A9104990B919342EF +:103C100007F11B010C9138BF043379680D9134BF53 +:103C200055FA83F300230E93FB8AADF83EB0C3F33D +:103C300009031A44069B8DF84230059B8DF84330EA +:103C400094F82C30ADF83C2083F001038DF844301B +:103C500000238DF840A08DF841807B602A7BB88AD4 +:103C6000013A291DFFF76CF93B8BB882834203D1DF +:103C7000A3680AA92046984720460AA9FFF702FE32 +:103C8000FB7DBA8AC3F38403013303F01F039B0255 +:103C9000FB823B8B9A420CBF00206FF01000C1E604 +:103CA0007B68002BAFD0052001E01C3033461E6836 +:103CB000002EFAD1091A081D2E1D184401EB090C1B +:103CC000BCF11B0F5FFA89F39DD89A429BD916F875 +:103CD000013B00F8013B09F10109EFE76FF0090032 +:103CE000A0E66FF00A009DE66FF00B009AE66FF019 +:103CF0000D0097E66FF00E0094E66FF00F0091E66E +:103D000040420F0080841E00EFF3098305494A6B8F +:103D100022F001024A63683383F30988002383F3A6 +:103D20001188704700EF00E0302080F3118862B600 +:103D30000C4B0D4AD96821F4E0610904090C0A43CF +:103D4000DA60D3F8FC20094942F08072C3F8FC2005 +:103D50000A6842F001020A602022DA7783F8220022 +:103D6000704700BF00ED00E00003FA05001000E01E +:103D700010B5302383F311880E4B5B6813F4006396 +:103D800014D0F1EE103AEFF30984683C4FF08073E1 +:103D9000E361094BDB6B236684F3098800F0BCFC0C +:103DA00010B1064BA36110BD054BFBE783F31188EF +:103DB000F9E700BF00ED00E000EF00E03F0300087E +:103DC0004203000800F1604303F561430901C9B2F1 +:103DD00083F80013012200F01F039A4043099B005F +:103DE00003F1604303F56143C3F880211A60704713 +:103DF000026843681143016003B11847704700002F +:103E000013B5446BD4F894341A681178042915D189 +:103E1000217C022912D11979128901238B40134286 +:103E20000CD101A904F14C0001F09EFFD4F8944498 +:103E3000019B21790246206800F0D0F902B010BD44 +:103E4000143001F021BF00004FF0FF33143001F0B7 +:103E50001BBF00004C3001F0F3BF00004FF0FF33F8 +:103E60004C3001F0EDBF0000143001F0EFBE000057 +:103E70004FF0FF31143001F0E9BE00004C3001F08A +:103E8000BFBF00004FF0FF324C3001F0B9BF00005F +:103E90000020704710B5D0F894341A6811780429BE +:103EA000044617D1017C022914D159795289012382 +:103EB0008B4013420ED1143001F082FE024648B10D +:103EC000D4F894444FF4807361792068BDE81040C1 +:103ED00000F072B910BD0000406BFFF7DBBF0000BF +:103EE000704700007FB5124B036000234360C0E9B8 +:103EF0000233012502260F4B0574044602900193FC +:103F000000F18402294600964FF48073143001F0CA +:103F100033FE094B0294CDE9006304F523724FF49C +:103F20008073294604F14C0001F0FAFE04B070BD24 +:103F300068670008D93E0008013E00080B6830227F +:103F400082F311880A7903EB820290614A7909327F +:103F500043F822008A7912B103EB820398610223AD +:103F6000C0F894140374002080F311887047000097 +:103F700038B5037F044613B190F85430ABB9201D17 +:103F800001250221FFF734FF04F1140025776FF0BB +:103F9000010100F079FC84F8545004F14C006FF0FA +:103FA0000101BDE8384000F06FBC38BD10B50121FB +:103FB00004460430FFF71CFF0023237784F85430B5 +:103FC00010BD000038B504460025143001F0ECFDAA +:103FD00004F14C00257701F0BBFE201D84F85450FD +:103FE0000121FFF705FF2046BDE83840FFF752BF2B +:103FF00090F8443003F06003202B07D190F845205F +:10400000212A4FF0000303D81F2A06D8002070474A +:10401000222AFBD1C0E90E3303E0034A8263072260 +:10402000C2630364012070471D23002037B5D0F818 +:1040300094341A681178042904461AD1017C0229A3 +:1040400017D11979128901238B40134211D100F144 +:104050004C05284601F03CFF58B101A9284601F063 +:1040600083FED4F89444019B21790246206800F035 +:10407000B5F803B030BD0000F0B500EB810385B0AA +:104080009E6904460D46FEB1302383F3118804EB8C +:104090008507301D0821FFF7ABFEFB685B691B68D5 +:1040A00006F14C001BB1019001F06CFE019803A9D0 +:1040B00001F05AFE024648B1039B2946204600F013 +:1040C0008DF8002383F3118805B0F0BDFB685A69B1 +:1040D0001268002AF5D01B8A013B1340F1D104F18C +:1040E0004402EAE7093138B550F82140DCB1302309 +:1040F00083F31188D4F894241368527903EB820374 +:10410000DB689B695D6845B104216018FFF770FEAC +:10411000294604F1140001F05DFD2046FFF7BAFEC8 +:10412000002383F3118838BD7047000001F0D2B836 +:10413000012303700023C0E90133C361836203627A +:10414000C36243620363704738B50446302383F388 +:1041500011880025C0E90355C0E90555416001F00B +:10416000C9F80223237085F31188284638BD000062 +:1041700070B500EB810305465069DA600E461446BF +:1041800018B110220021FDF78FFBA06918B1102291 +:104190000021FDF789FB31462846BDE8704001F05B +:1041A00073B90000826802F0011282600022C0E947 +:1041B0000422826101F0F4B9F0B400EB8104478974 +:1041C000E4680125A4698D403D43458123600023B7 +:1041D000A2606360F0BC01F00FBA0000F0B400EB25 +:1041E00081040789E468012564698D403D430581A8 +:1041F00023600023A2606360F0BC01F089BA000074 +:1042000070B50223002504460370C0E90255C0E9D9 +:104210000455C564856180F8345001F0D1F86368B5 +:104220001B6823B129462046BDE87040184770BD81 +:104230000378052B10B504460AD080F850300523CA +:10424000037043681B680BB1042198470023A360E7 +:1042500010BD00000178052906D190F85020436870 +:1042600002701B6803B118477047000070B590F8E2 +:104270003430044613B1002380F8343004F1440292 +:10428000204601F0AFF963689B68B3B994F84430F5 +:1042900013F0600535D00021204601F04FFC0021CD +:1042A000204601F041FC63681B6813B106212046DB +:1042B0009847062384F8343070BD2046984700287C +:1042C000E4D0B4F84A30E26B9A4288BFE36394F9D1 +:1042D0004430E56B002B4FF0300380F20381002D5A +:1042E00000F0F280092284F8342083F31188002141 +:1042F000D4E90E232046FFF771FF002383F31188D2 +:10430000DAE794F8452003F07F0343EA022340F202 +:104310000232934200F0C58021D8B3F5807F48D0A7 +:104320000DD8012B3FD0022B00F09380002BB2D18F +:1043300004F14C02A2630222E2632364C1E7B3F5F5 +:10434000817F00F09B80B3F5407FA4D194F8463084 +:10435000012BA0D1B4F84C3043F0020332E0B3F5A6 +:10436000006F4DD017D8B3F5A06F31D0A3F5C0635F +:10437000012B90D8636894F846205E6894F8471043 +:10438000B4F848302046B047002884D04368A3637F +:104390000368E3631AE0B3F5106F36D040F60242CB +:1043A00093427FF478AF5C4BA3630223E363002363 +:1043B000C3E794F84630012B7FF46DAFB4F84C306E +:1043C00023F00203C4E90E55A4F84C30256478E7C5 +:1043D000B4F84430B3F5A06F0ED194F8463084F8A9 +:1043E0004E30204601F044F863681B6813B1012188 +:1043F00020469847032323700023C4E90E339CE72B +:1044000004F14F03A3630123C3E72378042B10D1E6 +:10441000302383F311882046FFF7C4FE85F311880B +:104420000321636884F84F5021701B680BB120464C +:10443000984794F84630002BDED084F84F300423A0 +:10444000237063681B68002BD6D002212046984752 +:10445000D2E794F848301D0603F00F0120460AD534 +:1044600001F0B2F8012804D002287FF414AF2B4BDE +:104470009AE72B4B98E701F099F8F3E794F8463068 +:10448000002B7FF408AF94F8483013F00F01B3D03D +:104490001A06204602D501F065FBADE701F058FB96 +:1044A000AAE794F84630002B7FF4F5AE94F8483034 +:1044B00013F00F01A0D01B06204602D501F03EFBF1 +:1044C0009AE701F031FB97E7142284F8342083F354 +:1044D00011882B462A4629462046FFF76DFE85F3B4 +:1044E0001188E9E65DB1152284F8342083F3118840 +:1044F0000021D4E90E232046FFF75EFEFDE60B22E5 +:1045000084F8342083F311882B462A462946204616 +:10451000FFF764FEE3E700BF9867000890670008B4 +:104520009467000838B590F834300446002B3ED02C +:10453000063BDAB20F2A34D80F2B32D8DFE803F06B +:104540003731310822323131313131313131373780 +:10455000C56BB0F84A309D4214D2C3681B8AB5FBC4 +:10456000F3F203FB12556DB9302383F311882B4608 +:104570002A462946FFF732FE85F311880A2384F87C +:1045800034300EE0142384F83430302383F3118860 +:1045900000231A4619462046FFF70EFE002383F338 +:1045A000118838BD036C03B198470023E7E7002169 +:1045B000204601F0C3FA0021204601F0B5FA6368F5 +:1045C0001B6813B10621204698470623D7E7000051 +:1045D00010B590F83430142B044629D017D8062B88 +:1045E00005D001D81BB110BD093B022BFBD800211F +:1045F000204601F0A3FA0021204601F095FA6368F5 +:104600001B6813B1062120469847062319E0152B95 +:10461000E9D10B2380F83430302383F31188002351 +:104620001A461946FFF7DAFD002383F31188DAE70B +:10463000C3689B695B68002BD5D1036C03B19847B5 +:10464000002384F83430CEE70023037582680369C1 +:104650001B6899689142FBD25A68036042601060FF +:104660005860704700230375826803691B68996866 +:104670009142FBD85A6803604260106058607047EE +:1046800008B50846302383F311880B7D032B05D032 +:10469000042B0DD02BB983F3118808BD8B69002240 +:1046A0001A604FF0FF338361FFF7CEFF0023F2E77C +:1046B000D1E9003213605A60F3E70000FFF7C4BF8E +:1046C000054BD9680875186802681A6053600122A2 +:1046D0000275D860FBF71EBE485C002030B50C4B5D +:1046E000DD684B1C87B004460FD02B46094A68464C +:1046F00000F05EF92046FFF7E3FF009B13B1684628 +:1047000000F060F9A86907B030BDFFF7D9FFF9E7FD +:10471000485C002081460008044B1A68DB689068FA +:104720009B68984294BF002001207047485C00209D +:10473000084B10B51C68D86822681A6053600122C3 +:104740002275DC60FFF78EFF01462046BDE8104071 +:10475000FBF7E0BD485C002038B5074C0749084826 +:10476000012300252370656001F0EAFB022323701A +:1047700085F3118838BD00BFB05E0020A067000837 +:10478000485C002008B572B6044B186500F048FC80 +:1047900000F0FEFC024B03221A70FEE7485C00208A +:1047A000B05E002000F044B9034A516853685B1AB8 +:1047B0009842FBD8704700BF001000E08B600223D6 +:1047C00008618B82084670478368A3F1840243F82E +:1047D000142C026943F8442C426943F8402C094ADE +:1047E00043F8242CC26843F8182C022203F80C2C3E +:1047F000002203F80B2C044A43F8102CA3F12000EC +:10480000704700BF2D030008485C002008B5FFF783 +:10481000DBFFBDE80840FFF751BF0000024BDB683B +:1048200098610F20FFF74CBF485C0020302383F3D2 +:104830001188FFF7F3BF000008B50146302383F36A +:1048400011880820FFF74AFF002383F3118808BD71 +:10485000064BDB6839B1426818605A6013604360E8 +:104860000420FFF73BBF4FF0FF307047485C00204B +:104870000368984206D01A68026050609961184631 +:10488000FFF71CBF7047000038B504460D4620688E +:10489000844200D138BD036823605C608561FFF706 +:1048A0000DFFF4E710B503689C68A2420CD85C6861 +:1048B0008A600B604C602160596099688A1A9A601E +:1048C0004FF0FF33836010BD1B68121BECE7000044 +:1048D0000A2938BF0A2170B504460D460A26601918 +:1048E00001F028FB01F014FB041BA54203D8751C42 +:1048F0002E460446F3E70A2E04D9BDE87040012095 +:1049000001F05EBB70BD0000F8B5144B0D46D961D7 +:1049100003F1100141600A2A1969826038BF0A2236 +:10492000016048601861A818144601F0F5FA0A27DA +:1049300001F0EEFA431BA342064606D37C1C28195D +:1049400001F0F8FA27463546F2E70A2F04D9BDE808 +:10495000F840012001F034BBF8BD00BF485C0020E6 +:10496000F8B506460D4601F0D3FA0F4A134653F840 +:10497000107F9F4206D12A4601463046BDE8F840E6 +:10498000FFF7C2BFD169BB68441A2C1928BF2C4657 +:10499000A34202D92946FFF79BFF2246314603482E +:1049A000BDE8F840FFF77EBF485C0020585C00205F +:1049B00010B4C0E9032300235DF8044B4361FFF703 +:1049C000CFBF000010B5194C236998420DD0D0E933 +:1049D0000032816813605A609A680A449A60002322 +:1049E00003604FF0FF33A36110BD2346026843F814 +:1049F000102F53600022026022699A4203D1BDE861 +:104A0000104001F091BA936881680B44936001F003 +:104A10007FFA2269E1699268441AA242E4D91144FA +:104A2000BDE81040091AFFF753BF00BF485C0020E3 +:104A30002DE9F047DFF8BC8008F110072C4ED8F8BC +:104A4000105001F065FAD8F81C40AA68031B9A427E +:104A50003ED81444D5E900324FF00009C8F81C4094 +:104A600013605A60C5F80090D8F81030B34201D1F5 +:104A700001F05AFA89F31188D5E90331284698479D +:104A8000302383F311886B69002BD8D001F040FAF2 +:104A90006A69A0EB04094A4582460DD2022001F062 +:104AA0008FFA0022D8F81030B34208D15146284678 +:104AB000BDE8F047FFF728BF121A2244F2E712EBD5 +:104AC000090938BF4A4629463846FFF7EBFEB5E7E5 +:104AD000D8F81030B34208D01444211AC8F81C008A +:104AE000A960BDE8F047FFF7F3BEBDE8F08700BF5F +:104AF000585C0020485C002038B501F009FA054AEE +:104B0000D2E90845031B181945F10001C2E9080163 +:104B100038BD00BF485C002000207047FEE7000061 +:104B2000704700004FF0FF307047000002290CD0A2 +:104B3000032904D00129074818BF00207047032A21 +:104B400005D8054800EBC2007047044870470020B4 +:104B5000704700BF786800082C2300202C680008EC +:104B600070B59AB00546084601A9144600F0C2F88F +:104B700001A8FCF791FE431C5B00C5E9003400224C +:104B8000237003236370C6B201AB02341046D1B266 +:104B90008E4204F1020401D81AB070BD13F8011B53 +:104BA00004F8021C04F8010C0132F0E708B53023C8 +:104BB00083F311880348FFF739FA002383F3118840 +:104BC00008BD00BFB85E002090F8443003F01F021B +:104BD000012A07D190F845200B2A03D10023C0E910 +:104BE0000E3315E003F06003202B08D1B0F84830F5 +:104BF0002BB990F84520212A03D81F2A04D8FFF7A3 +:104C0000F7B9222AEBD0FAE7034A82630722C2638C +:104C100003640120704700BF2423002007B5052945 +:104C200017D8DFE801F0191603191920302383F390 +:104C30001188104A01900121FFF79AFA01980E4A53 +:104C40000221FFF795FA0D48FFF7BCF9002383F323 +:104C5000118803B05DF804FB302383F31188074803 +:104C6000FFF786F9F2E7302383F311880348FFF753 +:104C70009DF9EBE7CC670008F0670008B85E0020FC +:104C800038B50C4D0C4C0D492A4604F10800FFF7CD +:104C900067FF05F1CA0204F110000949FFF760FF40 +:104CA00005F5CA7204F118000649BDE83840FFF75F +:104CB00057BF00BF806300202C230020AC67000892 +:104CC000B6670008C167000870B5044608460D467F +:104CD000FCF7E2FDC6B22046013403780BB9184652 +:104CE00070BD32462946FCF7C3FD0028F3D10120F0 +:104CF000F6E700002DE9F84F05460C46FCF7CCFD21 +:104D00002B49C6B22846FFF7DFFF08B10536F6B2D9 +:104D100028492846FFF7D8FF08B11036F6B2632EAF +:104D20000DD8DFF88C80DFF88C90234FDFF890A04F +:104D3000DFF890B02E7846B92670BDE8F88F294686 +:104D40002046BDE8F84F01F089BC252E2BD1072263 +:104D500041462846FCF78CFD58B9DBF8003023604B +:104D6000DBF804306360DBF80830A36007350C34EF +:104D7000E0E7082249462846FCF77AFD98B90F4B30 +:104D8000A21C197809090232C95D02F8041C13F843 +:104D9000011B01F00F015345C95D02F8031CF0D15E +:104DA00018340835C6E704F8016B0135C2E700BFC7 +:104DB00098680008C1670008AD680008107AFF1FF6 +:104DC0001C7AFF1FA0680008BFF34F8F024AD36808 +:104DD000DB03FCD4704700BF003C024008B5094B20 +:104DE0001B7873B9FFF7F0FF074B1A69002ABFBFA2 +:104DF000064A5A6002F188325A601A6822F48062C8 +:104E00001A6008BDDE650020003C024023016745B2 +:104E100008B50B4B1B7893B9FFF7D6FF094B1A69FE +:104E200042F000421A611A6842F480521A601A680D +:104E300022F480521A601A6842F480621A6008BD37 +:104E4000DE650020003C02400728F0B516D80C4C67 +:104E50000C4923787BB90C4D0E4608234FF00062B5 +:104E600055F8047B46F8042B013B13F0FF033A444A +:104E7000F6D10123237051F82000F0BD0020FCE79B +:104E800000660020E0650020C0680008014B53F870 +:104E900020007047C068000808207047072810B538 +:104EA000044601D9002010BDFFF7CEFF064B53F892 +:104EB00024301844C21A0BB90120F4E712680132F9 +:104EC000F0D1043BF6E700BFC0680008072810B522 +:104ED000044621D8FFF778FFFFF780FF0F4AF3233E +:104EE000D360C300DBB243F4007343F002031361E9 +:104EF000136943F480331361FFF766FFFFF7A4FFE4 +:104F0000074B53F8241000F03FF9FFF781FF2046CC +:104F1000BDE81040FFF7C2BF002010BD003C0240BA +:104F2000C0680008F8B512F00103144642D1851894 +:104F30002E4A954257D82E4B1B6813F0010352D0CE +:104F40002C4DFFF74BFFF323EB60FFF73DFF40F2E3 +:104F50000127032C15D824F001046618254C401AAB +:104F600040F20117B142236900EB010524D123F07F +:104F700001032361FFF74CFF0120F8BD043C04301E +:104F8000E7E78307E7D12B6923F440732B612B6993 +:104F90003B432B6151F8046B0660BFF34F8FFFF763 +:104FA00013FF03689E42E9D02B6923F001032B61B4 +:104FB000FFF72EFF0020E0E723F44073236123690D +:104FC0003B4323610B882B80BFF34F8FFFF7FCFE21 +:104FD0002D8831F8023BADB2AB42C3D0236923F038 +:104FE00001032361E4E71846C7E700BF0000080893 +:104FF00000380240003C0240084908B50B7828B14F +:105000001BB9FFF7EBFE01230B7008BD002BFCD092 +:10501000BDE808400870FFF7FBBE00BFDE6500205A +:1050200008B50649064800F0B1F8BDE808404FF45D +:1050300080314FF0805000F0A9B800BF00FF0100A0 +:10504000000100200846114601F06CBA012001F071 +:1050500069BA0000084601F083BA000038B5EFF3E2 +:1050600011859DB9EFF30584C4F30804302334B1EE +:1050700083F31188FFF740FD85F3118838BD83F372 +:105080001188FFF739FD84F3118838BDBDE8384039 +:10509000FFF732BD38B5FFF7E1FF114C114AC008E8 +:1050A00040EA4170A0FB025EC908A0FB040C1CEBA7 +:1050B000050CA1FB04404FF000035B41A1FB021271 +:1050C0001CEB040C43EB000011EB0E0142F100025B +:1050D000411842F10000090941EA007038BD00BFE3 +:1050E000CFF753E3A59BC42010B50244064BD2B2C0 +:1050F000904200D110BD441C00B253F8200041F88A +:10510000040BE0B2F4E700BF502800400F4B30B56D +:105110001C6F240407D41C6F44F400741C671C6FBC +:1051200044F400441C670A4C236843F480732360F2 +:105130000244084BD2B2904200D130BD441C00B2B0 +:1051400051F8045B43F82050E0B2F4E70038024025 +:10515000007000405028004007B5012201A900203E +:10516000FFF7C2FF019803B05DF804FB13B50446D6 +:10517000FFF7F2FFA04205D0012201A9002001940F +:10518000FFF7C4FF02B010BD704700007047000079 +:1051900070470000074B45F255521A6002225A60D0 +:1051A00040F6FF729A604CF6CC421A60024B012224 +:1051B0001A7070470030004008660020034B1B78CF +:1051C0001BB1034B4AF6AA221A60704708660020FA +:1051D00000300040034B1A681AB9034AD2F8742809 +:1051E0001A6070470466002000300240024B4FF006 +:1051F0008072C3F8742870470030024008B5FFF78A +:10520000E9FF024B1868C0F3407008BD0466002037 +:1052100008B5FFF7DFFF024B1868C0F3007008BD48 +:105220000466002070470000FEE700000A4B0B48B0 +:105230000B4A90420BD30B4BDA1C121AC11E22F000 +:1052400003028B4238BF00220021FCF72DBB53F82C +:10525000041B40F8041BECE7C86A00080C67002038 +:105260000C6700200C67002070B5D0E915439E68DC +:1052700000224FF0FF3504EB42135101D3F800092F +:105280000028BEBFD3F8000940F08040C3F80009F1 +:10529000D3F8000B0028BEBFD3F8000B40F08040CD +:1052A000C3F8000B013263189642C3F80859C3F8DB +:1052B000085BE0D24FF00113C4F81C3870BD000049 +:1052C000890141F02001016103699B06FCD4122091 +:1052D000FFF76ABA10B5054C2046FEF729FF4FF0DC +:1052E000A0436365024BA36510BD00BF0C660020A0 +:1052F0000469000870B50378012B054650D12A4B8C +:10530000446D98421BD1294B5A6B42F080025A637C +:105310005A6D42F080025A655A6D5A6942F0800215 +:105320005A615A6922F080025A610E2143205B695A +:10533000FEF748FD1E4BE3601E4BC4F80038002307 +:10534000C4F8003EC02323606E6D4FF40413A363C2 +:105350003369002BFCDA012333610C20FFF724FAB8 +:105360003369DB07FCD41220FFF71EFA3369002BE8 +:10537000FCDA0026A6602846FFF776FF6B68C4F8C3 +:105380001068DB68C4F81468C4F81C684BB90A4B91 +:10539000A3614FF0FF336361A36843F00103A3608F +:1053A00070BD064BF4E700BF0C66002000380240D9 +:1053B0004014004003002002003C30C0083C30C0D4 +:1053C000F8B5446D054600212046FFF779FFA96D29 +:1053D00000234FF001128F68C4F834384FF0006694 +:1053E000C4F81C284FF0FF3004EB431201339F42F6 +:1053F000C2F80069C2F8006BC2F80809C2F8080BCD +:10540000F2D20B686A6DEB65636210231361166953 +:1054100016F01006FBD11220FFF7C6F9D4F80038B9 +:1054200023F4FE63C4F80038A36943F4402343F037 +:105430001003A3610923C4F81038C4F814380A4BC8 +:10544000EB604FF0C043C4F8103B084BC4F8003B7E +:10545000C4F81069C4F80039EB6D03F1100243F48D +:105460008013EA65A362F8BDE06800084080001080 +:10547000426D90F84E10D2F8003823F4FE6343EAF0 +:105480000113C2F8003870472DE9F84300EB81039F +:10549000456DDA68166806F00306731E022B05EBED +:1054A00041130C4680460FFA81F94FEA41104FF044 +:1054B0000001C3F8101B4FF0010104F1100398BF65 +:1054C000B60401FA03F391698EBF334E06F180569C +:1054D00006F5004600293AD0578A04F158014901DF +:1054E00037436F50D5F81C180B43C5F81C382B18E0 +:1054F0000021C3F8101953690127611EA7409BB30F +:10550000138A928B9B08012A88BF5343D8F85C20EA +:10551000981842EA034301F1400205EB8202C8F801 +:105520005C00214653602846FFF7CAFE08EB89005D +:10553000C3681B8A43EA8453483464011E432E51D6 +:10554000D5F81C381F43C5F81C78BDE8F88305EB77 +:105550004917D7F8001B21F40041C7F8001BD5F804 +:105560001C1821EA0303C0E704F13F0305EB8303A2 +:105570000A4A5A6028462146FFF7A2FE05EB491069 +:10558000D0F8003923F40043C0F80039D5F81C38AE +:1055900023EA0707D7E700BF0080001000040002DD +:1055A000826D1268C265FFF75FBE00005831436D1F +:1055B00049015B5813F4004004D013F4001F0CBFE2 +:1055C00002200120704700004831436D49015B58BB +:1055D00013F4004004D013F4001F0CBF022001207C +:1055E0007047000000EB8101CB68196A0B681360FB +:1055F0004B6853607047000000EB810330B5DD68F5 +:10560000AA691368D36019B9402B84BF4023136083 +:105610006B8A1468426D1C44013CB4FBF3F4634391 +:10562000033323F0030302EB411043EAC44343F086 +:10563000C043C0F8103B2B6803F00303012B09B2F1 +:105640000ED1D2F8083802EB411013F4807FD0F865 +:10565000003B14BF43F0805343F00053C0F8003BBD +:1056600002EB4112D2F8003B43F00443C2F8003B86 +:1056700030BD00002DE9F041244D6E6D06EB401366 +:105680000446D3F8087BC3F8087B38070AD5D6F858 +:105690001438190706D505EB84032146DB68284634 +:1056A0005B689847FA071FD5D6F81438DB071BD577 +:1056B00005EB8403D968CCB98B69488A5A68B2FB78 +:1056C000F0F600FB16228AB91868DA6890420DD20B +:1056D000121AC3E90024302383F311880B482146B2 +:1056E000FFF78AFF84F31188BDE8F081012303FAF4 +:1056F00004F26B8923EA02036B81CB68002BF3D0A1 +:1057000021460248BDE8F041184700BF0C66002062 +:1057100000EB810370B5DD68436D6C692668E66057 +:105720004A0156BB1A444FF40020C2F810092A68F7 +:1057300002F00302012A0AB20ED1D3F8080803EBE3 +:10574000421410F4807FD4F8000914BF40F0805058 +:1057500040F00050C4F8000903EB4212D2F80009EF +:1057600040F00440C2F80009D3F83408012202FADC +:1057700001F10143C3F8341870BD19B9402E84BF3C +:105780004020206020682E8A8419013CB4FBF6F486 +:1057900040EAC44040F000501A44C6E72DE9F843FF +:1057A0003B4D6E6D06EB40130446D3F80889C3F8F1 +:1057B000088918F0010F4FEA40171AD0D6F81038B0 +:1057C000DB0716D505EB8003D9684B691868DA68E2 +:1057D000904230D2121A4FF000091A60C3F80490B8 +:1057E000302383F3118821462846FFF791FF89F380 +:1057F000118818F0800F1CD0D6F834380126A64046 +:10580000334216D005EB84036D6DD3F80CC0DCF881 +:1058100014200134E4B2D2F800E005EB04342F4444 +:105820005168714515D3D5F8343823EA0606C5F812 +:105830003468BDE8F883012303FA04F22B8923EAD4 +:1058400002032B818B68002BD3D021462846984732 +:10585000CFE7BCF81000AEEB0103834228BF03463C +:10586000D7F8180980B2B3EB800FE2D89068A0F1A6 +:10587000040959F8048FC4F80080A0EB0908984483 +:10588000B8F1040FF5D818440B4490605360C7E793 +:105890000C6600202DE9F74FA24C656D6E69AB696F +:1058A0001E4016F480586E6107D02046FEF7A8FC13 +:1058B00003B0BDE8F04FFEF75BBA002E12DAD5F860 +:1058C000003E98489B071EBFD5F8003E23F0030317 +:1058D000C5F8003ED5F8043823F00103C5F80438B4 +:1058E000FEF7B8FC370505D58E48FFF7BDFC8D489F +:1058F000FEF79EFCB0040CD5D5F8083813F0060F5F +:10590000EB6823F470530CBF43F4105343F4A053DB +:10591000EB6031071BD56368DB681BB9AB6923F00B +:105920000803AB612378052B0CD1D5F8003E7D48E8 +:105930009A071EBFD5F8003E23F00303C5F8003ECA +:10594000FEF788FC6368DB680BB176489847F30282 +:1059500074D4B70227D5D4F85490DFF8C8B1002723 +:105960004FF0010A09EB4712D2F8003B03F4402341 +:10597000B3F5802F11D1D2F8003B002B0DDA6289EC +:105980000AFA07F322EA0303638104EB8703DB6867 +:10599000DB6813B1394658469847A36D01379B68B9 +:1059A000FFB29F42DED9F00617D5676D3A6AC2F39F +:1059B0000A1002F00F0302F4F012B2F5802F00F08B +:1059C0008580B2F5402F08D104EB83030022DB6809 +:1059D0001B6A07F5805790426AD13003D5F8184802 +:1059E00013D5E10302D50020FFF744FEA20302D540 +:1059F0000120FFF73FFE630302D50220FFF73AFEC6 +:105A0000270302D50320FFF735FE75037FF550AF5E +:105A1000E00702D50020FFF7C1FEA10702D5012053 +:105A2000FFF7BCFE620702D50220FFF7B7FE23078F +:105A30007FF53EAF0320FFF7B1FE39E7636DDFF876 +:105A4000E4A0019300274FF00109A36D9B685FFA62 +:105A500087FB9B453FF67DAF019B03EB4B13D3F8D0 +:105A6000001901F44021B1F5802F1FD1D3F800199E +:105A700000291BDAD3F8001941F09041C3F800194E +:105A8000D3F800190029FBDB5946606DFFF718FCBD +:105A9000218909FA0BF321EA0303238104EB8B0329 +:105AA000DB689B6813B15946504698470137CCE7ED +:105AB000910708BFD7F80080072A98BF03F8018B29 +:105AC00002F1010298BF4FEA182884E7023304EB81 +:105AD000830207F580575268D2F818C0DCF8082016 +:105AE000DCE9001CA1EB0C0C002188420AD104EB7C +:105AF000830463689B699A6802449A605A68024406 +:105B00005A606AE711F0030F08BFD7F800808C4590 +:105B100088BF02F8018B01F1010188BF4FEA182804 +:105B2000E3E700BF0C660020436D03EB4111D1F8A1 +:105B3000003B43F40013C1F8003B7047436D03EB97 +:105B40004111D1F8003943F40013C1F8003970470E +:105B5000436D03EB4111D1F8003B23F40013C1F86E +:105B6000003B7047436D03EB4111D1F8003923F43A +:105B70000013C1F80039704730B5039C017204333B +:105B800004FB0325C0E90653049B03630021059B26 +:105B9000C160C0E90000C0E90422C0E90842C0E9D0 +:105BA0000A11436330BD0000416A0022C0E90411BC +:105BB000C0E90A22C2606FF00101FEF765BE000075 +:105BC000D0E90432934201D1C2680AB9181D704766 +:105BD0000020704703691960C2680132C260C2695F +:105BE000134482690361934224BF436A0361002125 +:105BF000FEF73EBE38B504460D46E3683BB1626928 +:105C0000131D1268A3621344E362002007E0237AA5 +:105C100033B929462046FEF71BFE0028EDDA38BDD1 +:105C20006FF00100FBE70000C368C269013BC3607D +:105C30004369134482694361934224BF436A4361C9 +:105C400000238362036B03B11847704770B530239C +:105C5000044683F31188866A3EB9FFF7CBFF0546F9 +:105C600018B186F31188284670BDA36AE26A13F85A +:105C7000015BA362934202D32046FFF7D5FF0023C6 +:105C800083F31188EFE700002DE9F84F04460E4634 +:105C9000174698464FF0300989F311880025AA4627 +:105CA000D4F828B0BBF1000F09D141462046FFF7D8 +:105CB000A1FF20B18BF311882846BDE8F88FD4E905 +:105CC0000A12A7EB050B521A934528BF9346BBF166 +:105CD000400F1BD9334601F1400251F8040B43F841 +:105CE000040B9142F9D1A36A40334036A362403598 +:105CF000D4E90A239A4202D32046FFF795FF8AF39C +:105D00001188BD42D8D289F31188C9E730465A4676 +:105D1000FBF7A4FDA36A5B445E44A3625D44E7E72E +:105D200010B5029C0172043303FB0421C0E9061381 +:105D30000023C0E90A33039B0363049BC460C0E9EA +:105D40000000C0E90422C0E90842436310BD00001E +:105D5000026AC260426AC0E904220022C0E90A2243 +:105D60006FF00101FEF790BDD0E904239A4201D102 +:105D7000C26822B9184650F8043B0B6070470023F4 +:105D80001846FAE7C368C2690133C3604369134424 +:105D900082694361934224BF436A43610021FEF755 +:105DA00067BD000038B504460D46E3683BB1236982 +:105DB0001A1DA262E2691344E362002007E0237A1D +:105DC00033B929462046FEF743FD0028EDDA38BDF9 +:105DD0006FF00100FBE7000003691960C268013A37 +:105DE000C260C269134482690361934224BF436A5B +:105DF000036100238362036B03B1184770470000FF +:105E000070B530230D460446114683F31188866A27 +:105E10002EB9FFF7C7FF10B186F3118870BDA36AD2 +:105E20001D70A36AE26A01339342A36204D3E1695D +:105E300020460439FFF7D0FF002080F31188EDE7FA +:105E40002DE9F84F04460D46904699464FF0300A2A +:105E50008AF311880026B346A76A4FB949462046FF +:105E6000FFF7A0FF20B187F311883046BDE8F88F17 +:105E7000D4E90A073A1AA8EB0607974228BF174643 +:105E8000402F1BD905F1400355F8042B40F8042B93 +:105E90009D42F9D1A36A4033A3624036D4E90A2374 +:105EA0009A4204D3E16920460439FFF795FF8BF34A +:105EB00011884645D9D28AF31188CDE729463A465A +:105EC000FBF7CCFCA36A3B443D44A3623E44E5E7B8 +:105ED000D0E904239A4217D1C3689BB1836A8BB17E +:105EE000043B9B1A0ED01360C368013BC360C369B7 +:105EF0001A44836902619A4224BF436A0361002302 +:105F000083620123184670470023FBE700F0D2B8F4 +:105F10004FF08043586A70474FF080430022586327 +:105F20001A610222DA6070474FF080430022DA6083 +:105F3000704700004FF0804358637047FEE7000051 +:105F400070B51B4B01630025044686B0586085621E +:105F50000E46FDF7E9FE04F11003C4E904334FF0E7 +:105F6000FF33C4E90635C4E90044A560E562FFF7E4 +:105F7000CFFF2B460246C4E9082304F134010D4A41 +:105F8000256580232046FEF719FC0123E0600A4ABC +:105F90000375009272680192B268CDE90223074B43 +:105FA0006846CDE90435FEF731FC06B070BD00BF90 +:105FB000B05E002010690008156900083D5F000808 +:105FC000024AD36A1843D062704700BF485C002081 +:105FD0004B6843608B688360CB68C3600B69436127 +:105FE0004B6903628B6943620B6803607047000072 +:105FF00008B5264B26481A6940F2FF110A431A6178 +:106000001A6922F4FF7222F001021A611A691A6BEE +:106010000A431A631A6D0A431A651E4A1B6D11461C +:10602000FFF7D6FF02F11C0100F58060FFF7D0FFFB +:1060300002F1380100F58060FFF7CAFF02F1540158 +:1060400000F58060FFF7C4FF02F1700100F5806089 +:10605000FFF7BEFF02F18C0100F58060FFF7B8FF8B +:1060600002F1A80100F58060FFF7B2FF02F1C40160 +:1060700000F58060FFF7ACFF02F1E00100F5806001 +:10608000FFF7A6FFBDE8084000F090B800380240D6 +:10609000000002401C69000808B500F0FBF9FEF79B +:1060A0005BFBFFF797F8BDE80840FEF7E9BD00008D +:1060B000704700000F4B1A6C42F001021A641A6E0E +:1060C00042F001021A660C4A1B6E936843F001030A +:1060D00093604FF0804353229A624FF0FF32DA62AE +:1060E00000229A615A63DA605A6001225A611A608A +:1060F000704700BF00380240002004E04FF08042AB +:1061000008B51169D3680B40D9B2C9439B07116127 +:1061100007D5302383F31188FEF744FB002383F374 +:10612000118808BD1F4B1A696FEAC2526FEAD2523A +:106130001A611A69C2F308021A614FF0FF301A6936 +:106140005A69586100215A6959615A691A6A62F09C +:1061500080521A621A6A02F080521A621A6A5A6AE5 +:1061600058625A6A59625A6A1A6C42F080521A642A +:106170001A6E42F080521A661A6E0B4A106840F48A +:1061800080701060186F00F44070B0F5007F1EBF83 +:106190004FF4803018671967536823F40073536015 +:1061A00000F054B90038024000700040334B4FF00B +:1061B00080521A64324A4FF4404111601A6842F02A +:1061C00001021A601A689107FCD59A6822F003024E +:1061D0009A602A4B9A6812F00C02FBD1196801F000 +:1061E000F90119609A601A6842F480321A601A68DC +:1061F0009203FCD55A6F42F001025A671F4B5A6F47 +:106200009007FCD51F4A5A601A6842F080721A60E3 +:106210001B4A53685904FCD5184B1A689201FCD5E7 +:10622000194A9A60194B1A68194B9A42194B21D195 +:10623000194A1168194A91421CD140F205121A609C +:10624000144A136803F00F03052BFAD10B4B9A681D +:1062500042F002029A609A6802F00C02082AFAD10F +:106260005A6C42F480425A645A6E42F480425A6632 +:106270005B6E704740F20572E1E700BF00380240F4 +:10628000007000400854400700948838002004E063 +:1062900011640020003C024000ED00E041C20F41CB +:1062A000074A08B5536903F00103536123B1054A56 +:1062B00013680BB150689847BDE80840FDF758BD1A +:1062C000003C014084660020074A08B5536903F08A +:1062D0000203536123B1054A93680BB1D068984714 +:1062E000BDE80840FDF744BD003C01408466002045 +:1062F000074A08B5536903F00403536123B1054A03 +:1063000013690BB150699847BDE80840FDF730BDEF +:10631000003C014084660020074A08B5536903F039 +:106320000803536123B1054A93690BB1D0699847BB +:10633000BDE80840FDF71CBD003C0140846600201C +:10634000074A08B5536903F01003536123B1054AA6 +:10635000136A0BB1506A9847BDE80840FDF708BDC5 +:10636000003C014084660020164B10B55C6904F4C3 +:1063700078725A61A30604D5134A936A0BB1D06AA6 +:106380009847600604D5104A136B0BB1506B9847C1 +:10639000210604D50C4A936B0BB1D06B9847E205EC +:1063A00004D5094A136C0BB1506C9847A30504D56A +:1063B000054A936C0BB1D06C9847BDE81040FDF7CF +:1063C000D7BC00BF003C014084660020194B10B5CB +:1063D0005C6904F47C425A61620504D5164A136D67 +:1063E0000BB1506D9847230504D5134A936D0BB13B +:1063F000D06D9847E00404D50F4A136E0BB1506E70 +:106400009847A10404D50C4A936E0BB1D06E9847FF +:10641000620404D5084A136F0BB1506F98472304E8 +:1064200004D5054A936F0BB1D06F9847BDE8104073 +:10643000FDF79EBC003C01408466002008B5FFF7D4 +:106440005DFEBDE80840FDF793BC0000062108B5DD +:106450000846FDF7B7FC06210720FDF7B3FC06212F +:106460000820FDF7AFFC06210920FDF7ABFC062153 +:106470000A20FDF7A7FC06211720FDF7A3FC062143 +:106480002820FDF79FFCBDE8084007211C20FDF7F0 +:1064900099BC000008B5FFF745FE00F00BF8FDF7CA +:1064A00045FEFDF71DFDFFF703FEBDE80840FFF7C1 +:1064B0002DBD00000023054A19460133102BC2E907 +:1064C000001102F10802F8D1704700BF8466002075 +:1064D0000B460146184600F02DB8000000F040B809 +:1064E000012838BF012010B50446204600F030F8DE +:1064F00030B900F007F808B900F00CF88047F4E76D +:1065000010BD0000024B1868BFF35B8F704700BFDF +:106510000467002008B5062000F084F80120FEF78B +:10652000FDFA0000024B0A4601461868FEF78ABDD4 +:106530004C23002010B5054C13462CB10A460146E9 +:106540000220AFF3008010BD2046FCE700000000F1 +:10655000024B01461868FEF779BD00BF4C230020AE +:10656000024B01461868FEF775BD00BF4C230020A2 +:1065700010B501390244904201D1002005E00378B2 +:1065800011F8014FA34201D0181B10BD0130F2E7F2 +:106590002DE9F041A3B1C91A17780144044603F16B +:1065A000FF3C8C42204601D9002009E00578BD421D +:1065B00004F10104F5D10CEB0405D618A54201D174 +:1065C000BDE8F08115F8018D16F801EDF045F5D024 +:1065D000E7E700001F2938B504460D4604D9162305 +:1065E00003604FF0FF3038BD426C12B152F82130D9 +:1065F0004BB9204600F030F82A4601462046BDE857 +:10660000384000F017B8012B0AD0591C03D11623CB +:1066100003600120E7E7002442F825402846984718 +:106620000020E0E7024B01461868FFF7D3BF00BF28 +:106630004C23002038B5074D002304460846114678 +:106640002B60FEF76FFA431C02D12B6803B1236065 +:1066500038BD00BF08670020FEF75EBA034611F898 +:10666000012B03F8012B002AF9D1704773772D73A2 +:106670007061722D663430372D626C0053544D3387 +:1066800032463F3F3F0053544D333246343078005A +:1066900053544D3332463432780053544D333246DE +:1066A00034343658580000000120330000104100F7 +:1066B00001105A00031059000710310000000000BB +:1066C0007C660008130400008666000819040000B8 +:1066D00090660008210400009A66000840A2E4F1D8 +:1066E000646891060041A3E5F26569920700000025 +:1066F0004261642043414E496661636520696E646E +:1067000065782E00000100000001FF0000640040D9 +:106710000068004080000000008000000000800051 +:10672000000000000000000065210008292A000880 +:1067300031290008A5210008B1210008B123000873 +:1067400075210008852100087921000881210008B1 +:106750007D210008D5220008892100082D2D000880 +:1067600099210008A9220008000000005D3E0008F1 +:10677000493E0008853E0008713E00087D3E000845 +:10678000693E0008553E0008413E0008913E000861 +:106790000000000001000000000000006330000065 +:1067A0009C670008A05C0020B05E00204172647508 +:1067B00050696C6F740025424F415244252D424C64 +:1067C000002553455249414C2500000002000000BD +:1067D0000000000079400008E5400008400040004B +:1067E00050630020606300200200000000000000F1 +:1067F0000300000000000000294100080000000024 +:106800001000000070630020000000000100000084 +:10681000000000000C660020010102001D4C000871 +:106820002D4B0008C94B0008AD4B00084300000089 +:106830003468000809024300020100C03209040064 +:1068400000010202010005240010010524010001DD +:10685000042402020524060001070582030800FF44 +:1068600009040100020A00000007050102400000BF +:106870000705810240000000120000008068000847 +:1068800012011001020000400912415700020102EA +:10689000030100000403090425424F41524425002E +:1068A00073772D737061722D66343037003031325A +:1068B00033343536373839414243444546000000C9 +:1068C00000400000004000000040000000400000C8 +:1068D00000000100000002000000020000000200B1 +:1068E000000000006D42000825450008D145000861 +:1068F000400040006C6600206C6600200100000033 +:106900007C660020800000004001000003000000C1 +:106910006D61696E0069646C650000000000802A8A +:1069200000000000AAAAAAAA00000024FFFF00009D +:106930000000000000A00A00006800000000000045 +:10694000AA6AAAAA000000007FFF000000009009C8 +:10695000000000000000010000000000AAAAAAAA8E +:1069600000000000FFFE000000000000000000002A +:106970001A000000000000009AAAAAAA0000000065 +:10698000FFFF000099000000000000000000000070 +:1069900000000000AAAAAAAA00000000FFFF000051 +:1069A00000000000000000000000000000000000E7 +:1069B000AAAAAAAA00000000FFFF00000000000031 +:1069C000000000000000000000000000AAAAAAAA1F +:1069D00000000000FFFF00000000000000000000B9 +:1069E00000000000000000000A000000000000009D +:1069F0000300000000000000000000000000000094 +:106A00000000000000000000000000000000000086 +:106A100000000000000000007017000000000000EF +:106A2000000007000000000040420F00FE2A0100A5 +:106A3000D2040000FF00960000000008009600004D +:106A40000000080004000000946800080000000036 +:106A50000000000000000000000000000000000036 +:106A60000000000050230020000000000000000093 +:106A70000000000000000000000000000000000016 +:106A80000000000000000000000000000000000006 +:106A900000000000000000000000000000000000F6 +:106AA00000000000000000000000000000000000E6 +:106AB00000000000000000000000000000000000D6 +:086AC0000000000000000000CE :00000001FF diff --git a/Tools/debug/gdb_crashdump.sh b/Tools/debug/gdb_crashdump.sh index 89f6b4d66c160a..917ffa75033fbd 100755 --- a/Tools/debug/gdb_crashdump.sh +++ b/Tools/debug/gdb_crashdump.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash # script to more easily get a backtrace from an ArduPilot crash_dump.bin diff --git a/Tools/environment_install/APM_install.sh b/Tools/environment_install/APM_install.sh index acb7a1fbae9448..869687dbff0179 100755 --- a/Tools/environment_install/APM_install.sh +++ b/Tools/environment_install/APM_install.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash #A simple script to install the APM SITL environment into cygwin diff --git a/Tools/environment_install/install-ROS-ubuntu.sh b/Tools/environment_install/install-ROS-ubuntu.sh index 565670f5a502b1..435560ac4f0ab1 100755 --- a/Tools/environment_install/install-ROS-ubuntu.sh +++ b/Tools/environment_install/install-ROS-ubuntu.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash echo "---------- $0 start ----------" set -e # set -x diff --git a/Tools/environment_install/install-prereqs-arch.sh b/Tools/environment_install/install-prereqs-arch.sh index 52b94eca23cd62..965815ec71efc1 100755 --- a/Tools/environment_install/install-prereqs-arch.sh +++ b/Tools/environment_install/install-prereqs-arch.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash set -e set -x diff --git a/Tools/environment_install/install-prereqs-mac.sh b/Tools/environment_install/install-prereqs-mac.sh index 6486b007d6452c..de2cd666ef760b 100755 --- a/Tools/environment_install/install-prereqs-mac.sh +++ b/Tools/environment_install/install-prereqs-mac.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash echo "---------- $0 start ----------" set -e set -x @@ -42,7 +42,7 @@ echo "Checking homebrew..." $(which -s brew) || { echo "installing homebrew..." - /bin/bash -c "$(curl -fsSL https://raw.githubusercontent.com/Homebrew/install/HEAD/install.sh)" + /usr/bin/env bash -c "$(curl -fsSL https://raw.githubusercontent.com/Homebrew/install/HEAD/install.sh)" } echo "Homebrew installed" diff --git a/Tools/environment_install/install-prereqs-openSUSE-Tumbleweed.sh b/Tools/environment_install/install-prereqs-openSUSE-Tumbleweed.sh new file mode 100755 index 00000000000000..5895dbdeb5b2be --- /dev/null +++ b/Tools/environment_install/install-prereqs-openSUSE-Tumbleweed.sh @@ -0,0 +1,214 @@ +#!/usr/bin/env bash +echo "---------- $0 start ----------" +set -e +set -x +set +H + +if [ $EUID == 0 ]; then + echo "Please do not run this script as root; don't sudo it!" + exit 1 +fi + + +OPT="/opt" +# Ardupilot Tools +ARDUPILOT_TOOLS="Tools/autotest" + +ASSUME_YES=false +QUIET=false +sep="##############################################" + +OPTIND=1 # Reset in case getopts has been used previously in the shell. +while getopts "yq" opt; do + case "$opt" in + \?) + exit 1 + ;; + y) ASSUME_YES=true + ;; + q) QUIET=true + ;; + esac +done + +ZYPPER="sudo zypper in --no-recommends" +if $ASSUME_YES; then + ZYPPER="sudo zypper in -y --no-recommends" +fi +PIP3=pip3 +if $QUIET; then + PIP3="pip3 -q" +fi + +function package_is_installed() { + rpm -q $1 &>/dev/null +} + +function heading() { + echo "$sep" + echo $* + echo "$sep" +} + +#Install python3 1st, as openSUSE TW WSL does not come with preinstalled python +$ZYPPER python3 || echo "Check zypper output for errors" + +#As tumbleweed can have many python versions, we need to know which one is currently active +PYPKGVER=python$(python3 --version | cut -d' ' -f2 | awk -F. '{print $1$2}') + +BASE_PKGS="patterns-devel-base-devel_basis ccache git axel valgrind screen gcc-c++ xterm free-ttf-fonts sfml2-devel zip glibc-devel-static rsync" +SITL_PKGS="${PYPKGVER}-pip ${PYPKGVER}-devel ${PYPKGVER}-setuptools ${PYPKGVER}-wheel ${PYPKGVER}-lxml ${PYPKGVER}-pyaml ${PYPKGVER}-wxPython ${PYPKGVER}-pyparsing ${PYPKGVER}-opencv ${PYPKGVER}-numpy ${PYPKGVER}-scipy ${PYPKGVER}-matplotlib" + +PYTHON_PKGS="future lxml pymavlink MAVProxy pexpect argparse pyparsing geocoder pyserial empy==3.3.4 ptyprocess dronecan" +PYTHON_PKGS+=" flake8 junitparser pygame intelhex psutil pyyaml" +# GNU Tools for ARM Embedded Processors +# (see https://launchpad.net/gcc-arm-embedded/) +ARM_ROOT="gcc-arm-none-eabi-10-2020-q4-major" +ARM_TARBALL="$ARM_ROOT-x86_64-linux.tar.bz2" +ARM_TARBALL_URL="https://firmware.ardupilot.org/Tools/STM32-tools/$ARM_TARBALL" + +ARM_LINUX_ROOT=gcc-linaro-7.5.0-2019.12-x86_64_arm-linux-gnueabihf +ARM_LINUX_GCC_URL="https://releases.linaro.org/components/toolchain/binaries/7.5-2019.12/arm-linux-gnueabihf/gcc-linaro-7.5.0-2019.12-x86_64_arm-linux-gnueabihf.tar.xz" +ARM_LINUX_TARBALL="gcc-linaro-7.5.0-2019.12-x86_64_arm-linux-gnueabihf.tar.xz" + +function maybe_prompt_user() { + if $ASSUME_YES; then + return 0 + else + read -p "$1" + if [[ $REPLY =~ ^[Yy]$ ]]; then + return 0 + else + return 1 + fi + fi +} + +sudo usermod -a -G dialout "$USER" + +$ZYPPER $BASE_PKGS $SITL_PKGS || echo "Check zypper output for errors" + +python3 -m venv "$HOME"/venv-ardupilot + +SHELL_LOGIN=".profile" +# activate it: +SOURCE_LINE="source $HOME/venv-ardupilot/bin/activate" +$SOURCE_LINE + +if ! grep -Fxq "$SOURCE_LINE" ~/.bashrc; then + if [[ -z "${DO_PYTHON_VENV_ENV}" ]] && maybe_prompt_user "Make ArduPilot venv default for python [N/y]?" ; then + DO_PYTHON_VENV_ENV=1 + fi + + if [[ $DO_PYTHON_VENV_ENV -eq 1 ]]; then + echo $SOURCE_LINE >> ~/.bashrc + fi +fi + +$PIP3 install -U pip setuptools wheel +$PIP3 install -U attrdict3 +$PIP3 install -U $PYTHON_PKGS + +( + cd /usr/lib64/ccache + for C in arm-none-eabi-g++ arm-none-eabi-gcc arm-linux-gnueabihf-g++ arm-linux-gnueabihf-gcc; do + if [ ! -f "$C" ]; then + sudo ln -s ../../bin/ccache "$C" + fi + done +) + +ccache --set-config sloppiness=file_macro,locale,time_macros +ccache --set-config ignore_options="--specs=nano.specs --specs=nosys.specs" + +if [ ! -d $OPT/$ARM_ROOT ]; then + ( + cd $OPT; + sudo axel -a -c $ARM_TARBALL_URL; + sudo tar xjf ${ARM_TARBALL}; + sudo rm ${ARM_TARBALL}; + ) +fi + +if [ ! -d $OPT/$ARM_LINUX_ROOT ]; then + ( + cd $OPT; + sudo axel -a -c "${ARM_LINUX_GCC_URL}"; + sudo tar xf ${ARM_LINUX_TARBALL}; + sudo rm ${ARM_LINUX_TARBALL}; + ) +fi + +heading "Removing modemmanager and brltty package that could conflict with firmware uploading" +if package_is_installed "ModemManager"; then + sudo zypper rm ModemManager +fi +if package_is_installed "brltty"; then + sudo zypper rm brltty +fi +echo "Done!" + +heading "Adding ArduPilot Tools to environment" + +SCRIPT_DIR=$(dirname $(realpath ${BASH_SOURCE[0]})) +ARDUPILOT_ROOT=$(realpath "$SCRIPT_DIR/../../") + + +exportline="export PATH=$OPT/$ARM_ROOT/bin:\$PATH"; +if ! grep -Fxq "$exportline" ~/$SHELL_LOGIN ; then + if maybe_prompt_user "Add $OPT/$ARM_ROOT/bin to your PATH [N/y]?" ; then + echo $exportline >> ~/$SHELL_LOGIN + else + echo "Skipping adding $OPT/$ARM_ROOT/bin to PATH." + fi +fi + +exportline1="export PATH=$OPT/$ARM_LINUX_ROOT/bin:\$PATH"; +if ! grep -Fxq "$exportline1" ~/$SHELL_LOGIN ; then + if maybe_prompt_user "Add $OPT/$ARM_LINUX_ROOT/bin to your PATH [N/y]?" ; then + echo $exportline1 >> ~/$SHELL_LOGIN + else + echo "Skipping adding $OPT/$ARM_LINUX_ROOT/bin to PATH." + fi +fi + +exportline2="export PATH=$ARDUPILOT_ROOT/$ARDUPILOT_TOOLS:\$PATH"; +if ! grep -Fxq "$exportline2" ~/$SHELL_LOGIN ; then + if maybe_prompt_user "Add $ARDUPILOT_ROOT/$ARDUPILOT_TOOLS to your PATH [N/y]?" ; then + echo $exportline2 >> ~/$SHELL_LOGIN + else + echo "Skipping adding $ARDUPILOT_ROOT/$ARDUPILOT_TOOLS to PATH." + fi +fi + +exportline3="source $ARDUPILOT_ROOT/Tools/completion/completion.bash"; +if ! grep -Fxq "$exportline3" ~/.bashrc ; then + if maybe_prompt_user "Add ArduPilot Bash Completion to your bash shell [N/y]?" ; then + echo $exportline3 >> ~/.bashrc + else + echo "Skipping adding ArduPilot Bash Completion." + fi +fi + +exportline4="export PATH=/usr/lib64/ccache:\$PATH"; +if ! grep -Fxq "$exportline4" ~/$SHELL_LOGIN ; then + if maybe_prompt_user "Append CCache to your PATH [N/y]?" ; then + echo $exportline4 >> ~/$SHELL_LOGIN + else + echo "Skipping appending CCache to PATH." + fi +fi +echo "Done!" + +if [[ $SKIP_AP_GIT_CHECK -ne 1 ]]; then + cd "$ARDUPILOT_ROOT" + if [ -d ".git" ]; then + heading "Update git submodules" + cd $ARDUPILOT_ROOT + git submodule update --init --recursive + echo "Done!" + fi +fi + +echo "---------- $0 end ----------" +echo "Done. Please log out and log in again." diff --git a/Tools/environment_install/install-prereqs-ubuntu.sh b/Tools/environment_install/install-prereqs-ubuntu.sh index 594aa33708e456..0107c24a33e11c 100755 --- a/Tools/environment_install/install-prereqs-ubuntu.sh +++ b/Tools/environment_install/install-prereqs-ubuntu.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash echo "---------- $0 start ----------" set -e set -x diff --git a/Tools/environment_install/ubuntu-18.04-python3.sh b/Tools/environment_install/ubuntu-18.04-python3.sh index a82a4138a4c73d..1b0df324fddcf3 100755 --- a/Tools/environment_install/ubuntu-18.04-python3.sh +++ b/Tools/environment_install/ubuntu-18.04-python3.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash set -e set -x diff --git a/Tools/geotag/geotag.sh b/Tools/geotag/geotag.sh index 58703fd43c6b72..02b30342560bf7 100755 --- a/Tools/geotag/geotag.sh +++ b/Tools/geotag/geotag.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash # Advanced geotagging tool by André Kjellstrup ###################################################################### VARIABLES ######################## diff --git a/Tools/gittools/git-commit-subsystems b/Tools/gittools/git-commit-subsystems index 4ef38059960b73..a06fa7dc54b28f 100755 --- a/Tools/gittools/git-commit-subsystems +++ b/Tools/gittools/git-commit-subsystems @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash SCRIPT_DIR=$(dirname $(realpath ${BASH_SOURCE[0]})) GIT_DIR=$(git rev-parse --git-dir) diff --git a/Tools/gittools/git-subsystems-split b/Tools/gittools/git-subsystems-split index 1810aea8932c95..a8fd09787244ac 100755 --- a/Tools/gittools/git-subsystems-split +++ b/Tools/gittools/git-subsystems-split @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash SCRIPT_DIR=$(dirname $(realpath ${BASH_SOURCE[0]})) GIT_DIR=$(git rev-parse --git-dir) diff --git a/Tools/gittools/path-libraries.sh b/Tools/gittools/path-libraries.sh index 14aaf4f2e33ced..711931776c62df 100755 --- a/Tools/gittools/path-libraries.sh +++ b/Tools/gittools/path-libraries.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash usage() { cat >&$1 <&$1 <,$>:"--debug">) +set(WAF_DISABLE_NETWORKING $<$:"--disable-networking">) +set(WAF_DISABLE_SCRIPTING $<$:"--disable-scripting">) +set(WAF_DISABLE_WATCHDOG $<$:"--disable-watchdog">) +set(WAF_ENABLE_DDS $<$:"--enable-dds">) +set(WAF_ENABLE_NETWORKING_TESTS $<$:"--enable-networking-tests">) +set(WAF_ENABLE_PPP $<$:"--enable-ppp">) add_custom_target(ardupilot_configure ALL - ${WAF_COMMAND} configure --board sitl --enable-dds ${WAF_CONFIG} + ${WAF_COMMAND} configure --board sitl + ${WAF_CONFIG} + ${WAF_DISABLE_NETWORKING} + ${WAF_DISABLE_SCRIPTING} + ${WAF_DISABLE_WATCHDOG} + ${WAF_ENABLE_DDS} + ${WAF_ENABLE_NETWORKING_TESTS} + ${WAF_ENABLE_PPP} WORKING_DIRECTORY ${ARDUPILOT_ROOT} ) diff --git a/Tools/ros2/ardupilot_sitl/src/ardupilot_sitl/launch.py b/Tools/ros2/ardupilot_sitl/src/ardupilot_sitl/launch.py index 6578e537d8fbc7..10203e148bf530 100644 --- a/Tools/ros2/ardupilot_sitl/src/ardupilot_sitl/launch.py +++ b/Tools/ros2/ardupilot_sitl/src/ardupilot_sitl/launch.py @@ -284,21 +284,21 @@ def generate_action(context: LaunchContext, *args, **kwargs) -> ExecuteProcess: # Retrieve launch arguments. master = LaunchConfiguration("master").perform(context) - # out = LaunchConfiguration("out").perform(context) + out = LaunchConfiguration("out").perform(context) sitl = LaunchConfiguration("sitl").perform(context) # Display launch arguments. print(f"command: {command}") print(f"master: {master}") print(f"sitl: {sitl}") + print(f"out: {out}") # Create action. mavproxy_process = ExecuteProcess( cmd=[ [ f"{command} ", - "--out ", - "127.0.0.1:14550 ", + f"--out {out} ", "--out ", "127.0.0.1:14551 ", f"--master {master} ", diff --git a/Tools/scripts/CAN/can_sitl.sh b/Tools/scripts/CAN/can_sitl.sh index 65aa2339a5f9dc..54be78e2cd2a2a 100755 --- a/Tools/scripts/CAN/can_sitl.sh +++ b/Tools/scripts/CAN/can_sitl.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash # this script sets up SITL to be able to attach to real CAN devices # once run, you can configure SITL for CAN just like a real board, with the CAN parameters # diff --git a/Tools/scripts/CAN/can_sitl_nodev.sh b/Tools/scripts/CAN/can_sitl_nodev.sh index d31514c802f4da..8928061c3067fa 100755 --- a/Tools/scripts/CAN/can_sitl_nodev.sh +++ b/Tools/scripts/CAN/can_sitl_nodev.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash # once run, you can configure SITL for CAN just like a real board, with the CAN parameters # diff --git a/Tools/scripts/board_list.py b/Tools/scripts/board_list.py index ab92794673821a..9758a1cc800ea3 100755 --- a/Tools/scripts/board_list.py +++ b/Tools/scripts/board_list.py @@ -179,7 +179,6 @@ def find_ap_periph_boards(self): "f103-HWESC", "f103-Trigger", "G4-ESC", - "HerePro", ] ret = [] for x in self.boards: diff --git a/Tools/scripts/build-jsbsim.sh b/Tools/scripts/build-jsbsim.sh index 9e84927015e76d..a1381949557843 100755 --- a/Tools/scripts/build-jsbsim.sh +++ b/Tools/scripts/build-jsbsim.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash set -e set -x diff --git a/Tools/scripts/build_all.sh b/Tools/scripts/build_all.sh index 5a3eaf84130a1c..590c115305b7d5 100755 --- a/Tools/scripts/build_all.sh +++ b/Tools/scripts/build_all.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash # useful script to test all the different build types that we support. # This helps when doing large merges # Andrew Tridgell, November 2011 diff --git a/Tools/scripts/build_appveyor.sh b/Tools/scripts/build_appveyor.sh index 23de34276522e3..d392bbe4e041db 100755 --- a/Tools/scripts/build_appveyor.sh +++ b/Tools/scripts/build_appveyor.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash # script to build 32 bit cygwin binaries for SITL export PATH="/usr/local/bin:/usr/bin:/bin" diff --git a/Tools/scripts/build_autotest.sh b/Tools/scripts/build_autotest.sh index 53bd889e5a5ff9..8b42e0a3c0ec08 100755 --- a/Tools/scripts/build_autotest.sh +++ b/Tools/scripts/build_autotest.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash export PATH=$HOME/.local/bin:/usr/local/bin:$HOME/prefix/bin:$HOME/gcc/active/bin:$PATH export PYTHONUNBUFFERED=1 diff --git a/Tools/scripts/build_ci.sh b/Tools/scripts/build_ci.sh index 4dbc66c4bff61b..75a42b516c6bbe 100755 --- a/Tools/scripts/build_ci.sh +++ b/Tools/scripts/build_ci.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash # useful script to test all the different build types that we support. # This helps when doing large merges # Andrew Tridgell, November 2011 @@ -215,18 +215,10 @@ for t in $CI_BUILD_TARGET; do $waf configure --board f303-Universal $waf clean $waf AP_Periph - echo "Building HerePro peripheral fw" - $waf configure --board HerePro - $waf clean - $waf AP_Periph echo "Building CubeOrange-periph peripheral fw" $waf configure --board CubeOrange-periph $waf clean $waf AP_Periph - echo "Building HerePro bootloader" - $waf configure --board HerePro --bootloader - $waf clean - $waf bootloader echo "Building G4-ESC peripheral fw" $waf configure --board G4-ESC $waf clean diff --git a/Tools/scripts/build_docs.sh b/Tools/scripts/build_docs.sh index acc4899a954e24..9c183e5d9866e9 100755 --- a/Tools/scripts/build_docs.sh +++ b/Tools/scripts/build_docs.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash set -e diff --git a/Tools/scripts/build_examples.sh b/Tools/scripts/build_examples.sh index 5543f0ad16e763..127754df830e64 100755 --- a/Tools/scripts/build_examples.sh +++ b/Tools/scripts/build_examples.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash set -e diff --git a/Tools/scripts/build_log_message_documentation.sh b/Tools/scripts/build_log_message_documentation.sh index 1ec04d08f93566..14bdcbd69f608c 100755 --- a/Tools/scripts/build_log_message_documentation.sh +++ b/Tools/scripts/build_log_message_documentation.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash set -e set -x diff --git a/Tools/scripts/build_parameters.sh b/Tools/scripts/build_parameters.sh index b0ee979a6a6cb0..50c01e53bb3cf7 100755 --- a/Tools/scripts/build_parameters.sh +++ b/Tools/scripts/build_parameters.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash set -e set -x diff --git a/Tools/scripts/configure-ci.sh b/Tools/scripts/configure-ci.sh index a547b729fce176..207ee51959d9fa 100755 --- a/Tools/scripts/configure-ci.sh +++ b/Tools/scripts/configure-ci.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash # Install dependencies and configure the environment for CI build testing set -ex diff --git a/Tools/scripts/cygwin_build.sh b/Tools/scripts/cygwin_build.sh index 7761bd5ae32cee..8c8228df90afa5 100755 --- a/Tools/scripts/cygwin_build.sh +++ b/Tools/scripts/cygwin_build.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash # script to build cygwin binaries for using in MissionPlanner # the contents of artifacts directory is uploaded to: @@ -7,6 +7,7 @@ # the script assumes you start in the root of the ardupilot git tree set -x +set -e # TOOLCHAIN=i686-pc-cygwin TOOLCHAIN=x86_64-pc-cygwin @@ -22,13 +23,16 @@ git config --global --add safe.directory /cygdrive/d/a/ardupilot/ardupilot rm -rf artifacts mkdir artifacts +# cygwin doesn't work out the parallelism properly +WAF_OPTIONS="-j8" + ( python ./waf --color yes --toolchain $TOOLCHAIN --board sitl configure 2>&1 - python ./waf plane 2>&1 - python ./waf copter 2>&1 - python ./waf heli 2>&1 - python ./waf rover 2>&1 - python ./waf sub 2>&1 + python ./waf plane $WAF_OPTIONS 2>&1 + python ./waf copter $WAF_OPTIONS 2>&1 + python ./waf heli $WAF_OPTIONS 2>&1 + python ./waf rover $WAF_OPTIONS 2>&1 + python ./waf sub $WAF_OPTIONS 2>&1 ) | tee artifacts/build.txt # copy both with exe and without to cope with differences diff --git a/Tools/scripts/esp32_get_idf.sh b/Tools/scripts/esp32_get_idf.sh index 4ad61e15e9d360..f7e8318b472fd3 100755 --- a/Tools/scripts/esp32_get_idf.sh +++ b/Tools/scripts/esp32_get_idf.sh @@ -1,5 +1,4 @@ -#!/bin/bash - +#!/usr/bin/env bash # if you have modules/esp_idf setup as a submodule, then leave it as a submodule and switch branches if [ ! -d modules ]; then echo "this script needs to be run from the root of your repo, sorry, giving up." @@ -60,4 +59,4 @@ git submodule update --init --recursive cd ../.. echo "after changing IDF versions [ such as between 4.2 and 4.4 ] you should re-run these in your console:" echo "./modules/esp_idf/install.sh" -echo "source ./modules/esp_idf/export.sh" \ No newline at end of file +echo "source ./modules/esp_idf/export.sh" diff --git a/Tools/scripts/fix_libraries_includes.sh b/Tools/scripts/fix_libraries_includes.sh index 8e3ac17f53e1a1..171fa598dab05f 100755 --- a/Tools/scripts/fix_libraries_includes.sh +++ b/Tools/scripts/fix_libraries_includes.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash src=$(realpath $(dirname $BASH_SOURCE)/../../) base=$src/libraries diff --git a/Tools/scripts/format.sh b/Tools/scripts/format.sh index cef831de596d4f..4ad18ba18cdfd3 100755 --- a/Tools/scripts/format.sh +++ b/Tools/scripts/format.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash function format { DIR=$1 find $DIR -regex ".*\.\(h\|cpp\|pde\)" -exec astyle {} \; diff --git a/Tools/scripts/macos_remote_upload.sh b/Tools/scripts/macos_remote_upload.sh index 2d27eabeb4df84..399d39929b1e02 100755 --- a/Tools/scripts/macos_remote_upload.sh +++ b/Tools/scripts/macos_remote_upload.sh @@ -14,4 +14,4 @@ ssh $USER_HOST /bin/bash << ENDSSH source ~/.bash_profile $tmpdir/uploader.py $tmpdir/$filename rm -r $tmpdir -ENDSSH \ No newline at end of file +ENDSSH diff --git a/Tools/scripts/run_luacheck.sh b/Tools/scripts/run_luacheck.sh index 43e0af5d0e9275..7b613634fb3ed1 100755 --- a/Tools/scripts/run_luacheck.sh +++ b/Tools/scripts/run_luacheck.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash # Run lua check for all lua files passing AP specific config # Can also pass any number of arguments that are passed onto luacheck # for example the path of a single script could be given diff --git a/Tools/scripts/unpack_mp.sh b/Tools/scripts/unpack_mp.sh index 3719836f67f79c..b75966e7b90d4f 100755 --- a/Tools/scripts/unpack_mp.sh +++ b/Tools/scripts/unpack_mp.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash # unpack latest MissionPlanner*.zip on firmware.ardupilot.org # to facilitate upgrade of existing MissionPlanner installs diff --git a/Tools/vagrant/initvagrant-desktop.sh b/Tools/vagrant/initvagrant-desktop.sh index 702c78d5b08753..f9299044e04e27 100755 --- a/Tools/vagrant/initvagrant-desktop.sh +++ b/Tools/vagrant/initvagrant-desktop.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash echo "---------- $0 start ----------" set -e diff --git a/Tools/vagrant/initvagrant-trusty64.sh b/Tools/vagrant/initvagrant-trusty64.sh index e820d91ad0d7b3..318be2cb94ac95 100755 --- a/Tools/vagrant/initvagrant-trusty64.sh +++ b/Tools/vagrant/initvagrant-trusty64.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash # this script is run by the root user in the virtual machine diff --git a/Tools/vagrant/initvagrant.sh b/Tools/vagrant/initvagrant.sh index 08bd7d81c3b0a4..acb0f482819d96 100755 --- a/Tools/vagrant/initvagrant.sh +++ b/Tools/vagrant/initvagrant.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash echo "---------- $0 start ----------" # this script is run by the root user in the virtual machine diff --git a/docs/build-apmrover2.sh b/docs/build-apmrover2.sh index 0bb15a95371af8..d3180ffb76c459 100755 --- a/docs/build-apmrover2.sh +++ b/docs/build-apmrover2.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )" cd $DIR/.. diff --git a/docs/build-arducopter.sh b/docs/build-arducopter.sh index ef8dd9e13f0c59..67db80ca2cc775 100755 --- a/docs/build-arducopter.sh +++ b/docs/build-arducopter.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )" cd $DIR/.. diff --git a/docs/build-arduplane.sh b/docs/build-arduplane.sh index 125d4302882807..35ccddd35d4733 100755 --- a/docs/build-arduplane.sh +++ b/docs/build-arduplane.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )" cd $DIR/.. diff --git a/docs/build-ardusub.sh b/docs/build-ardusub.sh index b34490428c7ed3..eed18f8ee64b7e 100755 --- a/docs/build-ardusub.sh +++ b/docs/build-ardusub.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )" cd $DIR/.. diff --git a/docs/build-libs.sh b/docs/build-libs.sh index 0a843a5427a3dc..9d796bdd391954 100755 --- a/docs/build-libs.sh +++ b/docs/build-libs.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )" cd $DIR/.. diff --git a/libraries/AC_Fence/AC_Fence.cpp b/libraries/AC_Fence/AC_Fence.cpp index ac9d7f50a031ab..c1e3b4cebb56b4 100644 --- a/libraries/AC_Fence/AC_Fence.cpp +++ b/libraries/AC_Fence/AC_Fence.cpp @@ -205,6 +205,9 @@ void AC_Fence::disable_floor() */ void AC_Fence::auto_enable_fence_after_takeoff(void) { + if (_enabled) { + return; + } switch(auto_enabled()) { case AC_Fence::AutoEnable::ALWAYS_ENABLED: case AC_Fence::AutoEnable::ENABLE_DISABLE_FLOOR_ONLY: diff --git a/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp b/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp index a4138916877693..f0f240dbf4eb68 100644 --- a/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp +++ b/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp @@ -20,8 +20,6 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL(); static AP_SerialManager serial_manager; -AP_Int32 logger_bitmask; -static AP_Logger logger{logger_bitmask}; class DummyVehicle : public AP_Vehicle { public: @@ -36,7 +34,17 @@ class DummyVehicle : public AP_Vehicle { ins.init(100); ahrs.init(); } + AP_Int32 unused_log_bitmask; + struct LogStructure log_structure[1] = { + }; + const AP_Int32 &get_log_bitmask() override { return unused_log_bitmask; } + const struct LogStructure *get_log_structures() const override { + return log_structure; + } + uint8_t get_num_log_structures() const override { + return 0; + } }; static DummyVehicle vehicle; diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Scripting.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Scripting.cpp index 337c9d9b7ac2c1..e7b846258dd4fb 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Scripting.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Scripting.cpp @@ -1,7 +1,9 @@ -#include "AP_BattMonitor_Scripting.h" +#include "AP_BattMonitor_config.h" #if AP_BATTERY_SCRIPTING_ENABLED +#include "AP_BattMonitor_Scripting.h" + #define AP_BATT_MONITOR_SCRIPTING_TIMEOUT_US 5000000 bool AP_BattMonitor_Scripting::capacity_remaining_pct(uint8_t &percentage) const @@ -81,4 +83,3 @@ bool AP_BattMonitor_Scripting::handle_scripting(const BattMonitorScript_State &b } #endif // AP_BATTERY_SCRIPTING_ENABLED - diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Scripting.h b/libraries/AP_BattMonitor/AP_BattMonitor_Scripting.h index f68f11b9dceb5b..382437d0aa55ea 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Scripting.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Scripting.h @@ -1,9 +1,11 @@ #pragma once -#include "AP_BattMonitor_Backend.h" +#include "AP_BattMonitor_config.h" #if AP_BATTERY_SCRIPTING_ENABLED +#include "AP_BattMonitor_Backend.h" + class AP_BattMonitor_Scripting : public AP_BattMonitor_Backend { public: @@ -28,5 +30,4 @@ class AP_BattMonitor_Scripting : public AP_BattMonitor_Backend HAL_Semaphore sem; }; -#endif // AP_BATTMONITOR_SCRIPTING_ENABLED - +#endif // AP_BATTERY_SCRIPTING_ENABLED diff --git a/libraries/AP_Camera/AP_Camera_Backend.cpp b/libraries/AP_Camera/AP_Camera_Backend.cpp index 4781c4180721a9..fafe4546aa2535 100644 --- a/libraries/AP_Camera/AP_Camera_Backend.cpp +++ b/libraries/AP_Camera/AP_Camera_Backend.cpp @@ -17,11 +17,13 @@ AP_Camera_Backend::AP_Camera_Backend(AP_Camera &frontend, AP_Camera_Params ¶ // update - should be called at 50hz void AP_Camera_Backend::update() { - // Check CAMx_OPTIONS and start/stop recording based on arm/disarm - if (_params.options.get() & CAMOPTIONS::REC_ARM_DISARM) { + // Check camera options and start/stop recording based on arm/disarm + if ((_params.options.get() & (uint8_t)Options::RecordWhileArmed) != 0) { if (hal.util->get_soft_armed() != last_is_armed) { last_is_armed = hal.util->get_soft_armed(); - record_video(last_is_armed); + if (!record_video(last_is_armed)) { + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Camera: failed to %s recording", last_is_armed ? "start" : "stop"); + } } } diff --git a/libraries/AP_Camera/AP_Camera_Backend.h b/libraries/AP_Camera/AP_Camera_Backend.h index a6b4c8a60a3200..b60e06d4dcd142 100644 --- a/libraries/AP_Camera/AP_Camera_Backend.h +++ b/libraries/AP_Camera/AP_Camera_Backend.h @@ -36,8 +36,9 @@ class AP_Camera_Backend /* Do not allow copies */ CLASS_NO_COPY(AP_Camera_Backend); - enum CAMOPTIONS { - REC_ARM_DISARM = 0, // Recording start/stop on Arm/Disarm + // camera options parameter values + enum class Options : int8_t { + RecordWhileArmed = (1 << 0U) }; // init - performs any required initialisation diff --git a/libraries/AP_Compass/Compass_learn.cpp b/libraries/AP_Compass/Compass_learn.cpp index 12861e3fe29ca3..f39933f1fe928a 100644 --- a/libraries/AP_Compass/Compass_learn.cpp +++ b/libraries/AP_Compass/Compass_learn.cpp @@ -9,6 +9,8 @@ #if COMPASS_LEARN_ENABLED +#include + extern const AP_HAL::HAL &hal; // constructor diff --git a/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp b/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp index 1164d4f7346c5d..12262859c53a0b 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp +++ b/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp @@ -448,6 +448,7 @@ void AP_DroneCAN_DNA_Server::handleNodeInfo(const CanardRxTransfer& transfer, co // @LoggerMessage: CAND // @Description: Info from GetNodeInfo request // @Field: TimeUS: Time since system startup + // @Field: Driver: Driver index // @Field: NodeId: Node ID // @Field: UID1: Hardware ID, part 1 // @Field: UID2: Hardware ID, part 2 @@ -455,9 +456,10 @@ void AP_DroneCAN_DNA_Server::handleNodeInfo(const CanardRxTransfer& transfer, co // @Field: Major: major revision id // @Field: Minor: minor revision id // @Field: Version: AP_Periph git hash - AP::logger().Write("CAND", "TimeUS,NodeId,UID1,UID2,Name,Major,Minor,Version", - "s#------", "F-------", "QBQQZBBI", + AP::logger().Write("CAND", "TimeUS,Driver,NodeId,UID1,UID2,Name,Major,Minor,Version", + "s-#------", "F--------", "QBBQQZBBI", AP_HAL::micros64(), + _ap_dronecan.get_driver_index(), transfer.source_node_id, uid[0], uid[1], rsp.name.data, diff --git a/libraries/AP_Filesystem/AP_Filesystem.cpp b/libraries/AP_Filesystem/AP_Filesystem.cpp index e62ec5920827c3..564696bb979045 100644 --- a/libraries/AP_Filesystem/AP_Filesystem.cpp +++ b/libraries/AP_Filesystem/AP_Filesystem.cpp @@ -290,6 +290,9 @@ bool AP_Filesystem::fgets(char *buf, uint8_t buflen, int fd) // run crc32 over file with given name, returns true if successful bool AP_Filesystem::crc32(const char *fname, uint32_t& checksum) { + // Ensure value is initialized + checksum = 0; + // Open file in readonly mode int fd = open(fname, O_RDONLY); if (fd == -1) { diff --git a/libraries/AP_GyroFFT/examples/ReplayGyroFFT/ReplayGyroFFT.cpp b/libraries/AP_GyroFFT/examples/ReplayGyroFFT/ReplayGyroFFT.cpp index 70b74f42283dd0..c607c88c53dfdc 100644 --- a/libraries/AP_GyroFFT/examples/ReplayGyroFFT/ReplayGyroFFT.cpp +++ b/libraries/AP_GyroFFT/examples/ReplayGyroFFT/ReplayGyroFFT.cpp @@ -29,7 +29,7 @@ static AP_BoardConfig board_config; static AP_InertialSensor ins; static AP_Baro baro; AP_Int32 logger_bitmask; -static AP_Logger logger{logger_bitmask}; +static AP_Logger logger; #if HAL_EXTERNAL_AHRS_ENABLED static AP_ExternalAHRS external_ahrs; #endif @@ -123,7 +123,7 @@ void setup() sitl.gyro_file_rw.set(SITL::SIM::INSFileMode::INS_FILE_READ_STOP_ON_EOF); // SIM_GYR_FILE_RW } logger_bitmask.set(128); // IMU - logger.Init(log_structure, ARRAY_SIZE(log_structure)); + logger.init(logger_bitmask, log_structure, ARRAY_SIZE(log_structure)); ins.init(LOOP_RATE_HZ); baro.init(); diff --git a/libraries/AP_HAL/examples/DSP_test/DSP_test.cpp b/libraries/AP_HAL/examples/DSP_test/DSP_test.cpp index f40e0653bc621e..23e079f23ead8c 100644 --- a/libraries/AP_HAL/examples/DSP_test/DSP_test.cpp +++ b/libraries/AP_HAL/examples/DSP_test/DSP_test.cpp @@ -32,7 +32,7 @@ static AP_SerialManager serial_manager; static AP_BoardConfig board_config; static AP_InertialSensor ins; AP_Int32 logger_bitmask; -static AP_Logger logger{logger_bitmask}; +static AP_Logger logger; class DummyVehicle { public: diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HerePro/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/HerePro/defaults.parm deleted file mode 100644 index 16b4cd021aa557..00000000000000 --- a/libraries/AP_HAL_ChibiOS/hwdef/HerePro/defaults.parm +++ /dev/null @@ -1,3 +0,0 @@ -NTF_LED_OVERRIDE 1 -SCR_ENABLE 1 -GPS_INJECT_TO 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef-bl.dat deleted file mode 100644 index 5f8cffae714cd1..00000000000000 --- a/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef-bl.dat +++ /dev/null @@ -1,147 +0,0 @@ -# hw definition file for processing by chibios_hwdef.py -# for H743 bootloader - -# MCU class and specific type -MCU STM32H7xx STM32H743xx - -FULL_FEATURED_BOOTLOADER 1 - -# USB setup -USB_VENDOR 0x2DAE # ONLY FOR USE BY HEX! NOBODY ELSE -USB_PRODUCT 0x5011 -USB_STRING_MANUFACTURER "CubePilot" - -# setup build for a peripheral firmware -env AP_PERIPH 1 - -# crystal frequency -OSCILLATOR_HZ 24000000 - -# board ID for firmware load -APJ_BOARD_ID 1037 - -FLASH_SIZE_KB 2048 - -# bootloader is installed at zero offset -FLASH_RESERVE_START_KB 0 - -# the location where the bootloader will put the firmware -# the H743 has 128k sectors -FLASH_BOOTLOADER_LOAD_KB 256 - -PB15 LED_2 OUTPUT LOW -PB14 LED OUTPUT LOW - -# board voltage -STM32_VDD 330U - -# order of UARTs (and USB) -SERIAL_ORDER OTG1 UART7 - -define HAL_NO_MONITOR_THREAD - -# USART3 F9 -PD9 USART3_RX USART3 -PD8 USART3_TX USART3 - -# UART7 F9 -PE7 UART7_RX UART7 -PE8 UART7_TX UART7 NODMA - - -PA11 OTG_FS_DM OTG1 -PA12 OTG_FS_DP OTG1 - -PA13 JTMS-SWDIO SWD -PA14 JTCK-SWCLK SWD - - -define USB_USE_WAIT TRUE -define HAL_USE_USB_MSD 1 - -define HAL_DEVICE_THREAD_STACK 2048 - -#define AP_PARAM_MAX_EMBEDDED_PARAM 0 - -define HAL_BARO_ALLOW_INIT_NO_BARO - -define HAL_COMPASS_MAX_SENSORS 1 - -# GPS+MAG -define HAL_PERIPH_ENABLE_GPS -define HAL_PERIPH_ENABLE_MAG - -# Add MAVLink -env FORCE_MAVLINK_INCLUDE 1 - -# enable CAN support -PB8 CAN1_RX CAN1 -PB9 CAN1_TX CAN1 -PB5 CAN2_RX CAN2 -PB6 CAN2_TX CAN2 -#PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW - -PF8 blank CS -SPIDEV profiled SPI5 DEVID1 blank MODE3 1*MHZ 1*MHZ - -PE4 MPU_EXT_CS CS -PE2 SPI4_SCK SPI4 -PE5 SPI4_MISO SPI4 -PE6 SPI4_MOSI SPI4 - - -PG15 spi6cs CS -PG13 SPI6_SCK SPI6 -PG12 SPI6_MISO SPI6 -PG14 SPI6_MOSI SPI6 - -PF7 SPI5_SCK SPI5 -PF9 SPI5_MOSI SPI5 - -define BOARD_SER1_RTSCTS_DEFAULT 0 - -#gps f9 -PD10 F91TXR INPUT -PD11 F92RST INPUT -PD13 F93SB INPUT -PD14 F94EXTINT INPUT -PD15 F95RSV1 INPUT -PG2 F97 INPUT GPIO(100) -PG3 F96RSV2 INPUT -PD4 RTKSTAT INPUT -PD5 GEOFENCESTAT INPUT - -#others -PG10 can2int INPUT -PG11 can2sleep OUTPUT PUSHPULL SPEED_LOW LOW -PF1 GNDDET2 INPUT -PF2 GNDDET1 INPUT -PC6 EXTERN_GPIO1 OUTPUT GPIO(1) -PC7 EXTERN_GPIO2 OUTPUT GPIO(2) -#sensor enable -PC0 SENSEN OUTPUT HIGH -PB1 IMUINT INPUT -PB3 QCAN2TERM OUTPUT LOW GPIO(4) -PB4 QCAN2INT0 INPUT -PC13 QCAN1SLEEP OUTPUT PUSHPULL SPEED_LOW LOW -PE0 QCAN1INT INPUT -PE1 QCAN1INT0 INPUT -PE3 QCAN1INT1 INPUT - -PD6 QCAN1TERM OUTPUT LOW GPIO(3) -PD7 QCAN2INT1 INPUT -PA8 QCAN12OSC1 INPUT - -# This input pin is used to detect that power is valid on USB. -PA9 VBUS INPUT -PH13 VDD_33V_SENS INPUT - -# This defines some input pins, currently unused. -PB2 BOOT1 INPUT - - - -# passthrough CAN1 -define HAL_DEFAULT_CPORT 1 - -FULL_CHIBIOS_BOOTLOADER 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef.dat deleted file mode 100644 index 0c8c2b46a8174d..00000000000000 --- a/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef.dat +++ /dev/null @@ -1,221 +0,0 @@ -# hw definition file for processing by chibios_hwdef.py -# for H743 bootloader - -# MCU class and specific type -MCU STM32H7xx STM32H743xx - -# USB setup -USB_VENDOR 0x2DAE # ONLY FOR USE BY HEX! NOBODY ELSE -USB_PRODUCT 0x5001 -USB_STRING_MANUFACTURER "CubePilot" - -# setup build for a peripheral firmware -env AP_PERIPH 1 -env AP_PERIPH_HEAVY 1 - -# crystal frequency -OSCILLATOR_HZ 24000000 - -# board ID for firmware load -APJ_BOARD_ID 1037 - -FLASH_SIZE_KB 2048 - -# the location where the bootloader will put the firmware -# the H743 has 128k sectors, we leave 2 sectors for BL -FLASH_BOOTLOADER_LOAD_KB 256 - -PB15 LED_SWITCH_2 OUTPUT HIGH -PB14 LED_SWITCH_1 OUTPUT HIGH - -# board voltage -STM32_VDD 330U - -# order of UARTs (and USB) -SERIAL_ORDER OTG1 OTG2 EMPTY USART3 UART7 - -define DEFAULT_SERIAL0_PROTOCOL SerialProtocol_None - -# USART3 F9 -PD9 USART3_RX USART3 -PD8 USART3_TX USART3 - -# UART7 F9 -PE7 UART7_RX UART7 -PE8 UART7_TX UART7 NODMA - - -PA11 OTG_FS_DM OTG1 -PA12 OTG_FS_DP OTG1 - -PA13 JTMS-SWDIO SWD -PA14 JTCK-SWCLK SWD - -########################### -define AP_NOTIFY_PROFILED_SPI_ENABLED 1 -define DEFAULT_NTF_LED_TYPES Notify_LED_ProfiLED_SPI -define NOTIFY_LED_LEN_DEFAULT 16 -define CONFIGURE_PPS_PIN TRUE -define HAL_PERIPH_ENABLE_NOTIFY -define HAL_PERIPH_NOTIFY_WITHOUT_RCOUT - -FLASH_RESERVE_START_KB 256 - -define GPS_UBLOX_MOVING_BASELINE TRUE -define HAL_GCS_ENABLED 1 -define HAL_LOGGING_ENABLED TRUE -define HAL_PERIPH_ENABLE_RTC 1 -define HAL_NO_MONITOR_THREAD - - -define HAL_DISABLE_LOOP_DELAY -define USB_USE_WAIT TRUE -define HAL_USE_USB_MSD 1 - - -define HAL_DEVICE_THREAD_STACK 2048 - -#define AP_PARAM_MAX_EMBEDDED_PARAM 0 - -define HAL_BARO_ALLOW_INIT_NO_BARO - -define HAL_STORAGE_SIZE 16384 - -# disable dual GPS and GPS blending to save flash space -define GPS_MAX_RECEIVERS 1 -define GPS_MAX_INSTANCES 1 -define HAL_COMPASS_MAX_SENSORS 1 - -# GPS+MAG -define HAL_PERIPH_ENABLE_AHRS -define HAL_PERIPH_ENABLE_GPS -define HAL_PERIPH_ENABLE_MAG -define AP_INERTIALSENSOR_ENABLED 1 - - -# enable CAN support -PB8 CAN1_RX CAN1 -PB9 CAN1_TX CAN1 -PB5 CAN2_RX CAN2 -PB6 CAN2_TX CAN2 - -PA4 MPU_CS CS -PA5 SPI1_SCK SPI1 -PA6 SPI1_MISO SPI1 -PA7 SPI1_MOSI SPI1 -SPIDEV icm20948 SPI1 DEVID4 MPU_CS MODE3 4*MHZ 8*MHZ - -PF8 blank CS -SPIDEV profiled SPI5 DEVID1 blank MODE3 1*MHZ 1*MHZ - -IMU Invensensev2 SPI:icm20948 ROTATION_YAW_270 - -define HAL_DEFAULT_INS_FAST_SAMPLE 5 - -# compass as part of ICM20948 on newer cubes -COMPASS AK09916:probe_ICM20948 0 ROTATION_ROLL_180_YAW_90 - -# one baro -#BARO MS56XX I2C:0:0x77 - -PE4 CSPI4_CS CS -PE2 SPI4_SCK SPI4 -PE5 SPI4_MISO SPI4 -PE6 SPI4_MOSI SPI4 - - -PG15 CSPI6_CS CS -PG13 SPI6_SCK SPI6 -PG12 SPI6_MISO SPI6 -PG14 SPI6_MOSI SPI6 - -PF7 SPI5_SCK SPI5 -PF9 SPI5_MOSI SPI5 - -# Now setup the pins for the microSD card, if available. -PC8 SDMMC1_D0 SDMMC1 -PC9 SDMMC1_D1 SDMMC1 -PC10 SDMMC1_D2 SDMMC1 -PC11 SDMMC1_D3 SDMMC1 -PC12 SDMMC1_CK SDMMC1 -PD2 SDMMC1_CMD SDMMC1 - -define BOARD_SER1_RTSCTS_DEFAULT 0 - -define HAL_OS_FATFS_IO 1 -define HAL_WITH_DRONECAN 1 -env HAL_WITH_DRONECAN 1 -define HAL_PICCOLO_CAN_ENABLE 0 -define AP_CAN_SLCAN_ENABLED 1 - -PA1 ANALOG_CAN_VOLTAGE1 ADC1 SCALE(21.404) -PA2 ANALOG_CAN_VOLTAGE2 ADC1 SCALE(21.404) - -#gps f9 -PD10 F91TXR INPUT -PD11 F92RST INPUT -PD13 F93SB INPUT -PD14 F94EXTINT INPUT -PD15 F95RSV1 INPUT -PG2 F97 INPUT GPIO(100) -PG3 F96RSV2 INPUT -PD4 RTKSTAT INPUT -PD5 GEOFENCESTAT INPUT - -#others -PG10 can2int INPUT -PG11 can2sleep OUTPUT PUSHPULL SPEED_LOW LOW -PF1 GNDDET2 INPUT -PF2 GNDDET1 INPUT -PC6 EXTERN_GPIO1 OUTPUT GPIO(1) -PC7 EXTERN_GPIO2 OUTPUT GPIO(2) -PD6 TERMCAN1 OUTPUT LOW GPIO(3) -PB3 TERMCAN2 OUTPUT LOW GPIO(4) - -#sensor enable -PC0 SENSEN OUTPUT HIGH -PB1 IMUINT INPUT -PB4 QCAN2INT0 INPUT -PC13 QCAN1SLEEP OUTPUT PUSHPULL SPEED_LOW LOW -PE0 QCAN1INT INPUT -PE1 QCAN1INT0 INPUT -PE3 QCAN1INT1 INPUT - -PD7 QCAN2INT1 INPUT -PA8 QCAN12OSC1 INPUT - -# This defines more ADC inputs. -PC3 ANALOG_VCC_1_8V ADC1 SCALE(2) -PC4 ANALOG_VCC_5V_PIN ADC1 SCALE(2.044) - -# This input pin is used to detect that power is valid on USB. -PA9 VBUS INPUT -PH13 VDD_33V_SENS INPUT - -# This defines some input pins, currently unused. -PB2 BOOT1 INPUT - - - -# disabled compass cal as it doesn't work for now -# define COMPASS_CAL_ENABLED 1 - -define HAL_ENABLE_SLCAN 1 -# passthrough CAN1 -define HAL_DEFAULT_CPORT 1 - -define CONFIGURE_PPS_PIN TRUE -define AP_PERIPH_HAVE_LED TRUE - -define AP_SCRIPTING_ENABLED 1 -define SCRIPTING_HEAP_SIZE (64*1024) - -define GPS_MOVING_BASELINE 1 - -define AP_RC_CHANNEL_ENABLED 1 - -define AP_RELAY_ENABLED 1 -define AP_SERVORELAYEVENTS_ENABLED 1 - -# bootloader embedding / bootloader flashing not available -define AP_BOOTLOADER_FLASHING_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HerePro/scripts/hereproled.lua b/libraries/AP_HAL_ChibiOS/hwdef/HerePro/scripts/hereproled.lua deleted file mode 100644 index 106d27e150ff42..00000000000000 --- a/libraries/AP_HAL_ChibiOS/hwdef/HerePro/scripts/hereproled.lua +++ /dev/null @@ -1,315 +0,0 @@ --- This script is a test of led override --- luacheck: only 0 - -local count = 0 -local num_leds = 16 -local total_time = 1 -local animation_end = 0 -local current_anim = 0 - --- constrain a value between limits -function constrain(v, vmin, vmax) - if v < vmin then - v = vmin - end - if v > vmax then - v = vmax - - end - return v -end - ---[[ -Table of neon colors on a rainbow, red first ---]] --- local rainbow = { --- { 252, 23, 0 }, --- { 253, 72, 37 }, --- { 250, 237, 39 }, --- { 51, 255, 20 }, --- { 27, 3, 163 } --- } - -local rainbow = { - { 252, 23, 0 }, - { 253, 100, 0 }, - { 250, 237, 0 }, - { 51, 255, 20 }, - { 27, 3, 163 } -} - -local led_map = { - 14, - 15, - 2, - 3, - 4, - 5, - 6, - 7, - 8, - 9, - 1, - 0, - 10, - 11, - 12, - 13} - -function table.contains(table, element) - for _, value in pairs(table) do - if value == element then - return true - end - end - return false -end - ---[[ -Function to set a LED to a color on a classic rainbow spectrum, with v=0 giving red ---]] -function get_Rainbow(v, num_rows) - local row = math.floor(constrain(v * (num_rows-1)+1, 1, num_rows-1)) - local v0 = (row-1) / (num_rows-1) - local v1 = row / (num_rows-1) - local p = (v - v0) / (v1 - v0) - r = math.max(math.floor(rainbow[row][1] + p * (rainbow[row+1][1] - rainbow[row][1])),0) - g = math.max(math.floor(rainbow[row][2] + p * (rainbow[row+1][2] - rainbow[row][2])),0) - b = math.max(math.floor(rainbow[row][3] + p * (rainbow[row+1][3] - rainbow[row][3])),0) - return r,g,b -end - -function do_initialisation() - local pos = math.rad(total_time/2) - local v =0.5 + 0.5 * math.sin(pos) - local invert = 1 - local r, g, b = get_Rainbow(v, 5) - local led_trail_length = 3 - local softness = 10 - local bfact = 1 - local updated_leds = {} - if math.cos(pos) > 0 then - invert = 1 - else - invert = 0 - end - - pos = math.floor(6 + (v*8))%16 - if pos == 6 then - animation_end = 1 - else - animation_end = 0 - end - - for trail = 0, led_trail_length-1 do - if invert == 1 then - bfact = softness^(2*(led_trail_length - 1 - trail)/(led_trail_length-1)) - else - bfact = softness^(2*trail/(led_trail_length-1)) - end - local led_id = 1 + ((pos + trail) % num_leds) - notify:handle_rgb_id(math.floor(r/bfact), math.floor(g/bfact), math.floor(b/bfact), led_map[led_id]) - table.insert(updated_leds, led_id) - end - - pos = math.floor(6 - (v*8))%16 - for trail = 0, led_trail_length-1 do - if invert == 0 then - bfact = softness^(2*(led_trail_length - 1 - trail)/(led_trail_length-1)) - else - bfact = softness^(2*trail/(led_trail_length-1)) - end - local led_id = 1 + ((pos + trail) % num_leds) - notify:handle_rgb_id(math.floor(r/bfact), math.floor(g/bfact), math.floor(b/bfact), led_map[led_id]) - table.insert(updated_leds, led_id) - end - - for led = 1, num_leds do - if not table.contains(updated_leds, led) then - notify:handle_rgb_id(0, 0, 0, led_map[led]) - end - end -end - -function do_point_north(r, g, b, led_trail_length, softness) - local north_bias = 4 - local yaw = 8 - ((16 * periph:get_yaw_earth()/(2*math.pi))) - north_bias - local ofs = yaw - math.floor(yaw+0.5) - yaw = math.floor(yaw+0.5) % 16 - local updated_leds = {} - for trail = 0, led_trail_length-1 do - local bfact = softness^(2*(math.abs((led_trail_length-1)/2 - trail + ofs))/(led_trail_length-1)) - local led_id = 1 + ((yaw + trail) % 16) - notify:handle_rgb_id(math.floor(r/bfact), math.floor(g/bfact), math.floor(b/bfact), led_map[led_id]) - table.insert(updated_leds, led_id) - end - - for led = 1, num_leds do - if not table.contains(updated_leds, led) then - notify:handle_rgb_id(0, 0, 0, led_map[led]) - end - end - return yaw -end - -function finish_initialisation(r, g, b, led_trail_length, softness, speed_factor, next_call) - local north_bias = 4 - local yaw = 8 - ((16 * periph:get_yaw_earth()/(2*math.pi))) - north_bias - yaw = math.floor(yaw+0.5) % 16 - local led_id = math.floor((count/speed_factor) + north_bias) % 16 - if yaw == led_id then - if total_time > 3000 then - animation_end = 1 - end - return - end - count = count + next_call - local updated_leds = {} - for trail = 0, led_trail_length-1 do - local bfact = softness^(2*(math.abs((led_trail_length-1)/2 - trail))/(led_trail_length-1)) - local this_led_id = 1 + ((led_id + trail) % 16) - notify:handle_rgb_id(math.floor(r/bfact), math.floor(g/bfact), math.floor(b/bfact), led_map[this_led_id]) - table.insert(updated_leds, this_led_id) - end - - for led = 1, num_leds do - if not table.contains(updated_leds, led) then - notify:handle_rgb_id(0, 0, 0, led_map[led]) - end - end -end - -function do_arm_spin(r, g, b, softness, speed_factor, arming) - -- reset led states - local updated_leds = {} - - -- calculate next call based on time - local next_call = 1 - if arming then - next_call = speed_factor - math.floor(((total_time)/speed_factor) + 0.5) - if next_call < 1 then - return next_call - end - else - next_call = 1 + math.floor(((total_time)/speed_factor) + 0.5) - if next_call > speed_factor then - return next_call - end - end - -- set trail length bassed on spin progress - local led_trail_length = 3 + (13 * (1 - (next_call/75))) - - - -- create a trail - for trail = 0, led_trail_length-1 do - local bfact = softness^(led_trail_length - trail) - local led_id = 1 + (count + trail) % 16 - notify:handle_rgb_id(math.floor(r/bfact), math.floor(g/bfact), math.floor(b/bfact), led_map[led_id]) - table.insert(updated_leds, led_id) - end - - for led = 1, num_leds do - if not table.contains(updated_leds, led) then - notify:handle_rgb_id(0, 0, 0, led_map[led]) - end - end - return next_call -end - -function set_all(r, g, b) - for led = 1, num_leds do - notify:handle_rgb_id(r, g, b, led_map[led]) - end -end - -function animation_state_machine(vehicle_state) - -- change state only when last loop finished - if animation_end == 0 then - return - end - - if ((vehicle_state & 1) == uint32_t(1)) then - -- do_initialisation - if current_anim ~= 0 then - current_anim = 0 - total_time = 0 - animation_end = 0 - end - elseif current_anim == 0 then - -- do finish by move to north - count = 0 - total_time = 0 - current_anim = 1 - animation_end = 0 - elseif current_anim == 1 then - -- do always point north - current_anim = 2 - elseif current_anim ~= 3 and ((vehicle_state & (1 << 1)) ~= uint32_t(0)) then --VEHICLE_STATE_ARMED - total_time = 0 - current_anim = 3 - animation_end = 0 - elseif current_anim == 3 and ((vehicle_state & (1 << 1)) == uint32_t(0)) then - total_time = 0 - current_anim = 4 - animation_end = 0 - elseif current_anim == 4 then - current_anim = 1 - end -end - -function update() -- this is the loop which periodically runs - local next_call = 20 - local vehicle_state = periph:get_vehicle_state() - animation_state_machine(vehicle_state) - - -- Initialisation - if current_anim == 0 then - do_initialisation() - total_time = total_time + next_call - elseif current_anim == 1 then - finish_initialisation(rainbow[1][1], rainbow[1][2], rainbow[1][3], 5, 20, 50, next_call) - total_time = total_time + next_call - elseif current_anim == 2 then - local v - if (vehicle_state & (1<<3)) ~= uint32_t(0) or --VEHICLE_STATE_PREARM - (vehicle_state & (1<<4)) ~= uint32_t(0) or --VEHICLE_STATE_PREARM_GPS - (vehicle_state & (1<<7)) ~= uint32_t(0) or --VEHICLE_STATE_FAILSAFE_RADIO - (vehicle_state & (1<<8)) ~= uint32_t(0) or --VEHICLE_STATE_FAILSAFE_BATT - (vehicle_state & (1<<11)) ~= uint32_t(0) then --VEHICLE_STATE_EKF_BAD - v = 0.0 - end - if (vehicle_state & (1<<17)) == uint32_t(0) then--VEHICLE_STATE_POS_ABS_AVAIL - v = 0.5 + (0.5 * math.min(gps:num_sats(0)/20, 1.0)) - else - v = 1.0 - end - local r, g, b = get_Rainbow(v, 4) - count = do_point_north(r, g, b, 5, 20) - -- --[[ ARM Display - elseif current_anim == 3 then - if animation_end == 0 then - next_call = do_arm_spin(rainbow[4][1], rainbow[4][2], rainbow[4][3], 2, 75, true) - count = count + 1 - end - if next_call < 1 then - set_all(rainbow[4][1], rainbow[4][2], rainbow[4][3]) - animation_end = 1 - else - total_time = total_time + next_call - end - elseif current_anim == 4 then - if animation_end == 0 then - next_call = do_arm_spin(rainbow[4][1], rainbow[4][2], rainbow[4][3], 2, 75, false) - count = count - 1 - end - if next_call > 75 then - animation_end = 1 - else - total_time = total_time + next_call - end - end - -- gcs:send_text(0, string.format("NCALL: %s", tostring(next_call))) - return update, next_call -- reschedules the loop in next_call milliseconds -end - -return update() -- run immediately before starting to reschedule \ No newline at end of file diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h b/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h index c2f75d230642fc..136987f000d948 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h @@ -325,7 +325,7 @@ #define AP_AHRS_ENABLED defined(HAL_PERIPH_ENABLE_AHRS) #define AP_COMPASS_ENABLED defined(HAL_PERIPH_ENABLE_MAG) #define AP_BARO_ENABLED defined(HAL_PERIPH_ENABLE_BARO) -#define AP_GPS_ENABLED 1 // FIXME: should be defined(HAL_PERIPH_ENABLE_GPS) +#define AP_GPS_ENABLED defined(HAL_PERIPH_ENABLE_GPS) #define AP_RPM_ENABLED defined(HAL_PERIPH_ENABLE_RPM) #define AP_RCPROTOCOL_ENABLED defined(HAL_PERIPH_ENABLE_RCIN) #define AP_RTC_ENABLED defined(HAL_PERIPH_ENABLE_RTC) @@ -400,3 +400,43 @@ #ifndef AP_FILTER_ENABLED #define AP_FILTER_ENABLED 0 #endif + +#ifndef AP_ADVANCEDFAILSAFE_ENABLED +#define AP_ADVANCEDFAILSAFE_ENABLED 0 +#endif + +#ifndef AP_ARMING_ENABLED +#define AP_ARMING_ENABLED 0 +#endif + +#ifndef AP_LTM_TELEM_ENABLED +#define AP_LTM_TELEM_ENABLED 0 +#endif + +#ifndef AP_GRIPPER_ENABLED +#define AP_GRIPPER_ENABLED 0 +#endif + +#ifndef HAL_SPRAYER_ENABLED +#define HAL_SPRAYER_ENABLED 0 +#endif + +#ifndef AP_VEHICLE_ENABLED +#define AP_VEHICLE_ENABLED 0 +#endif + +#ifndef OSD_ENABLED +#define OSD_ENABLED 0 +#endif + +#ifndef OSD_PARAM_ENABLED +#define OSD_PARAM_ENABLED 0 +#endif + +#ifndef AP_SCHEDULER_ENABLED +#define AP_SCHEDULER_ENABLED 0 +#endif + +#ifndef AP_RC_CHANNEL_ENABLED +#define AP_RC_CHANNEL_ENABLED 0 +#endif diff --git a/libraries/AP_InertialSensor/examples/INS_generic/INS_generic.cpp b/libraries/AP_InertialSensor/examples/INS_generic/INS_generic.cpp index 1856e6f801ed9b..b5c8ad97fea719 100644 --- a/libraries/AP_InertialSensor/examples/INS_generic/INS_generic.cpp +++ b/libraries/AP_InertialSensor/examples/INS_generic/INS_generic.cpp @@ -22,7 +22,7 @@ static void run_test(); // board specific config static AP_BoardConfig BoardConfig; static AP_Int32 log_bitmask; -static AP_Logger logger{log_bitmask}; +static AP_Logger logger; void setup(void); void loop(void); diff --git a/libraries/AP_Logger/AP_Logger.cpp b/libraries/AP_Logger/AP_Logger.cpp index fb55e52f4ddeb5..5477e5b7516afe 100644 --- a/libraries/AP_Logger/AP_Logger.cpp +++ b/libraries/AP_Logger/AP_Logger.cpp @@ -193,8 +193,7 @@ const AP_Param::GroupInfo AP_Logger::var_info[] = { #define streq(x, y) (!strcmp(x, y)) -AP_Logger::AP_Logger(const AP_Int32 &log_bitmask) - : _log_bitmask(log_bitmask) +AP_Logger::AP_Logger() { AP_Param::setup_object_defaults(this, var_info); if (_singleton != nullptr) { @@ -204,8 +203,10 @@ AP_Logger::AP_Logger(const AP_Int32 &log_bitmask) _singleton = this; } -void AP_Logger::Init(const struct LogStructure *structures, uint8_t num_types) +void AP_Logger::init(const AP_Int32 &log_bitmask, const struct LogStructure *structures, uint8_t num_types) { + _log_bitmask = &log_bitmask; + // convert from 8 bit to 16 bit LOG_FILE_BUFSIZE _params.file_bufsize.convert_parameter_width(AP_PARAM_INT8); @@ -629,7 +630,7 @@ bool AP_Logger::should_log(const uint32_t mask) const { bool armed = vehicle_is_armed(); - if (!(mask & _log_bitmask)) { + if (!(mask & *_log_bitmask)) { return false; } if (!armed && !log_while_disarmed()) { diff --git a/libraries/AP_Logger/AP_Logger.h b/libraries/AP_Logger/AP_Logger.h index cab112ea654c38..77abfb47577aaa 100644 --- a/libraries/AP_Logger/AP_Logger.h +++ b/libraries/AP_Logger/AP_Logger.h @@ -187,7 +187,7 @@ class AP_Logger public: FUNCTOR_TYPEDEF(vehicle_startup_message_Writer, void); - AP_Logger(const AP_Int32 &log_bitmask); + AP_Logger(); /* Do not allow copies */ CLASS_NO_COPY(AP_Logger); @@ -198,7 +198,7 @@ class AP_Logger } // initialisation - void Init(const struct LogStructure *structure, uint8_t num_types); + void init(const AP_Int32 &log_bitmask, const struct LogStructure *structure, uint8_t num_types); void set_num_types(uint8_t num_types) { _num_types = num_types; } bool CardInserted(void); @@ -426,7 +426,7 @@ class AP_Logger #define LOGGER_MAX_BACKENDS 2 uint8_t _next_backend; AP_Logger_Backend *backends[LOGGER_MAX_BACKENDS]; - const AP_Int32 &_log_bitmask; + const AP_Int32 *_log_bitmask; enum class Backend_Type : uint8_t { NONE = 0, diff --git a/libraries/AP_Logger/examples/AP_Logger_AllTypes/AP_Logger_AllTypes.cpp b/libraries/AP_Logger/examples/AP_Logger_AllTypes/AP_Logger_AllTypes.cpp index efa9c4253aa14d..76e8aac2b696c3 100644 --- a/libraries/AP_Logger/examples/AP_Logger_AllTypes/AP_Logger_AllTypes.cpp +++ b/libraries/AP_Logger/examples/AP_Logger_AllTypes/AP_Logger_AllTypes.cpp @@ -106,7 +106,7 @@ class AP_LoggerTest_AllTypes : public AP_HAL::HAL::Callbacks { private: AP_Int32 log_bitmask; - AP_Logger logger{log_bitmask}; + AP_Logger logger; AP_Scheduler scheduler; void Log_Write_TypeMessages(); @@ -248,7 +248,7 @@ void AP_LoggerTest_AllTypes::setup(void) hal.console->printf("Logger All Types 1.0\n"); log_bitmask.set((uint32_t)-1); - logger.Init(log_structure, ARRAY_SIZE(log_structure)); + logger.init(log_bitmask, log_structure, ARRAY_SIZE(log_structure)); logger.set_vehicle_armed(true); logger.Write_Message("AP_Logger Test"); diff --git a/libraries/AP_Logger/examples/AP_Logger_test/AP_Logger_test.cpp b/libraries/AP_Logger/examples/AP_Logger_test/AP_Logger_test.cpp index fcb6aeb95a52cf..b3b14eef05b1dd 100644 --- a/libraries/AP_Logger/examples/AP_Logger_test/AP_Logger_test.cpp +++ b/libraries/AP_Logger/examples/AP_Logger_test/AP_Logger_test.cpp @@ -41,7 +41,7 @@ class AP_LoggerTest { private: AP_Int32 log_bitmask; - AP_Logger logger{log_bitmask}; + AP_Logger logger; AP_Scheduler scheduler; }; @@ -53,7 +53,7 @@ void AP_LoggerTest::setup(void) hal.console->printf("Logger Log Test 1.0\n"); log_bitmask.set((uint32_t)-1); - logger.Init(log_structure, ARRAY_SIZE(log_structure)); + logger.init(log_bitmask, log_structure, ARRAY_SIZE(log_structure)); logger.set_vehicle_armed(true); logger.Write_Message("AP_Logger Test"); #ifdef DEBUG_RATES diff --git a/libraries/AP_Mission/AP_Mission.cpp b/libraries/AP_Mission/AP_Mission.cpp index 2fd101c8fab0bf..e13dadf3dc34a2 100644 --- a/libraries/AP_Mission/AP_Mission.cpp +++ b/libraries/AP_Mission/AP_Mission.cpp @@ -2,18 +2,19 @@ /// @brief Handles the MAVLINK command mission stack. Reads and writes mission to storage. #include "AP_Mission_config.h" -#include -#include -#include #if AP_MISSION_ENABLED -#include "AP_Mission.h" -#include #include -#include #include +#include +#include +#include "AP_Mission.h" +#include #include +#include +#include +#include #include const AP_Param::GroupInfo AP_Mission::var_info[] = { @@ -836,8 +837,6 @@ bool AP_Mission::read_cmd_from_storage(uint16_t index, Mission_Command& cmd) con return true; } -#endif // AP_MISSION_ENABLED - bool AP_Mission::stored_in_location(uint16_t id) { switch (id) { @@ -864,8 +863,6 @@ bool AP_Mission::stored_in_location(uint16_t id) } } -#if AP_MISSION_ENABLED - /// write_cmd_to_storage - write a command to storage /// index is used to calculate the storage location /// true is returned if successful @@ -939,8 +936,6 @@ void AP_Mission::write_home_to_storage() write_cmd_to_storage(0,home_cmd); } -#endif // AP_MISSION_ENABLED - MAV_MISSION_RESULT AP_Mission::sanity_check_params(const mavlink_mission_item_int_t& packet) { uint8_t nan_mask; @@ -1510,8 +1505,6 @@ MAV_MISSION_RESULT AP_Mission::convert_MISSION_ITEM_INT_to_MISSION_ITEM(const ma return MAV_MISSION_ACCEPTED; } -#if AP_MISSION_ENABLED - // mission_cmd_to_mavlink_int - converts an AP_Mission::Mission_Command object to a mavlink message which can be sent to the GCS // return true on success, false on failure // NOTE: callers to this method current fill parts of "packet" in before calling this method, so do NOT attempt to zero the entire packet in here @@ -2746,8 +2739,6 @@ bool AP_Mission::contains_item(MAV_CMD command) const return false; } -#endif // AP_MISSION_ENABLED - /* return true if the mission item has a location */ @@ -2757,8 +2748,6 @@ bool AP_Mission::cmd_has_location(const uint16_t command) return stored_in_location(command); } -#if AP_MISSION_ENABLED - /* return true if the mission has a terrain relative item. ~2200us for 530 items on H7 */ diff --git a/libraries/AP_Motors/AP_MotorsMatrix_6DoF_Scripting.cpp b/libraries/AP_Motors/AP_MotorsMatrix_6DoF_Scripting.cpp index 42b9d164b30678..d22c75d1e0a2bd 100644 --- a/libraries/AP_Motors/AP_MotorsMatrix_6DoF_Scripting.cpp +++ b/libraries/AP_Motors/AP_MotorsMatrix_6DoF_Scripting.cpp @@ -266,7 +266,7 @@ void AP_MotorsMatrix_6DoF_Scripting::add_motor(int8_t motor_num, float roll_fact uint8_t chan; if (!SRV_Channels::find_channel(function, chan)) { - gcs().send_text(MAV_SEVERITY_ERROR, "Motors: unable to setup motor %u", motor_num); + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Motors: unable to setup motor %u", motor_num); return; } diff --git a/libraries/AP_Motors/examples/AP_Motors_test/MotorTestSweep.sh b/libraries/AP_Motors/examples/AP_Motors_test/MotorTestSweep.sh index 9aa45495411d26..387192b96ff433 100755 --- a/libraries/AP_Motors/examples/AP_Motors_test/MotorTestSweep.sh +++ b/libraries/AP_Motors/examples/AP_Motors_test/MotorTestSweep.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash # Build and run the motors example stability test at a range of yaw headroom and throttle average max values # Output results to files for comparison diff --git a/libraries/AP_Mount/AP_Mount_Backend.cpp b/libraries/AP_Mount/AP_Mount_Backend.cpp index 28536134adaee3..9e15e719abee3a 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.cpp +++ b/libraries/AP_Mount/AP_Mount_Backend.cpp @@ -387,7 +387,7 @@ MAV_RESULT AP_Mount_Backend::handle_command_do_gimbal_manager_configure(const ma // send gimbal_manager_status if control has changed if (prev_control_id != mavlink_control_id) { - gcs().send_message(MSG_GIMBAL_MANAGER_STATUS); + GCS_SEND_MESSAGE(MSG_GIMBAL_MANAGER_STATUS); } return MAV_RESULT_ACCEPTED; diff --git a/libraries/AP_Mount/AP_Mount_SToRM32.cpp b/libraries/AP_Mount/AP_Mount_SToRM32.cpp index de3c8035c989a9..333bac05775059 100644 --- a/libraries/AP_Mount/AP_Mount_SToRM32.cpp +++ b/libraries/AP_Mount/AP_Mount_SToRM32.cpp @@ -128,6 +128,7 @@ void AP_Mount_SToRM32::find_gimbal() if (GCS_MAVLINK::find_by_mavtype_and_compid(MAV_TYPE_GIMBAL, compid, _sysid, _chan)) { _compid = compid; _initialised = true; + gcs().send_text(MAV_SEVERITY_INFO, "Mount: SToRM32"); } } diff --git a/libraries/AP_NMEA_Output/examples/NMEA_Output/nmea_output.cpp b/libraries/AP_NMEA_Output/examples/NMEA_Output/nmea_output.cpp index b2d7f5e33fda33..554e766324f8ea 100644 --- a/libraries/AP_NMEA_Output/examples/NMEA_Output/nmea_output.cpp +++ b/libraries/AP_NMEA_Output/examples/NMEA_Output/nmea_output.cpp @@ -8,7 +8,6 @@ #include #include #include -#include #include #include #include @@ -40,10 +39,6 @@ const struct AP_Param::Info var_info[] = { static AP_Param param{var_info}; - -AP_Int32 logger_bitmask; -static AP_Logger logger{logger_bitmask}; - class DummyVehicle : public AP_Vehicle { public: AP_AHRS ahrs{AP_AHRS::FLAG_ALWAYS_USE_EKF}; diff --git a/libraries/AP_Param/AP_Param.cpp b/libraries/AP_Param/AP_Param.cpp index e3983e2812b9a6..996960a0b58197 100644 --- a/libraries/AP_Param/AP_Param.cpp +++ b/libraries/AP_Param/AP_Param.cpp @@ -2369,8 +2369,7 @@ bool AP_Param::load_defaults_file(const char *filename, bool last_pass) } #endif // AP_PARAM_DEFAULTS_FILE_PARSING_ENABLED - -#if AP_PARAM_MAX_EMBEDDED_PARAM > 0 || (!AP_FILESYSTEM_FILE_READING_ENABLED && defined(HAL_HAVE_AP_ROMFS_EMBEDDED_H)) +#if AP_PARAM_MAX_EMBEDDED_PARAM > 0 || defined(HAL_HAVE_AP_ROMFS_EMBEDDED_H) /* count the number of parameter defaults present in supplied string */ @@ -2416,18 +2415,6 @@ bool AP_Param::count_param_defaults(const volatile char *ptr, int32_t length, ui return true; } -#if AP_PARAM_MAX_EMBEDDED_PARAM > 0 -/* - * load a default set of parameters from a embedded parameter region - * @last_pass: if this is the last pass on defaults - unknown parameters are - * ignored but if this is set a warning will be emitted - */ -void AP_Param::load_embedded_param_defaults(bool last_pass) -{ - load_param_defaults(param_defaults_data.data, param_defaults_data.length, last_pass); -} -#endif // AP_PARAM_MAX_EMBEDDED_PARAM > 0 - /* * load parameter defaults from supplied string */ @@ -2508,7 +2495,21 @@ void AP_Param::load_param_defaults(const volatile char *ptr, int32_t length, boo } num_param_overrides = num_defaults; } -#endif // AP_PARAM_MAX_EMBEDDED_PARAM > 0 +#endif // AP_PARAM_MAX_EMBEDDED_PARAM > 0 || defined(HAL_HAVE_AP_ROMFS_EMBEDDED_H) + + +#if AP_PARAM_MAX_EMBEDDED_PARAM > 0 +/* + * load a default set of parameters from a embedded parameter region + * @last_pass: if this is the last pass on defaults - unknown parameters are + * ignored but if this is set a warning will be emitted + */ +void AP_Param::load_embedded_param_defaults(bool last_pass) +{ + load_param_defaults(param_defaults_data.data, param_defaults_data.length, last_pass); +} +#endif // AP_PARAM_MAX_EMBEDDED_PARAM > 0 + /* find a default value given a pointer to a default value in flash diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_GHST.cpp b/libraries/AP_RCProtocol/AP_RCProtocol_GHST.cpp index a51c9dd795c88d..b0b678d8a5f8f1 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_GHST.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol_GHST.cpp @@ -435,10 +435,15 @@ void AP_RCProtocol_GHST::process_handshake(uint32_t baudrate) || baudrate != CRSF_BAUDRATE || baudrate == GHST_BAUDRATE || uart->get_baud_rate() == GHST_BAUDRATE - || !protocol_enabled(AP_RCProtocol::GHST) - || protocol_enabled(AP_RCProtocol::CRSF)) { + || !protocol_enabled(AP_RCProtocol::GHST)) { return; } +#if AP_RCPROTOCOL_CRSF_ENABLED + if (protocol_enabled(AP_RCProtocol::CRSF)) { + // don't fight CRSF + return; + } +#endif uart->begin(GHST_BAUDRATE); } diff --git a/libraries/AP_RTC/examples/RTC_test/RTC_Test.cpp b/libraries/AP_RTC/examples/RTC_test/RTC_Test.cpp index 85c987a58d148b..18963e86528f6b 100644 --- a/libraries/AP_RTC/examples/RTC_test/RTC_Test.cpp +++ b/libraries/AP_RTC/examples/RTC_test/RTC_Test.cpp @@ -17,7 +17,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL(); static AP_BoardConfig board_config; static AP_SerialManager serial_manager; AP_Int32 logger_bitmask; -static AP_Logger logger{logger_bitmask}; +static AP_Logger logger; static AP_RTC _rtc; void setup(void) diff --git a/libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp b/libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp index 04754e651a735a..5a9eb79d20ee78 100644 --- a/libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp +++ b/libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp @@ -17,8 +17,7 @@ GCS_Dummy _gcs; const AP_HAL::HAL& hal = AP_HAL::get_HAL(); -AP_Int32 log_bitmask; -AP_Logger AP_Logger{log_bitmask}; +AP_Logger logger; class SchedTest { public: diff --git a/libraries/AP_Scripting/applets/Aerobatics/FixedWing/dual_plane.sh b/libraries/AP_Scripting/applets/Aerobatics/FixedWing/dual_plane.sh index fa67876008e8e8..6e95e303aeb25e 100755 --- a/libraries/AP_Scripting/applets/Aerobatics/FixedWing/dual_plane.sh +++ b/libraries/AP_Scripting/applets/Aerobatics/FixedWing/dual_plane.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash # two planes flying together doing aerobatics diff --git a/libraries/AP_Scripting/applets/net_webserver.lua b/libraries/AP_Scripting/applets/net_webserver.lua index cccbc6eb0c36fc..278acd2b2575f0 100644 --- a/libraries/AP_Scripting/applets/net_webserver.lua +++ b/libraries/AP_Scripting/applets/net_webserver.lua @@ -913,7 +913,10 @@ local function Client(_sock, _idx) function self.remove() DEBUG(string.format("%u: removing client OFFSET=%u", idx, offset)) - sock:close() + if sock then + sock:close() + sock = nil + end self.closed = true end diff --git a/libraries/AP_Scripting/docs/docs.lua b/libraries/AP_Scripting/docs/docs.lua index 3208c6ac224a82..8a8db7001b49b9 100644 --- a/libraries/AP_Scripting/docs/docs.lua +++ b/libraries/AP_Scripting/docs/docs.lua @@ -3411,6 +3411,10 @@ function fs:format() end ---@return number function fs:get_format_status() end +-- Get crc32 checksum of a file with given name +---@return uint32_t_ud|nil +function fs:crc32(file_name) end + -- desc ---@class networking networking = {} diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index 7a2d88e470d7e0..5f4458985fca4d 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -77,7 +77,7 @@ singleton AP_Arming method set_aux_auth_failed void uint8_t'skip_check string include AP_BattMonitor/AP_BattMonitor.h include AP_BattMonitor/AP_BattMonitor_Scripting.h -userdata BattMonitorScript_State depends AP_BATTERY_SCRIPTING_ENABLED == 1 +userdata BattMonitorScript_State depends AP_BATTERY_SCRIPTING_ENABLED userdata BattMonitorScript_State field healthy boolean write userdata BattMonitorScript_State field voltage float'skip_check write userdata BattMonitorScript_State field cell_count uint8_t'skip_check write @@ -107,6 +107,7 @@ singleton AP_BattMonitor method get_cycle_count boolean uint8_t 0 ud->num_instan singleton AP_BattMonitor method reset_remaining boolean uint8_t 0 ud->num_instances() float 0 100 singleton AP_BattMonitor method get_cell_voltage boolean uint8_t'skip_check uint8_t'skip_check float'Null singleton AP_BattMonitor method handle_scripting boolean uint8_t'skip_check BattMonitorScript_State +singleton AP_BattMonitor method handle_scripting depends AP_BATTERY_SCRIPTING_ENABLED include AP_GPS/AP_GPS.h @@ -891,7 +892,10 @@ userdata AP_Filesystem::stat_t method is_directory boolean singleton AP_Filesystem rename fs singleton AP_Filesystem method stat boolean string AP_Filesystem::stat_t'Null singleton AP_Filesystem method format boolean +singleton AP_Filesystem method format depends AP_FILESYSTEM_FORMAT_ENABLED singleton AP_Filesystem method get_format_status uint8_t'skip_check +singleton AP_Filesystem method get_format_status depends AP_FILESYSTEM_FORMAT_ENABLED +singleton AP_Filesystem method crc32 boolean string uint32_t'Null include AP_RTC/AP_RTC.h depends AP_RTC_ENABLED include AP_RTC/AP_RTC_config.h diff --git a/libraries/AP_Scripting/generator/src/main.c b/libraries/AP_Scripting/generator/src/main.c index b414f45546c10a..de1c6e48eca242 100644 --- a/libraries/AP_Scripting/generator/src/main.c +++ b/libraries/AP_Scripting/generator/src/main.c @@ -1918,7 +1918,9 @@ void emit_userdata_method(const struct userdata *data, const struct method *meth } else if (data->flags & UD_FLAG_SEMAPHORE_POINTER) { fprintf(source, " %s%sget_semaphore()->take_blocking();\n", ud_name, ud_access); } else if (data->flags & UD_FLAG_SCHEDULER_SEMAPHORE) { + fprintf(source, "#if AP_SCHEDULER_ENABLED\n"); fprintf(source, " AP::scheduler().get_semaphore().take_blocking();\n"); + fprintf(source, "#endif\n"); } int static_cast = TRUE; @@ -2050,7 +2052,9 @@ void emit_userdata_method(const struct userdata *data, const struct method *meth } else if (data->flags & UD_FLAG_SEMAPHORE_POINTER) { fprintf(source, " %s%sget_semaphore()->give();\n", ud_name, ud_access); } else if (data->flags & UD_FLAG_SCHEDULER_SEMAPHORE) { + fprintf(source, "#if AP_SCHEDULER_ENABLED\n"); fprintf(source, " AP::scheduler().get_semaphore().give();\n"); + fprintf(source, "#endif\n"); } // we need to emit out refernce arguments, iterate the args again, creating and copying objects, while keeping a new count @@ -2924,6 +2928,8 @@ int main(int argc, char **argv) { // for set_and_print_new_error_message deprecate warning fprintf(source, "#include \n"); + fprintf(source, "extern const AP_HAL::HAL& hal;\n"); + trace(TRACE_GENERAL, "Starting emission"); emit_headers(source); diff --git a/libraries/AP_Scripting/lua_bindings.cpp b/libraries/AP_Scripting/lua_bindings.cpp index ffa3e349fe00b9..f4cf9bb30735b0 100644 --- a/libraries/AP_Scripting/lua_bindings.cpp +++ b/libraries/AP_Scripting/lua_bindings.cpp @@ -826,6 +826,7 @@ int SocketAPM_close(lua_State *L) { ud->close(); delete ud; scripting->_net_sockets[i] = nullptr; + *check_SocketAPM(L, 1) = nullptr; break; } } diff --git a/libraries/AP_TemperatureSensor/AP_TemperatureSensor_TSYS03.cpp b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_TSYS03.cpp index 649a0063a31b06..eb14de06a77575 100644 --- a/libraries/AP_TemperatureSensor/AP_TemperatureSensor_TSYS03.cpp +++ b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_TSYS03.cpp @@ -36,6 +36,7 @@ static const uint8_t TSYS03_CMD_READ_ADC = 0x00; void AP_TemperatureSensor_TSYS03::init() { constexpr char name[] = "TSYS03"; + (void)name; // sometimes this is unused (e.g. HAL_GCS_ENABLED false) #if AP_TEMPERATURE_SENSOR_TSYS03_ENFORCE_KNOWN_VALID_I2C_ADDRESS // I2C Address: Default to using TSYS03_ADDR_CSB0 & Check I2C Address is Correct diff --git a/libraries/AP_Torqeedo/AP_Torqeedo.cpp b/libraries/AP_Torqeedo/AP_Torqeedo.cpp index 0d4b80ec86396f..2f4ec59e311adb 100644 --- a/libraries/AP_Torqeedo/AP_Torqeedo.cpp +++ b/libraries/AP_Torqeedo/AP_Torqeedo.cpp @@ -345,6 +345,7 @@ void AP_Torqeedo::report_error_codes() // report display system errors const char* msg_prefix = "Torqeedo:"; + (void)msg_prefix; // sometimes unused when HAL_GCS_ENABLED is false if (_display_system_state.flags.set_throttle_stop) { GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s zero throttle required", msg_prefix); } diff --git a/libraries/AP_Vehicle/AP_Vehicle.cpp b/libraries/AP_Vehicle/AP_Vehicle.cpp index 37507b41a2d53d..04f80777fcf7fb 100644 --- a/libraries/AP_Vehicle/AP_Vehicle.cpp +++ b/libraries/AP_Vehicle/AP_Vehicle.cpp @@ -264,6 +264,12 @@ const AP_Param::GroupInfo AP_Vehicle::var_info[] = { AP_SUBGROUPINFO(scripting, "SCR_", 28, AP_Vehicle, AP_Scripting), #endif +#if HAL_LOGGING_ENABLED + // @Group: LOG + // @Path: ../AP_Logger/AP_Logger.cpp + AP_SUBGROUPINFO(logger, "LOG", 29, AP_Vehicle, AP_Logger), +#endif + AP_GROUPEND }; @@ -372,6 +378,10 @@ void AP_Vehicle::setup() can_mgr.init(); #endif +#if HAL_LOGGING_ENABLED + logger.init(get_log_bitmask(), get_log_structures(), get_num_log_structures()); +#endif + // init_ardupilot is where the vehicle does most of its initialisation. init_ardupilot(); @@ -947,11 +957,14 @@ void AP_Vehicle::accel_cal_update() return; } ins.acal_update(); + +#if AP_AHRS_ENABLED // check if new trim values, and set them Vector3f trim_rad; if (ins.get_new_trim(trim_rad)) { ahrs.set_trim(trim_rad); } +#endif #if HAL_CAL_ALWAYS_REBOOT if (ins.accel_cal_requires_reboot() && diff --git a/libraries/AP_Vehicle/AP_Vehicle.h b/libraries/AP_Vehicle/AP_Vehicle.h index 953ea8d7c5c547..6476dffea19ec1 100644 --- a/libraries/AP_Vehicle/AP_Vehicle.h +++ b/libraries/AP_Vehicle/AP_Vehicle.h @@ -37,6 +37,8 @@ #include #include #include +#include +#include #include // Notify library #include #include @@ -286,6 +288,8 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks { virtual void init_ardupilot() = 0; virtual void load_parameters() = 0; + void load_parameters(AP_Int16 &format_version, const uint16_t expected_format_version); + virtual void set_control_channels() {} // board specific config @@ -317,6 +321,15 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks { #endif RangeFinder rangefinder; +#if HAL_LOGGING_ENABLED + AP_Logger logger; + AP_Int32 bitmask_unused; + // method supplied by vehicle to provide log bitmask: + virtual const AP_Int32 &get_log_bitmask() { return bitmask_unused; } + virtual const struct LogStructure *get_log_structures() const { return nullptr; } + virtual uint8_t get_num_log_structures() const { return 0; } +#endif + #if AP_RSSI_ENABLED AP_RSSI rssi; #endif diff --git a/libraries/AP_Vehicle/AP_Vehicle_config.h b/libraries/AP_Vehicle/AP_Vehicle_config.h index 8cdfa764a05294..91e365aa50a4f6 100644 --- a/libraries/AP_Vehicle/AP_Vehicle_config.h +++ b/libraries/AP_Vehicle/AP_Vehicle_config.h @@ -1,5 +1,7 @@ #pragma once +#include + #ifndef AP_VEHICLE_ENABLED #define AP_VEHICLE_ENABLED 1 #endif diff --git a/libraries/AP_Vehicle/Parameters.cpp b/libraries/AP_Vehicle/Parameters.cpp new file mode 100644 index 00000000000000..7741d1ac0e08f3 --- /dev/null +++ b/libraries/AP_Vehicle/Parameters.cpp @@ -0,0 +1,28 @@ +#include "AP_Vehicle.h" + +#if AP_VEHICLE_ENABLED + +#include +#include + +void AP_Vehicle::load_parameters(AP_Int16 &format_version, const uint16_t expected_format_version) +{ + if (!format_version.load() || + format_version != expected_format_version) { + + // erase all parameters + hal.console->printf("Firmware change: erasing EEPROM...\n"); + StorageManager::erase(); + AP_Param::erase_all(); + + // save the current format version + format_version.set_and_save(expected_format_version); + hal.console->printf("done.\n"); + } + format_version.set_default(expected_format_version); + + // Load all auto-loaded EEPROM variables + AP_Param::load_all(); +} + +#endif // AP_VEHICLE_ENABLED diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 87a76c3823f3f3..1990426423b600 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -25,6 +25,7 @@ #include #include #include +#include #include "ap_message.h" @@ -527,7 +528,9 @@ class GCS_MAVLINK virtual bool set_home_to_current_location(bool lock) = 0; virtual bool set_home(const Location& loc, bool lock) = 0; +#if AP_ARMING_ENABLED virtual MAV_RESULT handle_command_component_arm_disarm(const mavlink_command_int_t &packet); +#endif MAV_RESULT handle_command_do_aux_function(const mavlink_command_int_t &packet); MAV_RESULT handle_command_storage_format(const mavlink_command_int_t &packet, const mavlink_message_t &msg); void handle_mission_request_list(const mavlink_message_t &msg); @@ -1281,10 +1284,12 @@ class GCS char statustext_printf_buffer[256+1]; +#if AP_GPS_ENABLED virtual AP_GPS::GPS_Status min_status_for_gps_healthy() const { // NO_FIX simply excludes NO_GPS return AP_GPS::GPS_Status::NO_FIX; } +#endif void update_sensor_status_flags(); diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index ec4ff7eae0d762..52fbfd97c07b27 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -54,6 +54,7 @@ #include #include #include +#include #include #include #include @@ -887,19 +888,31 @@ void GCS_MAVLINK::handle_mission_item(const mavlink_message_t &msg) if (msg.msgid == MAVLINK_MSG_ID_MISSION_ITEM) { mavlink_mission_item_t mission_item; mavlink_msg_mission_item_decode(&msg, &mission_item); +#if AP_MISSION_ENABLED MAV_MISSION_RESULT ret = AP_Mission::convert_MISSION_ITEM_to_MISSION_ITEM_INT(mission_item, mission_item_int); if (ret != MAV_MISSION_ACCEPTED) { const MAV_MISSION_TYPE type = (MAV_MISSION_TYPE)mission_item_int.mission_type; send_mission_ack(msg, type, ret); return; } +#else + // No mission library, so we can't convert from MISSION_ITEM + // to MISSION_ITEM_INT. Since we shouldn't be receiving fence + // or rally items via MISSION_ITEM, we don't need to work hard + // here, just fail: + const MAV_MISSION_TYPE type = (MAV_MISSION_TYPE)mission_item.mission_type; + send_mission_ack(msg, type, MAV_MISSION_UNSUPPORTED); + return; +#endif send_mission_item_warning = true; } else { mavlink_msg_mission_item_int_decode(&msg, &mission_item_int); } - const uint8_t current = mission_item_int.current; const MAV_MISSION_TYPE type = (MAV_MISSION_TYPE)mission_item_int.mission_type; +#if AP_MISSION_ENABLED + const uint8_t current = mission_item_int.current; + if (type == MAV_MISSION_TYPE_MISSION && (current == 2 || current == 3)) { struct AP_Mission::Mission_Command cmd = {}; MAV_MISSION_RESULT result = AP_Mission::mavlink_int_to_mission_cmd(mission_item_int, cmd); @@ -925,6 +938,7 @@ void GCS_MAVLINK::handle_mission_item(const mavlink_message_t &msg) send_mission_ack(msg, MAV_MISSION_TYPE_MISSION, result); return; } +#endif // not a guided-mode reqest MissionItemProtocol *prot = gcs().get_prot_for_mission_type(type); @@ -1605,11 +1619,13 @@ bool GCS_MAVLINK::set_ap_message_interval(enum ap_message id, uint16_t interval_ } } +#if AP_SCHEDULER_ENABLED // send messages out at most 80% of main loop rate if (interval_ms != 0 && interval_ms*800 < AP::scheduler().get_loop_period_us()) { interval_ms = AP::scheduler().get_loop_period_us()/800.0f; } +#endif // check if it's a specially-handled message: const int8_t deferred_offset = get_deferred_message_index(id); @@ -1981,6 +1997,12 @@ void GCS_MAVLINK::send_system_time() const } +bool GCS_MAVLINK::sending_mavlink1() const +{ + return ((_channel_status.flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) != 0); +} + +#if AP_RC_CHANNEL_ENABLED /* send RC_CHANNELS messages */ @@ -2019,11 +2041,6 @@ void GCS_MAVLINK::send_rc_channels() const ); } -bool GCS_MAVLINK::sending_mavlink1() const -{ - return ((_channel_status.flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) != 0); -} - void GCS_MAVLINK::send_rc_channels_raw() const { // for mavlink1 send RC_CHANNELS_RAW, for compatibility with OSD @@ -2054,6 +2071,7 @@ void GCS_MAVLINK::send_rc_channels_raw() const #endif ); } +#endif // AP_RC_CHANNEL_ENABLED void GCS_MAVLINK::send_raw_imu() { @@ -2893,6 +2911,7 @@ void GCS_MAVLINK::send_heartbeat() const system_status()); } +#if AP_RC_CHANNEL_ENABLED MAV_RESULT GCS_MAVLINK::handle_command_do_aux_function(const mavlink_command_int_t &packet) { if (packet.param2 > 2) { @@ -2907,6 +2926,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_do_aux_function(const mavlink_command_int } return MAV_RESULT_ACCEPTED; } +#endif // AP_RC_CHANNEL_ENABLED MAV_RESULT GCS_MAVLINK::handle_command_set_message_interval(const mavlink_command_int_t &packet) { @@ -3355,6 +3375,7 @@ MAV_RESULT GCS_MAVLINK::handle_flight_termination(const mavlink_command_int_t &p #endif } +#if AP_RC_CHANNEL_ENABLED /* handle a R/C bind request (for spektrum) */ @@ -3368,6 +3389,7 @@ MAV_RESULT GCS_MAVLINK::handle_START_RX_PAIR(const mavlink_command_int_t &packet } return MAV_RESULT_ACCEPTED; } +#endif // AP_RC_CHANNEL_ENABLED uint64_t GCS_MAVLINK::timesync_receive_timestamp_ns() const { @@ -3767,6 +3789,7 @@ void GCS_MAVLINK::handle_command_ack(const mavlink_message_t &msg) #endif } +#if AP_RC_CHANNEL_ENABLED // allow override of RC channel values for complete GCS // control of switch position and RC PWM values. void GCS_MAVLINK::handle_rc_channels_override(const mavlink_message_t &msg) @@ -3819,6 +3842,7 @@ void GCS_MAVLINK::handle_rc_channels_override(const mavlink_message_t &msg) gcs().sysid_myggcs_seen(tnow); } +#endif // AP_RC_CHANNEL_ENABLED #if AP_OPTICALFLOW_ENABLED void GCS_MAVLINK::handle_optical_flow(const mavlink_message_t &msg) @@ -4106,9 +4130,11 @@ void GCS_MAVLINK::handle_message(const mavlink_message_t &msg) break; #endif +#if AP_RC_CHANNEL_ENABLED case MAVLINK_MSG_ID_MANUAL_CONTROL: handle_manual_control(msg); break; +#endif #if AP_NOTIFY_MAVLINK_PLAY_TUNE_SUPPORT_ENABLED case MAVLINK_MSG_ID_PLAY_TUNE: @@ -4171,9 +4197,11 @@ void GCS_MAVLINK::handle_message(const mavlink_message_t &msg) break; #endif +#if AP_RC_CHANNEL_ENABLED case MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE: handle_rc_channels_override(msg); break; +#endif #if AP_OPTICALFLOW_ENABLED case MAVLINK_MSG_ID_OPTICAL_FLOW: @@ -4475,7 +4503,9 @@ MAV_RESULT GCS_MAVLINK::_handle_command_preflight_calibration(const mavlink_comm return _handle_command_preflight_calibration_baro(msg); } +#if AP_RC_CHANNEL_ENABLED rc().calibrating(is_positive(packet.param4)); +#endif #if HAL_INS_ACCELCAL_ENABLED if (packet.x == 1) { @@ -4534,6 +4564,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_preflight_calibration(const mavlink_comma return _handle_command_preflight_calibration(packet, msg); } +#if AP_ARMING_ENABLED MAV_RESULT GCS_MAVLINK::handle_command_run_prearm_checks(const mavlink_command_int_t &packet) { if (hal.util->get_soft_armed()) { @@ -4542,6 +4573,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_run_prearm_checks(const mavlink_command_i (void)AP::arming().pre_arm_checks(true); return MAV_RESULT_ACCEPTED; } +#endif // AP_ARMING_ENABLED #if AP_MISSION_ENABLED // changes the current waypoint; at time of writing GCS @@ -4779,6 +4811,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_mount(const mavlink_command_int_t &packet } #endif // HAL_MOUNT_ENABLED +#if AP_ARMING_ENABLED MAV_RESULT GCS_MAVLINK::handle_command_component_arm_disarm(const mavlink_command_int_t &packet) { if (is_equal(packet.param1,1.0f)) { @@ -4806,6 +4839,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_component_arm_disarm(const mavlink_comman return MAV_RESULT_UNSUPPORTED; } +#endif // AP_ARMING_ENABLED bool GCS_MAVLINK::location_from_command_t(const mavlink_command_int_t &in, Location &out) { @@ -5152,8 +5186,10 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p return MAV_RESULT_FAILED; #endif +#if AP_RC_CHANNEL_ENABLED case MAV_CMD_DO_AUX_FUNCTION: return handle_command_do_aux_function(packet); +#endif #if AP_FENCE_ENABLED case MAV_CMD_DO_FENCE_ENABLE: @@ -5228,9 +5264,10 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p case MAV_CMD_EXTERNAL_POSITION_ESTIMATE: return handle_command_int_external_position_estimate(packet); #endif +#if AP_ARMING_ENABLED case MAV_CMD_COMPONENT_ARM_DISARM: return handle_command_component_arm_disarm(packet); - +#endif #if AP_COMPASS_CALIBRATION_FIXED_YAW_ENABLED case MAV_CMD_FIXED_MAG_CAL_YAW: return handle_command_fixed_mag_cal_yaw(packet); @@ -5279,8 +5316,10 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p return handle_command_request_autopilot_capabilities(packet); #endif +#if AP_ARMING_ENABLED case MAV_CMD_RUN_PREARM_CHECKS: return handle_command_run_prearm_checks(packet); +#endif #if AP_SCRIPTING_ENABLED case MAV_CMD_SCRIPTING: @@ -5298,8 +5337,10 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p return handle_command_set_ekf_source_set(packet); #endif +#if AP_RC_CHANNEL_ENABLED case MAV_CMD_START_RX_PAIR: return handle_START_RX_PAIR(packet); +#endif #if AP_FILESYSTEM_FORMAT_ENABLED case MAV_CMD_STORAGE_FORMAT: @@ -5468,7 +5509,11 @@ void GCS_MAVLINK::send_sys_status() control_sensors_present, control_sensors_enabled, control_sensors_health, +#if AP_SCHEDULER_ENABLED static_cast(AP::scheduler().load_average() * 1000), +#else + 0, +#endif #if AP_BATTERY_ENABLED battery.gcs_voltage() * 1000, // mV battery_current, // in 10mA units @@ -6037,6 +6082,7 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) break; #endif +#if AP_RC_CHANNEL_ENABLED case MSG_RC_CHANNELS: CHECK_PAYLOAD_SIZE(RC_CHANNELS); send_rc_channels(); @@ -6046,6 +6092,7 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) CHECK_PAYLOAD_SIZE(RC_CHANNELS_RAW); send_rc_channels_raw(); break; +#endif case MSG_RAW_IMU: CHECK_PAYLOAD_SIZE(RAW_IMU); @@ -6721,6 +6768,7 @@ uint64_t GCS_MAVLINK::capabilities() const } +#if AP_RC_CHANNEL_ENABLED void GCS_MAVLINK::manual_override(RC_Channel *c, int16_t value_in, const uint16_t offset, const float scaler, const uint32_t tnow, const bool reversed) { if (c == nullptr) { @@ -6759,7 +6807,7 @@ void GCS_MAVLINK::handle_manual_control(const mavlink_message_t &msg) // from the ground station for failsafe purposes gcs().sysid_myggcs_seen(tnow); } - +#endif // AP_RC_CHANNEL_ENABLED #if AP_RSSI_ENABLED uint8_t GCS_MAVLINK::receiver_rssi() const diff --git a/libraries/GCS_MAVLink/GCS_config.h b/libraries/GCS_MAVLink/GCS_config.h index 8960a881ab45cb..14449af38220f2 100644 --- a/libraries/GCS_MAVLink/GCS_config.h +++ b/libraries/GCS_MAVLink/GCS_config.h @@ -89,7 +89,7 @@ // sending warnings to the GCS in Sep 2022 if this command was used. // Copter 4.4.0 sends this warning. #ifndef AP_MAVLINK_MSG_MISSION_REQUEST_ENABLED -#define AP_MAVLINK_MSG_MISSION_REQUEST_ENABLED 1 +#define AP_MAVLINK_MSG_MISSION_REQUEST_ENABLED AP_MISSION_ENABLED #endif // all commands can be executed by COMMAND_INT, so COMMAND_LONG isn't diff --git a/libraries/GCS_MAVLink/GCS_serial_control.cpp b/libraries/GCS_MAVLink/GCS_serial_control.cpp index 50322e2e5dac29..0c60dcb4e27bc1 100644 --- a/libraries/GCS_MAVLink/GCS_serial_control.cpp +++ b/libraries/GCS_MAVLink/GCS_serial_control.cpp @@ -64,6 +64,7 @@ void GCS_MAVLINK::handle_serial_control(const mavlink_message_t &msg) link->lock(exclusive); break; } +#if AP_GPS_ENABLED case SERIAL_CONTROL_DEV_GPS1: stream = port = hal.serial(3); AP::gps().lock_port(0, exclusive); @@ -72,6 +73,7 @@ void GCS_MAVLINK::handle_serial_control(const mavlink_message_t &msg) stream = port = hal.serial(4); AP::gps().lock_port(1, exclusive); break; +#endif // AP_GPS_ENABLED case SERIAL_CONTROL_DEV_SHELL: stream = hal.util->get_shell_stream(); if (stream == nullptr) { diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index ef80a7ab849cf0..a544f8638e5a46 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -617,7 +617,7 @@ bool RC_Channel::debounce_completed(int8_t position) // // init_aux_switch_function - initialize aux functions -void RC_Channel::init_aux_function(const aux_func_t ch_option, const AuxSwitchPos ch_flag) +void RC_Channel::init_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch_flag) { // init channel options switch (ch_option) { @@ -805,7 +805,7 @@ const char *RC_Channel::string_for_aux_pos(AuxSwitchPos pos) const */ bool RC_Channel::read_aux() { - const aux_func_t _option = (aux_func_t)option.get(); + const AUX_FUNC _option = (AUX_FUNC)option.get(); if (_option == AUX_FUNC::DO_NOTHING) { // may wish to add special cases for other "AUXSW" things // here e.g. RCMAP_ROLL etc once they become options @@ -1066,6 +1066,7 @@ void RC_Channel::do_aux_function_fence(const AuxSwitchPos ch_flag) } #endif +#if AP_MISSION_ENABLED void RC_Channel::do_aux_function_clear_wp(const AuxSwitchPos ch_flag) { if (ch_flag == AuxSwitchPos::HIGH) { @@ -1076,6 +1077,7 @@ void RC_Channel::do_aux_function_clear_wp(const AuxSwitchPos ch_flag) mission->clear(); } } +#endif // AP_MISSION_ENABLED #if AP_SERVORELAYEVENTS_ENABLED && AP_RELAY_ENABLED void RC_Channel::do_aux_function_relay(const uint8_t relay, bool val) @@ -1178,6 +1180,7 @@ void RC_Channel::do_aux_function_rc_override_enable(const AuxSwitchPos ch_flag) } } +#if AP_MISSION_ENABLED void RC_Channel::do_aux_function_mission_reset(const AuxSwitchPos ch_flag) { if (ch_flag != AuxSwitchPos::HIGH) { @@ -1189,6 +1192,7 @@ void RC_Channel::do_aux_function_mission_reset(const AuxSwitchPos ch_flag) } mission->reset(); } +#endif void RC_Channel::do_aux_function_fft_notch_tune(const AuxSwitchPos ch_flag) { @@ -1210,7 +1214,7 @@ void RC_Channel::do_aux_function_fft_notch_tune(const AuxSwitchPos ch_flag) #endif } -bool RC_Channel::run_aux_function(aux_func_t ch_option, AuxSwitchPos pos, AuxFuncTriggerSource source) +bool RC_Channel::run_aux_function(AUX_FUNC ch_option, AuxSwitchPos pos, AuxFuncTriggerSource source) { #if AP_SCRIPTING_ENABLED rc().set_aux_cached(ch_option, pos); @@ -1245,7 +1249,7 @@ bool RC_Channel::run_aux_function(aux_func_t ch_option, AuxSwitchPos pos, AuxFun return ret; } -bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos ch_flag) +bool RC_Channel::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch_flag) { switch (ch_option) { #if AP_FENCE_ENABLED @@ -1680,7 +1684,7 @@ void RC_Channel::init_aux() if (!read_3pos_switch(position)) { position = AuxSwitchPos::LOW; } - init_aux_function((aux_func_t)option.get(), position); + init_aux_function((AUX_FUNC)option.get(), position); } // read_3pos_switch @@ -1722,7 +1726,7 @@ RC_Channel::AuxSwitchPos RC_Channels::get_channel_pos(const uint8_t rcmapchan) c return chan != nullptr ? chan->get_aux_switch_pos() : RC_Channel::AuxSwitchPos::LOW; } -RC_Channel *RC_Channels::find_channel_for_option(const RC_Channel::aux_func_t option) +RC_Channel *RC_Channels::find_channel_for_option(const RC_Channel::AUX_FUNC option) { for (uint8_t i=0; ioption.get() == option) { + if ((RC_Channel::AUX_FUNC)c->option.get() == option) { return c; } } @@ -1766,7 +1770,7 @@ bool RC_Channels::duplicate_options_exist() } // convert option parameter from old to new -void RC_Channels::convert_options(const RC_Channel::aux_func_t old_option, const RC_Channel::aux_func_t new_option) +void RC_Channels::convert_options(const RC_Channel::AUX_FUNC old_option, const RC_Channel::AUX_FUNC new_option) { for (uint8_t i=0; ioption.get() == old_option) { + if ((RC_Channel::AUX_FUNC)c->option.get() == old_option) { c->option.set_and_save((int16_t)new_option); } } diff --git a/libraries/RC_Channel/RC_Channel.h b/libraries/RC_Channel/RC_Channel.h index 368e3a013eae56..4ad9e532fa0494 100644 --- a/libraries/RC_Channel/RC_Channel.h +++ b/libraries/RC_Channel/RC_Channel.h @@ -285,7 +285,6 @@ class RC_Channel { // this must be higher than any aux function above AUX_FUNCTION_MAX = 308, }; - typedef enum AUX_FUNC aux_func_t; // auxiliary switch handling (n.b.: we store this as 2-bits!): enum class AuxSwitchPos : uint8_t { @@ -306,7 +305,7 @@ class RC_Channel { AuxSwitchPos get_aux_switch_pos() const; // wrapper function around do_aux_function which allows us to log - bool run_aux_function(aux_func_t ch_option, AuxSwitchPos pos, AuxFuncTriggerSource source); + bool run_aux_function(AUX_FUNC ch_option, AuxSwitchPos pos, AuxFuncTriggerSource source); #if AP_RC_CHANNEL_AUX_FUNCTION_STRINGS_ENABLED const char *string_for_aux_function(AUX_FUNC function) const; @@ -334,10 +333,10 @@ class RC_Channel { protected: - virtual void init_aux_function(aux_func_t ch_option, AuxSwitchPos); + virtual void init_aux_function(AUX_FUNC ch_option, AuxSwitchPos); // virtual function to be overridden my subclasses - virtual bool do_aux_function(aux_func_t ch_option, AuxSwitchPos); + virtual bool do_aux_function(AUX_FUNC ch_option, AuxSwitchPos); void do_aux_function_armdisarm(const AuxSwitchPos ch_flag); void do_aux_function_avoid_adsb(const AuxSwitchPos ch_flag); @@ -482,10 +481,10 @@ class RC_Channels { // is RC channel 1. Beware this is not a cheap call. uint16_t get_override_mask() const; - class RC_Channel *find_channel_for_option(const RC_Channel::aux_func_t option); + class RC_Channel *find_channel_for_option(const RC_Channel::AUX_FUNC option); bool duplicate_options_exist(); RC_Channel::AuxSwitchPos get_channel_pos(const uint8_t rcmapchan) const; - void convert_options(const RC_Channel::aux_func_t old_option, const RC_Channel::aux_func_t new_option); + void convert_options(const RC_Channel::AUX_FUNC old_option, const RC_Channel::AUX_FUNC new_option); void init_aux_all(); void read_aux_all(); @@ -586,7 +585,7 @@ class RC_Channels { #if AP_SCRIPTING_ENABLED // get last aux cached value for scripting. Returns false if never set, otherwise 0,1,2 - bool get_aux_cached(RC_Channel::aux_func_t aux_fn, uint8_t &pos); + bool get_aux_cached(RC_Channel::AUX_FUNC aux_fn, uint8_t &pos); #endif // returns true if we've ever seen RC input, via overrides or via @@ -637,7 +636,7 @@ class RC_Channels { HAL_Semaphore aux_cache_sem; Bitmask aux_cached; - void set_aux_cached(RC_Channel::aux_func_t aux_fn, RC_Channel::AuxSwitchPos pos); + void set_aux_cached(RC_Channel::AUX_FUNC aux_fn, RC_Channel::AuxSwitchPos pos); #endif }; diff --git a/libraries/RC_Channel/RC_Channels.cpp b/libraries/RC_Channel/RC_Channels.cpp index 4beee5e5d69f2d..9ec73c5dab365e 100644 --- a/libraries/RC_Channel/RC_Channels.cpp +++ b/libraries/RC_Channel/RC_Channels.cpp @@ -236,7 +236,7 @@ bool RC_Channels::flight_mode_channel_conflicts_with_rc_option() const if (chan == nullptr) { return false; } - return (RC_Channel::aux_func_t)chan->option.get() != RC_Channel::AUX_FUNC::DO_NOTHING; + return (RC_Channel::AUX_FUNC)chan->option.get() != RC_Channel::AUX_FUNC::DO_NOTHING; } /* @@ -276,7 +276,7 @@ uint32_t RC_Channels::enabled_protocols() const /* get last aux cached value for scripting. Returns false if never set, otherwise 0,1,2 */ -bool RC_Channels::get_aux_cached(RC_Channel::aux_func_t aux_fn, uint8_t &pos) +bool RC_Channels::get_aux_cached(RC_Channel::AUX_FUNC aux_fn, uint8_t &pos) { const uint16_t aux_idx = uint16_t(aux_fn); if (aux_idx >= unsigned(RC_Channel::AUX_FUNC::AUX_FUNCTION_MAX)) { @@ -295,7 +295,7 @@ bool RC_Channels::get_aux_cached(RC_Channel::aux_func_t aux_fn, uint8_t &pos) /* set cached value of an aux function */ -void RC_Channels::set_aux_cached(RC_Channel::aux_func_t aux_fn, RC_Channel::AuxSwitchPos pos) +void RC_Channels::set_aux_cached(RC_Channel::AUX_FUNC aux_fn, RC_Channel::AuxSwitchPos pos) { const uint16_t aux_idx = uint16_t(aux_fn); if (aux_idx < unsigned(RC_Channel::AUX_FUNC::AUX_FUNCTION_MAX)) { diff --git a/libraries/SITL/examples/Airsim/follow-copter.sh b/libraries/SITL/examples/Airsim/follow-copter.sh index 47625999c82c9e..302f85ac33dad6 100755 --- a/libraries/SITL/examples/Airsim/follow-copter.sh +++ b/libraries/SITL/examples/Airsim/follow-copter.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash # Example script for multi-vehicle simulation with AirSim # see https://ardupilot.org/dev/docs/sitl-with-airsim.html#multi-vehicle-simulation for details diff --git a/libraries/SITL/examples/Airsim/multi_vehicle.sh b/libraries/SITL/examples/Airsim/multi_vehicle.sh index f02717e6fc3895..f227173d40faa1 100755 --- a/libraries/SITL/examples/Airsim/multi_vehicle.sh +++ b/libraries/SITL/examples/Airsim/multi_vehicle.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash # Example script for multi-vehicle simulation with AirSim and usage with ROS # see https://ardupilot.org/dev/docs/sitl-with-airsim.html#multi-vehicle-simulation for details diff --git a/libraries/SITL/examples/Follow/plane_quad.sh b/libraries/SITL/examples/Follow/plane_quad.sh index 171bcdff20cbd6..1b6310cc5035e2 100755 --- a/libraries/SITL/examples/Follow/plane_quad.sh +++ b/libraries/SITL/examples/Follow/plane_quad.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash # a quad following a plane diff --git a/libraries/SITL/examples/Morse/start_follow.sh b/libraries/SITL/examples/Morse/start_follow.sh index e213eaeb8daadf..43bc88e1805f7b 100755 --- a/libraries/SITL/examples/Morse/start_follow.sh +++ b/libraries/SITL/examples/Morse/start_follow.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash # assume we start the script from the root directory ROOTDIR=$PWD diff --git a/libraries/SITL/examples/Webots/dronePlus.sh b/libraries/SITL/examples/Webots/dronePlus.sh index 171a0f4850f928..6b3b3b087650a1 100755 --- a/libraries/SITL/examples/Webots/dronePlus.sh +++ b/libraries/SITL/examples/Webots/dronePlus.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash # assume we start the script from the root directory ROOTDIR=$PWD diff --git a/libraries/SITL/examples/Webots/droneTricopter.sh b/libraries/SITL/examples/Webots/droneTricopter.sh index ac6f520ac2ee8e..256f3cdbe27873 100755 --- a/libraries/SITL/examples/Webots/droneTricopter.sh +++ b/libraries/SITL/examples/Webots/droneTricopter.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash # assume we start the script from the root directory ROOTDIR=$PWD diff --git a/libraries/SITL/examples/Webots/droneTwoTricopters.sh b/libraries/SITL/examples/Webots/droneTwoTricopters.sh index 3553228de3a7cf..9833af3422ca84 100755 --- a/libraries/SITL/examples/Webots/droneTwoTricopters.sh +++ b/libraries/SITL/examples/Webots/droneTwoTricopters.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash # assume we start the script from the root directory diff --git a/libraries/SITL/examples/Webots/droneX.sh b/libraries/SITL/examples/Webots/droneX.sh index 45d18874c15f1f..0c29da5877e730 100755 --- a/libraries/SITL/examples/Webots/droneX.sh +++ b/libraries/SITL/examples/Webots/droneX.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash # assume we start the script from the root directory ROOTDIR=$PWD diff --git a/libraries/SITL/examples/Webots/droneX_TwoDrones.sh b/libraries/SITL/examples/Webots/droneX_TwoDrones.sh index 064a7d8125be1e..0564cb8bc01945 100755 --- a/libraries/SITL/examples/Webots/droneX_TwoDrones.sh +++ b/libraries/SITL/examples/Webots/droneX_TwoDrones.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash # assume we start the script from the root directory ROOTDIR=$PWD diff --git a/libraries/SITL/examples/Webots/pyramids_droneX.sh b/libraries/SITL/examples/Webots/pyramids_droneX.sh index d40d123d0ccfaa..02328840b1fbfc 100755 --- a/libraries/SITL/examples/Webots/pyramids_droneX.sh +++ b/libraries/SITL/examples/Webots/pyramids_droneX.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash # assume we start the script from the root directory ROOTDIR=$PWD diff --git a/libraries/SITL/examples/Webots/pyramids_droneX_twoDrones.sh b/libraries/SITL/examples/Webots/pyramids_droneX_twoDrones.sh index 0081fe283bc823..d9064a0e634235 100755 --- a/libraries/SITL/examples/Webots/pyramids_droneX_twoDrones.sh +++ b/libraries/SITL/examples/Webots/pyramids_droneX_twoDrones.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash # assume we start the script from the root directory ROOTDIR=$PWD diff --git a/libraries/SITL/examples/Webots/rover.sh b/libraries/SITL/examples/Webots/rover.sh index 187d7315262e65..568495d5199eed 100755 --- a/libraries/SITL/examples/Webots/rover.sh +++ b/libraries/SITL/examples/Webots/rover.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash # assume we start the script from the root directory ROOTDIR=$PWD diff --git a/libraries/SITL/examples/follow-copter.sh b/libraries/SITL/examples/follow-copter.sh index 8dbeebc75f0d68..5ef7c218582d8e 100755 --- a/libraries/SITL/examples/follow-copter.sh +++ b/libraries/SITL/examples/follow-copter.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash # Usage - From ardupilot root directory, run - libraries/SITL/examples/follow-copter.sh $GCS_IP # $GCS_IP is the IP address of the system running the GCs, by default is 127.0.0.1 diff --git a/libraries/SITL/examples/follow-mavproxy.sh b/libraries/SITL/examples/follow-mavproxy.sh index 54cbc889e20928..0fa14fd85765f0 100755 --- a/libraries/SITL/examples/follow-mavproxy.sh +++ b/libraries/SITL/examples/follow-mavproxy.sh @@ -1,3 +1,3 @@ -#!/bin/bash +#!/usr/bin/env bash mavproxy.py --master=mcast: --console --map --cmd='map set showgpspos 0; map set showgps2pos 0;' diff --git a/libraries/doc/updateDocs b/libraries/doc/updateDocs index 50cf459f4a4e83..a0d60b7b264db2 100755 --- a/libraries/doc/updateDocs +++ b/libraries/doc/updateDocs @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash rm -rf html svn cleanup svn update html diff --git a/modules/DroneCAN/dronecan_dsdlc b/modules/DroneCAN/dronecan_dsdlc index ebaf96860a11a4..2465ace6c8cb01 160000 --- a/modules/DroneCAN/dronecan_dsdlc +++ b/modules/DroneCAN/dronecan_dsdlc @@ -1 +1 @@ -Subproject commit ebaf96860a11a4cc43c01df6b651df143c6cde2d +Subproject commit 2465ace6c8cb0148e3ff5865aa9e4dd17d691a71 diff --git a/modules/DroneCAN/libcanard b/modules/DroneCAN/libcanard index 22102c717db29c..0ae477b82bc18d 160000 --- a/modules/DroneCAN/libcanard +++ b/modules/DroneCAN/libcanard @@ -1 +1 @@ -Subproject commit 22102c717db29cc2a2c2869ff80f3e4389704d89 +Subproject commit 0ae477b82bc18daf642383079a02710f69294aa8 diff --git a/modules/DroneCAN/pydronecan b/modules/DroneCAN/pydronecan index 19fdf2e5b38324..1f494e9a56ac99 160000 --- a/modules/DroneCAN/pydronecan +++ b/modules/DroneCAN/pydronecan @@ -1 +1 @@ -Subproject commit 19fdf2e5b383243ccdb1094edae0603cf11469e8 +Subproject commit 1f494e9a56ac9930f1e11c2f453789414b10d54e diff --git a/wscript b/wscript index fa333e1d30f33a..7d4d9e19794151 100644 --- a/wscript +++ b/wscript @@ -726,7 +726,7 @@ def _build_dynamic_sources(bld): if (bld.get_board().with_can or bld.env.HAL_NUM_CAN_IFACES) and not bld.env.AP_PERIPH: bld( features='dronecangen', - source=bld.srcnode.ant_glob('modules/DroneCAN/DSDL/* libraries/AP_DroneCAN/dsdl/*', dir=True, src=False), + source=bld.srcnode.ant_glob('modules/DroneCAN/DSDL/[a-z]* libraries/AP_DroneCAN/dsdl/[a-z]*', dir=True, src=False), output_dir='modules/DroneCAN/libcanard/dsdlc_generated/', name='dronecan', export_includes=[