From f8ed9f0e8d4f7ec496f4e40ca8567a781d5a3606 Mon Sep 17 00:00:00 2001 From: Phil Date: Tue, 27 Dec 2011 00:42:50 -0800 Subject: [PATCH 01/33] APM: Fix rudder in elevon mode. elevon planes can have rudders too --- ArduPlane/Attitude.pde | 2 +- ArduPlane/radio.pde | 5 ++--- 2 files changed, 3 insertions(+), 4 deletions(-) diff --git a/ArduPlane/Attitude.pde b/ArduPlane/Attitude.pde index 08a9502139..e8b0e70216 100644 --- a/ArduPlane/Attitude.pde +++ b/ArduPlane/Attitude.pde @@ -314,7 +314,6 @@ static void set_servos(void) if (g.mix_mode == 0) { g.channel_roll.calc_pwm(); g.channel_pitch.calc_pwm(); - g.channel_rudder.calc_pwm(); if (g_rc_function[RC_Channel_aux::k_aileron]) { g_rc_function[RC_Channel_aux::k_aileron]->servo_out = g.channel_roll.servo_out; g_rc_function[RC_Channel_aux::k_aileron]->calc_pwm(); @@ -329,6 +328,7 @@ static void set_servos(void) g.channel_roll.radio_out = elevon1_trim + (BOOL_TO_SIGN(g.reverse_ch1_elevon) * (ch1 * 500.0/ SERVO_MAX)); g.channel_pitch.radio_out = elevon2_trim + (BOOL_TO_SIGN(g.reverse_ch2_elevon) * (ch2 * 500.0/ SERVO_MAX)); } + g.channel_rudder.calc_pwm(); #if THROTTLE_OUT == 0 g.channel_throttle.servo_out = 0; diff --git a/ArduPlane/radio.pde b/ArduPlane/radio.pde index ac4b802ef8..933c54aa45 100644 --- a/ArduPlane/radio.pde +++ b/ArduPlane/radio.pde @@ -157,7 +157,6 @@ static void trim_control_surfaces() if(g.mix_mode == 0){ g.channel_roll.radio_trim = g.channel_roll.radio_in; g.channel_pitch.radio_trim = g.channel_pitch.radio_in; - g.channel_rudder.radio_trim = g.channel_rudder.radio_in; G_RC_AUX(k_aileron)->radio_trim = g_rc_function[RC_Channel_aux::k_aileron]->radio_in; // Second aileron channel }else{ @@ -169,6 +168,7 @@ static void trim_control_surfaces() g.channel_roll.radio_trim = center; g.channel_pitch.radio_trim = center; } + g.channel_rudder.radio_trim = g.channel_rudder.radio_in; // save to eeprom g.channel_roll.save_eeprom(); @@ -190,7 +190,6 @@ static void trim_radio() g.channel_roll.radio_trim = g.channel_roll.radio_in; g.channel_pitch.radio_trim = g.channel_pitch.radio_in; //g.channel_throttle.radio_trim = g.channel_throttle.radio_in; - g.channel_rudder.radio_trim = g.channel_rudder.radio_in; G_RC_AUX(k_aileron)->radio_trim = g_rc_function[RC_Channel_aux::k_aileron]->radio_in; // Second aileron channel } else { @@ -199,8 +198,8 @@ static void trim_radio() uint16_t center = 1500; g.channel_roll.radio_trim = center; g.channel_pitch.radio_trim = center; - g.channel_rudder.radio_trim = g.channel_rudder.radio_in; } + g.channel_rudder.radio_trim = g.channel_rudder.radio_in; // save to eeprom g.channel_roll.save_eeprom(); From 3fbb5a2d6c185512f9d3446f9b326e7e3b872d71 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 16 Feb 2012 17:48:04 +1100 Subject: [PATCH 02/33] ADC: on channel overflow we should not zero last_ch6_micros this happens every 64 seconds because of unused channels on the ADC. Zeroing this creates a bad delta_t value for the DCM code. --- libraries/AP_ADC/AP_ADC_ADS7844.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/libraries/AP_ADC/AP_ADC_ADS7844.cpp b/libraries/AP_ADC/AP_ADC_ADS7844.cpp index c3cf71cda2..96e3751d23 100644 --- a/libraries/AP_ADC/AP_ADC_ADS7844.cpp +++ b/libraries/AP_ADC/AP_ADC_ADS7844.cpp @@ -116,7 +116,6 @@ void AP_ADC_ADS7844::read(uint32_t tnow) // reader below could get a division by zero _sum[ch] = 0; _count[ch] = 1; - last_ch6_micros = tnow; } _sum[ch] += (v >> 3); } From 43e695b1ac9f838a8209854b456d5643375f839a Mon Sep 17 00:00:00 2001 From: Jason Short Date: Thu, 16 Feb 2012 22:07:00 -0800 Subject: [PATCH 03/33] removed some unused vars, formatting, made loop speed same as PIDT1 to eliminate variable. --- ArduCopter/ArduCopter.pde | 30 +++++++----------------------- 1 file changed, 7 insertions(+), 23 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 2f6a396fb2..0ace4409a4 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -32,9 +32,9 @@ Oliver :Piezo support Guntars :Arming safety suggestion Igor van Airde :Control Law optimization Jean-Louis Naudin :Auto Landing -Sandro Benigno : Camera support -Olivier Adler : PPM Encoder -John Arne Birkeland: PPM Encoder +Sandro Benigno :Camera support +Olivier Adler :PPM Encoder +John Arne Birkeland :PPM Encoder And much more so PLEASE PM me on DIYDRONES to add your contribution to the List @@ -659,11 +659,6 @@ static int32_t auto_pitch; static int16_t nav_lat; // The desired bank towards East (Positive) or West (Negative) static int16_t nav_lon; -// This may go away, but for now I'm tracking the desired bank before we apply the Wind compensation I term -// This is mainly for debugging -//static int16_t nav_lat_p; -//static int16_t nav_lon_p; - // The Commanded ROll from the autopilot based on optical flow sensor. static int32_t of_roll = 0; // The Commanded pitch from the autopilot based on optical flow sensor. negative Pitch means go forward. @@ -829,7 +824,9 @@ void loop() uint32_t timer = micros(); // We want this to execute fast // ---------------------------- - if ((timer - fast_loopTimer) >= 4500) { + if ((timer - fast_loopTimer) >= 5000) { + Log_Write_Data(13, (int32_t)(timer - fast_loopTimer)); + //PORTK |= B00010000; G_Dt = (float)(timer - fast_loopTimer) / 1000000.f; // used by PI Loops fast_loopTimer = timer; @@ -1426,26 +1423,13 @@ void update_roll_pitch_mode(void) g.rc_2.servo_out = get_stabilize_pitch(g.rc_2.control_in); break; -/* case ROLL_PITCH_AUTO: - // apply SIMPLE mode transform - if(do_simple && new_radio_frame){ - update_simple_mode(); - } - // mix in user control with Nav control - control_roll = g.rc_1.control_mix(nav_roll); - control_pitch = g.rc_2.control_mix(nav_pitch); - g.rc_1.servo_out = get_stabilize_roll(control_roll); - g.rc_2.servo_out = get_stabilize_pitch(control_pitch); - break; - */ - case ROLL_PITCH_AUTO: // apply SIMPLE mode transform if(do_simple && new_radio_frame){ update_simple_mode(); } // mix in user control with Nav control - nav_roll += constrain(wrap_180(auto_roll - nav_roll), -g.auto_slew_rate.get(), g.auto_slew_rate.get()); // 40 deg a second + nav_roll += constrain(wrap_180(auto_roll - nav_roll), -g.auto_slew_rate.get(), g.auto_slew_rate.get()); // 40 deg a second nav_pitch += constrain(wrap_180(auto_pitch - nav_pitch), -g.auto_slew_rate.get(), g.auto_slew_rate.get()); // 40 deg a second control_roll = g.rc_1.control_mix(nav_roll); From 691340022122c0d528471330ee2894eb1c7a13ba Mon Sep 17 00:00:00 2001 From: Jason Short Date: Thu, 16 Feb 2012 22:07:35 -0800 Subject: [PATCH 04/33] cast D term to float just in case --- ArduCopter/Attitude.pde | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde index c9506b91b3..6c5dbbd940 100644 --- a/ArduCopter/Attitude.pde +++ b/ArduCopter/Attitude.pde @@ -21,7 +21,7 @@ get_stabilize_roll(int32_t target_angle) // limit the error we're feeding to the PID target_angle = constrain(target_angle, -2500, 2500); - // conver to desired Rate: + // convert to desired Rate: int32_t target_rate = g.pi_stabilize_roll.get_p(target_angle); int16_t iterm = g.pi_stabilize_roll.get_i(target_angle, G_Dt); @@ -115,7 +115,8 @@ get_rate_roll(int32_t target_rate) target_rate = g.pid_rate_roll.get_pid(target_rate, G_Dt); // Dampening - target_rate -= constrain((current_rate - last_rate) * g.stabilize_d, -500, 500); + int16_t d_temp = (float)(current_rate - last_rate) * g.stabilize_d; + target_rate -= constrain(d_temp, -500, 500); last_rate = current_rate; // output control: @@ -133,7 +134,8 @@ get_rate_pitch(int32_t target_rate) target_rate = g.pid_rate_pitch.get_pid(target_rate, G_Dt); // Dampening - target_rate -= constrain((current_rate - last_rate) * g.stabilize_d, -500, 500); + int16_t d_temp = (float)(current_rate - last_rate) * g.stabilize_d; + target_rate -= constrain(d_temp, -500, 500); last_rate = current_rate; // output control: From 6732f0934a97f7180be7a9964720ad53bcb894e3 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Thu, 16 Feb 2012 22:07:54 -0800 Subject: [PATCH 05/33] cast to float --- ArduCopter/motors_octa_quad.pde | 4 ++-- ArduCopter/motors_quad.pde | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/ArduCopter/motors_octa_quad.pde b/ArduCopter/motors_octa_quad.pde index 17094cf699..1728d0754f 100644 --- a/ArduCopter/motors_octa_quad.pde +++ b/ArduCopter/motors_octa_quad.pde @@ -40,8 +40,8 @@ static void output_motors_armed() g.rc_4.calc_pwm(); if(g.frame_orientation == X_FRAME){ - roll_out = g.rc_1.pwm_out * .707; - pitch_out = g.rc_2.pwm_out * .707; + roll_out = (float)g.rc_1.pwm_out * 0.707; + pitch_out = (float)g.rc_2.pwm_out * 0.707; motor_out[MOT_1] = ((g.rc_3.radio_out * g.top_bottom_ratio) - roll_out + pitch_out); // APM2 OUT1 APM1 OUT1 FRONT RIGHT CCW TOP motor_out[MOT_2] = ((g.rc_3.radio_out * g.top_bottom_ratio) + roll_out + pitch_out); // APM2 OUT2 APM1 OUT2 FRONT LEFT CW TOP diff --git a/ArduCopter/motors_quad.pde b/ArduCopter/motors_quad.pde index 55c21f7b97..eb29581ea3 100644 --- a/ArduCopter/motors_quad.pde +++ b/ArduCopter/motors_quad.pde @@ -37,8 +37,8 @@ static void output_motors_armed() if(g.frame_orientation == X_FRAME){ - roll_out = g.rc_1.pwm_out * .707; - pitch_out = g.rc_2.pwm_out * .707; + roll_out = (float)g.rc_1.pwm_out * 0.707; + pitch_out = (float)g.rc_2.pwm_out * 0.707; // left motor_out[MOT_3] = g.rc_3.radio_out + roll_out + pitch_out; // FRONT From cbe297b634ca03e0c6ecbd3ba3e6c99b84acd3e9 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Thu, 16 Feb 2012 22:08:07 -0800 Subject: [PATCH 06/33] scaled X velocity --- ArduCopter/navigation.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/navigation.pde b/ArduCopter/navigation.pde index a2b178fca5..d7e9ce933c 100644 --- a/ArduCopter/navigation.pde +++ b/ArduCopter/navigation.pde @@ -55,7 +55,7 @@ static void calc_XY_velocity(){ // straightforward approach: ///* - x_actual_speed = x_speed_old + (float)(g_gps->longitude - last_longitude) * tmp; + x_actual_speed = x_speed_old + (float)(g_gps->longitude - last_longitude) * scaleLongDown * tmp; y_actual_speed = y_speed_old + (float)(g_gps->latitude - last_latitude) * tmp; x_actual_speed = x_actual_speed >> 1; From 75919436aca9b83d685ce3a95b06405f68315eb3 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Thu, 16 Feb 2012 22:08:19 -0800 Subject: [PATCH 07/33] added extra gain logging --- ArduCopter/system.pde | 20 ++++++++++++++++---- 1 file changed, 16 insertions(+), 4 deletions(-) diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index 1d6c8832fb..e6637a1fe0 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -327,10 +327,22 @@ static void init_ardupilot() #if LOGGING_ENABLED == ENABLED Log_Write_Startup(); - Log_Write_Data(10, g.pi_stabilize_roll.kP()); - Log_Write_Data(11, g.pi_stabilize_pitch.kP()); - Log_Write_Data(12, g.pid_rate_roll.kP()); - Log_Write_Data(13, g.pid_rate_pitch.kP()); + Log_Write_Data(10, (float)g.pi_stabilize_roll.kP()); + Log_Write_Data(11, (float)g.pi_stabilize_roll.kI()); + + Log_Write_Data(12, (float)g.pid_rate_roll.kP()); + Log_Write_Data(13, (float)g.pid_rate_roll.kI()); + Log_Write_Data(14, (float)g.pid_rate_roll.kD()); + Log_Write_Data(15, (float)g.stabilize_d.get()); + + Log_Write_Data(16, (float)g.pi_loiter_lon.kP()); + Log_Write_Data(17, (float)g.pi_loiter_lon.kI()); + + Log_Write_Data(18, (float)g.pid_nav_lon.kP()); + Log_Write_Data(19, (float)g.pid_nav_lon.kI()); + Log_Write_Data(20, (float)g.pid_nav_lon.kD()); + + Log_Write_Data(21, (int32_t)g.auto_slew_rate.get()); #endif SendDebug("\nReady to FLY "); From 560985b50961833649fe6586f6a50a4d7707982b Mon Sep 17 00:00:00 2001 From: Jason Short Date: Thu, 16 Feb 2012 22:09:14 -0800 Subject: [PATCH 08/33] made I term return in same pattern as D term --- libraries/AC_PID/AC_PID.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AC_PID/AC_PID.cpp b/libraries/AC_PID/AC_PID.cpp index b68c79d005..3034468352 100755 --- a/libraries/AC_PID/AC_PID.cpp +++ b/libraries/AC_PID/AC_PID.cpp @@ -28,8 +28,9 @@ int32_t AC_PID::get_i(int32_t error, float dt) } else if (_integrator > _imax) { _integrator = _imax; } + return _integrator; } - return _integrator; + return 0; } int32_t AC_PID::get_d(int32_t input, float dt) @@ -73,8 +74,7 @@ int32_t AC_PID::get_pid(int32_t error, float dt) // Compute derivative component if time has elapsed if ((fabs(_kd) > 0) && (dt > 0)) { - - _derivative = (error - _last_input) / dt; + _derivative = (error - _last_error) / dt; // discrete low pass filter, cuts out the // high frequency noise that can drive the controller crazy @@ -82,7 +82,7 @@ int32_t AC_PID::get_pid(int32_t error, float dt) (dt / ( _filter + dt)) * (_derivative - _last_derivative); // update state - _last_input = error; + _last_error = error; _last_derivative = _derivative; // add in derivative component From 9c7b8586d537e37b269b177272561974b187921f Mon Sep 17 00:00:00 2001 From: Jason Short Date: Thu, 16 Feb 2012 22:19:39 -0800 Subject: [PATCH 09/33] Adjusted gains to move closer to Marco's tests --- ArduCopter/config.h | 20 ++++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/ArduCopter/config.h b/ArduCopter/config.h index eb9cc0bf97..aecf13b8fd 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -555,7 +555,7 @@ #ifndef STABILIZE_D -# define STABILIZE_D .06 +# define STABILIZE_D .2 #endif @@ -567,7 +567,7 @@ // Good for smaller payload motors. #ifndef STABILIZE_ROLL_P -# define STABILIZE_ROLL_P 4.5 +# define STABILIZE_ROLL_P 4 #endif #ifndef STABILIZE_ROLL_I # define STABILIZE_ROLL_I 0.0 @@ -577,7 +577,7 @@ #endif #ifndef STABILIZE_PITCH_P -# define STABILIZE_PITCH_P 4.5 +# define STABILIZE_PITCH_P 4 #endif #ifndef STABILIZE_PITCH_I # define STABILIZE_PITCH_I 0.0 @@ -587,7 +587,7 @@ #endif #ifndef STABILIZE_YAW_P -# define STABILIZE_YAW_P 7.5 // increase for more aggressive Yaw Hold, decrease if it's bouncy +# define STABILIZE_YAW_P 7.0 // increase for more aggressive Yaw Hold, decrease if it's bouncy #endif #ifndef STABILIZE_YAW_I # define STABILIZE_YAW_I 0.01 @@ -601,26 +601,26 @@ // Stabilize Rate Control // #ifndef RATE_ROLL_P -# define RATE_ROLL_P 0.14 +# define RATE_ROLL_P 0.12 #endif #ifndef RATE_ROLL_I -# define RATE_ROLL_I 0.18 +# define RATE_ROLL_I 0.02 #endif #ifndef RATE_ROLL_D -# define RATE_ROLL_D 0.0025 +# define RATE_ROLL_D 0.008 #endif #ifndef RATE_ROLL_IMAX # define RATE_ROLL_IMAX 5 // degrees #endif #ifndef RATE_PITCH_P -# define RATE_PITCH_P 0.14 +# define RATE_PITCH_P 0.12 #endif #ifndef RATE_PITCH_I -# define RATE_PITCH_I 0.18 +# define RATE_PITCH_I 0.02 #endif #ifndef RATE_PITCH_D -# define RATE_PITCH_D 0.0025 +# define RATE_PITCH_D 0.008 #endif #ifndef RATE_PITCH_IMAX # define RATE_PITCH_IMAX 5 // degrees From 03aa28224b1ea295ab7dccb032e8b8156361bbd6 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Thu, 16 Feb 2012 22:38:23 -0800 Subject: [PATCH 10/33] re-implemented WII Dampening filter for Marco. --- ArduCopter/Attitude.pde | 51 +++++++++++++++++++++++++++++++++-------- 1 file changed, 41 insertions(+), 10 deletions(-) diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde index 6c5dbbd940..80af18322c 100644 --- a/ArduCopter/Attitude.pde +++ b/ArduCopter/Attitude.pde @@ -107,17 +107,34 @@ get_acro_yaw(int32_t target_rate) static int get_rate_roll(int32_t target_rate) { + int16_t rate_d1 = 0; + static int16_t rate_d2 = 0; + static int16_t rate_d3 = 0; static int32_t last_rate = 0; + int32_t current_rate = (omega.x * DEGX100); + // History of last 3 dir + rate_d3 = rate_d2; + rate_d2 = rate_d1; + rate_d1 = current_rate - last_rate; + last_rate = current_rate; + // rate control - target_rate = target_rate - current_rate; - target_rate = g.pid_rate_roll.get_pid(target_rate, G_Dt); + target_rate = target_rate - current_rate; + target_rate = g.pid_rate_roll.get_pid(target_rate, G_Dt); // Dampening - int16_t d_temp = (float)(current_rate - last_rate) * g.stabilize_d; - target_rate -= constrain(d_temp, -500, 500); - last_rate = current_rate; + //int16_t d_temp = (float)(current_rate - last_rate) * g.stabilize_d; + //target_rate -= constrain(d_temp, -500, 500); + //last_rate = current_rate; + + // D term + // I had tried this before with little result. Recently, someone mentioned to me that + // MultiWii uses a filter of the last three to get around noise and get a stronger signal. + // Works well! Thanks! + int16_t d_temp = (rate_d1 + rate_d2 + rate_d3) * g.stabilize_d; + target_rate -= d_temp; // output control: return constrain(target_rate, -2500, 2500); @@ -126,17 +143,31 @@ get_rate_roll(int32_t target_rate) static int get_rate_pitch(int32_t target_rate) { + int16_t rate_d1 = 0; + static int16_t rate_d2 = 0; + static int16_t rate_d3 = 0; static int32_t last_rate = 0; + int32_t current_rate = (omega.y * DEGX100); + // History of last 3 dir + rate_d3 = rate_d2; + rate_d2 = rate_d1; + rate_d1 = current_rate - last_rate; + last_rate = current_rate; + // rate control - target_rate = target_rate - current_rate; - target_rate = g.pid_rate_pitch.get_pid(target_rate, G_Dt); + target_rate = target_rate - current_rate; + target_rate = g.pid_rate_pitch.get_pid(target_rate, G_Dt); // Dampening - int16_t d_temp = (float)(current_rate - last_rate) * g.stabilize_d; - target_rate -= constrain(d_temp, -500, 500); - last_rate = current_rate; + //int16_t d_temp = (float)(current_rate - last_rate) * g.stabilize_d; + //target_rate -= constrain(d_temp, -500, 500); + //last_rate = current_rate; + + // D term + int16_t d_temp = (rate_d1 + rate_d2 + rate_d3) * g.stabilize_d; + target_rate -= d_temp; // output control: return constrain(target_rate, -2500, 2500); From d0c67debeea2436f25383b284f896d8e62d79b3d Mon Sep 17 00:00:00 2001 From: Michael Oborne Date: Fri, 17 Feb 2012 17:09:27 +0800 Subject: [PATCH 11/33] APM Planner 1.1.37 fix misc errors update polish fix linux/mac bug. - seems alot more stable --- .../ArdupilotMegaPlanner/ArdupilotMega.csproj | 5 +- .../Controls/ImageLabel.cs | 2 +- Tools/ArdupilotMegaPlanner/Controls/myGMAP.cs | 39 ++++++ Tools/ArdupilotMegaPlanner/CurrentState.cs | 12 +- .../GCSViews/FlightData.Designer.cs | 4 +- .../GCSViews/FlightData.cs | 15 ++- .../GCSViews/FlightPlanner.Designer.cs | 4 +- .../GCSViews/Simulation.cs | 127 ++++++++++++++---- Tools/ArdupilotMegaPlanner/HIL/Utils.cs | 20 +-- Tools/ArdupilotMegaPlanner/HUD.cs | 14 +- Tools/ArdupilotMegaPlanner/MainV2.cs | 4 +- Tools/ArdupilotMegaPlanner/Program.cs | 2 + .../Properties/AssemblyInfo.cs | 2 +- .../bin/Release/ArdupilotMegaPlanner.pdb | Bin 886272 -> 890368 bytes 14 files changed, 202 insertions(+), 48 deletions(-) create mode 100644 Tools/ArdupilotMegaPlanner/Controls/myGMAP.cs diff --git a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj index a0ee6c833b..e00cfbd8f9 100644 --- a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj +++ b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj @@ -242,11 +242,14 @@ - UserControl + Component ImageLabel.cs + + UserControl + Form diff --git a/Tools/ArdupilotMegaPlanner/Controls/ImageLabel.cs b/Tools/ArdupilotMegaPlanner/Controls/ImageLabel.cs index 2e9637b0d1..a5524d2cd4 100644 --- a/Tools/ArdupilotMegaPlanner/Controls/ImageLabel.cs +++ b/Tools/ArdupilotMegaPlanner/Controls/ImageLabel.cs @@ -9,7 +9,7 @@ using System.Windows.Forms; namespace ArdupilotMega { - public partial class ImageLabel : UserControl + public partial class ImageLabel : ContainerControl { public new event EventHandler Click; diff --git a/Tools/ArdupilotMegaPlanner/Controls/myGMAP.cs b/Tools/ArdupilotMegaPlanner/Controls/myGMAP.cs new file mode 100644 index 0000000000..8af08373f7 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/Controls/myGMAP.cs @@ -0,0 +1,39 @@ +using System; +using System.Collections.Generic; +using System.Linq; +using System.Text; + +namespace ArdupilotMega +{ + class myGMAP : GMap.NET.WindowsForms.GMapControl + { + public bool inOnPaint = false; + + protected override void OnPaint(System.Windows.Forms.PaintEventArgs e) + { + if (inOnPaint) + { + Console.WriteLine("Was in onpaint Gmap th:" + System.Threading.Thread.CurrentThread.Name); + return; + } + inOnPaint = true; + + try + { + base.OnPaint(e); + } + catch (Exception ex) { Console.WriteLine(ex.ToString()); } + + inOnPaint = false; + } + + protected override void OnMouseMove(System.Windows.Forms.MouseEventArgs e) + { + try + { + base.OnMouseMove(e); + } + catch (Exception ex) { Console.WriteLine(ex.ToString()); } + } + } +} diff --git a/Tools/ArdupilotMegaPlanner/CurrentState.cs b/Tools/ArdupilotMegaPlanner/CurrentState.cs index 57709156c8..fa10636601 100644 --- a/Tools/ArdupilotMegaPlanner/CurrentState.cs +++ b/Tools/ArdupilotMegaPlanner/CurrentState.cs @@ -309,12 +309,18 @@ namespace ArdupilotMega if (ind != -1) logdata = logdata.Substring(0, ind); - while (messages.Count > 5) + try { - messages.RemoveAt(0); - } + while (messages.Count > 5) + { + messages.RemoveAt(0); + } + messages.Add(logdata + "\n"); + } + catch { } + mavinterface.packets[MAVLink.MAVLINK_MSG_ID_STATUSTEXT] = null; } diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs index b9ecf16a80..b125db82f4 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs @@ -55,7 +55,7 @@ this.zg1 = new ZedGraph.ZedGraphControl(); this.lbl_winddir = new ArdupilotMega.MyLabel(); this.lbl_windvel = new ArdupilotMega.MyLabel(); - this.gMapControl1 = new GMap.NET.WindowsForms.GMapControl(); + this.gMapControl1 = new myGMAP(); this.panel1 = new System.Windows.Forms.Panel(); this.TXT_lat = new ArdupilotMega.MyLabel(); this.Zoomlevel = new System.Windows.Forms.NumericUpDown(); @@ -1320,7 +1320,7 @@ private ArdupilotMega.MyLabel TXT_long; private ArdupilotMega.MyLabel TXT_alt; private System.Windows.Forms.CheckBox CHK_autopan; - private GMap.NET.WindowsForms.GMapControl gMapControl1; + private myGMAP gMapControl1; private ZedGraph.ZedGraphControl zg1; private System.Windows.Forms.TabControl tabControl1; private System.Windows.Forms.TabPage tabGauges; diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs index 31a96a2db7..5094e64519 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs @@ -369,7 +369,7 @@ namespace ArdupilotMega.GCSViews try { //Console.WriteLine(DateTime.Now.Millisecond); - MainV2.cs.UpdateCurrentSettings(bindingSource1); + updateBindingSource(); //Console.WriteLine(DateTime.Now.Millisecond + " done "); if (tunning.AddMilliseconds(50) < DateTime.Now && CB_tuning.Checked == true) @@ -402,6 +402,11 @@ namespace ArdupilotMega.GCSViews { gMapControl1.HoldInvalidation = true; + while (gMapControl1.inOnPaint == true) + { + System.Threading.Thread.Sleep(1); + } + if (trackPoints.Count > int.Parse(MainV2.config["NUM_tracklength"].ToString())) { trackPoints.RemoveRange(0, trackPoints.Count - int.Parse(MainV2.config["NUM_tracklength"].ToString())); @@ -500,6 +505,14 @@ namespace ArdupilotMega.GCSViews Console.WriteLine("FD Main loop exit"); } + private void updateBindingSource() + { + this.Invoke((System.Windows.Forms.MethodInvoker)delegate() + { + MainV2.cs.UpdateCurrentSettings(bindingSource1); + }); + } + private void updateMapPosition(PointLatLng currentloc) { this.BeginInvoke((MethodInvoker)delegate() diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.Designer.cs index d4b7fcea02..4f77a22a7e 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.Designer.cs @@ -101,7 +101,7 @@ this.lbl_distance = new System.Windows.Forms.Label(); this.lbl_homedist = new System.Windows.Forms.Label(); this.lbl_prevdist = new System.Windows.Forms.Label(); - this.MainMap = new GMap.NET.WindowsForms.GMapControl(); + this.MainMap = new myGMAP(); this.contextMenuStrip1 = new System.Windows.Forms.ContextMenuStrip(this.components); this.deleteWPToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem(); this.loiterToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem(); @@ -979,7 +979,7 @@ private BSE.Windows.Forms.Panel panelWaypoints; private BSE.Windows.Forms.Panel panelAction; private System.Windows.Forms.Panel panelMap; - private GMap.NET.WindowsForms.GMapControl MainMap; + private myGMAP MainMap; private MyTrackBar trackBar1; private System.Windows.Forms.Label label11; private System.Windows.Forms.Label lbl_distance; diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs index 50a4a64515..8c408cb277 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs @@ -81,6 +81,31 @@ namespace ArdupilotMega.GCSViews public uint magic; } + [StructLayout(LayoutKind.Sequential, Pack = 1)] + public struct sitldata + { + public double lat; + public double lon; + public double alt; + public double heading; + public double v_north; + public double v_east; + public double ax; + public double ay; + public double az; + public double phidot; + public double thetadot; + public double psidot; + public double phi; + public double theta; + /// + /// heading + /// + public double psi; + public double vcas; + public int check; + } + const int AEROSIMRC_MAX_CHANNELS = 39; //----------------------------------------------------------------------------- @@ -263,6 +288,11 @@ namespace ArdupilotMega.GCSViews SetupUDPRecv(); + if (chkSensor.Checked) + { + SITLSEND = new UdpClient(simIP, 5501); + } + if (RAD_softXplanes.Checked) { SetupUDPXplanes(); @@ -286,12 +316,9 @@ namespace ArdupilotMega.GCSViews System.Threading.Thread.Sleep(2000); - SITLSEND = new UdpClient(simIP, 5501); - SetupTcpJSBSim(); // old style } - SetupUDPXplanes(); // fg udp style SetupUDPMavLink(); // pass traffic - raw } @@ -545,7 +572,7 @@ namespace ArdupilotMega.GCSViews Console.WriteLine("REQ streams - sim"); try { - if (CHK_quad.Checked && !RAD_aerosimrc.Checked) + if (CHK_quad.Checked && !RAD_aerosimrc.Checked)// || chkSensor.Checked && RAD_JSBSim.Checked) { comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_RAW_CONTROLLER, 0); // request servoout } @@ -567,6 +594,8 @@ namespace ArdupilotMega.GCSViews int recv = SimulatorRECV.ReceiveFrom(udpdata, ref Remote); RECVprocess(udpdata, recv, comPort); + + hzcount++; } } catch @@ -598,7 +627,7 @@ namespace ArdupilotMega.GCSViews if ((DateTime.Now - simsendtime).TotalMilliseconds > 19) { - hzcount++; + //hzcount++; simsendtime = DateTime.Now; processArduPilot(); } @@ -607,7 +636,7 @@ namespace ArdupilotMega.GCSViews if (hzcounttime.Second != DateTime.Now.Second) { - // Console.WriteLine("SIM hz {0}", hzcount); + Console.WriteLine("SIM hz {0}", hzcount); hzcount = 0; hzcounttime = DateTime.Now; } @@ -758,26 +787,13 @@ namespace ArdupilotMega.GCSViews float rdiff = (float)((att.roll - oldatt.roll) / timediff.TotalSeconds); float ydiff = (float)((att.yaw - oldatt.yaw) / timediff.TotalSeconds); - //Console.WriteLine("{0:0.00000} {1:0.00000} {2:0.00000} \t {3:0.00000} {4:0.00000} {5:0.00000}", pdiff, rdiff, ydiff, DATA[17][0], DATA[17][1], DATA[17][2]); +// Console.WriteLine("{0:0.00000} {1:0.00000} {2:0.00000} \t {3:0.00000} {4:0.00000} {5:0.00000}", pdiff, rdiff, ydiff, DATA[17][0], DATA[17][1], DATA[17][2]); oldatt = att; - if (xplane9) - { - rdiff = DATA[17][1]; - pdiff = DATA[17][0]; - ydiff = DATA[17][2]; - } - else - { - rdiff = DATA[16][1]; - pdiff = DATA[16][0]; - ydiff = DATA[16][2]; - } - - Int16 xgyro = Constrain(rdiff * 1000.0, Int16.MinValue, Int16.MaxValue); - Int16 ygyro = Constrain(pdiff * 1000.0, Int16.MinValue, Int16.MaxValue); - Int16 zgyro = Constrain(ydiff * 1000.0, Int16.MinValue, Int16.MaxValue); + Int16 xgyro = Constrain(att.rollspeed * 1000.0, Int16.MinValue, Int16.MaxValue); + Int16 ygyro = Constrain(att.pitchspeed * 1000.0, Int16.MinValue, Int16.MaxValue); + Int16 zgyro = Constrain(att.yawspeed * 1000.0, Int16.MinValue, Int16.MaxValue); oldtime = DateTime.Now; @@ -849,7 +865,7 @@ namespace ArdupilotMega.GCSViews gps.v = ((float)(DATA[3][7] * 0.44704)); #endif - asp.airspeed = ((float)(DATA[3][6] * 0.44704)); + asp.airspeed = ((float)(DATA[3][5] * 0.44704)); } @@ -1160,6 +1176,50 @@ namespace ArdupilotMega.GCSViews return; } + if (RAD_softXplanes.Checked && chkSensor.Checked) + { + sitldata sitlout = new sitldata(); + + ArdupilotMega.HIL.Utils.FLIGHTtoBCBF(ref att.pitchspeed, ref att.rollspeed, ref att.yawspeed, DATA[19][0] * deg2rad, DATA[19][1] * deg2rad); + + //Console.WriteLine("{0:0.00000} {1:0.00000} {2:0.00000} \t {3:0.00000} {4:0.00000} {5:0.00000}", att.pitchspeed, att.rollspeed, att.yawspeed, DATA[17][0], DATA[17][1], DATA[17][2]); + + Tuple ans = ArdupilotMega.HIL.Utils.OGLtoBCBF(att.pitch, att.roll, att.yaw, 0, 0, 9.8); + + //Console.WriteLine("acc {0:0.00000} {1:0.00000} {2:0.00000} \t {3:0.00000} {4:0.00000} {5:0.00000}", ans.Item1, ans.Item2, ans.Item3, accel3D.X, accel3D.Y, accel3D.Z); + + sitlout.alt = gps.alt; + sitlout.lat = gps.lat; + sitlout.lon = gps.lon; + sitlout.heading = gps.hdg; + + sitlout.v_north = DATA[21][4]; + sitlout.v_east = DATA[21][5]; + + // correct accel + sitlout.ax = -ans.Item2; // pitch + sitlout.ay = -ans.Item1; // roll + sitlout.az = ans.Item3; // yaw + + sitlout.phidot = -0.5;// att.pitchspeed; +// sitlout.thetadot = att.rollspeed; + //sitlout.psidot = att.yawspeed; + + sitlout.phi = att.roll * rad2deg; + sitlout.theta = att.pitch * rad2deg; + sitlout.psi = att.yaw * rad2deg; + + sitlout.vcas = asp.airspeed; + + sitlout.check = (int)0x4c56414e; + + byte[] sendme = StructureToByteArray(sitlout); + + SITLSEND.Send(sendme,sendme.Length); + + return; + } + #if MAVLINK10 TimeSpan gpsspan = DateTime.Now - lastgpsupdate; @@ -1624,6 +1684,25 @@ namespace ArdupilotMega.GCSViews } } + byte[] StructureToByteArray(object obj) + { + + int len = Marshal.SizeOf(obj); + + byte[] arr = new byte[len]; + + IntPtr ptr = Marshal.AllocHGlobal(len); + + Marshal.StructureToPtr(obj, ptr, true); + + Marshal.Copy(ptr, arr, 0, len); + + Marshal.FreeHGlobal(ptr); + + return arr; + + } + private void RAD_softXplanes_CheckedChanged(object sender, EventArgs e) { diff --git a/Tools/ArdupilotMegaPlanner/HIL/Utils.cs b/Tools/ArdupilotMegaPlanner/HIL/Utils.cs index 4d55cd86c3..c3522d9b2a 100644 --- a/Tools/ArdupilotMegaPlanner/HIL/Utils.cs +++ b/Tools/ArdupilotMegaPlanner/HIL/Utils.cs @@ -175,19 +175,19 @@ namespace ArdupilotMega.HIL // The +Y axis points straight up away from the center of the earth at the reference point. // First we shall convert from this East Up South frame, to a more conventional NED (North East Down) frame. - x_NED = radians(x) * -1.0; - y_NED = radians(y) * 1.0; - z_NED = radians(z) * -1.0; + x_NED = (x) * -1.0; + y_NED = (y) * 1.0; + z_NED = (z) * -1.0; // Next calculate cos & sin of angles for use in the transformation matrix. // r, p & y subscripts stand for roll pitch and yaw. - Cr = Math.Cos(radians(phi)); - Cp = Math.Cos(radians(theta)); - Cy = Math.Cos(radians(psi)); - Sr = Math.Sin(radians(phi)); - Sp = Math.Sin(radians(theta)); - Sy = Math.Sin(radians(psi)); + Cr = Math.Cos((phi)); + Cp = Math.Cos((theta)); + Cy = Math.Cos((psi)); + Sr = Math.Sin((phi)); + Sp = Math.Sin((theta)); + Sy = Math.Sin((psi)); // Next we need to rotate our accelerations from the NED reference frame, into the body fixed reference frame @@ -202,7 +202,7 @@ namespace ArdupilotMega.HIL y = (x_NED * ((Sr * Sp * Cy) - (Cr * Sy))) + (y_NED * ((Sr * Sp * Sy) + (Cr * Cy))) + (z_NED * Sr * Cp); z = (x_NED * ((Cr * Sp * Cy) + (Sr * Sy))) + (y_NED * ((Cr * Sp * Sy) - (Sr * Cy))) + (z_NED * Cr * Cp); - return new Tuple(degrees(x), degrees(y), degrees(z)); + return new Tuple((x), (y), (z)); } diff --git a/Tools/ArdupilotMegaPlanner/HUD.cs b/Tools/ArdupilotMegaPlanner/HUD.cs index cce7c32b16..2b01f3242d 100644 --- a/Tools/ArdupilotMegaPlanner/HUD.cs +++ b/Tools/ArdupilotMegaPlanner/HUD.cs @@ -240,6 +240,8 @@ namespace hud started = true; } + bool inOnPaint = false; + protected override void OnPaint(PaintEventArgs e) { //GL.Enable(EnableCap.AlphaTest) @@ -261,6 +263,14 @@ namespace hud return; } + if (inOnPaint) + { + Console.WriteLine("Was in onpaint Hud th:" + System.Threading.Thread.CurrentThread.Name); + return; + } + + inOnPaint = true; + starttime = DateTime.Now; try @@ -284,6 +294,8 @@ namespace hud } catch (Exception ex) { Console.WriteLine(ex.ToString()); } + inOnPaint = false; + count++; huddrawtime += (int)(DateTime.Now - starttime).TotalMilliseconds; @@ -1479,7 +1491,7 @@ namespace hud if (e == null || P == null || pth == null || pth.PointCount == 0) return; - if (!ArdupilotMega.MainV2.MONO) + //if (!ArdupilotMega.MainV2.MONO) e.DrawPath(P, pth); //Draw the face diff --git a/Tools/ArdupilotMegaPlanner/MainV2.cs b/Tools/ArdupilotMegaPlanner/MainV2.cs index eeab0ed1c8..ffbb76efdf 100644 --- a/Tools/ArdupilotMegaPlanner/MainV2.cs +++ b/Tools/ArdupilotMegaPlanner/MainV2.cs @@ -233,9 +233,9 @@ namespace ArdupilotMega double Framework = Convert.ToDouble(version_names[version_names.Length - 1].Remove(0, 1), CultureInfo.InvariantCulture); int SP = Convert.ToInt32(installed_versions.OpenSubKey(version_names[version_names.Length - 1]).GetValue("SP", 0)); - if (Framework < 4.0) + if (Framework < 3.5) { - MessageBox.Show("This program requires .NET Framework 4.0 +. You currently have " + Framework); + MessageBox.Show("This program requires .NET Framework 3.5. You currently have " + Framework); } } diff --git a/Tools/ArdupilotMegaPlanner/Program.cs b/Tools/ArdupilotMegaPlanner/Program.cs index 9cd29cbabe..58c39688c0 100644 --- a/Tools/ArdupilotMegaPlanner/Program.cs +++ b/Tools/ArdupilotMegaPlanner/Program.cs @@ -33,6 +33,8 @@ namespace ArdupilotMega Application.SetCompatibleTextRenderingDefault(false); try { + System.Threading.Thread.CurrentThread.Name = "Base Thread"; + Application.Run(new MainV2()); } catch (Exception ex) { Console.WriteLine(ex.ToString()); } diff --git a/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs b/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs index 7b31841394..3a28cbf8cf 100644 --- a/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs +++ b/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs @@ -34,5 +34,5 @@ using System.Resources; // by using the '*' as shown below: // [assembly: AssemblyVersion("1.0.*")] [assembly: AssemblyVersion("1.0.0.0")] -[assembly: AssemblyFileVersion("1.1.36")] +[assembly: AssemblyFileVersion("1.1.37")] [assembly: NeutralResourcesLanguageAttribute("")] diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.pdb b/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.pdb index 6046b97ded3c42894014bb0f8548bf0cd3a56757..11b35bd52b6ec275bd0b58728c7f1b031cea281b 100644 GIT binary patch delta 171241 zcmZ_12S60Z`#!!iyBr(>(xpjnA|iH0M8K|yXspBniX9aYYY@;Fd&4NN5>&87ja|&y zqlrm0QDaMD4^fk-Q3P9zvHYLeyTj%4{rxX_nA>@t_no@4GqbyA{-Wmj+nX;7wfj*g zNu%mY>gSYhAG7*_?d4ZEm)`DUJeV!lIa_}ry?duXAm@X=&GuR;+%2t6Ob>>*-&S=k z*zNti$I{QrJUVRYw{M@9b+}@G@YvE?zjD{f_YdBlxnTT2*FAAt*mAqh8#>$D+vl`T z8JXwvcb#=s4_>|8b7hO*_WE~rtUWJp=HCxrUHNju^Zpy}+<9gAy^Q;?f}{m|n|IdP zckFw><$Be4Hp4(3S zGpNmo4V`xEs-+THowxFMBGfKW}@#KhDNXZ`N{U z`|d?5u>uwinm9knSyptX|A=>wtv3JJS0z^64WNt+Tg8x{VY`JzTHQ|8T)?U z&0}>KbD|U3wuVo)AAd>tlWnc`?LLtsliPG#w|(uuJtb4wFk3f^F=(){pVmA54Q(H4 z>z3CJjnE#L419$a`3~3s$wuHEN2DxC3`hqyA#OA9IWP{#re!%x1fiu8az*&)cNb%?z?SS^cc8GQW9q@e)Fc+8y>_pryU^lP_n2)#x zz+Qac2V_`C(rAR~x;=4GtX4o19OHu!J?;@(e$GnS86!!bo;a7ZZ{WE%L7$HML$4b* ztyA~7q)#2Len8_p+164@bvDc=FFZ<;76TErC20+iA1z5Y0P(T0m!xUH|9J^F_0J54%(nSCtYGcbfcqBHKr2T;T^UOz*ditV@ zT2rwt^Kf@JWk~RQ8%UB%gd~lrkG7znY+0Q~QAl$YFiS5EpGM&WIm z6~uYa_}Z*#--qEy1KEl|D}D+*Xd_82QTd+%323@<Cvzz}*_n}yj%!1rPx9^H8}^_*|xRFGs(z3iD=;&-U#hR9R}nlGs} zdcCD2Sz1ZbhwyaI8J*GvNx;1aTDv8(Q~+o{(~;yQz#i3=S&t6bvoN-)AZ|dRBU5ar z+DVfC<I1=CyrJy)9d@1u8rwWuFD_vX8IXIlg!4P*PEZ6(j!k!<7Z zNzwiBU9_vnjcD892+bc+S!V5)S;x81ib@n(!D+RhdZ}9a%8>=x|Abss8}8V{1GLM!@@@GCfz zmX42kD^5?L9UMtN zxUv!6qQjdtz252Ps6|Aa(7X(z#5ydBBI_Vw(O0X5VXu5D(4yWFt^P7d!Pu`j>gyJL-!k#VYtq`WUq3rkYhdrfCALf)N&O;%1 zicp)XI0ekk0@q!$63)b_A+&G=Zp-(YIWM}c5E?NM3(eh@G{S>*)IS@) z&_%@WrTrePhvNQ;ZFjQrL^rtXiCReVWV7?cz-CUW?uO5s3Aq^Xgd4$Wvn~c(v$oyK zdPzbn24SHUoK`CaP_y=@(Z|mVtr%E^R&XXQg?O<>gaS z(Kcwv-W#1rT!GBaT3rcI6Bbt{AzaX$BD`6aW7G}rmBPVGjLsrH(UNX?GY`e)=JX_b z?ag{CKE2MKquxF&RR3SyDodgLjy~~W?FNX8quG7h+>dVxN?bIB8^LMIC9bw+?aeJq z7YMDm3Ja~^wAwRN;KrOydhr*Q@%!O8P!}r8}$_o8iAbU(f z{>(>yyqZyuU*rLX5`SjRSTucA!CdJ?0IS0s=xP89K>+oqtPZUVWG$FGoegBISs3Yq zSQFNP+61w=>>Pa?!~zi94`K`19hwx(n()^}v@Mv;VqK^~2=ifG4BbQ6NSRgA{xDd& z)BP~kkfo7(eFPJzOMQ4Pq))`rM%rH=lF4+xK07S)Qby~R%U!54oQ1Lga&N#oAfH1T zum)@tEjAuq5=ZNaMX(Tg{boi!mO6K8AHf>)fdeU}0duBB5zGy#Zi-+X>O@O6sE^T1 z(s4;AJ;C=B;4vZXk<7s`x*_vq`g280690Wfaj$evR1(Ryi$XMF^<~Bl)0(o{3UV{Q zCHqi6YO_%qMGl$VsjwAmsz)YN>nRjBl{-;VD^|kX4OOjJL#{g@OS&Q5C^(vV%R{=! z^w`Sc5V1C_8!zZaiEUU{ezqGGwP7hJ=7bg8h3sRPv&}(Rbxe@q74x6C#9DQzQw($9 z9TO-yhW*LsB~W}@)|^Lnr|E53Uv_{lv}FOhL$KP?onEzN!F)@1gMTa=&-ktGv^)-V zb1ad*i-V1S4|*G?+VqKs&0*MdNTS?$*dW{-&wBBbN%Sh7Meqwr6xNO}uj%DeN;(PyIw061N9+yN>!-6%}aC_ui6n5QmD|bV2dlt!%b;G$1B0tDjOegj= z(|1S`SqE7JX zYz)-DIf|s4+(uEWOX@K`DRuPtY(cn6vV)k6Tmgh08gT-AXfHe9{E#jKm~%>7+fZT? zIhf{Eut+L@V5Kvj8ZPV##dVXNI?jOmWAEK}pD=0S@a_{PtLLIf!WUWE2)MzQStsKA zBd!DxX`E8iNT`!pTU3_Fu&AsEQ=y`%z(aP@7WC$s3{YEaAJK6ex8tefN>{lC@*?`D83MlibMRGv?F~dC0efQlzU# z7>HwQQ-~?28jrk5L5O#dg6R79mhKe0UZ-#r-)^MhL0(?6y}uY3#Ya?Zd(6@Y0@=Va zU<+_WE{Gdkn20g!R|-nR2={BOL=#r>{e|9^Zsgp9-9}6P(*whW7X>A;`pnDFGl_L$ zY!|@y4w;#+xS8s5getCN!Wod(1MaOCJm|vuIi$*coU?A2!#jBRV1agG6cI)P#lfxkG#jx>i+CkHit3? zz~d^~G=TNs*4^mE0E~o@6qF3ZVj7f;Q8}9KC$l&nEz$7|WH0tZ=4REQyD4plp0zyb zqYsf)46LJ=3mpK>66wN+aFA%w4`fRjYeB0AA(do0I|#A2$zm{yt?NNigIRO7lrnM1 z_R*%nAfxG~I7%UhAvmg}E<=##BlPVML>{4kMeqeRNMS9wU2htZ!gARp`XdF&Pa@k? zTu^q<%2d?UG5R)@ZD2_>dMGMlH9Z;%$!c;L2FV3lGYri(fbI{2GM(Jh*j!$#Kdn#0 zD24E18r#e2(I>-^R)0D;9Qi1us^Kh;^`*=atciQy0mj0MvvLJ`Q#pV+x3rv&j)3X} zwHXP=Cup1q0%*-h)?GBN{Yd6qI105BP41(NSE5nqOewT@6p~1xZ%47w;-V8d8gtJ) z8Z?@q2~pIP+A zc+_JYjuz95aYjxYy`VSaSZn@bAVp+gy%*|>u>eR!0U{`KJR87AJ5b6fv~>A+_@6=l zjz{)pP@@S5_E#&C(xJFA0ewLkZ0ZY{eQE_z-V|m*z8TDhDO8%t>QjGw=h1^{%mmh7 zxJD-mXA9|32J0gFlYN410ZPq6=RH7+vtW(7 zQmr3?vifm|DHk*P)(WJ^iMRs6JL=Mz(kH_7U;1Ps>r)+9DdIv%pUwJ+o|}z|8A^+B zRIPZK4aFLAm}HDoQ_7iyxGS`Bl3JZ=e}9cAE2mUb;&J_J`Ot)1i;!wJQzyfu9u-VR zYu2L+lUdJds^t_=y{P9DP`#*N3Qp3+bbpGm1w?P5{!^i7N10R6k=jw|R5nwcm59b^ zIStel>NyRqGKJ<(Gx}9?St+O@(oaV-7Y(DGIV=ffY}+4QX8UwdN9o(?sKujHHJuG( z|52ZhFoCd1qxB!LU#zaBnTq08^aH91g&8R}8q3>-Pqju~u< z964N~bt||ZbH zc^5#T9rd4KM)-m}5wB?dpoT`T0#uK}-L4idKz|?ySOFXXE(4g{NNzwZ&>xrzECa+A=PBSJpjb-5 zQaI)b?SWB%m@|kisw2QXK*HRnDUg6EBJ<2k!c<}uunO1>+yI^dftXrE18G1GupKxF z+ylhqt0|BGe!wn7zOKghq(4>l`W);i)-v?h%XPv*(j_1uH|Z$6BtQ zj=`(_0;;IMSc=f~G0V3aI1t4_Wz*Wn%wNZ$NL@hR;X6n8;4$X==?f^P5>E3MP?jm& zT*;C-YDi_oWsJ6 z>k}{*Un)Qqg<#h_^&u6eZUO*ntSznR$tmjBmhcs6&r=sVWBdw+x zFIo5Z+4X(_fh7bHpHjycFh-dBk|n%XoD&KwC^mgcFN6YNO-1fMQ0SqESwWlsL5305 zRD```{x;T7>|bG8&t(p(g)7`kX3zKkulORwx>^vstfW^jSr|uH)7|ucp|FAC#7bKK zFBAyR{fiPGT1~;Pkb%>ysqZVSpavAt=2vX6s0rPFu(5^B7e%5Gd%tg&1z>FK!2JA~ zDRbinV|Hj5Xch8a#9za_HblRCMq#g6?0Y6lF!o^Lim3?SIl^PF(X8pk)cg&a=WQ{K z7vYRGwD}F{Z^;_ECXSD-A;-6DJny=WX1&Gn#C3G&EqWp{YxfR5v1-#TT1U;_v84B@ zEfI_(m_6(0%XjGE2yeY(uKe;kdht%RUfGrV+mzti)w{i}u;2++#`Pe| z?X5%BU0@OUxw)UD)T&QYblibQeohN?{OPlO{B9#Hh#L&N8;*lq zN4P-v!jVUCi@g-=gp!u*r4dfrCOYHBGEuBxe!a{vs}BE~@elS>M|V{8;Qch+ z9m&RiNqfa{;+OQNI~t<9ftq_DThk2KTn7J_f!2EPBA$1EqCB}ecoccUxeuIwe2~8O z)OIyTFEGAfW*?*|FCOeM8{1Z5c`LGsUA2;J4JZ=Al(+B*CBGP z%ah)p1LNz$qaQr>IYfnZQ4oa3>hdpn#vz*Qjl$kNMCZJb&w#_E^MQxR!xZI%{C7D_ zV|@5fQ5ola;KLt2wjjL5f zgv>!X^lcgV+ueRY7rS80^CX zxII63gkl2t?)Tys0dN-#@vNid9mqA8%fW$QLcnZ3N^=5{5W<~-#$FyA1TGZZ*T*O^ z2z7vPRuJ#Xe>g_xg0$V$KN!k-P|p5JY}yT`Ey3K`G7J&xzrx-e=Kgg{u%q4|HzBGp zQ$nPgWidL4thX|b4zV^C3i*ccp_ay8UXSL7@BmBPE7yJcgG@{FSra#N`QI-QPGO3e z_Oan@2tS~>Wnu3q5bzRvM(UQ)Z1~6gw9jyjGj`mv^by*}boqsbI?H;i(c@pe(@9%3nS+6vp7`4_xmI$J+7=&T+BY8PAh(NitZs+iXnfv2m4jyfc5MHxB(fKYsfn${S?uuSJ{&Pd$uKb#% zzTIx4VN-G_K|vCF@lgE~Q`}r*+%m+85%5qizChn^k5NCAO1tTt3@IP*bS6fxbGZB4(jm%h$ecbe?u%N%P_nikU#`d>A2iiK!a&r(?1P5E1Nj`L?}JTe z(P|&i%sI^I%fTFby*Sw#58)5QiR7KabH!=0HU$ac45&!qJ30FM+EgBoUTwIY%I%ow z!cT_603G$#FbLOwWr#>aIr*nQkaar0mM3n3h>uvMoWVr89C!&hW8*U%=nSL)vw>ou z3^)Va1zrQb*cfdIqySTa5~IAFu|R(y8(0Kv2TlU_0I?11 z21Ei0KpLjc2XNE?_+I6%QDb~ zqNzuTl?w#=O#Y!R7H0iD3gQY2vv{C9i8K1@6W#=(53_g!tdQqtaolvG9a(&}*m&qX zk%zO-Y0^YI*YvqzSZp}JFeeFR;m z@T+xceGEkRM>msAn`v;cBF?lRC`h*AQ#)0VnKg3Ewj0chb zKg7R+m;mB<6#38L(bcYo&jFDE;&Bu$nZx}#!j4bm&ZaBFSi-JsfG!h)KCLNiuEuhl zAhJNrYfXh(;wlK6i69QQHr~FW6QeL)^_<5;s*~+9560QhTy0Ia=4rg{7sMnGHqkW+ zzxg00gJ=*<-U~Dqiv=+S#Ik5wuzCrh+*BKNhJAKuiO1_J1r+3t~EmYti&% z0V)Hb>q0)Yx-wQSgy16xLUBiDAp{78z}?tGMXQ?cmtkW}5-r=hhuoc`0mr|RJ?O?F z-jt)!aL}0AFXmqQ{3uaJOo~-+JyOnM-c*0w6xWbaH=#$LS&YFM&2nooAEED~)~UFZ zs9eetZm*wLGj0*$_~F*Hb_oyTsNWwD>TR&`Bhv9R+SxCKT?13xFk@Ua;y5ZXaVZaz zk4Gysz@{z+M4&y82IK&%fZf0u;4XkWS&|#j6i5I@0r@~N zPzId$mMo=v_@ej}#Jw$iDBFFPSaFCckrX{CBP}(1c=yzdqzMy8XOEsR zK4$2UAw%hSI14k)f*NYtwKq&c+{k;r;^A)1rF@LtQZ0nR2*s_jP=vO0a5)cg6wfV) z4|cmGFFf1U-e*so9V=Xc!KK26(XMuE5Y1kJQN@PVtl$k1oL#|tieb}tCC0$v)O{s} z&EbY|E4hQXwVzjrA-0Tm6k-G_qYH)nFq3I9!BVE9#9QF@!*jyO`XTm7akQ6GSMfal z+JSDb!a@z9_i9Y0;C{<$9&XjfQS=8)XCIBl_P{@@kwzQR7x8acE}bpnbJ-#4^BKnA zLp1X<{*>Q!q{+pYnm%%*ZN-?LS2@zPV%`zi@>_#6yHTGtd?72K-`5~N1>~@n_d_sx zEsi$P>b1NDf8azH*Yd{9k}TH2qCT}+$JfcDTo~oWGk4nq*u4wHtUME$8bz#xcNbYr zD&gV$sw?G|V9Jbea|wUJM$(#6cqpa|rTk;7wjQQ}*p9;;xQXjgkhb*6dep!`I=Y_s zWEoU@18QzFwb{VqL_KccE@}(Z?uf?{$~SO@*%Z!PxQro z?AXu6+zJ)Aa|yfpW!%>WkEiNBGIe#DIj)uyiYR)v=?=fPXN$8MQhNMM@9t0sT^dsk zwM%2VAi2|yG9FN)ODnh|9O}O(&YKl}iA&lBJS)9tLgC+7s@}topmdbv-Y7>bbtqYwht9EPU9+bH^&SG!0bud6e?4XCUQ4=8_aZU z12s5^@fSNbx}QR+??H^e2&W(9=Bw2PIxPg7AjqyqPY$BXAoMuI(@i7z23mXwf>lU* zLp}QP5RZ^I)RXDA`j$ORmyHe7<}ehP#Oo}=XvAT-K)B>EUsUbF?+65+!9|BK>Uso; z8!yWnXtf}UL8PjLFWo-EL#tVbqhPUtqw}v%QAcqG`PVm$LCAQ6`c!mGEdT41<5wVT zBPjkWoNA#FH2Evcsn;~5LtpU(OXI%M2C_X4PqyG>dV>4Vq7&ST&umPEC!ky0lzuqD`=Vm~zJ|-KaQUnmb^RI@`>dH^ z{MTadXk~Mn{tXfzrLLGa(AjUG+y@7)li3y%<_@nh!=U9-YQ2^b7dz-xg2R zaO<|!l{e@Iq`DnUep{OJL-o}k4GzL)4eESmTVq-2Xa+`s+CNrLHqfF!!WcVRx}|Mt z#E-bRErt8qZLMPH!jIeuH(hLh;@zujx78V_cS3!xEe$<`&Uwz{S!{t!#c+Qd7>&+} zc^ydXF2&Jz=g}yC#?hI?Kn?DLbacF_1`Dz0ZZE^Ghfi!V#C?{-bupFT?%bcGO&iciYjJ%W5(wF2iI$ zOd7VQ2bW>eu)V?KXAI_ic6)OC6arzbQOCtIPMi% zQPl?SWZ3O*W!Xhm_?iduH?Ju8HLhO>6JJ;ip-r#(XiOMt zzrpmOA+>pf>w81P@HhMe#>@Z1?G4OkR?(xke3<^tE8`llv2ly1B*5B+roQ8`&>wuq z*DURo8hRfjH6N- zC(EsjM=o?kmfi4_&CkZD+6n{*sg0t_apXet6bOz}sUrIzIHAZ*`1da;Vyl(532>Gz*m4vc3MeT2Bm9BX!vySzGQeUo|T>LLs9jjqcCmi2X&s*OnKeV#e9aq~G<@ z*kLk^`O-e_d$F1k+tm9Iia8i6MO|hbMA!hwhY&VHco<rvNl9OYf(m!WHK1dagbfqQ^d4`&z<33LVq0@=Vkpadub&H&}WOTa4( zXDl!f$OejmGT;nw7m%=P=mtdB$65O)D|D58ZSdZg?jSC9qSNBp9$dWIy2>H{j~(nt z2oCP0Tvs_>*Bef<>x*}<3V#vnLO0o2*UduG-M>J=Zs<=46W!z$IN|QN$@Lr(Ks~!) zS~7l+oti~GJ(PN;>uopc?k)#7bccprtkz7(pcCQjy=D(Ixj9I9i|P)LY1S_CX}-#dGTpzRkk4NXBfY2W#h+cE2v4~= zXBS22LHQyQX|DB@!(@?!D!nUW;kNq8%qa2ny!Z%@i%>gTfaAbr;2|L4Zj~F*6i5Kl zfE-|1xVnqzE&J-WVWIqM90hyJ{_?MJ3QcGy->1l)7S>|i@{#N5zJTCX9F6yp&HFUl zXon99xg7-NB;qkyQ|Y&ngD;33AOhkk%2#7CO%OXlgvHZ(U)kRyEZ$h_Vv1JAvEG-} zjv@_-r(3>qZ%Z%rmfSXK<%gQy1;c`Pg?<`o*`hkFQZTyRV4la*4}NlNHR0e7Vh@O* zb`<3=w={JtQBrdgh>--PR%>#jKgJ}K@Z4Nn-p~7^j!~)#e|ZERLF^f!$Fn^F7&?sk zWztCFO^)IKd7d6wQm?>i#=8o!fpV<=xhXEvxXDr+C^yvy;mt!aMX@#N9zxeuyhSBG zvA`C5KMC9bUIO+QDguFMpf`{X%m#{qGT;pG5Ktm;_Tjy_1%<(A$$sc!%`Q@KuC(*oJYrb(ge>FAEdwXuGhhdDVdh1PlpwAW$VL3}i}XWC zb&K?)piorr0628GM2Vr*ZQPF*3nCdr&r9@Ws2s!k(Q^^?A)-<*k#{|fc2GSK13`?s zM02#nw}Kc1V!|b=&=L)BCg=u(n0$%)hG|@_6vPk^m6zyP7z&T@R+#L{Um|}#I^24! zFE`Pt-Kig5dXNKRQXqD`Y&z?cQt=$Q>29e7>K4GfNHX)HHu4d73J@c@$L0U)^bMTq zQsK1eWeN_L{W-#};qr3c;WFI{mlI5#xgRxZfX+M=!t~1u{Wi@4ThtBYU{lBKM{7Xq zhJk)^nZ9cPKL{T*ke6`xpJ{r8T*z1dOpXoZL%i%~I@eHc%y0foJW@_ZMGuOEX__$o zh2}(JFhsaBQl4j80{5dfjUX5f!OCB0L?bzZBP?trr&SABV+ck-aQjyZYYYzvdo|X0 z_#Fb9kq|^*F;*R2$icuJ&_s6dFh_~n3baL!1$3ybc zM2_bO?V6&k=3SxSrgBnsP0eTu;b;gStHNM9(^PJ3dKzDJbn}Uvf<&6B9b2pb#8dAS z*-TF0X%`K-&1BrvLML6)T+Zd_lXflSWR8xgp7oXYbqdXEA=_~DKs9D}3ycHkb?U(l zae$sy(L&xSI@H>huywpFLJx9og%iE0+JTtV5)Z12TL`V>3_Y4vJ<;bFUqN}@N-jYg z8rDY1uefNDqBih`itidDuNU=O5hG(?{0d$l!7-}BJ60~#KUS+(j5O-)(etr#PM&z7 zNPJcSO>x$D22y}*U=gqpI09S-9s){3j0`|aAPGnZW&_1Q8E^_H2c7{oxO#*FvA{qe z8(0Qx0ZsxpB5^_}jo=W726_Y8z#`xza074_Z>~FGqtw^(724+8SWdfUh|SV?T%`X) z%$-DN%SkEg_TIDHY0Zzn&)(51eKGqt_!Z1VYN4YN(`SQMPiAzK$xj)Z~r?Ad)bG=4X`2@748+-M;VR3Pv26R)G z2}{Khqodu_wa7o>$en@`RPMtB9JQzU30QNqr>zN?=Xa-@39@)pzJ7OblW0J9*~fj- zYH|HCj*_ErrN(}TBzE&BQ9*ZA{F@MeO16oz*skr7h@+!4BT)`OP?`w0-_g&Ba(B~< zHz}I;z&gXt7u2eU+(RwGgjZOmd zK)z=t$rJU)EHcU4I11SJloODlK|Qe`I7;(-%6T29qHY%f8-WABdEhSa8gRqLe<2G}&)6StQY_LhBhV=xT$y-LBo(Pt5M?2QCXeRfN4^x3iC2VFG{ zm1pzOXMgLBq0$^BhRSl3JskDwi*U?UvhITs(70tdhEn^Wo2J9Zva7V9Pxah$44oCk zI1q(b>4lbP)fZQn@gUY*RcO~9oeNFvi)va!J=5eart@tKU4@EblV!!~pgD8D&#dJ_ zb^FOqSdrGy&g_Tt3O{?G`&lEcL*Mt49oWw`rS`xbt0touF?7dau^=WuEEz$2A>VS!!_!dEPLar^&0%R z7jhjslPuflCP9>Xjcz5&!MM{~L)7O(IGGH7#x=_Q5Q*TO4Q(d=75o(NtFMv&K-jOY z$*&#=ek%C=*XZkkvOiw-sA1o15cp}}FI=O+gJ6H5CjT>dvQL#2{^%OL9RvrDY6>z3 z!@);zpubKSk>K;dPrFX8so+@P)_kqLw~1V@En0R%g4(4QmW0bvcnpivMkgy8fInllO> z5Y`aOdy@u_fd_;&1V0PG zQV3ezq_<<>0bvb6=2!@pLD1(W6^+H{h_Hr0pDqUk7eJ7C(>MS~BZp@Xnbur=WYOLY z8-IWo#>7mcp=m2f47lbiw791B#W0sw!QJUhIh_uBZAR;m1zyguRKL1|o4@$7CQ9=dT*MOhn>j-6?^v*;a zPBc}RAtG^BEfJA8dDO^q5s5S9t%$@Kp++WUArjqwd=?_nxz)(yA`<=hmWV`mRU;!O zA`)FQaUvqo1J%e95sBV*Ohlqnsgd^Ch(rg9$VMdki5i(NBGD(-ibyoQ8d)hK(ad&} z5Q$b(BU2{HUU}k&6T~MLm$^Vph*|;Bc8~`o@4*{!I5CYMF_??V& zU^Y+;lmTaeyMPphgn_0&0x$~52UY>Qfm1*^Ahm`LXbL2>PJj?!@_|*rZr}`X7kCXg zM?(lC0BJxDunO1>oC3;$mw-Js3q#weTVGRUU(12mc^VR8q0aYAtH*dsor=?L5SUpZ zv|wuW0y&;e3t}*c`62XVD)xEi!&JQu7CB9hFii~NY4|kAhCudL2rZdbJ>iI_3xY@i zQ4vBB;a28duy|@S9YiXKF}NwLCANaF910>c)PfrRW6`=glP({@WEhzIP>T6TlgSx^ zNCPo9l&&?fGVe9T(;tEu4q{Cx+2vrkSrck#oFg}99B-P9nIV^$W=!$qkc(9D!&AEQ z`WEU|k!kNO9#Q6Tqc<8z)ZDsEY$0#Vm1E^uI1(Gmg?ZTJLCr{FraRbp3nx5J-Y)-T z63{cDs4yvVj7vP*!aS><=Bmtv<*+4N+7DI=Y${q#n z(hFx}c8Z@<()GHF$JNl@z3y`A;U+gT0&C!!oAPgdk>Kl%>;6 zsB{@n_4tEy^Wdh(AD@TKlewwGrBkB?XfOPtmu|=dPD_XC{U~RFY$J=KuZHTUnC=gX zf|y$mXM%)6c`QUlBG-c#$|Lk^?}|JyX^U~WT)t4w;T`{=!HX~w_4vb3xJcg2`H%+` zvsBKF7}ypg53mT>2pj<}0}lZu7L^M$1rmUa*n&7$;}b~BP*X+dMdM6Q33Oa0N4Sfp zC(Id}D&e=v!i@Lh_KPQ{ovC!0JV7@Pe#+qIL7}UaA69F+o|eXkz-KR)oh=t5VuB@Z zO}bijrTfd}fRH7KspDwe7nd~qbd~VG0=uNxR*}Gq_tZ8~WiP87>b*jqju!oC1-5FJ z!aC5A-ma)_%q7%jC0bz_h#*HAu@VMdziA@)T2 zIMU`q?3yf*Y5aDbD@7Bg&;{@^+=&tilLCa3Nsi(rPPCUGOmwEkt8n$b;!LwvVYR%3 zuCBr?e>qI_E~b6{%*9v(`K*>5xZZ^tuZG&$g=VeBK31^{eJPIXx{|J_db?-|4Jbn9 z@pQSajVsM65_2+F+F2xz=Od?8*WfqAS}ZKuuf>V&<3WAbYLi+EM}=_I)&mbup{fwRS}SMqLHH4}b@DO(#)BeC zP-s_A8d`$9dwSCH5_u@9?0E@H38rP99z>>)g{-BqRPE# z#70f_4{n5m)o{?+n{ID}1B7;)V6e%X;zfAKnbhCu zXw7D{Kc3;&`TLsMztK{x^2#@(&isAp$!7S-^QGX=5w7s1WD)-COG`e7&xU^VP1G@#Spd%paqSrJ;-JodNmF_ zw!wXD0Of8&a+3mR?>3E<#TT$z1FMSx6!8VzBOLsNyp7inBnsFK7JhWw`bo_I}aD3{Os>TcckX2LC9&yz(>ra8_Q+M3asANj{{% z7+`e0pDvu0@p#{Pc{bA<>smYxvS$yrV9PJyUW>6xnKYmF{B4QN;EQq^N7bFXh^hSU zinAl54;5I zJK*{RBmfz}JYahV+*iFV?uq*9s?fN@CQ;YC*twONwoG?xhs#GOb>pQ zQ*gBy^0}2OrCz~r-8_N8_Q^E;3JeggzapRG{!=LHD)ft|(6OuN?JuX$ldEzs?m3k@ zUXur7J7?21bg`!}Jv^1pU4tpY7uPVFjG0CquVWmZIE|KEmm53$G|hN6h(Xf=oz06J zBIR!IQ1=ErJc9?T>D2KCJRlr@1GhHPrc>BWoRb;qFZ5K=jGGWXhj8n3+I$nU2!ub} zln#WB8?9{)HoJhMjk0Yc5joKB@OGT>e9jW^iM0{0rSN z=p?GJ9C!&hcf@`i&>2Vp@_|)AnPJa8c>>enwRzpC@9?^~9BsO(SWmMi6?03l(;vvm z4&t}(#K#Ia0}l^{2Tz9Sgs;sUc!>=%ZD!A0jx)d0L!9}sL5Adqat6yYKAdd})X;yAd`*cnM)+gf9@{Cr|U;k%6WNqY*ZVQ;ec@exux{xL;;`4{a?{30uL;?B(p}vc!9J`M zt;6qRp^gWX)86OE)VOlGEyC<_a(sasfy)Uyp16j=1^=CL{}F@U3ltv*$6m|UbXtiq&wfLNe6kPa-O z0!JmU&`t?t*%V}_1R!Ws$EpeC?^c@9ZabwfGGtj>X<&8o8{-Wp>RE{Kv0rV)ft{q$ zwH4#L7WRrWov)2D)uQ{g)l&G_u?|WCd@XiRHn4bV()ci;tmzMDCT{WQo8D*1n4$^XnBXYtA^;{3SuLO zs5>-XOY9NECJ?Rf;C*wAMcq0eHiKw$hdS2L5c37`If$4$v{y?!7sM72v3JPZO=FSj z24X9SxI45!OPm$NHV~cf&Dp|6`HVMua{M?AN z@{S?iQ#sE}qjD*^*M-a7u>9;Vim$85#7sf#0kQEf{8*`mxG#vkAP)aUj@}xgr#Faw zAWr^8)3wAwL6m{G{ukZW5`I1)_Jg?l7j^Z~xSB7BFG2kG7wy#&Re~^pQ0|e3uf}44 zuM%K+0EFi~g%(bg%@0JC(g`rSgJA02qX)iF-mnzsB-}AdZ6Yy-yFc zM1uej$3RTDPkjS47OO$neFb9j{pz#^2WZl=2!!Qv2y*XJM4-kpQxGRWEV@rcTH>Z4 zz6NpnKIwuq7F~isd;{YAeaZ?_f<4Zg(iHb#=V2ms8K{HN0lc}QnwuU)K_?A{^+{OY zyHAaSmDuX)ng+t=TM+L|?kH|89*F4{te7{!O6k5Z{tlYN2jm!{F&+>CD3xbSNT#Z@S_(4N*% zl>8sXYN5CW#g9fG+Yhvu5e!=mPz z0<>xY4-de;G<$IP9KW{sYpBMP~Fn$Q4^&?Xo!q}O1d|u0v zK5D7)uoXhxBM9Rk2@f9s4~btZ_^N3(IniZ4aSLops8)rVA!*6 zqZw=tLSXX}f=*^91;WXHS|{~l;N)Lu65l&{pmnku0^KVJ`c}}_F`B$vv<2}Wh;bDZ z(N;rbg0OiF;)prf%rB7aH~8s?>hAu#Fn$BgHx*rYfByn^18T)- z3jQrLx_8iAt)Pln#k|#7O0D8h80_8a{2m)?O&UqJ;xt*?0fCM|5c-&YiPKp6#Uoh` zBGP0@7q%nMpZaQ&#Z%k?IvJXn$8;!OlV{cr#tMizX5+XW==$y3Y5G|vG&&1t7C)w< zb{gZ~1)&46@-bPr*JP1NUpvh~S4$$bKxoy^r z`#+jJ(CDn8dGMI7b)r*|rljw$QXN zYXZ4ezR$-A?L7~L5yYY!sLmzvBMq= z&GWRz`=QafK=V~4-Ri0tMjCa4u`7r>X5&&}oZn58@(yTpb)b2m8oSfuZi;!AsFdm@ zzyp4pQ)gFYs`N&CF|PlepsDmyXmsw-xKxRHbE7c{N@R8E-MfSJ0NbRB;=5}q?Gr(G zf{3c3om!$w5MCfYs3MOcT_W_JUp^11xy*|(wuLfaL4@3vEag{J0`+>$--y6nZ(9C;6 zjeBd1r-87k4`Qj=IQ2^yck8V&zAuc!p`j<_*hgbLpbv~2fY@Xqyhpdv;T&5m*5j00cpx=1Q}HBaJaT2+JrQr2sy_=C zIbI3n*f6<;-=Cpu2sk!L&gJ5uWIVPVCs1iNEUhMhm<&R^h1PU};>EG=fh0UAT`<_| z$eo~!V5e1eVFr>hZep1Ku?GszP!c${DAZ(DK)~Obk~t0r|FXdEQ;|$)CWt-{jLG!Q zRJ`!4uSzTu1hx~_W-7^St})Iz3vt*m*qMcF#AYe6c(Pd)7YhRW0w9vv9b;VJM8rK% z9bof*BE+`jkb@+*3&QztaRVWl;bm(P*EAb(t<*RVO38+}pOH8sh{1o;xon7YjB)KJ zA?{<7IAapTrAFe6Ah!HXw9Spr$UcaB5DcEH&uz{^G(ca!C>`g zHx2TgrpVdT5Q$Zt>VEe$$S;`~o9SS%TJxR``Abve3PkGPsf#ow;U6OrKaPHUI;>hh zGG^E7BUoX574Z?QhMOWcib$-Mj5laLf_#CA3C{t81yD>5M0dH0}NIyi8CN)6~^9o5|J`iA~a+n-omJyfv(hv*le_6|6IruD~w%fb}o7>mJ*`( z;Ym7$j^`>i97_mv^bz<6C{&B2JXm05p!V^cJXri_N~KINnD!sbN4=KkArU_+or^>| z=PULsl+KFp+4<bVdpMt%%!3o2NE?*l)EwyiOK1>!m8 zwQ7AH{}>%E%}99727zg7#BB7=CC0doA`TN#wf~%-4eMU`k7{JOVE?mG{W+f4F=d5~i&wqzbgy_>2MPf_o~uaaJw zr?_#Qo>1;W2>>L#} z;~SR2dH4P|j?!-HvaD4WI08L6w^~ooDme!nh+E)@PL@yI$&W|8T0BparlDmh9i2gs zkr(}jLs2;Dj1tjIvBCpmwGDTr13dNxbC(WC=o40oB6B+vu^Ilvt9HO`E?@cC<-N^IVc^S zL5|KW2GvKMdDh@4nB2JwOGC?08oG{NqGDZH42nkaXc}6E_Mr3VCGzV=icoVDhbEw9 zC=H!QkC9(@whA>zF=#SML3_~o?&Kw{2bl|np(vDyrlGZH54wf4o+Jo`q3&oTT8K8I zGw31m>&1#tYZQy7p=Ia*x{Mq#Y&)utI-?0_VGPe~(wR7eULwEVtOP}=gvIQfs6K2M zT8K8I^XM@O?8}Cu)+iQDKnqbCI*A@5uUOK9>Z2HxgchRB=p@QSUj5iER3CLlNoWq* zjE?kU=VUVB=#LW$L!D6~nuFG&Bj`GE3?NY`3`LPia|*zWzeRGHZt5{h_Qo?RlTBI zot2mJAe(Wijd4+G(NafwJ3O}35%20wvO_iaj*En zT=Ztu7COiZSAu6ptpORVW>0 z4tDn4+enXyCaU;GM@btWJlyEGX6Lodia$EW+jgXG`H_ASd<^pJW=Caul6r4($N)!H z4})o2=x*?XTE2z(eo#lZI68phKRJ?VGA;iJBQ2+&9ADbHsV=F^+)vF)byT;FR0mU8 z@=4WVt0Nc;+{%0>)!wa+R9iJQW*f6_QLnbK)-9^=c1K&=&uZ9q$70(vmG@_s;-;GX z>_~Q>z@_6J#vYcT$6cK*(z127*vJuUlIox4NOh2=6X}lqZlQ;4>cbkmueEun;}$FY zc9-L>ZAiKCxOe&SK8J5WmPsD-)+cHj%89hOYS2ChUzboj_mOL+F?WTz@8ec5A4~p z)=cKRK1Z!T;F#y>T&_*Ks&?L>D{J?Ij>fiJRoI?r6p!X4Y>H@Vn|H(!Vhm*&)9M~{)$5Ndu@A9Y6~(HyiE9YB}SGvqUrqCIq0#MODH z93gr#d1$pNeu^@;TD3Ukh~z*lKIO=87kY^U+3>K~fLRJ5LTA z&5>!CsY;x81i3Y2C%*kc(!2|fA#CK(3yxAHl5mR2be143X7I;7;(A$K7ERLrjEXcb zMJFax?YiK2YLCfG-G0##YjgFl7_CZOCL5(+b~rpfz3(c7JAb7J55D~N7UO93Elyrz zS&fiA z@^w1bz4y^-3O;_H;j_@?qeVqWb?Y~g;8KS=%J1}9(p><8-VO|sOL2P)uC zM>X%rN6zCRy|>*|!YxOBmG~zYTRnM5K)n6rBemmCvg8$>4gBe-W#96*Dt}An|6BFB zMg2NjZM#KzpUk>m{7s4FY_4A3;#~aVZ%J2kSNmbK>T;VTO~LKWV>Rja+bU+XI!J{3 z7eu%}VH6J;eYy1=hoAdYEXA={U(TC$hb0z&lKRaZwjqx=XVoOM@-@k`mkiHBDkRep zCYi5mCT?zIHRrp-8TY7HOddGib5wI9<2bG1_p#2nue#pHN;Ys>H;Q#3`&O*qWm!WW zU|n-x)p>w*QsAJ9x-57&C==;P+eZr~(kq5q@!pdI@3ra?cHo~=Un17DoLEhDJEvX-)O;; zUb=1*vm+PgQ>tPvy*4WvoQo9|Qs3s%mv34ADWTRX zuMdlBts;E%Ca$j-e3oqpLaCAWswF;pE4J~GkG>#;ZJSqSA6+U$dI>g(EU zCWlIDW6@*5QzUueQ|D8*w-BRUI4~sabWIyOG*bS08L!po)j< zm2HdFC*gXs+waHtki`y9h83sjNDq8#u%q9VEdtM~Dj`CTbbY7ku1yVk>XuJkj?jH< z1J$Dlz8X64xawM8U#imT>0b8n$5pNddJ&Z=fiI4$It}!mD!wiw=cGNdd8oLLneS6I z=3`Rwsao=}K2Wj^DKBfwRJH4q=uFk6K8Mt|2Jyq=n`gq$pwX*?n=hT%3dUfF6 zP>;;-{BqRYYz<#I9M9FbhI%qP$<|1}#NN5mh&=Uus&`|ymW_{Sg7tS*xT*e|=fLAq zAJ{Z6=Qm+|n(1*iNnCSX*)mh}wqWBu&z*4kL^xk@O=+o5ZaIg;xC*7CGw31m7_Dg` zs0wP1Vo(yAk2azs=sMDp$S$Y?YK%H3$ry62^$;VRhd=X=s}imCAh-F)-yaR|qe#7! z5rM<<j-$pN*_hTaV9?yD$$AhaT1AFvU zvqIhu#Tc%};b+vx@8a?7qXven+p>TLMBK=}fT-Rh-|Ju;t|HsAfQIh`GeF9TkDiNsS)m;`Bg|e zO3Myq3uI`~?(K9RPv=Ixz0*3a9cA~TGd@G&ooTk>TN-}qRXe?;=WEw81DubB!rSYi zZdTHy#y4p#Rm(`--d>+%>lj#>r0~01%}J?v5;<0rQ3^^&XV63BF^1!gYM|CA7MW;1 z+KMvJEhNMF6&t%LqK|D}M?J*7A#K*q`Tu(qfsX9TM#QYoufFK07qP?j9rabNb9Ft{ zr4zgK2OJXpb?f5KH7Z;7HyY$}hb5D(ZCV>=rp@f6C&{ww_PcibJfwVdV&<*@NN{|zG`4M zige%9S>5zma*`?9gBpF2itM5H;u8j2dgu`tHw@PEDzBcphp)6svwpvm1Cmtno_d)= zVoq{owS2g8q&g}_b(F~AnWP5x)LZFInXQuA*;B7e9cJrAQJci zHndwTTi=F{WLukksgIu5Kib#1y=U@fZ8z6Fq$^gviq(TXixDkRv8l!T=~Hc zzZY25s*>vBV7*8#=|6t}ABo47D_%b$rSf54-7moESdV=ahdS$bk$LNfsvHS=P%avm z+L3(Dcx=@Y^!vHOu%-DilnOgBK2%j2qSwnM-}KswBY`+a&xZR8U=q>g6q4CblE^1yoYs3}wBN zmQZHgitTA7btlX305(Pu)OJ)>B@$U)S;F$2u$;2Is;Xm_O+FdMe{Fd+H6u~)s?M9b zXMp5Ee&wC8{$66A?5O4(2qU)xhh<0{#3ePbr6(srf%yv9(<95F~SB-onC$|R< z^2sD|5M$P*j?~}*DX!hH-?|X_Q!1qqhhVBDkOtDICYbBJ@-SF7=ydG60H`uWJu*fNqPm@ z0_%VjDC}IukZgPK0So)CmO7TC=PR_3xvz(?1meGQtw4rXFqmzzb9jaDDeevxGDd$b z3$^mGd|*d@*_Nq2WTAQaTGm)AA6px;wusZMPBuU8dKme5yID-?+Y>qS=dr5PIV^D` z?&6v+Og$Z|_w+uAEfL!YT+gdS{7|=0;|l zgO9{xV{x6;AX7JT$!8g660we%^g60fvTl66S|a3@g7IS=_1a{iN0@I8 zJ`#_u{5ZW~Auqx+Q35tcUFT-W$x712i20^oThg5VnI5X*Khqud;dRyPaeCvd8i5`P z6>B>37*ANun7V5CXYZoy6-ua<loo$=WV*ksN_v+Js>Tu$V`$mbm7x7rEo?{k({kPo{|)SFj)zy2)msz1|Rb7ec4+7uGI zC!8w#-6N0;7R3LzqsWd>7bbF@JU6x6B;73^P1K4D^@0)iXyQtFy$_{ceh8&RJ%Y0D z{(|Ksp0AUA2>&Kr)fKKLVKsdr?cYV}mxcOo5j=J=gGtvkyJnV#GhkJ?7ly+_usQVN zrTxzE2}_g8=pPshpQ#hy(%f@bT^8vD>%GM4#X4R?PJL2>thCu-1%eJ30d?308n731 zhl$X`rnWEAOM6eYXEmdx1K+0a^gPL4xa7bk7vwCf@yRZ0bNQ^9S&?uaSPA;WdaxjD z1q;EBFbLAd(F#KzhiXNk9O2?{1`LG@AUnZa0?WXaP!%rA0!ZcV3%DKKW zJPoVBtFSt}4L^b$8?82c0qa7k7V1H^Tl*NYQCdS72xUbiQfo|Dj)<_9%N}M+*0iQJ zZG!CjRz%3IZw-gSNI2Hzm<-z!{sMM@GhsB8R^cb`JJ=C!g`MCY$YC{)z%Ec4tX<(% z*d5-1J>U~bVIL-Rjtna|bHjen4-QasQ}l9r8OAuTtA0(zWCr-uVocfa75}oCw(@YyYuH z+7!ZZu5f~l11ARAKU3jEk~;$~fM3ECI1By^XTx+j2mS%)LfS@}f|{GvvNm=24PnOK z(H204?b5!5P2nQg3Z}sRa0wjj){9Dn32rTG%ix!A1zZDH!nJTU+z;2lgK#ap4%fk( za08Urk{MLPh@Co=VYE?YFs30a^WnOhf+yM!I#1$zls!PIS`c~ z%|opUloo_6rU(J3*>Ua~O<(pFx>#0&GBdwv-St%)!tY!(5kx zf=vj23!B03VGFp!6`u~<5IzH=;9bb`DDydN4XGKd<$A(T2 z9qd)vU}|h_G+~eWu8AO5LT@ovRv=rR!A$U zeq63MQ}z{lpskK7xI!<)<$KK)dcne9;VLJ+xpr+_2%Jy2Ec^z_(ORH}tTR`cC=$h|neE?2q#Ah}*L%Si0ADAA_u1TG(~ z(N~(!Mu2X=(q$B9P(f%~J3UjDS=%CRMd&gVbLdT>;GTlDplQ zpiYvnotRV|R!XTlG!Mc%p(i{GbHGP1Cv+oI(Hq6g3%wy%>6#C$3AxK)Qq;6Oa47VH zGhqR!U;x|=3&IEFU@edd0$LC(0YhL1SOji>#o%Qa3Ug5}m4^PXJS+u2gf(FW*aTLB zU0^jh1lE9jZC9%a7r|O^CFDxpOg_X!7!$w2+VBs^m-@`dFdTa8)J(7hjDmGxJIEbc ztvzf8qhVJl$GAJ}On4~l3MavCkWqQ0hmpzH8(I(eD~xf|l1<)cwr1pQVU1zzO41!%Y8~6|| zg$!aYlOhZUg*tO;|# zVK67$1ij!R$k$uV98_ME9P=tHY|W2J8%JTA1A-pPM#^Bs0M$pv^_F4qOWB!p$%o zUWWDHb@(xS3hTonxoF|S60i}J+ro`u3~UNxVKXRq_?p8Nuq9jrTfsEg8YchAL?jdc zLfOJsur1-&uCT`K)^>!wUv+_JY0PaM%YxfesC9z zb5Q;-F%gg9Ii$8SUqHTGZU%5x839W`NmwWxMff8)61Ie6U`IF>c7Z0G0LQ@%@H3bJ z$HRZ&1XzNz{6rWDCpjqpNlbi>VI`ab{{z2(ui#V|`T^x1wuRH-SU3Z&hF`*ya3*{M z=Rkk1(B{E1a6T*x7r^H5TNniw!6}%5U zX$Q!m$OSn+m;vw^ECQdyc=!TNgfHQ2_!=&PHZF8GLN}NWb$B>0UH{yfIE^8Pt}brS zQ#^ZcbFU}rp1N|Qe%BsZhv~}bTV$e=*;Iz<3aC6PW_L8 zPv?zwo91gZgMw<13Nnbbc^_E=m04H(){RTKd%jsOQo69N%^mCVF`>*e&c&}?cDdB8 zsjH5g^%BYTL!Iq0DT7qO+CCIT6)L|v%uC&&@o?8_X7WVVtW1~(t7bjOgHx;7$!XT? zPMD{o=3v+qCc)-V*4YBe)pJXD6t;pFU^|_nb%%-e7#_fAXs7ie$Ik&f66SV+#Q>LG zE=D_JF9tcEo7G@9$R)GJdEJ!Dz#ecA>nWN364rGkO&_x?21Xe)sk60jAyuNb3`)CfIiw=d zR>1GzN|*}2hZIX~J(OnIMtBSU04a9XiYac|X2KLFZ43MWroti|f6Jj5hHV%=gxg^l zOoL<~E1ry_?I8RKq)le_fjeP8xEp>7WeZ2c{e;;&R+zn`F{qKrMrubPiPw(9pWuJs zK90Zk8xurozr!9ht7Jia;5ouC;6><1>*q2Y2d}{y@CGy}GUD$6X%m_`Tnus9i@>|s zE5Lg&95M=t*#!OtdnGgRHxuLGW4H)Dfxp0iU^;vbe}gaKHOMdyW?qUYLp7L;3z$2hBy2ZitN?S5E4&Z#y1sb|@)Ew8{1+1;Oys8ZQW%zjyd!Tln|R&b z97mW|tkq1S6>Bw*c-`Cl0Xr{Wn?FNdr8a+uyf$q;)^s7}yy0hFxGkI2aCq zU%)uH91eu(a1i_*#>0PM0`#GEGz1ohL+So&)?#8942L6NJ2(n{0!PCEFbO8WG4KmG z7S4n+|7ysEgSi2YgL~j-@DLmiFTn}$2Al|Az)4V}%8%svt(ljJ$*>@t0xQ5TU^O@u zHiI)^7bu6Q8~loJ4;M$c?4QE9se8B6EzCQP>YN9V*0p|lm9Wl{r_wjfLb=fvLOiua zkaMb*0_9%RQdj~mgJt0gLp5CJS;V~<)0sTWe6ZEcKhHWMJ+&OxeR7Go=Zg4%o+WQ1 zqKM$R+`Z1S##(%k=bh)2WRez=Tg7e{{O$$^JEA%{t&l4+;c4cSEZTyRb<+-SYtd%29X>$>|p5XgpDy(&^yRKV8q^dBHWSuX9#vL2Fi_%=)iuR-w%LQf3WK<{71R zxO;MjrJB-YFMBX8KfAkgRvpUy9s|lTc83u#CzLz&-f$?)4W~h0xE$t%(uBwlkHZ4+ z77T)NyD->Yt83k1;X>Ff$V!XCval?y3CqC-usr1ExmF2svs|kJ<+fpUcQs?D-qp_Y z)B8L1faEaja%gHpIW*z0DvW?NAQ#wXP1pc7fQ?~e*aS9#&0!DN8jgUG@N?J}&V^C% zd-w^I4U zqXM>Im#e4KH5L~+Ed4Cks_(gmzVAB73BVXz1s z4y(WsFdTjgn?r6qm|fv$*dLC832>ZxvRnT!+4*>urE(}Fk%f^ww~*f?TsaSGpF=M= z8A>_e9)@*@zJS4mr$MPdro(cOleBfnX2Nj7v!EnpHf#&Of^u(rt~;lpI40&{7y}iY z0q4UM_zheM7r-rWA^Zh?3+2!(hG$?3l;-Oa_#s>hrFr@tZD)c}HpdTEfO(dFEwuMrLqM)3?WLce|EW3+~!(4Vb5p+-u4(pZebQ&0Sm?GN=H}2tRU7!@%?ywl_ z0VU7IKzSt58_M~m4~&9+VRtC2>j4K7mO3mR%Hia`t2qGXZDokx#R z$arpYpcs^dR-ts1i5%>KP!x`$Q9PQAQcxN?i5?=4i8K^YebgO|oXA$pXJR8di87I6 z5?h7pqt3`g^HDlFgI*#(PVr$V3MHXAC>@*iA!cY{7N0ZTJbOc>TZ+|~}dHiOZ z7jI{{_G9!rFGW}LuhZ#P-;E|(*fHJ9%?i!6S5!&I^q=U2Rrxrb>`UYJV|w-vA(T?z z9;aV+86xhbt9{4ccCs&}^b8`(67eKmmCw+F?675q{vZ1XJ5`YrdV4;Z`soQ=%Hgtm zr&@YKFJa%kGxg93{i@A=b*EbYo6g&#yVT9!^jh}ZyH$~sdK-J~-D>zrno*^6RVUOl zpUOO`dl}_fLeO6I`lMdk4om;8|7EYeR|TD70bBQ~_NSQf_+GW{p(?$st+eZ{f>P>)%wG|=M*Gx@(|Qp*3_7DXc6CHA zr3RkCp%M<`_o;bjaDdy-=uvMS@}9+^G7jtasXAx%tZ}YOsc{lfg@~Q|)SB!O_lR(> zO2qAbe5gV?YL`97DIYW6ucGW?*rc}_2HA9hgX`$Mm1-*ixQ{6lZU zo?iC{ORmNOem|&A{lR{M_VfBY`^|&uoAcIwd2}9^>bP_~qyjFyeOIBB>T!Vx?(-Ra z4yi9LaFpN=7xb97+f(Qw4mEL@b4WG3hyxsSQE&Zrm+cjYS~#par0!p2?J(d{Hiv{u zIDCY|?nCOEOL}Ry-G?0V87xMZxujQmyCVO~dQmTK-WYEVIggO?J;T74oiFPQD#bc4 zXFCeN;A_;zckE$x^D>DVdpI@M6`jxfv^%24Ue)7*1M_%M9wh5$b&QeP*-P14HIXtiL>D4^@So^@Hl~<9QJ^fVVeZ8{h9GA^c^;k|9^pyL&?y<^c zE9e}o?8tq+iYL3*+Q=}cE${(0=RT!Vi*tOZ3eWitef$GGOm^J*2Re@lvc4U&irw^* z+Qg5>Nm&$*qERB6hEmX0bP{DEuP=Chi^5Sfibs>tGL(i+qDdQ~vJ|gzCgkKZ>u&jrKKYoU{uS$5P%f~9d zmrzl4mXK?d0S67UtejMgU9?|Ke@@^3`pGpx7fUg{yn1qWaGZKz7T#S9(1*Vel*J^oz{#Q6shJm0ra6qejkR6+|yg zwubRaB9h#K)x%f%8GHW5>duz zGG5)9sylD=O7?C|w*(mtZT1$eR3Dom3)*Hgih5naC5DG@HrB^w2yY7Kv>U$mm`D|5 zH-4}eXsiBXH!9gnc2JCkTg`5CQgz&nI`*qw)L1v{Pr9fdgtfY=n{GxM`{=H!mIJ1B zRWqQscQ@yv1K1=l^~lX&L_6JxV(ndYqo{F}wU_L!Ch0~IJ6xk1!|j#3t0D%A4C}7i z8%BFv*BK=A8m<$%yAt~99NmcjHVof@ER*!^e4K*=l9S#hY|QQ+D#+cMdzd>by3X8- zd#Oe4EEsP0HnL6_7gS*n9B$yS({cz>u^xt>oxoTRBcJ_VFE!7@C~yC}m)hrH%qBUX zc#@o(_>YWnCFhqv*l)q5jI8&-FQ~Kl7=Pk(I!4)Z7+K?HUr_CG5OIr$YQ5Fi999B< z7t?J_>wBx$IgG4&8{eEn+#%u>zB!F*ygqa#m(k?yG3MOM;M~Lq_fh4&*dk{a)eCBj zMDWzin9@hB@G|NIOzGoHsqCebK2!&^Nq^^vZ|x&lr=x6?Hyg#!*T$m0u8rDsfsXVm zy~zxV`o6!zJagg8!#E>7o3FpJb+VOun}l)V^8laHv99HfyO=Xj9m&P6Egk#*@+#)W z_aVLv)acBJ_y()w+#KI5lcZewoyvp9cBH&#tXh-X*y!$j(ei@o;ln0BVi^VdsV{su zUhuu6?CFaG!;KoXEr$Tr+}FrzRj|j1^3;L__dB_h5xxLtm3u;^*9G~LYc7R%w z#|W~+L*n549uURdkG1`SL&^YG$|?qWKQES@;+{jxkOQP}}{CtP!#=C_OI` zJQg+VajJY?BkL8+3u>T5@ZiR%7{@ng*j=QRWBb7@I8mU;=mJD zW8y${UmW0j4hi{jc!k4Aj&c`#@FKc6l57$ZW+keiBH6aScM&4; z5V2~Qno-2ax+=J!PDq3w5vzx(7ezQx!63e1{C2<1Es8^49EuNDI~beV4&QV5q!2eO4^nqW4Nfep&Qzbw7JV#o|U$6<^YD*f$MV9gAn1TS{@&gdOGx%~or43FXiP<4}}tGuCnKahpQ1I5b<~If{=Ff=|N{>S?HT25eD^*$QLY zku}?u+c}G=3PWw#3cmR8NZF_`GV7?{p@x>qLA8vt8Jxo!lxE3AaalD|4JvK5adwJ{ z=g&sSr|M2=Yh@8-Fcrr%|5Me!jAhy>rV^NZMyWexjCyuhzO3=oUUrl!QO-EzJ$ICI zozjfqMp!wTF$KyS%j|BW)sFJU^|xoC)gKx~-Al3{?QZPUQ0WMediO-)I5N<$-* zwoU4xhDKAHr?UlP)4HjOiVKzsjg856S}fZe8%ympP`WlTmU=Qmvz3-s*6LJXQ)3Pd zk-{xl*pa42sAsU%wyCEzZy~32_#2h8|1EKi(Cp-_fWdCx-hSN${MGMzov+ z2n_K&6YorTjB}SKbz+ZF&65Cz-tNpYh9x*u-7gskE50+cQJ){`Z1l1Jnvhzli&4ks zdCIDFZCW7}F^!F!*3}5K|2;&l>1tH-^sy?{w{b5euG~-+(2d4R)1j$tx{;YYXC*ol zkY5#EDi^xl$)D7l&XK))7(Sk>={_eJI7wYGameUl#CR4T{+_LMPb0=ojcASfo6(ci zNG;ft)llbI#_(Pkspq=(!br7d88?cNs_d8;sktm;NDM}5t2!}k!4=nf>N!8+H#5d) zZZA4QU5qhW+8U}JvE;$Vy~#Yz%0?b_S(!f*o4vwF$@JW6=tF>N#0pgDOMnVwM_;ld zwT5L(ie(W#R=r@;Ua2J)8M7^=$jR<@ zuEe=|oPZXhttbO!BFC3BbWwejh^C=sC=Fdk&rmUL`-Y(yl!VrzJ?Js=nnfInLKD!! zS=@0wz{F+bHJh1HG>S(H(PnfRJwu^9;R#1^XaZV`_Mlrxn?u4-eH4c#pk*ixWuRNg zYc9)2jZt@$gyziUj%ykdC(%pfH;)veC^QnyL|ah?dWL)yw|!A-G!o53o6!;U5P8fe zA*eozMJ8H?($Hn}3q71nP?R{fG#8Y4Qj~+_)`TnN3lp=n^}l9qYQKlc`RaK zC>%wj$tVS#M470-VtUx4&L|NrLun`zIa1i8C_7a3(h z#3Ew@V@p0-WF!+xSZv537(XsH%GsjTmBmJN;GbgjwRKD#mtvH(dCPXlPfB$MXNftm z#3)uS3|k2{ry-Q56^&si;U+Fdx$Ny>DdoGAmQr)NKz^wH*zfMI!j~Ejw+`HTkmnP= z<(V(*!KZ`r5v>xI8U>RpVRmQs%FrKHfpUkZDl87GL&TdSn$>Z!7W|knNwc2W)PchY z*M-Aj1Y8F3v3eggfWHxL1TR81!Mp^U!hbn*S~Di($!}}u4I^Oz*cKLr?cg!UHkyCH zXm}HLgz~yZXZRd;h3;%ucPJecd%}D$2FmLjeP9I`3*|MA{;-~%WX3Vk1j8WM8V-gX zU_9&!Wyec}GK6ps7vo&^K`>Dr{m%F~UwR6831uR$B@|QCdda4U_O^K|jA9IxUwj3J z`fzHC6~u^Llu z6}j5527U_J#TYj!*xd3Lv{^$tIvvX~_-LUu?`Dfz!)$%jM5pQ3HRQuF>fRbd#_A%J zSA~C%!vyuo_m;_8)mkwvPkp}GxsJ!?N#kfRw!9Q1J$}sZ#Qh-56qjW{C~)rH?N8l(^NI_2Wu89&F3-Y zm|f^?nrHlArP+#W{v+uvGJYzpdT&w{F{w(9{XKpHT^Fxk56wV9XV9LpWd0$ z#8g=Qp3M}RiYZh@q*`9dsVt_hT9^7RL%kG-hAQt?%hYNs4n5TvXUNJuN4Db7Pu*~u zg16ydsutU@ws7)L-r~^3f^E$Zs2~HtjNs z`j0L0Zhd#hd!4ywFR8ez3hjHBm*V!Z)vwh=r|H*yIJ{B! zTp_8P!uE6Av=XZQeybj_j`=EV6#AX}-<78V2QW2I6%SY@tG1aerdYM)0BMd@2M@60 zCaJ;)jnTFTVl1e(9^`WIK?$|vu+dcc95TEZNU6{v;s>d(4>8jqwet`&%~t-0F`g1* zLACKPey7wghlzP1?!DB=Bdn;7nstPE>ZEQv!Vci{f8r>+Wt@sU#tFZwnsUq-&w9O& zzsoA!kF#a@ORHSRtu1qw9Bh=88^^6Z6r92CIH6i(uxC%GgbX9qb|SUZ31hK?>iXdC z#)k|S{rq?1Bfbq@^^{T9mZFB8Vz>XPRtpl;g;TinQr@R=iB(NbV_dJs2n@C9H0e5` zZl5-+0W?xJax!UthLg#S7B*{`;;d4ThS7FY{eFh6yQyBCAzR&4!_GQqOJBomXU^i` zryiZf!%z92Gj1^Q!@NI?vYbK6{qgQtC;frnIyLtXHfNpM_J?ttuYXKAPa6MK+s+#U zYz0*D3&vE+%BBk#FRCjSjM2V4@p}6!PA(5n120<3w6a3lMV7fj{eF>_*9v93WaM|- z+J;dLE4ww5F*dBtO1gy4Q8o7xK1bC~@wt@E=izF$A?z|fk5#+Nr0uc#^fE`cxjJ## z=xaY5pl0mh>m5;7xMt)ey{NxOkXm)csNm+oY1bOz`0*8kFSZb}#!U{nY6MacYF{-L z_>QqT`z0*E4wENt|{?cg=yNNxIO1R0Q161Lg zBw(wUDvF5*Nq^#6!)dSbC-zoO`vkGKciK0KeV}EZcMEf(^1VfRr>Y*eSmz&qI8ROB5NokQ8~kjD99DlDdg z>ed}xL!EZNyV&_sjM!uDa>3lts^Fyyv2Oy;y=O{%PiOpP;yF=0x=X@M6_Lr(KX)!= zawc93WG72GlZn@Ir`>T6dz#Z8br1V)r`;6$Ij22C>{p!jmtueBv^T$x{f*N;@;-K6 z(!S5~4~V^xI(y$}S&i#M7)lXw0?P0qa(Pe=%Iiz?1+_-?s0gLIAMekbbzl`JeUjrCjM;%dpb{#Htn?Xz0RO2^guOv7OJ&?`Cv;}7`BEbVI-^o>7i{l3;AwX2R()% zu!FFVEBpccRZaQF2&N4s-o^L+m-qhv@;*S=SJ|$*=b!h?aL~-E_>3VKk7CWb6(HC8 zZ!Gf%|H)>SI}5bAx;`@k3ZKF*W#kOZN}3$1^MvJ=!A14;Gs;Ln31_A&^R|3HT>g3CW5Pw?Qx*A~Esj+Q&&e+@T;4CC zB;pm6rN4$DQ1+W_lY}cm&F<`DD)z=MdrL869}3;zNGS22LT({Q??lZLdQ*QmUofq% zmDI{$)l|+Gw8$Q)nlE@5?v0P^7>3cX(&7UpExs@WW~D{Kl9oKMzRNCY5xb;?Q6{XS z#qA2Kv$V{YfIWclSQw~&c|o;5NZI~n4}@TqwHASSU{NS*Ee>VNOTZFPmLmIG!g2?P zw^gkHgv2gu6}uef(opJtv3G>!3HOEEEOG6D((DC!<+i-+1-0N`_P{ACE&ZzCBWdAn zB`Ynw#$u&~8!T2@csJs`v`AReB4gt;g;{A4yQGCa#_y%&W5SY_2CBtN_5e-nm+XP2 zSf$Qr4rLFtfKpeqf<+;BaZEW{GC+>(_bAAX9&3P{W{|r(W=|+p^W1ffI z;0? `hgA3%-FdFrQ7UWzATCG8~J63d$NFXAb1Hkohef2$w=xft39O!jyk*Wb}ST zEBApq@ruGb0;|-xBcV4p#IlOyDs1^V*~!0t)`Ou>WI!C*&&g1>*o1P-KZA12$3xlT z39u?;ye8{z-6YtY@aHfRN`l(Jsf1(UbT#I+@sX#TTIFA)HEwVdUemSKHV4Yu7&FIO zn}V{o`B2vOHLL=^fiPifZV^;Hp10#Gu#G$f;-_>cmQsLe?l1#=K=f$K8CyCzf#lhWkQbHe#i!E z2VoU>2+Dg-N1(JRj=@$i19Aq|PQYI9Hz?!u{0=9P5N{oC7Wu%*6$k4iGGw1D{=AYskn9LXjJ3?ZBg7J*Hmtf(0*LHG+83eURi$?}SGSqwZ!w-(G}YK!zz zwT85zbFej}O($3bzk#q890tRn3G2Y=FdVLe5sfgu1&N_mM_YekrkKWnXFB#eZ-$*Q%1^I==K56XN;T|5Qb6TSjF!l$q^)ZKX( z0hWO>G!E~rSwrLSl9bj7QbBSYeh zAuL1T`~+nvoP%%_yadOF@}g0rTXbK?O_0uV6Je2abVr;S@L@&V~!&RVYK@+=PqZUAP#^8_g;34NP9bgj-G; zTChEo1jw7q%L(^@E8%9BeH&a&co+O0=A}cI_y@psgz2Va4V^RGWtUN_e#9;>49f=o z;o<`*L+LoYDgQf|@Sp*c4&_baT`&mlhGpSCSQ8$Ejo@L}4IYEbpp2=L2LA(J!IQ8# zZIDxNC1j8Q^C>(BBWb%`ggxLTcs4iX|B6J=n7alK!W-}eya~O0X(7QpP{!DiUW9ky zNAMnO03SdZ*5ncF3IB$p;8S=F{sTXvk@y_SXeKhmPA_P4@XmKK6K+f_fI8d&-C-*9 zghwD{+PnjELW7#$3l@XkuqMn6+dz8In(bj8*cJN0zA!Hw4D-V=umJoV2EgRmOawBq z1{Q)p!60}S217SL-d%+GU{P2e7K625ahMECKm|*|1yJ%t3M@ld2C6Ox_rUTnH;u>& zumG$qBhmC^q6&r$P!_Po#l5fw;ghf?ya{W;LR{K~K^ciU9QK6~@O#(@o`ckS=3kIn z&ouH=PrzKT6)Xx{!w4AZp!|1Xq78=8uq~VkJHXYjGh7F|!k=L`co6o0Ct)v`31i?h z*c+BB;2eXe0i<`Q*%{Jl!%Tz&pb6<-VeW+klbN`{1l=3VD^PabO-OeI)8WtM8uWoO zHcux=Zy_@V@)X`&4;jhAda-h?vt&I7m@zJw{TMj)@0 z!rFn9f7#-?7{0^M7%qoVa0Q$RSHih)4Ll3Khdx}vtcOM5CRi2z2x~xDUM;wV@Ru(8 zTo)I>?buhqpW)6zl>am)PGHypFT-EqUoaiMf;(Y8nsvKj2e=3Jga_bP@F2Vn55o_G zX|TW~coZIl$6;Uy6%{NC{{xfZN%$X`IK{*Vg&EWj7J_uCHygu?P;LTTg4^IVm=15i zqwr6763P~zg0~4@gLmN_mpv2SBm5jbfLal!za2gzoSd79znRDf>6B|WhV-j7Tf-Ny z7o-eM<8hBkN6gUX!ve2ziysoQS=KYUkr#M(z-^6yG{nX#r?; zA!ijWT&?qQ&!4=mr8DKUFsxq$e+#&#Te@ax4arzqBqSqgQSd|94px9&VRhIY)`mS{ zIFt<0*cFy*${6geVISB9#>y~71DNQKVKR(^3t&840~6tPI2`VUBjEwaur$`-1f!wN z<{b6M4~`>T6i$HL6VxWbI#3ewu`A47GHo*Uu5b#&)L8F>Gp>y_EaWu!scVL0*9_ci zvKAntM9w0fTR+;@P~LS|0QbR#@EDZAea^wfkb4Z;5?J0&r2^~0Ww1S51-Y)&RwpyT zg`+jv&tSNL@L0GBPKH0g1#mN53V(uJB3YySaOq=_OB`)0_FrB618yUH)kR+p=XSz! zScNp3wVz>KSa=5$w1c&D*a^z6>H*~##=%{wS3YphY4e`RZVzbV%q!EJ7lQk6k({(2 z(!S6RLMle>FqCX^1U7{-4p4u163Wp&4adMg;8b`~b@6i#R*VJY=efeQijvCey;dQw zdp-4+pL-F{qwhu3e8{|#oBx6|qO4>~8lDiQiDI#ki&Da5vr53Hs$X9BGMa9$WzG0 zi*;{8!p{j8Rg!GLd5`S8J#SYK~%15}Je7qCMy`dWQVI<3bJ9 zN1ah3nub=PbaWm)Mn21^&rp5T86_>_Bs+(R&FBcaj$R_a*yu&Ta6#8k2<47Gz~37Y3Mw9jQpso%A)2d22DT<(N>g!GLhqZ&H~B&2}7MxBASmj zqLU~Sd8}nCQ5cFs@n|wyhSJa(^bmQh!w=O!tx+tJCjxWOTC@k9N6(PYdJY2$N6FFr ziAR%B3fhV?&@H5GV4RC<)C+8_^MT9ci1$s;B~L zjJl(do3xL$`Alp?N6>ZT_<_8Os-Wg57MW-v+Kf)3Oyu<=yAOr^$k&;lTHnKV*Z8jF z!Fqgz()tKhfV-bz!}4c6wJ5;7y#3F5smB7`Qsn(98bVMF6>^)aAR?$;?$7BxRi=ZT~XLQht1w9PW?~>-_CLBY7v%U#;Hn0 zahMvX`V@7qX5TPSEh6l_ox6cH_EvVfS|zA1w=$d1Ox=6si=sEsGx|5-|x)q zhFJdB^@Z!^-Z|$vPTobtT9T+TDjW8cWlrF-QOWZuZ#X}r`f@2TnEfT77~EIc|E zUyrwM50=MKYzWZgoN{4ck@=!LF7Juf;OGjTPTD&!%9IKO*WNvbUPjDjx21l~z@8 zn+LZ8rplPAgdbj2)l*PQohm!464kX+<(A@;QzfEWuDl;z4TrSm?kiJeSv5~|ktbVq5t&W0cP|$yxyipyW;q%q;2{vm`Hj<}F z{TiO01ae6YMDrn9Vul=0R`8t~h_;_0rEBusZH9EJX^C#GiD-UA@6M3(H3`;TCYtRs z?aF(XvD-MtTMGyl_C;!W7NC7&El*@f0i4X3X^To;4_oVgtmR=}sozK~Zn}$0byLq! zT+f&(MQVFSX?JJJ+}gP!b)`1mbE=yA@l0{op%lZF>v+a1URQ^Z2G5f7b*zw9tBYts zy#0EX^sGy+eLc%Jr7ndk)SPXHLv1s0h_itwpRYrGPkE>IbB0W6fRcw9@ieqv z+6oovuS#@lOLS^$LS7uv&ac^VlhH;vRB!94>U z7E%haerx?fOEN=>imM%o+HdXORc>yFY-wbd2V~cnyp6vg>%!OfS=pyl@KGPeUSiM@+jlPg$+ zl*OVqpM_LSB1uo7esxDrVCStST|0Ur?eMCX*&y6(yn4Y|R33HqBx~K*%YZI4Y%i^sEnO&qpRAY1T_}M)HcD*QTs6d^ zu7sc>O2=;WNB(q3NVr_+>dE86NQQ54x6etb_-=%N?Mo0Pa&Dw%~PnzTE9z` z1sSCMDZpFm*uGK5clUInkOz0iT@3E7S?(%paNq83%Oq$1;r-+SB;v>C4-7_AM#Wm*N;uI>5_g#r8W+VZj}T5JoPpBVLwk`Yb-sN{s`1T z;LcWA)<0Ksa79_v#iHCcaVL4=a^loB35$AIl;0-flSpj%)g;d(t>rd}7+{r}(E|`+ z`oP`fZCN(J(HzvY-(O2|K30fQNTzQq9d&s zXSHTvMW+cjVP%+HLq~GJSz_??~-ImdK((h{Pf? zbGz&rlq*`!6fBtPa4+31(J8qSVk8!xI4s`U&JaLYMYlD@6QaGfT@IvphU8>l%wS>= zkJy)dTDG!gUf4k^SMWQ7yuO8C1Im-RccA2kZi3&x=ZGcqT7?n ztd&YlRa2ISPgpgj@A4>5hEw}%moFvNvr5yh?-lo0&jKxTpJa_?3{&}lv>xZV#QR?M zc@(xmVOb8>dY)*(lb)x&4YVP7$0Lw{!0Llie>^^}KKR5(4Ie+Y>*l-3TvV7j-m@ns zRvll!Wm{a1IV6)_AlmR7FVJ#rJ0xGez_2LQIzd8{J`+g(b_i}c?9bgr1t{EaO`sOo za##*e@C1&E(j;agO4}oQ=dg5}=!tdRIczno+~qtmSAqFKiFH8iz4xTxq+D;<=t)>~ z#3J~JEX!?iUs-g*BJzktyqL?y#1{!&XDs#}@rN$7kR7^UIrSnXeeV&u`eLpiwo3Cv zKGOvU)84loIEFnxGW7*nQz)c}cxRDJE7EW_jRVEfJZU+}6*HLta4C$t_fhFKnW_kW zd9rHYj>?ylNxt9@iqq{o} z1|E~v=`@xw0!8KZbWgRM5L{7GiAXj3P~2Y10$kmjOU+C#0zDAu{-JD90^L9KUGjQ5 zICDx%wP{H7M55Di={XGvc-A!DjuFRY&osuC_NgJ7flGqs(mTy0j@iRR2^G2|6L=|*3z<0yvWlc(OQ`H2|L=!6m+;vY#<(a%Z zaJQMbgcm556LNH>X8@uVW|3}v5UusGKi%dO4k@S7Ew5JVW8cfOJcpgySD#3?3?dyE zv~SEne_tFOJ1u82JWVvX;2h5_E#-`8bIF%sXQcXE>qVbG7twx*MxK?Oa}k9f&h;eb zq;QXyJdsiT5tx3~Uo=ujr9L-eBC&Gi?LV3cnlUVS_^PG0H;x(N#6yOD|p!g z&lYX;XVQ8h;dfk+NeglE%mvx9kn~z{LB3JXTP{eEOezV9oJF(-FVjkAT(qx`47V#1HOmw@AD|@>{IH2UUPR$$eyQEdo;>-T z6@2~Hc{=J^%VEB^x2T>CQ$WMEdfYBGGc)EL&lx6Qd@Z&!eo)gZ2X=a1)tE&Y;3Fbm zkM}*Z%TwE>CP!ND^<**k;rnv0=VhnyZJJ7Er=yo_+osl}@AuR+npkrcPRAy39%Gj1 z`hL$Q?apN1f&;3EFh8;Cl&6S<9P|`Za}m)8Nibu8H9z2VyeOwf>s)hv*mFu_?x53q zgsT5EU(^xxRx+@k^1kP&VUOCKj>Wcc|D&E$hCLQ{vMSf|GvNdLWLW+11J6-4c0PQ} zQ#x3ymFfHDV=86WXNxs?le5I-@+Y41#xvG9(aEagz&W338Y4`CSzGgF`Ocs6tkW3Z z`KEm8sqWMmsJ(sGGsVSd%UAt^C)TM3Q0*=erFj=UaTkQ|L^geirXp{M`zy~D;~T3B?Q~3+)1Nc7aOx{hh*KN7Nv__&#g$FIPG9o|8+O;# z$u1Bpd{w_i16|a)-+EFEyGQDD*axgi$W8K@o@Vq-?Cg$Zj@>3@M~Cq^cB)@k{X0T% z$Ld%*SpsjBs7K#SRhuRJ@ou)*iE^U&!bizr2Ro2&}5(ggEV~aJ=>=yvh8~kAp4Og z*%f?*8R*tdM)7}A!XmAv*6CPkM>+LRqD(V;;7^i~b~E-dFM02yzVnY&I#2sx$rioH zl7@OJ%^E-Fs&=csQ*TG}By*j5Poooy4^=fV%JMMFttT4?{YDemK*qTTUbjBOsag!T zu5VFo!A@OIaZ%O#B0_X(Q7ZBUp=hLDz8b1$QT_VHhbfDw&wSrJty5j8sxhxV#-QG_ z{3;-8TDl5J)o1i(>0Ov|9|2~74d5WS4DNwq+nM$O9l#KvR`D+d+rbHN13UtGcJKiL zv;_S@8dwZ=fm7f%2-@jzlmvA_Z!ivI?&N#X27a6XH$adNPeB|=1YWQd>;k92JrJ^s zPcfhw=nck!Ot1kQ1J{9LHxs3xA?N}ofK0Fz90NCj+T9qwhwnvI`OyW80Q10Fa01)_ z`d&f}T7v#y23P@(fXhJNhdpQs`hyIR4UU29AZR}k0&yS_OaPf+7dQp(rSo6N0RjP9 zf>e+JHh_cRI(PuW-$e!_f>f{=Yyua+T@Zc{d(a5Rj5~P9*kPUW$3*auu^Byvw8R!i%KsML~PJw$Mc0Sdqn;04>k3GfKyKSm@# zBFF&Q;1swCihYPX&;^VD^T65V7Sy^L%7yH0tlDF+qJD5!@!&&bMx`dBtz<}IX`fT|VJ@AHA_ zxy2fLT*LKnJ>or86EGE)a|j*Q%fs~;SF87&vNt~q;2X-*h4liK;-_1h2w7B2@5TO8h>d*3^_JD%jzKMdqcqJk6Xtd$`)DoECDxl>QOf+W0*9^xVdQl%(;l(;f_G37zu zGI|Pn_?V_|iLTp7B?NB-7(!Ilty)XLR&Wel2KPY7$wl!4vc_onWy8aekYKLQasN*` z{$$kh4=9>QQWQaLh54DnGB=8#!drR)zJe-i$}m9ZF) zMUNN>OLG;J#L9Yz)+5H3Qd!U9Lv3YwTt$Dw*+e#0#Z&GDa=%$USUwr-spB64iN%JT>+5DvfbmGLSz+!{E|1DeYp*5>*WUo z@;i|rZ6$w?fXm<>2>FCE02+cskP7C3wcsGQ0Pca1Q^Ad5^_^LD z^)j5$TehxV!j-qCL!N8u+MQKTPYKjbY4!AQS7$65?AJ=ku6iVG=bF;Gksd8~d0<=8 zpY`-~=bJLQz8(p!sjqis`?qXutml`I2Go3?O4$Z_Jo-Lqq!*AhjP&5z>a-i`x-UvH zTlP)^J+BsATaGr+uj-xa_^pbU!fNoBhC2L0xy)*Wt~4p!NUs95YNXe3z9Lf_=`RF( z$&TVHdd0$Z>f7F_ zaqa^Tb-T`f213?MO2z4`ofG6x9BL=XPjPx7=S*doE*bH9Nj70`j7RrwIUSG9QQM|> zech1JO)z*UbDEGI4`p)`y_HIjQ;k%5G$jtjq-;~YiczeA?Q?`28gAy3)TVlECD)-o za{G|esy2`{Cc38TkDY(Vg5@AFLH?APWxa zMY7uQ{!}Hz^q*Uaw;hdDJKxN9dS}fQ5o@1IWZj#P)lm;mKS7DS4jzDFr)g|K0!RiK zAR8P3mx1F9eIC#dbO94UCfEdyfSbVaDJ35?1iisHkO?+`6W|7T1oEGyCOzx$I6ClS z$XQkGccSrbxSpNYT{(`vVJAv_!}T(1iMCGecG8arUW`+n$)ld@Wz}M>w1jj)iieYn zwGJw8Ms(3DvApw@E)rHCfgQtZux(A{Q<&_?EEMAq+o|Jq|n)lReIGf4D zo_ZVTef#Nmn__zD)14h;TQ6N5B6F=b?_)@BN>^`XL|fcjuNpA-Vy+L_@gIE>oW-!) zKeW#iB}4k4#4A&6qYwI6VZGnS3ajNyLSF=y%AmfMn>YI+uvRYi)m!0RWIvv^O2>Zm zi?+(>e!QwzeDC+uJx=FW@^OD6HAI4wtW@Zngs4xZCJ}F+Y)sO>bvk6x03y6a-XDPE zY58-2{u~EvjT}honX+-9 zkp8AKMk=K6)KL1Q@bbsY{1m;hbH99?Lh7}Wj)SdWFCUDSWchHgUeT3IS8wldvyIC7 z>%Dn_6NeDr2{L-flQcS^jAkgKg0iW6h;E%T97yfBp;%^0{4i#5Mhw-fW4?MQ`d28U z0`le1CmButIgFlQPu~y2^j>a?VXM(ph6Cio(fapB zD|RBPe@$iEYr)J^jM2ww&UwD(&r{nu7y7;)ue+QSkx~3>vQNSb;j-L2st@NkJ8{@=g>)NBJ<~B)dj0fC7B_{3cfm*CJ8S1l73jL zSxPRwq<2HK+B`(LFw(uFl=PgJt0VS`vgn4zH>Kq8JUWu_H}mvkIbGr%^AX@`N%tqE zX9Ld2rMh(kKE~KdI8-R>Umul$y;g8z^CyhatL7$7gM^A zVe?5^aDl8$D&b>gd|{bXzBxMM7vX77#GZ|kVTtw0<|1QS3e*bYvB8{iQrc3B>;)T3M_Xg}?- z6G;$O{L%g8W|6n(e4M6D&C;nr*Q z4*xO0=|a5U_4jR)?UMmctkvV538V|XEyoG;-azk{S?lPE*5;%v?vevr=#lQ)tk;!I8|a=rEgx^tD?-0-peB!y zn2ox9&d~;H=gf^HT5Z|55sBJzZX=aOf`q<7T|ZSCDVixG-=NB`Et}uK*^s=FXA{oy zyh)4i2;n4EXOZH1Frfx~6es)qT{%7hX*@C%e~wilX>Za$_Q{+#(YRN3ze(%SKpJf# z^bKUtCPLp)_HV-OP5D95TT*;8p8g_zHuLnG%-@WIc9M4sPwgari~gc>xa{A;usfgR zd5i2lA&uVBn`;dn>M_48eT!J#l5M%oLblS1>jmuKNlay4CUp{cjvFub&M0|htKCj* zC4rks=r*h2ZoiGE=VY?|^sahZCO_CuRo>?5ed+VICAnHX-Ib5urm>~rdYcxj>N_Z| zD6QUkVzdb(J*A*OETL6HO33OLf>rn4a#4OeF4jo=cFV=W?Wnvg`?u?LT$c+{uBT8o z^X#BfqlvYmo45n{NEy9@y_mO5>WWG=D zh@aPdcyL-mcUg@&Pn_zv3upIbrfu}eE(G$)pSzyKp#N@S(5{F-21(VQ#DL%ylqr@#K|8`z*V3 z_4KA}-j^%4_5Eo6P)hC3WtOJQzLh1p&F*5R2N&~)`A|)N2_Oa9A3$p)r`PE(xZ;aB z>?5?p-=)mP`^vscA{DYHU8?4~{YBMdwPpT6+V0lAD+l%Un!%NPv_npZe@935dwR07 zwlDaIK3(Hw@y$KT*xT8_SL>Mmu4c5$ZwpWHpJ@G&ofoY14Z-;<>JT*8vWdxB%c$nZ7`-nYKgQ^;%=wsbR+Nj1Ql!F3 zXpKx%bXh(;srNF}9!(YY9`?~tai7r1Nb^1aiSBb!QesZ)gN@ULZILpz$kx-0Y3>)c zs?fq&XXvQpv&w_h(ZCkypv>$tl4F*w%;x-E?yfRB@^`biPxYGGUq!eejA&rj{ z^QT0mtD>S=XEE_g@w1q`DW%Sl1gU394oZRgy7%U4f0$=4@dyXUY0C$1@HB+CU85jc8 z0U&F^K5!P?26?_=Z^Bjo-Ey~h(~3&jTY99c=o!wNV~2sT!$6nJTXd5A)1r@*RB0*j zy{^u1ZU4On{LzIOg|%Awpj-R zT4v!tpmLE^`@tH?Jof`SUO6Ktw^}N%smJwaBzBwi*!~VG-;&99tV-lv^>k8xu%D{@ z$kTVy=SRysJjc5q@$T^%S@4#1rYPRUFsU4K*Ye5o+#MrCDC?NgsBhWx5-nWv+ir^__ z)K$LACDrg(jD}0sU!O>AQbx1o{a>GW7XBMX??|=ZETiXs!?W$O@;9qh<*9%?Py%}; z?}H~sBOYM%q0G!>bX^&pQd0S)Z^IB%3jIzRHk8J{qtGQI)sst>{H||Q4O-ko8nk&b z@*$@4WXVIT1{>la$ zkx;8(<3oR=rW29Cn7IrgX5{HMxYEpRCG5$! z{<=|~_i+wZyoiT%qoR8G?&wBs-nxzk8siKj53d`)D>^I5WW#96>vYI42D@&3N+?DU z!e%C(KH$mnG}XjY-W(Ih8vLxf%hv%%_lRAe)sy zSGfoo!_V5mE@t1nS2Bb^&6a8*MpM^2IJ0g)%~XclWladq_R7a0MCn8IR8&faVslEW zg_1)qnHp*grl@|Wp7u(;Fykeot5uqujs=o;Bx^RVhZ#q-ug=TK5GLRcK5c{-?oa31 zE^Xm})C zM@zSl=xc@nb75Z2ymEX8_k_QP2f{zVMYr{H2jkWp?0^?;Zyu$^vl-Usk*H7mMFOrvKtk&UaECIC+Ph-8H!^E5= zca9Kv5F82*gNcpzd6-qt-bwH?@Ju)#JQpqiFM$if%U}jw-q+#6@EdSZcn8cP7;pL> zenjx&eYgaC94-Z)gG)@vFHkj=4z5};_IS#_{ zEPN1d1#`TEqczO24%U%o7vRo3e*<@c@4?+*XE0@q{P)K2gZ%bB3n#&yVDjDD6CMN) zga^ZHws#DLC&R2Ni81{@2|gxkQgVJ3PU?1A?Vg6F_|D0Iw+C<j zneZZ*%}I{`!K>jV@CI1my>R+cew^gTEASWa9{4uA555N`CxWkT1P^ea2cN2@95!U7h$%Bd1t`vq4F+)+0W!%1+xjsyB=l} zk#`3i315NB!oR`nI`IY@ybW+D%w7&}L6}V#-f}S8BfM49`N3R`Hx_0$f;RzX^MSV~ z%w7ZU5V$@(9%ibaIzk;49Y15U9Yjc5 zjFT>6OrAJChs(g1;j-{m_<8sm{672z%(TDbOZaQ}2CNPrq2;i81mD8+8XVuj>VUvo zFpa$9C;70L(I&n8Hx5S}NCc@M18e{X!FBKeiG% zrxDxJG{`~epms_fGzwBH45&gKTR|qzdz#9aNF%ThX^(t?!w}AFa<^_~JCu%%`LI)T z1H1U`l|y@^V;REmDKg`m$)qwyga&iVY`EMiohu4IDJf2Ua&K%VMamjntJq9p%jWWG zb6Et=A#kUeoG+WpWq~LxI3~({9~V(Zlm@3n<#KsW34De?)#jW8kjrJGa#+w+akptM zDdmg^SDWVkd(N}V8G(Dw_sB)WJQoogs;r+5dXjF9$`k!d*vx6}kN)X6qMu&g$g9n1 zuENif>+(iB|971|;;ev=9A)L+-<*>Nh$Y;vf-y|H)?D^fFuHMTMc!ycE+bN|h18EW zYWhD=sPYsT`}HR$C{5&)(^1I2)hs*ONYE%RT#TNgQ9P`x*HSAQd5jr;LH|%_1!kHm z4Hb=c8rk`{qH)x)bI<9hWM77Uy^@ira;bidF-GOXmKftzjbslS%#{Kh6wgiMm5mUU z&QmHIDMnQ*@=k`M>a6;#Dn?B!A^Bdzh?6ISbhEretP$mQ)r>9a6Dku!{xZOAUaX)W={SR`pe5)JCV-`2D>wmefCnJYUF1MZ&>M^c z^T1lL51a*efzE)dB&Z7#Kr)yBGJkU9b8O|uF>oC`03knHcY4=kIc^2QmFuIas zG!BXNvJDC7T%7TmbCOJqNBwWIIo|llxkM&5!S5x$HBAhrr}IjWW>{8``OUDrDLtAS zYE1{e#jqOZr(4hrBbdsShu<9i9Ti8}x8{+wGW%ZH-KZ^%1NzAio zY%9M%i(p$R-qQG%H4wqA7~9ADsv4)`nVF@m51(`bZhIkpgW{ z)kYe%$rXSVZLoS(cCThkHKJaSPzRg%z7 z#zLndD?8!0!69zUL$sF)ov}M2eLCZHqWsyJfFw%sF2wgO3GRyBFsav-fTYQ}uEah~ zoZal`By=+>X^+Opq;5vE;&t7OmMUy_F(-z_yQ>&Ve0QS|)T6sG(z=U8W%K3kguIg6 zR}z(cg%inUu723x1J7QNpA>DEvOOtHX_C~FS&|~MttUlvsnqI42$o7xFLdseiM`NS zET5eVk9wgqpA_g#YUGnfy^VJ%9e?&F;A7>LJ{XRbLw$@kd>0ArYm8RTynPAhGqSla zme0t!zQ#o>W&2@zMy~WTsz9Or{idpbJnD}Z2c zQH9ZeRmQuBw2{pNd3T?e`vZ-1{ncC!3$T<&rL=EjvMN%SWXB-V@kjY?kkOBl-YSJ) zs=HuR`fo}hm|l55h4lBzcgl)jT2={zv05X824l76?^d^!)nN%9g4N-_Tg@AS)mQSm zvij=pR+WZgWlHm*Mx0Wb_p_b7Tsiu>mhZiH5YhxI5T;g@2BAg*L-~M8~vQIP*YXh7-OuF zx2HX&*VDd{xFHgGB z-$~6f+G~8`q%w)0X1r#!VHQmN>u#O5m^Ix=&rE|{AN~5Kd!uHB4-e(GyqQg>ewb9=7)l{|!jA0&k z?P?>=FsIppDrGnR*`$2M9HVMIxuvLMHX%vy&CDhp)6Y~O+xa^jW%F8(&8ZZPGK_)h zf({@Vq=8JZ0h|T5fzI@3Nzf2<0pq|tkPUW$Q{X0WFnt;hYJvoi3Nr37;K=63E^rFm z1VQ)dT7a4$0gM1MKsML~&Vt)OXCAgBs0k9l5TH)ATLHF%Q{X0e1oHoe97q5ozznbg zZ2yg!k5l}(3G@dj1PwtKkP0%uTCfjX2M<8_@APLt0!RiKAR8P3mx2BeJ)kb=0EPfB zSPHg+W8gY?0P=+X!B7aqfi8b6ia&0RRXF$7eWlTpu}Y|>9{#_FDjb*VzSk)CP-V6~ zRN?qscjegJLzUU~P-PhwRbq1wRc6b~b@Y3eW6>s7wyewPrO%chl*KA6ddEt^^^70j z+Ux1PmToMw)*FG9VzcGqdV1rl5qz%k|1lVuEv+^%(#b~VCBKZL)1ahe%8RPGJ1|RG zl6k@9JipXfUfy7^l&rBF-(XbMwl|iC8|a|V<|<3Vvj!DWaWZKmeRw$6NM$yQau9eG zf#GqvM=G=Bd1dh$7GvUM)f*;4CG1ekkuZ;s17Qkg9)mBs5=9E+2qZ!%Ij z7WeOw%515(iIEC(w(f6~^^=hb3a|;`v|zV74%%wGtdYvKO^j3=@&6jB%$B6h__zTF zHREOOW?~6%+000#Tf99|nJuHYAhHpWRq?q;DylT)9;r~W@G}ji>0<4Y}#g&*T|{!+l*T(8yKh* zk;`uz85&7%jaIzxpoU~-pu$k>9U3!|_Tf85J1YgPAxiRgqo(#voGjZ;h)4^DB}Jsz z4n&DEW0PNvRaTm*hCyAxBxyU1xb!^!icAerM({Sx04u;&a12}r4?y@MUSE&^lEDO! z3ATb`;4-)eLjI%z1PwtKkP0$DHrNGDfE(Ze$n%&XO4Y}VaX^1C0nB^6DE{rNhQTF0 z=h+?JHq|BN8U`2F+NMgo^R8I`cYgn*LxS9G80@C^Yu)G?vfIe-{tQP`QYC6P#S(6} z+t{OBN|op})cSg(0dl7(l z?lnef$3{!kJ~HsUOx{Nk<@<))9OIHIvB7ox^91MRYi!)ice(S9k+A*Dgq)XF`!Qnb z%Uzt~0r#U1&f0HeUXITl525%v zVs*#Kq(jt7@Ulb30WT zTLiZcw@)Tg`4)I_CQz)%x>fHPQ^*cq#1RsY7?<_JwYNv}y^k4*#t6Sz7u)O6PzEE6H3);-Cu z)bZ?~aUGJzB#o3qm7IZ->Q2aLfXm|d01iCNP|EYST{?T=&=pg#_4f}g~pA({1Uez`M^yqb5(D4*|6eN6b%K`N?dXwGf% z^_*G7%#v+Thh`Jodhe5nm*{%SN?mLTIEicIfoa^Opl(l;Lq;K$Z{#tLC zl=>Q%i;2ZIU)cwe6t-u1RayrMT7ObXrT33j3{J25ni6&TqVMt71}n^4eC|8^t-%Q! zM1I&U%9I^frz5{TNZWVIDCQz=_5zK2x0t@{ZN=2-NU(Q=mHggV?6QK*_N=ViMv!*& zn$LZkEH(&|RX#`9WjXFgqf5_r)d>uL9l#38$5wC*+yo9*RD^@7AQ7a3#b6US3vL5e z9Xd*ax}XCX2j+pbL2~CurifdU6a&~Q`}a+&cS$6^7rR&d)8>6;lYq_cf7(>|37fXq z-2JD`d~8D7VbiLZy}f`VVcWR^r@pa28GCno?0XfHB0p1Y!u5ZqTkPL`%!S+tbUWZP8HTfepeP9vG}~0l>Wtta(!MbSW1L4Yn%Lw@pJgUcQ30(X+TjKb&p1AMNzfi zw4JuQsKnkkQd}zBdpj}GJb2$obrDus_n}?y}y_Vn&KP!ml|6Cx@4u9&ZJgxr`g!)kv@v%$V#UDOae}In@iN%{%{YP`$=;TuKUSE54x^OEuE)(GE_I)urO_hZocMf zBL4mSy9_g&>#t86W);Y3njQU%%KH9eBi2J1YMSkd{ch8&qT};-&zS994;T4YO?Am< z=5hYv8?{24ub38 z0SNc-0)h@;2*?B*z(H^UJn~SX&#@|W&u>&Rjb5Z*d)X-NQa}DxqZc{x_A4%RwGt$GN5_g5^E?MYx*6`QB zDsghxz$$&L8aO-BOd$5YJCP*4x@Zep(+?NKz}9bzA?+e5d-01Nn8{P7nwBg9#uLYyhXg zO%P`N@hFl?OxKe zlG#7-=ANoV`thOO{SYT_alS)Vj2WUm>?L6_W|sC;Z&?>(vbn4`+wkEsy*VJ;9M3%Z z%*tfMQQSHD%9hGx7JR<4c}J_>SB_ROQ?#VMQn{*GJ#-%nE>xLPhcO4s=_+i0_Et6X zYbX0k7WUfcesa93SzC)r60Mrq7u8ACP|cbFcZ(#MTMgAMl6-GhGwXATRFd4Oj+<|j zq;w6lvL*wiQw_5lZZ_7y%`x1RPnI(^a8o|n_ppY^zOB*8Qm_`XS;^9(mL}a9rRC6kyVPbQsj){>=bd=HCt=G6zNo#XUAZfRTrK4 z2FuR6W(xinuZPa#==^-JT`t$wGxNJy=-~c+upFp|EPV3Spwtp}^Pofn#qJ=fLxx!e zWQ4>&baO^neRC6;;EQcQnIma^DGg0iQwcF9)-0&0*v*YI*|T_4COM$nU!Fc(SmA9RDxOB6~w6mES&El z*_tazHYAw!{fY=!j-oCo!okA?GsTmQqFqnX5WSMs&MfKSnlHEGg#Q(9*^V;mIN|Ho z&ZIJAwS8B!g1ZV5J#?AU72kU3K{*!z99ON>o86J9io|kVE_F8}H27h6bG$ankTHp5 z>3T!fCGvWlHRMVkNY?Z)i_54vF1KX&FteRiB)%v4UJbp! zgvhX-WHY?1ry2OtUqy^w2vkR4R;X0(Wd@E#t|Bv)MGY)o4V5ju%xDe1)XN;{b@*v8Wp+Ut*!#eaR|8a$uLc;4`}oQqlic6aB5iq+K5~ z!mZ3(h55$xF%s2{OZ41YxSdRnhR>%aCyg7_Way~mp`!+Oe(w1(0|&(p=+`faEq-O4 zE_0{+5Qy0Ujzw$O&|JO!e=WuD4 zWJZLAW1k6>J!X@V%<}Z_S2uQ6tZKiXfq2*UD;!tA)|6Xe9TYANm&ZwFkpjn17KeJq-zh3$NiZG9LNr4KaARr~K0TT#gJ*|E$f z>;HNv=vz2QKC9^|UT!Vn9D8LBb180s zVn@*+NpIpT9JUq(>aIIWfaL*$%!F$HoyCboY*nXnLde7ns)`m1l4}!#3rDp?O&Nrg z0ERg!pl-%4iTQEMT=t}xYpag2PL&NLLm*>L_`UGA{FX<|^18n-CJP3e&HhoC1FqtV z+96Uy>A)Y8zV0H$MH^x^tNq^@8dA)b-4t*FGk5QfD(){4@%=arJ9CH`6xIw6E&wGO zRa_pYo2mZ@N+2K8{7U=gQW}TSGsUIJP_spJAi{y_;+|h#WntitNnv-@2zh&`+4BGJ zCAqjQn=4NpO>mVGA<@IkxPQ0`_;uOuYC^yxm^D1^!4a}-nA!3l$rNzaCBhcZoh7Wv za$k$^C)3FO%oM0Ip8w%(Aa@)kYz6*`(RyIrjytS`%pGo)4ok#?6F}Kxwr9AR@Q<1x zkhrOSO}V4p0!^h#NbM13-2d^i-wTUF?(Vn}Qe>nV9d?r-xsozz)c;w$AC$Jm7vyr)T7{{U+!;jz?nCPlWRyK-5zm<^VUI97h}jU# z29=VRpEE}k`ui&v$lp{sT{|eByA29YmXgY;|0;BWn&fh%?SE*lU?kw`b}3nxYBu~w zf(G&|K`k=nFWx5W|F*dLy_7sN`d>vgkWdHxuKej`xoU^2`lV&s=zqP@0ar81+Maxp z%dhsh>Q&lbRPzoDDU{D@ERNto2gH?VuhJ4V#!U7PTLXC(h`>ErGsev4<`bSfI#TwG z`B#_&g310b&$%pp_ZF7aW6Rr+L%CfO!?hv$I2g)8ZYki|S zL;L?o?tOlB1)NXxbw*uS8IBTH?K<`uK-ps!p{9j1$C=e@|Gml&#Ho_MIj0HB`RjtZ z$g=(vt(MHp=2Op`|9tra3Rd_Pw=joT<6M4i}7Z+oC-ORA3@Pr z@>j;LX}{jjVY9dEYIkq-oQoL@e71)hj}wJ53og4v>Kpg0Be-~12#J&+$9D#DIL`K=KiVBj2W7sd3Ji)Bo=f5+z zY9(7=?uxk=`rh{k#nGf|mwv;Zn>cpd(1FAIH66kKR+4Ap$0MNJA*=j(_Wvk9*?uo_ zm!IBvaUl>}XNp?ZI`RK3KP_YIFs`)8`o9kf?nKG?iInHHc#t0%Wsez+2cK9cnbrS~ z7G#%SUGB!LFX~<@CsQW<>m3c$e4G5MMtA25L_b{ZDJOR(nMK0(p;fIcRrZ(_e9>$Y zb`P_0n5nW>xV)siXm-je3#|j4aMg9??w;NX%;uDrU(?L-VP}ciJXS!dx_VuCnKapqF09NtAom*Y{5`*Fd$QrD z$!30;-_h`dW#T3QnMufmRFH2bo3kwa^OSyc9g3DoQ*ym7f#RRxp9gQJ!tVb|A_|YA z<>3_a=NRt0AfxOti%K_#{3C1H`4eME4coadpavd*ri6-eAlFs&XZXm`Y4;qxCG7${w@UQ)y+( z^Kc5NQeLZ)9GLnaDU|B3Nh@@U-;BP}@ls#s{rkVHU`#ByXtR)s1 zR4d(ZwYrjwpHBBfnbk#@9cT_SMz%~hqr&DPQxmfen3ax^FQ=Q!a!OjD*16#iM1w#G z;1mLpN%cgIJ7nY#ZqmpOcSrprbpi^u*0o*s*Pmz@jDnA6n{%kcN!1|H!XY zRm0^mn*gTpG4XT1d4weWq*go3H0#&4FP8{Zl7X_Yww~?F?I)h8OTFC{8L?Tx{b5K* z`Dc{=?dVQLT1i%{D^at|8UH9>fs&e9-&W?Y0j!6i=qyxEF3lnzHlU>;GRj_=^)e%* z%xp7KB46@UN&I^a8mJhK_|x+}TebE7FmyI!V5q|B=sa-D(A06A$0dy!ryf;^$KgjN z?v$Hm_2lGi^VP6Tn9alN8O-k0lPMXD!Tz2ymHlr?`G!i5UH96*xRaZ~u%|xtFq5|a zIU_Y06qr3LqpF}2z7})L8{y8%zKXA!&7U%u{~?4<2dB)cGu`KHW-eFF{A^~~T_azg zE#@DZnyKlz%}g<7h1#;k?9<9GZ!?RjxtNE_u5_4fSI|C~EbVQxrcu{#=0Cjs#M@?g zk^CMtw_?kxc@|ZSmH^%3d;GRJKucdu@qfX|?nRhN$jkmB2g?$@Kf-Bnz92S&!A0RI zFe5cbI!w3T;f068Q{l1jG+1psoer;tXTa~lGhwx%bQb(0JRANE&S2-Vw5k2rq!S^w_Zo=1O4)JDk18VYPpYdw{u8kBe(zMhV_)@G>~q z&6h&BHoOXc7G4c=JgsA$Gu__cxeb&p4Z^IYiUGR_a9$4+; z+z&^Vg zsr}e#{80O`r^5H(*|1VP2mX!cm;AiOZ~hwmknC66C4a|$mwNWi_nFn4tR{YUmzngG zdPj;oV%aX&SW4_R_lMHXIqbQ(zzqUr9h!X~vhpggf1vU+VoKDWUsKFa*tWgu;;G=0gNc2 zIp(MUR`^E%)wEGxrj7QPMbgzqZc@ro70v^z4c&!cwV_)L_G`dp;aae2+3LcoNo@dk zhE)iuKFyp(ZACpZl53_lHbg-gQ9S!w@s1-LurbT=G5;3lxz2Cn)YN;9OOD zKkqJB?F|1AUI1T$GvV*ymo-O(_YpsqW1zlitbw0~UxSOl>*UIQv%OZdm{dMM8gIrp z9Pur%njYE)tH$?jSQYAbU=^;Na9emc+yPb_%T+k{!zwKg!Cv?gkIQSZHFa)UADbz<}>UmJyu}Insr*f_^+{58S@RSUY1)h z{TFNV`Epo=MGYu^z+6Q_@kYP-n~J5>L9>c+#+oQ}@?B3|kWud*QX$wrfK`$yEluG+ zcy8wB_I~q@@FUFoz<~>F`isHpr7sSviZ23I z1)v1{EUf%#2}knW1ug^khs(mMphm$jz~$wqLuLc*T7*POV6ftY&r)vkJ#rnTT_V70kEl*=7M8Q_FcsRvY)!LC#Z zf0P>_6tGZHDP2PD5EdgIb5+KhNZ$7-6mfnpmsod;q_@CU6|I)AN??W;!Yr%wj)hf@JrBRY^LRhg zld_&)_S>@{#M*Wr>X6tY<}Bk}Njn>c+l4S4r=`Jd;*%Vf>_ zymlx3TK^weUjtWFmA!qhfr%GPQdCqDN=!-$kc*H~kWx}&Qc_YyHr?LtXO zNh1|)DJf~Bk&==|QW_~KX{3>ol158P8fj#b8EIrj8>#o%=UE31|F>U{&s}@1{k`_u z`|SI{6~;d6`zow1g?2kw&+hB0zj@^NOU?v&sMn5M>VL%>NY^g(2e1#GWlhh}PK-;) zg`bR^81xo&dhYcX`UAnb1-jpLkmJCAR3)E`oZ@xEmFy4yY>#`dSnF@~``B(6C|U2d zymGV~_lqM?!dT!Up#R$sd+pqfMn3!~2Uw5GhhV+r4uJJ&H-Yv3^$}R_w;zM`{)Kn` zbK_@r_k8hMr1-I5dTgQtp+ zQ_$+p{{YsT-D$91O5NZL@Q+~aE@xDw&fRns>rG1`yBWh@PEMJV0<8@Z~^$d z>OVAc$}oM4*@B(y7bNQtVe{ZA#txnV@e**fP6p2ddx95%F9qw-)LqhzaX`)idxIYb z<6*@Z)XTv7ureBqQ-RGF{5BX5B*tKl1)tD6*?7D-4+V~Ig=66Y6IDwKb~0X-+HK=_ zf<%-r^n(?G51b})z-jW47Gqp*+VNEZV+(*}crNbB3a3J?TRIJlE1bfsg(DOexnq;)beKwWG`fPXy~ybQHzonXxK0PnUE(ne!n>f${DK zR$he77k>uqodY9-yuyu}L310Ndk6HoT-;#~*#>bNY?QBAkA<#JZ-e(h*4y9`Fw33K za(TaMx3Rr3xb!p1T?V$cHxsgsBATu3#bt@n-Un6lVT>)VSB)dy)pT?`d>X!&4b}&W z9I)P0bHP)2YLwI|nrbx+;|Yma^l{3N&*tiW%B-vI9h>u^~I-lu=)>s__sbDWiN z-}>3-h%oOVU7uz4frG&BgJ*)Z?`faY^3CA=V7;Gd`EJo?gPS1h2=ftmE%+d~0Ne~N z0{Lrryo*ILY^$LK4E+hc?S4z;5pz^;M;ITVe7&R{Ua|wfYZUJ!TM;?4aTL4 z?ME=KDr{%KxJj_#lBMu4xEK5__$TmL@PENSfzN~SU~l^wJYpDjNbqQIKNwHNMg#r9 zdSs^JXTEH9PaML)mw@p&Y8cD`UkZ7l$cseAW1h_m>3C{0^lL?rM=6^((tYr`313^N za(^+>Uma~5dBp3NYv{uGeQEvBF&ajCUHXD`j2Hvfo84Hjp5Jk*^9!5`7F^3*dyT)L z7d{bMz0UCQV(iBR7Fz6~4;P6F$dwh+7!j61TzRPZA33UD$w z4~!pQGoJhxgI|Dr4|pp$75o|)Kgw3P6TB3xSDtQ;c4RFd&>p`GFAj_1GjIlE{gkNr zDEL9}_uwqB_V88UpTG};$H1{xgSCg}fVC&*g6DzPfHT2s!TQXMUxO>erJgMh{1W&P z@LuilkKzR`)ol6Tli&g{?yhW)fxX~JxD71C7aeWu!MH!M;pgNEZvf-IyYN1+8@wD` z2*$I$tq8ms{3Q5g@J8@Xa4{Iq*tVy@pMakRAIBwutpqRdoN9X(j2}m{m4fj+YI_d+ z6L<^w7x437JTux}01pS3gGYn)kd6cEAq@g=1z!!W0EdEK2K(49Lp+{fz!$OE*LIx& zg`e{}<;C|1^v^dNtKwB71EMeZDh#!*K)cos$l6EVP*r~&ImOL40qn*b0(vF*n7%=W?3m>F`{<%uq0m$pXAAz@kKL&pwdR&#-njzyR)b?jE zZZ7d10PL9jF{x|q67?I1? z3tj;J35+#hG*I7!pMwnFH)Qy{tq(F>)8^Ja_#IySj0DUZzBYm1N(1BP5ev~v+pl1x z+3dsNx5Kg9f~SBz!1KVv!TP5WF9kmc_5yDPJHYt1lg%6a4tNy!D0npZ8!-Orbm4!8 zBXo?xi^+(Ie&DOXnzF~#0{J=Y*!#ac00s24u5G0PMh`nHa zoQVYMqvtH}Y;ZJKZ!Z|$#+y@iy_4Xc+85vO**FbWi(xeboT9=za0|`1u6^905)PBYf<(Kp+lS0^|c*fSter;51+xg>ry7z*1lx zum#u&90ksd!Y(ly7p&8P`9M0LFI=|*dw|2hX~2fSG#!WoGJy5Kc3>ZH3^)r+@Wppl zfJMMcU<Z|r$ffdxPYuo>6^8~~01=K=f? zZ(Ag=0LTG00Xu;Mz)9ddFd4x!5?BnZ0yYCXfP=sZ;36;G&rd$OpCpyMe>NDd6HnJAS9W#s1RwBS*N?@l>#JEbd6LT+lvSES8Jrnm>|* zupG7Ai8G4kZWlS`YjVpRasf6WtuN0f2OT4a;>@Gdi~mQqV;O7Nx5Hq!t-O{A8|ul) zW5}KvCOH|ALg#Okiv19nw4B^Zu8{`#%%@y>B{?)5jQVZ$Cz;TS zMXoc}$xv1ym}t50L2`W&xjBJc5lBvw3d1i_uKO3cPtuFNr|f)}oQMFZ%k}rio}^!7 zZ)d^=gi2i@lneKjpSei3N7dThH_gDxmZTXxr%b{hvbrevR5y;U-C6L z(0`-Cb5!_ChBQPGo!)^Hj%Lqna>>=?+Aqjn{~>oak*g3ew0-d~aux!FmP2u}(%kbZ z*)@;6VKn-$6~TDM)Esk^oc&*N$;aeG1QM<9-axrS=GI@l+4*Otw~4QK>0KQ5Nf*c^ z&E#AJ5}lsnN$zmhP?0CjSN9jnRZ-*~bI$C{&?w8Z5gUarsQC}%q;|>IMy|ugr1dR7 zle46O{W7(Q*D>AQA?vtA*zXf6yu8TCcoWa4s72BdfwWv4OZkE{AmAy=-6P5V*nqTM zg>0rsyYk5?$H;kkWT!Y^fY{lwdFT!_ z%M>JZ&@QW%T=N6D{bh0jBCN6g{R@~-c{jPBj_k9B93acDHI#DM-^u0G6ubq`?s`fkjNTznsTfD1Mj-Uy%IQ5CA9jipg~7C*>4^B_*`_jSLeo&6lSQ=GF*B4)Kj z%vhPSBnR!fzaY2wk*j6O+)mOS>tzTu-i#C3{{<-tZ*33m-Ai zBhxp9vQws@YbNESzmR=#6f@R;tm)-9QIT*JIbajH*@s+#LUqB;AIV8k+P_B$2cUO|V7L%Lb zAQ#n=0~*Oy%_7UlWRH^d-~N^;_K@qPg;`rEyOxm?BvQ6KN;z|mq`ydxk@(@vr`-5g za(y1T;s$bM5ji0b^RI_AMq1kW1LYoB4aa3!mP^PiM#$9mMN-fOnadJ!veaSJ2TRN^ zmSq_9Ez?WHX;UQv7PZRC3XO$VtL^Vpmzl^t7AEeUe`MU&^gt zlKUlJ-^Y~OZ$x68xRjR)_=gin9$ur?mt1U5)NXlwzWzesFQ#bEZovc`(|;* zep$vbuQNUOIdW(TITO9s9f*Bg)_>l5CM4yPyVsI^g@ad9PF+auN+joswrrxv^tVj*stZLmq2;}cNe-?r!==tJfZq? z+QpZWoi~zGe8}a0C1-N4b=yLoU_w%y7@Q)f?j=|4C+BV=mx(L(d`sDxNa*c;y1_mFB=;NTVG^7&5sfkt0n+1m8G)>yCBvV|rScpT{|)8pU&xsk$r~ih zBnx-_i|OT$kvq4Mo6#I&5f(@R!II%ZFAWmcO9okV;h$12m&11D^_08C<@~>(oV$@6 zFI+Aj;eV~<&m?D#lttJezUeEAC{-SqJmqxYD-~p6`1BCw-9!$bO!kc;2b)vy9_6A! za>}pd4ypLULCS6BCftisb-~TKcWmYwepR8;+&ocbX-Se|cUWmm7vW_ngLIaZck$VZej~c3VNQ8ovd>_8 zZ!)<{;z&Irps@+NB&61flQfE}xOK9#Fo6`T~iVF+WqTmx$Rc z5wqYMrf0uF4%s1_aMK7T^vn8glL(hB5iU(CsFsYu^J(Ard-8=4az`7vekD2YALQDR zLc}PNsK>FEoBlx%oHb8mYLUkaF;^ zWDAZLkvkT_-d0j6J&2-v@tGCtI3bTBqX zi@zUyDR20bpDp4X`uVT90MGlH5_s=GW?jzUAYH5>r&~{q%Y2@4jve$94 z^AUsHHs=jY$T~{y=^!Ua*y!+NQ@OUCQg114*7VAXqOqOm+4m za_t(;nEzfWxJG=S_&XZ3yhHBWOYR>-ZjwmZltH<8p6JCX>*FW~{FPiJBa$i+(j`;X z)CoQ6x0Sw6!{%}1%1UzMUF7F5lKavw=H;k7Enf4mfE5+$*#JOW- zHB@)W`p^A^vp*S4$7u-rk$L2LfwJota%d8{L<(%Ip?sXqW%H2+^vfO-Ae&c> z+^Yn6ApYr!8Zi`_ohQge;*4F=u++m$Px+(pc5;h^UmwhyOa(I@0m*`?aArRxoy>#GDCu#a!U?T4v;zTl671nLl`XH+xjW(f@QCWxt?;Y$bC;xhKm>t&0>YN zgks8NjheCk%H*lNKz22|>}o0Ewa!9jXt|Z_?@jKAB=^Z?(k;)r$K`E`GFff`H`1(h766*`TV0xb~*+-l$L{7T}e`k7- zM9$L7DR)$0{B=*0my>J8iJ=#{?k%!ib~8_rTSJ&0D_&mlJ>?2nEqP)WBl%)QE*MX{ z4w1*RKZ9H#Z^kvuqnvb+9GXZDm&oRKHRU?#NQsPK!_7=D z79VpT|Bwm2bIGnca*Aw9{W2n1;#A2GQtx#Yxh{}gau+#ELTjOH|pEpCHHV- z+%~WMOvsa6%l|boTq)`QCWp%=)wWjBOUSJckuxQ5`G~WHk70UA8@cTq+5Z69%UJeq zT#P)!gp^g}SgD{`0!rmXrdR%lT=fyTTQ;c%ne%Xo^`){oU06W76zM>xgzi+?tg^eI zNBy=7O*9PlAbUv+4;3#ilNjDB%dJ)-T!8q5*U!usBO$y=Mxy3grnkxAwMhb9h%_J# z5!X2XCrHbxrZU3@iRsPCN=&NOH(O$aNB` zgZyRxPm@@kEU~&mytY*$)dmC!9Ve=9B706I=Sk>Jko1CHruW}X?t7N(C(E;IKIIab z;vV-;Ob9UFWPg!zmc;B1=~-Vc(=!pXbwlhDvP&goZ}_X^TSvy%+Bn3~p*dJ1?U_fgjp}|DLqEH=@D{k3_107 zgWa|b9Za}TORoDnxw3*>x}4noUvla<&Q-tn8gw?JEYvw-%%f= z&jYC6<|U!AQbJ>p3}MTD8n%xYewFN#MNU{r&R#`MlIMNrUnqxmkz*wQ#g|a_{0+G# zN%nvLSxm^5x$>M#*+(jL|;n$}Y;Y9-gr z!T9TnIwUX@zeqXdJQ<%KH}uUH$o&#ZJH}BCzEjd=kLbLCa)Jzfkd%`uc78unpL{*J z%l!~vcnXI~NDYyY8qh+0jm&NC*Ocq8Ay;^jnBjS-Ed%T4i1L6jSb#ik%V(%hxcyX)?JvO61SUUK_~q;*?dc_f0$g{Nw!NQYki+`**J2eM6?od%5v#hOb+!)eBWEpu$1grUg=@(=~Vt+%q_yuzAhvcFw$o|6N60)7mOivc43~0mn>mklP zNA5X5E|tiY`wZn)iCk%4Qg;4_?E5jfNX~*)4^vK(A?}inl_W5|{sg&F0#vnIB9ypZHLI6GWXSAQ}&d(?~s60CIKnnFVuI-M_f|G*L*o5ZdseGx|zJtrCzDB`%anK=PM>R4M_f?|SB|zmZ(|Cvu7eCJcztQO`KdnEzIJ zmp}7OD#}KX@$FH=uv-oip`x$+mFYphC0{sCu96XGOrz}8PIgJ)>YGftM5eIsbI7RQ zmMlY4+eCv6lgOSD$$HjNZWC|r5+^DPVtT(+SW!s1Ba9sT5IOz_a$-HXQAV)&3v>NH zN=4UFa>7<}i3ARpWN4eo^v)1+Ru9>EHM#l@(Z55k70#1}q{J}2M&d*NZLiGtR{EeNv>N<4v;|9FAesT({{zbWc@cUreTd# z(6f?qd?UH>8M1Q^IrnpNM=9AZ&epS#a+gHTSh1@SyVh9hgYF=wxG@KM*_F%OXUZIA zeZ}fiCpVL0 zkC0oXhoP;MgUiXer$xVm>?8J-=JNZF>4`hVPF79RQ- z6v1?-+~F3yM7boLykR8SCxBeqLN5N199m6IJ5H|h(Tw>|JHv!BMeaUCc1Z^NJCtMP z0i#0flSVMTMSSSEgxnOFiuSYAXH6qF|AXu$XUNVn$jEC8s->b;8c<`xZm1$BNkdcR98rn}8vB3J-83k@mRu%I8B#>K^H*~5 zbL7e;b%Y*`7a!NQkw3uA^Jh@fk zLaszKUx{dT@trgYWL4r50oO?W9&*1-MXoHr3yCr$_`M`!8OA1)t6w2!N^nN-hp1+ZU2s zrDu7v-0aJk-YBaeNCHll7t;fp$@R0qsNa?+UfS%UqWwE^;{o!9o#cw&lKY<```tpW z7Vl4$IWOvBdb2m#x0Bo|_DOG2u8olO?~}ZW{|0i9 z94KmjPdTlKT=y%v;W{`$=T;IYl|kSFlScJ4cXfyOvbM#82X^s$(@grFUUE*_blZ`i3_db%pvtm zuh>BD_&vE;8q)I|#$Q()^lx%eJK6Uua+PkN9f4Gf(}y{CA0QVQj+YsiV!|aY{%7d zvT773?npQ6@Fkp+%+UW1xm4!JSwT5>F}XwvsI8@(eT3Y9Be^`D94q#DQz)lSB*#dH z0wms~80BI9{lx2=q+*{kW+(_E_e+6^A(Vq&B_~LLiv1(ywl~SXGJ*|#lv8BHdZH<3 zUr8?dGZ^*TV!D}7DFsxFp}awSqQop<5!3BokeyP&aar$K5;>g-)QA5&dQjvyDuknvkq#wy5_ zKo|Utx&E)AqDDev=6964B(m8hvK2{BeZ8Uf4wgIE=mDsrNFDmxw+&EmkIw$-XKS@s%eyyW|Lb-lPiUDbpXx|n? z@3z(7OT*;P$bGHktjEbcFOzen#Wjyn?%hcCOCuLcImee#jt?f+&nI_nBD>`2I&!r$HXi(;lL}Ti!+Q{)BQY zrodSL%`b?7+tD<<>g2k#ev!phK2vsRW{IKk5r4zgID3Ke1lF^tcq+I;c9W#jyI^!b4$c4 z+RB7fdFbqUld?5IPp+2;7P66YsKoHJRLXr7`EY9YBooV82>RH`S_izkv(a>zcb$)3`&cqu>NL0SLdlW5Q;2Z&JN zB)JzjF7M?e%au$|7wt1okn4_;{e(*nQ!bXFF5XW0f<#Qauy4Ms|LR9+(ETuZgK&Qw z?I+*6QinqDpa=d7Ma>aa|C3BS}tPzwPB*H>kcW{DWUgx zGW9({! zHte9h0ok?h)b&!1{gQk^LV1gHAbB;@gJgM@?4n#y0Y?3{kPasJNnogu-LFRiPwGbM z^L|GTNF}F9zAhPw6e&3SW$HWsK=%4AxuuL86irU7ll5Qa%LJEh5gJr=7r9iNsq=r7 zv!tS;O3Jxw$xg9vyp(dLjA*u`H%U3M642UuXjgl+x&Pn6gq~Z-^|C(OWX{56D!h`# zPIk?HIT@8pg}vr6TN)BPj`ntG@bM(dp?8yW=ga!fmE{o-PK9rvWRy6NCl&RHFZeH{ zzPO5<_fN7*;zR0U%5CCHF6mgj1iDgx>iygj7^-Alddggvx@b`S6*)!Zp7E5MCy>iA zU-;kVD@U@#&6GW5L{d5__g+bk?I-u$PIkwP<%=X4qP8l^_0pjBV9FOHPBh67c6c!T z_|xQ8Ie=tspqw2_PWqADR!H_aNzSV=*lmlI0_tUmx?i9{@craOS;t8Ulv`wVq)A-p zmc60BoO-`>a*Q-2RvMBgN44tfsP`YP8S~%K%!E>z-C?AcG$t4y;S%uAqVu4v#ucL%DOEQ@2-|N z9NQnHKIjc{jRdM{i5DFbFB;BKUn%yXh!e*7-(Tk1Zzl~Zipf6DlM|MbTZ|#Yh)KK% zka!WWm-@^n$aNAgDkNUyinFzzpuSQzrK*o*{U_H_QJYIn$tH*1BpGB56E2~gdo|fh z;zp)8XRvs8wG6rM*R)IgfZUKn*1xo>N8Dw;|KGld3AyI=xU@J;0!Yg?>ixtgD(6%7 zO(LfTl3V4(6feHgKa=V8W@ME(fxn1kG$7b5fg(W)s=kdG8YMu~Y^U7z9Jyx}IlG0N z{0TWx*1w;u{}S<)RGG4nX|%f_Q`#u;z?~~Y)+9a7lX#FK`*fwO|6rMdGHGbS6c*U< z5xHAFz!WYG_Yvm|ew_Mvc@R0CLAmE|2IKob3_6GB-iHqylep%C+PyIR*QCPq|b^ zs^=}r^|Dt~%g|Oxd}x+ECEz!-E5A?d^~j=rTZ$tuJk#qT?#OUM$cWud88906W z)whlFw+~YJCn&#Jj=O?( zA^e^L@Z;n!0M^wiw$J~GgIDYBBF25Z(2pj>XPC~zdIVv{VaZ_?e0REN$a0EC3oCeMTbKqO6 zfP7#hunjm11WrM3fM{SIun5=+>;QHH`&DbS<7)T5K-35v0c=6&9xwq21LgqpfyF>N zuoKt=oCQW;&5Z?S0MWoAU?s2v*bVFl&H(2DkE_seU_G!2*bbZkrcT9fG-oO*0Tu(R zfP7#Junjl`jKHED3q%7efptJ3uo>72oB_@Q)2CsSfjD3Rums2eb^!+g+tuhCFb9|q ztecKb36KM<2Q~pmfYU%&C|V9|1hxS?fdjx{ z;23ZUI15|^0ugU#0PBE4U6TpNp%nc9*%mFq6 z`tRdz19k$ZfQ!Hg#M!YxAP^0#0}28CH*=2y9uXKtAQFfJ)&u(Q<-Q2)0}e*m?#ItR zV_tv>z*Ha%*a&O^wgJb0i@?}OR0PZbHUs;Cqrgev3^3h^9sx^$3}8EOTD8n}ELV|p z9HaegF{lSv45S13z($oa$8oLKj2kdBz&cet$1%mdU^bcxya;Ru_5sEpI-P?O0Q`km z+Z;U!yhk!G{^cyiOKpe0D*beLh_T6Z^(RL0m zY&W4YU@8y>%m=mrhk;|jDc~#+9fwMQMZi*ErOJ+VjCY^J%QL`vATl2H0PBHGz;<9C za1fYqGpYbq0r|j2U<8qJZ?pt1tNh3z!G3Pun#y5oC9q0Q8f?-%mL;D>A)%=AJ{e@VQD8`>;Vn~ z$AGiIMPNiC1_M|GtOV8pg}`Ru5O5SY35>oC4FMv7IA95|33w6M4jcqd0H=X-fbDiP z2v`iH-|j|h@FE}B2y6p(0(*c1z%k$~5V!!I2CM|u0s7BEZ3eaiJAnPb8Q?tNk%UG8 zalis#36KM<2PP~;H1=!}sKZk*1z$xG?a1j`B2Py^D0foS3U@LGGI0>8wJQkrM zU@{N~EC4cq9AFc05I6#y045}3_JKLTd|(T(4RG(oKYM@!z+vDb5O^ng3(Nx+0ZV~G zU7lG}-Y2X}S zy9e_>^&ZR#Fb7x+qyzcDMqmrD4LA#21V$`@Qv%VzJYXrX4$yygel!M{0jvbp0foS3U^j3GICDSd|2$rdegLfk)&rY> zeZWEB2yg;84V(kK)6pOx49EvI0y}{Nz+vDRa0(df!YBaqfJMMkU>#5hYzDRhJAmCT zH(G)hM}f#?m?vNXums2ea)9-~E?^&U1ULbl18mFD7+@+82FwA{fmJ|0um?B*90N`P zBQnr1AR3qlECqJB@y~8xKX3>*3Y-Ma0OtXZOpFdN8JG@40&&0sUA)%=AJ_vN0NjW1&oST>5cnYG3y22R0s2p)Yz7XlM9+b9Kv)+1 z09Xv91FL|1U?Z>v*aqwb_5jC#Q@~l^A~5zLlnu-SmI9j}!u)T=i`~F};1F;UI0Kvq zJbr`T0t;m=y2Z1BN3E(tv4hUO?DFM=fRX{$l4cH0n0S*JlR$=}} zWTRz3AP@~K1y%x^fvvy};1F;WI0KvqJRZih01JRkz>C0kU>C3tI02jnY^yN^z#L#c zkPmDDwgG#918)3t7&rx-1ug<3a?l`P1`rL*1J(ihPkL)od6@qLcyS6i3tR+7Jc6kJqJeq9 zBA^i14D1IE0Y`z8zc0iC zcj^L%&oFzmidg8FZI4k8FLcbbyVUENmZ`56I@?Y=-ULd+u;_I)+6@s2lEcgeY~N!$;-dl|5X&d>{G| zp+39MFbi7Lq*|8lxC0G%H{EgLFjs{7DIFz6scT#)ewKQ~1)FH~rVEKN>U%A@ z)VO7!W$LzNMnj%hh7M$?cXeW>`e7N`vqDW9Kuf1K*!4CIeeuVz3uOMQ`H^!)NnB*v(lGmV}x z9Z|!Ug{e_%kQ%OTTLYU2^@OIG>V2IUss5wMsUp^*iYT>gEu>j{UtR0C_Yz9Q=bORm2g(8ZFjA6tywp)YM5rM8fPR{rD?kuD@@z2Mo>0aBh$nd ztI@1>pJDr8=DG(GR=IN4WAQP363DaSQhN;7JTZ{HP#<-1_GBL}-2iveon{ee0 z6vs3v4tu@X2Ho`-n{LCJ%(YpM>3JW>L!FT)(&ZY=vjFXm!JintFW=$sj*-x$e@)yR zggu7A&@jU^DGUQ<_Gbbb%LXjY%*V!I4jR+N9wTGg7aI0!(O|=VaKNaL43+_ly95;& zu{6MVX|@-GaD{}$orXzbfn$ol*_~x!gH=wzK*Xq`0>}7~18OY(LdP|+&RK)K&Oxu^ z{?D*8&1jU<89i9!4D=#S1!dya(s(Ie=ZqONdC@Sb`_wVUX}mN|FcIchT+}AUoH)Nq$5)9HM4?jtiVxfbu`bKBmj zlgzHcTTIi9qr@~&9ge)jG0wC%(oOpq_3{QIl76}YVQ!fk{P2=P|t!Znd&fjrJ)`>9m8#om60l)ng!1?t&a^@tL!HnmkpK(*D~WnAsjhgl|O-r zHoG(nu4OL6sqkG4+Y?wN18U3eqW_#-yy}0#G9a@oUbGZ`8?VBjbWE|wtK^MXv-%JC z#jC6*tr?7-@Nl@@P**-_tq#s&Hg=Ae(HfNJ9%zjvtentlBW7f*eiV-==J+t3YhV_9 z!kn*stQ*>|$Xb*AsA~--%gjTaa!hl-U(UwRv1B)qMxr!Z=oaXrGJ9V?ahqc-m zpOsmwa#pz>w)EG~sk)~yN2@N=rL>@wfeuDnT*7;_R`(BS16;yv;!Z;y`jn*y(H57O z=c{w4J>{5^G|)r@7PE<`wc2Q+(Y~zZs~;Yi66!c5(Qq0w&!)?b_C958uVp`)KE`P8 zkOskN%-jbJb?DR9-0%^zI~ikjZr9V+?!X;PkF@z|b=lL7DTxE!fisx7w`;Z0owchU z#!pI^-oJ$oLpNC)WATps@j7>!RUHHGFdH*^f>xIfQNugT zEe*i}e?LC?4#yb(+ZaruoR+TOf&}WSSMb~xc7?Zx{WfKP2F`NCNN&@~=}4Y5kQL1~ zhj@*<8#Kt&KfP@@#Z;LMynq*;aTf< zAeXvd(=zq)?_jxHeWs-hHF682Om*WH$4#nX3mUs=iz7@w(!Re1dbCnggo-G`b6rIl z^f_gCnu|~`BLNRNpOv9LG~#*3%+Z$Up?x$~B|h(%GBQ?136Du@o_E|d8bQSB$v4xJ zZ>E(q22*aTkD`#9RgfEx83Ss}u&IuQAKq+u(cJ^yz%;Jc7)-8dyUnoG-ZN;+G_gh7 zO;5AIJ8!lvT)igSwJM9pM&*9N;pIQj2z0?T-lmOJ)eBhZ18Pgi^MF&`tlD01OiCC~ zBjlOQI;+*TxvO(CGzqMQcs2!G`QN)UF}wWrOM*Po2ALhZE}tV#-bR7OgfKl$ec6uMD(j zVDhMw23h>zqETe(R%?Uc2WF8gF)DLa=@7ML>pN+n0&p6Ox_=P(~ZM#DK+{>|#X3P;f3m}U$bZPG?+_e76LYIlXhJ7J)q z7#`EzZE&Nx|L5tHX;SHm!66C68F8+%zic={5Voz^n{*1-yK7ZmCN|8$u2RQR^fiPz zuxE`t531K*#*S9_GIlhxUCR(?Osge0U(QvPsB2Jd@umZYx((_(269`xX*v#)mUf}s z!FEw6?XtMo79-DtYV|8<*P>S(9`N?$ZP;SYYlX^w#o843kr{5%aqOI{H}~;_Ewvn> z4jF1}@)otlk2c~|iZR{BF|EXyp4BPFn9grxQnTd#MyPOYJ+-kOyMb}db?Je?V7uK)#^2C2i6#M(k_d~ z=<}{_*Xl|=rj?d6hNuyL%-rc?bm4VSPZ}uP5^9cU zHHKlzYYxAcUbBvZCE!Gl)nx>{W*r5Kqii?S$xsi>&T<4Ca}2%xbQQ+=E$iXC^OsXA{-7!>h(+UcO3-%eP@+0>Fb){%RH%`m zOlJriuQQZcGh|@?%?#TObqh1tUq=Rg+{UV?veb})MQmm$G}JLe)Rw6}Yp8RFs4Y{S z?yn248KSmK^$|neIYe!l>bQwIxBu(breUhhz`WZ~C%=xnA=48wFv+HR`Xpl{hNv;g z*O@mhhPv%_$Mu7`G0CQS@?^<9R)zlF;wSn&Y13w_VdMI}wFu0nsU90JP{g8e4{z1- zdt7b|wA8YBY%vUbe{bywCfV%Bh%0nC;XABqEPPX4XsC0oYP~y{>hp%WZipHy-c;vI z(S`R8QDgc|^=U&LUTvv66Vq>YF+EV{&aJkLKqjW&RG%=^sC%qxt+oteCVarOSrVj+ zu)kp~0zP1>j~Z&Dh|y6P#H=?Qm%-PY{-77fl{#zL8`j2I9N>_lZX2S816(5x5Oau9?6RilGl zjU@=LfOD8u`ctV0b~OxkZ(+FfM^Z6zZ(7#-3QIUx6r$CsQ0ri)GaN8d%7$cs1DLT( ze@u0*Y8j%21DNXVhT8s?wK_O}srJ5B=Z+bo#*~}td_$c(M2*F7s!tp0njvb;x_RfR zKm0mZb-slQR5K#1z+9W^!-hIwmsO3qHq~*V#z;Vok*KP5jJb4=PSI}&?Q#SJP%t*3 zs4&d0*{12&>1=Jg20I)TW(oCM4YgOTRgGCSD;;sY&K+NCR9f~nhCkm(**@1}EGBN? zfMTS|Gf)^7x|#p9VLf`D$9Q$5*5Pe>PE;7C*tA&+XVu;KQ!TndLArssZyFuZMk@U6 z!NG|N!>pU?dFU~YI78H!byL01P@hadGY-7%@WuezcVhr&U?6nOZ@rD0DM-zjb2IOD zZKQ(UvDS<^H`QY?T60y}5H;r93=*3R_3m3eCRm5dNHvEGE?`>g4+76s$KM$YZc+Lp zL}pz%SV`C$cjJu$aiFMhjEkv0rPb)pq}}Ka1$HOgvflOQhq01&TdD}REcL^Nx^0LW zjWUBt9Oe!2vu-dRMd|PJn(F1P&XMm9KITS+WA&Tr&01|7@)l-hX7Jg-yrZB_ z#?ulK&KpJg|Ir9g$$PLuGH%e7BqPOK=27AB2y;OmG1Mi@(4;fO&DI&3hGf93n;CW+ z>I=*eUXKicb99FAJ(e0GEK6R0V0*60f?7ukoxv8XQ>un!z^s}zU?R;7i*D5AB|?oFigbnpMoQ6;445`EgZ_y3T-Cq~y*k5oBc*pp1`MT{VRW3% z5b~Z;gKIA`6dEZmqznvegk>Ji8tRH6YD;KNkJsh34N+Ss#ZY_gwHA(bX|^WrW}Q18 zYTaL4hI;NcQVOgYW@0It83O0(40S`)m?3keZZXu|do2rjCKjQow#`FsEaV^eVj)wY zKA#8Na{a4bQqD~6~sgXUB9{9Cjd_qqd*%~3P46iv1M5Hx~hgH?^` zG}W67b@&i9R-UOoYp7jA)Rmrjg9aBabFD16lT&||Qk1OL$b@%(Y(_NvSe;>EY%kkl*_i=}dn_f*3>bgJS zT6*T*HGgtkXCD?Fsb1f2+!KGRX}Ox%h!SS1+cZV0#~P6ZA8=~K<*@$;xEwy)XnfRX z;s>}Kj#djlfK`lo`~%!+yVRRHafSN!1AKI5nY!XbWL>WA{t&ul>WL3wxm>;bp;6aA zKSUEURm1_~15axX;Nw%#Vd~ujj$2hs6Ke5jayV6iel-uT(45DbU>T|2Z$dt&`lSi) zGe@agK0=xJoYhCDC|bS!5o*WhtaPGFUH&mDTDEuL$Bx%M>^JfX`bIg{Mp|5VzTIZK zQ3V{r8<_)YxUM<3`?OlF0$mRde!_t1#>_bN7h+8Nz+u{6KR735TkV-H_Hb*{UVmbS z`PV8VQf=N zeeo$t@khM@nuQ)!p{+Pp9aYJ#j`726W7I>fjw=FeV+O1v^fjw#?J*wdD*c&D#;cRh zIz~)1WR@C{fz86)Lr;uXueUm`3pkP5qJyx|}U}o>!^SpE*VhTQWi2|CwW) z=P@IF^dp{=RqVYEhy9qU`V7rlM>cSe*Q%D zi`LJ_WBWjJFga$o4o*}zf9|+)qW)6gfZj4Y(Ua8UpF74)jK+iefF6TrI>UDA1GZcB zh(uG}>jD=+C%JG+vq}h)8BDcLboOl$kcm&bpoRQ!33Y~BMr1A@jL(HvsP~RIuJA83@`@fil3C|j z)pNvg)ouE#jsqQsKbRfghG+E2w#0{X^48tFI$x)=I;Kl;@C)-~IXOt(+vb=yadOaL zdHN~QtnS4i^>P~~;zg?-%ihet`%3kd&ac1wXtqZ`BAWRRU!}%a9k6xU+ZOR^z)(V zVEQYOlhvvxJ*TJ~QS+TtjIc*LD-%gf2Y4BqO> zdU&nn;f6Yn=?dgA>prFPsL92s`{XycC@^HRZg`kESLrzVPc}X~7+}0KtGAdSz~GCp z`cr3W(NTv-!W`N-BVc2`l@N!>JLmtrmB2KkY0e0Etm%^3h7BNl|cAv#3G@$T{i)it-;Q3Vv!1?1|x89omlVVn7W)HFJ-^yAh}{Q$OAqxy%T#YN)UF|F%YJmuP}lthheEz=`YT@U!MhA|RP$HZ zbq1=0+nS?x9&Z((MMKmUZ(VtrRy+S{&24eksiU)mp!%@t_4;$*LA-UljraB)R z(j0Ysh#J0OuH?YWwc7U>o_7aYZgGc$hC1n(W75b0b;jN`#~e4>?X!8Rm`&%6%z&Gi zgSZ|JIa_rcN0SHC7B|uFKh9RZUt87i2s1k9O?tLE`zxYD`qvKcfg-Fs+W}8)6W{E( zR_*>88@X9cro|C5;3>0J>(_9E0ktKF?SY@nR{dY2>jP>yg1O$;W2R@TMI(k!P{+S@ zT&B{$u~uUVX4CPWlwmkYP5#a?LTw*ni0#kZjnm;JvsL3ac$^-n5ME-cPa5hGBZmhX zo3aW!VXYAUVjAlAr)I096V`IzFQ)p0p)MbyhQFBoS_*HQt%5on{^~y`9G4F^1x{ny z=y#e7n`;NvaGD6YSKVl+cXFPf(RZihzfhYjCGw z)BK%dO2R-5@C!3OZyJvxYtyJ zWUFCvVC?YmYW+#e^3j`_xj?=Bbum>ZEh}&Ze8lY3Izzq955v`S(mF2i5z{6Rhq&3w zuM>yfflk3kO!Z+yoiaoX*DxEIk0ab{wS7DqxvSIKNce|Y#2Le;ZAcMt4O5+tqa5b( zduszMQRJwhPPV9>`X>O)-1Bj|o2|-*s1ZBN_U$*+ZQtX}j)iavz7mGB*=*(WH^)^0 z(qCs7{J_kxL#u7`@0zK6|K^zFX^5&yXPkh;+iVp#30+P98&-=UbKacR+tba4T@xxW z2h?f3IE@a}#iUP0F&9su7(+ITu}uFd!!G8OwHVC2>CRh%bTRt^hV$qjV8~`MZ~?PF z`X@1F;{$fX@y5=nK^Jg_SzI9Bu-SeE+{CBLY6CwoeP91<#%$&6!sa$GZ14kf8g^c# z)kmfbpJY6ts4ZQCLC+axafZOD+OW23aJHRc7H8OMs1F31<&6HpT8_mnMhEM1LVvK7 zqiwCs^v@8PC!u3Tp80o0KClR9(!sC6FkS2|XOV3bfCnIF_l74$-;0q1NHE8=k$xNC`S^Ee|eaj=^ZW z`!ZXlo*oP`PV4>adP7}0L=DF=bDuWUO;9Hf3@{wWR4=~P=sX51DSpZSc?zRW`VSv6 zdvL(Wv*?~A)%Go(5h;ope91J+z*{r3m8;v@EqIW*B^@=?7pD)uiVp&YEGsAiu4L|# zi}8ldY}MKAm^tA2`rg)Dh(`@|=syPc6=#HH+gX6OYG$k4A!_)F*$Dj;C^#csgGPic z#-ZcnKP>(p0VgpH=U=Z4bFPJ9;E#iW))@i6h?4#MkYRK7+Tqu#oFO)F4%0bzqjE$- z{bd^CrP*Oih&3Bzo^pKRRx{bg$>I5&yfSY?0^Q$bUQBj!R~Sg{k*` z!8KL5`so+kT}7yAzv7l_rdshUq)7Ghueix_s!z2PrGC-Utn%w{0~1|-uQ$F@SpK{> zzF=4WiMRgD=P)~j3hI+`3#7y;umR6{*?cUQ~8ty$-f4gzqaAd`|8;8RnLOnCw zTUYq0PK;E;E=3|fXnH9mmwMz<-16XCm6xK7S?X(@7_BZJ0g6$#jez9}^^~Se^^s0= zsh>41QxRUsw_Gjrf-Xb7>V?Ei^_3SY!Z!>@df%YG+IZ(ki1>EXNZ8KAUW0ZnxfPfnr5lXyP)kG!En*L{$sBcGm-;PdS;|r5zYK^Al>V04I9p5PQH9CFe z<)9Vn-pjoshDC;{=PpN~;p&UaVH2T-jWHT<;~3aPsz)?A)!SpdZ&D#+(dzSKyu;D& zYsMONt{96J;JY_tVdYX^=)`4elpmz!>J~pp8R`i?v>;P`>gRn2>YO;v`?g`uFtuVF zS{bh1)fAzA83&u0>Xz}wKtD4cl2d)5DN0S8;C;KQoPerxCU}RUpRZ0p@iFQvO)fRc zAGA!};*W+bSC9FlybSe;KPt;q<0cw)u9%4Xz^E|w(nO=q?EFW*%HbLBtSMKfizkO z5EBw02@n!GO7Be|jT#b4DAKYDidZm_G6;&GsHmWz_=BBdK~V$?U_-EhT#TT2FPE$E zzu(N9b9Ps<^E|urp83jrGxJS3bDGXrFR_Oz?hCV~4Vf;6tBx7yjpp+4s^Is35KyKm zUY{vrp98viRa2v(OTzHsMnisen2`{MHG*luRGhZ=A+AW?Ww=qBe=yvr>nhSH@cD}KG1nw7l;l+y`~_5ocJi6He-tcHalRT*Ow-1}sKEYwKpbkp zEJCM%`h|IZWDK;XbUbRQKi}y`_8nv0L>5n^Uy3uFb*vl;_Fj)O4&rJ>>fVD1Mm0d% z-j|vgr(Ie{F6VnA(qg zlx_f?OGS`djxt?(RtFT#tlBMtzkgYN(X`SjVw2LAku)Xav*38cMR^S1o05&Dwv9eB zO5+f+@p!V)Z2hXbja>9ny?#8j4JzL<8S4$RM166--;Z}~W5m_5$oYJ78{=sWGrswp zf1Lqls~7G~X=_{$*Rt)cxQc8^%qYMz*X&?}QIXjJTX8Z?6e**iz;0oB0ymqLmra>c zQrvU+P^;Qxy5h$&#Nr`FP_T}n zd)9(temobw%50`0xRN;l&?cxXn=sR|Q>H6*a3?eC#@M6EW<5&Ec*EomwfpB~o* z{+D?Z=a%V;A3e@&QhG>R@xxH%+%i!yqqmvNxo}vUSvt2&Q@lRo^)}+=Lk1Xee9OYR zjfPHzH_Oudd$UYe@;)7j9%aq6JydwJOjEpAZVeEZSoMKeZgt|>1F_u7#OqwJWX$55 zDaz+Z2ZE)5U!$W!o;(OFc$W!9#r$E4CiC|OVX0M|%KtqGtZ6)PFrq>}kRq&*2Sc!! zKQ~ygo*oR=BD~>Z2oBSD_aPv*=W`H+p$W`dqQ2ErtZw-JCWgU}4KZ3{*?MgV%*3lN zhC&Fhz8Grc=vnFfiJ@4LcH*apVojaNV~0U;79TncJo)^tVMb^E-}`W7|L`!QdARQ* zT$D#&kw-;eHAQ8hkC-OVqO5N~N0n)!@;dsyOyi@Q@X9pB>oaVmqEiRxc>56}{JqXZ(q%Z4JT;4Z-?$jP- zyx|BVoHt1}YK3?3S>ZAC@4me22qUJBSxX(#_7;pV>g%ZUIit`Zc<0P0RCX5sY7|-^ zpGS{I3l#8yqmfw1myH(Z3$M}9WPV|^(T4XMgH?L`7&K`Ie(M-8cjU_`!Zm)1@R;Ek zoFioMl(C`>CyW*69~hO2-+=bhfo|9C*_BiE%j9XwRd^gEgHG zrKlsnkD^Ze;CSPf3Upg@>xo{tn~rxliK~*`rf05%;Nk$s=Sl(lH9uF^A2@jrjHPM(mKrjmQYafUa+j(1%63R6Zbo*4VPL znU+D4rerX+m^&QwL_|8@RZyo%3o&HM!9}Dh|EBeZX@07Qzi_*e7)=}MmIWxDY2h{x zzi_(|J7SwJ-Dk3)=N{5A%ugvUEv75;gUd?pnBw!$wxla7(XY&sZEH+c(oF-=0-A-# z{A058jpC~(7}3#vqkK$57cyIJd^A5e!Dtyh9(&%F={`j}7R~jEC>p&8*`lMTm__dy z!*ht<6C2(Z9X-P=dRP;_Xd+G;!+7{4BU1M^;V(@zT1I)X!)>x>poUHMtNijrTpzgV zOU4vrT00e6+v$AE^g1zO|0-G>t5VZ>rO9`uDW5*cXxa1(@tbt`t7-LU?0Bd1${BSc z6V2t8NHSUBUM8zEj{iK#NYoLp&Nn=+a%^>{^BpC18uPCCM%||3*p&0}AbK_-oyX6t z6UTQ&8MXBDalBpuD*fi`Dee!rWPHV;&2JG1aBnppYu^sZ}`&D^d|i;-lD*0 zHSn)QA90^%FK9jvR7`JKhvjs-OXqhBU?f^e9i?qKLPbor?_6re3 zhaZ^q)FeKc=&4CQMxgOc`j#ZTpbPXZzH|&Nrjct~^AklzV$-$QO*UJRUio9vYhfce zo#!s7(@1Q|M~h?C+Vr{~lW$=%A6Sg4qgPd1dVB_mi^=@HV%Txfmkw_*afQ37fU3mw76Q}a!)WUC^%ZsKjpCMPibRtc4DHn>?*r}m z8+{2`wr*s~FH;omzS1no`o8<$o zqblE?OuVAa=oq~RE@A2MnLoB?@$6}s;kLsiEIP0`$d_kR`mn+|(`J>+*O1w^OPaDB zE@LkL4|gWp=sjWe1e9iV%rCCWt6o3dFrv3JcHgtCZ2ogh6YsAtS&erbqOsa0@|M$$ zF8JKWHU|z7F6#1Q2bpcp^6!=#(Y$K9krr_ui&yk6nxyw_bC%aH!OmRubR*NVfvv!t zLV?~64;9RNJu94tl^7mAbcWF-_GxxWknvJT#L$74r=P{dAOjEY>1f3F&oHt*Yglfm zO#B=-K9HvUO4G=QJMkR^86HJMN>0H_Sdqk^EHS!y*0b>>fN&l$!C8Ni73DCq{!Am? zGl3n0r%_l74=0AozonURe8Ehkv!{U3`_3rr!jE9?@9Cl(as1p&qff*Nw!t7WG+>w@ z4Yi~Rk$h|^Dq&~e1p&4d@;X#%P zSE0}tu1y;DZ#&n7Z<%G}L~LRU;l>pDgGNSddHkGg<2tip*%NG113_jVArmV4E~|~F z&xZ0cmWnb{_}n!8GRoe61&PMf*V^>w>WTI__{ZAqH_&LVFh_!4j7C;ml!!1ZV zd+Hp2Xugrax6Ls+dLCl*0ul;coRWU&4=BGh$GFwAn9-gzg)>k}dgH0p2G51wWh_kP z`FSl#J7s$AhjWe8h)FULGC)H1JldmvxiQFdH=~n63iQPcQhP=@gNLUqG3xNO zCwd)ze4df#DP>L+o5D9xL0WPxEq&&rZdZ$!o)W{7C6b|%7%Jx*V?7mYo2nm@q#RPw zFzXi>rJgP90h~Nj2t!$kYm3lZZon%R80|fCSQvbb!gd%S45dDGeu0tW@v<|j!T(Zv z_gfV-bRk@3IlHR-afL@&EjlC(3oj8vIUA4F8--fUB*T7-p}`$Ss%Hvo1OkQJc*($2 zxjnoT3=vPUazVzsT@jOgqpkM6!{`|?m!UdDsKh_flTy^kmA%O5=^4)!qH!toM@$uv zYjv6D78zYUORYj0=zPR5i!3;^9D_>3#YQL3HdYcw@~9z_HzLUcL-0O2ql4#3 zwnQ~ihO%(5s6@2k`lV>XiR?;Okq5ilQyFL#al%rx!gQ++`+|?G7)%{kjNWf8HTp)} z#eSqzgj~b~D@`8YD9a7(^(8Rn28t0hXnMoOllrO?A$ z@~8^KQ>T#iPV3pL2W~du$4iY?jTTB}R=><8o8ZqaB>QBR*&{D2JuM@hYqP*URaI1& z>83P1h_R=k7p-(V%cZ74phpcTcV<>X{h4?48IU)arKa`hl+isejcYTE7M@4hH>&ra zSA*>&(m2VBfw+WuRd3t_rKBw0^2)EgsL_pVi4wk73Gb(o8p4fvmphG)5%;rGYOqb3 zA}ebb)o8g9#kYX&S;ek4A{(*Y6RvWg+(nbX`hCG&Mqkf8Y>zVW zQHRXn7&*oMyD%os5VJgqn{}}dvdxxbew)b*)nof&*rbwW!r>~G8@G98vF&Pv{svV| zq)SvLbcB(fg=~i!Mrej2+7?y)BRxylwjoGBNK$i-muUM|7`-DNXHzA~>b?6goi@DN zDD+gaOKNa=0QyK}rE>!Pask5ibqEAwEuNq*K zmL>O~hiqj1=A zSpzl69Y#rU{F~KFr7C2UuBr=Yq{T&PqxpbUMpQ*Sdmk>XCVDWd^^y>r!@dNqp%T;Z zA~!Q=@IqQS+H(H1>wa>5Ofl$R!0>r2TQ1xhiln8@9Q>_SM&ogXtRvV|m%t#4lM)rk z_FF-FSGAxnzOo~U8jBCF4`*$qcy*?ja7=O?LHm#&@HiVLX!KzoxO``*q5y-@@nq1T zvNM0|J|im5$p*rRWs0Cfzs-b~s`JbD8POxdFMvnQYfwZFM$15X){5|@HBYr^@!>7~ zX#TeLB8z1^%sn1GF}>NKTd<nr{={c^gHlpHF(_Kw`75H1)tO>7ozY*=u1J9vIKJY%n zljY37SM`(u%Du&rhVBp!T6aZr2DtMu{@`jOrs7$!=wvv88j=M@Quy;7FszFsdXc?< zIX?rW>uyT z9NRim2G1Lg&Ms*c0U6Fsd1NF$X`vh-(3rZT@m4&G=9^*uoRMP~o1t>?&#;6Y0Bx~F zD>rSy>`*Z?rOQ}YV-bBV#n~cg*cBEbgpHb}pqN%FK%|4UH&5NGhXu#LGa{HU~ru4kCoGDLz%o*n^-=qXvvFuD2mQHX^@MVK{sX%t$584Q+&&kf<;FKbUFo#cj;iDT9G4Ps;T+W z5o@thKS#{xf3L%HOK$cqm|_)EZHx!DvOSZ20Bum3Ofma29U&ukdp=}6#+YM#=6WNl zc}d!iOW52|!nFhH)q5F+=sb44;n8;R1CUENaRn;@i{0G8Al0>X`YiNxes;YP=~@X` zDPTh6zv&ABGSm*J&B37IO*ZR|h*4#wYj9wWa&_3u9!dtPoz9JZv^|q-8a@gS8kTt? zU`cPaB~|NAzLjGM>}0R{DaiL}H%It>(4s5_PK9J!e(5Kt>J%JM9)8A;=G#tgb`G=^ zrp`vF98;@?_b|-(4_))$y1|HWB!|Dq@7!QS=eXnk%h>y-1S=`C1)R>GL7QyR{EOfJ z8e_Zp0giVH{|#tP&p4^^tBG59=p#l<)@L{Hfgh#GtTZ~Lg#*X`OpBJ|Gss3RXfjluIaqME{s!!$NXs$}&7hMGN~(fKchdVb3j?8JrR?1txWG(3skuJ|PU zQppBB=2cLb{~Bl~1>ab2RYPD)pFiK!2#w9QX{HL&;r$X{be`;xNrC#i;p59wNPnd3 zX}}iBq$9v_N(oNay{10O;R0x}JmFC?y;h87b&^27`k>WPe38IrRRr=)YyusMZ!&OX z4f!th;ad@eZ<7z-6G8Z1_2Jtegzuye-{~NHe_DL8-oJwIHRNfVv6N)qXpHJL6*kRe z$_&CZ$YdHBglVS9R33!sev|3pAWYAiOuK?Gy>Bud4Z`%3$#gLYlY`&+xDg%etrJ^w zH6j{>cp z5Kb%xRC{x*K5LHiE*WV5V<~7=8bA7k;ptir=TF1cFob??1={>5Nc5|JA3K|;E(7hP zv~xr=jU5y)A+ou~4%pg!BueI;YN26aC`$G(8(s(0WaIW=O zqCsoJ&pw7a>IK+LicbYxNuyFkNPfX@IH-{6rL8o4t#{|6IMF%5XFq8~hp?O^jqTQW z4o1X;-&$+d>1us?$B_zDipXRQi|EVL7+%03yo!t)G5k0V%!?59*|b7mnV$wwfnY|Y z>u10enR6pPWE)Pg*e0CeHsBgeckcw8>EK5<;jWSBp&ENYn)@_hD_M+bMIVa;QD;{G zuZi@E6aA`(Y1Wb@%+Kg9>>6ll&SYUM*{2O~&W@)31>QsfS15cY_yOJjH3~G4?Jafa@^}CXl$5e(X=8Zk7;mN@%em>9k&$H&DJuIk*^kL>=CJug%2&%=o?Sl zQRnvq9+YrEk;bkF=*}zF*an>sd>VEAZB!}3n0S4;IKp&4 z?Jv-twrIX*8*^toF;`>vF`n{_;c>Su$JT0yEX#()8e1&v>4vkeB^sM#HK4Bo#^x^7 z*yEOR|J8njWg6QrlsK6CQ@(pUIqLojv%xx-E%*@!=D8EhR(i-aPV@`)!pSYoJ$-05 zZs4iBXR+vef_Ht^h#J@THt(GpOR#u*Of{J`oY-#lqn+qy(-=GGN9$sekiVP#09q?y zJ+@ft+~u3WfbJ$Ic~cudn!h*o=h|~{gbVLoTZv(l?|jaPOlWYg#$HorKjC&)L8jQ% ztr9&OY-6qgs!B(d55p;%3>sV5>BrYV1vm*27210(O)S*kMF<(^$Vv8hh0xX$>tFQMX=wD+*!L zye662u-VfZo8oie2neUI4;D2}(!n|3GguQYs? z7qqWbnL)Dx$@P0%vo_TN<%)RTi{eCJA(+gw-$14neD{mA3a$*o^C%OB| zdsBft-9ZcCyLVx->jyZE=RGergqioH4>UGkX~xNs*R+u8H|ayox}uJ?p08<`YT5?R-Y6g1jw;>KC;eq`QqJ1xb_2oa5tI%Ul7cJ3EMGVA&o!Mll-y9 z7IEz*>T}zGF=UDm$oD+|Tj=U@RAZ}a;Q0cy4MJC1Z8NTt~-utco`JsndrR; zTwQ~{ua48s0{9|bF`rT`pA{mBz@}4RCG1twqByx0U#z!J5WZrb_A;F{c$b3-I|(8L zDyssmmdf;zAbijG@Vy9ZZZ`z#I|^D1>5J$V!+ybm>9*0%*FZro0DdI|)9twycG(Tm?SB zWd>Shr~74SPWDu`p{z4#XcG~l*+5eav~g?%Xz1FC=3DM&YzAoN>9&7UWwDVfK{WT2 zqgkbo(p2^`Xm%-j`Ot8Q2{f~_MO(Y1vi)EGoDY22h<1HIJi-CTdXE94u0;rREXNlb zTV>I*6(U`|*#n^6V$nwV&=`9iw2i`-Tq91PUyH0pdVc`6eZaqiT?VaXsMKQCB^{xd z-pC()i{vkdQFkw<_ys@Fv|qK4y8b%gPgT9*YK>Pal{GL$*YTlm$+sDJnySV?z7VI* z<`G{6o|IgIg9x=8h_Sq%6gFX1Zk=^@$}D26eNLh!vXAQMto){O!*PeL4$m>=%%va6 zC9{V?TW%WGma0GnLJ{?K>&!6F>Y@C>eb{pKP6f{?H3$Uq zjc?p%geH2ck!W`AKqKmQ0!=k#5@D59AYU)gnkc?};1Y}Px>rGA)W@KOsltB?jHSN_ zF+LNbhD#~cpy6Ct(U6-8G#3ue(ydDZG1eGL1#H41vvq68it+217}-HnXFjNGRrn;o zM1Ma{18t5f)RTlQgZ%j-x}e5Yp*+AjHSi7Zs^&F`jL zqfLx89#DZJ*;0SnTpy)P*a|-)W^xtC749dRD%``sc1!pd?n%%V5+COAT%A2D;X8n$ z$dRsh0b_AbJ~n@T0L<6;<~IzF-m^Pj_6CN*itajd3$p8Oz-AI|2gIf+g!B)(^J*~a z=eqMcZ$hB&be)~$Lk=Lr)+IVV3x51fz^Suz_B_7~0awG>I%_FYv*zh6O7ae!ud_9R zLH}t!KT4V^7wb4X5i%D5|CaFF5}l2cu=`S-?U1k<@DZtLWrfZ{`Rw;`-4y7kOf0xl z$DV}H^)29X2`Am9v$rKf+zOo?m#LQk*GjnJZggS^uLGVF(EZarIvZS@pGFy-xTE_C zS(uY+DPPK>>yLo_Rb!b85;`R3NnNM2?`xnnSdRvf+06x%+FV}144KECjXL{IFz9PG z@zVXMrAN2wY_BZCuqSoAoKh6>A;19=eq*OL-lpS@C&4fgQ1Na8Y$cT*+{OnUfYOUk z>1>u{9RIYAlVBmU+J^gW_&cB`8U6rNEjHj8YULq^(cp8R)mfTk*ap~H!tZPt{hW?l z($Ws1#ekN}!c5zNi9xb{3piEk>h+?IFK)^r0%k~f2ryj2&jDj3{LM~fyR6h0z|SN@ zHDH#6t#(_5NCJ$OHgtbUXOkqu6M*X_%zW8&Ro4-~*JSG5d+0UQ!m zfQb@1U$GiD9I%~C%>hi1a3Y|pvPwWzy;XpxB*V1-)7b=Rtg0CW_&>=o^g|unn}T;g;6iCt z=0{df@9;6zvlu=OW5a5k^nhlcTWzu&P_~I4^#vbz7>?WWq~&(~aTBQW@OuFxL{|D^ zU-GxWs2~55e}&lH`)hPy2S0rnRd)U~26%pee74VbI_{Gaa2%i};dsFQ5^e{?9T4Ev z-}{bl{s4LZ`~xOVNgetliHCm(O_KpL1=KhH$m@Lw#@;_+CKE~SL4aW{p7J5GpLhYQ z0?GN{1-^_pul)=2A-_y|^ozm|0CmSjUJa_=K*b3vPL;8%8(2exl-~OypKt`MMHl%Z z#I8H4iIjf?3cWU5X~WevTxY{aZTO@OpR?g^8}0+#DYDRuf8#HFgi5~lht6CYUv>ng zym5t!L>A~Fe@f$8{K;cKhH*o%r-B9Q$C!%B0JqoSIUhqJvVj9bAtme08}QY{*#b$q zeD+Zkqqw1iZIiGzu1RGGsCV`7>%_>S9OzRd>q-EOm5kk@9ay=NxV|TbmmUS<7kF%E zuB7&jb-=ZS@2@XtVA~ma-1CxzV`YGTmGIeDO2L^AEdLD3Za0`q` zU1GzPfDJ{ezOf~L>k}BzGs(el{qz_t{RA*yz}VE*4(m#ay{jo_lJeF(02qnD$n@E@sXb7m!Oy;ja#+}&4!PYtX=})kCzxNgg>*^L*ztVx%I}Un-Ob6>7 zBGO!=yE#~r)Z_)!B)k)_o`eqpc9ZZZ;B*Nya~a|ArgKHsCdKk9N1123}XT7 z^8=rt@YA|mVt)aq%hX$XI@r(r_@`iqz=LVALQGHZ%a48v@1A%Yzkt})yFb-L-e+*2 z?E@U_F`ZX`inUCy!93?Pkh6!9pZ z4q!E|OMV7VoHW+K4ol9YaXj{OWW9PE&qnOJHV)S*coj*o38*^<&-ol#_s-|5L3Sq< zp}ui(4{5G9izz>1b$vaBU{}iezf<^iQgo`s!N&8mUx1oXO4T--U}r#VMFZ+HOL^%R zU|fWx6q&SLCB1^AB$@PWDL+kI17N*FiWfh7*5>Mzgc15bdl&K$~2 zFopvf5;g@KBw-2Qa0&MVUXpOvTnD>X!pw39`(481c@E61LVw{re(Oopz>fK7VqEPy zi5hr)p#!Uv0Vk1ttwnq@$gXD>kwsgP|WW=sf zUI)fv!Sy6ytmHc2<;#fLdbtA&4Whb>0C%`~y)Th**nJLMFujaqJ^wylO`Ku(JJ>Rj zT;M4d_So&cO7pgRxG!QAGMIY02Y1NYJhb9X<^U-$~o^cyfPf7L493c%x1X2fd_HcZNF zf8D|UPo_?I1BI6GSwNg(evQn5u&|-Jyz5N|uG9+nG$1}&K^1uLEe9^EiqsWvlM9Ia zpLmF12lC~XKmCHt4RBZr<{hWF}0jn6m2~X z$Jhio+Q|o=hGYC;I5EOevVKn}-%OlOggSAb7$vz9>p5}tEB_1%0)#8ml-LjORUZBw zpx)R@Z3x&%Dr(i3Cw~V;!;q9Dk`fjJnkViVsuZS$8!R^0e!%-=F1JRR`dkwLH%ir4 zqj)u`W-(4$B9jdo&00`X2@P3*O79{-)t1)) zJ4uGLmR8}X0IJl@fUP9MyMU_1rvR1SYQV=N!~LzS+IbD|RgvnRo8)Bo>-^|hoKz;` z@g2$Azl{@TcfvA9TPJQX5ikWXLy8purZ}WOR^H;ophq0;BY=}?$>cVfPIgfWMrJv2 zwjp%%1Uw{RNVa8hG$1Vg2`-(Q%{Tvq0e7^FU0#rK1r(2sfRQ}m7r-lk*%GGYkVA^pTL7C#cpG52fbQ{t4KZu~g3eyn z&EmKpaFb+ind`*GSyG|T$mOxWpnJ_h67DgeymkV{NO%|!iwsKr88BKxmPZXKQZoRj zOSl;@OTv?YAzZrvvD1LHB>Wk$tAx$ETMWs7Q)FrtV3CA>0;WpXq6bx}P}UwWl5f2T zz5M{QC0q`OQ=Q+@+ku+MM10K><_gx=04pWDwWsJ_q+mWE+M3|AfW0KF2E^j!GIRmK zEs37miz-CG+W@hQ`vY{Kc$v5g5ROf(Zvsx2uvKr-(v&(6@I8L#6}WikK2G+r&Qq?S zacbS_WTRyAL_k-FNOl(ufsfadEUhLv+3k{L1z?OrCO=;2#928hbR7WPE8)T-C(Z;# z>PZ`RET$1oq`m++NW#AXm4>*a6{qqTHiHH>VcQnKGzpK}P%oiAD;UxMpOf%w8{R$BO1%Zo#Eg{; zs{pekJZQuJ*)XHb$%aaXdjM6&du@2$hEcODhFbyqNU?7seRpqvh?eoa_MFl+zxJ1Gh^DVd) zu$E%5;cgqgYQqCI{J@6CZTO`P&jNOrdYdh9(iSUuV{bs^Y;OV1k*TQ*t<>!{jK9N5 z-C#j?*dizUTUAi#66$TD-r4|`_LQFa$bRbEOaDZEF9T*v_$y#73I7BRxsP1$9cj8$O|7 zuHvr-_8MRj;7$p{KNE8>r49iM6RCRs zXMFQD%+ym=Tqa}Je6TE%f|mdjC2a7y1v3CMWoilFJp#Ia2V^)?yM}W7e!|I~lpO0$ zilr0f{XO7VncC%)SQ=C6GQim~^*6vN5{~?m%B0-@!|i~03j)DPK(~bJZHC7Ho5<8x zZTN)^FWWHmD~q?a4SU%z--b(V_=pW(vEgwW{%XV8Ut3wUuwkAJZ@1wcHe6@J-8TH# zhQHX*^^KK9f(^UcaEuM-*|5rnJ8k%Z4S%ws_N|pgQyXU4aD)wK+weia*mXlfamosG zi$GriCGjd(Xk+JTEVD#fG|&OQyRJ-25^0X_@T{~zyMd&ZPkM|_r9&qN<2{iM(Es&NOL@qmsTxWl|3M)&> zsA~|x9DhMSx!fRfd7zm$A_Nwq?++CiBb2H@;_X2Mi$JSM?v5aG-at9C{8ajNAi6Ow zPzW?;(>bSgWj2tu4YWup_7Az&gUG!DT18EQUk4HVF-V603nJ${{|`fD`Kk0VAewh& z1eUNhX!~m@;V+=o)V`NMGq33e>a6_>8PiQ_4J5{cIH-mU%RsX-5!KT%(98!sRDO0Po(Hj}7QF#lO=TK*!KX|C8IAz0rUKqB zG)w~fz@Q0fTD!B`w)nsVsziO_TMxfE1 zdZPS+C2Su=FiQzS_8&cVR1modH<*$?HGzV~eu7el{zhnEytQ3=aj#@Ca!BlbR|&S^6c2eU zR#OR6LG#a0WKUwp2kPN>MlHr9Q8D70f zhE#saFZGhBQCa@L(su%}rYh|w1xe389I-cOHFd+Ho5~@7vStQ|HTC<|Hx-m}>w?Jb z3nKS6Xw9hvRQ|xy{}4p*f+=_txq6ptcG3vYZdNlDRQmKFg4v+ev<@8xT20=a51M)N zbzlJ>wDYU@N9ossSX0|S8YIK#f@FBY&M+W9)c?0ZGW;n>hJOUfFz)x7o1!IXRsp5| zqYV(KDN;bJX%*ZHv>t--uejElvIWLE)THm_<3-H!s|u5*H~0^(T$f|mftNZ7B53lE%&)Nz25 zBzzq(Uc#>dzm;%bQy1>Lo!tmIKOT!h>3nsgP>*{@yo=Swh7qvq6+AkbCRkiQ1O6hp zKS^}4BZ^~Va~It!LrM+)*`pO!AxSg}lO<-*qc%m`R|7hs5ls{kiRc+O6(23#Uj zrzcswvjOYNRIi=763`=3-H!qGaPZOy*nFl9HJiw;8ZeR{K+YAewx~JP(6_0WB5IvP z&`hrjq_qZZpW+Xsoed&)9<&@=&cCm=Y*%xJ?Lez<3o0ZH?Gi+;2WaM_K7odgY1acj zsh)xjBtGBXWxZB2koGocW;g54-}QvX#WYJtH`JwBHxLL>JOJC$H$0*9LWbf^t|Qn; zzBn?pDZXpNBSYu%T8%@KDvsf)uBY(m@oN~QqZ{MhW0+JEQPcz2Qlt0=%+CkyA+*U= z{3y=DYYU#ik6sb6(t-Cb88Y694YLL)P%<9J?14Gec;HBzKN=O+Aq zZ-nK-1Z1=j3a;ZxAKXXCoVc}rISlCtqlVU%zqN3Lzwz@z@dym=^jnO_EWX5V1s;-k z3&;1s*zfQ=gX3I0qgo0>-ocMz`b|KU9Kf#=@_8J;58-&tW8ngcP;v;*7jXzVkXV4< zbkrs83>GorbEuU*D4qE`4@29bCJG>T61DI>46cisoQB_jpof0>D9HQxRe+ui<6lSV z_n|;vps@6714G-y(qGNLH3yCkUeozh{WaT94O(;mg+_c;bm;4AX8u&$Enkkj_i}XT z5xfnCzn&S|+!%{jdQz)X*qygkd$^7>swgsN5DaDCZMd~+SL~mI9@?}gy4UtmFJIr= zG&}Uk2wvJJw61f?%=}qAuXpH#z554+UN$O5K;Sw2U^$z4$A*cM+=n7dTF+fOF23Ua zt`qd{@v;IDnxh(Mu3dy;rXt3(gbXEQr_fHBh)WT7LcAN!l7jdb@TDQHgdCbmybq6j zq6Mm>8RBcG3Dk52TY&nbnd%#~#Q?;M;~5)?t}D!h*!fadmvtgjGH44g*C~DJuvVVTEn(WWa72FPoQ|M zL5PL>_CuVH48X%)M=t4z%OKbWaXbv_jQAiL8oF6BiUr?b?&0>vmKn}Vv&K|CA>bE0e`b<(E#FaSifVel>KC3D(qUrNEAj^M8#b+X(cnp6C&%qNG?rl0L6qm_UCxtp2 z(1)1FxfX^L zqiJ*)h1YjE7(ZGNn!J8lXmj1o_C^AxoxAdeejug9%w5 z3yS9WBI?%v*eoZ@BhraI?p|?*ZY0ed+s^s-uuWd56NB0$!+gWaw-n~;nA!mcX#dcb#xYL<&VZ9mR z9Fp>5_xv^VZa(rNK>#=DUe_69R=6|Oq(i}gFtQ~RwY?*cR z`e+*)o5y!|@TY09i-#Q^mT3Qb+o&B;o7m2#(G6@Gz8erTdJ+q%Sv2CC4Fk;g>4}hN zwav^~(a#RW9Qtj3vFnMf2mWjILjO^wv?{LW2_t87>&%5d=O)id`?X_$yDDYWRlT#6Xw~}YG;WidRqtrtya@K! z@U4>vmCt&iC)1-{Z8U%B@@CAYuVcEM&1gS)d$rzMeD_`5i{3GtgI6xw@*5A-4OcXB zu$onzs<$e>?WxP1Yqg27$zSGu*F=|^V-?8QPrI%kab$F6zSVBZUtslGSCVU$D}U{~ z#ER|mJyp%klF%ljX!A6ytIN*VWv#-|YTzxGq<4TMOVW5?4dP0HwZH@%PXtncNkA$v z6PN}30IY*%J#Y%&%Mfk=PUHKJ!2f_VKtnWf6wnFi3~YqvYqiu?>VktDU>>juk(+@n zz&F5r#4P~I@qH^W&PJ_ylup0H(=7OIC4lJw=#%D7#FE8jHx z^4+gms_bHAzANzWyN(5MD(kuERkwhBwvy!EpdczFw4$vfxwk_h;p-=ZKfP1&C#R7l zT>-{~qCh}EeMwpc9BeO1PDJ%tldfKEB|z$Y0OIN*? zzO!S^vP9dO44BDWv>rZAG`tCGXeoNT;GM#0zC8=;A-b)}N9UJ*al(h_&O#$NWqM=Kn@rlq>%aa; zXhlC1TJ*)8_H3D(=%Xghxv@tog+}yUp}7!1Ar5RARXVa39BAL7#9sJA3LL)k;@Dd$NE>6&h6V#*$z2s9WG~&b+nv);VYA2RVgPoC5 zp!idbKW?IyTJRM4NU04{i zAdjZ3VTd?sMYK3^m6atrtjWc@Hid(P3(=8X|AlDrqryXj}YvpJ+7>`>SAb{aI$F3 zT-~-JIa7)WKmSrJMB;oFUT{u#YK%VO)fkPIZ|zSGPXYB6jIb+A8WHbGYt zgIb+t-1J*QBL+L6dEJhF5gKbncl>Kbh(>6{^+0H>KO*jqzBR_3C8?&)>+VgJ?x+Vb zPMX}#I({QZn27OInB;}f4R_|E>YY5J1-*7>{Zv1k-f@EZc`#p1!^ygQp}j!!JXq(f z)9867H>VeF)DIbAh!t)Gr>vVqG?qzwcHgMG!i^Z3g;sD%tr(6?TCX)%EQD4J(?Tma zqn4azYVQ}sRTX(LFZLHT^I}cpzg9BpeN7&yEA?WQj0Mqm&zJ)pZN?m#JzZ|bd=M~i z_9bgX%e`4!)|h_sX6;!3X?$24)}11J*aCK*PWUiS1P^@JVs?+F`LZ@#`ii#rvbn4m zwe(|6ST9{KKQ>xs&uC8zST?2yEm$iyhMZd>m`dGS!fP?j6Gxk9PfJK<(Sw%kTUou9 z(V7)&{wKH`IWI??1KuT=I z>}W|Kb3&>c0$EqbAW4gw8OtO!m(FT3qP*f&wNOA31DQm3zvps9Y)jC;H zukB9W9hjTEw!2J!SeqRn){*t(KX<3tj;sf---C)fvP6_@QZctDn@DD--3P1O9x}X2 z5=9NJ=SUw%GFzV8gAyXyUH)Sa>J-I7_>`VBD~b(ZI;x6dp6dOudf1cxiDKUTVNYGt zPAr9S_ZV8%8Py^6qLZCrlhljecGlbU?*f|xuvrjGnO$ImaAOzNm#cfzKV4V=Z`hms zyRrnhpVt-AZz0WyqitQ;6!k%TFOH+tE95TDhDsHzsZzTj-=eTW<+yf{wxHijK$Jindpa4hS_NY#(I zvs2WpANua8NQowW#rG8Xn>&$Re|8I%_jiAE1S@JbfHh}Ux;_I~Pln#L>Qi*xFX^HP zdXiN1aHBP}Bw~Livm_Mz?^p^;Vj(P>CgYHm(S{_DE$O;A>O;1p zaCDQpk3yce(uq-s+)A%RP(m$}SzG?@6G~2InYgy!Nk;O?WHlN?#cEnU8a1_@PK;*j zSrm;OgNj&0PsTv9i0sEga*S4uMYHvw2VGL*zp1)albDXN zD(XKO+4+PPPBu8xH^t-0@TMiRDQNSiG-7)I|#2larO-^G2dE@$&n1Y;Fr@?;;y-Gv=QmFMb1RLuVaZ{kU zG!32M`4D4gU`h2nDQh+}Blqb{%bp99<`j?byyZ|DH;u&$*T{McmO)RZv+kl(>HWma zKuT3KY6eE>Dq1@O?W-MDXAwCRNkykavYCdbqxWv6ymVNjvh>!EL0KFeX3T}vC`=v$ zXJVv*cT}bwO_&MOhcs^{>t7dFE8?6;GmG^XU3V5L<`c@pQJv!DEGU+e?PrEKeM%Xh zA?`FS|4d(<`VRjZQ5LG<#>A_V>ouWa^UQqe+@xo~#Dxkn(3~z*mBISdQSD}f>P&rR zgX&BLvvHPY(u3KC77*Qq;xnNLrpcM;Nx`%>lg-gza75#@%K|lq`edP1#?ZnngI|3v zYX!BKG}&n8#Up9kTo#8ib{vY+vpgHrHad}wTHHo|X0ws(G4-E=3&op}v~CXj#o~WS z#-i*PQ_q!3<}w@hKiWE1U*LChQB9m$ey%^t`W#0xZT+0hkUd68w5FJQP;?Gj-b2?v zhiSMzuk)F&*=)6>ZbW(W*+<4}V>jvjFrJQ%cZx30$Ejnb8@Pb|Eu-7_S&S2wdFf^@ z!Ktb-40TK*vaK;|NY#1lndYp1_+wHM*{)*^sdg#LU_rWxU$FmioMDrfVMft!8FOVJ z;=34&HZNm~WwurKQ4yQOSh8*dF-Oi8=?<+#_2b0Xy)DL-11I^!680@lU%yotL0ZyJ ztJol%oqnqkr0V9a7N?_@B1&0XP1C`ms+bf-1!2fSekqH@nO6l0?WkFci~T*CjOhhV z9?d!g&qdIP4z5F1GbnUD+m6ouU_JX89r{oi>&*_5)dnQQNc!huik*k z$tQ;IUK{a!sp0z=@%^;;-kGb0Q-@OYvD%F&whLK(jVyN7cT6VzNq??K78Ac_`&h8f zc@vWvdQIca$m(JdG@{hau-c}}+bnA5fAnSx8zghIYF44jnbN*tHnNPP?J*b=E5BhX zwDHAn*vC<@Z2W|E%n~zY@kz%;xeIoN;sLRvR0xy<$AN3WOTY$;@L(VYNC)zP3g8s* z7*LsE%LC{Fqyo7>1#k+u4`5OyxdZKh!9bc?3Xw|iWjAmMs0HlI;RJ{WQUS4_a1gi; zNEVV52t*UBVU4n4G?J7A6awYI1>iB@ifxTxARb5s%7BAFEnra(d!Rr+AQvbFE&z`K zS4{tcfkYr3CV+|}Cd7d4^FGp~G{QZP9rkvM;@p zY4vl~RL!7RpGzn4og;ks95cFYxzynWoF2=iDaLT)3zooP!~cd27hV@q0OJl6`8RWt z`!1B}+#+-IufJK)`vkTLu?%tLLi*)z*3QB(_k$aUmta(2E-j=E_|6fIc*&-7)grp` z64&oOi^%d7vaoCsbr7LuF->`e_#umF-7CyXzsjR4BD|4D4gNvsv6Om`wttz z2Yx|!|A8IPCzpTO0Fm`6{~}E@q;fD(Ux2&mF1I6FVj8k?tp&l-7Zm3yJppXk`-8(1{o_&WRzozBhJb>3*v3vlJzL5_V z^`K_FsagwzCo4n~_Iuwdi@<2Dz&I8gbM|HeriHpO7C!GqoWtB2BBx^V=REQ~Get1< z!F*m!#rVz<9_D;H-&RZ^G7sUAUr~w(zx#?d$~=fyennTru~b40R6K<*Sw(YIINr00 z4ybrvky&dq_{2D)KD&xS%y``U)Rqdy7R+C(Xs;Rf<_K??aR=_OnqHV0tb3?Yps#Sz zn!UzYAdeJO^%6Dre(&f2L~4vW>TlQ3Ew!>h{^npBAc+}puo$_7(MnN+Vi&CqgNK4k+f((>Ey`|flr zxX0}R^@a_!+KNZNFJBE9tv%dSnA{Xhs@ITOS#w)kQkNri-pFA9SBbs2%&+wl% z=)&rAOU5^Cq;57S%$|)j%Z4ZO;a}4&5qfW;9=5y#&)=k5WXm(rmA)a%hJ3zN;WzJV zr6~=!<35%dUXnBg30(e$&O*YS%V~fe593S9X_+0m=k{{CWrsApwvvNAKhMW*qlfl} zitFHjk~tv%^R`j41Mg>U97U*cFLOt_0;ecvI*uW8;4xML_BP^Z3MQ*2^ zj^Ge}c=7}|LE#L=%I%cUn7dG_6W4MaWIDkG!WT|Bg+8tzZ)X(rRs|(HD_iJ*Gt6CJ zZncAMIU@mtmM%D@>c-e)7bqG*(P0NIb%6rmUKhTIAKgKn8o~F&9WE<@(#~5F}i@G&IJ(upHSxu1a+}*TO9Ov(*yG_szU+kd}cVz3^J(TPY z-fu6hcIUKR^$Cki9K-#xt~&FO;58K7!I0 zN`%XNm7~-{D70Qs{EMvr!kc$Ky81pO_lmK15Gj@O*PaXU1-DOYUioyN>FMr)2tK zK5OG-x}LvZ1c<5M#yPsTE%`o`Q<`KYc>%7HMzYlJpXHziFb_E!gfjrMjf6J5NQ21( zYKBRfbaOtYw%TBxBv*eCk{8SQzl zxDu%{;J9(Bd3kvxf;WjmPv_*HAY1Q&%lLL7tn!ohU=v+s3Y&7(mYvV@QOk3 z6N`qlq%*%J<4S0lIp=gii#ZkRin?%bhAW%ya93W#IW9}vqIm)?K03?p92-`%*U+pU zJVEoV{))q-4u&;FZ4VwPE+0WX`4n06d6^-lKMd=jBeDFM#xTe;sSVk#MVTsl^B9h? z+$|2Bvtom8Kpekfu9>&ZU>Hoc8zG8`=f0Z##<&HBxO~Kkf$l&&U!+;N-Jl;qYx}Dk z>JkU?2}}%9XA^L)ci5qG8^lL2jbUVA(gB*>nl=2oWH4$4BgX0>e3?oD7z=0Sb3CIOXf#bk6;5A^^01FBrv4NB& z<>E^za0Ivn)B+X_v19?_fC)ejun9N<+y-6)P8j9_ffyhOC;@f@*MMh$9qxj*01|<8 zpb#hr&H%Ro44IOXLl)K;_!0w50CIp5U^h?++y`uMo7NZT0t^N+fI^@GI0f7WUIVV! z+zJNbfm9$DC4dHJz^%`wP)Cc?))drp@F{*ahA4nY=y6Vby264f}%3GWcigHqFU^$!*$@!S#Da zwHYw!M~!Fm<_Nma=9e7}L)AX4EKQrsyHS_xC^VCQtLZ0;4$Gu$iV|yRn=D?4q&8&n z?^WV(1>9Z(r9KBOsP%J96;l`RcqmRU;BBoh!R2E>)d+3X2oFp= zWkrj)yLv1}=N9eAdl7e&TeMS&n=rGA)mJ4<5ZcKgehO8gUT|^jGXpczMoYO*U9#Pma!<<7 z<0}3rlx{3lxZMLrJr&k&VILA6Uw}vh(J_qN@)Z_&f|v$kT^KFO=k4kec`k_QAkP2C zVt77?86bZ9kHu+0V9!JSIE;^6Xj{%FulH?AE zhuiuAsX#7J1{?$~0kwb@&$D;|k#3T?6pt@yZUs?qi&k)VFFYxw4#lcNbW16GT58hp zv{Ai=r^Zd1IyP~`A`WzC9;F|0JQVzj+0ZfxWfV>}6^RmHp&f}e_c zA2DFMe}&O+8TI-K1LiW_#ILxmxGkGig2DABZ7sprbCaq{__r*O@>anzkPfZlZ87P4 zz6xV%E;d4O^cxLd&9k^)1G=>ut1*ObYcQ9B`%Pe7(5tivSStsz}m$Gfqy5j8=4`bO zn{r;5drwBDmJ{2^dx@;ZZR9Pu+L1ChVq%PN<3|3171FA&;o&q@ea%0&nBZb8$g0n9 zk8SEE6l4O;+k_feNQXA@KGOj4jtS z-i2diQrB%a|B)jTwmMEocC(IuI!-*wBR+}18FYr*z-z!AkD9duVt^zd8(0CH0;&NE zcW8h}ARfpDRsg$!Gr)a7@<7!A;lN;z9Z^NB=m2-u;z2)kp0S&gZAQI@EJ@$1jkjr) zy;_{ikS_nj(%IIMOWBxI=zBA+laiLU9^jrI^yV}qv;qmaF+4}0CGA0Or^arH`kEJc zALMQv;nK~jouvJfxl;Hr3$4!m5bt4pw7{OS4?~}i+|Bo<;=|m#(R^<);WVrzEAS}f zOF&GN?s?19J5=sTZ+)4Xt)rITVc=blglv6iz;_sU5zhLKo32yq=(G@E03Ks~M z9_35wTzDLVpa?D&_)?E!NZhbeT1P7dK_J%a33s}6jQiHHw%>!@2){{w6!tyNpd>%t zIE0K(@}uJ8Vv+Ap4NidQ-GVxuz^OK_1x-JJDfMqH>A(pdV{TYEuOq9I@boo2y=qAz zCy_&hLr-G8i}1xsVHiOEKkyK%xvfmq>Tb(v?GL;OE%||4@b3eu=m+S|1<{W`@Bye; zk5h2D2`)o|smCc)Y)G&!<&@YU`ZbtlokrrD_3Pqw^wVi5H$&MkgkGG6vR{bKV;)nTwP)az9-V(iKvh+|A-@(u))!Gi!|n{`ljkAd3b{=O8gU-I z)24%|8fDvbjQ2-?vFM$Mr`~>e$mHO8-VWJ+E)20?Q_t!^Za<^M2xEW7t|h``ah%zK zihkDD_miI?U5RX4btH!iias>z0thVZ)OH_hOn}`KfJd$2rKu()<{4l4(FG5@a z@h2T=(M8^+uDUJ?Vh4zlj`a2-W&jBNf5BFdeI%Xy1#RLRN&oz!&q<$OQGwWfQhyU^ ztU!-Bn5TXDD>fp(iKLCcVko;GNmDNILi5J@{VR09%W%I7HXWiU@i>{2f9IWKoP)Y8ce&US57ym!z&l{)G(^|*5nrU{#Syga zPk1eF4XKPuP>wH(m5wgvf`e?AG&DDQ$B^G@7;RJPl~RyhDOoV{Eg+jsOssj(2N}Qh(~IA z=r4Izs5*W5Ti|A&1^v01H`Gmw*Zk^v8i~z-zz`4>*elox1>uKsrzY z>;@`<`+%J%G(bF%3KRn6z$u^_cnR2G%h(r)1QLOCUA2ur;jNA{F!3Be9pYbiHDaMV(6 z!}qua$3zNm{Cv+yd3L%1Um7;#XP8R!l@!TO+!Ztm-4W zl%nd(mql!(295)5WD8p?+3P-7%ByXtyN%q$Ohnu0CfdmM%(&OSS)#XAmJU>EE8Fmf z|Ikib*;|BHY~|a+CGy&W&7>y{BuG@?sFu*D=$*~>PX9r}7=lCxoS2(*{ubB{;Q@rP2){)*2;o75V-OxfI1S-pgmV#|Mz{juj|h(<{2#&x2!E2Kj@ed{5B6}q z0TKEE&5fb*dpE>QGa^C1_$z?}G(durybcxr#!23uBA!0A16lx)Ks=BNe4C}Y5iaT97c#}1n;p$AKnWhCA3miw6-?&fTuP#@Iv78r&{s_5KQ^R~vC-au=? zsJ{VI8c9F;$dPq~tuKgj5S5V><}0@|_9#(OQxk|01*O*4WSK9b~e`)i@zq;L=!qPS>r4>?&4oBU{RT9XCm58`zt?G2DSU@P^xh#G(> zZ56q-QfP;?0`Vz`hE+6QNt_TwJP4O6s!73nBr;S5#Hc%PmTMFt>rdq{WQ2Qb#EIAGE z1j8Z7yGZ`+-~nOZb_x$SA<&M1;NC?;)zR?97`Z(|Wm^|hl&CE)D@^MEHEPT37m5u< z1sImWeQ9kd5*Y~}e!tL

ijV&^iol)#exS4wK`ICx2g>9R^_%gvENHH=PNSgPIst z?V_WbPUl1D01FURoumAcIKGHz+1lP(RHGdcRCb%dP2(Gm4$cI{tk z73D_AT8!n^kCX|4rY4nA8qWqKkV6 z9pzLFnpHn4%s0GB@VcX1iZ;}(j+Fo5qD6{3!y78TM;F|HLH*Wrkr(lM7im^k9HT1S zy2(YF;$I9-MjIv_mEADu5brgKkC+sc;nd#;R06kw*MMCBMs}bJFc?S!mH?Z8BfvG_ z8K7;2VFYLg!~sb_2CxFC0L}on0dZY%0)l~`|!9AI^47F3L&z9|LZo%%`yJR$g#XxN8QjEc>ojna;q`N zRic+1&yPluf2?%J*imfhSJ%=l~iuT3I?qT93CGkOZNhPSO z-M|^37Qn*>k}D7l!~>~7DXwV>3cnr1qC*Wq%z)$2R&NEkv<+ow99E0mN=5P}B?WLJi@QGghn-CLO z^^?V}ZSQ_KI!d$q$({(-_Ji9W>0&>*m!n}oNL0Ma6Ad@pDYU=bTNGjWBuw~m)5VRB z^_LywCy4nDG0*y=QO#Bw4%`P|!rqu#50HB!({l#MQ#FSCG0Dv^6xe(!#~?RDKE)d0 zC@uU{&hogAihT{(Va4nVL<0SQ2|zATO1ANG!v=O}vlc)MkOX7|?}*yTiV|dZ^(YKK z>{s$mKzBvhEdgm5yX&R|bk}6?7QY&Y$RS^#yZ)AdA<`5jhRAA^wFTURl{NzyCj+gvLTP3s;q22d^)@~TI`~IVyISl1Zf%d|$v~HN}&k=r5pvH+1 zOoE^mt&oV;K=^@R;%nKF&LqlOHJ)}>YcJ7_L|oSpexT|<9Bw8<;CqQOha(+?9|&Fv z!4wF(T%x8U-~r(Wf|Vm6mR6Q4k>fK(Ipy(jjK3%IR^$lZ;D^(cBG_*vk+E|bG(@OYU@$uArY{xk5AmuaWq zBR}MujRBtle(+_A9V2^VmHmPJ3Bk_>pMIHY1fTvPKWZ%aOz?%5Y3W$-g&*=}<50^s zqfyHhmnmQzGEniMU@ZjdY&bY`nSK=fnGgAh@!;oxzkivM$IJfg{)hZc!OsP+x4ILN<3O((%Y{)ha^N#JwAmtUb{lVD%|A^%Y-_=Vt4 zU7?|=us`)7e-S)YPecZ8U!k|DaB%xW!Q{yhWT!wNU8Um5vK!tlIjXE8%@oWs$5@=GAXmCLWv=9^;E33G29`<8yzANY2Yo&@foKs6h9JcI4T(yY9dGc1o z;ohoEI#a+bM55E^BeO*$ddO-KiH@L;tQC=HbnDL$>3Y==nfRIPnk9b0L3|={!7Ie2 zbQ5p{xDC7poUoM<2*dzMfY>ox0UQJ_051U>%zuM{7$6nM1vUXkfJ;CvphY@fKo?*z zkPhUx#WQ1@@Z|_l4ZH+w+Tqd413Iyc{?VTmzl~+E6$I!hwE3Dv%450SAFg zKrLVqhATPH4u}I%fn1;rI2aZKA->cC7Pz164uk{!fC)ejPzH#5%@=^jfJHcTKsz7~ z7z1PjE5h}=UzxJI`KQ={vTSCipXnLbj}bIH6Q^%Hn3m0GQD)r|If70LVjzg%X7n@@ z`#r%h)!zmS%#s6)1AGLH%7QEbvSrO^X;$6TBZ8^~F$l!UW)#rQ!n7L}K@r&?@T!p7 z9(RS6#AXoYLqNECn^7yKZeN#4`#CTf3Z}U?b(o{bxTXRMzxtz3eN$4?olt8dYV(k*PCjk`FU2(8kkssMPo+Bz3{>q+SX)1;2mo zzf|VNem9<4=cC#1Qk#11eNJDbXgnw*U)IXv=(`ln4C9SLQ4mujqLw5S%B28xi(C&a zkdrmlw?rP8w8^k;t}c)>c<%2sbQuPug5PyT%jAumuf0zlmdlxxu~2rhAKVcuWnc+V z1{?&csbHb(h)0g>8tf4bWc(~g587^gM4(%d9N;V-oiODl9ir{NhFf!c#8cCDw6;i| zq<#s1UXcY+5ApnvyLvG!zBDsD=$*3yRlWofJIuse_&snR>A?!w(Z zt`;d2Vz1N+A$ajN+6Jl}YLP+xise~o$aBTmuw4r4WE*;0T-Szq6!8@*{|gYKZ7BIG zOp+1K|4M#nm2FH$yegxj9VNKKlQ%?TPAf{VCqg!~u>`v&c`~K!RXb4lDompD;pJ;v zid}`dBf{yc5AmUga!Fuwr>t;T{Gj~dNgjRkWaU0#i;KAsC#_iSj~=w~HZ3pH7T zB}C7L6to8F0Z^~OKGuzfv{xJtvm)_~1IO^m`=hxv(=;SEVqbZu6 z#y*%w-Pc2bmnzjG9cjvXB!zJGdgN)GBh{>zgRIs#8j9h7`rhHWjMu$JJEnL zWm08uv>cA+IN{kTR29O1%H%10jT5D8kPq{Y&J?f_g^qWo5gU>BA}&4tx!h<}Ot8wLFf`aiN4wIR3(gmTrQJLKix`Nlu1~W}D%H z;KH#H#coD15YE~RX=x+cCc-_9=#~hdHzJ2EqRL$(3R+^9#n!qKX7wEs#tN^&!{|It-=)1tZ@ zb(Z8tPs`!ss2h22Mfi&wC5X_m2`$|UpOc%=)2;An<4ytF6h7x{L+0=uwU9`ftF z8|RC^7Y*1gkEzq1*o_46LW6o2e$HvPYK5l`Ax?8RJuhna5gUiqmxA812c4r9p0AX9S~ePgtZ z&gDCdKNt>lMMvbJ9A~!f#WDFU!^_4PRV;2 z&JA77Y2o07vu@n~WW2B8*hqKf3^s((?{rVkqOYT~=!RB_FX8UGAAgotGtrLYF3JZq zc1;bg_fXZ(G9LN+MaJ9lhPoEdi0sf|U$**J+=VezDU%k`j=#+tQs5;yiKFVyUcwrn z;u0pVs4g6Y$fv#VG{zO|-nn0vqqD*zabX1}0QtZs;2>}TcnqkbFna|8ffyhO$OTG) zBfuq~7O?1q2`3N<3eNE(KTHAYtgJ5rjqwHj3pbU>SC|Sv5YrLqt(~t9{lq(dU#zH zzg#nHmxTijzackN{|SSdG@5k-1_;;Pkk9g@X*A_G=+8}~!@r@QhfSxazsY_1km=N| zS{}-3X+t$S*Hf6jnNDY`VT$lYH3paR8Px42hUGmoXz5LyaJK1&t}Vt;+)u$G&o)Hv z2@j2L!NXth&?B9?-GT>%DYtN^V`Dn`|Be&eMSuUMmS+DB;WG#yrPIdWF_%F2Ap1`-rT_sd=R7mlpywmpz7xk$mSQsbh#@JJ44aHDJR1Rb$i za97N^fiXZ1Py*}&DuG(Sq8r*tx1&a$#MJoVMfKF0gH{NOVQY=)(L=)_+S~z?=^r+g?jwvu+yjJ(2p=NMM)(-vR)kLwUO`xc@E?S=2z?k{ zGeg)9;ZuZjTjI-K_)>xJIl`Y2zCic_;ok_Ik%5;8!x6qx(e!8X09)}}W#S_Wnudaw zh=O{uq8BJ=9xA8ZRq}ozyUFdY{{Ou?@j^^wpd4^jd4m~)>fdPjFF?$@N(q0oolz zh3`FrC<2jpoo@VtSsB8&|J2=$%cHUX%AVc?f$D~FpQP`kG(7UI-zULtrWCHmkAI?) zRX1qozsQu+4Z0=5CO4?TYupmdBkX?SN)8uWZ&2nNG19$8@o{kYwQPEcFpv7bfodgG zy5EG#o9lklZG0oYWX3Z}G@7aRi5`sxJUmm}E`Nu6U<34_`Kl0Y15D5EfRnbihPc|x7onpbV($BDnbTqsect)%8ZD3jlT7Y-$ zj%Mv%5cN-ywF+|p3HN-gRgLvu6mJ=Ed7PPR+S1bM{QNTVQ$+%H5CT) z8mNBu7e7@gKJGw2WN-|S4XgkvfaAb5;59OyS!Ad3!me#IJC&!{y!EtbL)m*(!BkJoJS>T2?KQF-&~YF(@gvWAl2$2{yQqY;{a z6$H1csi=|4v@23Vmm8@()vH1LUQOIpL3DKmu?EDQYD!TOI|NY*;%+rw8dq2}ZVX~A zi2K#lt+9ewD2R0+9#qp#CGlJk>p?uKCO0>Q#c($eWgs3`(;_ADlOQ&L_^X;;D2dP} zDo^{3AS`YwHfy_0N=Z{bELB2lp;LbiUHzN%V-uBW=ca@-?jSaS@VZGs?kdw`_a!t( z5Su|Xze!t^#48ZqTR=pbl2ojMC3BpKI8)RrOo49dI(eunnQ^QwA!kpx{05fY?ocOB zMJDD5q8vo;JG4bfJP^cI5XpC_ftSLfj~9q-AST_RSxRERAhv^;e}`@<36EwVDnNX3 zhk7(qxLPQP9UwN|p`A+NPeJSivHcFYcq=RhdaFFmcY!#0M@5S>Wz%C%C3F;wdN-I0 zcj%$Fswqck?W1zwE_cbz0}r}H`l!P3Gj6kepxXmo;a%E@sJbe80K$4Nh_CJ%+jA;y z^HG^Dr6ttg7nV8*cHgB;UxnpSLF@zZzq|BMNwo9>u^)uXJsRMruviJg`Tz(I%t+!LMP$_$V~5?oor53gdw-VSEgPn2U+>Q`A-%H*cvhJ`IifduS}~)6Oh4>_dw+QG>E09obT9%oG%VkHbbEO8G;y-lbaQ|5RU&y;l$%3w9N%*K6yYLLNMEU9IOhc z>z6CRYA=GFZt^gE2OfBN+)-tEl&pm8L*U^TXlCm@#MBuVfYAO5;wzK!pTf90L}6^z z7RHyLS!YZ>uB|Gl&ci~m+RI>%m^{qci30R&rzikx2M<@E`N8PnOj|_(W`fmT1$)Qj zf$f5a_Mr+7e+m!Rpn3d&-iDzH4z^Qx7#j)?*TGt1WutG-Il@EpFolPk(5P=fWBbtH zp*&RKVPF_M{027IRZqx z8k4sPS5#v6aCrC~Y^KSB#~u`*UWB3mN1;*QhGw48!;)}C0YW3-;SSjKCJ$@(;5QO~ z4N!R41C9DFG+Q3hjR@8I0<`V`<9i_PDva$YVsAZj`mBS(!)6H8_aS_u_u%sXka%=d zd73?d#D=PZRSs0Kr=A&AcT^O16%^`+P&hsk*>L%gb&iDnBd{MS?0f0zX=!j*KQi{i9s4jMH0rEKxO-=e2v4CoVANn(vFxlER`x@n{R@Jp zCMO>I;pAVX6TdES@(h|+@0~nUI#~&U`Z)yn-N|EJ6nQu63gQI_r^gh~RY6P!q5T`g zXzU6YhQtF%_WOXkTQ?%G6$TRB><98rhWBWs2;Hq!2Bi*IDqL)pE25Sv$R6L>L?h50Z zf?yybpO9q_MV9*a0Kq}TKA}t{aTXm zZ3fNqCv>H!BIRZ=Ak-k%KcUzd1+fx@)*QrDlh+-G#A9eNij=K-L1O{UEtBTS|Iy5W zMy-M7;S<`@OOe2HL0E$L^9i}dDu}VMXxVxo>SJd~R54oCy0@ZbuS1~LLf}v%EFGzF zZ&k~>OG}^L$dnb>P@_3{d{@tjv~h|SIsuK^8k)!&s_CsrJ2Vc)^+Aj@8L#~ggL1CY zcn>sc8)(MW(2Y37Akw-IjBPLvGV{JyMpL%GCnGdAHg`#u!$+w(PA4ZO!61|mC|dmA%YK9 zbakJ`a4_c&+Brbs`IYeO1|rwwx%Kz({J#N;Y>oXC*=hn!{vWjLQ-$$m5L$N-t4+ph zh4D9^DvZ0w!`K6wAOD~!@e1SpAhb zmd+1Wr0hHd#w|dsG#N*ogz+P#@j__SEupEZrJX|*#;-tFy4y`U?t6S7@Q~hn-sASAe+9sH$*NE} z`kjh=Myp!OariQ5w5q?n>zzusYqV;V$cpn=Y?%ZhMc)Quvk#x%DSbyx9Xo5(hg&9d zpi{Sju2TcrGFDN}2Ow;NL3B4cn2HDF$ktUkOpb%`N6_?XK(odvPWwZG2muk_fbJ>@ zzwy{qXbU2-0iJwWA$K<3uP~jKPmxhC09#$##$zKBJ6f6IZRcm>RW=;EScr5X_X#+_ z&Xt~t5eL|<8ae@TY)(G(Eave6SQrhvdUjou_fFxZ*_6U$HDp&L`+ z9Q!SnQ&l%O_Eq%RQl%kVhP@Q=hN=E1-~!WBz8u>pH}GRKlm-FEmdV*19F(T1VmP)* zYSQ4!At~vzZr0jy#;+{m&|}1`w6ROVBZ|u2l`06bVOpyU|TwT zM5bf^9@_)~^Hq&#Rl2G^$JPLt1isWL_nHa$a=j1i)X#)`pOGmS%y;+2y@3RN-541> z3z4_=kuH=t3v&LzknTajXdcknS&;h}BfETt$bbii`wOX`K^|jd&Ikr;;TxYpKHV7E zF9VTS-s*2hWM@GBm65q77_41uG9W)hS}08@x3%t6^Wm~(Z|0=JjZ&_It$u?hPa$8#9^7IcU_SMai)RL zW`n@$%`F?^^@g}Y#A&wZmt9N>H@p^jBpWt&4ZQ0d*kH94Fb6g^R4@}6C_@}`q(kC+ zXcx^u1&@nyO|aV{!9f zfpvoZZOV*!u$T@Dk;-ntU=eV5J`SqqA(1l%lj!*%Fvr)Mq|JxPRijC{U@(D)Niyz8 zusKK|aslEnFW0LlEPxtwaeV@1VC2{*#$r@1Knn8>Htlj@lV`L^%7qPP(R!N_!C>aR zEf*g@e ziTNqcHQXs%1o=oK(_%3gOg=j-hJ2|payKI7x3Ui$}G=A(bMA+`u9W#>Z|Mo|m#y*wW}%wY7Hz72xM)fzHwQ-GeEVX&A` z0E^EJ7Ap#1ftiQiq7sCR*@mI_zAiwsR~bx_mcitb!6bhfOfXy6woG-FaZC|#LGl+f zfh~oqrS)W7sA+p!{FX<*QdO|r2}k;eI?GDo8`ogN&z@G6!UwLlHKi(lIo=c-yjJC^ z!4(x3dL{)Keqmt3T2*|O_(zKst~Qlmo|sYT#vD79940Lm(PR z1Tug^paM7r+y-6)u6*AR&hixNPsQ39HdR-klr4n0Etz1cX_8udrh(PAXuc{z!mA>Vk? zL9J0Dnu*q+J@M47Yb?A##rj}`x}Zd~0IfmCP!{s;%jTn46pyB(#V7-1q8G@&ACKix zdz6f3p-t!zdW5|DQ#L3TC7|j3d5p7$g*_-6IR=mk)LQlVn!;&4kc~pK&@tK97C`{QK$z>MhnoIAr#Ib7Oo-3 zPzne|p*WO`W}!7`54wh4pkl+wKZ-*MXck(5_Mme}OW;UHQ78^2qgiMT+JnxaN633P znHsK=zHt;Nu#Dv`=p@QUz9Z!OuQCQ%-_H0bCUIzL>#e4*;da$@6&DjbF&NuPjacOfu|sBvd&cAM_g3>vK7*i5ofwPU%NCqZ1}DdRFrdgr zVRd5UsH2npR3}yUJ0AS+RP(;$@?#hFUv^=Vu)(&#e2g&F7CWfDY~q())D`UPKXg%b z*N~ALUDVJuj=sb@yoO84-NYN()irR8sm!>?J?9-8pF&zo7i4Hx6|t766T7MzYaOiv zUGsrSrgO%u#Ik~~JGw?Q8s4n+=Z_r$VhBakCCnsc$*mv(MFZt>?k8&qucDb zYPT&{Rkk{&*>

xRoIi3;{j!lcSm~RQYUk$Q(x2u!33J7-O(meZ7r%o7LfMj?SQT zx+9fOHGZ9rXGL{5-7&}3PxahRu+2oMJFDS=L z9`MGnduE}$sPTL?;*g`G&8Bu8qUyXy?4(?={gvae!#^m;OJaLcVFy!ruMj(FzN&iI z(a}C;zM3K2Hea1R%sl}60#)FMqpH2>0@dt@qf-G}uKG2Xc;WNax+9K7UaoX)+7-3y zPsXFhA9cjq@~vQ__M=P4F=|6}OWUFojxZyMG>&Ge@DtpXfV}knQ<~#9hri9bMXI%J%t4ER}eio7(+9(r* zd#<&QA;3AFfGMn9UO#u=V35tsITYo)f=9E`ZvXCRY4eD}&YDr40bj-JF}Kx-Gjy$* z;(Kofmm-_a(48e)7tS~ud-TikjXLWn>yeb>GQ}n9vpQ@tElx}MP_q0Qp<<(GT2X7% zAElthXcIbyvXCPQJ5(FBM}v`x79`D!zOv|?BTSz_75Yq-KF4wQnQC*+A)kW#;+!J@ z*N^8M%2)EROt=FTQCaCcQcuylBJ7-0K$H+{p zTe-IUfkd8;&0pCn=ytBiLv9oKT>}2jiM-?(x!iW!;b;GwOXb@P_zB<{)ICSI^8V9N z{&jiR|C1DF5b@hPYT%zVE8pHp``}N`zxI=N)RkfHPzMNb@|_8z#a~R&A(JX|yV~FR z0X~E9vA%dW>pm$C`YY|T`)or&G0tg7=*DYOXD=4;3RYnc9Z^#GdOgI=WxHN{FHpAPdp*ZD>@mLC*{Z=~eE-Vvoh!cV zhjowXDNw?7pEw43cu@=-^EOR)eX1h;x#OHiG#g^IaGU;i6!Wk)l#jd_F+MyL`zx)) zKaP$*sq!Us`OQRKI7SoDbhH?4LYe43Dwa%JhI*i6v>0td*U$@8Y7AXO)E}jw6(}8L zA#E((5)_N#(Kz%8T0d4Rs2yVA8hU~J-=SrCN5-G#(Mx%3W)^+dbk}+GB24|iB#&O1 z>G==m(T{t`Fw$lD^oq8U>To_i)K)U>PCmVg42%r*)n&$yHokfpk6m{)buTGTE3w|= zi}e!q0DlnZr!N=ZbU%DYsat+}1rSg`pDn&C3Rt$s3*fsX?PUR7w~4pIAMbstioaf; z6^-;~Mfubce_g&Rd{tcIlwW`@?Q_2XT%KxPfG*#lyeY0|6;O!eqE&Puy@mU;1XFWO zG$^g|X0^PK-i~d2P)PqgjBT4;OaI=sE3JNQy|ay+EUd#khqh5^pVrmqi@Q>kKG8;w zR@K)BkrlrN`d8%P#|HZMUY<`}18nQ44LdvvDzl+pmUXXcsK3{%J*7MtnP>${N5@bW za*ShFquQuFN<=f!N|b>vp=YSrc&Y>Hk5bSkbO>dS-w>T-TNKBabbT7@g>5fY>Bf4f z$IJiyKtvIBD8JrX-EXWL6p%HJ*t-dPIYO0gqL&0Mnotn$s!yA+r7KmX7`=|nFX`J- z_g5(~7=Eu7#<1VNS3kz+&ADaxG6us|YF<-fw^Bbg)koUCP^Fvc)wt`~wV9skapnl$ zs5t1wl;LzC8I*3#WOPQ^nqyfG&Dhm-!4ou1Hwc$3tm7UX1-THZn*E_H{T zSL8L5`Yp-yebuui`_)iBt*FsHs(vedn(czx)rznS>T)Z+76@#ucPN~bqc<%NWv{(d zQ(Eh(6q2otev#6-+=hzveVR{Oww8^LZinv~RlL3ao7bqLu2I(BuFt*rcF+@SlDUq$ zvfWP$c#Dnqx^UcO6YY9!by=J~v#nzSR}&}_#iDpL4$Va?P&zt^vXSRRPVXoR#i2wr z6D>nq(4mPkOI#;C%&5mR*d~Wncqcu?qsig_PWV@^vtG`K!l3!~T&84a;}|8VY! z0qdz-l0YK@=H^ZyZos(zj4rOHI&>w0XzW%URuj7B%GxdhoQ(aLfyvjvvHF)?uE+A`>3_^X%Q^)g zuZKCK>A5-s{&$LicnY&IAzcI12l09dJ6sp9uXLZX>#Lr9DAY9=gcjDV%fL|A1N_`C zGsra$DO+c}j;?B(-G^_&kk-(?`j__5!YW@sy=IA=mm7*;zlO|ZpiFchc}}L9{WzL`9HhHGru`m`l=ooW)6bLMY0mEym0+SOJy@?0EZ!5DphWuU*7YMT67Owk zgYbA)4Iiwx)8h%sr*;k28}c5FZ3svEG&N-iE1#D3^$^-s+dZ{?s6MPX|-RJ|ObhkAJvEJ01vN{`e(w0X_S#|vI;`FOQ8kxVA`A2M*D zsxnG1tS4EEZCLafFN>rj?}_JC!K3t|d_ABJ2&N;Wedc=qOje{#7&JbKt9r{apBg2W zym=w;RjWqnB~@~g?yJs?(!Fg3)U8ouNWQ~*gcwtlUy@!e;2O@G?1k}MSIFLxRTflT zlSsi|jY-nW_$21nwAB=AVqq-!7PnqlWh9YaA!~IiZZs=+CLTo;8&onN1N%DImk-L> z-(h}%s{Uy9VUXG&(c|YjJ@ff9(T4K`3egj62 zj!x=7ru~qFk@PLCG_y!gK654UHifIU@91~)l`6>Di0V|2O}`YbT8`5j=L^HV3*~IK8}OC*RpRjo;V`>O_v8d~-|g3GmH?JmdB9fs$SC_b(M9qN-{z zK@Si1$1UFn$Sdhpd$Ud{eVUeJy@(H?YY_jnfEwzX33@MeZldlPB)6jFCv_s{cafru zsG(j>)LXj;KIOc<+0s4mNxuIjzud7d5vy_yH6cZBFS}Q&L0AuIH2DR)VEw&}U1SaS z{(8SLB|4J>o1lo8`rRVuZ9{r*=3hOZ48SEav5+d`t|QRc3tZJ7u~#ys$SFdNXfCa1ImWE(n!ixVs}aGdTq61nqDa18e%^RB?ZE-*G{`KjgzoM zwwkGB?#Q{~YTQ;ZI@eVV-hItCz^Pf^=qLBjNbncvtV6 z?;3v7@#Bg}3#q3%&CpwOt9<8sdO%QS30HExb0znHI`5^`0Ypo-zv7Fe%^ zyOuO<8t0Fb_0@?Fa_V6~Gf=&j9Gf?D*t_#J;L1@9&^XawKuitWY%D!*j&#b zj*$@mUr*0ERvn(j1?qyd;MuxIA$o?zztW3FpX8!ij=ob+n!?{9)mO`evbASmB`BZ# zstnKKuHkmq6t|l672VDyYVBA0Z_&$b#3o-O?V4F0j)FDdO4talg{|Q+-hl4`&ykum zEf?Tmcv0@p={9`r-cGwO&U^l44 z0g%Tc<}jEC%I@}tlQkZ2`mit^4=KbMkoio^`LH1T6#BzeFaU0Xh2TyY2=~HZco?fv_eV1;tKUvU<2D!6-Nl)`uTL8X$8KYzV)D>|-+xM#G)3F+51(S`!vd!KUy$ zYzDJnEBFkyfp&IBTj+%C)$DKeN^1AFdZew1y7#R%yVeg0Od^xn*o9{p(fS>UFx_CA~g*%9VyI18?UAHjWa4&orZf_C?adCbIP4Bf!7-42vpE$?yy>t!?vLH>1+WtCg>JWk^lQx} zav(*r@Esmi;SRS!2CRjf7E3N$Oj-qv4wQ93$O`_!&1@Uy3n=bauo3P$?8C;8DycPv zZ^7n}3ZS)sQvX{)idkz5m&$=82`s~-Jsvc6misH%5%-U7Zia8;-UU0u>#!^Q3wDFA zV0Y-CfF(UzX{{G-X_|x~ZvQYCkGmf12OD!OrS)f_4IBdBf<+;bv;@^>jow+MuhCo9 zE6Jq$)lo&ZR4z43Yh|^8?&XGDWfVt|_*Z3Ww34qsYaNG0FfZKdMT?ImQRz93vujhr z;6&V#*d!?XbF!MWmK%Q~)e@{zr{kL!Uk(OSdW18eG?(we&hSGhdvg~24Socr)tUoo z0kyfX8vGc_PGDGsIT}jYjDd@Ab5L32AhG;8NHm4NpBABNt<#&zCH~}fdQiE=cort{ zr7#M90e!SOY-zXGTPo*{%4*j-^1g!L0GwaD&2ql+eU1%kn%`CV!oF+B; z1`D(V8dnGAw@`Ar3ev&0YA_Gf%rm&@F`Ex09C}dU=(m~y@IEX9>8qI>e%fQ$1wMiA zz^9NssQm+%z!z{id*j@cCk!TyjL*34ACu&af#Fdc@$1+WBM3B%!b z$Rvg4URVzD?yXiH@&bfb0dhl6s|Z72B^VAXL+;&bk+2J_0!P6Z_yKGRKZeabv{aM% zY_wQBnAgGDawcQYTI1dU+d|%));J58ywa+*hrF|?b%4A`ro};CXR+e(4vE$UH*Y~` zJz!JV3$}&vum|i92S7^891RC~q|#AhVF(^G;84i$4=n-m?MRK{G*?1KNSMDu#zUCb zAj2QbY{+N_GryB|0+xl0WiTTl&&kcVAdkY$1jqwzGa2&m)0_=?x@j(i@AL54+|0rU z@E6E*kLF1@3*LfEv1S(KIFmXN1{dJ20GaR4tOY-TG4M0k1~TQG*$pm*3GfRz9WH|k zu7RuJTDTpiu4Cai3!C5#xEcNnx4kT6evpUb|92L?!Xp!=!?W-dlr26B&*Q!hFTp$T3VZ@Np_~80 z8_<(RDGU0-+b{(F2`j>ESQkEk?I81onZ4j+I6N=M|5FxH@OTEN!@pq${0F{(FJP26 zEue!I3wptxFc16$dc(EQ2kwUX;O{U$%;Uph2t%N3P)S$>cU2e!qf=QZ#zK1-0(-&Y za3lyaOx4e_mKOYzAcuV__5AE!^%_ zuqp1&usIw8W8p;D!ol%Bn}xUV_y)$ob?|Mt3wDAhVP|*~c7gXHt(fV zZ~*p#zrvyLh(mQs)0dSCrmIx$wKz$=UKW2pt!s|b{!P>Ww5!J3^u~7XIv+Wq2Zg*K zF-pt#~r9sVQ;e#gvUKt4BDknKqk2u);J5Ax|>06|6(u<|5C67tO-lPSXc_mHCAcJ zRfxvf)9P-Qfh%yAg}=daFdwJ>@;Vi^919ijh=CPhZx{i`!zyqJtP0Rw3?865n3&{8PY0=ISRBS$V7BnGR%Tw;WH?^ z@^3f}w@zPUJft3I6Ct}V)iPkeX_N4%3@1aLfn&|B9ViL3g;Q~Nh11|b_%0+<+Ix^h zEjtp`KE#bI_iXqPZW-$^4}JsZ!_9CJ+{^yg6bpy(_!Rb`6Cx`d2$$mi8-5A>={u}| zQ{cDoBe)7095Q0>3D@Gzdm9{)(V0XBl0U<*hl%zmjXq_Hp!Zh=eTRw$i` zZ7>6FhrhuLcomXaGeG(Xu(|XR-~{O-z_su!+yx~AKf`ml_qg4A;bq*X;Z>OWkcDe3 zaIo8dDD=iX0rLL8ISu;58IafV%{h>F>dl2P z2!0NW!sU>+;>~YiFkAz9Pu<)OiyIvOatT%fkE@W^$jv9P6!fCg5e`Ejy<)Q(pH{WslkB42;#_VRa zld}}NH=+g)cy@RM7VL#_&XuqPRCWgx=$9)Xj)2G-DrBD?RD2NrNVR;g9%^snHs|8QG9U9l=HuPw6V*#G=ee4dx)i#kKIMPR-*ub6r@HRLoX2Yu z$V}t%kpMyKl?Jf%E;`URvyUxPu*goCi<$By^;}*(>`g*}~3karfqAh}T z;b)Lbb!{<>hfCowxJ(7^*Gt-Y^44HKMX&;I+D%PJYomP)shJijXYCs`em_s|Lu`}BgvzjMbDN~|^RSVD=lR-GbNDv#bYxewQulOZh%oe=A8Gk^JRt~=^xD0e>6 zU`4nEM#FR{cd2*4(J%wfg1h0@a4(dz{eE~99)MZ!D3qJZ#|*xoE4LU<;87Hwgcad= zC^ykAK)H!_5w?d{VJCPU_JLW3+IT?kmC7SPYa{lNsB8rNH0?f;-yLjaU)_bWuO7e} z@FA=X|AKYk6WA0!hp~_bUnbVnUcx@m=CsBLYIgV@ZUjxEp| z_g1%i8_b7W`c(PV_Jew7udcOSdFHE5e622|Afd9GIKNOMga30!iKmfmf7OG$0tu7N z3sR$g)eFkgNbwE{b$f?dQER-8Ivvx|JUqlEx)fnjbHiZ?SO!*yTw9xsV0qXYR)D== zMK}~jz)`TO3OuA&w(~5qTc8ASi0&ET^!C3eaYyp?a&8=1}e2YhG_#U~z3zU2H-Jl#A-68k$wVrUKjc!wKHQ=y5 z$D?yySHl)KfPkEa&6EV{x^`~^wW|mBw}%ic1vb>FO_N$U0(WVc2qWPrSQAR+ky<$# zcMKc@+rhE$ZFhKQI1YC|I024;6JfGDd@P)Vdn!zYv!%eOT-JjjS%FmBskoQJ>2M8v z4@$wk52fHfgm<9WONV?8ZZEd$V<-=R=EE?!07}Q3n=V#?D(ItyYCc+i)QO9jE=biq zs*mtmRL@l=y{W$*1yeuARLW$ryG)khmNNMgN}0&2tHKqy8^CX%9FgMR3a-R0Ww9Fe zb^G^+Yj7vRb#S8FUnMVCV64&~c8IBW$2FNhb-H4U+Wb;5&_5js|hp zf|rh&l8*n$wf>Qo|+5lXd`r$YOhUIBD znF+}zP)hxdWmNQaYau1R({1y>ZS(N|u;J0SmCh5l&C~zGhG*cG%|C9N7ypM155VP8 zmRH?wozRPVxgK=em^Zk?KE4SM_M7e*ZTEDwCLS^Yzu6grgij+9#u=)~RA%`tBO zcc7;l@|#}G&NJ_&zp)#4_GmDg zg;t<+bP{DD4qq({)kZx~GMa@}pmcN+-AA4#D?^P?JQ{~SLF>^WbPah=A)`}BF_wjR zWTH>desl@>(rlDPaVPL$y(RG!D&0o6sTj2zk$-Cx~KEBASWTqy6X+^5#rj8?{G?XeL^L(oq)D zX0rQG&dj4b9iptczJuKJf_9`kRQ{T)Oj%sHZh+P`9 zUORHnf6u4j&gdl#?kX6c>`;5pydH>MO6g|_C_})q9V+6i9%6@W&*~@a+jpoEf9RcT zrPTO8FyRh_F=D6s@((@SK4NFu!9VmXHv8aaYYX%GUsJhqmPWIpSsE@C)k$>)0H?HXs_ON}b z&~@&T_1LGnUDrEO(rd5lCB3U z2KlIpwZ2~k-F!W?y_D*6lK}4c7=HWJ2RGSaaN|wA|LaW)&cdKN1`YSCW?2}(5m|cs z*QNK17;ulscx%79o5c=;LAP=ljJkzEO$dOoVaimR|MsiUMzA z#=RwD^?ud(HtE0-w{z`3RW(Z+7g*??S*x4tqp6WHd{Pw#t8lgI5c=@Xi&-7|u4c&hJ zs?T?}f@;|_UI=*0?N`(_fz_dBdUY?#)Y`}>mtV2x_^o#PF)t4vO;ElbPKQc-u1871 zt$VJ|aHQsZEkxS#NE(w^6pxb8EVL43ppz&YdD6)ULyb@ul#FJf6(}8LqWj461ME-~ zibIKLCR&EJpiFfC1I82ien^vyVo^LwK?~3(bO>c5$1H46Bh+KohUg&M0;7~|%fiw| z8UD60HrT2z{MV?&2cIk140&T~n9ZoRR z8%BsnSPYH%=k_V;P$`evi=2k9y?cymTaHPkDmsnEY{y6^Gwq!r#*G-Y)M=Ek--t=u z?KBLVeRorJ(9`J1JM+O_Od@y|n;)91W?tC9SA|Gpx|dPYeI#b8U08W@pVP<_>uy^7 zZZTFcZyv+Xo+mafB#+U|W`EXN4a{pLx-~E6=P=LT&TW4DH{K)7>y3H-b}Gc%*l7Q` zy*lA-RJEUoQ-+UG)4rjLYT#ouu+Q$UCi~#Oth?GMyxv{i@G&~t!+WT@`QV@)>Lcj0 zrH3o&AO`Ats|P;p4$u5X9GlcLKbyn{Jd6`P)r|aX5?r0%7;C@KQ8(QitSDprh;orAE&HgYexwF} zDs1GO8ZuS!0vKGvAi**SQG*K@{&pOb3mAp$pY&0S3K$XgrG3=i0>;PWp=&`3>oWEw z`??G3{o52)Xf-3})!emQ^~&GKX`!(VAmBOyEBmR*0Y*(;B|GkCw0OP0^+JT-ApBrI6;X(da}A-)RFeqs zzDYp!{_f0H$?~rp7~qb*D?4wX zT3*;FY;Q5(zs2ZP1Y5=l7{hYe7E_Kswl|wR1smfwHm3%t)kUa8@IU*aN+1S*V(@f; z>K16!40`HLO!6p$AuIZGSxg>%2CCJ8#(Jmge37a81hMvPBJLgN&gr~6%m%wMh@))p z!2hnqt0=a2u+7S`J${Fg(Cv!m+JTeA<}NlJ2f5ShaF_J<6gB*99o5#txyrs=F--4a znw-m&kFnY9Z|cKxvAK`Ug&doCcRAHxEye+MVUT)KjIwApSVaUIt=%6e%~Vr@DGNTb zWV{-zRtFm)c6d+>Twjc#DF`u2Iv--tYKTL9KG?I#>%BgY5bwVTNg0x}*YB}~omb_` zk{(L(kFZ%gL`8%eIWOxm8wdg3e8b5&mlJvUJvMz)C`Ea0hH+I$j54&iYtd*yd z#>E6Rv}CRo{U`x138*q$UC13!t`sT1BB1Z^+&Or_ejZsWSJhe~cK>2G|BW3v`2Xzu zN>dyfJ)u2rJJsPK#qpoC-o?hSVe@#nT36bLusv46#f>(vt4Nh_!tI1djZodfDRcOr zGCwZ{9vDm;p_n5!!Vdpq@O~L`;lSV~Ps^=69Q~L3Ws=v`%~qB~bZo*#s`6!xoEJhf z)hGhI4FcMZbVuIx7u91+*<8)wb&2f6X6Q(jubdGcG}LV?hkU7$T<0OVJJ>BzPL^+u zkLBfv=t;yWiRxgvTy0)pdDiMhz)~LUTUj3eh?C#ZZJuuq$a&ZpJQy~%C90pw=ZfrA zfyj9Y$jpiS{QrwQ1slT~o5zW2b%k7YW+l7@d@WtTRXtkpf2Jk-yT_Z5?!=QDtni`QS>0cy( zXP8D@vbvi)ph{%|3KGyGS#_(NE5;HD@F$>uvf7(Fz$=mf#(WtG$*O8(t{7t^pb!Dc zd?+w?z-0+2Oh8Jq%2Op*j5bvWC_=#WWHmN-z*Y$eBw$vux>AK#m0+H#x!RhZRWS&{ z;7GEXQ8icL9+rTj1UyJqPpVoc(l*uDi^cF7!k7)K3aovWx0H$;pX+3F7#kxPn?J^= zC)JF$obQ@e$BU==##>|6i0W3?Xcu1Ip?Lkus1GZpDbG3E%NtRuZIaC(R&))cq`F_# zaM+u?qlVV7GO!Cj@8U$;#vlztssPJ0GK_BK)wM?XE z=H%{%SZCrbOj$2iS_PzvZZW+%Nio5|ES=aD)mc-{YKGsAS33Ux` z`|0s%6Y3i6J>1_GlPEb?Q!hA>=!ddCo3>Xi-^V;9FX|gv($l=rz<6cz`k}ciu(OK( z%2seuw6Q=sjBvAqu3%c*X2wuY>7f18)>ve(+$*hPJEN*i`c%ET(FtAF-Y84gDeYi; zqovKu)j^VB)Ezo<^%B|9m}#HdSN+t{_|i_Nr`KD?mtI}_xz^XtTAwNw#|r7>Sg9R~ zGs=1$bQ=tHCF1)wiB#{O_SxIU44bWm+7L%^MRmr|)$g!rZbP%PG1GR+6<(?f*?Kx4 zt!)=0+$Q}2EBU!y@y()h(AD^olX~&aq%^J@DY;JMuTx6zX3X?*ow#jUnDYDEV7{jA zMuyGn)nHfV+qgeF*V9O}w;H0>^)!;~DHelNR4=28*IMgTn)C5HwZ50p$jfzlwP~x> z14>$X_cpe8xlW_6{Vw4rr^(OajT82>!_}!{qq?0_$ldoYaYV~bee^=?J44_bNsylrss<4415jN7H8ZKlKro@57YCBRL9B2%*4;`6Sb&%1( z<~7A?L~Sy_`eU|n)?lNUeJPFRV56qjw*Q8`kg&`|6*Ppt(Bs6kjzg$eUQvw2lDb-0 z6<{cbfz?Qh zn80di04>i(!||li>oput+BnN|y?D~D9T88OG0QV-1fDcq4Mwm9vltjA>u&7&e%#y< zMr%8b(}fZ24celJk<@Qj17y>ZTm_gtlIlx?L*3`rMIsKG8p~0A6pmlVsvV;^I%r5N z&y*ypo~sG5X)o3CYfKduHrfcYdsuCNOcl_jGWY7or+qxe=v6s&tlWv_cek#K@pi84 zxh&m+j-hPi;8|4|s*U2&IJ6RFpiFch`Ol%Njk=&j^a)yzE}>_rEVq&yp+qzjZ9&K8 za^v;|3;y#6L|xDl!@*m2agzv zp+=|+NEkf zlz}qQBjo)#89`Af4ke&jXa(AX&Y>5`pF8^1QEF@c3`TN`e=*vGj-f2%SVGaEC=`d1 z(JYjXP9o2xWC*oJ{n1>s5@n+MDC`UB3`#^Z(K56JokQ;5yp{_Wtz?3W%u+u2Rmqh` zuq{?auQa}AR>21=jZ|EtRv9t_!4IprW79%iUS-q*fvb%{wpM9VR&zVZhYDo<nYzSAt zX!te6)_MbkteO{aH-i^pEc{0vptN8?9t5|AKCm4u0z1Hx@GW=*#=$>eCwK#Pf%0-f zH~1X(fKIln7nFg6@vso=3*}{n{xA{_g!0nDVA$AB_J*>+%RgEIY!8RS&Ts_m1*PDn zElI@P$IS${{|K0*&a5@I1w5iEcrK%=phl<*ny&hMYkV=U{hmeZx##yxm0r(YewNl| zz441o%wbJqS$3mQM7}=Xcq9EjICP`Yp0ImA7y;@SVa#EEYom3m&+@AM171<8!w-fv z)lk?Ws@yXCJYtI4tO*5OaVyzoso+g-q9tr1+I;n{%WLN*s^DsMXOnfq5m$g}^dklv zRM#IZFKbn6#B0C$RWuZC$xCA%Y7 zjYu=(m2E3hMjG3jH&~r@`F-&dE3dc(zY@W!*%qS_c9!2_{5;DA%b`G{wEPv9lD)T3 zeD0$0-b$24!K&9kp0)Aoy_MWGSF^Xi$=x}z=oPGPb0*DMdF)SQZ-DCala)QzQ;7*d z5C3Exm-)Bhnx^V+vs|g-`b@3e_IleEr4x6#3QW(58=w-zYm0g}-HKvm`y5`LJKfn{ zxWT)i`Xb%RwH4ZWI}uK+0o&h1NXN_be9m?jw-FmRk% z<@y(wy+DYH*lEb-Tl*_zCmS3Xq87RQj_xEvBy*X*-U8J=gVonkLo(iYrHfZvbt;!v z*RNc+xw+27Y(!5S<)u$<5-u~*+Ub@8Y>Q-!@Q6x`AcQ7ASIkML( zSgXp;B8*p3zuxyIBhSRErSjWvd9~Y5P6w()U8}zQ3vpvuHHUi#jy%% zrFea;b{)udH2WUJZ?!6S&%^CLzzTS-;vsPP_GBtIT?)uN;1B1;7ydsC+pjZwI$ZRUx^=6bnH6*=5Q)<0ZNTxO#$#R<>S9oER$7-OwRXJ)%%&o zG}h~L=1pCSKf{*!msk1DSX<^gg79MowCiWA5(+&_aU4-?&Qh{R)TpyYn(athxj&3A z9JVRyz(u37ZKHaA(Wu9KzBMix4S6+x%q5Ebnp!0oq0V2zBwqPk#$eLms?y7oug=%$Gjk)TI zma$2?K3B2uQxC3U;im$x8Q1Mix-PnIRJ47fDqVlGuT!pLw^}W{&gQIETdx~OxvqNu z26=p@w%#y?@y+PcH;oT%acaX&JpWLaZyFQ*=mEd}m8O;#R>QNbG_9(Tp2gw4nh|2w z;l0b3X7pZ`;Ya$mTSj4z^p4D{SI48(>rG6#MIMf;g|~RtbzJQdo2$8O?*G8{MBT>b znR@#+`Fy6v-)2v@SI2J~gY3_O)JF&TW<=bdTs(5pUOLt@M6LYOi1etzY1o=)_tBp` zZ;QfZ&21T$&7-v#RX^MK+>duLt&5>w%YV^B zyqAl2J5G^(9+K!zm(j|H7@c-SekNAuUH+y1!vB%WKlv~G|8e;*6aNCL!z1#3U;G2r zgU2ivdxU?a_*dYhW_f)gUTs~bS&uM%+vV^782<#9fB(l^I*$&Knqt$6xgI#rmGC*P z@Jobq@*=%g%y_}_B*$34aWzRTal-@_T|t`Nrv z@yLg3PLhLpU?q&xk*l(_e#S$CilM64Gw#JTQEQ*E(w6GXGoziyKx}sUbC)6JIq{Ql zr52NW4$rAj)79+fMiWjT$DeZ$uTJy&+xXp<%Jc|Yz2dIz%Q-a^<HAWknNzf0bzyLT+y7Yxv;K{c& zm&H6NJ!m<4>Eu|$u}GCpq(bNS@78kZ!*u^|sDwva4krLGdaW%hvPyxi#Ec zGLauQV0emhfqQd#b5X6mbgv`Gb$lEo zSdNcFFekIJ50BxN8w4lRDc0dtINY^q71VN^0rV5C%?g3%uq+QRs4CL>HC7!woJD2) zj(32++bjTPVJ4N}Hlt858=%%=mUM)G(oD7OvGRQp%Gj|5XUoz+g<8$lPYptne@s+ifhXr8;C~K_*Wvvk~9OkT5+_F|~wESnS;xB8h z26L~K*F&teazn=28$R6Lk_k$DwDMXht*rXOa8{y6eb}I8G{8oh;zm&N5)Gv>X#z{a z7%2O&8I*#Lh1}lJTEbSa73>Qoul->=+;X;&d0fsxrdBbpLz%~gQ=~PI%fFDBEzCkT zZg@#Vxii%RkM|*Op_;Tf)`TrIC|V!fGz^xVG!6rBbI9{)-{nr{FzNJrI*WP@!&lB6 z395>xv!IthCo}ms#CitQRc6nU0v`=!Ba@*N_*f_f{tlFl90zN_@vt$R09(U}umhC5 zc7&<82g50{TMMc~p3bsfliaK9VBKMCF#{7>?m_SdoDXlorSMO91oE!2$+C7AzJw1U6QF31U?KPv zGLMNh%StQw0(WO9`=u+hY*@3b^o5*{%&E`=GWmry%LIv@E@0Gx!N?4);Qdci7F-uqE!xur1_uG;3BC-N`*_+`O2jb%eao zq`d`s-$v^!v#jt^ipJ-dOkM`jdcu3KH{_)Vtq+t*PWr*xZ~$x#2g6Bl7~Bkp!vk;x zya;)p+`J7(!zVBq)}s$U7Pf=qV0Sp4{ckQ~AqB30vaeP_@y~!$piE*yy)X;rp{E7Q zLz%9nCY0$~CP6+YVZIM#c9xIfTzCb}gE!#E@J~1&%6r8Npv+N{x{w8ryqr*BCny<^ z_lG~l-3Rg}yt&EkzZEXQy&HZ31H4`KL2x;4h5~6{!Le@taqwH*^4hL!;2&<@gBx%= zd^r9$vfxPvW)qb6c{f9ulq3ySgd7289k?AfhdW_!xErp3dtf@;3tz(hur(clgYa8; z2tI*FU|C8U`MFKPS6Q^K~Fdcdclz}FPsFu;d_ua!c6^`1z#3cLqE6~7Jz@k zf>5UF2!MqklN*>3un4RR17Ru*f(i!1&!N;InKU^R_ZCe!7&UU=dhGW?AXW zLRmb%hmydLZvFx*;+C0^E5REu0tR#46bZ}1>TnRO0l$Ow;8|E7K7K_G}sw#fqh{*oDa9dYj7v597=};rodhB z0Q?yi3!|Ze72#f(3irbkvT%@v0>yc&8wSJUFczMGa(Cc2xE1~mGvFC`7;@@1PeR$^ z)9^g*tMDSc?e@=xmvKLbSD{wIWp9Vqai`{I;U)`(;B6QSvtfI97xse;@HL0QzhEMK z1}DMi@LkA|R`YYnP*igjd6J9U90(2s$CuP>FSvx2K?L!h&0G-LHlPWM(xa8lF6O_Og; zhC`LH7zU-JNz2Xj)HU?&GAs|Q>7m+32+0+^5DLZH7m`xke;Q<4HRt- z+zaPI8E7yMo`o_C%`3PNM%ZacU}N|R>;xCX?r;h055IsT;a6}n{2I>W`b+zUh0h^f zSo2G`8gf~qeFwRGvA6}U!M)Q>E*h-aYPd+S=*J#iM|cr8>GE2$)-;40@oxb)!R}DD zybqLJs3)+nIW0KYnb+pCm|`#7(RIB!-x`zE;U{e9lUNhk(5J8_vXPp-6Mv~D8L%bX z2ZzG_Pt%MFM0a?y zJA8uModWF!4VVl$u__-P4m_lIJmD`0|4aHoC>F(|acC}D zi89bR^a%NWMazU@P!BW?%|+|K;^5xTLKf0i(Dfh&>>@`^b9@eO45O;!pybjuxX$Xg|7yo+010Y%GdFJy0@AoyDIOC>@b=n{H?{J*DEP%P??QqU)8JvxN0A#FXShpMC2s6R?U3(%VN zS`+OM3)hgg0Yg+9wMT=I%;2yXZ9>OT7V_Lk$)HB43rgHLFFIVlxa|Cw+n#x&`N*O5 zb)#^nzoGFZ!*bDTX}B}OUM@QANVqf6?tZ!BUv>V4XJOT&oYUK|VfMjbHKLp|+~b46 zd{^k4NBy)*eeyK2DgO%2bM^&;)x!!Tv23s^QPJ7fzH_ijs_3k0-#1u&QxX58gVpJZ z&IF!vH>u<-=WQpsVMAp)3|f3!0q>$}ekG@$eb~^nZz?(S*zEI$s*MpuTRK!-i6FV% zLsiwvBzJhI8d%v`)Ba$XT8i7}#V}VIg{)WpMpfqK+x^N;U%Mkg*(06J?C+0IEhC*d zZ*3;O&uWXcY|LM^&5~?fVi{RiMa0IzD8>X=R(t*TaYhTCDcYGm%fX!UV5XR`ZKm^S589YX`d1<9&rb!T<= zn-?}UiU6mRfHGrTpQ%-^$}-;HrcOx=PXbPiSFfr&%iCf38qSXP$K%!H8f4e?EjSEo zVCaQm#R=+F4YCVM)O5DAcbK3?)TF?=Oi*76w@gr{YdSZQ_WQM*CB5?yrQAe!`7bZX zD4j#KD7JDF)rDHQN~1ckboSoQ|7E#2_Puvx$Dk+L$f=i>Eh3p$s)n+nlzmckL z3w=!$Qa@KU7*(G#;KrK~YP!qdfj>hTeyH#C3(E15!8x0_C@jMD++eC{SyNr8PgR_6 zs)z=;(wfqMOwe&KzBJY924n)BZoo=mo`%$zZ%kFUp|czLUDy!Q0+{xhs&+^ayvvu7 z?enIp5{+p=8#&7dRh^bo(>?s|b7hyz)!0X5i}0Xm=SQTz zDw>V*C(2&8sX8CvU0B_VW}|YvWTWmAGnwAU5Mu8oc4OxVd)4XcgT}cw>U?8X|1O`t zXf$2@Kf2BXK8m9K<5!Zq-8G4nP!d|`5L!TbO(66Dp%>|d5HLXKMIZ-KLN7udN74A2r7cxga42l1#p(IiAfIE)xST`XV6Q#Ij` z*7z*4MCvLou|x(bj$9%uTAQi=vo&2(I9@I<;VaDD?FB*t$}-wjU?0lGX4?{Pn>KDP zQ+T>W4z;D^oJ-|tTN=gkrP8P!C1Wg?sqNey9I4CY7EBzfv?mVvPE7O5&;d_q zPfc36Ql7R)#le*l*})W@*a1)a9ZnaG4=Jp@&w#ykDf=b}o zvBu|l)4x17>`urfk*T~!26fNUx$jmErEsXSM!xRuF7K?e#vyr9jXs%0I=%-IrIDDs zMn3G}j?6yS7mRAUI_W%MHQg6I+zE~)YovEi2DdY7_(~+TF8hb_vM04}*+){hSC;-@ zelL_pqIAbcvZoip?)b)0*A3T@EbK$khb9o2cy${1q#kGEs6H25UB3;+YFMTM+t}I1W zRa9*|v@VlNpw>Xg*Gk<4qV6Bi=O^H?JRVD}lRXKv0r=Yl_fCRc-WR6|IBi%jNBg>? zGZPb>hyzb^T!l7B)kOTjy%XKPIA(8<4*lpja&DCM{oF&*Q6P!Ztcd6|p6r=TqfP;; zLdSRPe^-S?$hayYbAFTTOCovj!zAKpoeF1;)E|MF^kIRUWkCNd740(|g5JPq?#({! ze=6Fm>D&(5Hp0i0||b>$MXI__gKe_kNNneStEuFLQM^%CvTCZgWT;h z)A2+(u#4cjw?zsL&XQF_2IEi*hp}5_>0o!w@UdI}t{{h-vI1$wqJj#tY^yvROd-6t zRSKq<1MZjIa%8|qHVEVOdN@E(m=v2D^}Se9O5 zjdF;=q0u%uJIw7r>d)MFIQdu~hql{%`FOK1J>ci%vsAc=$haCHsam;pkuDI!Ti5z9-lv|^j z6X-j=t}$-zQ|Z1_LdH_y`CbpA6z$S$ERyUWxi0LK8Do*Wu+#g=Sf)vi7_T>RoO^}C zQDl#}Qr&YL7xqYcDoc)(z0%C%zD~0(J`vB&@Z68fv?h`ScVVH!-RPqfuJ@TY$-O5t1+Cv9kK^#UolP;bq8Bbk0m(a5^zHj) z{X2{?|J^TNzr%ti+?SSalkw96KaURh{B$c8R8&5mjGspby3 zrTd6a_ofm=#?*aahSGgR&d$iv&laAE?hbfZb5xqmWSoN$$R}%Nx+`YJ;3iT*9g&)P z%%4FeX(WYaQ5aK?Nu^m?G)|d?#!kpCIVPKDQID1!^Io6jj<;u4q>6LU))|R~$9>wi zDs98&pl#uCnL3B|viZ2|nZqj4U$wK(MQa!QI8I2-xoCwG=elP&YM+o_<}zO2J0W%F zQIATWl#%n?HM95REe}=I)T*6XrR|EWQXd~?WSx&DHdkF^PfGduG!nSOe0;)l6kj_j zN9VhHBU*X^qFoUkbxPVSU=}=zS4R9b-asigAN(hvkoUj>_d>g)_*v<&kc?PoUjD^e zX(7q%hHrxxOUzoos#H)JNu5qPYl|ogtp4W${#2X((&5&f;>-mcgifF&f+dwq6Z$1_&nHB2Bi#69%If0dJbWOYAAOi z6XPQn__7ZKB!Gn&k1Y(M#> z_2I<4RzIb7pZwPZG$FyS#mLL$v=#Q9TCQ+s3$@33dwk+I00K#qCuckg0r#@pxsD+#snvhR@leFyt1y+0>WB}aI39ClZAs%?{I z$K2`cig>?1=3ZdetvwIB?M>P0u(Y-L_Hem)JkLbHcsR5jD;`=Op#a z!FI)p8}4ukI_=J{wk9G^lX?2;R4X=b%lYwIPVt;|pVO^<1G|kwFDiz~Ul7ChJ>C-M zX#8rSKjFOlsBW#|?YzZhdhB@tkJj3p4^LR($6X|Rmf6oQx{s>0^r1`K$lw??$NTLy z#sX*9yL|4ItHkBTSG;7_&Rj*>ZM}TghTd?GbL?2CqFmK+XrcGY4flr*R(;+Hx82;K z!1C>rJMIZi)?nUB_uO^uYK7JETaq{H8+WvWRn^&V+!NFq3Ck{yF7M0wZ{0)Hs;1y~ zm~Xx>W51)g0zUAb{LWp%u9r906LwpQm777|lbhBW!_JM#L$-1CL)Y)!o%C})IiKA* z>>Q3Y68QtlSu(8nfj)y3!pR>f!?|m`gMOqg>&)5B60c}p9?l^RcbtRSdclWyV!{nG zXMBhzrr55Z-JA7N>nsoN$ocQsYB=|^JIL-}u6*keJ_>E{wt4J6WY?{Uuie(nieJ=! z(ZB?E#(&+34(7A!PF4x}mBMDi8u=@h%uh|rjmnal=SgMB1hdi;!i+L!hjv>HD+gXY zaaVTs|Jb?{S>m3u;2iL=xBF9fGrNPS;ridmU1oxj&tN8g>z`32f~v{eooe>cUDt-{)+EDjyJ*$E2f8*+%^3z5+Ed+{8rW@| zbW!zS+-q7V2UCD6uW6h0Kyx%!w;F8yjU=xO(h{5u@A7dRhfX4bwaR*5pTuG-ktxAi zoEoe51#1)35L`DzOJ}6@UJ232S;o!H*);CK$fl*JF%rWJC!?XBV3z`|4OIEdX z=8>p^T5M_>+wv>HE^q_<3bJiuml4E+Brq9dfbHNkxDV6|(s@A?hy`82IIs|G0ms1u z5U|5$ivZO@JCF?Kfwkc94xTC9;D>D|%0P7x4~BzTU^_Ss9)JKZkpj`6Cm0RpfwkZ; zxB*^(&|Pd+fjE!?(!fS=7~BIdK>ppxfVkZ}Q%c}R8dwPqfU7{Ag3JqQgLYsXSO|83 zbKn`s_9^b59T*1|g1z7pcmYE9k{}QdhJ#sPBRC8mfPl|PP%8gLg9I=RtOk3*4e%=n z-N$nv5C;;#EU+3J2X{cwex50TIFJAqf{oxRcmyI25DCx@B!hWiEjSMDfYi`~1OU2% z;b1k`3od~NAm|VQfLPEKj0W?-UT_IK00Ezq5)ch~g3(|x*aEJCM;;!Vz;XP6 zc#s6rz)ElcTs_{7fccT_1PVYCkO0PkE#Nq?oun>+c#s4G<#945LB_K_Jqe!gO_spqjoWk6Y-zR z(j+YwyJf|+a$1YeRp-ZJsfzv!?QnU$xR%S*`+A(SsiYLw0_<13BZ_OM9B7OwrM0pb zk@=;xH|;GHaqnbltx3g)?3}8jzBZswqbpT z_h>LUS)xWe{MQ%Pk;i4VqON*~?am?L<+OqhxMn%czeQ3nIOaENzP&%kxQsdF9a)+?~6dlT*t^9G9gbax?Z2AVY$qlpNL$uzsI zo^`j+gEzDU2P)fCrbB<2S3>$Q8wjYP*3thwDOMMOG~3_TAX`> zxoW8+OR6FG7J{=PWlpNo|2VFW1Xjl(8HaZxrF?bmZ-*huVIU6YBV}n;hnqOK2jOrv zl0vh)YGr0^(;9dgjLUbCQg>pOXl_*wDL6cgl z2q@!Ctf{5j9nZ_i%UarcdmULq~gjkR0$SXt9VQ@3I$>GY;_rUNCcsa64M+ElA%pCJ>QYNG<*rbOq+pUPp5lxv2= z9O>JPNVS)5nrS7W;O1Iedq?TjTx(&^FCRD8%GpcF&E{H}uu?Ux$fMb1&UmTZ29 zW7(DC@l;P*#A_9t^=jGVi=~cMrp9=!lxrMmf4#2EnQE_0KD~D%AQy$%w6!)-=0qV=7zUU+Dwu=zO&ZP5nM~=oYunAyU>0L z6JzGpO@+_52H5L)r*zTUI-IZ9wMpuwz|s=XO$$x6ontr!WkEbh0v@m!>;;#=Gmz~( z^EVI&Qa~Em2o8fg;2Fq&0U6K%GA_=K>7Cx4 z@jLn>-WTn~ZTGdiQ`@6Il0nNHAIhWd+DU(-IM;*n>Hd+dSn4PuK|PVeaCWI9UX@F7 zPpzyyuPo_F^~mcz*i++CXoTp!wQhLt*IO&+O#C?W5}#9;8MJ@zjc^NZ;XV*o1T;UI+CFDQwc)l*sJlA1|c6xvODkFrmeB}snKa`w>@+~04? zB}x4em@E@5t7HAm_&w=w#?RCcHvoYQ={vymvta=9nzcK8^O{vvcqa450HR+>ioS){ z?b7-!rbgRk$XhhiyWS&jX>L1rMVv_{QOOcG(9DIl0}=gHCJw~or?PIK_8qq#%pXL8 zKanGYki0B^4$=nOyUM`9=mW-P)yO%Z72=Dq0Ant)w3UzGegO}7Sei{))XzvhM^@%P7Kq^IFp#| zZ5VAdS4Dp(iN@P$IBDnBgyDbZ*J)*yrmS+yAH&h>%joD4*e{frk!<25kI*V%|K12x zuT)mK)QT=Nmch>~6Loq=c?y%4EHk?RLXMflG%_Plfr-~GwOtTJ{tmUU} z@LQFEY2_KqOl$OHqA*(KEBnco{XHd0{hWeThGo@m3RY`nh_c%5T{lIW>9l|9tukGE zEs(N^nL`wZdFRieE6`i)w<49#+`>qo&+3~jHRBm-?P|nhM}~ejpJ=U|kK#1-yBZm1 zT4h^+)k-P10IQ9bm1lt#mAaiqeHz>Y+9jJU0@McWKoanP46q$s0uO+8895LOx`N3d z0~`QX!3z+2g|!uk2gAWEumv0kkAU_iI=b6MNEq7$n12S_@qm&I8oUQ3h%C+uAF3(29yOdR2F7i-5er@=dxAkYSZu@Q1>2@xI} z@sY7qvu6rqUxq+i1R55Rn#;8E&W1$-<>N_q|C91Mau5l3J0ynTvj3gHTOFBkhn~g<-7I-f!cdsi_7ynZjBP z_JXV65y*C(*%*ihoxpG~3v2|3!F^!+ig5`*U3aEFX>7rgbL`J+{#c z){@!V==*BPj%`{;D0sV8%hALs`}Q#T+_hV)E*rNq6SK*g?HZSa$nV?fxL=oYJ2dN# zqwRFY^L8-BEJ@hr40Kg3o+W+0L(5Lsmv_)#)REwwbjL%bj-rt=a3{TeN!hd$75QJ6 zY`ajA&C6i__%+@^u!k4W0_jiykIrq6U-Ql2e9t&tvUL>0^*Arn;cooKHG&`hWw;xr4-mrp!cNPZcO*N+zt=*B>Nsr^(1DG_BKP>XM0$3 z6Q55h@6WirPHX6>WK+gaS^Oz=<15*k)h=i+QT{ztO6=8QGX*_Za*fuKz1Fz2mmIDl z!JnCfcB{`Y^_20JX}>bfl%Fh9g?*TIO1FKcHfd1 zHY%%*awLmYsRLLokeCCe)Z7E8IU}DP(5gAlVXa_adxne(2^{#7kSSXN&gMj$}`Jp6a8dmcfc9{0}qqnKN69?|k>W5a#*XGjbWW9Lo?R8to->79<^ zV}}emYWmoJ6qS$Ur=w<0RXBzzpL9EB<(o1!k~5a+_2Za^NS))RTdFc;$fo02id8#- z<~>sQL>9Yo*lAbu`6AQ00qZ4o<$GocKf>MdG@lqJ&F!RCCs7+J<4UR~nt9~E8%8=eu{jNqmG_5LM!)m9rzJ}FZnSPB3=9g=VI!fv5&;l8w z=!~4WuDz*;=CR_@*}C~D`YWao1HB`@(!6%+NV%I@KmAacB~r{1*>aQB%C})=w;7gx zi)l!JS?qROElVI?+12}}-AZL=RgX-$N6K!;Kjort^AO-sxNN@7bAoxdNlHH1bep6! zQj{J8Tf_@fo&bV1|10j@CdGuqjacE}ILXl&iVC+H#kE zzLIyxU9C*^R0l<>{;JdKMbYQRg05gRmW7(C9s%t(gB*yy&F*ebevAgI!Cr75*zPc$0kI$jq=8-F9QYLk-9-V2 z2E)NDupOKR&p@`XnJ$5LzylV8!{7$c{zC*oH0bo7SOVwAJg@~E2ls*P9{Zi3Hs}dP zgAA}8Tm_GS_6>?a>^Ix&>_DVHWt=J`#h+?LorNxNxg5t1gkuMq%zMh*$hQaj;wf#l zgyi~7Q{QT8^_y1C5qm*eer{fKx?dTaUyyy4vBEPNWq;}R%#{7>5BjBz&uF&OF39Fj z&6@#DyS%@na*faDNb-j#y5Wexex(o56T z{hwx78#SWx9aor`Q7IfpRNiSGkQtQ-UDxs!4kntuzcZ{VpZr6-qpk-BDv>AN{<@yi z9ykxtJ~GkJTk(d+c||Lv@M}9l4{h#_PEKA=4G5$u&hAq;xi2?78J&HZzH4#SY3& zUKEhx+4Z7O)9m^Q-vFnP7XKo-7?Ca{TXX1qD=mkf%~^t0y?+c>^`+#{quKq!r3_2d zn>qA1o&9mU{UzVYYnM|mWuGQ@bK+}pPJAuG#k}$Ha85lx7jfcJhDZg6>ecjZ7p&E5 zA#0PZXDEIz$aI`&hzCRUGOF=C4AraB>RRVQV{|S(8xiJr87?{;pG$8*b2^wy@8^7Y zkqD@J1Y>g(=nG6{peeZtl$Mhl&uf)Sj!Qn5OUfl&xs+kAu0S5Bv?Z622f1o~xp{ez zt0$Y3KxerI>4VK`sxHtoKjIgWmq^W&ih1=0PA}fn0cx42EO*JOym;F$XY!IHUhK*y;4Ac8jQNLHF{Zb=bpQ(2?>yq6zN3sv&dHkJl{jlS^D{?k3A2>Xa zPtO}xJBXU)6Y^I?CzUly9_Q10q}H@^3Y@ZINK?xdTW$C;To--`$G|~|b9mT1V9cdI z<~Pk7!|F~rbv54`aC0~sj)Pmk!2Hs5OSm6qbrT<(D(V_V&qTO2Jjc$E)`lNkENANo zuYrG6W#-NgHORdV6xKI3%(2YhPm#{yoB!soPgPISeNkSg%dFshY8$M2~L9R z!T9yGfd2!xccgOQo*&(@_zqSlkiUmV!#~1P;Gf{x@Xs)}2bp)LaXifS1T$xi%)8P! zCu4h#IRaL9q!ow%gn4`0_7dhLW_8b>CmOcHyw7TL!tts62;c|r53080=?S~xzOW9b zz@*AE0uF*ba4}b>Yo$G`t&*fj@;Cz(?U&mHe*>#apuUBjYSY8XZ4$5p=F`^Zy2w13X{c}8NvsXR|AoC}@@=Yf~N9JKPh4|CYbvjyg$5^E}23H%FO0=DV223UhR zpyE+STsTSMDFSoq!&3&1f@{DW)9^HgIf~(FpUMwTR(SfrmEj?96JzZelRrd6OdBfN<9Oj*1^Li^@)Ah{6%nP@kC2)86 zBe*BL1Lnn4&*yM&_&l5d--i3bKf#IWrm;Wx@fH>?c6|oIA@E>04?F}e1rLKO!Xw~% z@JP4?JPKCVVvT|O!(-u5@Z0bd*aN={PlA`hli}6yRCouRrfwSB$B!9UoPuY2lGBH13rj3JFKoU$O+SLdqRDz?&DJS5%5tdTuiUmt^afO+3mG58AR;_y{?1bhuX z0)GXwNpIe}^$mOrvz=l0He3JuZX@}g! zqw5SFpTvj}l_lWTQ8=8%p>TZ}8>JU?ze)53M&e^w@!6sWHkvb(%>>g%uDSx2{Mpii^6mCFrS$q$#( zu@qfC85OISbNt*<<_u!VcraGaWB=KEEmm)Aw`)?kk^TmI1??N@@37N(tq~g2l=1DVT z`pA&x#I29aZ?3CH1Mjs~yEV<(ESM(QirJ;t;^{U5Tag?`GuM8>ov>?Ph+Ep@h)b4llT9LveZ3v-*^lyVx2btZ*a@x{_z#k~5xf0lx0Om@$wrFfEzqduO zwG?Qlf5)2%f$dp^H}qC)uQ#=;O&`!`nG=YhdDoye_F3GA%DXYVa*I+Lgya;>wzj6Ke29uS`)A++Cl`yHLx! z6Lzp1?9PrsTPfWGx8u^S2SIn0KYI|7u2P^U>D?xQy>J^OHG1jGG|y1~Mpk>C=>6PF z&u-`1-riQy;(F_>?1stM-tEl%1;n>u2D4pQ&*RJGO&!&C;b1*`nBPi` zj*~0UCq*&srh957n+DU4$HJ*eqThY~gQ z6&jW28;26L$#P^Uc|KXbS58FDbc!2>(;DeJ45u~!bb6qij!NKgoR0p}Y1VL@zLPb| z>AQbAl^uaoh%_9b7j=Y8k{^cBP5T2ot=uZeH_ENT-)@g$h-30d+~Q@*NV>)NNm;wa z2P5?fzE^RWL}m_N5OaH=7XA(0<|3GiWzLfgM&SWP?&h)u@3dK8Qu3nEG!@G5!{+FE|Ve0}~cvbKB z3zRX~`~5=wUAw)jcYL~D%R!sjy;%Q1HOTHu^b6FHic9s2G_$~E`o}Ik<84d-+t!C> z&#fYWJl>f1m4;Dr`2+n&dv5Q+)l?(ie1EbAb{n%-ncZWz zKGzz$R_{a?G;pncO#jehDZeGX+H2ebvrcbfr?M?sPaCFUDLN`OHt4OK-%aG*{n2c7 zuHK+W>midYe}&B_fax2_`3jj<6%+UXN$ZWoB;Gq^Bl(ybQkr7t?`3g|SGz4vp=xwu zj7wcr4_1Rj8Z|1#|cl|dXx0v@m$?ENo`hfDl; z00MqR5L5^8APK0O=2n7T;1YNMv?l}%YJ+wl33xyT*bdHt`yk*c`al$D0+N8bv2G>U z13^;~-a+=gT3J^f zldP4;WE`&5%DVEHWUV|F;c&fH)|JO3neqvf+jJbB@&@lGne*>S@{@8{f&&*H1hsf++2Zp_M?W}W%0qXFp4VwfzoKmuWU;)S6LDKSuv##%XyIOyoemyWw9@P(YF^e}ps~U7f4|TB>3(m_8Kfxk5V<@lmBt<@-12~OaEgCu$km~ zGFTQILjc}+OdsShQl!LjO7Suuex!P`&*X|raY}{Qz-qotgv;^`F0Sjiv`vwa6M9XA zo1Vam%_vt7F6=vjJ~;h^o|YM4@skMLKwxuLxc zXVA@-m}~4%8GDAF2uAlD$Go9RE%%WP^=sU57STJ1CJ&QaXAy;8p4F>5lZQDaUtD0T zyw=@8s_6VpXf!2H>8lC$4l(0_2MY&6fzJh(`8C+l8b z)a&a#Qk-VfYh|s}yI#^e>6?9a?JT=<*pVCF$jkazyG}|?4{6pbM+dIZkj4)6Hv3XJ z5=qmMY0vvKy*pR+w5C_7cMm`S&kc)#+Mp9i0cl_**agmkd*B5K{fkNrnt+~Q99Ssx zujx6RK{osRm>TKV^$6D~@*w;zDRG@_f~mbdWX*N`b4UHRWWZNcrjp5W{VUd(HIpUe zhOVxoeESAFUZ?RlGFjH&(EXP)o|12Fknd-37?12ty-2?C$to#US0BNqR1(OIIX&5_ zK6)4~o0_;^llWM@gzx>|Q?mRfI?kfw<77E{Q}>_CIwkroy=bm4aMC{1#9SViMg%&F9$g# zV{Yq3OI|>%&_FBlwzho-CA4W^j#nPWs{24qk8oGFky*F0_+Hvox#_P_vycgY%Nuz| zUto8TRr~JhRdp*z)LDOX*CpH6^nRqY``2{7dy{3x*Lr;i5kLDivc%7<2&Jr(b`k&4 z6C8yGdZ+$JUvIBh45#WK9wdNqU?JEDj)Obk8OX*?a#;`yx`N?gmYw3CpZ+a-oYi?z zb^(VF|7vZ2!P_44sW&{RaOJ!zlfEax@aFIJ4vy%n;`%{P zabL_IgxWqb{s(#lo@BVvu5qkAc8&WE*!)^_P3rzgjofn0JM>4rh~07R zD@lK#cW1lg$pgxG4rz+KDFuH*2F`LlXCGPjlU_84ha;}(H`NJqUU3=Ui-qFPKk5G4 zym+JIAxioov;3wsdZ_y^cIzXHlmm6xwc@7idr0>NfBR5RcdWcA6Mm*M>m%2GChGkW z`Qavq^VNyko{#iU_W*3PTMp}e#*9bI=#=S;guubR{;j_hevHq#M7`A4)(s$G)_$+b zRezQ0NrY9-{#;Avx~a$1ot#&_FCXi?*qwIGd+5J9S67hY0Z*wtRs!v|P;0%l_o<%W zxtvIuZ$4kUxgU@bTRt~%x6 zA8hS5BrAf$UOf={f=uG!t*h~?E=QD0V_Xtmbt(NPE=_P*_NvQlT!Ne8@@tsyAg~l} z=PZ|buJbYOu4cH?M})tmgM@3oWYX(9-z&3UBG4Rx#Bka9GPAR)Bfl$$I2@*iOOe0y z63(gNfl??Zd#?$9>A&Rt_xWHo`~-(B8e~jxG!Ek^XG=#ynAEi!iB1*kPdl+>JYY9c zoWxY-I@$M&a~RoFe7ZY~L_IOwI*S=$y$Ev$H=Pj8GP`N5PJ^6AN^}2|FJae?Oe5nvQ!Pqlb}QONmn8lMkc7qC@=9`m@O zb`LGc8xd$kW}dn3=`!-NGc?9!6lGDo++{2aV2`!NYeoh8Bya!M4A#icWqFXHj%5}I zHtO+7*lvnu%kp4jn*E#<4>3wYEkcYTYX9Rvh*6fXe+n_wYjPD{H_F-nl5VdXWuWP= z8=tc8*)SVg7s{Ay#!Oyn56o`7qn%r*YB7zz@I=1a{y}ylJ1Tc%H%>8`o0!8`WJmRwRFSZli)m$ln($2y#=7 zZhG$NX3y<@N*|LthB@qgy?|5w_*d6m+9>V%4XJHoWKwA((gANSZRFPP@O)V1Xc3vX zpWA`%ls4-6y78w{JkluYdWI*@SZNt)6mh^qBMmND94m=sj1TQkCAh3n)crdmizhgx z@k5=fZEb1{cq&tHaXrUn$poIX86_O>m9j>G7UL*8eiTB zb-%#End-Fq+F9j|Ag3~A>1+9VZv}$oT@Ke<6P@N+cVAzt@*!(qtFprEYgbk<;z+ai zVFiOrfjncqMJgI4>`oPHvp-F!M2lN8!5Xi9{pq|)#zF@%yVc*(oN}=_Q@tbKFs|Em z0ySG^EqS~tAdjR}F{(GK#Kxrhiv~?7ovvUwSO_+P!{7!8&}gxsI*12Jzynr;z2K52 zzf>{GyFMo+=Q>M?szyQQxz1S%bZ0d~vpcSI7Na_y%&(oLOLe0sO~||%;aqj{?=W6# zcX7(c+?9}C!w7QJ?jj*IjC4nfF7jawqmrY07Y?(-iP+aPM%q7@DK#kwo}atwca_aG zDJ=L(P2-_scvm@E%Sd#5&{fLUHYx?bn7>AJGOO` zleLYij-(#qsAF_Tb+0<8K8otJ9x|g2s?&OSKdEEXr?JbRBOxfizM$w?-$o|DZYxWHX zlY%1TK@8pNUwynUV~hcIM^J(cXh2X$5@dzqs|j*J@z)9BiZz-!eov4#v6$=km8r3) zZ{JsT#u|x4r9eZXasu@Q60It_x}g#3;)MZMtwh<^5Lx)_+JF?_n4m=cHSho#MH!B4 zWE`aoymcE><;YoYViUt~sC*dO%*gFfiJK8;a4?MMUTI;xv^!K-aeSsZBHjo>^HlSo-dp|{FwG9Zzn zg_kB8{^#%IMej#ltBAmHzD#D;wXFjOfvinr1G*`IlPa<*dX~D2hHkA%Lj1Nn=5yY%{npn{qaVjYi5wN z>~9owDf^j0-l6@CMh?fJ5ZUvVF~HF$o0LeV9j?zQ-4*W-mGoqzrsK8Tav|Ah6RGl7 zRnwZb$m~kz)tr`Q-(HPrsEkbC+){IpQ81(|?yG@v$1ZV@QA#R>JIeY-O24|QK6RYZ z9c1KmRYAl0-15U9BRtm)e8-1c8rJ9bm4k#0HVQK!?;mI{6J<@R{HhxHRMpO9#cYN} z=Kmj&Nf&Z+iL6m1k9zE(b|TZzts$%AF63q}FUs92%AbQ)V(a=;ZtP zP*RN8ivRTG&!UZL;mhAri_HJ4;VUIifP5M4E?5GsqmfbW*qQZ1MeGsw!?9mz*-O3{ z_v|QtD*ej0Chq^Mj&dWfucG;{;tdShg069hD^Vk_JRD-Q40(XvXzZ%uH!`m@ z8)~#E;}61LChhWCit}X&q6R_a2n&$ZSbJEAy7@l>AtjI_Odbw3;wt{LO#G^n!Yozi z{85E#qN-eYfPCQz3@gzIHI)%k0$66|#XRhzus>L}}eN`GwqWpu+Agl||i z17hFP^=G(D7;eN?{bw2ZeZ_~Hg60&&`o&fYzRKqFWn+s$EEZoMVU&EOYWT|`e?H6G zM!#>Eom5x#e3CeVcF>Lh?gQnH-NRW%%KxKjmQPdnESh)$*mW)+82v9_{?f@-(DLQ$YfJ+#vA7}%$k@?F zk&q;`-T=xSyY-`uxT^oGfc|1KKRAX|*0jc=>5T%u%&M58?tK|!l<++$eYJZ1D%quoO0^P~g?%67cGl4gHL)Goq|u=)ag=3gWHw<#dTSR*pz8L5jvM!92G zf2^@0B)SmKrm$0)e7vAM97~F_ z-B*HU7){ZBr;rpJ|E~h~_Y)6%zJjyFsTsar7LxSwM(tNJ+F!U`i(29_S$y$%OV?`= z;+SAW|36LtoX;1@$^47MS6qZI0}BkL>Cc_;ucq(Mz=i4+PyW8J$o#(r3I;~Vw-d;~ zO9app8Rd>$?o=b;mC?_i0PYA$W%O%_=h}s3ed@m&pI>me@1bqhLT`nyq{0&J`Ij$$ zM2nTMV%Q=}M0pP9x>#6dc!=m|v_1mL9Xs0qVn~`e-)(P*G8YO zti{g>30L!?zW8hX{!j|R#8 z`9f^u->%1i!DEIEC%=8UuCjI|VFck<`9oHP)A;|XOj~?G zWUWkH2;zrg(qZcVTbVkQwIa6MBJ=+@@ntLS%lL^Ss7$w~8i66(37{C_rf6|B`fw}m zwEwqqANOg_Is|q_^YY>{XxhKpuD?gzTh5Be?kw@?hOg7bxs=@q4>^t2G-Q-JcCIv| zen?JWri`;)SsdBqw8WR88Fl6@UJ?#*tZ|uGBW|3Jt7I& zO3M#3nR;Ete*!Yf9lPAKjHFkpN=sj6jILy<@Mh7}6HVPqa|66lDI^0evB)TQ?Ec3j z&Y!K%e42c9&(zloO}V&?aJCWu{|sPxD_a5k$TalES9GL=%poN&(0cC;X2`f;S91qA7-muMlQ@VmSz@}zdQTY7m-?- z(V%FE$ou6aeZCRV%R1uP?rCmJ?%vQKZ~6w9Z0Cx!+`qfcj&OI@PgD z0}}!{aOkryD7}8;*=q6vqh^$KRiwWQ^jCuI)vYid_=AEI39U|5xw3#ta2SmqWRyF0 zx!*M=zfzt2o`PUCkrK`!wcggl$Xo*8cxnsv-zo3LJG>S^Ac}AdInq-gc z^v_?K8B0%J82pI`v2Clm=3E>-^-PuzHJ<}KjYuTDn_@% z?o8Em<6d5SQ*XYHjfSu3Y{?Kq^ET@`T>L(654)>u!kpY=Oycdj7M~h_IMn7zvwb|< zu=YySnb9o=`H+nl#IYwj~W#?!TOqb(%4D()}hfQhQIG7cIZ9GheZ<_!!Yqh1q zOmS=;cmzBV9uH4~SHbVVe2v>S89oC~fiJ^T;osqDu$|hN#vxr#aehq4q8vN}ZVk_b zJHtFe_Kb&T!|JRgr+Pi>;Q6pR6ZtND31-dUc@7I)h7>P>Yr{+7-ta1TEW8??46lI~ z!|VABv4;Y*ZNOp|ya_%FZ-ei_J7A}q4jj%2?}62kMRhi+u+JO`@5R0iybqq{v!4em zxs~ui>_3D*hd04T;cwyNDl3apC}-fx@E34vm;>paZZOA^JsGf4v;w}0`6B!kT#)j- z373HHz|G*V;WqGp;4bieI1&BcfQ7N9lk6*ChOWP)=!^(a!{G4L` z0R9#CP4E-%qQgc--ZhnDM~q%l`KYniRhtUMuGacvMiKpYo}QJ&?2!4#j64puuS{#& z!!%_bqO5be+VPVesE5al@UYwtnXn!?iGr&%6Y# zEmck!Z>CyXR6G|Z9V+fBZV_hpWgSMQ7TOx(H3V)1zYaHnBVeVvh|gRaZic-YvEtzR zusXD?#(O32k9u#+tuYUP+d6D5J#X_vonD>~D}}0i=!E%wxHG&BR;QZJz}?{6usYQI z1Xl7-VRfjPr!%%h>2}iSm&%@)P4#bTD@>&+JGctepE}n}&9@DORa%F^D&L30F|az% z+y-V)H9u%Q7FN|l9b;Yrt7FW&U=Mr(R>zpH!|M3*kMIe*mG%vggWe+a9%u7g{^8{v3( z6RhIC1y=dH9rnOG;CZkYR%zJfu$A|0=Z889y&paRpM+I@o`w%$R{5>WU%-c@+i9bt z{-?PYXt!06iN^wS7FGwNU&HkTtg`qdTogVHmxs^FiUmMCHmgSmg|_N|;}vS4XIqVO9}SGyOZ5Rf-g^^Vx5J z@5-7pMg{$zPiuGc;|VpsLn;W@A7Pb$N=pO9m}7n1%4gpi{u%pj@FOXG)+nP}dwF(S zRZH7bT$Q%xaG1|mKKLc({61EFjtWJ!j=!*HcE&KV4sFiS`2);vTBK@D)k9dl$y%Jp zm|KQCVdl5W0~JOFP=7(l2E!q+3R4~RR=r0yI10`Vs~VC6ZVaoio4~m-t4=Qu+!M|V zzXgZ!=*TmQANgd&7e+1pu`lcj=4U*ztApUVaV-q15-lP(zo1uTckkA9y3P_ZZ zpXeg<6Bns95K&dF7Oe8Pw$E!lSXI3kScT94&RUXfunF z3KNClu)oZkVjhjTFRX&-2fvLu$!Au*!#G)ffm+?Bkkwhvv09!7Db@E(f>q6$46D9p z3fuyo4yVCN>kL?(E1&5z&xU79@r$&)J3g(Pcj9|6+2ro3#g|~OYLGgW9&9U~Sp`&`eJ#R@V2nJzXM{!|p=!WNI09DjP^n*yIU43><4Z;% zM_h!Izhs2#>wRJyr1d2uXX-$oF4d{2wiOCq0QIL%uB+O-1rCO{!YU`!0e01oR*H^DY|!#Z}U;`TTtatEO`UPJnq8*i6Q4DSX8!s$cYl+QRDdzrj`c{tk|WzlSTr zKfrPDk23L!QAoFTAMLhWa(8P$&eX@as*d5ma6$N2xGc;IA8HY2VSD$#T>|Z z@x;thl_nLZmzY)a{R^G|+XJkub-?MEov@lO1i+hN);DI3y5SpYWo7W=84f)7HShWf zmKI+c9UW|CmjB8KFPI(cTsY@|gIU=7yW`Q=H80BLc}92*9_5+&&D_FM40{!~5->xI zr=*W7`Rpsh^rU8mEFcxH8f6@_ic0sZMtD=Q)0_tug_U;}HfHT&JI3=S=2Ea4bCmiX za3p5cK`VPTRZ^S^my?56jW={_3({_@X7vR;SvDid64Vopl+vR5NgnT+?M`tipS>!+ zT9~WCwWaAb`ho_BW~$~$swb>w2z_7` z#{{?#%+`dNzlpN@I@SNnV%Cr~0BaY{Z^0^Q$*`)K110-cMm`7Ik*Y%IL$FpAVyLwK zif+T&Z?v16i>mf3pBX^?jYL%0je>P}jL+*>SY_7RaJ~Pd>wDm$tg^6Y3=Ev1L`6X* zLB+(x804>t0zoS#C7ZO;N-@Zo6euVdY|_B4w9-mJNmoh=T4{BYR(2(&q@a~nS}EC; zk_}2qS}7?hX{D9=p8KA2hnM}nuV0VPd+s^+|GDSh_nmhJ@GkKEVBD!{TkqrGLdbUT z)8Ha-CAb(Y%lS5NWz$CE6s)o>Mgs>R-nzXa#?1oX1}--6{N>;cO?8b40n zGijFV8MbcH{%)JS3|iUBr@*q6<>1NSXTZ`yo(0RnuLOsIp99OI(SC3u_<68&#{*z_ zaHs}Lw|o)&8*mL+fNR08fPW8`G43Gvg#3Z1I$`X^v6r4`8nwrlvOUXyQxotH{=+@H zcG`FqEJJ!dcqv%AR|v~7;6EW7(M~x7ugM; zf=`1#1D^q31b+hV2VVhy3C10@;VbZez=L2HjPf_q*(T%S3V145w$KZVp(&aVz6uTm ze-FkDqo!X0{sHpcEXzlWQhoq@9sDrMxRcWCp9KGebT_=u;Eu;?iwr9;M)IYz1qQM9 z(@8z9ll{q)@1{NF24`B6PGA|dCW7V8bt72Lv#YROz@G8|=Q^(aeKw05w97;@^mnMi%Z)b7J=oeybUZvqqGZPJL%Jb zqN#7v(g}FZ`*k0lE(ALpo{-CK1iOz6UIqrEHG$XeqbIb1i-CHfur#o|-QEP29-R)31>3+j@Mf?)_dW#1V>H7S@N?h{@Nql_ zGdzrow~_D&_yRZ+jHgG2EU+s)YAe_sjNdTRe)KLIybN*<7>@@G+rfAYVAuiP4bBDc z1@8nu4}KJU2#nu8D|#JV0Dc$zD{yx@E_UJK3oxEj7vTmGzh;ILKDZeCE%-NJ+}auN zAh76$8}Kv{JQ2JHjN315NO7B`4XH2qcSy&Lkzp@509+;pKA-fH>&pS;Ps_>oE1-45 zI6e!W2bSY6PZt8Rbc8D5*FR~FogSzgwTJ7{={HI^;UD~04O1D)Ujj=h_$hqJ~a5?yOFrG+i72wIE;RNKrgWmxE8~i31zvQRsXM&p{<8hhcZSYEP z3pi8LBW&j2;vFR5xs2fyxDwn3{;Ov2V-X%k82$$NEVvzf8T=l2CWc=2a5nf1dPhI`}I1hKYDg3YI^<_aAU9cm#|uN*I0sKLmzt5&o3D;YaYZ z;Ge*M0vjh{xr0$g(Z^sX@P8&EK1{^LYy>_R@I0_9coog0QLZ11 z>%q&wZ-SSDWz54L{X$!oVpEIIPG$FeIVr-`KaAQGpxx*$ikWEGy#TiODvWlAgD<`y z&&>umgO}s3;v)3;@aO$65%}>Xm6I4}!;`R+eZiz?cXRj>m6pF89E5bd^{d^6?*m6c zt_1%KEWqo*_&7m3hdmFLr^y50=fE$5tHCwkqu}3z8xYrt$gOAQ7#0NFq}a0oaH zTmoDWvV4HmKq{~Yr~ys^J%GU-6#-Ge24FXE05}Eoxa0E>rzxlehy^wR`9L{v6gUlB z2Ar_vEd-)~R3IPN4;%%~0ha;uG^1fY5DRPsb^-fO!zb3UB6hlIIEd8HYkN7b61)F}xDz`N2G0boYhV23ul%3vI+7Q#$a&HCpqaO;(jbhnVyA(E7^LSIIc%yyP+K`Qz{0J5f9)Pbu`Qao{Rx)2oYHbBxDRxNr-xUomk=9I>kpaWhwF`!C7;UlZG81t_nvk2nJdL@77DLEMZ(1=auy*-;tsW#}z5JBXCIe-^&@Yh({2CWqMyHapW*@N-J?E;)K*U^3eMtE=alh zX43n<$aZ%Shun<*OM~Q6O33;raqaiSg9xQkUxFYaIqo)+t2>BGag>wk8SfH1vv=cJ zftFr;jdn4Pa5x1F*;_fTTrKNA-sRi+QUO7hTC#3Qc|7oQ{U zI!o+3k$7~3cz_!ifVd;eIlP3@?Oq?#MKiZ3zK!Gp7vhqMl)=(YavTDWEMPd2wKS4ZF%iKpC(Lh|tA#)TV zQ`#TqDTsWSWWS5VZ9~L4PZCG+NT%>|>)=)5!JAxwoxOM_kE1ykne~S zI6@k6Vv-FR{2is&a)fMVU-141rMnIjx9%eDKSS)Xkk}soJzY3A5)beYHZuG2@)_ji z*T4}hj-9WU^A&$g`7^k@=66VLvnCS{W2ChGzvG{j(6@@%?H1xV z4wP`cLX*J9geOj);Ty*GW;$kuBo@$-|q8 zn>Yg2T_@Rc7wcalcH{Nj8clM-e>t6(Z}L2nLvo3$I3hN41MHV!sWLQ+mfrVjJgg`krLtKZz|;M*RjW52cYqrG-Oe z^wbsEX84y>(zKV+8$bpAjU zto`ibHv88#Qi*C$;_kdoFlwSEXT+$tCqN~jMu-Fouun=Qq&i6 zf!y?3^~7aExlN0Gi^1#x9CvBy%3zwG%y5V0$BX8_4{ z%*BgI9=wgX_EzEsU*d>4#7(n^%b2aqAP zcMy;7w03s@zxQBQK zt@XHiggEbS#Ep2mB4;d4%YaYRMk&4Ozr+oE0xMzm`i9b-e?{zZfOzC5;(E@XEbURh zA%HVBJ;oV$`)_C`xfM@lWCM(WBq#AQPv|7M?l;7F%+9k&E?q?I%v(s8E6M&#iTl-R zEXAW6S;1j;(nxmdVs_pPSvlabir6@t_;4t3vYHCs!-mi+Y2WlCaRN6WfOq5Qn<#xq zj=wat5hc2s@=c z;2}yF;Js-04w7@O6Wi`0?q_F;KST0RG;!o=Vvl*mO;?HQJ|!OfH*rD}vHJ{`U)0!c z@Z#;giCOTjKV&I3sW8g})=&eJgP_dvlIjhOLxd!6RwiMRLST#J#-Pj_^p;RUjSp z8!Z1M1LyCF{r^fF%^6a7H!Ulrbos#<{x^j1kcK#sY-uC5a%i?DlI-;!aifK}jd$;U z_=vU}2e6_1U`!TV%neEA2J~`~ z?Ofm}dvPg;#zvmw+Ak?%NDgrwN65Y~lD&F}lb$5Dy-gf&nYfxGVqFBuejGttIRe^8 z_L8FeRpJ4Te8V@BoXC-{(n@l36mbU6X%3HAAFr0^7}7iQP*-mxxi6nM@;vbXMMArw zpZDpyWu&O)Q0mJOtbik88%M-Zcd{$xh*-=$&EcW8{EGC=++z!$QTw?e$rYsUTPGRo z&wD#1SUJ>Mc{gnOgwjV}Bd$13>@|(kUmz~D5&LuCioQ;A7av>_KV&_ROg%gC@CBsH z^>2KG46>#ZyS_-=@ilSCdg6fw;v{9yBhvO6rAPmnxcN=ueh#(0FOlq*LF^SsEWZS! zt^e+el+eqeGn$>IyOh!^UM9{7BDS(T#C9Isz~Zx{kGM+g+d>?PPwiw}iRTDfpGoP% z{k;DD4^u+hKZxVrA@1X6PL^FHr|`1Ldxq^76E`FfH}?|{9U_k3NgU04fra;)M4p=7 ziM;-kc;6o4k;wR%GB*B`*o(Q014k(jbtw;R#N%91A#viP#Qod=|E(lPMiEzAh)3-K zbP;kZamOvh9$v(?91rmA1#Jiuc&HDvGx~>9x`i8zm&rA|oc|Da|CP9uKbNTF21a*K zy1kIrp}}8U4%$mFS^>`Ql0gGLqm*-3$#a*(6*Lr)KA8hmeI>~w4-y-BB!}-IIfH#; zh#NF;Kufn9>Nb;s$Bo1Vyk4D8lN`r$-p?Zy{Vz%%Sw&n4FP05Ve2+MRPs>%jhYa(> zHveC<9=6iHTdUWO*LQYPLfc7Z_SSmd^+I^pE9DSdhdi=?2wumfCXy3^iTwvy=6voP zPeORkOIDJ8)D4WX40+s>+F7Is2_;TkLF~pAHSua_D&zDG#DnvRyRH#e^S0gLLvjKQ zwZZr|wmZj+y+vF9ojH`?>P>t&jJWgzVsCC(28Y^|TuRU35bM5+$c@Amyo?9; zkQ~4buX~l`#=r3T_nS-!9{Y(qt;B;-#8o^Jhx17;I8SWh<<;~9$=%C{ZSKU;>})CZ zB-is^Qo)fkehSZJ{PScmyouOrI&p;yasMBQL;g)1!E&TO$@RQ?I{HZN;MH=N?Xoyu z4$A{vzPo*dG7Nn}+|HYgKd9Jygc-4v?tYzkbPchM?;%STknGE= zWQ0dBC5F=Nee7JLzLa3SgShf2acdKCHMh9An&hsBhzsTt`?9kczae?_UgByFz1@nV zDc$vRjqL_k4yC@ANKyDEv9~92?MuWd8N`RbC9Z2`E+tNSgxH${R`gzyYo`!5a{zL_ zN^Li zdvj=xSLgr!KvKB!vM?Sa8Q&MDmaZc1;7B+ULUQu^#Dg5!I(|X2Kl@V2YLb(fn|W$| z*(Va^^A9-`L(h_7^*LhquUO`uM0%545Jud@p}FBhlD%_@BRM3uv-5g9L+Qi6ByRqW zxR)cOy@HoX9QU~7W-{m&#BOQCeSatRiYBgno4EZC#1XuFb2z}XenjckovdF*oby}a zh8~UWh5(Mu{T!QJpCW*whxpzxj-9rQBkAaIvX7WbT=oL7 zo7(?99-xFe4yFD7CApt7RI*Pb{EX78=Mv{!AhvO&%&R8ZZ3}S%m)rUj$rWzIk)IKF zVi{=bKZ%Df;v^{wXAtMSL|n;{ukj(0dmkZo=KK5%UM1FxoR6I=k0WCl+j}LDzBH7$ z7E`3H|2*ztAy?qV5wL*c!oXU}P{z*Y!J)K^ovEUQ^sOq!KS{D%7V#)|DES{GS91jQ zKF{ml`a4oI@+U2wWh5t=i2d1Hn?EMm`9H*or-_B-aC>WrhIukmDLkT zPO<+$7p13(yLe9P+1vdVQM#)u@i6b}5gZB2A}QUR)_ii~r_5gfUyXOkQkMqIFqIFFssjU!!sC#74TCyr;kRt`jM9N@e-z%_Azs}|B8 z^B<9kl`<>l3>mNf^iX1@Dv;=mPx zz@@GK$Tz5?!m3=Ca16AF3WS_)=%9)RR zwNGOF;lPH-EaD1|P#HXg1@BOLEgvk3uafM=BQ_FC@&J2v=l3Lga6{sGSq`yNW_6Ih z?O()Qc3w7B%=Pm~5#UVRe2qBqUE%^h(SS;3W#5RrNOs9S#C~@W4{{{+;sDpp z0mvTk0~sW80CM9q+yJ*QkLNsr15g_WpyKx^p9de!S~(CE^N6&wFH|xoaK#Ng_wCdX zyCITW*0hugY~#Sw&S$i44m^1rcshCL+c*GWAhap0TSc5Vi@22oQPp9RjV{Faqehy2 zt#(_E`M0t`=Z~bQ_!V&g550Rf%PGW>=ZKv-P<72F*)5FNl^;0tv9k@%r1XdniK}y& z{|QF@2BR+}WN`(qMI0OgzF7uwy65NgIg^1nYVIck&2FGbj4< z`merBhJ6c&-PaL&{E5>!0QGZ2+QKQlm*YUz8j|IAljLgZPb7BZhV-9cnVm6VEyN#dWtYT5W#ku{toM?k?+)Tb4mg%Ul5MC?R%rW%P;4z_Q;QKn;_ zB6zMUIJA~trwp!Fh`V{nM|cXd_(bGULHeX4#716jiM&^I{f5#99wn~wA;wSdXin?; z5g2tFBH8QfcrN|8z<3^s!5YfY{5WwvH*EMml1CR2x3Lpe6_FhO6LB~DL_#vjhxvg; z97aOh|0_9?MRE@c*$GFvA}=1ws$Ww9P36RvUlI>YCT*Z#s-p$ z8+h*HIWpN^Bt;*$IR0-W=kYQe7$!NAveyhNg zdo*XvSxr~IARxJP3= z|6{Mt;~{L|&7}D@GA#BYcDtFlWRN(Xxs9hHWHF^zuO%+ykL{xul3X>PxPUukydY)F zfB!5}F1(Vr7%4H5gL5j#_Tc0*e_ zB~M7Kx6Q`ozg8l#ok(dnE#B$ ztVkekyoI>HOq|03#5$kkjt=6ozY*iFC22m?{U724KD?&9L$W2BIGM}w=8^T2PL28v zR*qEt?1Z%(Fd9oJV+oIprIO_biTgJYHytL9;CNu=cwoE6cHHy4dXnpIB<{tnleYc~ z_&$GNE-B)ii8DA*H1gaR6j6HZkHpqr5qtAUg`hKXH8ra5BTOT?pI41Dmz%_KBJpuv z|0x_OJlIJ}enA-{^N3T95xW)=yZ@fJpBs|=G|5Td5;vYBj_V@s;8oVo9Vq4oR^Nf~ zmo3iY5Zk<-f<41>m z3mKGg0C77)vNyMQhyzA~8>L5bj|aXd*_9h!no4pV&#`42$!^?{5RNOA99QBvuGkxQ zkYRlcv2zBoD?3{odu!DiO85RbaR7UB0#|JPl+rCc60I+joUxy{kK@D$SKLP(wHs%mPeou4bs+sRxcTL zc@l>N5f5`uM>xXOafD0$7wPN#iK{*#_BuqI!vSoV16U#lupFMEga^rP=t*Ax{oJB} zFGw-SLpWq1IoV1)z>(`PKmGFO9v}XO^a1mT`?85MZszo#hzEK3x$|mhUWW0P>pyZb zu^Y2L-%fY))2)K1NFTz>vg1~gt!CoFVB*diPA?{IeucQCn>gV+;^JE3GW+9n5x@~J znj>H&M?mQyvVqlHa4{Dc#}Uw4MEc5P;>PL3{T{>t{J1WGd+chWbk{CoyEktdzI?VT zTSAHkj(kZR`P|S9*^n}hfO#ANOFGEjpShbuwD0qjUdIjg;-RFtJLZh77& zu6RDN-)iFe6U1J8TYb2N_8blpcQ%apPs;$oq*$IiQVflQM?aBasw& zJk;G&NN!_qwLL^~s~@p#GqLX+;!fU7%6?9A6R#dWUy@zFCeB(`HjVB6xYnw^O<+Pl0znum6VI zNf9?n+{OW;frl#YIZCg$5;w84);h6IoTT)2UVcU{$GDdBaf1gqeL7xxWua~^RqKblScoaFdJJm(R= zrG!d;@u2%zl0zOKcIScv_^8$>D7}n(=F59V?VmYcD)I0NVsBpegWr+Qr;^(?jhO8PTuYWS+4(KFH*E^BR;&9 zxPc3*<^WVXlhU2}V|FW_6N)*6yRi?Ia47ffC;O_8iTnRa9M9bRcV7QZJfux8kwM1e z#5sk;#g7tuFeh^Z2eT+WD~h1L?f~HBg8}h!T1|71=VMWeM^Zu zSoV8|E+wvIZsdsAb|0m8v5(|&{_ZA9cl!mgz2bAaC^$si@fdL(N5m9% zD(8KaKAJ+Dz}s>XN5E2+lQ|M5-b{7@9Dw{HNFG{7>=&uA-QdhUDPd=7=UvLiEp6iT z0Nxe--=_k~;5~Bc`f7=rc`E%lZuni{bPhbjJY@~P=X^g&Mke2N4ZC> zTS=~v>lGC?ze-%sb}2n1mvCI@;3@Fsxo-Xq>HD50?oB4Hkoi!*A&E1Va>2D#WZ>}! z;sOptDbH}mFycavfC=nF?VQj3Ueb>S6L)d>jR#2X+fH1ERimB%18$^*Djv#SC}dA9 z?4|V_$(#o%J%QJE{XHc6abPOskt$52^g7-xv$(u=F8?q;nrW0j2PZ4)@SqHl)x_}$ z#ML}^_5UTgb2V`vuadGrl8fgMXK*|i;Rzm&^ssv*0>+>v(Kf7yWE^`vlS=jn_i zxnU=9fERHz#|L+Rk|TI-M^j1e?jmkuIb{aPA)dsQs7%%up^j$uT1qIrK-@W(*v0`Q zgO5;E+<;=9LubzC#|;PGF~XY8&J;;sO2-7+wGL0 z)S1}5jd+xu%l90~{yfB${Nh3g&wWG-=}Y*yT^vHP$4TawC1d^h0&-3UdB~GEaAa`^ z9pHcwUrcrlKM`A>BJS8goOqQu`WE8eaN?nf#3?-VaSxH4R0l@g248j}|8i2)-%mWq zn~ED}u=4sY<-H;P4`kGYbv4^}J<8;zHbDStqay+FMuO)7uLma~KppAVZi+9NZ4&7aYJolCG0OAJ2aQ~y z2aik!FGJT-ZV3B83Wwy{)0AGq&YH#RJY_GXkFXtnR#dC6%I-%O0X%nBUjLQsj3L~B zJhjdKmh9s=Ul|X%``whDawqX%D{(E~Xw-55ieo3tQR_dC&-wA`l)?9N;%;8=!@S=8 zxZpxw_gTE|linozgizwnAmaMxh;vej-MIY3e3E-+kIAGL=lcI#z zfA2Pu+gMKF0!r&BJ%!^&4#$lwmG2*<4|tH+n*&qVuSkw4A?}0E;n4xMUy%`Qy3_b; zaWvZWYok#tjWKO9J}pFy>9*i?>)mfKEG)6QZ-~1qZSM{5Mc&x%b6~<#FW+VMEBg8Q zTBp=0>*B)`Tkb8--r}>c=GHaSy^J@A?_*30++vE-;*S<@SuyPf!;zxn{&$#eGurW6 zqK0EY3veB9xePiWY?)+OV93Qq5pWuCf=A5;76QS*24EjhBSvCPw|bv90bK@1X#lq{FXo93Csrqf!#n0a0WOJTm-HF*MV5LtNgL? zy}*9pAaD{m4V(im1HseKC?FVHTsn{qoC3}QJ-}7K)6*b+cBd)Ad&5i^0Y`wdKo1ZI zpI-s27S(r}RwZV8Lk(O4t^x))o*7sV>;}q#1HduBWe$1?!~*MpjldS*AaE2o37i%I zKQrBGKjniOfgZr@izWf{ffc}NU_FouWCF*47T`KC4J*?J2nS+;jX*AN8aM}B0G#Gw z;(^&fI;m=xXMsz={97@kKq`<4>|cm-7TQq|E=~fcfyw?T3|I)P1vUWbKsK-o zr~!@ur+~9S4={fb3I<3N*7l6ya zH6R#U!v-K7$OevxfHkH~{_@Xyo&wGSJ-{X4DzG8~RRO6$CU8hJt})%_ym1*;iWpd9 znq!Yzj)H(az&_vza00jlTm?LF@R|<<0xN)gpd2^=oChufK9OiN5Dvrw`+}mI0>8v&H&oCmu1|S=-*WjNc zzzN_Ka0$2y7*?ZEziE^vv-0?c=zF~EEv5Lf}M2U3AdARpKblmmx=^T0*G zXDu27gafg_I$$G^3mgQFuEqSH#Kmdg8sLTY2Y$&4Vav|4&Dg_1KGeXU=MH#I15|?t^z9( zQ8}<4NCh&1eBcmp1~?B~0j>isKSu+AjXkC}1tH0Z0dq04IP`z$M@+VE6?l1DFr209FI*fmGlSa13Yx&Hz_{ z>%g=PnB~PAFetzlAQvbCP6DTabHD|_DH$^Y%m#viwZH}-9oPfZ06oAZ05RR*3Csrq zfz`lzAQi|2@_};T0C3EXe_DVuz04H~<_1T7Waad0^TD@Lgar5Dshv za)JH8LEt2C8d&%sMg~X+vVmQ|9$+6(1DpU(0cQb2D*OfrOvU`K#>ILd703kgfkVI< z;5={i-o1*`?qfoxzOPy?Ju!|%}}vA{ZD zBajQozmm5X*biI)E(1=Fz$1X*N2a33xL6Bp0MdbMk#MhRhW!#QuL7Q#Xa^7otOrto zOkg)q4zvJgfb+l=U|JU10>lFAfQ>*dPz3A;4gyDklfY$Q_Exk72nM2nwLtb(49qTE z)Bs0-9^ew-xeW~gRsidPR3H=B4U_{1fJ4ABpanPsoCjR8(J;UVSO;tbwgB=EaqR~V z0!M+9z%{@r#}3!bL5qM5z%F19un#x_oC3}Qmw>B4;C3_w$Op=S1Hd8R7;q7|0$c}N zcAx>k79bZW0`>#ffQ7jj1t1E@w&R~&z&@Y`I0BpidVov7RUj}ABLSoWnLs|U8#n+Q z16qJHz;(c7C)Oko3##ZF0K z;`K+g`o5JEA(muYdCA0n3QfG$*|?a=!E@(v`1i+}9U`hHU`q`>1V zb4`CTqW-V*@Vvz;X6^)~i902265Drb^}n(cV-RW+AMQj0LN|*^k7^Bwkz^6SdQ@w` zYamhZD8~Qtqb7f}VR}B&L&O?Mq2h6nh|h=mWIoj4;tQD`A!Zhs7NFkf0+XjP`1t(= zruQbyMA$Y=H^?t>W7Ps7hQQFkz`#&zs93oR4GR(v@6uZE@-FmYsrbh(6csEc7NTQI zMNFYq@6JNg9jNyWNnzqgsS6d$9)~VWY<*lCi5DeBi1!~yVOBBG4oVX%?XV0Nzmn1> z@n=ct;!Bxm6AOwkkP%{YktuY7b+dS}2&sYMUqz-c(OrbD%`V0~2Z=SsrsX2O7zyRY zCJS2jPBAJ95#J)+7C$QzLNSH5*#WY5s~@|#$cu4 z-dyYUT*tUjnl>&W!C_;z>y2c)4G~X`A*Hcx_*k_kG~0)4xevx=TC;c9Fz(`;4^7i2 zN65TX_xuScPq_cxGGFu6?^(D(RWsr^#jyyA|D6&GkfEsJ`{Ke1uaq z1eC4~L9i7=pzMn@`yFWCcza4`d);tE-5|@qXX`p^##R(B%NGx(n4G;y!5J_BxA6EK zk{LwzZ%uQ&9G$_~sro%J2;stgk7>r38iyP;v~q}6iM|xm)VNjb81iLHrOw7stfHZC z^pw(QvO|`R)wCErT_qZJn5KGbm#VnnF_V3oNp!bqYJzsDOfWa9z1O9QHlM%9NYCBk zsFl*WR!o+f|8#VJmGCb$&GK?|0Mn(^XEb#R)W%h!c#mnSb1=HRN>r3$KpYt`{;J0Z zG<9pKX)6Ah4OfTJR_b-mvU%&Qc{^;5rfF%y9a)_5H^or6*OU6zV6;_h!f%x7zE4au zytPYJLHd}9e8`NJqJ#uT{cvhkLi!|G|Gn0owtM01@mn|JoT6Niblhev{srtIu_jsM zz>}t19X$>W9CIKSvsC;44i2Ph47H4@FKKG)I5j*ZRJos<%zZZEhTHs9I}XVt?pi1u zM49fsiA{aPnPoSarYn0bUD*eVMSHcNdH-I-GOKuQueM*jBc)B^$GzAj)5V=-FtHuq zS!Q~}D5Cb5X1j;Nh30aTYT(mRBIRk*yjfAISe?ggflo&n9uglsZSoLDpEfypIjnS! zb52@`j;Aq`4z(__MZry@gt1(&h8L+OT+q}x<)~pzx#^~{BH&8OW)EC5O2B5`m^y7t z9SBF%)YBGf;fHoBEmd_2o}~&q@30o5<))j*N`z~vNKpjejS_wpm}p0r;96?s;ZM#% zol=2?;ZWVRi-b%()o zRLkWjDrnj>ra3m%v@l&*>5*zJW~6U>6bF9gSd>l+B1{+m^RbA?esjk5tVgZewNan} z)^wt;0*l!b>jrIpM&Dzdhn&#V0nh5yy1>5y>n2KApVfCs7w4~P>WXn{IENaLa;zZ? zC)CC$(f15mvly!>(${phls_&BT5YJGtCK6?Um2el|x*TYOTFmV>32w+v=D% zO(&xFq1St+XicotH8EVb=PaD6HL+6HMENXTRdPyGH;>D$+iTLN$=pNZawAYEuQPZ^ zweNGLIq{AjXiJd}E;UlE^Ar-cDOENte7r~D}7Gi6`e!$XzJ$Y^j*<8 zME(q!dvKgOZEP|odrGyp(C3DCsBH_;!4R))^I})H*>$q68}jKvys-SyGTcvzfCio>9RuL*^B&Rr>GeRs?BxM$ zygj9}z0R#KYxe2et&e7=Wnv&yFroCo>DrBg+&@(X_%omAMIw$+&UEQpWtu9|t4w~P zG|g-h`?RYn9M(_Ct0sAMRbCCqtNG8H=F3~2HP35D{U@Hs-9(6Z?|E!+Y2pW&xJiV* zfITo>q`e?_J@L#7rbQFNH;cDkz^z80`1S?ZSj3V8xQ_@Dn-9Qdsd!FG!Q%Y`+MUXT zYDl;@sm5JHL^Uccs>WSIxcD;?}x@$~xCaqw1 zv0BB1TGU|?bDuUXat}v%Qcimg*3qJ&43i$sTV6OOR;k0`T+s$OvG+M9iPCuOVN#Xt z0nJuA&6q8vk!^%-J`HfYXv5vxwr5#0Gw7HnZhqP1iXWO|V}vm^`3I!2u)K_Q=TKu` zQy%UFXNnfqmvQ`z78SLosg^4;#c;>A?1C}ZqBJfX!=(yekMW8Yt>X&Ug|CyEdT5*) z;Y;Ptc9yw)f3I&E*1c+4F5EU+B>o<2)6sHWw37R|rk>%gU8=q#2IyyVjcEEkW^)bC zW@zZ~&wg)u(&!$BiBdJmS&tEgb*L#u6|-qfor}4N5e-l$IMnb0mHUEJYwJBaFL#?f z^^Of3>3HCDHLk_1#0alf^fkg8RFNk%b%I`Pg##${d`wY{D2Ce6AggZYDwk@lLGf9( zgl*}l*WrJpqXt=ZesEnYasWjdV}$V)go-T~l^Egu2VE1bn0nQQbDBC4YP%W~c?YZJ zHp*GG;m&RHHcsX(CaEyx)6^Bf-?r{{AHm2Sq)wJHN znRzx$*jT?w$3^OVOTKo4xe~V@#x^ziFt#a2$vPL?fb(FC2so^t3!OK$Xlg6eW9`y; zlYCo8*DlQZSi49^?Ml z;pj-3?l^Q>Q)A=SsdY}Z8;42^@EG`_0laAXCUsA5Q z5hqP;Okb5_`l@bB({$nGw6qcduj{yL9d&kE^m>Kgo7oK)d9a;tb=QFBM{RTvK#Da#2%Tj_8(qn$9`a;h^eh%8v05 zaY)Bafyb!GIC+Y!vFZr!w3NT4!DE!VNK<#})tlfPN-f{WiV?2$y4;%(f0Q~EhuRns z4fQNl_$IiBnx3;#jbZpxJ%*vYUN=3P;3>)~e3~qzzFs#yn{=L1qpAC#c1+JEgddgL zjH54&NkYcf`{ZgIb9vIym~7IyO}>`rAz^wP@;racVe)${jdE=Jx%QJ~v{DQrBqeL|ZEY~!K9(Dktkkn-bM9%Pxj{EM>6lbyvtP3r z8dn5@fKpHMb`-HL%*ia0|BOcyj+SDQRZGh?!{R^dTZ&0mYL{DNIj!T=m}I3c($vPk z=yPL|mHL{djvlARBrA3H99ekrI5j3&sV`~j)^TdMyXs=9kIZd6rXNJixKj6MYScYV zq#V-?qTIfe%?4jtM1{Tx8+<^i&uMC{h{-E3h$F{zgJ{!v!@9Y$9N$LWFxYh7Am3s{ z$Q`GKH!Narh?*zWwT-6R95W=p6sFWCHTBTz=*X@}CzEJtG`VwBT|j&jXL>xK6T(^N-9w!uYI zv~*dBauAX2CuHP1p^M1!o7>7NS6Yd}6T0SY)@=$GGM->x z!zE1}F;0zHSI;sxESBZvynzR!DpqX9Tr2e%OCuv7?VuV~SO&F1Jf{=bNT^atLI3`C3X% zywfyHoa5}GrSiQ}AZAzPzoc1DUgI=Fq@FaHRm(#IF~!PeBkX0%?>cGn_9j8wWkUlo z(aPwoG!m^R$Hp#HzJ#jOu_zBmp>b+Vv{IkY)EDkTGuAbm%;<~dq-pAni&25Bd3iHx zCV^|lnpb({OR(6doAotg&Xsx^S`i}#$EkH2z#dI~G{MPJKU`X>8ZO;_a9y*`cxx=u zg$C+eARAr6uKCuO3xo#hT;QTqqdTv@h3=5R-O=p|^0iw8)3;5xVierp!i=8LQmjZ( zZW$T~7f|sd3S)uz`Sw@{3YD+;DD_EAJ)l=xFjq<)j-kS6x9D znGvVQso?@jeNoQzMPU5LG%PD?J}4Q~dv?t8^)*M%`AgzEi5Le;d1R4qb}Xr_}O2 zUwF|tHRegF_h{p;FV@rBe`#gzA9nI>Z1*Pc8-{yyqY z7w^2UJ$at+foY{|Ma&1<>rqdBU|J6@`hFov0nJLUke$Z-I59BJ1%_I!!M-86&liMZ6;U7`qf3g<4OmjrbuZ zQU4*nIN?ykRn^4Gw_76lL7?@avG)NeU7MDWrSM&4?=wN#%ZG6BS$ca)XM4D@vX`&D zQ2FccANQ^aDL4c67?t6Qqk{2|DJY%ngLM&U!ws^3bsu3>sQv}(-2SwtmM?UOD<9$1 z>acJcC;3~}_?)85<6u5P*-@PX5hx0$Dl?8Rm$uQ+y7 z`Ry9jqjU^$oc3~%sDaHSWn$ZgXH5|waZ?fF1GfVmUv&DuG8!G@GUctE{b+J&l8g)%`P)F znQ9G^H+1S=>Cz1GV~=T(-z90U^ys$Ir+UitJ67NI^SJvS6w$vi&JZnWCYPC%uFX@B zys=aEJ)Yu;UMyAc)?U+e=M7%69odgN&k@-x(GE>k^&qsU$vNjGZu-PD*K$tUD?MV1 z8r{`+e1LXr+qxrnJ6<A@c&X%IyVy=x;i6x;(5Ys(XbJpS$m2K zlrZ7sEb+-FrkOKON{wm&HgVO!W3$DSPfc@Y9>Ze6Vh>bWY@g?TUPDc@#x@z!Kj4^APEqDGIS=`Tu-0L223yhXm<%;e(njK0l1L?abI@+kw&@UO_s}gV9js zn-Ptd8+JS}?yX8nWMkdhDMGAWF87jzZ96lzJ`|mwG4{ZlbeuX2V$10KEenywj=CLkep{X|P(bNI`dNtOWs_v?$ zw)W!~r+O?;d1^a9h7UWIi;8~Tc*#?qQeVR-7RyEZI5ifTQg69gs*PXhbL)J2{$#0+ z_(IpTrEoTt`;4Z}8kZaXrPTS@zm|)-acbRx&IcRTa?$$*?yVgi(>c#6P3`q>e6F)x z_{t}Pr95(O_)!>ErU`(@_B{B!`;8K%$SoDu#Q{f`Z zMCq5f4OhkJAH`nK)Sctha1qsS`N`Na;q{e1H(W%ido;CmoLU!!H^RY|iNUW-UgEjS zrkljsuW;sav_cn-yzLjjjfGhw6xYDQlTH>N(Lz93I30JaACoQuv7~Cw!_jO!b;LM-IDrtS&fAFE50_(iBqF3H)j>b_sl?U!@Zd{Tec(QQyO`yexsi6DQl|P;xa>+ztQz~Gn_Z_L4=f&bMPD5~6=>yH`_}jZ^E+ZQ(vLcj|(PGsJ~&@i-MrY6uS_ zE^5in-{}j52Pl^=_m#P#zrzPH+`*7Qcz|k>%Ur1rTsU!>sQM0%0v$FwH^|p)TE80` z>ySXWf%5pvn%a03TbUy_+(1p_p?R`~v;GrjX}3Avn#>0b`H)fB`OKGg1y}X8==@>7 zrfylJiqT|MjLtD8`^jQP#ucM;j6ItA=xr0nKN*&(sxWwm>e_Y9x?ot}HF$^G_A(d9 zx*CRYCUWGqjU6D)OEsJ)_(A&mg*y0Cy5=4s@}aIea2&uvRN627AA3qCd-;@CwJsG8 zx0f02xM%Hy3F5BrOo7dxj7%4W-|Jc}pX{n^;r>$HI8F_RQR;)5dJyUa)hP=c zM)i3zKE0t%CB)zTVBFSR+t|CRq~nIdfmEJdGLK09&sY=+kxzD&`jVzD8>fZ?DfRl> zWbRg|)e;S{z;9H0Tcp~s?iUH7deAgOOuja@(nBn8AZ3@14|DcDEqP$CU#QQX8WDosngt{@U1v7-E6TsP%SEQ(s>?aW+LBpAmg~;5^E3Ej|NU zCL%|43)2GUQSFgGNwQ27kBsg9Ar|)OffgUKGAG9-4KMY zH~!k)EWcLvmb+QLviYsMc@>`M1x{zQH{W~@YW-rqdCi1iJYM!gI|Iezk}TpqKiC9`DGRirzHb4f zVDX})5b?zVn1qU;TTy73co-xyZbie6+=_-ph=0j+JWO7QhTsdP3t_xTJhKp$rHjub z*+h`PdC7#3%_7ZTtMfH~lxq>+`=i4_V!U3Az|8r$l2lM^?fY++n%o-rww7D#At zpjdVu&&aVZ&*RZG*5!HA5_cZXO)$FwsDsz3^30cQzOnQb-t!<7^l{4 z%@;Mb_O?G=8UxHz?dvcms2R`9$G^Q#=`@C+|1*YnY4bDQUXHD5v;5kU>bwue?=Hjt z{kA`)^V|ONi%crR(TTE?@@@Z{v`Ze)u+Zc0Eiu1?4@}aIKNV>H8W)?6KOSWM#M!u7 zq=cL2h@LdFtNdvRH5^AUrmGEj@Va$JCZ1kuFA}Ts2I;7G!SE)vBg!vLt`_aGxGS5? zF7Cm)o`<6+tA#PbJVWZHIoD{iB?7atnj0B{eyE~OI!kj~gn7=GTDOmQ-YC^kFSyJ| zQjOA*R7u!{)QHHR!dq?lzn_*;I&~rh+mfnzHE#b`3)f}lIg=a>3lTxf%&!>N%7L9R zX{{R6u;V{0Gymw0#qD^K7eTta&LqociTe` zW!hrb{~YP`Y?sp69%mWV+SwTL2+aXw#P1T!US6sJo3P5%T<(=dqB#L$?NDQdsrCiJ z`69$nf_dtg8Vf^JaY<8q-))`~=g195QMor@A|nhxx5-tnT1#ov+D&i})w^rbRutcD zo-tOF&PR@6(j!EJUY(A`pt>;|z8xX@?l#Y|tA@yz5mn*xd1Hj(7uz#(ZEG{|{W8@U zN~gx8!-rJEW8oNV@35sbwuKWZ+Y94u#bfuFT^(IW*LhE@i)>@{J?1%MZGX%cI_!1bm+lxQN)oVal{!LqZkLW2MvmxE z>w0@tQ|H_dM|7xl2kr}S#4u5PKOE7aw(7cqK8F2|Bd*iZXsjaA#^zxIJS|KZe+fr) z6a|-8(=-jP6ecX=)ahf6xJy%8e+fr)sCR9aM3 zmC~Y%qF$v%MO9T%+FGirwAELu%m4SBb7tn={6Br?^SPPtJkN8Uvpwg`nYnW(^y3e+ zzvzXYezyGnV+cgE5cD$;bJT7iLmoR6foQ4G?`93hAP{9^1qPy&t9<Hu!zs#hat!M=r^*;ld&2g?iIX#OC!qvnKT!0zRHy_PdgjbbC;qOiYgS>mj7eiU z1^(tp>QovGK{E}*Xzt1@jxu6`t-59IZZOIS(b2N)vc)QTN;aCb1>cm7c5cb9W}}_) zj+W67j^sT?i)H(KI?CX0j~3na&1jh5-790T!@F0oQus?bSoAmIS94IZ#yoBu zcDN#>U1Pp@oYByO;bM-ydR2LsTq7>JURB1LsA-qJZ!s%>zAB%cYedJM_tzsx%xn3D zVMxc<=Lc7-C02uS5g?>04(O#H=H+BsIR7ozNPHwM+%GrGt7d6-33jd4F3b=iYgZAl^!#< z={JbC%r~lQLHu%_5#gGKTgXj#@zmfLamOcG9IM*WgDa-j+tv7+`9@OgZL&A@n2*fb zjKMABCVbAcVBDskUM>gHzfP%5gVpH61Quc z@RWJM0Z)btsfv)Mh!E3yp|D;*4|UpJXauzq$EKa%RPra;(Fh!Y=4?D}d~UfW{j(0A zU1<39^>umhWOUtn+`_dgi;yuZ+xY?BWio04$#8Z{{?!G5=$V(V*W< z^tz>oty$OjhvgS%F?0CN zLq|8^Yf6IUmtL{rSe3t--<)$#*o7`J?ZmNZhtO)K>UjtO(S)C05}eGB*EA~i6UU|< ze3F0aZ0 zW!B9yT9kBXwqk~1L~mm3nO9i;l+8?I$1q18dJgZO!~zIUKqbvE+W4Mf8yq;qc1f52 z6X3|c->dPoWw@DJGQ()(Tgc*-K^sjPwDIgl!$R}4@Vf^|G3f0SHjXfQhd6S^i-@o4fGYUtt!PD z?8(WVm3KuhwfW04jrQTo*igzF+jZ;-Q(E5VA@ht#9x}^l;u|Vn7EbzQh*Q#swvxrH z&Zo{YTKm!&y`_w{?f4J|t&%xZ=htQ#U42iml?JKd0YjfW6t^@hI%GClVl+!p2Gd;9 z!?YFfFrmnZ<_BjRslII1O|>Q6xf5AXV+(_%A{b0#^^`%XG6fI)BH2$td&xwAA} zT~XpRs(?s*s|eX=vS;x?18p<$+yj+wy{e&)_nQNQMJ%PY(6j3ZVe&BHx2BA*pJTKO zU&W>&>}czSu%$w@_<0ZynTeZQ!E;fv^(?)LP_tvmgq-)WDxWhK&d0M9RGPNas_56L z@>`eT*4Ycay4{)o`mC>EL3HB8dr}(_r4juA3tfN zgb$ZeBudAJ3{qN&uzA?`B%{kg+P12+-N>(q{07e&!F<^~qk)gJcooaHebT`kEBtTG zL&MBxr*Yn*ZGRV8^mt`Zoj>-J(cCwgouz!S{fQ6ZqiTc+gJ53vl+nSL%bch=ZRb&2 zs_=DHlj^+de6;Vg^4*?L%$z9=T2OJ(hC_U_*ap=^l#;RtLi4RyVC03bW6xH^F}6_D zmaNj`xQXTK7Z{Cw6Idw1jke9mpORjpsJgzuXy=>FE~!5MQ@LHK1|=eHA);n3yQe~O z9vVj!!HSwU$)JD@#iT@APz`C&jYfoM<0?-ZDZVTg1_fhDYP`l2 zdn(^byN91PI{PLvG>6!V@s|vysd4S&t)79wV{97wm$qKmQz7H6EVev@Ir4F=JSiBmxhME+T_x&#CrB4^3+g=d= zaD>vHL_bjR_E;@|C~M)H#EMn%?kR(_Rs~^Dfv8*vIk! zg9^OmVxy&RBWt6km{E_&eAZJ-AP8&m*B9e-GScdeT(}@N)2O<_AnJL;7d(5=UZLVKfVW znw?b>Y4T{<0<5)|P@+~W!9=!z-3t@7Ve|yOsE##cMlL}Hg=~V}aSf(K3br(g#`vX1@9?qgCJC_7FDc0Ty?1}-PcAjOhL2;08j9U8BZ`ba_?>^f z)adEUW1H3NOaD}dR7Ys)Mtl$SO<`Nr^gw4H;gOmjtvS#)gKg+bc_CJC&LG{R)R2+O zjV|G9*%+a*hvmKZe&>^x8=1bv?6#UUo<$l;Hb#Y71RuA;sK|{Kh}fst5mI5Br>v%_ zSy5QE_C0SIq$`7THLof+=gG~BY?Nv(TE>vag_M~XyRA7+`%Bp})uHj~v^2)*ke4_* zB%jSu19*>$r!f=~IPXUAuU8sjJYuEM&^MKB7KOFz8~L8uZM|0+RrymZjrzV~M&Ies zHb6}V+i9vXeRc9Jx7?V+Bh4CRa8p<7R??v={;d^#0fg${K>Yir?)>#tMpO~z4s^dd zPm9V@R7s+C`g=@EN!ihuj`uNl^cE{xAzXGFML z1OMaX>(=2#X!O>?+CuEA4g8oNsOGH7x34ptt~=sWh(dF=$AFqG(&+Dp z@!9K)X#Fd-|6T1P!iC(`G@P*qr2BLm7uoo>jhBI~rEN8wyc7lJ}gF841yVy9ao*{;b;nCihwxpS8}2!L7bk*d^S>RgzkLi{+o$m(-DZD*e3e4mt}z|M`)uS3{z! zAX0-_Bp}h6rgZWkYu6!QV}S_>W7b=xP$SYx(HS#l9bpzb9+>biW{dfb7e#wMf~%p= zWDd!#=&e~Iv#~aAvGE6BqBQW})D$K$0T?F`Z>cR=Z^XDl+97C#q$T}79knW9YUo=< zZ2;YH3<%oF>z?IWDLfrXqn}Wflp?e}9q`W(Tzp$8LVH3Nyj5L@wVHflDWVkLW;{m; zPGBsL5*k&+1MVK$0x>NXb7vh@3`w=#>UB9-UL1_vHlR@1@&zM7ryi>Q}!pnKX8V??pCl1IGGUeKLx^n<6Vs z=Vcp3lsd8~#z^K)0RAyh#zD+`j8&2jlYsSj#wH^iQ(!+nY?Da$Hl%TU$16rSX28=p zco=WQf5q@=HTaHA7_bNUacQ{rHuR?9#5?e%OT)E1;T6QyN59gnM2;{^R=&$vj(IQ* z2gT+=&~NkwFPWhf9r)|7h*Hdhv;t4qED|rW4q&o`$8I*F0P6(6_ZCZygB>`CG82C6 zuPO6CIE#aM!mK*}&B1^1Adbewrq0HKNwgmC=`x}dS?KS$F8vpqs(&z+ZRR;02Rls9 zb??(nDY@YUVr}GTC?Ef-5rerzV~3PNT`Y|r4)x(uXc9c{S4w>AxL)31Yn>e)d_D&yGPG?v10pqpjs+L$WTtRA}t-4~XwzMrl> z+gBAjD?fS)S8W<@<1NQO@0@5WO%jqn=y&l=VI)5K$8E;mZE6uJmX<16xR39z%Le~q2#zJu&kx)A!EyxKI@ zY4DMNbaey#e;Sa^KBs6btMF<-x~h(Vgg;V3?%jzRIGHo{-)m3_x(Hsj3sIHGcf3wf zRY!=ZArjI8QrhQojg8IiD$GO{E;c;C5YJ^;6|C7P%kt-%NoKtMPPFlprqrjqSF4;$ zO<9DtheT1;q005^MS2%v+JZ2dBxrbDi3g<6%et1 z@;h&$+VS4MU=*z!lpib+Ng6H*FkT}PIs!4Xi7kW$4wo$G7Kl1w$lSz1k?80+_qf`c zb=e-mCTFPhqEMglvYkeBJ8$b`jqR}N85pKF>u4<5$}})c!|Gy25%o-*1?+2?`NtDu zC!h+?ECCc!ReL14H8;q<_fPcCnxPYs}z%_h403v(eu; z2;$y%ut0PV(Af75esK>j6n+{6=9hOHKDYbqU=443AQLT|Yj0y^mY0z~M8k{+JuR~l z#C+mzxJyY{AP&fP`yBQf4sNM#3dQM36zuj(FJE*x)WXsk?RIQadM8e65( zg$9J9!#glj!&7{63k?`On9!gzM@cBF*~rd1-rIK+m7NM)!|8l5OJgh5L>|g^rQ3$M zAu(FRB}?gEu_%3*kKb)X1-aO!F&fL$cpjQ5AuI>IYo#{R(%kH1Nx4{daSctB&qlQgzTRH%KtcM}etu?z!G zWGRIj%T+UFsO=x+aI-a!Yq;oY`!;$sVy4E@W#>+vrLh-f=f-<|vo*F~2ErNc-HVgB z_fQdaK2@^ibzmJUIXu!fGHU$6oWG|MmoA}zjm|PwiFmJBL5-dOTf9&K& zfwYlyRGf&xhXc$4=YVU_nF9p9pK7~^_f~$w-+f^FG$fs@U>~0GjuF*9CFSo0n7fq& ztT+6Y99en3g&KROqEvcW;5p)C398KJV$`_)25N-iH5}|89F(b$3G|1%?|5`3e&)kUq1D!boR$(>$78CK_AE7gA zQ>EN8$F<5|XL_V4O-YG`?g1sLQWVe(HB-7lX^t>+t|MD2%yj6?WioVr&6iQYp{r{; z4bU-m0J_GuP7(PmEO7k-C6-{z{l^yg>t+%T|jH6Gxse_|CV*&j5jSn=YM9Q3uWO+!$ms) zi_SFx#(~klS=bb@U9hR3rnGX!X7BESFEs$e?7UE=Gu?Z>Z^v+0z=RPKG6}kKR5xs4 zn+Yqs3H*byW}}7NyB|hQwk*IX-Y;_LegKSO zw5_y@9_ZZzQ?tjzF*Qac)8IS{GmPK!pn`uM81}?z|SSAI4LR9VB1GI z#>n?8PR*1f{0_?DW+8_(+ySb805e4wUgrP;?IB2L#p9MY?B71Bu_=7+0mGNb>V2$P z&oe}nTf3fx?lRehSI02=L}MYUy|D!M%NbwN@G@khUE@CKgAY4M);&*XY_YQb61-AcXRwK%iWSNr7nR!0W}VdV@;Bir-g_Gd zw^X8wWw_%YIF406WnTnD3PgI(!KyyQdN>vVVK3AD$3M;u2v#!tdMK|lp8MUlEP zFFAykTh6sZki~n~TC#-Kfa(qk7QTVbcS48zl80!ibP9}Hj&S4p5g1MwULk+1{u!;Z zg!^Fr9Nc3e9}Af|Ghs39*R0vuDbSfGus~gI#vtgps$HONBD)2htcL4Ppv=_T&=6plPaHV*>Fg$bLs+iU1-kaBBYxyvlwtU{7*4X~JUr`Sm7@MQvgKUUYf3kNe)ECrUE zxf?Xqts#N>W|}3(iP_sQKo=MlDbV3Q{Si#M-iL@)!Wg@i;rGVj9AQWGN>~6i>kw$h z*vru2o({}hAB4fz3~Wj5XKc1FSE!@^7imBx-+X-`ii$K~*SWVt0zXRirM*CY8lOX3HRq3iKUI=iG9lqIhM%ha|?mWJ!kryGm)PExiD&Ev3$vbyin8Yk+6iCP?Wz zU}K3VZPYhf(o~?vJDf#%K|}b&&x}ZIBVT+9)q3j{9SbE55+?{RY@_B)*i4x51%#ku zyzgnytJLJw%dXe9=&Vp$R)0;$11lw`AYJgf&U#2`84zC^oJO|hrE`D@5=()NB%T7QVtocYE2XdDIjP~YgcaY` z*-;^Np8_tgAj4twJ}Ve6166%@eLyiF+V=K-9sfyBlqcnY&OVo|cu>b92SV5tC?QFA z5MMTvub_)Mi+76juHvf2a;*ZIY-@H>fjZ}JA`;o+d#A65I4YX61WUsU@mYJXGhf029FA9w`rb?N?< z9}$L5;ojZmXPvn;!LAO!P!*^IuI@lpn9;y`RiwpImjmKE7f{9>z|FyUuPe$pIF#SI zfHueub)e#;c8vz&zm8r6zT$PT4FdI^Rr&CXxXvoVGf*GuBC)GugagA$B+3NF$wYG_ z9c;41-|(e+g2adz2VHiN*JtqL^Erv5;v5)vLfQt8v$dD_c!C3`5aBm0(ZSx5(xbTF zl_8~dabxpoi93OnB<{2ED6p!Oo(FE>2fjhZ^OGEG5!WsQy?9(JL!e$zn=ihECU_g7 zhEjV4I8tKQWNHmcqc2G2f0NZ^8_(9FNr=XsaW zdd+b09;XYLdq6V>>rz3mYjs-(OO_cP1ZomL1Xh+<25c`ew4DRbJ&0P&04|m2Y41Qd z3TYTn+4cu^7gBvqd%o`*l>W6eD^0r&4osocH13HV9qcNGC<^Nu)P?$zT)8I$>q)V@ zw7Ua$miWGJVY09XHBg5|dR2b%Tf?c}=*ic83+D@ZJJ?-Y?w*O4Y{aQFtHG6c>9=Uf zjs1A#?=Uhx?8ob3@0v2uLI1%0JLI?vcuV6AzC$iA;qB5#gxHlc*n#IE$ij6Jn9DP+ z0NV_4U`^x!>K%vjTjX-#2p)U|EuAwGt*`OQSK#NLOsbGDi_PZ4N!>cz!M=71wL5y8 zgALXAEi#>wOU+nD9%tq96EJnX0g*?DT<-xJNW5W7{|ihOQg?NH12aLndOpvAGtG{x zDCd4)sX#p=pKrSguXpnuY>?FUnm~C9!~Q@+;t1fw61M>dNYp1f*lmeF0~bo1QQ%-d z^Mq?S7f*7~qc4={Mj-nBIvVv>p@W6!JnlL|@vkZT?`vqN9@BXAbrj@>X%4KiVqxYg zn(n~#JrStyoX+#0)#uFM&ydy1*%Xzea;*aPl6VCeC(!LEaGVU8gP}wIZG_*e}U;zI%p~Kl;~LIU^n>OAK>)Im3-X|IE`3MH4&a7f#U?ap9J=F zh;q74taae24Po&M@EKlu14W(nBE_hXzH6cW`-^<`5Agcr1_%2|Y6~{fs1k-7ft3X6 z+c)xCWcbuJYGa|@3tS*E?F|Q>u@ur(z>y+L{r+}7<0jI0c2FbxEAhWceWa2TIg;A-9dM4sQHB%O>q0sM=#}Xg0k>7; zvwy)YHy^+F6Ow27oHV5(dBSr*^E%o3`bN#tTZCDoI~Y2kXQbz$5l*ZuL?#n}t0e|U zIuW4lbw{>zkoP>P;u+UIOzmI*aEm!;&;H|5<6CNvSt#e0WsZ^ z?R4NYiFbg?S$wP$r!ryC1gLCNftaHySwG-%Q7qTBI41&HN^#S9vBXP2W&1bKBc+w% zow(g8YWc1*&c{ zYC3TU~f$}g+sWNW3tTA*s3W5B&a>V7K8$rkA%hFqa_ zocKyaWH%hRTVi-!Cp}H@Gx{2oDw7og8#s6zn$lU{iFu1s=@;tr#dp!cZJRmSO_{n* zb0@ARgwKJ%4<$ymunJobh+9d&p*=bRlO^U@s4v04!1xVLPeIgBYPFV5oYzE}(ZD7W zSKD|Th$)tw{$NYvT2YS)X?tL%#Fv065>Ej=62G?bCJ^5gk+W8~p{8&l5EoVVAbkniEeei)8D8DH2ZtJrXYfBk;mR`27_~?@k0Z=s*o5upzLT#Gb%tiCMs6 ziFbi`E|!udbfj(;H~{#d#8p6ir9lSkfw*ud{0bN&@i!nA*dz_>?>v_i={a+0}{FhY$yMb23*2A$Es6jJU2WO->DSvSHGs z;cyhgA;mp1oVeDel&)OhZizKUIvM^A1xcT<@iK6lln%~xVl^WSHUpK1kAXQt>P{Vn z$wZTRbkDLZ#sQ^;>vLQBU*M}>_Bv46_8VWQ*$XAg|G28ZnE)fU_WWlXuOs0NE?^h zc*w@Pz^*b`n>-7j1dfu@Ye1E8d_HD0DeVo!b6?c`Ilu^2`MDEtLX;NkY<$!$HQJkFs){uAysN!twWIRVFrC$M+wEq+fKe4gXR8#7H7xDF>a*!FTAM2-mR>=}aLU zd~M^;z&29a;1Hdjgu!5-vdsnJ{xjt}37Ek9y5MXX5a%V5&iTm6o{|QxBed`kwq79a zbC5xMAnub8_6NpD%mb>7w*ZTT)LrK&YU$*0f8puiPRB6=s%gEAHNDG=+dj}m{flla zbmndH^64i0k91E5ro)3FYNIns@&8EpDs<*oh2=B+5IXbQ^zypP(Ct)bu=2WPpE{g$ zW1#{X`^8V`R3LDxjeCLNQhEX?ZM83XSp`pw>k=dld07xrhn#fc_Km>zfN2u{1cpj9 z%BY8hK~)>0ZA<{pkOnUR6D7WHs}muLUxl-wN{hTx(A|*~`)*?Q@#> zM0U>she*5z#6Mx90@pd?#Oht(YT#&z+80#H4i#Y#1Z*O)HP9`wgKf|ah-s&yC(>yW z;?%}9HtwZJCf(O1m#N*VaN(<*jCw;R8vHNvkFuroF z>PtfNm$h6@mfN<%$#EQ3`Jl1MzbMa-3~T^KI#TTl%~$-DFGOu%(BA zc#xZ%od)igxa_J`$`^o9Qo0MMGX4bku#`q$vuqQ9K~h==sQfkuww2OC+xBr_q?9fN zD!*HR%J1*CExT^{4FalG4FT4W9va)ymcZIlnr=%++tS6hbU9FY*kemS0LDoV7i{Tw zwp9P#ECUY>L#!#|+LqYW0H~zBY-xX>%5I7+on_m;U`t=JrTcB^N4E5eExl<=gKwBc zb9sR(w^Uo&8i?P%g<>kSh3P^lf?&2Seae=;Y)iKQ+sM|rYD<3vs?0)vu!;}?RL#)T zmbS5_Lu_e=EiJO8^MOe+x2-@GQSSh8exacK*|z;1sG?81X+=~dP({>epo*P5pt79; zRDS0HyGg&tEL(ml5`CPvVN34-RRf3IvdZ8Cs?KO>OVey=rY+3@)|6FVY)hBh(!I8HKTzd%(Ux8TstMw6 zpsKO)6J247E@}Z(&E6iUTBj>e**;?1&b4h9+P1~E?K<1`W81dOw*3;QCX?I1PO=P5 zZd+w&1yp6|2vlY0161XmY1=+&+b*(gR{>RTmf5yvEnD{`U|-yJr-{4K&*nMB-5B^= zbtz7+;==M>v`^+1C+N(62N;tOZOy}&U7 z6B6*hf3K>QWhZkPi#>@dgu8GB_zn zpKG{Sq~hROE>?r_*)`$3KDdJ7RPb=cOZ?=kz%!LRJju4N1`bj32mIuX!9FGL2JYmL zc`d4gE|hZDDlmR!R?8Dnv>j;PAMR1Ew~j++Ud)u&orZ3YvM;ZDw(h^DTMAt}J6+&~ zPTBuRcosVK&J$KX!)yN|-7VT9?=5K!+dsCwZ#! zv$Z{8`U$-1x3Zw*rRMP8^RuAL)kF&?g*C7GT2C#$wsj( zUYhKg#C>%VGr>Fa5x$7OvX%C#5AQt+w_zcE_#{j8(+4#_7o<$iOS3I9wyS?wve=`61=d1P*v3xW}FYK?y%NNotMz_&5`#w}A5&Oz$ zX=<}yQK?$kKacM2M8{~1X4s!ZkJQ6{8R|#RVrC#Cdc^TvG*}a436z52bE_@s7WgJqfqS!v9AdSt+Ahhf}~)-03S38 zyN=xBvG0pMY>Yjg^bn73&qYfi3G0cPcE$b=I7MC9G8C)__LbxDatiDRqri_~kB00h zCiyQ=!rBldpo2PM|0$XbzS%uEM4?$e`uG9try^rin(ahPbilp_9Ct72uq5_X96-h< z*OFEL;RFt_U4^$^yJHJHUA4-4P%8?InJ~N;%4baSZ1LU8M{UqH#mI0}DS{3eo}a{9 z6?z)rXIf(mJ Date: Fri, 17 Feb 2012 09:46:05 +0000 Subject: [PATCH 12/33] Found free extra 256 bytes of RAM eliminate _clz use from libgcc Believe it or not, changing / 2^31 to >>31 saved 256 bytes in the "d" segment. The reason is that GCC version prior to 4.3.5 does not have a count_leading_zeros (clz) assembler macro, so it uses a 256 byte lookup table called _clz The _clz table gets pulled in if you do 64 bit division. This tiny change is the only place that we do long long division. Changing to a shift saves 256 bytes of ram. --- libraries/AP_Baro/AP_Baro_MS5611.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Baro/AP_Baro_MS5611.cpp b/libraries/AP_Baro/AP_Baro_MS5611.cpp index dae494ac16..6e1780b0a4 100644 --- a/libraries/AP_Baro/AP_Baro_MS5611.cpp +++ b/libraries/AP_Baro/AP_Baro_MS5611.cpp @@ -212,10 +212,10 @@ void AP_Baro_MS5611::_calculate() SENS = (int64_t)C1 * 32768 + ((int64_t)C3 * dT) / 256; if (TEMP < 2000){ // second order temperature compensation - int64_t T2 = (((int64_t)dT)*dT) / 2147483648UL; + int64_t T2 = (((int64_t)dT)*dT) >> 31; int64_t Aux_64 = (TEMP-2000)*(TEMP-2000); - int64_t OFF2 = 5*Aux_64/2; - int64_t SENS2 = 5*Aux_64/4; + int64_t OFF2 = (5*Aux_64)>>1; + int64_t SENS2 = (5*Aux_64)>>2; TEMP = TEMP - T2; OFF = OFF - OFF2; SENS = SENS - SENS2; From 0d5f7ca072956307ac3dd8eb1afb682d20207a7d Mon Sep 17 00:00:00 2001 From: Jason Short Date: Fri, 17 Feb 2012 15:20:39 -0800 Subject: [PATCH 13/33] upped rate loop to 250hz --- ArduCopter/ArduCopter.pde | 4 ++-- ArduCopter/defines.h | 1 + 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 0ace4409a4..cac6eeae78 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -824,8 +824,8 @@ void loop() uint32_t timer = micros(); // We want this to execute fast // ---------------------------- - if ((timer - fast_loopTimer) >= 5000) { - Log_Write_Data(13, (int32_t)(timer - fast_loopTimer)); + if ((timer - fast_loopTimer) >= 4000) { + //Log_Write_Data(13, (int32_t)(timer - fast_loopTimer)); //PORTK |= B00010000; G_Dt = (float)(timer - fast_loopTimer) / 1000000.f; // used by PI Loops diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index 502e868233..434a090335 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -144,6 +144,7 @@ // Rate #define CH6_RATE_KP 4 #define CH6_RATE_KI 5 +#define CH6_RATE_KD 21 #define CH6_YAW_RATE_KP 6 // Altitude rate controller #define CH6_THROTTLE_KP 7 From 677df0fe1ccaf9c719d5ca6ccf857cfbede17615 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Fri, 17 Feb 2012 15:23:36 -0800 Subject: [PATCH 14/33] added Rate_D tuning value --- ArduCopter/ArduCopter.pde | 26 +++++--------------------- 1 file changed, 5 insertions(+), 21 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index cac6eeae78..40b994ac87 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1926,11 +1926,12 @@ static void tuning(){ case CH6_DAMP: g.stabilize_d.set(tuning_value); + break; - //tuning_value = (float)g.rc_6.control_in / 100000.0; - //g.rc_6.set_range(0,1000); // 0 to 1 - //g.pid_rate_roll.kD(tuning_value); - //g.pid_rate_pitch.kD(tuning_value); + case CH6_RATE_KD: + tuning_value = (float)g.rc_6.control_in / 100000.0; + g.pid_rate_roll.kD(tuning_value); + g.pid_rate_pitch.kD(tuning_value); break; case CH6_STABILIZE_KP: @@ -1940,26 +1941,21 @@ static void tuning(){ break; case CH6_STABILIZE_KI: - //g.rc_6.set_range(0,300); // 0 to .3 - //tuning_value = (float)g.rc_6.control_in / 1000.0; g.pi_stabilize_roll.kI(tuning_value); g.pi_stabilize_pitch.kI(tuning_value); break; case CH6_RATE_KP: - //g.rc_6.set_range(40,300); // 0 to .3 g.pid_rate_roll.kP(tuning_value); g.pid_rate_pitch.kP(tuning_value); break; case CH6_RATE_KI: - //g.rc_6.set_range(0,500); // 0 to .5 g.pid_rate_roll.kI(tuning_value); g.pid_rate_pitch.kI(tuning_value); break; case CH6_YAW_KP: - //g.rc_6.set_range(0,1000); g.pi_stabilize_yaw.kP(tuning_value); break; @@ -1969,70 +1965,58 @@ static void tuning(){ break; case CH6_THROTTLE_KP: - //g.rc_6.set_range(0,1000); // 0 to 1 g.pid_throttle.kP(tuning_value); break; case CH6_TOP_BOTTOM_RATIO: - //g.rc_6.set_range(800,1000); // .8 to 1 g.top_bottom_ratio = tuning_value; break; case CH6_RELAY: - //g.rc_6.set_range(0,1000); if (g.rc_6.control_in > 525) relay.on(); if (g.rc_6.control_in < 475) relay.off(); break; case CH6_TRAVERSE_SPEED: - //g.rc_6.set_range(0,1000); g.waypoint_speed_max = g.rc_6.control_in; break; case CH6_LOITER_P: - //g.rc_6.set_range(0,2000); g.pi_loiter_lat.kP(tuning_value); g.pi_loiter_lon.kP(tuning_value); break; case CH6_NAV_P: - //g.rc_6.set_range(0,4000); g.pid_nav_lat.kP(tuning_value); g.pid_nav_lon.kP(tuning_value); break; case CH6_NAV_I: - //g.rc_6.set_range(0,500); g.pid_nav_lat.kI(tuning_value); g.pid_nav_lon.kI(tuning_value); break; #if FRAME_CONFIG == HELI_FRAME case CH6_HELI_EXTERNAL_GYRO: - //g.rc_6.set_range(1000,2000); g.heli_ext_gyro_gain = tuning_value * 1000; break; #endif case CH6_THR_HOLD_KP: - //g.rc_6.set_range(0,1000); // 0 to 1 g.pi_alt_hold.kP(tuning_value); break; case CH6_OPTFLOW_KP: - //g.rc_6.set_range(0,5000); // 0 to 5 g.pid_optflow_roll.kP(tuning_value); g.pid_optflow_pitch.kP(tuning_value); break; case CH6_OPTFLOW_KI: - //g.rc_6.set_range(0,10000); // 0 to 10 g.pid_optflow_roll.kI(tuning_value); g.pid_optflow_pitch.kI(tuning_value); break; case CH6_OPTFLOW_KD: - //g.rc_6.set_range(0,200); // 0 to 0.2 g.pid_optflow_roll.kD(tuning_value); g.pid_optflow_pitch.kD(tuning_value); break; From 6f080742b8d89ff473909ab7fde5ea8209a7bca4 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 17 Feb 2012 15:12:48 +1100 Subject: [PATCH 15/33] AP_Param: added an initialised() method this will be used by the compass code --- libraries/AP_Common/AP_Param.cpp | 6 ++++++ libraries/AP_Common/AP_Param.h | 3 +++ 2 files changed, 9 insertions(+) diff --git a/libraries/AP_Common/AP_Param.cpp b/libraries/AP_Common/AP_Param.cpp index 15e3119c4c..e3d73c3059 100644 --- a/libraries/AP_Common/AP_Param.cpp +++ b/libraries/AP_Common/AP_Param.cpp @@ -206,6 +206,12 @@ bool AP_Param::setup(const AP_Param::Info *info, uint8_t num_vars, uint16_t eepr return true; } +// check if AP_Param has been initialised +bool AP_Param::initialised(void) +{ + return _var_info != NULL; +} + // find the info structure given a header and a group_info table // return the Info structure and a pointer to the variables storage const struct AP_Param::Info *AP_Param::find_by_header_group(struct Param_header phdr, void **ptr, diff --git a/libraries/AP_Common/AP_Param.h b/libraries/AP_Common/AP_Param.h index 5d2de07d97..0cee4be55c 100644 --- a/libraries/AP_Common/AP_Param.h +++ b/libraries/AP_Common/AP_Param.h @@ -80,6 +80,9 @@ public: // wrong version is found static bool setup(const struct Info *info, uint8_t num_vars, uint16_t eeprom_size); + // return true if AP_Param has been initialised via setup() + static bool initialised(void); + /// Copy the variable's name, prefixed by any containing group name, to a buffer. /// /// If the variable has no name, the buffer will contain an empty string. From e656928c01a2f957857c529c9637f88fd9112311 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 17 Feb 2012 15:13:00 +1100 Subject: [PATCH 16/33] AP_Param: added a set_and_save_ifchanged() method this can be used to avoid the scan() in more frequenctly saved variables, such as the MAVLink stream rates in APM --- libraries/AP_Common/AP_Param.h | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/libraries/AP_Common/AP_Param.h b/libraries/AP_Common/AP_Param.h index 0cee4be55c..c811a23b44 100644 --- a/libraries/AP_Common/AP_Param.h +++ b/libraries/AP_Common/AP_Param.h @@ -262,6 +262,19 @@ public: return save(); } + /// Combined set and save, but only does the save if the value if + /// different from the current ram value, thus saving us a + /// scan(). This should only be used where we have not set() the + /// value separately, as otherwise the value in EEPROM won't be + /// updated correctly. + bool set_and_save_ifchanged(T v) { + if (v == _value) { + return true; + } + set(v); + return save(); + } + /// Conversion to T returns a reference to the value. /// /// This allows the class to be used in many situations where the value would be legal. From 70a135c47c4126d44aa72094550f7b2db65ee8bd Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 17 Feb 2012 15:13:51 +1100 Subject: [PATCH 17/33] AP_Param: fixed copy-assignment operators for AP_Param vectors --- libraries/AP_Common/AP_Param.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Common/AP_Param.h b/libraries/AP_Common/AP_Param.h index c811a23b44..3207911356 100644 --- a/libraries/AP_Common/AP_Param.h +++ b/libraries/AP_Common/AP_Param.h @@ -350,13 +350,13 @@ public: /// Copy assignment from self does nothing. /// - AP_ParamT& operator=(AP_ParamT& v) { + AP_ParamV& operator=(AP_ParamV& v) { return v; } /// Copy assignment from T is equivalent to ::set. /// - AP_ParamT& operator=(T v) { + AP_ParamV& operator=(T v) { _value = v; return *this; } From 8355823bc71ab3989af6206a25720b81acbe8cb4 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 17 Feb 2012 15:15:04 +1100 Subject: [PATCH 18/33] APM: use set_and_save_ifchanged() for GCS stream rates this avoids a lot of EEPROM scan operations when the groundstation updates the stream rates --- ArduPlane/GCS_Mavlink.pde | 30 +++++++++++++++--------------- 1 file changed, 15 insertions(+), 15 deletions(-) diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index ed7b0167d1..e5ecb7cd9c 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -935,14 +935,14 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) switch(packet.req_stream_id){ case MAV_DATA_STREAM_ALL: - streamRateRawSensors = freq; - streamRateExtendedStatus = freq; - streamRateRCChannels = freq; - streamRateRawController = freq; - streamRatePosition = freq; - streamRateExtra1 = freq; - streamRateExtra2 = freq; - streamRateExtra3.set_and_save(freq); // We just do set and save on the last as it takes care of the whole group. + streamRateRawSensors.set_and_save_ifchanged(freq); + streamRateExtendedStatus.set_and_save_ifchanged(freq); + streamRateRCChannels.set_and_save_ifchanged(freq); + streamRateRawController.set_and_save_ifchanged(freq); + streamRatePosition.set_and_save_ifchanged(freq); + streamRateExtra1.set_and_save_ifchanged(freq); + streamRateExtra2.set_and_save_ifchanged(freq); + streamRateExtra3.set_and_save_ifchanged(freq); break; case MAV_DATA_STREAM_RAW_SENSORS: @@ -950,15 +950,15 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) // we will not continue to broadcast raw sensor data at 50Hz. break; case MAV_DATA_STREAM_EXTENDED_STATUS: - streamRateExtendedStatus.set_and_save(freq); + streamRateExtendedStatus.set_and_save_ifchanged(freq); break; case MAV_DATA_STREAM_RC_CHANNELS: - streamRateRCChannels.set_and_save(freq); + streamRateRCChannels.set_and_save_ifchanged(freq); break; case MAV_DATA_STREAM_RAW_CONTROLLER: - streamRateRawController.set_and_save(freq); + streamRateRawController.set_and_save_ifchanged(freq); break; //case MAV_DATA_STREAM_RAW_SENSOR_FUSION: @@ -966,19 +966,19 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) // break; case MAV_DATA_STREAM_POSITION: - streamRatePosition.set_and_save(freq); + streamRatePosition.set_and_save_ifchanged(freq); break; case MAV_DATA_STREAM_EXTRA1: - streamRateExtra1.set_and_save(freq); + streamRateExtra1.set_and_save_ifchanged(freq); break; case MAV_DATA_STREAM_EXTRA2: - streamRateExtra2.set_and_save(freq); + streamRateExtra2.set_and_save_ifchanged(freq); break; case MAV_DATA_STREAM_EXTRA3: - streamRateExtra3.set_and_save(freq); + streamRateExtra3.set_and_save_ifchanged(freq); break; default: From 3bb84bb40c7e57436c6a4c6416febf6a3555f154 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 17 Feb 2012 15:18:05 +1100 Subject: [PATCH 19/33] CPUInfo: added timing of sqrt() --- Tools/CPUInfo/CPUInfo.pde | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Tools/CPUInfo/CPUInfo.pde b/Tools/CPUInfo/CPUInfo.pde index 37e6ae07fa..d0192b01e2 100644 --- a/Tools/CPUInfo/CPUInfo.pde +++ b/Tools/CPUInfo/CPUInfo.pde @@ -6,6 +6,7 @@ */ #include +#include #include FastSerialPort0(Serial); @@ -93,6 +94,7 @@ static void show_timings(void) TIMEIT("sin()", v_out = sin(v_f), 20); TIMEIT("cos()", v_out = cos(v_f), 20); TIMEIT("tan()", v_out = tan(v_f), 20); + TIMEIT("sqrt()",v_out = sqrt(v_f), 20); TIMEIT("iadd8", v_out_8 += v_8, 100); TIMEIT("isub8", v_out_8 -= v_8, 100); From 2b8f0c3a484df2ffb521e61fc3455830c0425ccd Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 18 Feb 2012 10:00:26 +1100 Subject: [PATCH 20/33] AP_Param: moved AP_Vector3f and AP_Matrix3f declarations to AP_Math.h this avoids us needing AP_Math.h in every utility sketch and example --- libraries/AP_Common/AP_Param.cpp | 1 + libraries/AP_Common/AP_Param.h | 8 +++----- libraries/AP_Math/AP_Math.h | 5 +++++ 3 files changed, 9 insertions(+), 5 deletions(-) diff --git a/libraries/AP_Common/AP_Param.cpp b/libraries/AP_Common/AP_Param.cpp index e3d73c3059..17c2c28ada 100644 --- a/libraries/AP_Common/AP_Param.cpp +++ b/libraries/AP_Common/AP_Param.cpp @@ -15,6 +15,7 @@ #include #include +#include #include #include diff --git a/libraries/AP_Common/AP_Param.h b/libraries/AP_Common/AP_Param.h index 3207911356..b898a8a297 100644 --- a/libraries/AP_Common/AP_Param.h +++ b/libraries/AP_Common/AP_Param.h @@ -18,7 +18,6 @@ #include #include -#include #define AP_MAX_NAME_SIZE 15 @@ -431,13 +430,12 @@ AP_PARAMDEF(int8_t, Int8, AP_PARAM_INT8); // defines AP_Int8 AP_PARAMDEF(int16_t, Int16, AP_PARAM_INT16); // defines AP_Int16 AP_PARAMDEF(int32_t, Int32, AP_PARAM_INT32); // defines AP_Int32 -#define AP_PARAMDEFV(_t, _n, _pt) typedef AP_ParamV<_t, _pt> AP_##_n; -AP_PARAMDEFV(Matrix3f, Matrix3f, AP_PARAM_MATRIX3F); -AP_PARAMDEFV(Vector3f, Vector3f, AP_PARAM_VECTOR3F); - #define AP_PARAMDEFA(_t, _n, _size, _pt) typedef AP_ParamA<_t, _size, _pt> AP_##_n; AP_PARAMDEFA(float, Vector6f, 6, AP_PARAM_VECTOR6F); +// this is used in AP_Math.h +#define AP_PARAMDEFV(_t, _n, _pt) typedef AP_ParamV<_t, _pt> AP_##_n; + /// Rely on built in casting for other variable types /// to minimize template creation and save memory #define AP_Uint8 AP_Int8 diff --git a/libraries/AP_Math/AP_Math.h b/libraries/AP_Math/AP_Math.h index 7fd090b9f3..fbff53cb3d 100644 --- a/libraries/AP_Math/AP_Math.h +++ b/libraries/AP_Math/AP_Math.h @@ -2,8 +2,13 @@ // Assorted useful math operations for ArduPilot(Mega) +#include #include #include "vector2.h" #include "vector3.h" #include "matrix3.h" #include "polygon.h" + +// define AP_Param types AP_Vector3f and Ap_Matrix3f +AP_PARAMDEFV(Matrix3f, Matrix3f, AP_PARAM_MATRIX3F); +AP_PARAMDEFV(Vector3f, Vector3f, AP_PARAM_VECTOR3F); From 371a91cfcfe87a08d0ead351134a847276760f73 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 18 Feb 2012 10:39:05 +1100 Subject: [PATCH 21/33] IMU: move _sensor_cal to general IMU class this makes it available both in shim and INS subclasses --- libraries/AP_IMU/AP_IMU_INS.cpp | 5 ----- libraries/AP_IMU/AP_IMU_INS.h | 3 --- libraries/AP_IMU/IMU.cpp | 7 +++++++ libraries/AP_IMU/IMU.h | 5 +++++ 4 files changed, 12 insertions(+), 8 deletions(-) diff --git a/libraries/AP_IMU/AP_IMU_INS.cpp b/libraries/AP_IMU/AP_IMU_INS.cpp index 9c8befd235..075678315f 100644 --- a/libraries/AP_IMU/AP_IMU_INS.cpp +++ b/libraries/AP_IMU/AP_IMU_INS.cpp @@ -21,11 +21,6 @@ #include "AP_IMU_INS.h" -const AP_Param::GroupInfo AP_IMU_INS::var_info[] PROGMEM = { - AP_GROUPINFO("CAL", 0, AP_IMU_INS, _sensor_cal), - AP_GROUPEND -}; - void AP_IMU_INS::init( Start_style style, void (*delay_cb)(unsigned long t), diff --git a/libraries/AP_IMU/AP_IMU_INS.h b/libraries/AP_IMU/AP_IMU_INS.h index d8f44d870a..6e5311ab7b 100644 --- a/libraries/AP_IMU/AP_IMU_INS.h +++ b/libraries/AP_IMU/AP_IMU_INS.h @@ -64,11 +64,8 @@ public: virtual void ay(const float v) { _sensor_cal[4] = v; } virtual void az(const float v) { _sensor_cal[5] = v; } - static const struct AP_Param::GroupInfo var_info[]; - private: AP_InertialSensor *_ins; ///< INS provides an axis and unit correct sensor source. - AP_Vector6f _sensor_cal; ///< Calibrated sensor offsets virtual void _init_accel(void (*delay_cb)(unsigned long t), void (*flash_leds_cb)(bool on) = NULL); ///< no-save implementation diff --git a/libraries/AP_IMU/IMU.cpp b/libraries/AP_IMU/IMU.cpp index ed77b1b759..913020235b 100644 --- a/libraries/AP_IMU/IMU.cpp +++ b/libraries/AP_IMU/IMU.cpp @@ -1,6 +1,13 @@ #include "IMU.h" +// this allows the sensor calibration to be saved to EEPROM +const AP_Param::GroupInfo IMU::var_info[] PROGMEM = { + AP_GROUPINFO("CAL", 0, IMU, _sensor_cal), + AP_GROUPEND +}; + + /* Empty implementations for the IMU functions. * Although these will never be used, in certain situations with * optimizations turned off, having empty implementations in an object diff --git a/libraries/AP_IMU/IMU.h b/libraries/AP_IMU/IMU.h index f5710d70af..f2ccb2d4a0 100644 --- a/libraries/AP_IMU/IMU.h +++ b/libraries/AP_IMU/IMU.h @@ -104,7 +104,12 @@ public: virtual void ay(const float v); virtual void az(const float v); + static const struct AP_Param::GroupInfo var_info[]; + protected: + + AP_Vector6f _sensor_cal; ///< Calibrated sensor offsets + /// Most recent accelerometer reading obtained by ::update Vector3f _accel; Vector3f _accel_filtered; From 6b357fc66b7368e4b66c391c3a1f0abd0ee7af5e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 18 Feb 2012 10:39:57 +1100 Subject: [PATCH 22/33] AP_Param: fixed saving of sensor calibration this fixes the saving of the accel and gyro calibration to EEPROM, which was initially broken by the AP_Param conversion --- ArduCopter/Parameters.h | 2 +- ArduCopter/Parameters.pde | 3 ++- ArduPlane/Parameters.h | 2 +- ArduPlane/Parameters.pde | 3 ++- 4 files changed, 6 insertions(+), 4 deletions(-) diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index a4e952f6f5..5023882a99 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -92,7 +92,7 @@ public: // // 140: Sensor parameters // - k_param_IMU_calibration = 140, + k_param_imu = 140, // sensor calibration k_param_battery_monitoring, k_param_volt_div_ratio, k_param_curr_amp_per_volt, diff --git a/ArduCopter/Parameters.pde b/ArduCopter/Parameters.pde index 27470800e9..f6520830b2 100644 --- a/ArduCopter/Parameters.pde +++ b/ArduCopter/Parameters.pde @@ -142,7 +142,8 @@ static const AP_Param::Info var_info[] PROGMEM = { // variables not in the g class which contain EEPROM saved variables GOBJECT(compass, "COMPASS_", Compass), GOBJECT(gcs0, "SR0_", GCS_MAVLINK), - GOBJECT(gcs3, "SR3_", GCS_MAVLINK) + GOBJECT(gcs3, "SR3_", GCS_MAVLINK), + GOBJECT(imu, "IMU_", IMU) }; diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h index e2d9043e09..f508e6c38d 100644 --- a/ArduPlane/Parameters.h +++ b/ArduPlane/Parameters.h @@ -68,7 +68,7 @@ public: // // 130: Sensor parameters // - k_param_IMU_calibration = 130, + k_param_imu = 130, // sensor calibration k_param_altitude_mix, k_param_airspeed_ratio, k_param_ground_temperature, diff --git a/ArduPlane/Parameters.pde b/ArduPlane/Parameters.pde index 08248072d5..4b0bda9ae0 100644 --- a/ArduPlane/Parameters.pde +++ b/ArduPlane/Parameters.pde @@ -123,7 +123,8 @@ static const AP_Param::Info var_info[] PROGMEM = { // variables not in the g class which contain EEPROM saved variables GOBJECT(compass, "COMPASS_", Compass), GOBJECT(gcs0, "SR0_", GCS_MAVLINK), - GOBJECT(gcs3, "SR3_", GCS_MAVLINK) + GOBJECT(gcs3, "SR3_", GCS_MAVLINK), + GOBJECT(imu, "IMU_", IMU) }; From cb2af1ef8615883ba4ed7774e627cdfc5c84c89e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 18 Feb 2012 10:40:14 +1100 Subject: [PATCH 23/33] don't need AP_Math.h here any more --- Tools/CPUInfo/CPUInfo.pde | 1 - 1 file changed, 1 deletion(-) diff --git a/Tools/CPUInfo/CPUInfo.pde b/Tools/CPUInfo/CPUInfo.pde index d0192b01e2..40b295b310 100644 --- a/Tools/CPUInfo/CPUInfo.pde +++ b/Tools/CPUInfo/CPUInfo.pde @@ -6,7 +6,6 @@ */ #include -#include #include FastSerialPort0(Serial); From db4fef174b6bb11997fc305d4ace1a56c848598f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 18 Feb 2012 10:50:01 +1100 Subject: [PATCH 24/33] ACM: expanded EEPROM parameter area by 256 bytes --- ArduCopter/defines.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index 434a090335..e40d8426af 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -346,8 +346,8 @@ enum gcs_severity { // EEPROM addresses #define EEPROM_MAX_ADDR 4096 -// parameters get the first 1024 bytes of EEPROM, remainder is for waypoints -#define WP_START_BYTE 0x400 // where in memory home WP is stored + all other WP +// parameters get the first 1280 bytes of EEPROM, remainder is for waypoints +#define WP_START_BYTE 0x500 // where in memory home WP is stored + all other WP #define WP_SIZE 15 #define ONBOARD_PARAM_NAME_LENGTH 15 From b6fdf626e4202259b85c2bca0143fcfbea98db49 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 18 Feb 2012 10:51:17 +1100 Subject: [PATCH 25/33] APM: expanded parameter area to match ACM this ensures waypoints and basic eeprom layout remain in sync --- ArduPlane/defines.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduPlane/defines.h b/ArduPlane/defines.h index 4b54294e53..a5ac6e85a1 100644 --- a/ArduPlane/defines.h +++ b/ArduPlane/defines.h @@ -200,8 +200,8 @@ enum gcs_severity { // EEPROM addresses #define EEPROM_MAX_ADDR 4096 -// parameters get the first 1024 bytes of EEPROM, remainder is for waypoints -#define WP_START_BYTE 0x400 // where in memory home WP is stored + all other WP +// parameters get the first 1280 bytes of EEPROM, remainder is for waypoints +#define WP_START_BYTE 0x500 // where in memory home WP is stored + all other WP #define WP_SIZE 15 // fence points are stored at the end of the EEPROM From 5652ccd3c6c3dfeb3c234aa3315cf031ae7d81ce Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 18 Feb 2012 17:41:46 +1100 Subject: [PATCH 26/33] autotest: fixed the calculation of the acceleration due to gravity this fixes the attitude calculation for the multicopter simulation --- Tools/autotest/pysim/aircraft.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/autotest/pysim/aircraft.py b/Tools/autotest/pysim/aircraft.py index 5038c90cf4..b45f3156a7 100644 --- a/Tools/autotest/pysim/aircraft.py +++ b/Tools/autotest/pysim/aircraft.py @@ -70,7 +70,7 @@ class Aircraft(object): from math import sin, cos, sqrt, radians # work out what the accelerometer would see - xAccel = sin(radians(self.pitch)) * cos(radians(self.roll)) + xAccel = sin(radians(self.pitch)) yAccel = -sin(radians(self.roll)) * cos(radians(self.pitch)) zAccel = -cos(radians(self.roll)) * cos(radians(self.pitch)) scale = 9.81 / sqrt((xAccel*xAccel)+(yAccel*yAccel)+(zAccel*zAccel)) From 9602b1f91b1b11ad66b7e6f666cd508f3dd312ce Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 18 Feb 2012 17:44:31 +1100 Subject: [PATCH 27/33] DCM: only add in centripetal accel if we have GPS lock if we don't have a GPS or the GPS doesn't have a good lock then we can't rely on the ground speed for adjusting the acceleration vector --- libraries/AP_DCM/AP_DCM.cpp | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/libraries/AP_DCM/AP_DCM.cpp b/libraries/AP_DCM/AP_DCM.cpp index c6deb7f63f..765e9d106e 100644 --- a/libraries/AP_DCM/AP_DCM.cpp +++ b/libraries/AP_DCM/AP_DCM.cpp @@ -131,8 +131,11 @@ AP_DCM::matrix_update(float _G_Dt) _omega_integ_corr = _gyro_vector + _omega_I; // Used for _centripetal correction (theoretically better than _omega) _omega = _omega_integ_corr + _omega_P; // Equation 16, adding proportional and integral correction terms - if(_centripetal){ - accel_adjust(); // Remove _centripetal acceleration. + if(_centripetal && + _gps != NULL && + _gps->status() == GPS::GPS_OK) { + // Remove _centripetal acceleration. + accel_adjust(); } #if OUTPUTMODE == 1 @@ -174,9 +177,7 @@ AP_DCM::accel_adjust(void) { Vector3f veloc, temp; - if (_gps) { - veloc.x = _gps->ground_speed / 100; // We are working with acceleration in m/s^2 units - } + veloc.x = _gps->ground_speed / 100; // We are working with acceleration in m/s^2 units // We are working with a modified version of equation 26 as our IMU object reports acceleration in the positive axis direction as positive From 2472f0a2f3fa36df98811a43a8472e0fa488bc9d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 18 Feb 2012 17:45:56 +1100 Subject: [PATCH 28/33] SITL: increase the amount of noise in the simulated ADC this increases the noise to 2 bits, which actually can have the effect of improving accuracy, as it leads to better averaging --- libraries/Desktop/support/sitl_adc.h | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/libraries/Desktop/support/sitl_adc.h b/libraries/Desktop/support/sitl_adc.h index 38a3caba44..a467a20b7f 100644 --- a/libraries/Desktop/support/sitl_adc.h +++ b/libraries/Desktop/support/sitl_adc.h @@ -8,6 +8,15 @@ #include +#define NOISE_BITS 4 + +static inline float noise_generator(void) +{ + float noise = ((unsigned)random()) & ((1<= 0x1000) { next_value = 0xFFF; } From 455f1a80936b08332ce9daa06ed9a381e67a296b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 18 Feb 2012 19:20:50 +1100 Subject: [PATCH 29/33] autotest: removed the pitch trim from the Rascal This interferes with the calculation of the centripetal acceleration calculation in the DCM code. We need a new way of handling pitch trim --- Tools/autotest/ArduPlane.parm | 2 +- Tools/autotest/aircraft/Rascal/Rascal.xml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Tools/autotest/ArduPlane.parm b/Tools/autotest/ArduPlane.parm index 80b1023365..bad1c82b82 100644 --- a/Tools/autotest/ArduPlane.parm +++ b/Tools/autotest/ArduPlane.parm @@ -2,7 +2,7 @@ LOG_BITMASK 4095 SWITCH_ENABLE 0 MAG_ENABLE 1 TRIM_ARSPD_CM 2200 -TRIM_PITCH_CD -1000 +TRIM_PITCH_CD 0 ARSPD_ENABLE 1 ARSP2PTCH_I 0.1 ARSPD_FBW_MAX 30 diff --git a/Tools/autotest/aircraft/Rascal/Rascal.xml b/Tools/autotest/aircraft/Rascal/Rascal.xml index 2e2813a25b..bf4321ee12 100644 --- a/Tools/autotest/aircraft/Rascal/Rascal.xml +++ b/Tools/autotest/aircraft/Rascal/Rascal.xml @@ -86,7 +86,7 @@ 68.9 0 - -3 + -13.1 8.0 5.0 From 0b369cf78b71cfcbe28bd3c1480b3f7b20f4075b Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sat, 18 Feb 2012 18:09:40 +0900 Subject: [PATCH 30/33] Optflow - added reference to FastSerial to resolve compile error on Arduino 1.0. also removed reference to DCM (no longer required) and removed some old code. --- libraries/AP_OpticalFlow/AP_OpticalFlow.cpp | 29 +-------------------- libraries/AP_OpticalFlow/AP_OpticalFlow.h | 2 +- 2 files changed, 2 insertions(+), 29 deletions(-) diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp index d2f6daa468..00fb2eca2c 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp @@ -108,31 +108,4 @@ AP_OpticalFlow::update_position(float roll, float pitch, float cos_yaw_x, float _last_altitude = altitude; _last_roll = roll; _last_pitch = pitch; -} - - -/* -{ - // only update position if surface quality is good and angle is not over 45 degrees - if( surface_quality >= 10 && fabs(_dcm->roll) <= FORTYFIVE_DEGREES && fabs(_dcm->pitch) <= FORTYFIVE_DEGREES ) { - altitude = max(altitude, 0); - Vector3f omega = _dcm->get_gyro(); - - // calculate expected x,y diff due to roll and pitch change - float exp_change_x = omega.x * radians_to_pixels; - float exp_change_y = -omega.y * radians_to_pixels; - - // real estimated raw change from mouse - float change_x = dx - exp_change_x; - float change_y = dy - exp_change_y; - - // convert raw change to horizontal movement in cm - float x_cm = -change_x * altitude * conv_factor; // perhaps this altitude should actually be the distance to the ground? i.e. if we are very rolled over it should be longer? - float y_cm = -change_y * altitude * conv_factor; // for example if you are leaned over at 45 deg the ground will appear farther away and motion from opt flow sensor will be less - - vlon = (float)x_cm * sin_yaw_y - (float)y_cm * cos_yaw_x; - vlat = (float)y_cm * sin_yaw_y - (float)x_cm * cos_yaw_x; - } -} - -*/ +} \ No newline at end of file diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow.h b/libraries/AP_OpticalFlow/AP_OpticalFlow.h index 0e36a6c5b3..968de9cd49 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow.h +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow.h @@ -17,8 +17,8 @@ write_register() : writes a value to one of the sensor's register (will be sensor specific) */ +#include #include -#include #include // standard rotation matrices From cd8925829466f73652aa2b4a1374606ca40a142f Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sat, 18 Feb 2012 18:44:29 +0900 Subject: [PATCH 31/33] ArduCopter - updated version to 2.4 --- ArduCopter/ArduCopter.pde | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 40b994ac87..21dfd0d919 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1,8 +1,8 @@ /// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- -#define THISFIRMWARE "ArduCopter V2.3.1" +#define THISFIRMWARE "ArduCopter V2.4" /* -ArduCopter Version 2.3.1 +ArduCopter Version 2.4 Authors: Jason Short Based on code and ideas from the Arducopter team: Randy Mackay, Pat Hickey, Jose Julio, Jani Hirvinen Thanks to: Chris Anderson, Mike Smith, Jordi Munoz, Doug Weibel, James Goppert, Benjamin Pelletier From b55db247ca6ba434dfeaeef40f238af9d562fa47 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sat, 18 Feb 2012 20:57:51 +0900 Subject: [PATCH 32/33] TradHeli - fixed small parameter bug affecting helis. The servo parameters were declared as GSCALAR instead of GGROUP in Parameters.pde. also renamed heli parameters from _coll_ to the more descriptive _collective_ --- ArduCopter/Parameters.h | 18 +++++++----------- ArduCopter/Parameters.pde | 16 ++++++++-------- ArduCopter/heli.pde | 22 +++++++++++----------- ArduCopter/setup.pde | 38 +++++++++++++++++++------------------- 4 files changed, 45 insertions(+), 49 deletions(-) diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index 5023882a99..b880130717 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -78,7 +78,7 @@ public: k_param_heli_servo_averaging, k_param_heli_servo_manual, k_param_heli_phase_angle, - k_param_heli_coll_yaw_effect, // 97 + k_param_heli_collective_yaw_effect, // 97 #endif // 110: Telemetry control @@ -268,13 +268,13 @@ public: RC_Channel heli_servo_1, heli_servo_2, heli_servo_3, heli_servo_4; // servos for swash plate and tail AP_Int16 heli_servo1_pos, heli_servo2_pos, heli_servo3_pos; // servo positions (3 because we don't need pos for tail servo) AP_Int16 heli_roll_max, heli_pitch_max; // maximum allowed roll and pitch of swashplate - AP_Int16 heli_coll_min, heli_coll_max, heli_coll_mid; // min and max collective. mid = main blades at zero pitch + AP_Int16 heli_collective_min, heli_collective_max, heli_collective_mid; // min and max collective. mid = main blades at zero pitch AP_Int8 heli_ext_gyro_enabled; // 0 = no external tail gyro, 1 = external tail gyro AP_Int16 heli_ext_gyro_gain; // radio output 1000~2000 (value output on CH_7) AP_Int8 heli_servo_averaging; // 0 or 1 = no averaging (250hz) for **digital servos**, 2=average of two samples (125hz), 3=three samples (83.3hz) **analog servos**, 4=four samples (62.5hz), 5=5 samples(50hz) AP_Int8 heli_servo_manual; // 0 = normal mode, 1 = radio inputs directly control swash. required for swash set-up AP_Int16 heli_phase_angle; // 0 to 360 degrees. specifies mixing between roll and pitch for helis - AP_Float heli_coll_yaw_effect; // -5.0 ~ 5.0. Feed forward control from collective to yaw. 1.0 = move rudder right 1% for every 1% of collective above the mid point + AP_Float heli_collective_yaw_effect; // -5.0 ~ 5.0. Feed forward control from collective to yaw. 1.0 = move rudder right 1% for every 1% of collective above the mid point #endif // RC channels @@ -377,24 +377,20 @@ public: auto_slew_rate (AUTO_SLEW_RATE), #if FRAME_CONFIG == HELI_FRAME - heli_servo_1 (k_param_heli_servo_1), - heli_servo_2 (k_param_heli_servo_2), - heli_servo_3 (k_param_heli_servo_3), - heli_servo_4 (k_param_heli_servo_4), heli_servo1_pos (-60), heli_servo2_pos (60), heli_servo3_pos (180), heli_roll_max (4500), heli_pitch_max (4500), - heli_coll_min (1250), - heli_coll_max (1750), - heli_coll_mid (1500), + heli_collective_min (1250), + heli_collective_max (1750), + heli_collective_mid (1500), heli_ext_gyro_enabled (0), heli_ext_gyro_gain (1350), heli_servo_averaging (0), heli_servo_manual (0), heli_phase_angle (0), - heli_coll_yaw_effect (0), + heli_collective_yaw_effect (0), #endif camera_pitch_gain (CAM_PITCH_GAIN), diff --git a/ArduCopter/Parameters.pde b/ArduCopter/Parameters.pde index f6520830b2..aa1adcb440 100644 --- a/ArduCopter/Parameters.pde +++ b/ArduCopter/Parameters.pde @@ -72,24 +72,24 @@ static const AP_Param::Info var_info[] PROGMEM = { GSCALAR(auto_slew_rate, "AUTO_SLEW"), #if FRAME_CONFIG == HELI_FRAME - GSCALAR(heli_servo_1, "HS1_"), - GSCALAR(heli_servo_2, "HS2_"), - GSCALAR(heli_servo_3, "HS3_"), - GSCALAR(heli_servo_4, "HS4_"), + GGROUP(heli_servo_1, "HS1_", RC_Channel), + GGROUP(heli_servo_2, "HS2_", RC_Channel), + GGROUP(heli_servo_3, "HS3_", RC_Channel), + GGROUP(heli_servo_4, "HS4_", RC_Channel), GSCALAR(heli_servo1_pos, "SV1_POS_"), GSCALAR(heli_servo2_pos, "SV2_POS_"), GSCALAR(heli_servo3_pos, "SV3_POS_"), GSCALAR(heli_roll_max, "ROL_MAX_"), GSCALAR(heli_pitch_max, "PIT_MAX_"), - GSCALAR(heli_coll_min, "COL_MIN_"), - GSCALAR(heli_coll_max, "COL_MAX_"), - GSCALAR(heli_coll_mid, "COL_MID_"), + GSCALAR(heli_collective_min, "COL_MIN_"), + GSCALAR(heli_collective_max, "COL_MAX_"), + GSCALAR(heli_collective_mid, "COL_MID_"), GSCALAR(heli_ext_gyro_enabled, "GYR_ENABLE_"), GSCALAR(heli_ext_gyro_gain, "GYR_GAIN_"), GSCALAR(heli_servo_averaging, "SV_AVG"), GSCALAR(heli_servo_manual, "HSV_MAN"), GSCALAR(heli_phase_angle, "H_PHANG"), - GSCALAR(heli_coll_yaw_effect, "H_COLYAW"), + GSCALAR(heli_collective_yaw_effect, "H_COLYAW"), #endif // RC channel diff --git a/ArduCopter/heli.pde b/ArduCopter/heli.pde index 964df74d45..95ee7a660b 100644 --- a/ArduCopter/heli.pde +++ b/ArduCopter/heli.pde @@ -7,7 +7,7 @@ static bool heli_swash_initialised = false; static int heli_throttle_mid = 0; // throttle mid point in pwm form (i.e. 0 ~ 1000) -static float heli_coll_scalar = 1; // throttle scalar to convert pwm form (i.e. 0 ~ 1000) passed in to actual servo range (i.e 1250~1750 would be 500) +static float heli_collective_scalar = 1; // throttle scalar to convert pwm form (i.e. 0 ~ 1000) passed in to actual servo range (i.e 1250~1750 would be 500) // heli_servo_averaging: // 0 or 1 = no averaging, 250hz @@ -39,7 +39,7 @@ static void heli_reset_swash() heli_rollFactor[CH_3] = cos(radians(g.heli_servo3_pos + 90 - g.heli_phase_angle)); // set throttle scaling - heli_coll_scalar = ((float)(g.rc_3.radio_max - g.rc_3.radio_min))/1000.0; + heli_collective_scalar = ((float)(g.rc_3.radio_max - g.rc_3.radio_min))/1000.0; // we must be in set-up mode so mark swash as uninitialised heli_swash_initialised = false; @@ -57,17 +57,17 @@ static void heli_init_swash() g.heli_servo_4.set_angle(4500); // ensure g.heli_coll values are reasonable - if( g.heli_coll_min >= g.heli_coll_max ) { - g.heli_coll_min = 1000; - g.heli_coll_max = 2000; + if( g.heli_collective_min >= g.heli_collective_max ) { + g.heli_collective_min = 1000; + g.heli_collective_max = 2000; } - g.heli_coll_mid = constrain(g.heli_coll_mid, g.heli_coll_min, g.heli_coll_max); + g.heli_collective_mid = constrain(g.heli_collective_mid, g.heli_collective_min, g.heli_collective_max); // calculate throttle mid point - heli_throttle_mid = ((float)(g.heli_coll_mid-g.heli_coll_min))/((float)(g.heli_coll_max-g.heli_coll_min))*1000.0; + heli_throttle_mid = ((float)(g.heli_collective_mid-g.heli_collective_min))/((float)(g.heli_collective_max-g.heli_collective_min))*1000.0; // determine scalar throttle input - heli_coll_scalar = ((float)(g.heli_coll_max-g.heli_coll_min))/1000.0; + heli_collective_scalar = ((float)(g.heli_collective_max-g.heli_collective_min))/1000.0; // pitch factors heli_pitchFactor[CH_1] = cos(radians(g.heli_servo1_pos - g.heli_phase_angle)); @@ -128,7 +128,7 @@ static void heli_move_swash(int roll_out, int pitch_out, int coll_out, int yaw_o if( heli_swash_initialised ) { heli_reset_swash(); } - coll_out_scaled = coll_out * heli_coll_scalar + g.rc_3.radio_min - 1000; + coll_out_scaled = coll_out * heli_collective_scalar + g.rc_3.radio_min - 1000; }else{ // regular flight mode // check if we need to reinitialise the swash @@ -140,12 +140,12 @@ static void heli_move_swash(int roll_out, int pitch_out, int coll_out, int yaw_o roll_out = constrain(roll_out, (int)-g.heli_roll_max, (int)g.heli_roll_max); pitch_out = constrain(pitch_out, (int)-g.heli_pitch_max, (int)g.heli_pitch_max); coll_out = constrain(coll_out, 0, 1000); - coll_out_scaled = coll_out * heli_coll_scalar + g.heli_coll_min - 1000; + coll_out_scaled = coll_out * heli_collective_scalar + g.heli_collective_min - 1000; // rudder feed forward based on collective #if HIL_MODE == HIL_MODE_DISABLED // don't do rudder feed forward in simulator if( !g.heli_ext_gyro_enabled ) { - yaw_offset = g.heli_coll_yaw_effect * abs(coll_out_scaled - g.heli_coll_mid); + yaw_offset = g.heli_collective_yaw_effect * abs(coll_out_scaled - g.heli_collective_mid); } #endif } diff --git a/ArduCopter/setup.pde b/ArduCopter/setup.pde index 7a327971da..4fe6e85be9 100644 --- a/ArduCopter/setup.pde +++ b/ArduCopter/setup.pde @@ -457,7 +457,7 @@ setup_heli(uint8_t argc, const Menu::arg *argv) int value = 0; int temp; int state = 0; // 0 = set rev+pos, 1 = capture min/max - int max_roll, max_pitch, min_coll, max_coll, min_tail, max_tail; + int max_roll, max_pitch, min_collective, max_collective, min_tail, max_tail; // initialise swash plate heli_init_swash(); @@ -497,10 +497,10 @@ setup_heli(uint8_t argc, const Menu::arg *argv) max_roll = abs(g.rc_1.control_in); if( abs(g.rc_2.control_in) > max_pitch ) max_pitch = abs(g.rc_2.control_in); - if( g.rc_3.radio_out < min_coll ) - min_coll = g.rc_3.radio_out; - if( g.rc_3.radio_out > max_coll ) - max_coll = g.rc_3.radio_out; + if( g.rc_3.radio_out < min_collective ) + min_collective = g.rc_3.radio_out; + if( g.rc_3.radio_out > max_collective ) + max_collective = g.rc_3.radio_out; min_tail = min(g.rc_4.radio_out, min_tail); max_tail = max(g.rc_4.radio_out, max_tail); } @@ -529,8 +529,8 @@ setup_heli(uint8_t argc, const Menu::arg *argv) case 'c': case 'C': if( g.rc_3.radio_out >= 900 && g.rc_3.radio_out <= 2100 ) { - g.heli_coll_mid = g.rc_3.radio_out; - Serial.printf_P(PSTR("Collective when blade pitch at zero: %d\n"),(int)g.heli_coll_mid); + g.heli_collective_mid = g.rc_3.radio_out; + Serial.printf_P(PSTR("Collective when blade pitch at zero: %d\n"),(int)g.heli_collective_mid); } break; case 'd': @@ -546,27 +546,27 @@ setup_heli(uint8_t argc, const Menu::arg *argv) // reset servo ranges g.heli_roll_max = g.heli_pitch_max = 4500; - g.heli_coll_min = 1000; - g.heli_coll_max = 2000; + g.heli_collective_min = 1000; + g.heli_collective_max = 2000; g.heli_servo_4.radio_min = 1000; g.heli_servo_4.radio_max = 2000; // set sensible values in temp variables max_roll = abs(g.rc_1.control_in); max_pitch = abs(g.rc_2.control_in); - min_coll = 2000; - max_coll = 1000; + min_collective = 2000; + max_collective = 1000; min_tail = max_tail = abs(g.rc_4.radio_out); }else{ state = 0; // switch back to normal mode // double check values aren't totally terrible - if( max_roll <= 1000 || max_pitch <= 1000 || (max_coll - min_coll < 200) || (max_tail - min_tail < 200) || min_tail < 1000 || max_tail > 2000 ) - Serial.printf_P(PSTR("Invalid min/max captured roll:%d, pitch:%d, collective min: %d max: %d, tail min:%d max:%d\n"),max_roll,max_pitch,min_coll,max_coll,min_tail,max_tail); + if( max_roll <= 1000 || max_pitch <= 1000 || (max_collective - min_collective < 200) || (max_tail - min_tail < 200) || min_tail < 1000 || max_tail > 2000 ) + Serial.printf_P(PSTR("Invalid min/max captured roll:%d, pitch:%d, collective min: %d max: %d, tail min:%d max:%d\n"),max_roll,max_pitch,min_collective,max_collective,min_tail,max_tail); else{ g.heli_roll_max = max_roll; g.heli_pitch_max = max_pitch; - g.heli_coll_min = min_coll; - g.heli_coll_max = max_coll; + g.heli_collective_min = min_collective; + g.heli_collective_max = max_collective; g.heli_servo_4.radio_min = min_tail; g.heli_servo_4.radio_max = max_tail; @@ -650,9 +650,9 @@ setup_heli(uint8_t argc, const Menu::arg *argv) g.heli_servo3_pos.save(); g.heli_roll_max.save(); g.heli_pitch_max.save(); - g.heli_coll_min.save(); - g.heli_coll_max.save(); - g.heli_coll_mid.save(); + g.heli_collective_min.save(); + g.heli_collective_max.save(); + g.heli_collective_mid.save(); g.heli_servo_averaging.save(); // return swash plate movements to attitude controller @@ -942,7 +942,7 @@ static void report_heli() Serial.printf_P(PSTR("roll max: \t%d\n"), (int)g.heli_roll_max); Serial.printf_P(PSTR("pitch max: \t%d\n"), (int)g.heli_pitch_max); - Serial.printf_P(PSTR("coll min:\t%d\t mid:%d\t max:%d\n"),(int)g.heli_coll_min, (int)g.heli_coll_mid, (int)g.heli_coll_max); + Serial.printf_P(PSTR("coll min:\t%d\t mid:%d\t max:%d\n"),(int)g.heli_collective_min, (int)g.heli_collective_mid, (int)g.heli_collective_max); // calculate and print servo rate if( g.heli_servo_averaging <= 1 ) { From e3c24fbce8d9077742b1c68948e22474c1659f98 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sat, 18 Feb 2012 22:04:09 +0900 Subject: [PATCH 33/33] ArduCopter - fix for yaw control on Octa Quad Plus frame. --- ArduCopter/motors_octa_quad.pde | 23 +++++++++++------------ 1 file changed, 11 insertions(+), 12 deletions(-) diff --git a/ArduCopter/motors_octa_quad.pde b/ArduCopter/motors_octa_quad.pde index 1728d0754f..b8566f7f8e 100644 --- a/ArduCopter/motors_octa_quad.pde +++ b/ArduCopter/motors_octa_quad.pde @@ -51,7 +51,6 @@ static void output_motors_armed() motor_out[MOT_6] = g.rc_3.radio_out - roll_out + pitch_out; // APM2 OUT6 APM1 OUT8 FRONT RIGHT CW BOTTOM motor_out[MOT_7] = g.rc_3.radio_out - roll_out - pitch_out; // APM2 OUT7 APM1 OUT10 BACK RIGHT CCW BOTTOM motor_out[MOT_8] = g.rc_3.radio_out + roll_out - pitch_out; // APM2 OUT8 APM1 OUT11 BACK LEFT CW BOTTOM - }else{ roll_out = g.rc_1.pwm_out; pitch_out = g.rc_2.pwm_out; @@ -64,19 +63,19 @@ static void output_motors_armed() motor_out[MOT_6] = g.rc_3.radio_out + pitch_out; // APM2 OUT6 APM1 OUT8 FRONT CW BOTTOM motor_out[MOT_7] = g.rc_3.radio_out - roll_out; // APM2 OUT7 APM1 OUT10 RIGHT CCW BOTTOM motor_out[MOT_8] = g.rc_3.radio_out - pitch_out; // APM2 OUT8 APM1 OUT11 BACK CW BOTTOM - - // Yaw - motor_out[MOT_1] += g.rc_4.pwm_out; // CCW - motor_out[MOT_3] += g.rc_4.pwm_out; // CCW - motor_out[MOT_5] += g.rc_4.pwm_out; // CCW - motor_out[MOT_7] += g.rc_4.pwm_out; // CCW - - motor_out[MOT_2] -= g.rc_4.pwm_out; // CW - motor_out[MOT_4] -= g.rc_4.pwm_out; // CW - motor_out[MOT_6] -= g.rc_4.pwm_out; // CW - motor_out[MOT_8] -= g.rc_4.pwm_out; // CW } + // Yaw + motor_out[MOT_1] += g.rc_4.pwm_out; // CCW + motor_out[MOT_3] += g.rc_4.pwm_out; // CCW + motor_out[MOT_5] += g.rc_4.pwm_out; // CCW + motor_out[MOT_7] += g.rc_4.pwm_out; // CCW + + motor_out[MOT_2] -= g.rc_4.pwm_out; // CW + motor_out[MOT_4] -= g.rc_4.pwm_out; // CW + motor_out[MOT_6] -= g.rc_4.pwm_out; // CW + motor_out[MOT_8] -= g.rc_4.pwm_out; // CW + // TODO add stability patch motor_out[MOT_1] = min(motor_out[MOT_1], out_max); motor_out[MOT_2] = min(motor_out[MOT_2], out_max);