From e2560c5865c2a34e3f12a7f15ebd1cb085071c06 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Thu, 22 Mar 2012 10:01:24 -0700 Subject: [PATCH 01/78] Throttle_hold was in APM_Config - which is ignored by the Mission planner Hex generator --- ArduCopter/config.h | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 8c489897f9..398cd1abed 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -722,6 +722,10 @@ ////////////////////////////////////////////////////////////////////////////// // Throttle control gains // +#ifndef AUTO_THROTTLE_HOLD +# define AUTO_THROTTLE_HOLD 1 +#endif + #ifndef THROTTLE_CRUISE # define THROTTLE_CRUISE 450 // #endif From f1acdb13c20796b9f76a6e748e01ac7f232e3c92 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 23 Mar 2012 16:24:52 +1100 Subject: [PATCH 02/78] pysim: added experimental acceleration support --- Tools/autotest/pysim/aircraft.py | 17 +++++++++++------ Tools/autotest/pysim/multicopter.py | 13 +++++++++++-- Tools/autotest/pysim/sim_multicopter.py | 2 +- 3 files changed, 23 insertions(+), 9 deletions(-) diff --git a/Tools/autotest/pysim/aircraft.py b/Tools/autotest/pysim/aircraft.py index af1d786853..2806613271 100644 --- a/Tools/autotest/pysim/aircraft.py +++ b/Tools/autotest/pysim/aircraft.py @@ -21,14 +21,20 @@ class Aircraft(object): self.velocity = Vector3(0, 0, 0) # m/s, North, East, Down self.position = Vector3(0, 0, 0) # m North, East, Down - self.last_velocity = self.velocity.copy() self.mass = 0.0 self.update_frequency = 50 # in Hz self.gravity = 9.8 # m/s/s - self.accelerometer = Vector3(0, 0, self.gravity) + self.accelerometer = Vector3(0, 0, -self.gravity) self.wind = util.Wind('0,0,0') + def on_ground(self, position=None): + '''return true if we are on the ground''' + if position is None: + position = self.position + return (-position.z) + self.home_altitude <= self.ground_level + self.frame_height + + def update_position(self, delta_time): '''update lat/lon/alt from position''' @@ -41,8 +47,7 @@ class Aircraft(object): self.altitude = self.home_altitude - self.position.z + velocity_body = self.dcm.transposed() * self.velocity + # work out what the accelerometer would see - self.accelerometer = ((self.velocity - self.last_velocity)/delta_time) + Vector3(0,0,self.gravity) -# self.accelerometer = Vector3(0,0,-self.gravity) - self.accelerometer = self.dcm.transposed() * self.accelerometer - self.last_velocity = self.velocity.copy() + self.accelerometer = self.accel_body diff --git a/Tools/autotest/pysim/multicopter.py b/Tools/autotest/pysim/multicopter.py index 1eca2c62a1..3447189271 100755 --- a/Tools/autotest/pysim/multicopter.py +++ b/Tools/autotest/pysim/multicopter.py @@ -143,6 +143,15 @@ class MultiCopter(Aircraft): # add in some wind accel_earth += self.wind.accel(self.velocity) + # if we're on the ground, then our vertical acceleration is limited + # to zero. This effectively adds the force of the ground on the aircraft + if self.on_ground() and accel_earth.z > 0: + accel_earth.z = 0 + + # work out acceleration as seen by the accelerometers. It sees the kinematic + # acceleration (ie. real movement), plus gravity + self.accel_body = self.dcm.transposed() * (accel_earth + Vector3(0, 0, -self.gravity)) + # new velocity vector self.velocity += accel_earth * delta_time @@ -151,8 +160,8 @@ class MultiCopter(Aircraft): self.position += self.velocity * delta_time # constrain height to the ground - if (-self.position.z) + self.home_altitude < self.ground_level + self.frame_height: - if (-old_position.z) + self.home_altitude > self.ground_level + self.frame_height: + if self.on_ground(): + if not self.on_ground(old_position): print("Hit ground at %f m/s" % (self.velocity.z)) self.velocity = Vector3(0, 0, 0) diff --git a/Tools/autotest/pysim/sim_multicopter.py b/Tools/autotest/pysim/sim_multicopter.py index 3425521504..803e5f1e2c 100755 --- a/Tools/autotest/pysim/sim_multicopter.py +++ b/Tools/autotest/pysim/sim_multicopter.py @@ -46,7 +46,7 @@ def sim_send(m, a): buf = struct.pack('<16dI', a.latitude, a.longitude, a.altitude, degrees(yaw), a.velocity.x, a.velocity.y, - -a.accelerometer.x, -a.accelerometer.y, -a.accelerometer.z, + a.accelerometer.x, a.accelerometer.y, a.accelerometer.z, degrees(earth_rates.x), degrees(earth_rates.y), degrees(earth_rates.z), degrees(roll), degrees(pitch), degrees(yaw), math.sqrt(a.velocity.x*a.velocity.x + a.velocity.y*a.velocity.y), From a6d66dc45b5692253541d0b5e26ffe333a15363b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 23 Mar 2012 14:58:54 +1100 Subject: [PATCH 03/78] Math: added mul_transpose() operation this is equivalent to multiplying by m.transposed(), but is more efficient --- libraries/AP_Math/matrix3.cpp | 10 ++++++++++ libraries/AP_Math/matrix3.h | 3 +++ 2 files changed, 13 insertions(+) diff --git a/libraries/AP_Math/matrix3.cpp b/libraries/AP_Math/matrix3.cpp index 236a4263ff..8ad2ffd15c 100644 --- a/libraries/AP_Math/matrix3.cpp +++ b/libraries/AP_Math/matrix3.cpp @@ -163,6 +163,15 @@ Vector3 Matrix3::operator *(const Vector3 &v) const c.x * v.x + c.y * v.y + c.z * v.z); } +// multiplication of transpose by a vector +template +Vector3 Matrix3::mul_transpose(const Vector3 &v) const +{ + return Vector3(a.x * v.x + b.x * v.y + c.x * v.z, + a.y * v.x + b.y * v.y + c.y * v.z, + a.z * v.x + b.z * v.y + c.z * v.z); +} + // multiplication by another Matrix3 template Matrix3 Matrix3::operator *(const Matrix3 &m) const @@ -186,4 +195,5 @@ template void Matrix3::rotate(const Vector3 &g); template void Matrix3::from_euler(float roll, float pitch, float yaw); template void Matrix3::to_euler(float *roll, float *pitch, float *yaw); template Vector3 Matrix3::operator *(const Vector3 &v) const; +template Vector3 Matrix3::mul_transpose(const Vector3 &v) const; template Matrix3 Matrix3::operator *(const Matrix3 &m) const; diff --git a/libraries/AP_Math/matrix3.h b/libraries/AP_Math/matrix3.h index f11b6153bf..202d294fe2 100644 --- a/libraries/AP_Math/matrix3.h +++ b/libraries/AP_Math/matrix3.h @@ -92,6 +92,9 @@ public: // multiplication by a vector Vector3 operator *(const Vector3 &v) const; + // multiplication of transpose by a vector + Vector3 mul_transpose(const Vector3 &v) const; + // multiplication by another Matrix3 Matrix3 operator *(const Matrix3 &m) const; From 0f6e7a144999ff5d2043bc62ce7ea9d472bd411f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 23 Mar 2012 16:44:11 +1100 Subject: [PATCH 04/78] pysim: implement partial 3D acceleration support The simulator flies very badly when using the full acceleration code. I don't yet know if this is a bug in the simulation or a problem with AHRS not handling acceleration for multicopters. For now set the acceleration to be half a 'pure gravity' acceleration and half from the full 3D calculation. --- Tools/autotest/pysim/aircraft.py | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/Tools/autotest/pysim/aircraft.py b/Tools/autotest/pysim/aircraft.py index 2806613271..08aaaa8f40 100644 --- a/Tools/autotest/pysim/aircraft.py +++ b/Tools/autotest/pysim/aircraft.py @@ -49,5 +49,9 @@ class Aircraft(object): velocity_body = self.dcm.transposed() * self.velocity - # work out what the accelerometer would see - self.accelerometer = self.accel_body + # force the acceleration to mostly be from gravity. We should be using 100% accel_body, + # but right now that flies very badly as the AHRS system can't do centripetal correction + # for multicopters. This is a compromise until we get that sorted out + accel_true = self.accel_body + accel_fake = self.dcm.transposed() * Vector3(0, 0, -self.gravity) + self.accelerometer = (accel_true * 0.5) + (accel_fake * 0.5) From ee4803c12db937fbc627d906d1f6206cfda2c9a3 Mon Sep 17 00:00:00 2001 From: Michael Oborne Date: Fri, 23 Mar 2012 20:52:12 +0800 Subject: [PATCH 05/78] APM Planner 1.1.56 add ardutracker support add load/save setting in Tracker move getserialports to serial class hopefully fix dtr issue for good. --- .../Antenna/ArduTracker.cs | 155 ++++++++++++++ .../Antenna/ITrackerOutput.cs | 2 + Tools/ArdupilotMegaPlanner/Antenna/Maestro.cs | 2 + .../Antenna/Tracker.Designer.cs | 191 +++++++++++++++--- Tools/ArdupilotMegaPlanner/Antenna/Tracker.cs | 101 ++++++++- .../ArdupilotMegaPlanner/ArdupilotMega.csproj | 3 +- Tools/ArdupilotMegaPlanner/CommsSerialPort.cs | 56 +++++ .../GCSViews/FlightData.cs | 4 +- Tools/ArdupilotMegaPlanner/Log.cs | 2 +- Tools/ArdupilotMegaPlanner/MAVLink.cs | 3 - Tools/ArdupilotMegaPlanner/MainV2.cs | 71 ++----- Tools/ArdupilotMegaPlanner/PIDTunning.cs | 46 +++++ .../Properties/AssemblyInfo.cs | 2 +- .../bin/Release/ArdupilotMegaPlanner.pdb | Bin 1007104 -> 1017344 bytes 14 files changed, 539 insertions(+), 99 deletions(-) create mode 100644 Tools/ArdupilotMegaPlanner/Antenna/ArduTracker.cs create mode 100644 Tools/ArdupilotMegaPlanner/PIDTunning.cs diff --git a/Tools/ArdupilotMegaPlanner/Antenna/ArduTracker.cs b/Tools/ArdupilotMegaPlanner/Antenna/ArduTracker.cs new file mode 100644 index 0000000000..8665324335 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/Antenna/ArduTracker.cs @@ -0,0 +1,155 @@ +using System; +using System.Collections.Generic; +using System.Linq; +using System.Text; + +namespace ArdupilotMega.Antenna +{ + class ArduTracker : ITrackerOutput + { + public SerialPort ComPort { get; set; } + /// + /// 0-360 + /// + public double TrimPan { get; set; } + /// + /// -90 - 90 + /// + public double TrimTilt { get; set; } + + public int PanStartRange { get; set; } + public int TiltStartRange { get; set; } + public int PanEndRange { get; set; } + public int TiltEndRange { get; set; } + public int PanPWMRange { get; set; } + public int TiltPWMRange { get; set; } + + public bool PanReverse { get { return _panreverse == 1; } set { _panreverse = value == true ? -1 : 1; } } + public bool TiltReverse { get { return _tiltreverse == 1; } set { _tiltreverse = value == true ? -1 : 1; } } + + int _panreverse = 1; + int _tiltreverse = 1; + + int currentpan = 1500; + int currenttilt = 1500; + + public bool Init() + { + + if ((PanStartRange - PanEndRange) == 0) + { + System.Windows.Forms.CustomMessageBox.Show("Invalid Pan Range", "Error"); + return false; + } + + if ((TiltStartRange - TiltEndRange) == 0) + { + System.Windows.Forms.CustomMessageBox.Show("Invalid Tilt Range", "Error"); + return false; + } + + try + { + ComPort.Open(); + } + catch (Exception ex) { System.Windows.Forms.CustomMessageBox.Show("Connect failed " + ex.Message, "Error"); return false; } + + return true; + } + public bool Setup() + { + + + return true; + } + + double wrap_180(double input) + { + if (input > 180) + return input - 360; + if (input < -180) + return input + 360; + return input; + } + + double wrap_range(double input, double range) + { + if (input > range) + return input - 360; + if (input < -range) + return input + 360; + return input; + } + + public bool Pan(double Angle) + { + double range = Math.Abs(PanStartRange - PanEndRange); + + // get relative center based on tracking center + double rangeleft = PanStartRange - TrimPan; + double rangeright = PanEndRange - TrimPan; + double centerpos = 1500; + + // get the output angle the tracker needs to point and constrain the output to the allowed options + short PointAtAngle = Constrain(wrap_180(Angle - TrimPan), PanStartRange, PanEndRange); + + // conver the angle into a 0-pwmrange value + int target = (int)((((PointAtAngle / range) * 2.0) * (PanPWMRange / 2) * _panreverse + centerpos)); + + // Console.WriteLine("P " + Angle + " " + target + " " + PointAtAngle); + + currentpan = target; + + return false; + } + + public bool Tilt(double Angle) + { + double range = Math.Abs(TiltStartRange - TiltEndRange); + + short PointAtAngle = Constrain((Angle - TrimTilt), TiltStartRange, TiltEndRange); + + int target = (int)((((PointAtAngle / range) * 2.0) * (TiltPWMRange / 2) * _tiltreverse + 1500)); + + // Console.WriteLine("T " + Angle + " " + target + " " + PointAtAngle); + + currenttilt = target; + + return false; + } + + public bool PanAndTilt(double pan, double tilt) + { + Tilt(tilt); + Pan(pan); + + string command = string.Format("!!!PAN:{0:0000},TLT:{1:0000}\n", currentpan, currenttilt); + + Console.Write(command); + + ComPort.Write(command); + + return false; + } + + public bool Close() + { + try + { + ComPort.Close(); + } + catch { } + return true; + } + + short Constrain(double input, double min, double max) + { + if (input < min) + return (short)min; + if (input > max) + return (short)max; + return (short)input; + } + + } +} diff --git a/Tools/ArdupilotMegaPlanner/Antenna/ITrackerOutput.cs b/Tools/ArdupilotMegaPlanner/Antenna/ITrackerOutput.cs index deb5e84f42..bee2aa98df 100644 --- a/Tools/ArdupilotMegaPlanner/Antenna/ITrackerOutput.cs +++ b/Tools/ArdupilotMegaPlanner/Antenna/ITrackerOutput.cs @@ -16,6 +16,8 @@ namespace ArdupilotMega.Antenna int TiltStartRange { get; set; } int PanEndRange { get; set; } int TiltEndRange { get; set; } + int PanPWMRange { get; set; } + int TiltPWMRange { get; set; } bool PanReverse { get; set; } bool TiltReverse { get; set; } diff --git a/Tools/ArdupilotMegaPlanner/Antenna/Maestro.cs b/Tools/ArdupilotMegaPlanner/Antenna/Maestro.cs index 635b5048bb..26c73d8adf 100644 --- a/Tools/ArdupilotMegaPlanner/Antenna/Maestro.cs +++ b/Tools/ArdupilotMegaPlanner/Antenna/Maestro.cs @@ -21,6 +21,8 @@ namespace ArdupilotMega.Antenna public int TiltStartRange { get; set; } public int PanEndRange { get; set; } public int TiltEndRange { get; set; } + public int PanPWMRange { get; set; } + public int TiltPWMRange { get; set; } public bool PanReverse { get { return _panreverse == -1; } set { _panreverse = value == true ? -1 : 1 ; } } public bool TiltReverse { get { return _tiltreverse == -1; } set { _tiltreverse = value == true ? -1 : 1; } } diff --git a/Tools/ArdupilotMegaPlanner/Antenna/Tracker.Designer.cs b/Tools/ArdupilotMegaPlanner/Antenna/Tracker.Designer.cs index fd998debfe..0c34115461 100644 --- a/Tools/ArdupilotMegaPlanner/Antenna/Tracker.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/Antenna/Tracker.Designer.cs @@ -33,7 +33,6 @@ this.label1 = new System.Windows.Forms.Label(); this.CMB_baudrate = new System.Windows.Forms.ComboBox(); this.CMB_serialport = new System.Windows.Forms.ComboBox(); - this.BUT_connect = new ArdupilotMega.MyButton(); this.TRK_pantrim = new System.Windows.Forms.TrackBar(); this.TXT_panrange = new System.Windows.Forms.TextBox(); this.label3 = new System.Windows.Forms.Label(); @@ -44,6 +43,18 @@ this.TRK_tilttrim = new System.Windows.Forms.TrackBar(); this.label2 = new System.Windows.Forms.Label(); this.label7 = new System.Windows.Forms.Label(); + this.CHK_revpan = new System.Windows.Forms.CheckBox(); + this.CHK_revtilt = new System.Windows.Forms.CheckBox(); + this.TXT_pwmrangepan = new System.Windows.Forms.TextBox(); + this.TXT_pwmrangetilt = new System.Windows.Forms.TextBox(); + this.label8 = new System.Windows.Forms.Label(); + this.label9 = new System.Windows.Forms.Label(); + this.label10 = new System.Windows.Forms.Label(); + this.label11 = new System.Windows.Forms.Label(); + this.label12 = new System.Windows.Forms.Label(); + this.BUT_connect = new ArdupilotMega.MyButton(); + this.LBL_pantrim = new System.Windows.Forms.Label(); + this.LBL_tilttrim = new System.Windows.Forms.Label(); ((System.ComponentModel.ISupportInitialize)(this.TRK_pantrim)).BeginInit(); ((System.ComponentModel.ISupportInitialize)(this.TRK_tilttrim)).BeginInit(); this.SuspendLayout(); @@ -52,7 +63,8 @@ // this.CMB_interface.FormattingEnabled = true; this.CMB_interface.Items.AddRange(new object[] { - "Maestro"}); + "Maestro", + "ArduTracker"}); this.CMB_interface.Location = new System.Drawing.Point(83, 10); this.CMB_interface.Name = "CMB_interface"; this.CMB_interface.Size = new System.Drawing.Size(121, 21); @@ -95,19 +107,9 @@ this.CMB_serialport.Size = new System.Drawing.Size(121, 21); this.CMB_serialport.TabIndex = 1; // - // BUT_connect - // - this.BUT_connect.Location = new System.Drawing.Point(476, 9); - this.BUT_connect.Name = "BUT_connect"; - this.BUT_connect.Size = new System.Drawing.Size(75, 23); - this.BUT_connect.TabIndex = 3; - this.BUT_connect.Text = "Connect"; - this.BUT_connect.UseVisualStyleBackColor = true; - this.BUT_connect.Click += new System.EventHandler(this.BUT_connect_Click); - // // TRK_pantrim // - this.TRK_pantrim.Location = new System.Drawing.Point(153, 65); + this.TRK_pantrim.Location = new System.Drawing.Point(153, 81); this.TRK_pantrim.Maximum = 90; this.TRK_pantrim.Minimum = -90; this.TRK_pantrim.Name = "TRK_pantrim"; @@ -118,7 +120,7 @@ // // TXT_panrange // - this.TXT_panrange.Location = new System.Drawing.Point(83, 65); + this.TXT_panrange.Location = new System.Drawing.Point(83, 81); this.TXT_panrange.Name = "TXT_panrange"; this.TXT_panrange.Size = new System.Drawing.Size(64, 20); this.TXT_panrange.TabIndex = 4; @@ -128,7 +130,7 @@ // label3 // this.label3.AutoSize = true; - this.label3.Location = new System.Drawing.Point(326, 49); + this.label3.Location = new System.Drawing.Point(326, 65); this.label3.Name = "label3"; this.label3.Size = new System.Drawing.Size(27, 13); this.label3.TabIndex = 10; @@ -137,25 +139,25 @@ // label4 // this.label4.AutoSize = true; - this.label4.Location = new System.Drawing.Point(83, 49); + this.label4.Location = new System.Drawing.Point(83, 65); this.label4.Name = "label4"; - this.label4.Size = new System.Drawing.Size(56, 13); + this.label4.Size = new System.Drawing.Size(39, 13); this.label4.TabIndex = 11; - this.label4.Text = "Range -/+"; + this.label4.Text = "Range"; // // label5 // this.label5.AutoSize = true; - this.label5.Location = new System.Drawing.Point(83, 125); + this.label5.Location = new System.Drawing.Point(83, 141); this.label5.Name = "label5"; - this.label5.Size = new System.Drawing.Size(56, 13); + this.label5.Size = new System.Drawing.Size(39, 13); this.label5.TabIndex = 17; - this.label5.Text = "Range -/+"; + this.label5.Text = "Range"; // // label6 // this.label6.AutoSize = true; - this.label6.Location = new System.Drawing.Point(326, 125); + this.label6.Location = new System.Drawing.Point(326, 141); this.label6.Name = "label6"; this.label6.Size = new System.Drawing.Size(27, 13); this.label6.TabIndex = 16; @@ -163,7 +165,7 @@ // // TXT_tiltrange // - this.TXT_tiltrange.Location = new System.Drawing.Point(83, 141); + this.TXT_tiltrange.Location = new System.Drawing.Point(83, 157); this.TXT_tiltrange.Name = "TXT_tiltrange"; this.TXT_tiltrange.Size = new System.Drawing.Size(64, 20); this.TXT_tiltrange.TabIndex = 6; @@ -172,7 +174,7 @@ // // TRK_tilttrim // - this.TRK_tilttrim.Location = new System.Drawing.Point(153, 141); + this.TRK_tilttrim.Location = new System.Drawing.Point(153, 157); this.TRK_tilttrim.Maximum = 45; this.TRK_tilttrim.Minimum = -45; this.TRK_tilttrim.Name = "TRK_tilttrim"; @@ -184,7 +186,7 @@ // label2 // this.label2.AutoSize = true; - this.label2.Location = new System.Drawing.Point(13, 68); + this.label2.Location = new System.Drawing.Point(12, 65); this.label2.Name = "label2"; this.label2.Size = new System.Drawing.Size(26, 13); this.label2.TabIndex = 18; @@ -193,17 +195,140 @@ // label7 // this.label7.AutoSize = true; - this.label7.Location = new System.Drawing.Point(13, 144); + this.label7.Location = new System.Drawing.Point(12, 141); this.label7.Name = "label7"; this.label7.Size = new System.Drawing.Size(21, 13); this.label7.TabIndex = 19; this.label7.Text = "Tilt"; // + // CHK_revpan + // + this.CHK_revpan.AutoSize = true; + this.CHK_revpan.Location = new System.Drawing.Point(534, 83); + this.CHK_revpan.Name = "CHK_revpan"; + this.CHK_revpan.Size = new System.Drawing.Size(46, 17); + this.CHK_revpan.TabIndex = 20; + this.CHK_revpan.Text = "Rev"; + this.CHK_revpan.UseVisualStyleBackColor = true; + this.CHK_revpan.CheckedChanged += new System.EventHandler(this.CHK_revpan_CheckedChanged); + // + // CHK_revtilt + // + this.CHK_revtilt.AutoSize = true; + this.CHK_revtilt.Location = new System.Drawing.Point(534, 159); + this.CHK_revtilt.Name = "CHK_revtilt"; + this.CHK_revtilt.Size = new System.Drawing.Size(46, 17); + this.CHK_revtilt.TabIndex = 21; + this.CHK_revtilt.Text = "Rev"; + this.CHK_revtilt.UseVisualStyleBackColor = true; + this.CHK_revtilt.CheckedChanged += new System.EventHandler(this.CHK_revtilt_CheckedChanged); + // + // TXT_pwmrangepan + // + this.TXT_pwmrangepan.Location = new System.Drawing.Point(83, 107); + this.TXT_pwmrangepan.Name = "TXT_pwmrangepan"; + this.TXT_pwmrangepan.Size = new System.Drawing.Size(64, 20); + this.TXT_pwmrangepan.TabIndex = 22; + this.TXT_pwmrangepan.Text = "1000"; + // + // TXT_pwmrangetilt + // + this.TXT_pwmrangetilt.Location = new System.Drawing.Point(83, 183); + this.TXT_pwmrangetilt.Name = "TXT_pwmrangetilt"; + this.TXT_pwmrangetilt.Size = new System.Drawing.Size(64, 20); + this.TXT_pwmrangetilt.TabIndex = 23; + this.TXT_pwmrangetilt.Text = "1000"; + // + // label8 + // + this.label8.AutoSize = true; + this.label8.Location = new System.Drawing.Point(43, 110); + this.label8.Name = "label8"; + this.label8.Size = new System.Drawing.Size(34, 13); + this.label8.TabIndex = 24; + this.label8.Text = "PWM"; + // + // label9 + // + this.label9.AutoSize = true; + this.label9.Location = new System.Drawing.Point(43, 186); + this.label9.Name = "label9"; + this.label9.Size = new System.Drawing.Size(34, 13); + this.label9.TabIndex = 25; + this.label9.Text = "PWM"; + // + // label10 + // + this.label10.AutoSize = true; + this.label10.Location = new System.Drawing.Point(45, 160); + this.label10.Name = "label10"; + this.label10.Size = new System.Drawing.Size(34, 13); + this.label10.TabIndex = 27; + this.label10.Text = "Angle"; + // + // label11 + // + this.label11.AutoSize = true; + this.label11.Location = new System.Drawing.Point(45, 84); + this.label11.Name = "label11"; + this.label11.Size = new System.Drawing.Size(34, 13); + this.label11.TabIndex = 26; + this.label11.Text = "Angle"; + // + // label12 + // + this.label12.AutoSize = true; + this.label12.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Bold, System.Drawing.GraphicsUnit.Point, ((byte)(0))); + this.label12.Location = new System.Drawing.Point(94, 40); + this.label12.Name = "label12"; + this.label12.Size = new System.Drawing.Size(403, 13); + this.label12.TabIndex = 28; + this.label12.Text = "Miss using this interface can cause servo damage, use with caution!!!"; + // + // BUT_connect + // + this.BUT_connect.Location = new System.Drawing.Point(476, 9); + this.BUT_connect.Name = "BUT_connect"; + this.BUT_connect.Size = new System.Drawing.Size(75, 23); + this.BUT_connect.TabIndex = 3; + this.BUT_connect.Text = "Connect"; + this.BUT_connect.UseVisualStyleBackColor = true; + this.BUT_connect.Click += new System.EventHandler(this.BUT_connect_Click); + // + // LBL_pantrim + // + this.LBL_pantrim.AutoSize = true; + this.LBL_pantrim.Location = new System.Drawing.Point(326, 113); + this.LBL_pantrim.Name = "LBL_pantrim"; + this.LBL_pantrim.Size = new System.Drawing.Size(34, 13); + this.LBL_pantrim.TabIndex = 29; + this.LBL_pantrim.Text = "Angle"; + // + // LBL_tilttrim + // + this.LBL_tilttrim.AutoSize = true; + this.LBL_tilttrim.Location = new System.Drawing.Point(326, 190); + this.LBL_tilttrim.Name = "LBL_tilttrim"; + this.LBL_tilttrim.Size = new System.Drawing.Size(34, 13); + this.LBL_tilttrim.TabIndex = 30; + this.LBL_tilttrim.Text = "Angle"; + // // Tracker // this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F); this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font; - this.ClientSize = new System.Drawing.Size(569, 195); + this.ClientSize = new System.Drawing.Size(587, 212); + this.Controls.Add(this.LBL_tilttrim); + this.Controls.Add(this.LBL_pantrim); + this.Controls.Add(this.label12); + this.Controls.Add(this.label10); + this.Controls.Add(this.label11); + this.Controls.Add(this.label9); + this.Controls.Add(this.label8); + this.Controls.Add(this.TXT_pwmrangetilt); + this.Controls.Add(this.TXT_pwmrangepan); + this.Controls.Add(this.CHK_revtilt); + this.Controls.Add(this.CHK_revpan); this.Controls.Add(this.label7); this.Controls.Add(this.label2); this.Controls.Add(this.label5); @@ -222,6 +347,7 @@ this.Icon = ((System.Drawing.Icon)(resources.GetObject("$this.Icon"))); this.Name = "Tracker"; this.Text = "Tracker"; + this.FormClosing += new System.Windows.Forms.FormClosingEventHandler(this.Tracker_FormClosing); ((System.ComponentModel.ISupportInitialize)(this.TRK_pantrim)).EndInit(); ((System.ComponentModel.ISupportInitialize)(this.TRK_tilttrim)).EndInit(); this.ResumeLayout(false); @@ -246,5 +372,16 @@ private System.Windows.Forms.TrackBar TRK_tilttrim; private System.Windows.Forms.Label label2; private System.Windows.Forms.Label label7; + private System.Windows.Forms.CheckBox CHK_revpan; + private System.Windows.Forms.CheckBox CHK_revtilt; + private System.Windows.Forms.TextBox TXT_pwmrangepan; + private System.Windows.Forms.TextBox TXT_pwmrangetilt; + private System.Windows.Forms.Label label8; + private System.Windows.Forms.Label label9; + private System.Windows.Forms.Label label10; + private System.Windows.Forms.Label label11; + private System.Windows.Forms.Label label12; + private System.Windows.Forms.Label LBL_pantrim; + private System.Windows.Forms.Label LBL_tilttrim; } } \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/Antenna/Tracker.cs b/Tools/ArdupilotMegaPlanner/Antenna/Tracker.cs index 5c1ee337bc..c51678b57b 100644 --- a/Tools/ArdupilotMegaPlanner/Antenna/Tracker.cs +++ b/Tools/ArdupilotMegaPlanner/Antenna/Tracker.cs @@ -15,6 +15,12 @@ namespace ArdupilotMega.Antenna static bool threadrun = false; static ITrackerOutput tracker; + enum interfaces + { + Maestro, + ArduTracker + } + public Tracker() { InitializeComponent(); @@ -27,10 +33,63 @@ namespace ArdupilotMega.Antenna { BUT_connect.Text = "Disconnect"; } + + foreach (string value in MainV2.config.Keys) + { + if (value.StartsWith("Tracker_")) + { + var ctls = Controls.Find(value.Replace("Tracker_",""),true); + + foreach (Control ctl in ctls) + { + if (typeof(TextBox) == ctl.GetType() || + typeof(ComboBox) == ctl.GetType()) + { + ctl.Text = MainV2.config[value].ToString(); + } + else if (typeof(TrackBar) == ctl.GetType()) + { + ((TrackBar)ctl).Value = int.Parse(MainV2.config[value].ToString()); + } + else if (typeof(CheckBox) == ctl.GetType()) + { + ((CheckBox)ctl).Checked = bool.Parse(MainV2.config[value].ToString()); + } + } + } + } + + // update other fields from load params + TXT_panrange_TextChanged(null, null); + TXT_tiltrange_TextChanged(null, null); + TRK_pantrim_Scroll(null, null); + TRK_tilttrim_Scroll(null, null); + } + + void saveconfig() + { + foreach (Control ctl in Controls) + { + if (typeof(TextBox) == ctl.GetType() || + typeof(ComboBox) == ctl.GetType()) + { + MainV2.config["Tracker_" + ctl.Name] = ctl.Text; + } + if (typeof(TrackBar) == ctl.GetType()) + { + MainV2.config["Tracker_" + ctl.Name] = ((TrackBar)ctl).Value; + } + if (typeof(CheckBox) == ctl.GetType()) + { + MainV2.config["Tracker_" + ctl.Name] = ((CheckBox)ctl).Checked; + } + } } private void BUT_connect_Click(object sender, EventArgs e) { + saveconfig(); + if (threadrun) { threadrun = false; @@ -44,7 +103,10 @@ namespace ArdupilotMega.Antenna tracker.ComPort.Close(); } - tracker = new ArdupilotMega.Antenna.Maestro(); + if (CMB_interface.Text == "Maestro") + tracker = new ArdupilotMega.Antenna.Maestro(); + if (CMB_interface.Text == "ArduTracker") + tracker = new ArdupilotMega.Antenna.ArduTracker(); try { @@ -58,14 +120,20 @@ namespace ArdupilotMega.Antenna try { - tracker.PanStartRange = int.Parse(TXT_panrange.Text) / 2 * -1; - tracker.PanEndRange = int.Parse(TXT_panrange.Text) / 2; + tracker.PanStartRange = int.Parse(TXT_panrange.Text) / 1 * -1; + tracker.PanEndRange = int.Parse(TXT_panrange.Text) / 1; tracker.TrimPan = TRK_pantrim.Value; tracker.TiltStartRange = int.Parse(TXT_tiltrange.Text) / 2 * -1; tracker.TiltEndRange = int.Parse(TXT_tiltrange.Text) / 2; tracker.TrimTilt = TRK_tilttrim.Value; + tracker.PanReverse = CHK_revpan.Checked; + tracker.TiltReverse = CHK_revtilt.Checked; + + tracker.PanPWMRange = int.Parse(TXT_pwmrangepan.Text); + tracker.TiltPWMRange = int.Parse(TXT_pwmrangetilt.Text); + } catch (Exception ex) { CustomMessageBox.Show("Bad User input " + ex.Message); return; } @@ -83,6 +151,8 @@ namespace ArdupilotMega.Antenna t12.Start(); } } + + BUT_connect.Text = "Disconnect"; } void mainloop() @@ -104,12 +174,14 @@ namespace ArdupilotMega.Antenna { if (tracker != null) tracker.TrimPan = TRK_pantrim.Value; + LBL_pantrim.Text = TRK_pantrim.Value.ToString(); } private void TRK_tilttrim_Scroll(object sender, EventArgs e) { if (tracker != null) tracker.TrimTilt = TRK_tilttrim.Value; + LBL_tilttrim.Text = TRK_tilttrim.Value.ToString(); } private void TXT_panrange_TextChanged(object sender, EventArgs e) @@ -118,8 +190,8 @@ namespace ArdupilotMega.Antenna int.TryParse(TXT_panrange.Text, out range); - TRK_pantrim.Minimum = range / 2 * -1; - TRK_pantrim.Maximum = range / 2; + TRK_pantrim.Minimum = range / 1 * -1; + TRK_pantrim.Maximum = range / 1; } private void TXT_tiltrange_TextChanged(object sender, EventArgs e) @@ -128,8 +200,23 @@ namespace ArdupilotMega.Antenna int.TryParse(TXT_tiltrange.Text, out range); - TRK_tilttrim.Minimum = range / 2 * -1; - TRK_tilttrim.Maximum = range / 2; + TRK_tilttrim.Minimum = range / 1 * -1; + TRK_tilttrim.Maximum = range / 1; + } + + private void CHK_revpan_CheckedChanged(object sender, EventArgs e) + { + + } + + private void CHK_revtilt_CheckedChanged(object sender, EventArgs e) + { + + } + + private void Tracker_FormClosing(object sender, FormClosingEventArgs e) + { + saveconfig(); } } } diff --git a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj index 80b938dd1c..7dc0487396 100644 --- a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj +++ b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj @@ -213,6 +213,7 @@ + @@ -230,6 +231,7 @@ ProgressReporterDialogue.cs + Form @@ -446,7 +448,6 @@ - Tracker.cs diff --git a/Tools/ArdupilotMegaPlanner/CommsSerialPort.cs b/Tools/ArdupilotMegaPlanner/CommsSerialPort.cs index 5b08850731..ae5d6ef677 100644 --- a/Tools/ArdupilotMegaPlanner/CommsSerialPort.cs +++ b/Tools/ArdupilotMegaPlanner/CommsSerialPort.cs @@ -3,6 +3,7 @@ using System.Collections.Generic; using System.Text; using System.IO.Ports; using System.IO; +using System.Linq; namespace ArdupilotMega { @@ -18,6 +19,11 @@ namespace ArdupilotMega public void toggleDTR() { + bool open = this.IsOpen; + + if (!open) + this.Open(); + base.DtrEnable = false; base.RtsEnable = false; @@ -27,6 +33,56 @@ namespace ArdupilotMega base.RtsEnable = true; System.Threading.Thread.Sleep(50); + + if (!open) + this.Close(); + } + + public new static string[] GetPortNames() + { + string[] monoDevs = new string[0]; + + if (Directory.Exists("/dev/")) + { + if (Directory.Exists("/dev/serial/by-id/")) + monoDevs = Directory.GetFiles("/dev/serial/by-id/", "*"); + monoDevs = Directory.GetFiles("/dev/", "*ACM*"); + monoDevs = Directory.GetFiles("/dev/", "ttyUSB*"); + } + + string[] ports = System.IO.Ports.SerialPort.GetPortNames() + .Select(p => p.TrimEnd()) + .Select(FixBlueToothPortNameBug) + .ToArray(); + + string[] allPorts = new string[monoDevs.Length + ports.Length]; + + monoDevs.CopyTo(allPorts, 0); + ports.CopyTo(allPorts, monoDevs.Length); + + return allPorts; + } + + + // .NET bug: sometimes bluetooth ports are enumerated with bogus characters + // eg 'COM10' becomes 'COM10c' - one workaround is to remove the non numeric + // char. Annoyingly, sometimes a numeric char is added, which means this + // does not work in all cases. + // See http://connect.microsoft.com/VisualStudio/feedback/details/236183/system-io-ports-serialport-getportnames-error-with-bluetooth + private static string FixBlueToothPortNameBug(string portName) + { + if (!portName.StartsWith("COM")) + return portName; + var newPortName = "COM"; // Start over with "COM" + foreach (var portChar in portName.Substring(3).ToCharArray()) // Remove "COM", put the rest in a character array + { + if (char.IsDigit(portChar)) + newPortName += portChar.ToString(); // Good character, append to portName + // else + //log.WarnFormat("Bad (Non Numeric) character in port name '{0}' - removing", portName); + } + + return newPortName; } } } diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs index fc46ee040c..651bfd7e74 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs @@ -792,7 +792,7 @@ namespace ArdupilotMega.GCSViews try { Directory.CreateDirectory(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs"); - swlog = new StreamWriter(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs" + Path.DirectorySeparatorChar + DateTime.Now.ToString("yyyy-MM-dd hh-mm") + " telem.log"); + swlog = new StreamWriter(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs" + Path.DirectorySeparatorChar + DateTime.Now.ToString("yyyy-MM-dd HH-mm") + " telem.log"); } catch { CustomMessageBox.Show("Log creation error"); } } @@ -1375,7 +1375,7 @@ namespace ArdupilotMega.GCSViews aviwriter = new AviWriter(); Directory.CreateDirectory(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs"); - aviwriter.avi_start(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs" + Path.DirectorySeparatorChar + DateTime.Now.ToString("yyyy-MM-dd hh-mm-ss") + ".avi"); + aviwriter.avi_start(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs" + Path.DirectorySeparatorChar + DateTime.Now.ToString("yyyy-MM-dd HH-mm-ss") + ".avi"); recordHudToAVIToolStripMenuItem.Text = "Recording"; } diff --git a/Tools/ArdupilotMegaPlanner/Log.cs b/Tools/ArdupilotMegaPlanner/Log.cs index f414925ac0..e8c7d2b14e 100644 --- a/Tools/ArdupilotMegaPlanner/Log.cs +++ b/Tools/ArdupilotMegaPlanner/Log.cs @@ -233,7 +233,7 @@ namespace ArdupilotMega case serialstatus.Createfile: receivedbytes = 0; Directory.CreateDirectory(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs"); - logfile = Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs" + Path.DirectorySeparatorChar + DateTime.Now.ToString("yyyy-MM-dd hh-mm") + " " + currentlog + ".log"; + logfile = Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs" + Path.DirectorySeparatorChar + DateTime.Now.ToString("yyyy-MM-dd HH-mm") + " " + currentlog + ".log"; sw = new StreamWriter(logfile); status = serialstatus.Waiting; lock (thisLock) diff --git a/Tools/ArdupilotMegaPlanner/MAVLink.cs b/Tools/ArdupilotMegaPlanner/MAVLink.cs index a324140c75..17588fa4fb 100644 --- a/Tools/ArdupilotMegaPlanner/MAVLink.cs +++ b/Tools/ArdupilotMegaPlanner/MAVLink.cs @@ -184,9 +184,6 @@ namespace ArdupilotMega BaseStream.DiscardInBuffer(); - // removed because of apc220 units - //BaseStream.toggleDTR(); - Thread.Sleep(1000); } diff --git a/Tools/ArdupilotMegaPlanner/MainV2.cs b/Tools/ArdupilotMegaPlanner/MainV2.cs index 8fc86cf6a3..511d6d2d36 100644 --- a/Tools/ArdupilotMegaPlanner/MainV2.cs +++ b/Tools/ArdupilotMegaPlanner/MainV2.cs @@ -117,7 +117,7 @@ namespace ArdupilotMega comPort.BaseStream.BaudRate = 115200; - CMB_serialport.Items.AddRange(GetPortNames()); + CMB_serialport.Items.AddRange(SerialPort.GetPortNames()); CMB_serialport.Items.Add("TCP"); CMB_serialport.Items.Add("UDP"); if (CMB_serialport.Items.Count > 0) @@ -253,57 +253,6 @@ namespace ArdupilotMega splash.Close(); } - private string[] GetPortNames() - { - string[] monoDevs = new string[0]; - - log.Debug("Getting Comports"); - - if (MONO) - { - if (Directory.Exists("/dev/")) - { - if (Directory.Exists("/dev/serial/by-id/")) - monoDevs = Directory.GetFiles("/dev/serial/by-id/", "*"); - monoDevs = Directory.GetFiles("/dev/", "*ACM*"); - monoDevs = Directory.GetFiles("/dev/", "ttyUSB*"); - } - } - - string[] ports = SerialPort.GetPortNames() - .Select(p => p.TrimEnd()) - .Select(FixBlueToothPortNameBug) - .ToArray(); - - string[] allPorts = new string[monoDevs.Length + ports.Length]; - - monoDevs.CopyTo(allPorts, 0); - ports.CopyTo(allPorts, monoDevs.Length); - - return allPorts; - } - - // .NET bug: sometimes bluetooth ports are enumerated with bogus characters - // eg 'COM10' becomes 'COM10c' - one workaround is to remove the non numeric - // char. Annoyingly, sometimes a numeric char is added, which means this - // does not work in all cases. - // See http://connect.microsoft.com/VisualStudio/feedback/details/236183/system-io-ports-serialport-getportnames-error-with-bluetooth - private string FixBlueToothPortNameBug(string portName) - { - if (!portName.StartsWith("COM")) - return portName; - var newPortName = "COM"; // Start over with "COM" - foreach (var portChar in portName.Substring(3).ToCharArray()) // Remove "COM", put the rest in a character array - { - if (char.IsDigit(portChar)) - newPortName += portChar.ToString(); // Good character, append to portName - else - log.WarnFormat("Bad (Non Numeric) character in port name '{0}' - removing", portName); - } - - return newPortName; - } - internal void ScreenShot() { Rectangle bounds = Screen.GetBounds(Point.Empty); @@ -313,7 +262,7 @@ namespace ArdupilotMega { g.CopyFromScreen(Point.Empty, Point.Empty, bounds.Size); } - string name = "ss" + DateTime.Now.ToString("hhmmss") + ".jpg"; + string name = "ss" + DateTime.Now.ToString("HHmmss") + ".jpg"; bitmap.Save(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + name, System.Drawing.Imaging.ImageFormat.Jpeg); CustomMessageBox.Show("Screenshot saved to " + name); } @@ -324,7 +273,7 @@ namespace ArdupilotMega { string oldport = CMB_serialport.Text; CMB_serialport.Items.Clear(); - CMB_serialport.Items.AddRange(GetPortNames()); + CMB_serialport.Items.AddRange(SerialPort.GetPortNames()); CMB_serialport.Items.Add("TCP"); CMB_serialport.Items.Add("UDP"); if (CMB_serialport.Items.Contains(oldport)) @@ -538,10 +487,19 @@ namespace ArdupilotMega comPort.BaseStream.StopBits = (StopBits)Enum.Parse(typeof(StopBits), "1"); comPort.BaseStream.Parity = (Parity)Enum.Parse(typeof(Parity), "None"); - comPort.BaseStream.DtrEnable = false; - try { + comPort.BaseStream.PortName = CMB_serialport.Text; + + // false here + comPort.BaseStream.DtrEnable = false; + comPort.BaseStream.RtsEnable = false; + + if (config["CHK_resetapmonconnect"] == null || bool.Parse(config["CHK_resetapmonconnect"].ToString()) == true) + comPort.BaseStream.toggleDTR(); + + // if reset on connect is on dtr will be true here + if (comPort.logfile != null) comPort.logfile.Close(); try @@ -551,7 +509,6 @@ namespace ArdupilotMega } catch { CustomMessageBox.Show("Failed to create log - wont log this session"); } // soft fail - comPort.BaseStream.PortName = CMB_serialport.Text; comPort.Open(true); if (comPort.param["SYSID_SW_TYPE"] != null) diff --git a/Tools/ArdupilotMegaPlanner/PIDTunning.cs b/Tools/ArdupilotMegaPlanner/PIDTunning.cs new file mode 100644 index 0000000000..866fe583bb --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/PIDTunning.cs @@ -0,0 +1,46 @@ +using System; +using System.Collections.Generic; +using System.Linq; +using System.Text; + +namespace ArdupilotMega +{ + class PIDTunning + { + + public static void twiddle(double[] initialgains, Func run, double tol = 0.001) + { + int n_params = 3; + double err= 0; + double[] dparams = initialgains; //{1.0f,1.0f,1.0f}; + double[] paramss = {0.0f,0.0f,0.0f}; + double best_error = run(paramss); + int n = 0; + + while (dparams.Sum() > tol) { + for (int i = 0; i < n_params; i++){ + paramss[i] += dparams[i]; + err = run(paramss); + if (err < best_error){ + best_error = err; + dparams[i] *= 1.1; + } + else { + paramss[i] -= 2.0 * dparams[i]; + err = run(paramss); + if (err < best_error){ + best_error = err; + dparams[i] *= 1.1; + } + else { + paramss[i] += dparams[i]; + dparams[i] *= 0.9; + } + } + n += 1; + Console.WriteLine("Twiddle #" + n + " " + paramss.ToString() + " -> " + best_error); + } + } + } + } +} diff --git a/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs b/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs index e99d7dd1d3..690be35904 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.55")] +[assembly: AssemblyFileVersion("1.1.56")] [assembly: NeutralResourcesLanguageAttribute("")] diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.pdb b/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.pdb index 10a92a6c02792cdbe13f8c982ffaa6414f6d2e19..ed5172ddaceebace73ddca6848e1bc7667b3d865 100644 GIT binary patch delta 194643 zcmb5X3w)2||M-7j_x;{`N4D7_T#` zBxhC&eBJl`p3V3Bef+=w`{CtzU)S}z&d2+{uJ=9Pu6Dk; z?dPXgc`MK`E+!lH^=4V_!0Wd^FJz0n~b8~^+xHkPj}vc2_{+7{$7 zYfUd2-$!9NyZb#cTLzYP`u87W^S`-oT=w?(kc`$5{Z4F&xSY3eUB;qnPu}_2xLsRw z*QsrtyN5*>z18F`kDrepy>0k^lJ7k7jqPw74zGS(_*78m=q38jE-!=}4jL>DPgm`} zru&E*5y6Y@3)#~pVfvlA=KgwNP0rh%rgo1G4;|I(sVyU0H!MzVSNpYQUG%vsX5!Yq za~zNJ(jpocz3wTD{oP7i{8aQ`=g&;C11;{cy~nHn1V#*eadGt)M~092xb^#gZ+mq8 z-FB$^x<^FhJo8q!!p3VR)QrjLIN;d8V{TF+sxK)Cf239PmFw;6{?~sFZLeY5-`yj; z=&|A7w!E`ADLgK_=Pk1{w&re7+dUt}2QI98YJ^Vj6dtyH{;70J59}Hqw(!8|Wx?N? z6gu)jgd&h^*3dWOgA(>=qN z>1lc4@v6_lRbR!aI~VT$Do&ry3twCIOt0`TrFZrYzo^&t317J|;+vKFV&CwH?fbsz zu5{Z{KYZr)4d3sy^wGBAnE@kd4Wo3G zTf*;Lc=@M+dTN{S^wNRhod;~dej~C8*^F#Kwj$e*?Z^(~735W<4B3gihP;lvf$Tzd zBYO~ONPFSFh5deRR&s(SbOqT7-+5Tprie;hf1d?NSQoj@W24C7PGCj*-pMjH&H zk^RUiEI&h1y@rv2v_rZe`Pda84=vn!c}2(uQRUjOUr*|wqRNumTc4|^uLgNO$uo?F z`>*z0GvsPd9r&NBeM0*7=-mIl2@}Rm7^8C|)a@Zf;|hvhbG|3MzdrkC)j&_~!6Tp7#V|sv8pay#H})+1C`a9IsrMG- zW|ekTo+^tYDZV>in+iEl<-%UyUzI@1~Bc+C@a0j&|Hvnd-y-8!ivzUXpSbEXphUsk<6xdFFgMxRvgk zr}}$5(Fq;O*5#>{9?#X!tE;lSe(Iv>c_4CfU|H+_%A-7)vlD`J&Hz-4>kS{F7Y|S; zJ@17)R96?@p}N=JNVfd3-Pilk_7a<9Rbt!NQ*XLM{ZTqleWeo0z8?dL*o-?lf4{OH42*4r7$Z@S0@x7w)?wj-oOWbmXs8(z3y7rV7j^gx|LY=zp4- z%>o^Ni8_CXO7XVCC4QTpGeos6cX&@6+T)P2P5&}P)v;2x1?a>yD@JDyRgD81_Lq1Q zb>UFdI-oXVo1QmRWtaOuCJs3`%-W_K&$4bfv>S#)E)JgUdTB+6mv9K|h(qZ10Ntcs z=q=@8RUeL*PPoKw*X@T_NaS>J=!`@1cKz9G>qhD?h(i|~T5Z==N2ofHt+of)MOWKM zili49@95kSDp9?oCxw`T8IEbjWHU}*o@05i+V5DMa}XJ7>m}#gzWN>a)YJp>RYYXg z4kzGP0w!Dn-rqDdN+->=f)d_QhHWSIlk+ExDQs#OHPB;hL2qlms!25O<*VGl<55m= zMvf%ix03FMUe#?!s@ApKdcwwEzy0z2`&PZYen6~VJ5uGC)ZC_dR&41g6%kA&kxgX` z(_0_3qIAY6wZWuj#9dz%g;}n`G<_utg`@(t(xf76h0_Hp!VKN6e=1NNO^VvK%)BMQ z8Oys^G9P-i?5EMHsq!-Vd4EaQX=7FQnE&1?CDp&Advs!M zKup=nvFa;JCFl+>tLkNo$E#sMX2bsaTCtiyb02e`y33@im1voN*U*{8D!T02 zH1&vAw5C3)CZqMkqbgLX<7NMusp=`QPkLOXtJ%88fUQqZ4*vdqpp(N ziI1u3dg@vg9rgw8BT`MLGpbW`#?5P0J-5A{)?chuDPd>O8SU3;cPcDNpM5*PqcfjZ zVdm&m-Tryix7@>`=ZW-7Jj_njd!8?^c1Z^R%DeRoDZ1(ls<(L{rEJ&>>JBAo+w`Y5 zRv&#)4Kzoj>IUmn%U~x`Wu)k=bt+0vTc_ep!u=^IFjo7HDNotXbt+G3Pey3GcQTdM zWUo%k2u(9#?~KrA$msC5%S~QbvxA&UogAp|XcStCd>ZeekHUE|QO$jz>s z^c9?N+xlEUyPC73rISdKrBE6h4Q$6Ez5j?OD)IrWKXUyUw-*-Qr}N(ptzXlhXva@e z*Uw3voMJ|Kr{d@MUVV3FXzR@XSusb(3a%6f_Wuv!%ezm1gs}k z!dLx$PM(dv`4hychG9i^CWavNMc41{A4?87W6Au<9*Q^E}vR519FXaVE_LxiP`Q?O#gA?i?Nl&5Q zI{U8RFdZ=@I4!Gkxc+5+eOz~!wRvL;BAH^mximT+6L4Lm$=(3{<*}fcs5ry$r5ibR7tX|? z4Gt5%o|r^&U`1mHdl(apiAIsFB)+@3zI9TD*Argf=veN(pX)s}-t{i*X-qOE8&hnh z9e8)TmNKT;V|;!+RKl^Y4-;Vnm<$_1NfPToUk>En*AcdWz2Hwj|LyAoTVd|&@*bBH zVH@lx!M3_r%h38UQ;i3W$BimRj1g>vlxKx5sT0qJq*jp$;JDpCmC;nIK`JV_GXY4C zruu!gU{`2oA4w8;;CYtm$ne38Dlh1>7Zx{hdo3A<~ZFYY8>GxWN##Nb$mD7=w zF-M=9XGPt62O7~>4}x{zU?>r=*7CK5!{AVu4`;waI17$}RVe)`Mr))Ml8TH%ijZU^ z*3PKp&FL=67;WdR$9TL-l=O377A%4iMKLUZ_roeiXMz}p+>6vfoZv>_?sOStbkSG7 zQ&9sRMm-4YX;AY12$W!b{G)!1f5A?0CahxABB&b37^JQ%H&RMRvDXOIoLcxdUPAFI z)h!M3Nz5#>ZL>r*PY-QFEfnq7kF*JmOcsyB+^G# zXirQ@ZC97pXY0`Vd@(3c7j}h9)WJpq4W~Aeh$P`^7*`R=wXDMBq7aRBL@EziXC-nR zYay+XzDN-=3t5KjKn@~jgN$2@YurQx^IU^;Mg}59$V_AzvJ*LqoJX!B(IMy}IUx&j zKPp|XlDv5VhWAXFPFv4P_)M8cPh6wE)0s~Mhd9fa`rckBTqx5MUM^pr=IMeU-mo%&fjoh82vmpe?J78&## zlJn87y{u<38Z-5z_k(I`&qmhfAKQz`Jl$p^3+jFZws@yU-!f9QDvy7axZH-zbzD}w z9onJXC2|u9xE+^_*L2%Wsh`1Pn_(`p+$;@i)I{=m$#Q! zU8GLkK{Z4XgJ+QLy`#K=MCvESAsUCygY>IARQq5_yVMM0>gOSG-s%|p57M;ER$Outo z@c$I-Uj*xoBiMR_b=ppz?&`V0OK*@>(K@|Et&967{v$DBiiH0YQ4hP8Edh zD?3%a$kwhO{{z`N{o_v6t~}{kuhB(Vpm>LqgboK;5Es3s(%gO$sh`8yn}G9$!TO!o zR2>s;+NEj-OA@GM<0T#WI**Dk=`08RUMJ45yPRV1KZU-eXX6_4lDhGnC^KssVaQne zlHQLm!uU=+&viY^f{aBIuE}qxI9%H~7z7e31~u;fym1rmF_=}7BIz4=Sm0=Gd_yHh zzUT%g`IlLk1n;6PUVejz+M^ZRWKOW%da6i0bQjsKE!iHTAK#_YA}&zPJgyCOlzN~H($GwFG zxw@uy^i&flYI#%!n%n7?c#Q5*DvJ*r1} zaOVgvEScb%4095r^Us7u>6E=HGS+V;jk7MrF&>c$=rv6D-mCHgo#&EBy=pH>szVr) zhUxeB@{kOx?o%})A9lm^XKRW2C$v|K~!_Rz+2YWidZPdevnU^2HU%+5ttd4%00omzW%4n_6J#R+oqPJC1Fnz*K z#pBLfgzInf7U9C+vgPlnKTMORvGhGcqk3{5{#K|MjhM-Qu6CFdEVuOSh%$ht^2B5#_;BQud@$PVN%auH#1W5grPkvyaTnTpIu z)*`!*lgMQxj4o9d$w3Ap#mHP_2XYv>RMn_yc*0RavXNqBE^;7T|MY=s>J6ZZPT#51 zj;J&f_CBK8tLOETN7MlS#BlA1ijMT6_U)ZcD>7~`&Y!GvXIk~$hvWdS?)@PnRv=1O zZzxSH(z%0G1*L5$d4o_=1NCPgD*w|r-fJIKbpm;V>#e~|)#q{5%zeg{)Kz>gzNnKo zsHnhTtdr5K@UY_7ls1)#oW7G0?l~U4B91YAe|x8Hd`z`8uiCU<8N{2UV)-%Ez>+v^ z)$^j7JkV)U@gJ%9#-}N%Ye)o(#=1y0(ia(v%tV$UJCMW3*@&&VOI7J{l@xfAm4&YZ z4@Dn@R@d3bRhVU))~GB!?YMf!U$O&FsOZ2`=q^RK!W+z!dgBRt&u6$C@1Q?9Q9f6l z)YU)1;d2~LchK!WQMDsacW^32MqlO^;~AZ-d76Gk=YFLU^}&;>b+8N`GJ!m!fBb}D zEd3NSNA{s076PBLhWXtMAXckW43&AGs%&*q&;FEnP7}}i9KG#RMxymRM#~f+@zCy! zMS4N|(6|7a7`Mq^;WH`13<{vEF!SOuE`TE8Hmh-9T!5_R7U_PC18ZvENoK1>`pP}@ zj%6oR826Fmx!=XTUiUe5l5|Q1>7dgptjffZciZE<Mi8Vd@n~gKCK$)ix?vFb8n=YB?izxan1is zr9{^4c*B!)$3=S4XQ~f{asgNG7Zgf(XI=Gk)gUsw^9@Z2zEnygP8aef@I^qSVPm61j?O>;^1@t5jX7&i#~7`k!VV zd#OUCQZl%GMx^sk^M1ZmFFLJKs_k=Cq~_(3qEzX5DV|tel<&zPACX^>k2B<>S{L2+ ziwdplK^&sL#38kdlQCmTVR7!%aZ_~8VAa4~C!Eyh#Q#~;T6fVQXH=cw)~M9pFQ6P*>?+GlO4^LYdWH^&(^t!#QjnO+o2?Yq621RqNTOPz&#kiJ z5?WKeXOS;)iRtQS`scGHdh1yl+!Fo4SyeB%u!rMXLvNL~9&wH_aj9!38Iejt^V@W7Wr41#jrFI7fc9U5u zO{ThD`jx608FA~4gvz9k=BKI~L94F``Wu3td8=;lwaO{4uSw$YEe`W<)l0voGtaLO z1R)sD>SJG%*Jt(qH#||L=UEc^E27bPyk5lXo?G=DIGC`(1qQH*&xiOoTu$l}qV*kG zAKj||K2N4TawCvTNd(WyXi-!5y-=YQ&A7now=1m^jrBWKQM9f zJ?stIex&2A(8nA2Ire*H8pU_?3-(OC@Ah$KR(B01Qx=JK8Xx-r{9;WO5s+vn1 z9sH|m5bU%p%XaGpADh zQ`b~lVz5bioo65mq)HIX4`Ih1R`nc&qb~?rNE7!F4`z)MIsST~;@ty;GRm5mHRrjowKs?)(RR8ym?jg3T0fG7jG@*TaI%+L7NazftQ_ zgm36o)7Tk)L+_tv=DO2JqW)F9)xlf871CnrMD|;8!<$TUyPW;!UC#dVE@%H4l2tFGyi42r&%3m}|GZ1H|I9Mx-|SNp0z1?CIxSK!3pFEjt-rY2$sJDbg_BpiX!upl_bK1R{|c(1f2?XQU|Y5%+`M9`xq4ERDZ8{U zN0~hWYvDvCgKG-&;%9n<1+du1yZ?|5p+8_ikE@ zZiU5tCr&QzoquoP6kH|ENknxR5kG!C|Jq=Zq0jU%Yn$-z9%igC_Et0JrbKsiW6zX^ z#+B#5{(m*GFW##3zi%~D6Xa#G983}gEbZcvs3fzKbykuUSNdpxM@`oKxYhG#D33YW z&{cbyv9-J7?HbYo)r}RrN(rOWwWrzHJQ1Y_CYYHqj5hY>1rI#D=C_O8-jJ%MS0$J= ztE|JysT^f=)~nuAQDbROK3Nm6E98?|pI3qQwufw%(JBnt^tZVf2LZxJgCZ zTV}mr9n7-vLfIH%ZU9M}k2Km_YB^BcrSFJ4VHpDq{rcl(TE`TMq6(#c6+3yDi)S{K zD;E251h_d2jtlrzO#>;qrQBV?CmUx0arp zWZofj#w3fg2uTdjW6+%Nk)D@qCg>)~W)pX?9jyzK8EnVmI?Hx#Y{EUsW)17zk4)WX zFC$v71S`vZO*dNCuY>vuI&b%n^=);`?&aaE5{GewGwEafejU^QP%v6Yrr@v=ACG;k z+oqWQvrMD)baA*FA7vkF4x0FCa#946pU zbV7fYYBr55I#D^w<4%;l(unf76XoQz3Q<0vMgS8D;DZzTNSfK$gny@*dF5&9SI1$_&2*}+tap90sS57?v7}xZ_1%4-24-`UdO7o7A+h>W12f*FEK-M zR8M+0xTZdkVRo0?S8Zf=wCv2T42;p^8%#B0G_j$Ymsg@hlzbj*LKNAuExC$XVnX62Vy4T&qs3+@21tqN_CJ z+{$*2`*rW5)0(oV>E6eq`-*3(;<^{VHQj{;;GvKZNd9FTly;>Kx#^FUA_UGw&ty#G3&-0g+({Z2D`&*lB+&-~dt2XGbL%&`x-Jnf{ zfbJECmv9)|OP5x3I3*72ad@(qHrtkW;MKZETO3}-;pJZXOxp@Uy&?`9a5!_5L-H*+ zY{cQ8Ub=R61s_j}!zLU?_SSQ<%g3eFdU_ADrVh(C!@QeueY$sLZ~57H+k(T2o4maz z4qI{9&|CkKO{r|)STc>qek=z@AAO~rSyT1V?HnYxuTVyd+TnW}zW?a0_q4=MJo0Z?o%689Dk~8(yXO zI+&TkPrG(aoCov69n1)mIzH2Z_FAu(v*+B*aT~$F5InfD-CXQUYHWE93uP+keHeVk z)k)U<&W6N9ImdMBlFENvhfz*|*|~V8DthPQnL>XE2CuLSK^e{pL+?W;*eOuP$q=e?fumRz58EM~}? z;iJPnp3-h+Q1D>_$&pAj+h4q<@5a+ks&3Pb2cdO&W|%JMW=2Q0TI!_2|4u(u&+cZX zM85m%4QokMs@^TuQOj;v2iVqE#Cm~iEz4rbWvWi?ZZ?dZ!5M#P|FTmn3%^vI-`%W7 z8fJIri7Qoa>~0QnA4+-^yQQ-kJ^$5)QmV4j3B$O3)a1g#3Ac}(SZqH4L=$}uenj7| zBhgD@)AX@FgA(q1x&!r|aeaF-Bq$F6rTGcVKW<2Q#Szmbq@kpuhxTL`JmD*ZkoCDg@zF(U45Ryl>} zfBRWaXYC27sgrt}X*Y%Le=3?L3s$bX9N7P76Z(-=`hI*R$d50&qa*G|{(pxqCyeB( zSPJb3z5Z&Q)`!sLK}b#`iF^Ik|JStp%lM=ldd0N2C-fIq>reVnGMTuqMa2Du|2_13 zDwn(eA=iG?!e?j1e{~>qwZ?6zy$UDX*LB?FdmqT3TsXYb_;I7|u^Y>2V$2J1{P}hN zhx%ywKgXIbD-W*u4($JPh_#CwtIod?7M(1Oawc(HMMTr@`ai_;zvRx|F2-jnP1}Fv z63>Z>x$87>!i2(6#ct;8++~nH*>VAcwRcTs;QI`4X|;M3@Y*ShPSWa{K!ILzIuzgf>cSnUtM-`4u` zQb4YI9N7PJ6xy4*UeD`q=G^4Ve~9<86fM^P8N1x83%=&B*MIjnYb40F{w{RHeZHF% zsVnI=^>x+&Uewjs{T!6fDAnZG+cGXdj~zJ${2<;wL| zU!NOb#wAD)Yf+&VjKdXFWW21eCk-=e+A6XS{tdBw;i^d5BrElGuR9239U;qs^KD((3B#RcMow-JrI3l9wYgjxX7GBXu%})>pdy=zv%|?w#nwVfStY z9T^Ji+uLpBjpJ6gambr`xl$e2|MPn^?}d$e>78cZn<~iv!YiYiqduoX!{~;ukWD&v zpc&h;m{6}F;vTZepI9q$19n%D0oXSxw|7?D4V2#Vj+w2`e5SnR$@DkGwQhv%D+}9mtj(7Y2 z?&LCJi+*R2Svw(#aKq3M_lPY{E~ToaH8j*5ut`)6b@E^{GmMulZE=v&a%{|IhVC%b z%qox5U$XL!Rj%U|ntl)Be0Pifey|yvAR8UK&=L1{E5s?yAj4i;1xRgkdl%7X=zItA z!r9)?&(NzJoBa-W-yA264IgTV?IU>zE1V4715<)*r_>_0*(lt-^+paQaT)qCze-nV1ZH|hJ)-oz(=>0>?xPB7KOjNS5D%tLD4bIS-p>C{9#ukq>WT_#OfcV*oA6c1< z+Hu1VD+_{U%@(C|hMJlGt^CIF+DWe89oYZhO8GszLoXd_##X;dn9b1<_h;R3>*y=P z2`_AEK!kmmO_JV7XALvs?D;5zSCI#i4p^`8dm)Dsb|Zaks2LOAygc2ad>vucZd|aH z^`7AjvNAIyh@-qSql+3dUb&GeX)ui{_s`qh{wePoUAZ^M{)qRAaqrxLGfzafMQzTqx^Lr=0iYKC%i0G=DDF0F;vqG6UsdJu#r4wiBtdW#k zrtUG)j59Npj{R1Cbv4rTBvkY^xp2~bg;Sj3mQI$bS2^BZ!&@cIaT5w;Ibc_e6c$+< zX+|X!F_P~};OG{So_X~~=aPvoQzwsNzL6I#J5kw#$`2J(SU^cA(?Y5TCPhl!W$H=j zx2TxD{86I{i;A5xmlriV2q%zmblHulWCf6^caLHw%G9SET&WovmB33PV+$gclE3pt zW0uC9sZ$Hg6g&CZJWFn+fgf^JqV9ZS%}vN--^y2L29dpE z{|eyB!R&2}6$17yC=)WjpzV#ndZ^FBo4 z=wBg#dbVbH9JPq^D0Td91(kGLg*YTI>Y{q06?u@LqS1XE-R~>t%79EC%nGcTP>UQ! zpz;b(2|+8 zdu}wYEYY-AJ2mu>PgO>yf5GWr?1o8samk?Izj#aIecKI0H~KZKo*q8VtT(3enB|{< zkGlaZ@cV|m!tws@24M8cA2;ESro(S5oHFjALZ|OU;AbTwe*AheUP%yH&c<<;y>Wcg z0>vNa)ViW+|8U8<;eXz(dgt)N%e$HMPZD-#bOvERXYY-I7Uc?0!rdxAdHJ6vFS()1 z)ak$YN`m)mHzXtbzM_Ks;=)d23rF1}xzo@6658mdCj$SFeksif;vJfW|LRLpzjFiA z$-i-8Y4bg1K*D9>-HE!W`kkdzBpprlv3po;G?futz=20W)_AjKn+)2vY*#&jzuzn5 zR$^?bZY&pyCQlqyIAx06f=oNi8F)|FhxhJy&&6u>KBurGTFX{>g@|mGX{bmAee0^o zl<2Wlu8gOtN+NckB3)zV{u>Q2z*dppsg9X#pC|G+K!05>mj1?-;lTdC9|iP|8;CK$ zF6_Mgk%i;MQKq5GL{xx3@#EK%BXr{4OgCB`&}B^Js`W>9wZ5qE!bQr)y>272U;L5T zb=q~}WG7NPvSmcH4}apvuP5arb3}9dy_0G#6~W=D31*O9TWm(_!*W+^3U=R4FstMK z*96|d^`BzavKLHJD9v@diDqJ>0u+hHFSKLO1rCa9r~X?56B?L)y0AR|Lqj(88;}S^F+5mo%*{*RP*s8`hJ}> zt?u$thJ)GTY<`zFLLWY5RaK+)m-(vUO)D*bM{O+wCl`}y`PH9jQx53+Cz+l9m%*cN zrlZUcWy-Gs_{uq;zn{e5kxi)a=!kpHfgAln7M3k^@?<(*3pt(=7a)Ue3!U%S@Wdbv z_5w<#Ic^=Bb397m@RuB6+4%q^UUv$wW%0M2AExC^VIpmzbLD_qBVJW?Q^V?22NLZn^-lSqio&y9EjfxMI-4#^i zalc~nit>xcV#QCIoRi;_O)ARH{lSMW{%-IPt!2`w)YVJmA?5>u_j_L--+mw>V@>HCz5Kb4BOo=yBa9 z(Yx23uCroT>cx}XFoJAJkcDp4(laDQt@Mls>F+=X#HNvN zXT&>>mja%_k}#jD;6*ahN`HZu5>W{vRGP3+>+p?+CFR(vLL0w-Tp>-;33e<&dhjz8 zbE@k{`m)U375z-U*U?{wzAW{ULHi1E(0@(R@!&(|?d5L>{41Eg@{q{&o&)>;ffV|( z!}3b9h7Nn!4653lK;uyqB^;ifX0lHmZ3U^;deXxTjIHG%v!;%iOrP-}~VeEeiHcg&_x!!bO|9=-DKYzptMNhgG78h$bv6)2B9d%LlJJ-+)O3bJ# zQ${)~c1d1a{p57I)Iqd6qg{yAMmI32GpXmcdjE8@U1sH3)<4}{c2gt+wf`DIipG4X z8}s8f_e%}_67rYpSb2o!k~ztL4aHZ{hn9Q*W@y~NHjZ_W4D9a3SGBzJP+0MpN=_J0 z2z5~s1uX61L&{L{bc_9VLHGTfC#_pJTosfER=pCG>z=)nm}KPie>Y;68yW4f{Mygj zy7V*4{?V3uwA`PGUr@S6<8*dTm2p)M^|6si@A8>nmuw;h4>J24fDggX;KT4oI34~D zAAtcB?F<+S{{|~hz~%5VTn&GNa#rjbT#NY+m(oAQToa0W4157|1Nb8B3txhFz>RP!+zdzL0WzsHuz z&L>|}lM?6v&tT4R&7I*n%w1e_H~2N?+u;Q`40gH1%~(-@4?^ZQ-@o7$xE#`Ydh`HX z-uT$3CneoIun)#O9)`dLko^+hYAEiTU{yWz3A0)7E_;tz8PlDQZ&X7|=EEo`%kF5H z1*^kuum&6oYr-N}3r>SEunH5VbI!3VY~)I7)|!*9feW zU=3IYCcwHd1*Sn3eFmFu_7_js0JAg5J7?cu?0GBdy9YLb^aEaNOqye+=#{g~=wN3{ zSQ&TOKZnib5yXy)DbkLrHI%5@LWwFHN>uG(N04CKMuurI6+rNkvv=6d_wtC(5l$@Ym)2A(@%4jcr#!lCeXoj=Qr3NGYU zig&dBV7A#U*x4m6&(7VrO2p%#L_7gXc8Z{6XEKzCi=kxaekj@DkhPti2c@K%1UtLH za-3JbztUzpt`ceqlu&0t3H4DZp*{vB)F&W|17kMq1n1~q=a>zHoxNUV%-5?HdZJ3^ z;VSdmd>8{4LTR>(U=yfe2e=eU16vMngHlNS;Y!Q{T=Si94d#*Xc{mQf2q!{*O7D9B z@^f_GBXA>pO4bjX_3nS0JxhFy8P0~VD&JHdhF&rDa&1SS&S$&=(_tCB1-=He;cnOq zz6B*+jP5@1FX^VLClh__aNyhF%EIVux%WMi(SQ~@Car`Ynv~-_KdFb zcF(ulHSdAPF*Al4pTP63{WtIw=D*_@DYje3k)=Qtq*I!|G+x%8q9)!!U6C)JOU-&qb1z@ zjm0sSd@Rj&;Ja&5Nxtu(2~CToBdiCRqJ7<=1aK=1!pw; zh0##H+F2cjP`$NaNh~)KP$G=QA_>-p4P5&Sn1s2JYnC}G1vA^+MqSA6laUHp*cHDdT~z!Og~cy4;id^7kD`*eab8tCL71EWfMNubnLZz%n~FKiF{!9MUdC_UnK zC@sG~q~+U*^1*?aS-%*Apfvblkkx@P0v?AW;jgd&GWOg482gPenCmINQYE>okHuJB zeSvwq#pwn86hDoNnSg@-*8of+M(TQ54JzXvJ!uB%o{Y2f>?u&Dw)*jx@rXT7o3SMev6gXm36v3MDZC3VgW`QTlnH(%lsRHGd>XEW z8{m5AA3*lH=EHCk_A+p6h8N)$_z#riDT;3gW)>MGwuJ`^38)Gb1*w=a%uK?@YcLbO z4w+GH_gml|%*>=VySw(i-~sF>xn`y!;~-`x8{-iC3Lb&q!=unN8L=2F>{ao{Fo6N$ z1Z)gHfpih$Q`i=sf*m2Biu4VJ3@*NV;2Ag-eg$RKd>%dqFTm&EH}GZ1SC)NbO1`x0 zBMgJV$oIuiZhqzlF|I()HrqK2guh}Ab{Xs1$HRB9myt_Kss;QVb1Rp(x%U0xpQhgS zjQNMj@r+H2%-CdQIg_IJOQtF;%yrxA3Cf zL;o>d(UJkD8%%}F1$M{mp*L!?UhqeiwQqN|DPLQAfUA9n4qlA5bFxDjWzP3Y@)nyx zx$RI%Bj6k;Pq7{0K-k$b9xsAY9g|@n?0M2M`e83q^kB@d!XbLmVzZgap^o<#Q!V*e z2Vp%D2E$QM(q9N=z!?K$;aC_C?}k##t-?``{w@K3ohx zgq*?k8FYi^pv?TsVGLXa`@l8uF6ppqxhcj%a&kX>5%UAC`9a9Q>{|dgz{QZmO?F4z z0(WBG0rx@nR(*^P1{;<>MgwCvJPG$fSt;y?SK-@G`rW&*fjow?4Dhvt??Z~wP6)+l z@FZ$KrXGdl%C=t$KgPTao`CF@8z&)w+wO0{&oJ{c+BP4A6ENe)_yShp4S1ye^Dg0Weg?pR^QUl70x~9jNDQjLSt{yM}`&%Jv6uaNDM)8ey z-N(WdkMYlXaum#04c-cCK@P0gzdK_e)$WIVbL+4?9UHMhO1y^5oLd3P$&f=tOE<7Ou?gJJIEr-p7JI@ znerw=S?o{p7>_Q3_hEhxviK_Tt>xxHEY`z^q4d=0P)4*z;3u#Ieg$X1AK|0$PdFRO zBAV~D`(ogeFcr>&S@0<+1KWJq13nE0L*7{U#=vJhC8UrWR(bYfx)kyVWGsfVsAk*3 zw-GLbJX#pbp>#PZk+4j+nssQ*o~R#%-9PJ zdcZyy0{26CVe}Sc-Y`nu=7xE|cn31h8wX)~_&)3c55XajpBMP1zz^UY_#xZ|k3#yh zd>Y@!dr0{_zV8A&4*!BDV090ZKa7W`U>5uga^$hZ_?#OWn(+l33D3ZL;FnOI_Rd1; z-8cv5z^~x~cpg&h#y5~+H7>$e;P)P5_Q(Jxea!d3|3G=M^gDbQ{sCvg>re+U3bI1? zt;K>Bx^F#{y4?&-%)6ln9)KJV^&Np;$d`}g!@|CwVKDp?iod@gD|=rRIwUK5pL`!U z1oGiBgG0@}`j8dAuL%_W<|W+ln*?7+SOfNeHKDwsss%^DSSY`9;K-m)db)U&H<3 zpN7fsIT#OLgeh=1 zz7%gXhy9`G4}vW*kB6-xpNf{heBhhqx<3iqVV2(%w1;aTpYibRfH?v5|F^lx#o}Ao z5&i=^!yxA7t}qIAgLNUFsPQ#~e0jsy2J!(FUq{#n4uO32&^H?PgHs^i+VsgBKL9=f z?|=&+-v;w7hZzCgn4`JjlWRWtsOepBFB}5jhQr|@C^uPg_ z8SET*QS8fKvCOE*F{sz2WsQZhL>Q;1KX29yc227(V}YY}FRrrwn*is-iF!X;7H3X$ z$#^R!cMA5hFu4!bfDb@fkUR(_^oOCWC#OSMPnN)La0Zn1(Z6(y7kF>voIK$t>h`BB z_&NWK7uZ|;Zm(Yc0;{1XP?kvMKpETr4O8G;D34oD!WQr;*agmqGoh4>EKZ-nEUTSG z@HMy?zT>(da?Qu!QtZEh&%#Tt`!BK@5)Xg47S|!4g7EzfSHf_2XqDXpUJCo7;aZpk zpNDZI*4n1n$86tcv4roN%)Ni!%6@s~}_i zYx>xW=CkHI`}Kr%W}Om-gvX?`-$D(rmWU{SUAhHz=X8fEKOIsBoweA@^)7y-kPkv) zG!8*2 z@LTvHK1imRZBPc7t#!wQ%Fzri)Suhi}fKpGbU~kw4-T`lc^2&gX2;UgU zMue{z=6I>Ee{sX`?t2n;g7cvipR9z~negp}-QahS;orwQeOs@VOL;WtgMA~|7dC_a zAaB79rU|>z_lNSRFaXNJ<_RV-EZY&V~PhPr|>Ulpqh*##5N1pqP{4Ld>Ob5#%|< zDAC;T9APYhvM^Z+FG2C}2V90(7Anl3z9^4lFAJ8{m}|i`urYiQwtz1|7UsswuoK(} zyTWa-J7lKyvGg`xhr?unvzwbSSnPxM!8f4~9)NSiK=!?dkf3eRKKu6YT( zfSEzi_y)cMzlHC^@8C!9d&t-Nj8l+-#P|_jhCjjI;Lq?cD2*?e-X;l(q2n9>@s>Tk z$=st#oO2_p{E$fsOTt7>&_{(ibf#-8ul)6*brZ2Ehy%0-M7y z*cMiSIj}113c~~Gi`}{5H>JM5kQI;Jd86SF%+=vYSOXS7RzmjE3x5;AetMDYJcxa5 z%n!MI9E$xc$d`Y7b6_%j8rFv^U_&SmHyQj6kmhr=TQDrUo%Dhb-KDFSzE- zuKPQ%3-(7`^HJ9j}f4n5#pHI0NQkZVe@Z zT-RPUF8b;#+sui<%MLrE_j~qNX$G;Lw5xdllxn;K-VO)CsgQN1{meKNuERVGN+Ax1 zZ$XLmZJ3W)vL)t&aFjl=-Mqyr{J_#bSY}M*7~HF1KNi-8<8-?n%o5JA4pn{xBpRpd zh+LCUjfDKY7JF9aFRl0nVP>gozu|ol-i^5gJ_2VzNfLh*!+sz47(9;o3HUW+Y3#cI z=fJD*-+@L;d-i3m>$3ScSj zUIKg;2Ek=81d4tbd=9g8ofR+}u7omuiQZtBGCi)w{1{}dZohDR0dBzjBHRTfygl$G z%rbk4c|Sdsk5Q{v%|6x`4t)$i%_*l%C`dy1({dDgqw;l9ckJw=BP#=Yc+axnpZ8(e zXRn&y1O{`2!=BUcb^gZE={@GIk`ZLJc@i%akrBu=M-jgImifPDzX7NfLua63`KR3Y@|Oj9$AL$NMQs&%FRV2g2GEj`XXbIS;$Ic z7jhiAj0B|;2{I6owZmd$Cvp_=r16l3v_|?OMaV2<19AX4k6cG;)njl#`XXcN6%Y_N zi;-Q3oU*-)1f`Q=BpVrm6eEj~EyzLSEOH%*u8$7VADN2GN7f;78u>hO9f@wRHMg3Q zPl1(%y=mUYm)pwtxJjI8&W_eA517$q^WQe_R_4ciaP%OihA+*=5!)ci%Kpf#WB<9T5g(h6NQ57o4>+i<#~(LGa{uA+8}W=d z;SaBd{^EpL=#O*YC$|0GPwbR6`P50EgYc8KspMpZj0c^nkk@Gy4VN)clzl!k>zSmo zZ0c#VIISe30WAa>h!i7pkqwBPe?E^~N8)+HXpZzn#v*f(wa7u_EaG9ti$`*hfygxE z8Ds}?7`cRa8qq+IY-9*hjI3-#bKc3#dE`2h-k3m;@yJYM2XYv>j080y07OpL79q2c zEyzLSDk5i1TO)E7dK&T!vJW|lc(ONzIeVWYuuFQGeCD7snwfJ~ssGbmL)i&Y0KCY;f(q1Ef(ar}f~XhyhU;3xJx~~^vtHusj6*`Ku*jcWw>oa*xE%`O zZ|Ifq=N6WQSeeB3L5P(S_8qZJ9^u5IcUx5wbzG@uo-ait=k9(X(cKX#^6(c_53ek|4-G178)j9rr0{x& zTXW1^L(4u3w@kjoI$WQLz+&UTn*-SgU!B^Q0-P1-%%_ zLkf_&Ew<*aSEcb*Qs5E-Y-U-yUc8lHHnVi^?9kdeERbIp6vbPE=?(Umq0Yuz(Shu~ zc-x}-C#rGW*mWW&ql2iNzKAT*N274_C*hXp#}cfRK=!1(GjQIVVAYS~rrbXVZ{$RX z!JuX=K!Lx4>HkF565XXXUfJ;R{)EfK+E)EYZpynOjnFv5p)`I(;jwQgb@s;bmR4*R zboSOPO|&9{qdbm>Se;dmZk3T}#Yc{F?WEO9+d88MC0Z$wUste}etJefnP{~O{JTaN zh9&wKI)TrTm{|doL!y;hg`4ukD1EFx{p<2L{-({WbSqpBPqHHQI=L%JvSI>kUHwHm zN5Xd|S&ajo)45CZk4f}jcIdnZ+`zQ*R*BY`$yP+9-zwG}8qVr|$yS^?tM7Gi?w%lW z^jG=!%K7kjGHF~vXpOy={!cOm#*LlE{}x8CI(AV1J&cX~InuzDgu!5{KdoaWTXNIk zc@?j}+!pHp*!B|LF9p3-=)I5g!zorPKA2>el%*f(99%;mO|ilPSL1#T_pehd|DPOP zqEqYQa}6#=APuIj<^S7BOZ1btgssJ;cA%4Nof}vsN`F|_ij4DHNvo50v9*GERZh(` zCXh<4rdKM#KTjb2ad{xMLh!GM%L}-a;PPdvl^VxQc~iVffY~7|y$Do0f%fCO>yy&( z^dg>)VE1fVh2Tz!%Q{>>#l@;;rABh&2FK9EbxyabXZb&9wnRTz4-YTlAu`C)YwB6a z^|>jJU;c*Db>wb5-mv!v^kY5RqBAZp(OKyP#P+OrH38j~ZY4x=V+SOIqBP#G^tlF1 zGGA%c&_=R@+=g_5>*>rbZNUgi|4{%MX$FC8 zB9Pu8mfqXebE8XK!Ntot2X8@$j%{T5|G<}wv;HYV8kdZ@6EpZk|I9{Ke6TZ`%J&rQ zKi;*gku@vW86lN%uk$xxMl`loS`2+)38t%( z9mUrg&dDE?+1J!6vZQ~0_%FU3p4ZH39!zhvH4>dqH7;vrnBEA53skxPBNq0${&Sx6?x3HeEq#wxRo%XaO`A(Bp{OUlCqw4IIRza}SdS!#d z{!6*LT3Q<{X{q6@@inuRHOrD#g=tl=Q@M&y;@Y`C+?w1wbs~25H{grfSOYC7>*0lb zS^az)W;@EaYFn#!$yz2f`OU{sjyqH8Kz>LgpfC5&6l)S;WKHk$9vzl7|!^ z@;i;i$QI-|KgZVCHjuqwY z%y+}jkJM>7tXE;z94ilx_E$mI<*)+og8L66^_w|XIFT(#7iTF1S1EQ>caYK&{&-Ct>L%U#ozd-yZb=2*Xg$8O6>XN>q%l%~{X9ya>1w5! zu#(n*ZUn>oeQ#)iex#e#z=Wa@fXIc1FWR*wkQli;jTjc zlPJJS3Wa@WCP(kEJmv$1dR`wiU?q)!zGxKPiN?Z0-MBBc3M*;6gobxGk!-dVYUqo7 zX^Zua6%MDqcDCn z-x4DYu#&>00Vs??Vb*B9bO0g1N(zy8pupynckO81_6|aTl@vCL!Z;N6jn<#sK?tyt zLa#efVB5-jdbGa(PC|f{6uuLMdr-JGT2~uL2(XgE?13nZM^%w8#0DsU;wfW1!7>Zu?@?_z`$Y~j*Edo#5RNt z!@z)H8#;@D!NE3669WT*ZP+0OI=yYUBnCRTZKyjO1D)A63=snz*ET#O20E#2I4lPG zqiyhvz(Cit4cTI#huMZ=G0>~{3v97^!w4oXdJrxxrJvXu5&3A)CmQEtDP2H{*(a7X z^W|bmYql*fizO|$>PReUptj|Rkyz3g9}!F1oNamZ|50`>@I9CP|NovoAN$&Ovv1}w zrwuuuC81%+{ z=k+;kpYGr9|9?FGJYKu5@AW=h=kxWsF6Bu1x~v>2MuuZtDvlJHv8gyxG7QI^sos_g z)P~k7Py|ZBdEmQ~;R)yl5{d&fgG>~>;xsC z9NYjAeF&foUEqDKAo141i7bY+V7+B155+j%zvFS5iHvVrLV5DPDeou>TYUP~|E9E> z1f?~Uul}3zl%lX5s5gJ@w=t&^D#Ax8OybDG)k92)-E31D1w{PmR!l2y&0uZDjEmcqY)T|%AVH8fX3z-{!uK=0h5h5ms9_)- zSiRY%u?v)klv90(_Z%uER zdXCED=_l(my@~Ek63>NY=A!W?37g>^${3qh5?bk(5&Xjt>>B)o^JXd!)Pz)-|3j+2 zM9lQskC$DNo-;}ID=4U!X!^WxrnhFpdYo2M(rS>t$U_nLlHmMqt=#3(EbncFbwhn} zex^6zA7=AP<18jw>D#=q?n^Rw7J9FuH^Cf58irR2;HJhoUuO1K}FU8e~0<1+Z`Pjm{_as9$MYzDj_XI>^9Vodu&mEUoueb*7*|4X*q zU+~uSt4c=BAia>JL$Yx;lj@zM4t67wrKbJ!IV3P#Y3yHxXM4kg>n;D429+kzo+An* zT12od#}ZXyC>rZn(0IFQ5c&CPHp%dB>R|f)e|xY>6bB;(2%GY}nR-4-_oMXt!bhpKpP*=OKWYA`H`ZDU z=Kx$~k_FXP=xy+94eM|PQqyj)$WJzUa=+}T7=pwvC(qRQbag< zp?_8^y~a7Bu}cw#LpWV5rD|Lt3(c)PG?Mm%OMqm@d8(g;{`4>sMol5s@J$mWY?$MVRMzu z87ZxFs3RAjq*7hjQ&p)503kTsnF<%PoVr>ft(No3CR+{0qO2m%oRF5tvs6YMq}_!* zWx4lmUaH-;ocN6W1GFMo(mNwu7}JqxU!yx>%C&RoW{U&)6-N}^1z^+QxwvD>;xzg`A~i; zF7A=<{nqX8$LUj5^CPXA|BScG0|O|uNgxX>2V1~?@F}Z}K+so=j#<^sA7)g`2&H*t(;&kH$E&nH|>PK7e z$;z#*a_exGee?VcxaBFggd!4Y=LUa3E*3E+*vTGp;~dLNm9i?192u^xVH2mMPnabc zuX^js%@@6);v*rlh=)Gcz+R+P@o-cWudh|5e_^P+LEP>~ix@lDzr_wl-d$5}F z4AFk2;4KHSni1X4Um~+JDNiaWN^gka9DLbGuauWbuS=v?{zO^!GU=6XajG0toB=uf zGKD6f(n=Xz-=qw#9ICIWeXW4HxkjRn97kc)g8A>U-I?jksJUE;Fad z$J>a@%qb?Pii_e5Gw-BQ(K4*otJtbogqgQfhnaUN=kdczub0~YyX0E$@hLnm9Kc) z68H_T5cn$uzS>lI_Z7x!)uvVjUL|z6S(PH@`F!qhv*dQfF4s##A|;u^hpX|NcZ9)g zKj-b!R3?O*&zl@lWz-NTHwBDL3s)nwntpYhLN)sEzUpm?Hfm-aNuuTjBdxHg=%@?| zSH+TSRn>kh&;#zA8X5s`OxcpoIS8@@*0 zf0fj3mSLTj+434q*)?4HWXQqSI4^_wzn+(|CWT7aW1Rvyglbw^qk&F0H+S-PdW$@L zQ;K`-@-}yS2BsEI{D-%?$8XjyHydyTYrQp#m+$sgxIHtc6fb+zJJ9W^HnsS(V(*`B zuMsLv0ZPn1mMHsV6gS`J{n6VihXy|%Yz0R_8Mpx=2CY4Z#D`%Qf_xqK2+gZa=XD5~pN1cDmvJ!8u9*dI6DEV=fdS2{(?KANJG_ys3ofy${GMbwVuWLvLS?J5L%P3Dm5972%K}6s#dC6r~)98Rv89-Y?9; zAsZU112LuEU@O~6%_IllyE=9I4Q5@7Rh1)t67Geil%r&avx-lwTq^ZON2$0)^Yc9i zSycgp+#>j`<*Z7dsywmM>;#QbH_13beNHB1e|{l_C%kc1lJHS$WwEJ%-}{AJKH;sm z;2W=b09TojxU0jXwJ^`~yDjDg%s!ZO?#9(cbaBT06g1t&y$LjX#@F4PhRNFm-%ps^ zF|T93fvNNrWB$hPqnLkSeui0r`88kPx&Fd(*<$=1(+-FoTK0()| zL`Hp9IdUE%Yd<5M5+VGnMBe_4A;iB*%<`lfZI#gP8(Yt^XLx8JEN#4b(WT0t_vLUY zXPh|oMKAoH%5{YyGWS2;rZtD6an3QTWX{T(nVLCQYK(Qau+AC{k<)PL_raBSO!SlZ zn`dz=f5XxLfjTNsUt_l&>x}m)*_kKl6+SSp>cy4e@?^6|Rl)f{3Ql_K{EeJqkyW|) zfS2w6i#*FBt48w!xdz$&f%rf7*8iK5bnYQkg)7A1>iN0BwJ^YWx6IEO#H06fX08WC z(~UP3K9I&E^!i3y9x%QAoVMKJ`tx(I{oLaa>2!(&xSs^b|46<(8_K}$6mzfqkIXcy z{eN3ru--;iIc_(9YVu9)*ZYElR%GwkFT4}|W-hv2Tg~xm`4`?C&zxg2wv0vGyko_M zW!{%O9(?Zgl{dHj9tu+_I1ki4q;)|@FaRWjY>*GOg5&oV#Mh?K(QuTr|N9+Z?hPoG z=H-;U0mW|h##blFDfjNMo0PaS6uk3r-CHc9&Qun>?_}*6;(q}`26KuBefHCv---V$ z1g`MVvx?;-Ct)sxNIuijpW$95mFKQW6SBr-P0unO{IE*acXCF_UxaOEu^hbDXFuKf z9cwcXE_sY794ppZWVK{{Hy~1FTbayjq3EL#?YK|gb`rv_ zP_&XD^s;nHC71E& z@4w}CZkbT`e}X|(&}ps3~PaMZD?2ze;iuBRtN)+ zEM)gq=j$6Q2#sWODGNpkKXX9z6U)sWIOWLPpGkupS^YEPr-u)i5wk}^IdV)n|LAa5 zGrt_UshnpYG`UrLR0o(Noqk~&nIl7gVY-@h*vb;9YG#ll1-CO_TK|hTGWd*xraHwO zIjltbzFpz4Z<1VJ5r@uQPoV17%S&zEN7J- zYE+sdOK*7F1ncvuwH=UK4Cmi&FzGD6K^R_h&}!N=!v1cRh#E=eNW0%ii0JpKoYlaR zg!qkt>UXkDQFl=4GA#~QpY-X|q*I2kRb`tH_B(Zk?^5+S?@8C+y-oacY;CH})C?Om zr)t}0zAXHmoSZM4P2;d>ocY}wUs+FD{eiv$CJ&`0GURc07i(~AHxue){jGqGed8bO z>EBDo&Otm*x&6VhybON5wt`=A72XJMmQ72q@Wy$bVX?4+VaU$n)$M)tByf{?`9Vqf zlQipglYQiOP4`UY{;BD{Ub)ka?z@THAI0+LO>b9k?LBUJ?gZ!R68~h?k?ye3P1>cL zKVhW{T=%E9wZH!!m7s1{O*xaw%c12k`bS!B15CHTUkIyy?l13M{t}BO=C)qWUu^4* z+iL{#oZ_SNQl6}i@HOx}tlV3B=$#CwES#P+SXUSMB0OvNu09BLohiKYh}$P2ZePGd zM`HxDqZ@uYmmzMr=u75d`pdbfMg4DJ2JMjB7vZhg%YbPsCn>JJ&nn+loC3|{xl!cEMcvoMpKWvxZr4&XqOsL{ z391oZR?RoWLz{c5ns1q(_R$E#LElu9rZl8U+JzV$$o-AVSjP1-}g~mcHOrkkKINCG)v71#+%z&TI>>JDSv3KBpXP&eMK z8OA|@-B^x;i@-OW!VO|U637DiU@JHd&H>j0C<9$U0>}hQKoK|!&I8wj=mD`{1jq!- z!4_}`oCFtvZv<7T-qSe zg=u(cL*GlfvSi=tJLvKBsUeBczDP-E;Zt8lyxhXq%Ke0#XyNPbZde@J(sv?!Vqhd; z1hF6)WP{~k3pfN$f{;-zR}2^cl7af>at$~HPJ-(oFq$ZUIFJT%z_tkMPmhRnsErJUzY1M?QalvAl(cM=cDjSw8pm+C$cow_m z bCJk*`ly2bKNcVE+1o_(gLN~u}}TkNh{?qXhR>=LQYZm|S=;7c6`yXxm~-tQjd z9wDoH_&CBxEMC|r2YdMJQxPNNH$~vC7JctNX>zBpNpP=21sYtBtLF~v?O_z%2|stb z=qFI5_)q-5`8&nJKL-8_`(#vX<-B2ptc7smjmrS7<`Bdg#9_ws4>F$wZJs4jHvP~b7WP7%0^ZNJYiIo zeZRxrcC_Jc!>mWGBc_I zQI?_f6?d5CyDh}Sm(e?iP*SsJS4p0q?bF@ve-~ews()J z6-uLwozL-YuT-=35#xuFD4v{4qo8w3fd26aW6+4FuP^Z3?7E;M^(q0R0kt@~2J8mM z!Fk{sOIHutg1#ULWP#;iD>wwoz;zH9M_mT7U>L{*OTZSeADjeNK_D4E&^MXxJqb$= zSOto}QBVf1gNPKmF3=YwfgG?3>;}iddElb?ZveW0VIUnW2V1~VPzEYMWGbuJAQ5DN z-0%Cxr3|t2hbZ9L>UyuZ{K|Uw~M?o354gwR10f+^|Kss0iwt)Sh3|t416G=Ic z0MbAnSOa#066rUcIC!sw4B+` zI4D|fnnu(CU;V!cWTa%zMU^3-89Il;fS#w6Ut;6RKV zyqlp_$Ab*5;5wq!G+yqEmca)ZqeaVvgNFEGjNnd3EW!*`Z#Fv_AGS$)KJHyL#Lh_7k2 zz4Q^M^QknCyKl3O)2RAn4+gIyN1bx18R#}S^8rW9(vSMeJpQG{1K;u8<@J!cD@uGj zJS1$dW4?Xf2IyMQo#VNY@B8BXW}3KNJB_CyB=db=saN@C92HFZz}K>C0#$i3P#bjX z!ESIIoCB^*8aL1dB!J04y+N`jvmm~I;c=>dE}uI@WJvSlzUH2YjN&23eRb7TjGIRo zD1AsR<&H4@mJBKUurlXzmbBy>OFYg&s-&h%~>=D{^%i>3ecX<5QqWqUy?S2n|^FNLpnhP;2Gaw?K5{*NIn zgD@;ZI)CgNU={jYS*Qq4LKvMP+nt2pAl%M9YI>&aW&6~u>6BnKDRfb(&r{HJO0rE? zEg~7|+GD0TCEL4OQ5Ejgk?M}i4MR*!Q z;S9OuGl#^`&miPOcy5Nwa}xF{LIH#~XUJJ6q49qpaLKCv&lxiCKMqw(6@km<^v`C< zKb(YXim(d8S2LvENr%M9lMuL;PXA?w^T=o}`=t;HA^2v>_a}W#Jec91`)Yd!&eSCO z4UP4`&wa7(TzTYk7zM_oGvy_mtPk#Ub;-TeSG(|(FA%;4>IXBe5;aS9d|o+g&XwV( z5MK+!xtWrC%29d`D+2f8>3aLUprDR;AhIOxmD z4a8izpoF;rP;Zqbw|wOg9{Cl*TOf4IG7~^fDB(6=IfReFqrV7Gw=DVbD@RG_R1V=K z2)(mpRJnt&RuNu?Fg{D(E_bAXb_T*$2vf48{TT;gh9Yc(ke?;%oP^VgupNSAiGJ2u zRt~<%{=H|(46cnC_5 za}FgJl#*RAbhecgC?##aaVQ!24NADCQSV-*q~13UCC6Y0ybi;Iwi5Rsl!SikP}2Qd zlyIxEKDJ89?@lG#UN=Z+-TtC0Eu$ z4HQFt$<}afP*{vyyyk0O*(laJPqJRUGJaq>97m< z&jpqG$Cm$z7kr&7H7tc1cnj)PTSIU#F&Ol{BL?p8(Xbz$Uo8#CFF0Z_7i!=D)LOHx zEGJ8TWR?j-`DR~!*I43GXUJa1SUmS1*6p!*dxya)9YTSKQrZg%=l zxkJMn@aQG*oSH3PUh!2$pwm@^k3pzC$I1bOBjv+HJ`kFJ)uCYjPNg{-&$^nj^X!;L(r6bGN1DZ`7zC(eNSE34haYdT3Zck}f#XbTy3nM=++( zk%K=v;uHJ{4gZ3$>~9(}?jt^^r1h}+SZ<1|g z$u6bj52un=zo6tZcv@LJDEZ#0WGxK(e_-g8EpPwg2)p(xgp&{kWJ~*B9fTPW0-r+= z+uMR+c-v=G6dJ2_i%ReLw|F`{2h4oGI(}p z%jFwB`+!BRbpMUmoQ60!bhiK#9@%Jl4L+4tFb!|AI zzAeMyZvi}dIXqEwW#8|PK)e4y_zZ*;TR7zb3V+`}93^cAJo;I9CeM|1e>jBCD8kne zI7e5#!V#q56%fur$ek;>PQoz=fo~wZX?r*HLDHzkO-ERJ-h}5{cn;V+PyG*`UGV7N z!Sl{sId#+FbF)7ooQLqqTp9AGgRmAt-~xouc~&aLkHF`z{&e^p_7^XidW};oRHO>6#?rZp}Ubmb?12#xXDG z{gqf9Y3SD4Rdz2!-CEPY6^K*p0PPwXR#yTZt*U!_2Oj+@Jel+4vb)M->Fz=J8ibX$ zaHml;%uAfYZ@{Df2+z8C@});}G>Tq?e}Zt(7Cx+m^Sln9Uxi1%4$nJ=aFkr}YW4*` zxzfsqhM%Ecur&-FO{@NcPqR-3F=K;A{{^0_D)M#ZA)nTj}U+U=&i7`5a-yy`#m&cuiV~X$xgvs;eM_scIQBfbO5&8-U z(|Iz$7-^kJqEdxcbA)~yJo-&|=FFFmt2uBFv@Jx<5zm z3v~#ug%Hpo#Mr{YaR^ThbqMtAHAgxJ9Kv%U1VSJ@WD74;!h-@1;R{OG56{dT zxh2dYJTeU7>Jaj5;cH5`O_)RY7(99?JViP3qf@whxW$Y@CGSZ>p4(V+$ z>0wB}l_MXAJG_pnf!E;>j@iN|l<*Hu;id5CT(_;eACZ65a0vefAv^*?$RlQQ)4T1f zq1neWb7e{dlAMFmBOZ}wBDChMA}mI=3Z}{rM>`Bt*;6~2t7EDl@0BwVS{?UZ`7J_= zuHocjGeM&3XtkwhPz#0Oo}dnQcLmQ~KIomkE_CDCEe zblCG9_MHxUsl$HNVUMU~=xkVvWZNe_O=FB{JYpIfOyhuQoHmV{rqQsrDQ6mEOyd#L z*kBqbzT;d>X>D%Y+$W#c)>;I&T1l)jU1jb*3D(i-MD26r{UjC=)mJ=fQI#C1qcuf% zf@v(RV|cmEG>)0Zg*qtK7MOXbBt3>?{yRM(M(g6q%qV^|MtjKPnLR@;Hz70&W@zR;eO;PDE;L-Z-L)y9dCn&7 zRHQdeQsJ#o{%KR%-U{V2ODG4DhXu$Lw`xN?zs!&?Z`E3>WyR{vv@hL9Wpi&L<7-a9 z%(X(dE6O|u(y_VL(tS=&$3xG8?qNmnqplhsC^y#<+yiB39|$2WNRgpZa2NJ2Ewl#S zk+Zbb9k^dG9fF5-z1$YsME4ehxv(XkmEu5JZC>t-8UX`{U3VHxM~*OOYUwHhAQ#&)zu zWn615&ck|G`)&kqgQBno24$4zprz#2HYj<=P{R4THn5+!C`F2LB})#rfjx}7bXRa1 zvP)YMnw2N>Xl8O-_&Zyq{g6D}AC`~W!vCP<*tZ@0V{QJ-cJSv|q~nl0tonS}4*r)c z$6@W^f7RyCYY+bi7O4!9hgF)(?cu*_IM$a59kd$WUv2*U4)E8SZ3gvX2l&;BN(cCR zSdLj8ab%H%G$SWF!k%VPDinpqkMK^gFSQ&Obs{+Vv#sdv>;(S~ixlV#KdTjuI>Y~o z<+ut*|0!dU!tIJRua!L18L8TH%s@4`4JpRPm`NKYaer5|FngxFPxMH(sXFlvv~0BbbMBzDGZQvE z*bT|Ul=omaQnmaJ^j9$T?uLHvTuXmeH~5*s8vI4w;Ag4||3pv9TvLBscl1xT`O~|@ zpK0-LQKVc*Mg&T`uh_Z`%~){=v_0pgMXBVnSz-{IC_~KnEZ$0Nj~NQl$X|?m>j8o7vX1U zZ?NXw1uMgOleOqBRL{&YLw*jDCojhgc|;$A!l>L3O78>Z^&H9VL&)E<*h_KrGQc)- zzM_wo;B`O31tgFA>dAz@)P2U!rZ4$@2~fl%#XI_HAGtj#xsuzTkd4nR-riqZ5$YMS zQF`1*4?uTq__pOf6w^hU!lm~iOlN%gKGI}~?b_vjt%08omvM{R)!Dp(l?!6h7VKoq zbsU@nt{H6Zf-WEdOa^&iJ=hIO!Fk|gcd-HJ1`PetAU^h4pE&?BiA8rM)APHoFRiFrzfO1d) zBH7sQ2nK*OkOS6$o!~e)2YmBLIS>nmfvg4mSq_T8QE(1afClr)1~3eygXLfgI10)@ z1&GW+5f}z?z$$PQl!3q_1R4wj>0mwB4a&fE&>$E6U_lapvcP(<8mZPa$6y%90jt1%@F{RDBw0aUkOUTi_24Kd1A#{g7#If9A9Xc%t;ez(oC6i$ z*2ho|(m)Pa19r-Z2ekSNvKEmLpa>iV=RgH$u$ZudVIUnW2U|c1C-lG!Eta7ge-NrVnAPz1Qvny z;3y~qu4N<+hy}wy4p;^DgHM6)NdgKIKpI#Dia;5-{v;{iU^y`bNgxa4gRS5wC<7HB z@+o*g0!Rmoz!tC{l!5CYas?FxB!D!q2&@PD!KdIl2s{lB=nK+7&I10d2fM+i;35d* zlVhMSNCG)v71#}qgNwjd01t=-NgxZX0!5${oCkqt-~oL>6379oKoK|!%0Tn${0Xdt z5yXOFAQLPBTflx$zH(Rmea53V5*VdL>Wlc$cfb{CK1yrk!QAmx$iBkS+DuNQ7)R=t zjMgG=UkuO0D;}4d9CD>i?~{_AYMh?P!{LUPH^e+HmrYmmy6UiH%Nt=+KVt(3J&G2C}EN~t$$`dNGBi=@?9R(BpJj`OdX zag<%DtS3(&Te&o}NH!>*C*XP1=DC#0w$$HvqQ=3)!6SXC&C@9@tp4A53KS2A*7SUv zXU6~F@h8K>(KQ}jvBQ%V)>L}`>9?0#7s*n1BA+dk?qmk2?TghiX-CJlrSgH^w+ORz3~p=DdQ1- z8p1wX_~ryc`PO(X=-GEoJ{qsp4*uIBsf7S?!S%WPJf54k&D-`DNzYVtb1F=q^rK8n zWtnNxk7k5bA@ak2N{05;qur;BLS!79!8*opF}{8bGk7|UHC&7@A60QWB{NKyg8m^& z_=Nfn5_brD(^zC!=;*uPtY_07HSs`E-h2N8%=E5yAVfn*mca3Ouxw30l)z z(ky2cUY~My$&d#;^*T_j^Bk>bxF z<-Q@0PpVvvSR}_FR9gwbf5RgSPI<;i;$$td+A3UH;PTvJ&fqPdj0gNOJWx?qiT8yJ zofaDH{z7J8$ks;c3Z;)jgHobw|D1;Hyt0iOu7^qK7akv+*GvKRd8$N|8BXL>eNE-~ z7gf21=F8RNt@{X6(Ch<#!{DQ-`tmmQDe*%LD<@tl&V5LGfLq6|$+Whl|JA9C@gBV< z;ptje&r-`VIUUFRYh1~Rqgaky_1nO+@tRy#j?@oBJT3#rqH8iX14qie;kZ*ds)C)N zE%QwJv3S%pZKBt2rnlRrN#je^_=0qXR_1k+V8#@lFWr1{a;8?-Yosa{zUXOWVv8Ha zcg@mrLl)eiJr1m*y#}#h7{~_sU_ba2RDj6U(7`aU2&@N3K^gEB((8e~APFo1n?NZz z4_rc*3c7(rkPa4s_2R0=_j9VD-W9*kU6`xI=p8sk`D4B`&(#`vf8@xcakJP0O?|9# z{{pR*-Vu890(o=+qixI`3#j7vQwCKzP^*g=t|pa_HMOsHd&2-O9i&+vrLGggKNZN3 zJnH#RmXIn$s%kWqg?TjVO=YubEM%2fGH23fG?g=^lY61TaCjzX@tUgT$)=566lCSK zy<*zb?J|OZlS_R+UR#0#xl3)$Le_Gds&BYz`t6F^R1PoH2Dv*(*rSyD&IB#A&@0dV zQ2lOe4ZMRahN9mFB~U0k9@Uz2nbm=ToQS<3G1KYh1;v*a zYn|Pmp9+ebJVC^~D(=P#V%icWqXENvw=2PTqEhmgXsf(NkSV{Cxm5FcW)~LEUaFmP z`|+2Mx?Ok5wNUPh%6wAm+v_T2%D09>31Y!8kPa4sB5)LxgBu`XErUvs0MbCtTKVxw zt$nreMBp!OrZLiFz;e=rUzKU18sMJB2884-Co_5)I}ozTv>O?7$g-=O7t2liVKS`n zDTDot%DWis5>m*G0GWAQ@7A(VqvcBBmak+*7@&TR`_vaEJR)m&p)O?HWZLcBh!8nc z>3~0#_L|Z$QVS_uVF((`iTsurheM`vh;umPD~Duj#$XyEQ$ zNduQkxtm^Ba#w0iJeXs*RPQgD&xA%6U%gGg)h#irwPp6e_|R$w&uQ@Qsw<~fYmI`t zcsALt_o^rBWp0tFv2ZVS`5@`CKGf&#CBby=8cHr?R53TI>f1-vx%X06G&c3@iIR0| zSnMfXLqW{rb5l9AhGJSySq*;U5K)7aUNWN#{Z3s$-A@)xHN~oq^r~!%LnKKMZeGvy zPcf+B3jPV>=U%c)y{~sj$evzuVvHv$^fseCSK|=VLG(3R4|l4>uc1+#K&*WY<)JlN zd%v%t6$Lr7mT~9qH7t_%mUq@vjyY1rzZRK^$Vfx!yteXSLaHoQgh>!yZzwy~YOVdR zTgtec=vlt{$m-OI?!>(wy@7RF53AWrmBH(1_9i1Yxsgxq&C_bh@^v&3{Hn|V)$hcc z8KB09@#Y?7xM5WdgmLXtym`xEgyE{12jeQecu~!R@ySWN7<-g84Ti>NS;SxeEPYA5 zaZ{^S%T%m(BeCJfg=e*B$=;;#{@!|~Eb-E6J<}2%0j}(oW=~0*IU&{T8&n3wOUil% zd2h#5g1m$mD)=qRUTN~-$W*4&+omlNw5eBRf@N_w1C>4|sCy7JI^60?EC*w(Cy zs7fO;>caHI4HSdD&8xgq#WP+W-oOad#YYr&cN%Iqb6a&EGX3Wb_2Lm66ZEa}=Jr z4xVUv`8kK4f5W3cgkMj$ls})-+6SMuczY0iLhHIq8jtdHl#ESmcw6>un>c`D4t)v8 zCOmluPfBc0UNr);+2P6X&3G~uPrhs^xtl8w;H1hiMM#IxsFnPdybHIWm~ zYmKG<^O}A0R;tW>9_9>~Q(MXN&uh(tsTOl{E2umzl))(Vr{}c}mBDNE0;dGtCwNa< z%xh)hQEZe z87TXpjpV+hHTQnd#wTrV^$n^_o8RE5HWQ9-+xnz;33Hv;m$g8BepSY$TYW~d;C(z- zT+dx%B_Zc!Eka5zF>Fc?(#2mr&n+0;uJChxo;yVLzf9nskl+R0DJpweYh7(=q-r)& zC2T7tWftDO$+uD}vE)()N417+tvoQ5DhuJ!v*7uroowIgNb#Q)fd}vPYwe`bHj?I= zrNqv<{^n;T{pE0urz!^zZ$oT0VjJ4a_uDE@kEBYc?GWZb_@ljy+U}@)+Y})iLZ=S$ z@pgwq)GH9?Lg?H0qM{7!VGA_K-L595QNQ<>lYUCmk%FIC}q-)Z2E|U*yNcX4v zxb#;GgxMsOJU%(`8ck^aGDg+cU*iy&x{=R)x7>V}(Zhh9G_2`6=wI%ZM|RL^<}sr% zi?Z3>-R-&#=Yjq#f;a8Qyx6kJFAdK$!o7^wSv`|4=BYd zNU9$l;23LSx34ld{uTj>*{RjlIw%1-{T87dwvzx3kO@1fo#s6Ssq*ShLb4EF)>w*V z=nR@b#~MwlG}}c;9);&kLb9uJVxB4mitreOBb{a6E=RJv{{dkU1mA7a`X7!|e^?O~ zLuhuJZ2X7T-rMXppVXhOQ)?d31MZh)#1Cm3418!f*yc;7JHycD0lgC?$7Zty~VHL3$J6)Vdtq&H?FHV z&*OrDy-axQM2O!DTLEkjb(4qo!uF8Ow$sV>jbeKSwnw^2_&$gK!}md031MY7$=$~^ z9dr9WM=IY`469)1*j<{x<&eyH3&Ls$TE4Oy7Vp;I@{aP?+JE@ALMi>K)`8?w)V7g_VjFWcKTt*0BQp~`Z{<%=_&6XCXk<4 zyh^nyCxiG1nW@?!X>1ztZ);7%PFYMUrQMQplq9{nk-mDm}d5jpk~-%up!JsxT#ReK496B;GVqOv5Mu3GV+{0Mz(9K@|WcbAob!!E~seR69x^ z(AUzgf~5L@1Zj7aKIb)uvs%1G#CqVwCpkw+%J&?hQq!jd$Ez?2viGRr8>)!mQLPK{ zYW5ECT2H)gkC!3uI9iOg5CR(@WX4;`J@h|;x>Ej*7E#Z3QmtEgclO+RxLh0`bmhfM z^>?*ll|9ddcTv6(9i{ikig&eMVWsy}C7MSTme9$oZ`s|0jXoA5We2mZmhUkdvYVul z@1f&4bnG7}k3#V8A86_@XK7OM9^GKbdj2dI)=aLv=NQyBD?xS>vKI!*kP;e|3zn?P zG?f8ERM#5q9>O!IEY%N@cS`90Lwb1_td%f@8Y0>;EjqY%kmaM58AIguV@xpZ{&ns# zQff246j^+7B0H>sN-3X|9Mb|`+|^6Y_g0RV+r7_#@&g9j|AL}EBe#y&sdXoN;jH7W zF4tdQ6hHsI*7a7k7;x$`=Sz0gExzlDmg}|Vy>8b^Idhp5EBld!HRiXif6}^I(^$9b z4Y~FsJ#EfUTAF8aqvEqaY2nrU?Ty)on=jjkY7hf|Xf6Hb^hv#M(P=A_%)~!fX-;h^ z)BfNP!`zl~P?=17!Yc?tiQ!&P@+-71{x2dMnT%7X z`SjKvhNbI#`VJ4H(1DtMmxn>;3QZs4QR7MtI-|(yy57}qjtt$dRWfvANX_CTU0>w( zn}a#GYpR*H71i`Kzd2rWyH=Q<=Y-(-n$B`LM8C`brZMDlyTZ(*P4MdtJdC6s@)HFg zCvGOwMy4l*6EJfS;&$apd^;bfeZ%z}4?~F|HAoFc4j(C#fx?goOvVKt zMd%Yfbo`_S=ktPk7Z2S#$~nCjB!G0~2ZN*=J@>R*NH03-gSU`1b$b+Vuc?3L@tYlj zn@VM5^7`6(oab7sd|6wc>7~t2Gro9ZeP)#&8jtW8{bQ@*yIt+fqFWK8xAdD8+U+{RJ=GMfxW;;^->imiR`reI z+_njU|JNWH*hHVVU=^#pdq62T4_xcm-T-YuBA5(Tfg*4moC6gg@>y1s!7z{omV-T@ z6jXr7^=xr~M34>g!ESIITm-%iE?3M3jwp1)k_K|XCa?#b1Xn@CMwX*NUyuZ{K|a_6 zO2Ksyc#h^43;>fs9@q*FfpTyI#B3rkAQ@zX^V(`*+#O1IFJOgz$UNgKaw z&0nKi>i^=3tTwIm*D=0orK?-X?rp7q;$B+Zw2l6ar~i3$R)EOu_zB{`Fpv(GfK6Zz zC^h&kxwX`VaSQoh=eA=Y4N?T^7EgzeEx!Mr5*07gL zd}rNS!?x`H&a7vf_CQx2)U&!+!=;Tykf*AcWN(!{aEB=nLO_?xwa)rrF7lGNy9n5@ z+lbIvB6KW4rroAD_a39C8@Hu;zsi;I61V#)+0~DA&}xW3WnQL#^>#fX_(_5pcQqb| z1TENAj}CriIUD0W!#TdIULPeV*81x-jM1rOXv!wl{&aA94bFnDdeb1mGtyM)^%>4* zVrXDbcGcN`bI>${_H$QVt?=J}hu$jiwaTy|rnD5yXBz&(9eOZmJE?JrIzq6*h!5vm z*@9eQM98?kux%_J%*h-#GbPQ;P?fPOq;WS6Agqvh3@L#{(!1%AI4tZ&tX9aGsd}A; zTZmEL>Qrx{QECN11)s>OjtkM?Y0Ft9i%Q8A;_hxJFp{O5yjkO?G~%cGUNZ)Y6DK%_ zb|+Z^mb21}S4u%6w&fDDJdCBg6ZDRWRdS&Q1IbyZ;d*p*Lm?4!Y=vCw zPT2Z5B-M&Kk?x`25iGf{DkIeD`U)wy&11iCcvfERq4V)5Nq*rz`K*WDBzVE%SLqD< z-`6qE%FsLE{|5e5_shIH;a|l)>UQN(nVBy`NBN`O`RYK3GJ?YmgTo-a&$xp7B`5dh zoWUal^=c9qO9523sw;WBpyaD(=%PJ$43`zX=~vgogO*ogN#=Yx7OUUuJ}Xf@3B z#CYHCtTgO}^6yao$q4D+OSdogJSz(!R67r0;z*BiwYYqF%B>TeZu;R!V%FUdO#strxMkOH_jS4wcI5mCTsD3@77AYH`q1Rb45E+cE zLpxSiYDSvzZj>qwDtA{(FrNHeDV^dCkMD^$GGuMM-Zbz7A)P$VjJb4rgb$m`;_=mX zvJ2EI=fe0|>30{AyohMYIGJ{rZhxwKR(2`EB?wu`a_TNJIV;)JZJ%RUEx|r|Q>i_rv#!I8Vq-wqKRk@|AYN2_g zsZeI9lTC$EU>dtHq~$%Txb)@E2y9`Q8RqJMO6fvz_oI*&N<-7=-j7Q8Z-;J`euXln zpWY%Eo@#ojGEy}!h3a+&Xa5X_1d04Qsv$LdS_3EH2GbbBh#e)-Fkwxeoo@tO@3WNa5DGps#+lnb6K!E za(M&&!R$dyhGj;Y{CN*Ga(|7G5Q!K-Q5GrqnyEzF0pxO-rAWm{r3N%- zGgB~tkaBuU=jH5u1E?ZDSp2H!EB-YyW1t$H#GIbgJs5>kl@AT@0Zc(-4T(=APGwtI#D2DF>t{(KMKU`< zj|tAN6f~Dbp8b19TuLC3gn9Lf$x?eTwQ7aMugaXti1q4OgJ}198Ja@rUoSIaxVe4n zU=rTuv|FF`vbl+mE*+Y_+R!4s9?)wS4$;VJUa5USb3Q_L7CkBE$G zgZX|!L&IvkpU}v#8t*4W8&=~4VT@rlPNFt8ti~zACWciVP%}PI-5|#Kv|A0=6Uw!j zX&sBTxnT`Hpx5#Dz;p5n&l|tw?5R>11XwFfC_Nr`%dbn6!&J+Zkr$Wju# zA#;z)Mv>bA&BrfLrW(u*au^mkPn*VXrZFQ|ucN8@xIYUX( z*;DOYHdn|tm`PfsXt@?ml_k~9qh&M~<&_PkwteoPslI-L+%$cNy3g?F_WKxXyqj(+ zSM8K(H(8dm^7t0R`GTocyPp!VK~AI-4BjvG z8T;!*=YGS_F{ZI=36aacAN8+hn(CDv+7Q&gaX;#xoMAevau8)WpHLlfU>Nb*G_xv1 zR5wKa){4v+Mw$ARGIeC8tQ$t*J!0`IU8;HAXbwI$nuCvx=HO$asB$Fv>aZFNYCN)0 zj6$RaSQ~{xq+E;wq!M$ZI^d{WPN>48#+oR4z;NkA8IlnrscSjU@+X9C`aey}5tp98*PeagV0F?i|G|rORjvZQBtHW9Fc2Fl?iJP8@4+YblRB8(zLe-NUvbLF8?^Z{cnX0_?A z#v_|0*e}r3SnS_yKB^Ty)}zbCQKZ{4TQR(_!fP}>4Msy-;h?FueY3>3Va$`DXwO(Q zRR~q?AeTiR=8e|7(MatbO^_-GQr~%UcC_B4Uf+3E`04zvw_$?WmN5|d1btl!8QEYK zonKrMo!|2^G!aF~Jj#H5LJ}3O(R^FjjL-8{Z6+0i%`BP3m-@kD2;@xy`BtvX9z(jlW$~+0uLdkHm;;snr6>c4Vy7nHEhOQ)v%SO zctYGYq;VP%$mG>xcZ6xrSN5Q3->K}knD$a-uc_>{$L`$YBz97w#X-giqsP;JOh1G5zsmV;H^=ZGjDp6G+&>)7$?fQMXup zuGHz%CQg~eJcI@Nj?4l(v0p=cY`O}7iU*$$zs~_z4AnnwQT<~Bc`8K@4NiQ#DlRa> zX*BeQQi#SA7EJ|ICDImka$ODKnvJIvl&A8v*XSo?$ar#h^b=JvR;(|Y$G2ZJKhro= z!tUFPa%?>F1iPvSQyI;x390JQ7k?98nZ+`OVitXW0w4HUX7Umn-{i8OXTqhdgtJzCI7$i8#)mc zK2*H0MCMJzrx*TLpWKs31`W3NEgz)uW9nOpNqW%p{t_8GNv|F3v-IzI^pYHyL?u{1 ziO%O`2TdisK~s68O~!v6#n+cg`^gNW%|ks5qZOeVgtTR{eX?$UwsBT|Q-lx*h0CPL z6bE6(6bOC@CCg-;lW+k-WOWF?FEc~vN=#3gHf_R8>G-g_Yo(849wLsRu>E1N$>v3T z2=l^2#PN@1Qg1qK)c@rS!C7fM70&|*4}VeyPNk>~f3hkoR70}WIL7SWDk&_B$f2n; zZClk6NgYj<{HiE3)nwim420A)TJ5dUjz%rG(&A8+TD52BOJ|6%RUT2) z|2U{>lCxE{gdKt@Pnls+YE^yR`uF;Jdj??-Bkc2^;?Td|-h;U!gLmldy!b{jgu_tu zl!Q-%0khXMvV6ZoF?zXh_`tiKp7z{*+cd;#AoiUhR!1&O)9bYQu2RMuyxNPUm)>ge z&E@*F(%tNZ{;n%yI++uJt|lwYxX6c#DS*Y(^|1P^! z71QZ3ml~&>&dTkXgpD-TFRzfXnN066H_p-f%ce*U-E0>%QkITqtNE}S>njm6^p0xi zJp;L0keiV&56#f+dzP3|D?&{O-{i}w8G7rmZ}O`O06XP#sR~#7u!Y}Ijg?+8M^Ues zqo`LLqo`MmQIurOr4J~X$-3t&>MU9<`F^Gze#`v@rcS#*c*P|HcWU+EX*P={`*R0b z6`xmR%q$AWD>8SM(I6h4MHnLq7E6l76e(TGPsV+r6c#sO1|V!SJ4(_ zk#cs6_>JOS$1LXqcprAu*p!DM)J93!N?G)XdGB5z2@n|Dg(C`LZBgp?S)qIJhGH)&Cbu$?F-e;O0D?_H-aZl zq}P1CN2@roGsGL5Jc#u>kWM0`RJxmqvO_k{X97RLa<)s`4tq7AVGfF;QT&NW{~YF@ zpIDrBNB){Q(S5DzWm)%YvNuPM_Mf&nCH_&OIpP6NpzsmB3pMNZ|HIh3z~@~5|Nqzf z+IGF)?`s>onDb!{C1-O;5;B%3L`nEKjX5?9BNcWjF>BbQJ&_n83C;16(DYHEC5oaX z;1m2?b7%A|KGl=hsXPRy`Hb<>-c`XU+32plvYFO>;=+)N>Hk|;LZ`8k2CXexo_$&l zp(COuIxhOfX}m>M(=_MjJw zT3B>g$d;d=AZICyhp-s7P_}z1A@F@wZR=@-r#1o$7W(s5%V6DJ(CSO78YNQ)nS}wF zxC}-FZ%%VXg;_?@;0@m4YOgUiv)(TfXdG>jPOtHy_$kO(eSbE{l-I~{eNmu**x#QG zV$Ce%y+$*uWRRU|Wp9wU_Vfe_Ub6~no!1FdUBWchFD6qm)GpH3dFKK~ft=VVS+A25 z8)Y3N<F{bm+B=y8dwIQ{q7p>W2cy2lgSr7ldc}HHG z?y42}%{z9`t;Vc)=FsiU+{?&+vpKHH(v3P-dZ?#lRr_ud1{}*t>>KnoHp!!JFb1(H zcno61=$8qPb*hp|oJ}$o5hSx-2`yKJE6*GUpJzS{n+Fybryb5G(pf=l$&>Z{O8mXa^goxF{K4}}%!>*J)(~?%b zY^i2H)6Hgsh5wn&gfh^6rnAky7WBSF33$eR8XM-S zJebL(wf?SjolF0>Mw+WEZXQjeO}<%r+w?M2;XVyXDb~s|)$G_Tj8rJ$LusVjX1QY1 z^%p}+TiaMSOZ8cd)}V71Ngu2wY4otf5krSsn$(QSW*Ixn(v)S>2AdAea@EB7t)gG$ zr9rx@Bu1^%Eye8WDs8GVU)EM)o6bt7j9*!5=b0M1Q9~!2<>Pcq+s`&>Z(15Eyy=Rm z^KMRY{;F}c;GiZGLDdKdR)Q0y8|?3%2Q8yQqGaMjta z%%Xa0%WMQ1BCvLaoS03yT)V>dI#7RavFq*r~r+h zFuLeg57ofmA{*wo0y}S+7?^{PjqovbrBt0upD1@O{~y74%&$GY^ZV zSd>~VZRQ18EL0ZFu!vnPp9Nb~d5fC!VJ!BpwnHu5=caiQ#TypN27|Y) z#&cvg-n38w{ZN``yIN{&(3x=E^1$Xu7n;%D0!`1&33hM!VQIXW}pE&O%P~_ zK=*aBMqG6{maNVq%140&wNmRWAXOhjC~=(~BDtPPzx~Apq-wxOm3G4D*kQK;ci0th zlxpy`G!{9 zpggjWfVUz{1J=vEh4c{zthd7!$ljgu=pt85^W}iCjC~hHlNQk|4)j~LAmD0^j<46t ziA8iXzV-{N$mp_riRxxN5E>zSme7Hy7R48^+dJglE>YvF5Yw48J^DxYXVWg(z0@ox zEtc}F-TMyBhL8LLDrD-zwo9(RLkHt#kg-aHU1}b@lEg2jQC=^%Sf@&rU1IIkKP?|D zrv220AU~1owD+%EUQAKpmsN}cbRo zuhK0~#xCWvmM2+D$*&d5T^04g)}BLCmMten=a#xkc?vcaC#d?W=82g@m1?j1JS|;v zC<$$e?vX7rF~`-;b7V_#f~pMIE!|h($!@z5K5&a+N|*Os;Sv!NZb)Ty9p!@e$nX4P zAtj{EGM5|4-N!;Igb(G|9eZ#Arz@!eW-fD;2^+r^?b7c(!fTJXFC#@?Qigb?iivvN zcgxSqtSP=a%gKv40vEf@mXHziBI~J2ElkpuGrJoww>E{zsFkj&^67F{U_%%m3>3K9 zp&*kBhTn5l^Tkas>oD|{BKaUjF2wx6TA#!rTteHz86$Q9(#}Qv`1a7kNx5K zZ60N#(F&@AfRQQ|D&6+j>9!}R^Rh>>NJ>vvzvDp7w?}rb;HBbhMKxJ>c?BtwG}MYAdl@9b~6osy)(rB`@QCzi}Yd@pz?c00sIGwyt;r-ITlBSGrnyntoyj zJ`mE+?T~)%FTks47k;j$)Y-pmKhw;O!RYf<1b(XDaUk%Y+jA+#`-CiVM{z!?P@_eq zWGiJC6FN+yRczdTa zcsa9LoyPyx6{#I@u;xK2u}XW&6-`TS?}NUJAGj)3Hd)R^3Dz8^Bq5V!w$;9HE!LcC zy83o~$*820g*#vDcYW)e|D12pSFVXpCyQcA9dIo-zw2c?dyA95siF@aaLsoP?d==- z4c}oWOI4P9%lgt6`}>-I=bEQEhYyhbhgq}AGK`8xTwgd-2Kr7PaShVUNNWj0(fZth zKhW&1ILJ5k2Ukm{T5z!a7;999C(5cH3B;vD-zz`4dTQpHp|Jw>v#uYtkRdNQ<(nBSV}9Vg ztG1I#u&(D_L;bT^nxm(^^!VU;we;AYP|_UdWVfl8_9g$uOXiG!#W(e$i`$Yvnd)nE z#Z@BIx#A69*Xyn}ni_JSbAzSAGE*+zV1+M(;r!-k)8AcfO@_0rRDV*&dgw!*{N2^d z$r!dJ(Bmcoj6z!i4@uTmx-GdkUCm5;=vi~rl?{zUOK-iU0>G$oi9bkL28sLs;Tq>; zOc>^Fl|RtPII#6&;GeEuA&mXXm{7KX9sZNi7JGUBFMPgyhlS4!c&`5oy*>UyFT%xt}~vxmY0cC2ac?5sJTHR}3$C&O0voO)L$qf}i(bTt^|dnH7F zN;99bhKw}FKzp(F$xuDfw1<&2*1uQ_xCe$|W)BysRsL2vI~k_0bu!{J$E7bfXIsN1 z>V9}@A%ACGuWjb|&C02j&(V^l>y@0o1+re(hnn{AipGv%OFq`nYda$rN*_b-V^&yb zN4{%uSNPUlGAQ|yOXhiCE@xP z&IOBoLnHK3F4ggQrIbF-Nk8XmDLvas?_)-3{SPM{g{jf{IFrV`mFP$89E>QV&o>Xg zZ=1EVQ({LMJu#%zY8H{?Fw@hjtlrFwwHoRgt7EL)4;f_%)85tcV_AKwlO}kda(cFD zHK5U5OQwbJxKtu-ZmBVbk(ATE6SM)dU8njbxxTZM!`(3h;F-WsyY6$m!juY z)Z3bNGf{JlwnJ385_w}c`!vTS`yE|eN#`B4+e;c-_^eu~RTX`{v)u;Yw^j6^A1ANP7Q);fB#e^6jz;~uC1x}&`kSNqrxBes9D-q`9Ym}k*a%p zEt2!?ozn0jeRS&l4;erOd%y+YSj$>y&$ zNCRuZ9&j0iGLjGrI)Y@726Dk(Pyh`2*7ZR=7!JH32W$f;K_RG|x|LXgULYAP0J-2G zxBv|Lz12Wl&nAnH>TfW9CTtOm!yP4GY-?!a*11-W1^CT>$zVR%4DxsPz+)alKSKd%1$u#GumbD=H$en#)OgSrq<{>N2aW<`4>1ERKsPXa z&xW|N{__dz>(MTbnRk7WC$;M9RYShWW6$g_#>d$WbdIOp9V#)k*wIqIf!>bg-D4W) zbzB@D@5wt^v3j%&TpMD@LABkybF5xc z9&f07BuPCD;7Lg~)XT|*SUp1KH`Jps_@JR4_F9QNCh}lTB`rOtdW9KuG7aps7JOQIX`!-z;y~uh1wr#mN zK*p=uwCOT!Am@{)8C4$DB@3!2hgx-QaA;Fvbu?CwLhQF#y;7BQ&Edh?`Wus!m^@~@ z-3JT7BweaE<^tKvO^ILU#(Mcub@vxXOtom!HEHv?lO05AC33oa+?asRA>eWO{(xIs zd&8R$@PLsDcnO@osS?{>-}I(^_)3&zYK2{e=uJE9rL0H7UMZ}!^=NJEJ=sK$(B4$1 zudtYAscG;W*;KFTx%G8%05wZIP8o-OYa6RBhsuyQWkOS(v-6JF#;T*N;`^qoYpOT$ zbUIcnt;)rlaz!cW8)U2^|E5%LhVil>W7Ri$Q?#MZa@I}ZYrNm@T6o)t^>n`ccaC zTX^=1UxEDgHe-*ez4eFW>Sn9hKiU$J`G~YRX?rb=vm>ji39^9179?D6Bk}G@Inh!N zEE`CdhabZt8;dfhr2k_<7F(2sV3BxAPCTYJcf$82!jM)7EI?q!DVfuX)UjuU)8%I@ zA{Js%aLON=ETJFYw6*T37%)=H0Gg3H)4>s98*^G!Lw!_qTjP2WuET!yyRN<SI6A$>lcw{|}z`F=+`c<|g zP;rxAnY9v%S3V=!;dq`f?n6OaJ=Z_XM|IW~-#L%l_1YPKNUtwo8qkQ-qnxjux!;o! zamX%3c11w8@j|BFK8n)=hoF*fN+t)H5@-GTHY`Nn1MMhVCC=WjZ&o{GmmwP)BwI;- zT~~B@T)JrOky(z+qJYfxg$%E@Z?AjIfKgRx9M2N=H4JJ&<|JG zYY>p%{K|H}^Y2hU(GevdB6IyW8QoD2?7X08V-d9$i@FzW$BvHAHR1HI$mpQC>~v|+ z39)sE4K5aI`ai{%A?8|-*y4+_zf+JmWuC&~BP_07lr~QVS$o)fs`! z2;9CT+m!%(pFry_2y8*1?PVF-1p)Xzf!`2_*owf4%l0}-EKj(1gJF$2>;JA0rza5`K#ZG=2_?-B@_8OP}ZXaC@%XVOHNTVofKudk;NE`}=>a%t@D9%I#;koqb)Z z_Q37z|GV3dd*JrJxHWIc=^jA=dhmHH_NV~ekgm@MS!5}T&#|a*L$(K7{H-j$z@qvM zsns*c#fYAI&FC+&sB^=P6E9=40bM$EmEc zM{nMcbG?ExtwC=rzQ$t94e8lC=)=7Zi--eQH2B?Lz#>;fK9Jofs8~1XgWGQqS^B&5 z>=RVJRw|2wSd_ad2l`Nn29lxre^7b|i@7)bN>8nz5fXIZce*S?#`P^S`YqZ2pP&#` z?~CK_ut>e-cRY3_6Ag2(n_=SZt4DYO=Bik!Ha6QARdbu~E|02TVePcYvbz=Pb>mTW zE6Q1qR@1z^^>|7-;|YO&{b=~Uk?0v0q&G64w_KR&pV+!(-~h`hp`>?ZKND1D5A0{9-Z}}=(jM45 znJ(r)()=)KKKW07n(tmoO`%$iMVUHH$s9rEW1E?cwfO z>pL4Ls`EG`%~{&CCin>JJc&!tYqGa7#@`d3fwx1|@x%W8>MI7($^HT3skddTNqPftEDeK*@LM zrq1qWFR1E=Cfm=`lzFEAS)H_-%d;eX&*J}Y26B+@LG?4^dj>*t2h*QpcPBUg*(ZK8 zpqfBoQk~eh?9((=cL??BG)>hVdP`mN$5AMWmP4K^g{d6$8)p_7Gcq3Zd@$&_Am}-2 zNI(ro^9DV43wlnrpQj9=z`iB#+O*TApKam@*}!?^Dj@??D|ZRl7kR#(Lv_vr$=L1d zGfaQYsrvpWMlcB7>T}vFOm=a zYD+HmqK4MJ6}Yz37`)!}t8e5qHTX<(+%jGJ8m24G*zyIhAy32FvYG!nHnC@w&2s0W zv%W#o^&d6W#BDQ!!C?Kow3$g@&dktzIa^pi#+f6mwx{NZmFw#EwEUS2G1K_GnucJr zG<}p)Vw10TjkHP*Q z2l-(xw%UW5<5~MEuWA{LJ74viHMTFfo1B51-MmwiBc59-V9LyH$`zSao{gE^Y*S{{ zXN5+~sM&f`bEDOi(;QDq_Z{KUvU9fnf_b~hY}pL-#m>=tg|xjKDkWPmwzXmoskq{@ z3UgN{&8w+%8MCJ~MRlP$D%(jDkx9}#bj8;vQ)kwR7SWQ$zEzLyBoC2v}vZ#CDY^(Oq)7U*rAe2lFkJ$V78*8Tu%j&b&TP;DV8#TVBS*rR^% zmF35B=Uj^`O2j)D^7XVNa@CL2TfUZybtW1o|7n|MF2VHXpT3Gq^+B3*;BA?jL%L7B z?K_a8Z;eg$GCnyUtOa|)NpKfLf6nj@=mDmK#b7hY2L-_Rg3(>j8Ki&=umccgF+CspMZfLU^18w zHiLX{5)^{UU*Q4h1(HDqSON0E84!`r;4bK#pGpXMNCP=wFE|N|uN{tRpd%Ov(m)Q_ z1C9g70mi^VE6@W>0-0bl$Oi?$_=bUY5D$_;8dwYVfXg8CAc08bpH?6dOa?2!4sZtC z1rHp;9wdUvU@_PX4uT87@ht%Xv7jRu4!j@-Yy(F@0f_pJ`3(>c`hrOy6Qr)?pFQ9t zCPm+Q}kO5YJd~gQb1<^l{wIJwE z{`pR??s}Se{#$zelSao(wY&m@VP8tZVg1nx_Byc`1OuNaHTZ}yd(D~Z&OfX- zb9F;^@()>Yce20NtGVv+IlJ+^)cT&)C*eIx_x+yhj{^$!A(J*CYL z3{AlOf6&WTDc$pa-&X{+Oj1N!r#1F3P`oGmexUX0;J=|g<;D+1V-5GD@lh-^EK**O zK1YlCQ}<-0vT$ON^MV`*wy1DSwPT3emoE^`;D9C%#O0vFIme2$jY$Te;FRr)NY7se4?n*f5P`$^qLzJ~#s$ zN6C873iJSzKqgpybVJ-6ZR-hrsHWy4-q6bUCjX+pqB%KAC-*D^^AV>QgsURo{HkMf zikV3NkL+LdLhW_m?O*jRnl{V#(OLb;5asCLugcMHtV!obx08CbZ^v(XDNEnMi+XK+ zI;oJ`#$lxbs+K+wUdGq)lD;j}7wR>S~qMpL)$f+m7)rfSVxVM~W`! z2$H~bkOQ`Xy=!xYsC5%TxiZm_u81q!Z$CfhGby#+AN)`KFzjX0)j{W>kX=6O1cv42v zqK#)(ww9!2#J(MIdasVSsV23P_1f|KAbi2j+%0<;BvK?;};)`Gp@BnUl0T@B(v zU*H7`zz%R26oRNjPaiGs_ipIv?O)2vgenMqwKLLPJ)cZ4)U&nOPu*tYJmZiPJ2?e)pt{<|7-n#+XDWxKHycKh zb{=G~F-4j6J*OLz%uml8zaN1v=o!fxWYjFRGRW&N<+VeW?Bcrds0pY&Imoa)syHE} zsw5?Z#yU5K$keAo%Sz|LMuck%QP@&W`VTg0dA6_tP9>1)3qy{xoL#HMR7pYSW|za! z54!@tNML0Bti2}jtTdQll+(_NmS|LhJmZaWRT!UjOvc?ys9M4XIi*^KTm|v0bhjn1 z5AjRpB3Tui2JC@TlFA2_j%Q_AqVc4*QGQD##kUgN{uQLu5Tl_JUO&R9D1C<*QQA4n z&l0gX$pvL`IiiBxQ}%0z80EvRE4A|V2<|26n`lIYg(7fH@V#c_OKh$S_{i4DkxYBo zGX)!E#8CY7;ipuTc|(o59`VbnTnMvsW!Z`s2pFlOJgY`O z{UCZhRfFtQGM$$z!|~fGr17Ft8Jt79)bMF$fsA4*G3q1opAaXQa)({u{$_|B>Bxw zl7bNgJuAp}6^h>^awOUCMUb&mrX>@boR>J0xYtNhXC50110fDomc@DWF^*l^@qJ@e zIX%*-<%Fw_4ftOFMSQ;~he{YVq24bVHO+&5T@_{bSk4&e%t3Zi@S7Qm{q>FIMyM2yCAgy!QU(tvm@4ur7cR1SnuHuaj+8c%D0&xVLrL`1=h-uXeTpiaN?4`( zMd^NyS*d}_ZjRqh<+4iki!v>VTz)Iai7Ha4OER9Lz=w?@VxJJP`qiZ2DBjQd)ryrP z=(r>a6O_j)ikGY?%B1mxDtDAo-t$zDaEK*rEe$RhMU)bP?9_{JNkyrgwb9^`{H@Ar z+tE~2m+Xl38cpDL1UXUV?UEg_gTokh${dZ({eA%zJHytg3TvLS`zFY-N);3*84qQT z2yZM8k0Fvfh~%@?rT-Yp4tz1ictF;VF-k<9Wg})FIW>u+j**jN2+co!bLAPex8t&C z$wp02Jlit^r9{Q~vaF*b(k@GvWaA;{`WiB0f)O}6YoqMLiEAfbAFClZlJOd@JCTCJ z(I633B1-dBisq|>!nSPLED8pCuSmjJyzApP4us;0Y)E1I$y!QH*m7kjohBMhrC==i zgA*0{C`ye-V|!;Hn5slw5njz0>8$K>g6vc}UkTnk&mP8cgn1WX&VN9@A7|7J%UAMp z=p}R$?DA$)Hi%k5mFq82Hj)U7^d&xK7r#YW#yhdtk;1NxOe{Qa1uRHQm1tM(M7t`d z#-eofBoy!-M^wou<8V}?UTucVjUYEF23J)K>X}(=LbW2sq0soTxT!O+1)fcqDTMq} zLcX(>Y)>&7dUpDS1C`1(RYjCxlegj0uGycJYxZa5n*CY1rjoFx=Nuba1F5Gf%WL+dG(=CMgF?g9LVNFuU)rW1J&$jP90&Q zB%UI2U4DLvujh5S{Sx6Q3<|OG@VeBQL^#~+#0^A5<<@oU#K0=8D$-7@hq`6|%e0B?F7QS%U%|)F=<`cE}i&Cx*5xFex^*)6-K7+sy>_LZ1w z>@u9RG7ro!+J&T)4Y5~S1Rs-_>`FC5(dCmO1Yl+nq~m`<_~&49M||OYwtjY?)(B zb&>_!bByMuo#L7!++H~yvCOC(LJHgKiQ|_U&736PE6a@LA=5Cex0?MG`ASA5(WkKt zhJ-FRTBUA2OYa_>0meCpqZ()iI)g+o8DxUhU=KJB9OvmFgBGA07!JH32W$g}!DSF} zfsrZD5ex*=!D5gHj)J=v9M3qSf1^JEI)WrH9pr#*;3Oynl`j$~&Tzm;G6Iq(rVUZqx13KQuO}&SkZ=^n?z6XsF?f zn6-4pW)q@g?+5youdg+(YgNi$CO<((kPOnmVz3$HE7hM$x9>tWOK7f9Iid*)3RrJr z)f{m)r;?CMZTP87v1y@A*IPR|G>Z^_DqrVPr+%tAtj`H1js&2p zT*I>dJC{1V9E)|7N6J`L)@a?pcd_jTnlPNPP-N!{*tPaw*Bm1&H;}VU3GBJma$p0E zzjJyOd)%X!ia&E8C0Ls=>mu-7g7p!HZWGGsF$eVC9wv{vS9F6v~* z$k)oEITpRv${(BQi1hL+Qc+L|`k6gns%|EgyIT#nJat+tVVxeGvDJvRZlF~!z-OXn z6aC+*82N1rY9B#u+&U?>m4+WYbel0%c5F3_lK<6;^K|g=7v-OAMs=;KRR5TqTf2qU zQ2fV6*CJgbe0*wJpsOtFlvEsL+D<+-ANdSV2u8tIVZ=y3X;Z+s)zZ_lz+bTZeiJ~wq{1|Uq;!S?8 zeD*QD)_l6+Dr|wW^SOO38XNjlvH4ua+O*+2zU_GfwaQwU{H*4igZ2~0$l2|D@qR?> znGN@i1qas%@%U2kzOT5zwd8Yh4qph>o zT3?CXMn#QG@YVgyIG{Ppek6DPYczMpf8=Yj$6)S~Xq5QESRSH0wuX$YyPgkzVLZ_F z4DWd873yoy0(1k(APwYzZQwAt3?i;lXM>JlAeaO)K`z(}PF~H5+m*f7sOGxCN4&;3 zskPUr8d76ih&)}w87FCbjn}A#tP#~}`;2JU??}atlO_9%z{%1#WWqj@o@2*dE&pY4 z42y?vVG%#h|BZNV_!u=ZVy(?2*&=AFMNn7+_A0N!vFDgrl@;D_-t&@7ztK@Bf6UFX zmHQd;EGb#)E|-$BVZTvR(vgpXvroQ6MoIKtR zjq**^YbgB6R``|C$a5&jR=u|+<@#5Yvm@5|+Bc+iK9T){ICV>rq4`CvrW>*Wi-rNBsDJYkNIQx6xzxYih~x3 z=TRyl7`>USsZ$P#aE$fwijrvu)P>Ez^JcC+U__`B5dC*k>QZokRI?2t5*&_}{xpq} z#@`r^VKM3(qn>m81lbiIUNLgegcPf#s@lv^vilp}w6M#|_CkNCMm@GTxW`39vyWz;_4v)C7zIFQZ2iR=NY16OyQhc+Ix*n)zP3 z@1AK@CIb!22k?Y)`F10wPx22LQBI2Ci9=LmlsdSgJn$`s@#B2Wzom)jBzvxYhiy-I zGfm%ShmD)g$`gEbj~Gm1dtZ`~-y1_ilz-QT(q@Zo6KcrK?~VE$3VACcuJP7@7N8qQ z1d~A~SPk;Q84$`)YGu$0^Z+R!1FR^>id&>cYNgsy;~pP%U$tXKLq?T-&-`fIc9z|N z%wcdDMA1j74O(5#id(KGHy#gF)i;0RRQ2Wm>rdkBWa*$~l=9Mu#Kfc_%1XUSD(~{J zQ1ZxFb8FUTKo#Hp)~jS4TZ6gxdgGbZtQR)1B%aQ`zem{&!t1gwg1 zNtkCx6kGwO$>FU5mx3RJuU@<7tqU_I;BDal-2`TQ!247x59N4x7A_CJ0Heg)2d1Cu zRn?wSFc~Hg-X$-0YT-D6t%bvW@S)YhGPONSg2>2S8%l8cYV;1 zKr1w|%&Rz>ThC=2m2ooy(qSydzUS>> z(V{BR-^=w0EG`SP9zC4S9Hxrp_tv>RrBvx%jQcbkMZ!IP6ZbIYI||ta)%ODBZ8{dG zke~3I9T)WuA?ILD-U=X(j=?EO{&zCO!&+kUP3aaP^yAkhcGg{iVH|tBm z{ty?hd?*W|AOBD*^Y~sBYW@msvi^OAI4`(p2f;BuVd9XW6J!tL9d|fd^2o^2U(8M= z4Gg$oQcX@fR$%z&FJ|{tm2xU|Tl!PCl}ZWz=Bm*7|6WBV^OE1EcF*@1fKQ``3{Dx) zK54|@7wz|*4POoex5`~WR;8ptBKHNVK4`{03o4-kQ#C)(@cbk(%#{3t;Zf4|lwnj* z;+cR^A;%cMxJoNc#tvm|t{Ph}p=4Nutlm<`n^&ab5HiO*G|aGUt0>!00`eTTpIj;S zkQ8zJAk!lF>|Q=)#MTW&yoo>JEBp~}ja=YwG7*otDjiN6En@BJDc~xQT-{U^&7bNL z2mYqus_#`=i#gVZ0*sj2cMGB(*2B4I@nW~VP6=VDOk(j?tf2)Zf@Iou%g#c^yt47rHn{Qk%EqT z^M560AdB|+_4sq&Qu;c2S_bs=7?&{kMgQr!CGQVQL)qCiw35D(205n4x0_m5H|%oCJ4-li>mI zSU3qD2UG4G)UDoGa0;9QPf$zW*77hB11160^sVE^jl)yFM1#lC1A>0981V0DA0}qCm!eihZcow`2W^NsV{s6uXuYuL)?L%0#zShFk;dO8ecmw<_yb&G%Z-SHH&9IsX-vYk{Z-tk_ zKKMg;8~ho(13us)A$Rg{8iQT%4fs>o#S4-Lmxg!4j0dXQki3oHFW?UFmvB#bFFX?7 z2fqaGhiAeE;J4s!;5G0;csqOuJ^+6U|D==t-|=t>gTwHj@DaF#;c&2+$y*Wr5pD+m z1job2;a>31@DTU}JOTa%o(7+U7r= zg=@pt;D_M?_z9TCmA5;53myXh0Z)McglEBpa5j7!UIqURZ-no```~}zV=&dK_X@1R zsdspA^5Aw;r^01n9c}>A*7UZ9O}IPkhWo?e@MyRs{0bZe&w**qc$dJX;Eix;_*0mh z#k}9Z<>8;;3UDD@k;8Pn5!6zZFsKYyhMU4w;I?p8xEovp9tPKhUxFWi--I881+E3Z z4?hHNf@{P3;rj6Ra0B=X+z|d7ZUlQG7)jN5|Eu!ARFbzL{4m@SZVvZ=AAu9$7Vsqa zQTPqGCHywr23`X{4sU?l!e78~@DFf1_yXJ>z6~>Ge~!wK+D z@F4gUoCrrcGUzFE0Ik3i;7O@>(Wn>Kp2v9g6LbX1TA}s75XbL!pcm*3YJf*U6&ZHX z7%b;58i`tM`Q^>)+J^zvC+ZBE0u`Y8K*=bdM}TL* zW1tg=^`jfC>;rlmTRzJEOGfz$wJ=xuRZNr~72?{Uj{Gw_yj+z!JSyw=fl3D@q9UY3 zM#z^JjhG?-TZmLF8i6k0VW6BUGbO7+p`d(f0#rvUZ3eACXtL$Ut+9l)Z)Fd8z zf){`acnzx$cY_)tgRgnG)#uQxP7$?~>aFti(%&E4BE#(|;0rRq2=DeJie%>W3Kn+xzM|qS4KaQXpIA{w`hU4Jr za64F~MtfOy*{GCS%j%J+zDo^yZB6I}cPDI(34w}y9eT`<(?jm){~gcsz@X>B)^lC* zqoxW0e|Da!(x>vMK~V;*#?J1gX;yDcWdI2+ABMWj)F%m(N_7=>53GJyfl1+MgxhMD zCBUS#mnM(Z4tp1Vmfs)2Jz&0WmOH*umL5JLsy*g?P$e~gW$D*@9FGveC;a@ZpL?Vd z_XjK?)#bmz(@7G@?!9SNPfmrl7C4N#`uh)xRdMMDQyHl%1iYo;fpATjzt?K&U+btk>9VY##a&#GB#3%|K?#%i~5zL{e&zax3AWbYNDYGh-Q{Bg>~!*F{! zf5m7}(nE#kp-S?Qdmcw8DSg#=utIRjA*hZRt9zz7T3Z)a$K{|@CBF)+%9>UDR&VF~ zFfWv4&WmKV{hIoJKMXI!z7_nTEW2vdli22=p(Z_1hZan&RZu5y^#B5!?Vj z25*ETtsVuhl@r--WZ zv>R6C=`&cplmC_3*NjT0-IXko-shM8$}gSom;PFQzGjruAHX3!L~Fr9>2I+MlyYT3 zkI%BG@I#P=N<+H~r#W*U59R85{)# zAoKjo1*WnN{W#(P?0nS3&&zT_NrhsoFTLv+c#!2%1WrGIByntqV0!>iKu zccxi8Fvdfvr|PqZbW6+bqwW~CRaO5ii~*BBnYJk_S|PKEmzlGuK!eZ|2tfi5WpNe? zmln@WrdF5xwJGBe%Q)^P%Vg}ss9o~LO=e9PjdGoTRo34$YDAt7@;y|({>x}25w}=L zy!STqBeiew&jt0A|3r8MdqtP|!daYn%Lp8J;gYOdOh1??e04I@56_!rPzRc(K><&zzach%(fA514_Dsidv7n4%4aUpf>LycUr@()7mM)|js z<-i|B6TL2p{1c0CERIc<=6@P3HJ6N4Mofyi&Q6v^e==8k_Fq9LD~JAKs;aD<+R383 zI#ToS+Dnkt{&A?|N6XcZjh^7f=)!C01)m6tLq9m@YNaetW%csL3@ zwHTmM?i~}7lg1<@T7y!&!;ZCXdtf$TA1Jf`-?89GX-ij845FRwQ|}A>&vywtMcCEU zE3Utds$osNcrI}_LdwWfg=Q(~_BYEBEkgoSQ4;R3d9-hTGjQs(OSb$?Qu`RxN%Gz| z1*YE0z!cad+^RRT z?)p1TR(ejBbf?+QN!dE!G{>2Cna~_P#M&3yH^l7aOq=4{8e+bpnReosD%jRMb*N$19-2cHvl--r%OI4GZ#B>YbOXbI7c2m4 z!5(lN+yqhdXKRCa&=*VsnP4@@1Bbz75c=naxY3%LOz>56n^Qy8G+RyybE?|B5ff!v z8#VSsnSZD?H9I`!ImIhVnbwZ8(x%!*^LlAB6$*(qUx#K!TW);y%b1;O_pJOUl_uy6 zl0h0+3^s#<-~tFOq;dtVKo5`tGC(fa3kpHhZ8~#cAn@MKifgj9jX5z4@2veL8STwh zF4r8gePnK6fltU&=5?dt0^~P?d~g9cXtq=a%|K_62)tkc$i0&lcS645hCTZun!)^UA>gEAXAjl-TH0PL z7(f2J8G%)o7tHqBereFttf}XtYyL(}zWKulT;Q@_-p0oDH8$^TlwCc|s^&XIdb;;U zPhn5=Ot6o4F8_iVVV)?mU#9HwhmrZ#;h_lmJ@mXHBL%D=0;leGNZ!YR>HEok6B(u^fJq73*~wr94zi-wjv_OdZGIp zbbqr+oV`shJqgksB8~rM6@0;e(4{u0D9zeS_Qj@Yz0D|3qs?|eD)Qk{)$B|1L2om# zYJb06?~U?L5uEZL!f=Q%ytYMF{l}~k_SzPe9#&0t zu`cJ7TiZH@-(js>tN)nntLV#VT=uZ~ereqo$KT@k&K4Qk*R1Nfqa6E-jQSG%pCVAx z6SdWLRvhSM>Ui&7{mckYIlrAs!}~(MyC0r^hvzr8%Ef+W)vy~%vbc^dQ%L2WNaarF z(_z`c|Ff#yFAMvlD3f=tsn2@n{7V$oyAxc~p4lKJ2AETwydHA~m?xa`H_GUN)T8fg z^eq}_vgeHAcOU@^ipu&y=C`Juo9duo>zISZgH4V(Aer4m%xveKExzSLR26N9OmoE9 zm1q57=42-U8ND^MqU;%F)_#63Z}f3+6GZ&QAQxx_dVt};3l@M}kPprP$6cC%pc&{4 z62WAU304D6!+*n^>pM7yLM{;_%>z_G)}o$*k)~Q_`1p(FFq_KAju*{mm35Li*e13b zCYjrvv!W#`iIU%Il;s3_WO-Km8S_%iXkWF_Sg2Y!c?=O%4=0n&me$_9wl88II}XLl zc=~wT*oQN=!DI5kL^CaH^ie{38HD~#Y(OmN2nK>lAQP+rJHSD30o(=AjBM5hZ9yWK z3|4?0;0(A6qW@tS5Of3s!SsK8o;D%pw5?Ok=0)56I;Wb=LQ5>hIv4B(Xa32G8<#!Z ztmaxsf$_a0wWgc3oN(9aX4#PMINbZ0Pg$wt?&FHJ8hoWsQ-lJgD3grwA+q#c)~uYF zZl>vXQCZ%hWyQ_T?yIpHb%q)3y2ZZYY0pWm8D`axY0t6R>pgZ3#m+R{r2bhD=J~9$c+hOZQm> z<1gg&9`eeppz!U+Lcfbe^&V^r|Iyh`I;NY^`rnv5j)~f)SV~z3lBx#*B@uR|n|++b zwc?vJRES#tH+kU>JSXYu_xb1Kfcky)Ik}^L<7b-;vt5YgMULLd%5Pf(T7x44F6%1hh7bS^K>GH+_Ptn;*_ayD;Cp6N8C?>q{Z{i&DL^T_M>DMZa1 za664zt5S3B4^kPV=6H|twW!87w+z3f0S&-UwWsY4#6EfcEz)>DzJJj`roP2@`imlm z_QHWbWW!s0$o^0lWXH&bx2Qxf1&N^2@kj8^jeXK-J}SRL<+z42ZoXNo`Z%sCvcpo% z>X^~EDe9mxw!)d>8{Xk#oIl?TT+zHwBHu;{Gb*lS4W;?pW<$?1zY_H|Q=ZP3X`90W zi@f&9P9>j@ry-5x+}nKpLb$C+d8*_U7h3xY&6a-Wh4v-qqq5Bg{twVTS(c5Cb@?deV=4u8}T(>*X9l*<&|7N#Ddiy#PoOqMk*9) zP~^6CVOSX75+1FK-T9>OXk8b^oPm0Lf{#^ls@n)tqi?sxGltGs<^ozAx9u?RTVRIs z-1ztKreZ8Kqs*p$e_P6-rKF>}y;^!Nw1l{~x`IqyXqGa+^9z-gX-a7ALNnUawW%Fo z^)*xh$Mc0|P0xrRW7W{O%~`74Q&4`9S8HuMXZPvlo$42S|&*o5|Ki zWW(Qn`9LG&j@<~kqaq)p-Ldb_yklQVmG};=oPYxrCiFY*sGCu_h4vi^-e|5_QsE4Q z_l}HB3awNnQ6(IS#XIGg(Y!c(D(ral4pI8@kz!-j`m~I>a&56`c)okI*iN+x?nv*& z=93!bVKI?mqSn>&G1rp8+77Nt(VB979WA#9#IqiHP#Ui{D`j)yu-sfn zEs@Dp)?p9f|6O$tPNlHg)}wWgTpmY9Yju?Ca@i~$((cN%(F~|8#%&e8kwvd3x895z zlQ_g0Ls7|j*S=_|a6OSYv(${bPk4OF%htL5iVvK&maC70RmcG|yw=2wMacL~U<)?HcKlV#LTccsoU%aaYsTIsMVmPLYX zGR>xCHtk+UamZ+6r=bd|%AmV)3*$QP`Hhus^@;}jsg_JBarM65mAK_r#QH7&SB$L0 zLPANZG3dLJWlOGGZr1Y*Xj@#;N?W$SEhjV=f{e>s##P>H z72K5(@8NQOyW)6MvP7mSk=*yp%AWP@ZMzycuWs4>{GQp!(=@)=xQ6Z73iBCC`=}LE zV}~ec@A)NU_qS>@#{?~~4Q!wMjEw7BWWI_Q*Ge;R8YFf8N*sSg4VfQs-1s}Shis); z?06?KuJ3UCW4xSOY1R$-F`m(evw9opzRE1^JR2`_J}?8DN%zUes}N_cn5)DSa(We? zv=UDQQZK|)NY=M4XRXn2U~V6!-s*j`1reF>J`RuIaMBa92QC9PJKWc{eXCf4t7K&>o95b(Dtz6G2(3mKz~=YL4ceV-iq5YLa{`I0B)&WE&x;96_V{UJX+86u5d*4`?rlxD9ZDnBCG zn1wJZ#iaESqVnB3K6wEn6=GGL{$qzYlXL2|e`8*7dIltTIb=&^{ZCJUwQG5WUZ&jpZ6Q9cU09#|H$XcxI(8u;jq)`AN!DleG>N( zk@|_CCU%mMAJLFV^h>JnsY=J8P8F{dW>tCifs&;x(`jmLyxK;}Jc77$sho|l@Q70C z{=p&R?D|LfkL8lljFYy&QZDag4{&m>8QPyzDXK)162_+_u|HJ#sOrW4VK;{R4Ea;` zYB)dGepvGOWVKo=h3ZGW$!ZP*FTc$-Yg7!D8|tq{RrQ2@i4A5|74C+9?h0!TIrN&l zT!}OiIF}mX4ypQaC%G5KFe%@i@}-{dY^R~}r-ZHN1htIZ-e888`Z36|q-|Ms1zoaz zGGrque4G@1s*B9oXpYl==6QG*jthB1t1h)SnGqrC*Eery&-j~K$7S{=TJRfqr{;IF z2PFNQ;Z!>~&}u(}FSLb;rRG>9V^=d2UU@S^j?EkRSae@PbJAqJx5Zp;+U-lt(a0Wa z+_BZ{W!lX}%`wP6=PuS~HZ$!eq2_37Z=}WP{VpZ_Fc^VzRXzns{;ifeLY&{RZRs4M6mU&J)%-E&* zr}HrPWohncIsPZ3#{96994%z5!mp&;ZQCMGt+?)d$DCt%teh0wu~q(MmXYMY7zV+` zU)Jz4R7NJ<4H%V?yZ&btD(~Os$UyY6@0mkwXJusaJ#&r!+1KhHh6Ge_3a**aZ})ZY zSDso?Z>71H+d=yT`t-C}#+U1KKkKy3%1HSzw;J_+JS+F+Nggsfcns$_cLKU=x=tYTe5x#(*Z0M8Lc|piLzUns>XYw910DuAhlj~mxxUCt5U5I zS`1UT6SDFYcg66=R#RU!1kmxCyAoQhDd4rQx((%ngvD6`naS>lJPFf_jn!v9QLaD92Jp81oOShC(JE}mC2KNKJWUkcZ^-t^?pmh% z4ck#g(WY|KBKIwnH=~Nosw=a_n`oKDKIaUTwo}~owc|2s3QD-h!u8}El0C&;!}Fxy zfl4RU$Q&xWmxaVg1nV{BssDzR)rN{W)g2>8Q`rt_&9Szc>W=U{?ROSviVcO?f%bF1RPt(= zOtESAI5yS}3!0i9CdX1q?_spnLrRCKbQ~tTr-hX>RTimc)-Y+{wFEkO-8DT`W)!Ec ziX)1Z@e#kVin>blVY0#NuIK4IvshY{oMCdsYelW`G@^EvsAbQTKGWP)L$YUb&g>}H zGydVA<8nwzoI_&!Ot~|S)ZOma6)1(nRpdE#=To{L3#OBzeP_818TgtzR2yzz&!dXd zaJx7S7f-gkT$Kp2zawRm%EcjR{w((wpW&)mSF=v#S;awC(I2iAw?Nr7XLXoW>vFhM zdEH$OuTITyKS^dyd7bc{C%h|X$*R}Mtd)L6#c!y#C@ioS`nc4Yj{F7WL(a((zr^y}^62V!FGbVNdED50za#I2f&fXu7x+!__2RoNwSq6D3YyRGO$#Fw&lW z&+EW3-6QQ|x~=LQm#)Xe0^t7c4zwopbCph72MM{mP}>$(VN97smjDi zSvP|`7S!brZX2eBex^A|uM0TE~XEbJ}JJ8AF^+3jT37HS( z$QLu+HJtE_Gt5 zT)CI#uH}Twrn|?8N7QfU9nn+)H=Y_0-L>RjHg*D#zG4*-ag+J|^hE z^)Yr%S_iK495`?t8CBm}r>*mRN*ChP`!?k-WfruurPz5 z6%e#4^X0P)cVKYhxP;Bd;yM;{=S#!cBoBOFdaqOhoY?F-I$sXVCcTfcKP^x^RrHfp zq+&Gav{ufVI^}VWyOR7r(%uI?=c<4FzpiU`*>%0IY4d+mEyiBD~du?lA=u9H%k4UulMU*w(igO_x(P;kMAB{ zp4a*NKJW8B=XL(P&pGe=pAGg1=koq%h=uPe_y;XCe>@{i-NK4kq>N3dsQBIqrtE%{ z`|xKemlHJSCuq)3aBI9-`z$5#WgCN(Qb`A)D5VLjnGTAn=PspZ@?0+>N?5A>1mm6S z*6W^gNe*9R@DE*NCeG!qVW)Y)@W*csnbYEdk0AKREi$#|;Q{`|!@PNT;3EY7>5I(U z^D1TNWpUuU0RCBvOq1uR&a)O(+^Mvj6ZNBAGKie0V`>>PP83zo?9_9?kawbq9n0^% z`rEZXQ^`K&dG*7Q`|hV6Cb}iSv^+$qnrJegr@5SGuPJ#W&uXF>H;PZ2iSC@pI}4P- zM6>64>hzR_2qt`a$$swF; zZ!(sW&K^s+zbQ*;c7M3TA7esmIHD)qyDC~je3yxD(sJ|9CFp@k%k}z_h4R2yFd-kK zlOjIFB)mXNGetX*QoQ*ook*EenxdUZ>EKRrb(;Gbjw$XZB-}3rPEn0k)Aev!BT886 z#;0G7Ac4f~eymRl_Y~<>%1RB+6{>M%*YFfmtYOMPYem>8Cm=XSsb;>EL#?AmJ+opoP>zjjo08m#a$lnx%P^^ zjuUcB`Lba6G@nDJ&5OkIC-ID3Wrn?o3L0zu%cGK8;q)#R@tF(DdD4ew1f$%hOtKP( z7fJ0@QMxr2E~my%)iN%5Hq|68=N=}$7EY8_ovCKfa<}S%mXux@PV^@^MkHT9V3Uc@7R%#0}FxQeH27k^C=m+*3l z!LOUoi%`q3?aRSNCh;Y@iThp-##}jt=W*Uc5W(Xn>m_n{Tg1k#))dK;l+;f%`Ls%I{E}7EOxDZ9kL}Ck*fdk9K)Kd2dtVM# ziJn&JZnI2zfj9gzmEqe8uJs8se4#a_(+WnEkP+ny<_O%uW8Ia(nr$LTOVS!mL*+w+ zW3H#%AloUhVRw13lE&%o=^l1jja(o+U)T~yhOKX}47QD6M5^C)2)z=F_c8Wt_Db+2 zA0x?+U%~ZzT<M+TglFJD_$wR&S@< zgxpNt)4p8YqBjo|+!OKYmc{OPZnBK@s zfV9VX98~CT(c{IdyETuOS)N+hGyCqT4g147kR8tMPP}JW1nWt{;v3i)9*0-MQ?Lp2 zP(R7;JU>il~%HQxx^U`~VWguVD7Tki(J z4)89R28Y2;a6FVPc$;7s_yOd(=Y0aZmY!TiOKykbvL`~8y{6uRvnZpUP#TS1um+@< zpib)>*ICleGTR6bXc|F)PpyP4*AWqV(sx@+DmmIn5?vmqL?k+jeta7)~+Q_as zS=%AInf2uHxqa1q;a=6;ZppEn53f{4)_OszaILEp_Z{1&ji?M$dz5t71 zA$$)mhg4lp5!?q~hEz$G>9B(qu7uyfSK#-uhv!v(P_;a-K`+&EHKgRb35tX3FekzF z@Orob@+dr|kSz9WggI~%{2P25a(8a{W$<0hFIqE+@@&V<#XUPVm^xbW6Zz6&&-H7g1-cqx$wxl6;==MDWJG7aFsH85Hh}S zV`&7xGPBh46o-WB9K2RSf}jo;{=hu{t4I^{s5C9e)Fz{r{N9oXV?Xjh`c_q z91e!R!h7L=-~;d?d>CGWkHOz%3$HxeKd{&jJwEOfc%eKa`loppVO4k;q9yZCE}kGv zh7PjJuGrzJfy^Wc*&MW zN%bVcC9pB1;CN8a?qLQ^;5(R8;6EX|v+}-$&EZLSy}7tH_L&mY~TdrDvv zmP>dDl-CMwhd06ZVQ07l4uK!SVelh(AKV2Wg#Ut*;BM1>J@r{(o~s}z0#H$o0M%6kVMf;*sShY#UV%zLf541SCGTX-DO^YCyhd1tJ9IpmgPv9RZ7 z80{&f+j}!B4C7$}Og5jC1e?pu)*mIb8t3s8h39|6TJS%x5xfXRLtKKQA%255K~IEk z<@G{oEqqX#rU*C!R)L}+BH;`uH!%}NVJ@)dzrg@zc5xfCA=ur=Y}%0x!FnmRu$08q zhLV^%P!hvoA8tFz!^vxhIo>3d1{(*)xRY;Q&qroLKCSUWT%}E43`Oa^0PDl0P?TaJ zYzbe4onR5{248}=z*peC@Krbxz6SH)>+l)48qSAn;3D`2Tmsj^<#c&G#r$|3i}i3F zEP?W1OX0h46O;%0wh3$u-sfY^@4<~cg7>hNbnk$Y?vJ3Pdnc51vk27P&bS*&g=Q6> z+ihYN2&eg1J5> zCV$+-{nAg&lc{C)^5xwI*=d$H4YGU7-2~2rnw!t`Bl8wuUk8fbiGx!9>%k*19)1lI zVRfp1BghdFp2jc*(%;N$22-HupKIYb>CRur4|+wO7Vt561Dplvh`MbD9nrkanCXb- z(WHCY!Ovg^D9w2%Sk>p@B|3@@rbF5r&&^PF``!xs!k%z2r2m?CAM6e9_uY)*=f`|3 z`a_hMX8?Q^(!tF`S$T%SjgStm9*hHj#C$J23-2@C-wD1MNN^`Z!=I|l$j0?5^5X#* z3&+9c@F93ToB+AF=V90#PKI~GN1?P@Iq*UF7?g6ucy4p>#=x`oDm~qAAGV)~tJKi~ zD0TEn*a-6O!>yyUp)@~F!4B|g*aOZnr#A<$4d?`}S4OaNsj~}km9qaYC}n>Sl(PRZ zl(Jt2rKSB0N{@ISl)8HW4uN07Vek+vg1q!}_qZQ{C75|lnYRfZh3~*`;CA>O+%0n{ zC;0Ih7Q8oc%k+;>%JgaI;aM{|pXZ0ntmirKS2zWJZcc9rKHy_UdB|4EG}8j^eK3Z1 z@8bqon`qj=#;`3E-O~<=21|ptz|OEY>;i9x-QXB_3zTQk1I~gy;X>F8E`_(j<*+w= zNgC_h`SB_iec@ZMKa?9D2;YNzQ_by64~Ac0&V)a}VesGZ9$1C@8V;p0Wx+&vFKhwt zhaKSv*b9z?cfo(aGB3Bt2iV<8!tp}xmiVslPdpUENXqOwv*6v}i!#^!;I?4B2Blcb zgWm}CtirbLSpt$tOm~Z)00%(2ezux<+k!PBrZ1{uzAlT3%YEMsbEE5@{+>rCxxJpR zxt#n-yG6&*{o}jH?x^TfHw*;{O6A}yyKeF2OS1r4#Roy z>qvUMqVenFR-) zv)I>!Z0g8sWZkcE-E%2Q{9ylu`$QyQC(M6h7HuZxd?*Qc8v6XSJ}?5l2dluH&<~~e zR26;#gK$5T@L#}a%m=LbOL!ILLomjqy%#JExD(;rKnLE6_-f?#!&RPV29%0C07^w3 z2(N*6KzX)zL8-t)U^jR-l#0M1Qf}j$1xI4O59Y!9;WKaql*V@?Tm(l!c?{WbInjB> z@IxA3PN8xe-*HfC{zGsZoB(&hhv9xW8J>WTK*|3{A=4k8DewlE1KY!?=H&aq$8vSf z-s@=`K^XpI*j~k!vAKAad!G;G-VKy{Uj*gem%z601t|Ai2xXMT!B}~Bz~yiREP|8Z zOYjM}0!o=%$w66pFY@CREY`q(K&jk^;QR0hyoI!W2M59va0vVX4uz+nD6OC2tI{h0@B_0aFSOZy?akfXkcrzeMj&edF?R$!(hFPo3W1KzPdwcV{U7l99ck^nm(6(Vn-%T-eu~{E(JRUs`xQujuT}09@rNgP>f609PdWcU`4`=_F zcRmWX59o^#ujeUE(_{FNG);psFc-$deAoicfNkItQ0{ytyd4(6;qXZ)Iq)}_10}7G z!KW}w+Jt|z_A+kgBLk?z`xqPCh4eJf?qo(uUb5_@QCotegQpi@G+YX$gHh-PV*CYV z{0AcnFS$l7KPrYs_OUWhP0?qKl8gJ@8v7vkb=} zb1k0lA#*FNh}3grPC|!qw&zEFNX6oWx;&;hJg1;^F@J$l!OCG9_$%xT&%xW_zu_J5 z0%YLtxdh*Vzrmf*8%1jkt3pnnbQ4|<9n62iXqbC-1f6q!G=Txw7FLHh!E7AIi~ z$VkD{64EjEw1Ugv4e&L{8GU)hunpV{+rizi13U&hLSDjpIzf7Cp3X1=c7-vp8%%_^ zKzeVUo>8>3biX{eVL>m-lK~%wcfhG|2wVn-!XlUn=?!`AfgJwt$%19@UU&eGhHTyR zjDfVRp0ThYd=R#R;~}l6n=^8>;v^0S%%fHFJPPN)sZh>RmeS2rhwC zInPo^!ScKeJ!q?cz$my1)`qXcTOr3E=G_k0z~S%>$X&V#;U+w9VV-8q`EUc~8P?2A zRrhSf;#n*3*p^r3`0WJ^P@vyI;V@@F2Vn9)kD5BPMb$ z(+2uN((AchdoJJMO73~ShceH00@j2lp=h@sp|tit!5iVvum?N?MXQy=40s-nga3gO z;YGLsUVAa@uY0ncFMP)K*~)DL9{5(Psr2zg=S z3BkrN8p@n$HFz_OfufwMn}o99V*z~;>h-+n9uAUQ4_C>ocqlDQ0;~%gz$UOEYz-4( zI!uCcn~h;VC>6IqY>HVjm7^-%&PxiMjQLvlJmjQacl6#IF2`CUxP!Sv?4>H^dtwtt?(X`@mX+G zKwr^%`I=YJaHebT$5k53kx*`942*+gq4Xjigp%y>@K!hx_JxyR7JLLg2&cg5a4O7) zkHMKxQu!pDj(Gvhg_7EQ_^I5+41Vm#;t41tyaFhV+uz`E$Qhw|Kf%XgIegj_>^eaIPv&#-w~BfXKa$V}u_WE*mz4sGuleni#vdJ>V2$UtN) zG80*WY(@?sXOK`FFH4Xv$X&=-WG1p4*@)~zP9c1I#gmA1LY_=X6@RpwDkNCD63}*7Ozy6oO6#s9e>cSM$>&syH zkbz5P-j^&8_#KB!Q_S062E&I8TrwANh`o%%?>0`)fUzS+n5>VS@X-L5Oy*Yv{sTV| zIp)c)f{p4&O- z`QqTI;_-LQF|Qq}l&F*9;KgBlj;VgQl0(K}9DF!T%P~_AvzQYuJA7rC9UG0sLj)dH z=9qd%cq}VP(miQa>zJq3N4B%;804{q*D*}ux$Jnf^ra&~K3qqxH8>h<7IA4xgn2U| zGS0-L`}}6i(O@uw>@g2r$D;DNM_I){M!az}I5N=2%?Ph2+8n!&t)MNBv0kLBwQFI@ zBUp4d^jPqki1DQ2`Z6{VEk8zR620|UaJp}0PHCrag0Fe|o}*YrB~Xr$Zpct%3Nja2 zfow+hA*Yb22KYnTA^niC$V_A@vL4ypz{|(4cX=01k4&t33wOG8i_bKj9+}|Vy2bqr z0w*2Fp&$cJP*iTk{p=Pq;{@x&V5d_-HkCAsh&5wR1+Ox>|MUe+UZX1Pygm^Or8L~? zb4zh;yEcRdFqVhz{;_r0(+GPhc?279IRtJLQujQsRo8_|&M zfNVt7uUG8S&G3^BM8uc_r-Jd-pQsdCp2{wdnf^p%FK#pAG?!z8q5oSh=N{;B;B>HN z)jrsGKj4THHWDTl}8UVQ;heXCh_*>94c% zFQ?f{DGb-Q;Y2_|toBQABqgr&kze>uyKmIHr5(zHV|)S4WwzAlC-=7fN^KeYzB%$M z>xlA5t-JNF<+)%?gk;t0IjkxgdM>y+!o3qV-uXl1j`xGoA?JhDBYbssng=fgr}q7h zYHT{>%>(5s$WG5$8|hjz69rGXKcHwl&P6sr>3t?hPmXIy|R%`lu7jSU;K@JK8NCU z=&tXJ|{LdY$bW&=K?<6cTB0~=Y$}8VDesJEw0aa zUuF66HlGs}?ekVrXQs>_QL7G9kq_QCam2V04@&1#o{m&LpDYipxLa?wN`(^Qy3+D#C0Rn`*9CwoWxPJp!Ec^?Ma36c^#GxE0w8Ed@xD z6=9MhojQMU9{t-0kves1{~xBToNGu_WEKTCNFMpn?&BzB zB~a}Sn*<&i+jnbLb!t|xZ|%ZaUBzpjd5jMny5|QRF$Gn*2yaFGGw(ESRCOj+{g&S^ z-O2vwZ4o!yeb3??)<@k)0Hu_4c=-r@);oNIc4?H;((9X>QTlPf;qa@o{YyJJ4qEEj zL8ZQE=QXcSqORuL?tAIZ(m$#>|MXrzmO3D-kQO1Ek$uP+B&rczPNX9;5E+ZiZNx^v zfOlbaY6|n%{?VgMlj>BJ(W4^GJu8CU&GIpUwkY{3eDTL!yLqU(Q?u%Ld_IYfKX35e zVB3v{Oll48l{s*K$tW|Vh7W>Q@POLF=l!kIkL8{6AB!*-fNo) z=PA|)u#1~osWbK96zNWDm7QuX*X1%h&r>H7wNluINQ)Ng}uQf)c>!f<#1<` zG-*{gm_9g1SH5o+pvO7Q<8=F+RK~DY7>IwVkYC?G4`XkAr%QxXzN^-8xWIMsP8S~) z?!kC8fYh&erey5{eh+~zEIqJ zjU&eqzV4#5MvBwNdwn-T4o9XS^O4oaPUI-^J5sX=F(ciOp-o7{1n zO|C=5z}v5L<`cD?zG^O9=hXDyi2HzhO!ekYcsp8KGpIS$q#X`f_n7I;o$!dbt=SXI^M#RQY-B=&vi6HW@yIezB>NoY9*KcZHW$u(JRlIMS zB0hs{MyEP8O=3rX$jnNWLr|{ggK1S-Ih|}Tysb%ZN%~P>{$GZhF)gp?%eH2fIHci_ zlx04x>=2uZLnj=%Wtk4C+;O+8iaVA{zgD+*Y-`1(=T2lixIC2&#B0sUR1$Qkm6PZW zO4gcV*K^)rE7xh>TPSy}SZz(uR%AnGE^ygK>>0>swTM`qB~@|F6=JZAU%>| zy>Q)hwBPPlPK>wM940Q{y@8%evH8novToo$x^S6i?=?@|Q0dNh;ZQXlhn4q6nrr)n z!i`H?)4Vk+@<@{TIL~T z-jbOP;+TFEty)aUlh4m`Z9c$&D9Fx=^SLq`RfHJ9#ZqAde z8wBO1?l9wSbQ=07)XP#L>m}WdwG^G9Fa~DAT5uSYytv2g!h1lAxYx7E)wb#P<60Bf zQLqsl4JGny*a41(#N;72^77%sa3!P=yX!q4G2Poa*9WxxdOgqSOAKz_jg^~sr@49i z=*IE{%p>$nI2S%?Hnnpa`zW@0X+MlHabw4(AfrMwx;GCUBoS+^kom}J z=&ndFyq|KgQm-)OenpYj_Qo>Oq&*`$NrB`b3(rVQ32JC2-GUBXK9$X5?yqh9^42ruazsWw6WiHEDv0eh!;XDyi@@>6o#{5$GdZ0} z*4x%KoUD4Xm#kL9h}fs8kgQ2`H)3A%L`B*~jn^~BI-@n~naiD>rm?qGa+T*_&$Q{{ z^z|m0f-b007F_zzJYnAG;xvjrV|~i4co-v9sn4Nzka*KohD_1sD%YEKL;W${c-_5vh}@4oWBo|W>BDclDelT{-LqL>6OR&K z5x%zBP?BSk$p4p*Xt0O78>x=}TSY=d>DDlnzNC?4V!M-^CL|~8Z}KIL+NK|$$cWCe zf!y}=|N3(pNhaYIV&%sC=l^DIxrLs=`AQLz2tL!5#n->>yt>rGaMReDXPTc^`tdDJ z2cK_Werd3$^SLjeCCST|Z@hn_kNf*=4ku>MES=h$0kCh|lch`gI(z~l>u;rJ`!Vzm z=+(TQ2Xrd^@%~Qh8?R;=a2Mn*WD@c;vI5zR96-(>F)R_j2I+vW5jtE4x|$) zb6i_LHcbYiEa2?}oekdIrfeNE)`^20IpbHpvunlQQ%`cu~*w9 z{mvfK6)*c+*nvakS+gGG$<~kgpiBa<3a-AxY3(EYkUN}(S3ONSRwExEha^2-@4~xC z&rouA@D|hLE~ioKU{*(l>y6~@E;o1WtVKgShI3c6zj~Gz=H9`)d)R%K)7yKF6}Zj` z4y5Lgp&=-w4Lp(keNB@gT73>Hlvq z7jcMXQHg)N4eZJ8F@mk+!<^JBfk)g!;4S!>+nNP2;ID#F@?Mlr8(Ad7~p{{Yi!l+)E*b1#bGQC6NyW`wh}KL-l){%a_1 zzC{DfhEYxvGgl1T2AChk@WH)KOmxJ+ico&DeH5+KtlCUvKB?!-weLbxhe14@x5}Vd1i#uBKnm(H9on)pqZD=b^8@?=*a;0yd-zpbpYK5T8U_Jtz){3 zq>C^>CY3o>gx_XgwY2U0gO+@+tLZfSEUnyggXST6!x)aFB~07)9gw zhjk0LNdwFpVl^?NsbVt+>xHF?Ny9n7q>U!J_#qYPk>@_ZOc3kNm8|8t+pBCG%~eKQ zH@S+;_}HtQ8SQi-<5RQA_-$nTvv->z*$yYJ-d&OLavuXt`jz9Fc8;M$JbZ7(z_14t^xC9Ni9K%UJEy8OL zIU@r%x;owKiPg8)<1f=QZaE&!fYR?Y-Wln8xL@fj^v3Wd*#m3_og@#BLez#y{y$eR<%k^lkvFoP(UAt zd^E%Tw8o*w9Zt|Br+ZCzKJ}4H4RW2fJ~9Q?<79Rx-bY3}BbK9wnd!@`_A)VfP8Hvi z!%A!CIqzMSdo^24+adjsvB*qh5waH9i~N9uu48n8bVG(BQ;@mHMr1E?0f}KvXltZ5 zG8UPMEJfBMyOHmZD(sqwM>-+{kx4DQF`lRSu>#qQ9Bo0vzSz6)IU4r8wLx&J=n@4I-wDz9(e9D$Cfh{Emn7#vPA?xSKtkQ2yL%9KA&RrDd7j_m}(20R`=-7@O0H)ld+i4pA-7rRF2GXnnjmXhNjw&)Vy;`lcx|)WCOb_o};?#`3$@-VOuVUsDa`~tiXqIoTWG@|~Oq2Wq&GJi?tVNk;R-TjG zYgWC$-F?B`6+dP^eF61WZ2gB-_AqzoY!c;Qz+sgR3>@aRfO=ryFq7J%DlbvhPeuzm z7)zIOhr`Uur6ggijk1Zo!(rz5QXVQhu9rA<+{waWaeBW**+y$Bl=<9>xe#( zLX;)?ps_d0L>5u7vrMw0yJAEU*`HXv9G+eV_D(Cptxc zgJvX)Vsg(|2TPl96bn7clFRzb`zWr4)`s!DmYkXuNhORb4_(-vi5m&!TRMn@I zHe1E3*8pim3wk{b^`z-DuQ^>tT|n{1aQ4GBNDpK# zG+*P~P<128+9%0cyznkrjq(Ov0^Z>IAKP5TJhX?-ZpSyAP=srG+1tkqZ^J8tp$nFUrHwKf z#dw>Jx8N2twV2^%kWrVEYEcQmGs~2B57jW6i)lG$wWu00dyB7(IY*hmI)djCyxCUM zYTcDy)+m#MLz6rl)-YI;_&ohNQ69*Phdgx656BIe*K9Sz(yG=qU#`3I+F+E4dy8oE z34L^{>G~GUIDBS3<#lx_t@!%&ym{fc*YMDnoD%;t@Spsy`Qxoh5v8ri;RzhBd)Kt+ z8KNJxo?aG)PQ5YcIre-2)Qs*O;!vrcp^7LkOURjo9QCgGxo0T+&V7^_QG!DO4l~|0 z&ypW> zR*_g~&z~^mrOvG!FWY`2@y;gR`?i^8eL@wbun>o;WmLW5ZK|d0tcaBOu$CH5Oq6%B z!OMqC%TF@$xo#63R!a2LP0mE$XPeE>o4B`qn@zp9on`^bqU)E5SI%TH!{27QCb*?^ z;oH1n4K#C0jF+UjQ&qd)K@Cw#dTk~m%E8vn&Px%=WaFF9@QV2HEl!L)&u6yKtsdoO zg?v2DjW%Yh(>j8uW3GCIN#)^~0%X5?;Y3a3+N~s#4F6**p*17r$ogad;=37n?>dKk zWX7;<&KthsZKm3Gr)%yhs(zJL^hJ@DNDpKdLvJW|fM72iyA?=Xf$oL*n8 zGA@Ust_dFQAbi5YX*x`wm_6^)f@nRfQ1S8|pf16TOK85EujjNjqZyo#Mr{>(DH4^Q6*O~bb%ueSAi3tmyp2XmqAmLltseaI;!sx8F{>4*$O#v`+k<;X^4cUwwMx_tJv>RJ+ee5Y4Nw`r{X3MQJF zyJ?S#v5wefmhE<0#769rdR@`h{`WFe9|z#)l`#u5a1S9l_r<^exOs37ZO;DVURj!- zR=RhO<9<`N?*rc$PyKIP-q#p$?n>3!YUU@CFk3QYz=NS*o+(&b5 zhHF%rb9HRsq}tV{)XGgx*DtE9GX-U&YXg@*chbC3hN3-ZeM)a#eCC>r2kG$TnhA=e zPhC^7n)nozxRtAE-XMQ{6C=mE=JLHEYQ^xMDlSW0M0Plf?|;R7=3Gafq@HWL%kNdhX-R=|pSY$mEOH`TLw}V#}?aWD2>9*VyOzM(sKiyPr(qFb#j7Gp56S z`eA*}Xr$rpLcW=>|4Ju)ohcFjoACeQ8FOU+l{&c2Bz=y<+c-2mYkGZN>8Z~X2R2vw z?>}qauI%9b0*B2wOg(FweZi%to~_7@BoaA8KRVaQ{h9v-*+0V+DN<#zcCz|Wn+ZcB z>qjIo7m$2xUX&P3jEyD`h;>pq2 z$B%yt1?`TYdE>CtB5;TG+kwqI5%$A_2}c~qJ5#?@IGEpN=a;OM2@UpFGt-Ya*V!@N zI#Yav$k@K&KN~b(9$`M@tc^^x2s4MC0x7ke^v$=H*_lBej2j_ z75Nn~_J{WWatq*zKO*4@b7#A75j-MY!$FkygO+A)gR z7d0z_$byIhlitN&!(B36VCEeo(zj}<4+(gc>th!IL$W;nTVUL>)9)LSGAgdZO(y=iW&#;IHmgcY6juqs{p?Ed7sQz(-|$ci!rslX zpUAVF6C*<2Cr$B}5p_VHZ=LY5^XtryB{L2>}hOINR@ne=BcdA5{ggx~PREuBOvugNF**fDr&IQ;s;{P(ILcC<^@d2a1DU}DxJll2u#@*n)f7yg3hIy3ou zuJa*Yuc>F2eShVp+B$Pm95{B(Kfj)tdg4m=W}V46fdf0-{VV> z#>Vog#WO!JbJy+{j7#&pREK{=MtT2cVoz3TPzIeOMVtudKN4@IpRCkw>=1|DID8*( zem+^LrAhq}hdns_5^sk5SSdu2IPh-Se<9xd^GBye#05#?Job}JUme-<$}RNy32$uN z@Q+C_kNiYGU`&E$v=m*@@Uu+D3U-*xy7Iws-z*P9xhOVOoS|Hf&ANBQSiFf&lNM!` zNjimYoMqBZQLSg0%v03oStkF~l{w*cW)F5DI>!D(oP;G0)l3Lgt8Y60apgOM>rD64 zq>Em$|8N8I;Au+qVe6MgEsyXW)6fJyys_=H6BReRQsec|$ot)iD;fLEHpfm=Szm5g zQE?=JvrWR! zm;c2Tr~Sg+f5sK3CfU1h9!qgY4tqy-}h#YrE>GT4@Oiowa+-!WB+C2 zkN}dCPyO}ork$aF&Mjw@kk-h&a>fbo4O?f<D!Mf?4azGyj4Q|Ca~y7KWENI- zI4%xf;LyL3sdlzfJu3?kK64L2s zVBFK}J;&Wg>?-~I924#v{GkI;KKk!pRtr592z@W@y4RC!GM2GFBk!uvOmASa+sF2L zCY!Rjs_Zd|4UPBxc%t;V*w750@7&4K+BHM0Jh}eo(*CtW!+ZhlA$ob+JRu-Yrf#T< zkKSOlxX=+Foxh*sLR};7KkGGrM)M8d-t|K9zNu$R$J7fo2>H4PO*L;-79%tX#oJbx zv5uJ#ODlY+N$4)$*N*2kGnsi9`Rk~lLa zH8dpfsjEi4tetU_ax^v6C7`PHie1N6B#)_~>8(OTeCWw9TM_+ySG6*l*Kk8`zz-U6 z*$wz9saJaGh7i*hXgD{oJ~A0z?z3f^&<{S8RK2#Lwt?@hTfn5g%6!Mzw%jG^=qYhS z>$u@2YIYuKOLmS)D82p0&}-fZ>c8Gk&Gy{S;RdBm+J~O>`syc^zR@AX7MZC@ra{Nh zr-3xLuy{RH^#Y+ZEWgI;zkKwf}3wJB~^0xlvq;of}KJOeUzw|I)#n| zC_rw?>T9I^+Mu16cMf&S{jM$Zx=76%nXy3nA)^sFWOhEX8rh9}heWkwD2lX0`XQqc zIsIiRvL4xooI*nFnbbhKAw!WV$XsM2vKKjrggUT1y#w3XyYXW*l83BCb|M#$n41{$ zA_I{;WD)WKatMj)NJ5Zq$WUYw@-(sn*^C@O&LE*Q5`y$Vh9i$7^O5z)ZsbhbC?e}b zWJo(?I5GuUimXQtA?J{~otgVV?n1^Ri;%U*A>D)5E901Gp3Wor8O?xDKA%j?Zkw^DC67e=c+kbkH>Lw6*31&<6U8 zlWq;w49ve`m(e3s)2zHTbQA9bj@`;tn-aNyg9-KsHS)p#|Hm$$u@))>z-X zD4#IVe;t{Y25ntK-x2}R`|Woto4W-N+(vK1PC zWhf}&`E|;YbIQVJmH8K~{SIZVNyK*2KG7qUk zdNXBewz7GNGUwmQ1@n}1jwz?*D${u{DG@F{s_fZUS^T#0@b}hCgCqXh*l=0AmX*_c zJtIC+567d_!>()9oIgfcwn16I@LnQ_eqNbyNqKRXvJY>>#l5JZ#uH}~GH9mSkDv_` zcdt<<`~z}*&jOo(X_M7q6Ait199N*`X@vODXA#r-lRR+!I(mvD!Dmd8`ooQ3`o z`|ewmk&BcIx+zE4oLZc$=E?R^#%(13C14IkT^O*1Bh7jcRVwxuX`NhdRTiCArdQQ) zSxl9Qd(oH5*{><5ZC9R7QeJGT{=Ik>{}*2j7luT&xV%r<^Q1ERMP(B6DH5Q$Ev(1C zRde_Em4%I!3pyyXXzj)SY2ND#H(AD|t9|CX%Glhs`lC-kJ?^p>NJv!kgeK~~fI2J@ z&AC-MZiI5BEvyG^LN4E=_GxTZ5&shcYA)d&mYCxXD7Pf2dv3vKwb-*mIp;oQ`eEgQ zgUa(k4bc6FnzL-_PQFIXm(!G|8Cl7N66_;NvyZG#w1)3_RNV`CNrS&!PxkFc2ZmOxzbNQAUPKdAgbx$0x<%ZkSLOHL7#?vNV&Dk$1iyEu_ zgec5h-?KPLE!v+|4~0d_T0vzStAGZ@s(DMaGT~n3h{%kdlR2}chsi`*@ zu#aq>jdyZ0TmQY;8Zgt=`@@f^xkL+zC-XTqr&|RzjagWEM44I2J{ij5Ka~rteSx)K zY2%B$PTe!CYG1s8{FjJItZqMSFEqzyW%7J=_hu^l*c>?7M$IX!lyO$~pH9>}J#4G% zVypApTb+OG74?76s{B5=R_71yq5)HE;c0Gl{SK?MCs)&eJ%=b~*HiAd)iKq!ZgXtm zJb%5qFR(f0eMilEtST@2NzJ)Qt@KCp2<0^T2a+RMR(BWLoGG!@FQ<|E+iowE^@Ey^ z|E5f_&Gp5v)y!fVH@;O{l@qL9n5ShS*K_zwbr=-Z*#p#^Y&BRJiE$rMJxy5b8)`m$ zwVGF1?rNa+3oK{b!kAzS+esU4{~7gH{H>7ZfBrqSC~IulL7D1P9<%j)+%z?x{83q8 zRrZ`iYEB-cjI@Pwhb;q{R%K7)PUJ?CW-GI$5ORIb$`NW&ViRzDmYPpi*E>8}UCqfh z0jZAKM;=l8)V|8hYpl7Ga!U{80;_s!9aZy$JCv6@+xp+rM!1+s0!iV@!RldEFJ+Fc zx5dZQyoZ?&@waD*nzPfDmwjsAzKb&1){=5tSOfNklKZItl$&k+kF@Rh@f+1)7c&`h zf#`eG+`gKcYvri9EKzybs@RM5)x7FO<$kMT+efK+@J3}S3r*aFk5}{Y0QoN#7e7<> zv=WvA{t2xQ$Q2DEB zp0>*+{XbhcM)XvNId>|@S(Ulis?12MGLKDGcdt$OeygG{KA`r2x0NMUVZs2sZF*8lysH5*i}0kelHS8i4&TUDB6RcWzRr3YK( zmX&N<=rXK^O_pj;`SS#B*MNal%Hl4{K~^tB-k|0Jt4im+tLE6n$^}jA9sR84l-HD} zw<{+nDKo4_J#Y2MnlxMgz3tV*9D7GeR@I)4(}*`&7Fd?p2;%G=t+9`0lf98P(>1>2 z`Wk-wS8AU2x^nyb*1d7K{@Ii(X|awqjrSrzT+bf0X66jHFo3`AO}Q>>#ty z7P86TsC})&%I&t>z3B@z=i6GAmb=D!w9o9MEd$;qYF}<^!9`n*7C)@^-eJn)cPn!S zD-YhO%(p6bac?zG>!s{@tFqh{*4!QT$70KImg$!HR^cRDu56=-mc3dIqoR82bIl(=F*r@gWUag zfD&hOETy%&U$zM>%vbZcLT? z)3z$tv&uHZ$GWS-j#L}qP35lj%0RJl@)_kI%Y^H!y{$btHUSfC0!nNGifm&RXDda9 zTPaW^r&Be>7j2G>vpJTTuMrp69NJ|Ih@jsf|qT?8Mg3d{iy-=Kc!q{`xTRqskzn?<>GW@tgQqmZ7q@| zIXnfA9AF{bV)aYO8&;9c>7tL|v|pL&br!P&ibXVfD%!TMPEoRQuvzmD7H){w$L%FWNRFr>D9n zk5Z<-W&PW-wf|W)M=n(E%3Yy93U(-aPO=U*qW1O?3_hp!J6=-uv1Mf3L^bcR3N6VN z=3U3sKD$KO-Ike5Tl&l9seSH*w)$h$EM-qy&yPQ(<}BNK?zbJ9>=SCwLUuRj#@TRv zx~h53waW5rWuR1<5UosmUb+26m${yk7u900O-RwJYTmL-ng6JDzf)Oglv%ce)8`{K zubHeIw^q5Ou9k(O=GMGPxvIAEpj+s9{?WEE%CN2Bu5IdJ(@Euo>y;_vl;hq}#x~On zWZQaQY&Gy2tH5$>;Z3sDdRI3M7iSCKv>P#Veb0n{sY4&@kZ#+Eo;K^dziZtWEBDxr z%l^}9o@XzVYU_2$cC{}~QZgIhKB`)uD@%%$W$kQ7CV!_|lz*k{^SZKlfO7Kt%0Z2l z?QgQ?>dM96DO1)d19pg)k*GP;-nJF1Y+JGAR`r+qsIC9e_5$g}>X2r2`!QRXE(e%u+^^3z1G7$ z%1ApFJb8zj_uCnk<0)!BY4u04y>P7;)P9_eXSN+#ZL#sC|Do<>xd-*f`8moF1C`}g z#kN1D<{VpUGpwrJldkr&ZI0#J=JjAbwJ$1ECfn+kVarP7JhfkJuajHWMYFENs@^R& zA?Ke{kC$IouCeX=p1Ep{Wpl0MT&7jcsV}O1s#VQ}QEE=8p`375nOUSv*Rqi7nY~6W zdbU=c@2}it+wu0J)x65upMFctg|<_AI9?OtJ)rhmo>6vRsGPGxx$6UE`oqdit|H_4 z&#@7Yo1qSA7nITSm9t+`Zn2}_Y+Fr}d#QbbEu;w>)V$`rGS#Zu5}RXbR)L+rr0(s- zAJ_M+>TCmcQ}tSaQnZ#r8*Q^4+)#qJlT${lC6q8T}|yH>nI0XbH1%D`&+4f@>ZpHyz-=dQF8ER z>wb?iwJP~9rFg&1s`JCtJkLJ+<2h_&qhB zPgEBFtZZWoWk#-T<)Ry?L!aHs0vlm>8{x@?YJc25`#CMN)Ti05RCc18&)e!a%}x!? z@v42oe{8(v$}MMQy#0Y_GuxPyvX#c#de#u2~*XaeYLV=t+G}pp)kAu+a@Z z$Y`qOJ&rOpO_|(7IXObZXWQD5e5cw^uw^KXN8;B1O+(dT&q`&iozUF%t(sTa1f~9} z<}BOI-c+LI4BI#CX`A8MXVw1r66GLUW-@B1xw&l(Gh?`ac_y1|;mYo!9?Gg~%4gfc zQnFO-k9AdgZ3Od{sd>MBPnZ^~<~AI%An|5(x8b@eCl@KB?^dRKX6yg?chw@tMtIUz zt2ledh0E1_a6p+!^m2hVb(GU=*(i8N-AimjYT1NewvE~0{_4KwE#;nE+luAeRxIs+ zIutykoNY_%pcQJqY)g0HaWzL?P^MXhmGP3A%WY%TW`de`B`MoTp(Ekjvz58W>@z%k zUM(&+QI4=Zo}5u?-ZN6UB|};34`rDx)u%sE^Df(4jaHuCi{x%2b(#^$&= z$Mc_XN*%V_>T%lEf-Sa{n>NV?yi0lT2j#`F$_(4ut&CQ4))3`(pO%fB&(z%9)`o1$ zj1$;%eNSYndXNp1lEP!Q5UmWiepjje!P?3|73FE$?{70+&0B0MHz-BT=ZmcWTFS`A z%4t>st%|hu|FA9n#}=uF)LWIYw$!$JvAfy#g_^`{%Dx!4x2Y_dyoEbSF#=4@q#t#+BV z-@heM6R;^+-H+d-obW68FA*HK1A@U-)MG)o(XoZ5(CYTX_!j?zZ6PhR7cAbO@iY&q z`^6(_-ZMy<-&9#>3-Ji6s>^e2R_AomfFu5HBeFR##}=aO7`0z%HQT&f)O`7h z@AcJu+GhQTu4)e02?;sSTl|;XHXujG3Avu0cEGTzmR>l;YQlroTwoQCy>dUn|O$5~a~-72E(u9@ebZVOeGE$tK5YXt4BYVK|mlygAs zn?I{8v#L2^g__qqtjzqz(k3|bel>5my1(o{YR;JtxxOdiB^$u%?6L`JZf+B_rkR@O zWGj>BDQDaF1gB4{`MkZ*Jj>{5YQK2Aa-MxOJFNSzf7trpr;d6^x25{z7&Y(Ns9g1L zWpYTl#;V}sPpCQnk}~o}xin{sWyO}3i!`C2{hw}ovS zI$E-_c$+e9k+Qvg=5uUcFzze0KmM9>fmOvtHm45TgrwNgKO#r{*)o#rPYLQ~= z|C}T>pKPa$EmwB`PT6OmGS&9^Qfw_cW>vG-r|!jFm3yrJ1-AO`(440I55MiQlSV04 zXD8XLOl|uA(e*X(H6L03zk4N-)V;TYgoF^9XuLLWH@QJHG*M9$6^+(QZgOv$XcD1` zCT&P!QIsw%Jy0~GK3EisrArr06h*PL(Z&A1Gw0lhKL6)_K40J8%sDf2 zX6DS9`OS@lD{#NdZ2F%0QWEolSbg`)2*5zi#P6h4RbQ}i;%{Ew4k_HK#U zZRL`wMts37F?+tm?Ada>e)O0tx*!LN12V*eM{xeg7n!XRz!H{mdX+5W_?~F&_|lN`FpQN(f&*kkf}`WCqA;SSV94;33QB%5pwom-Qbq zl?9gqnAfB;`^l!{yv1qvpO~%kg~Sr^34aO2y(AQyd|B@RTvs{oLJ7qWBoy!PWBJkP zvi=iKaK?NokX9>ciGbcYoQ~SUoG+o-UqbW!k3?UbxKcu~`URcJfPgaQCBHE5p2vJ) zImTZp%$Cr*WE`jSzhxdC&RioQc%;nT@U5I*d7t^FIMr0S6-$!_(1bSEwi6kyinHnLJ7gnuULL`EVFkq^ZY~13%4<^IwR>e%u&KY zIz(gsNA709`fkkr=a}(-6tr*T?qSYf!0audcd&%q9cwv%)jsAOq09$lil)jJ5ep^c zTK|jXi# z&vMhN%y+_=NA{5QKko0GF<&gdwvp41W-%vthW-ssFS*LRSN4kG&v1IZd@*sUp`<0U zR!U^O;MuGsq}vgZ*LUF3La)VKMk@J_!Vf9f2r{})NJRp_%!8PUt z3FY3xv&GQa;#0-#asQ!)68{lEbB(OuyBPp$y|PV2R{t|7qfF2^He|PUT-q{&0tRa9dni3`OKF1F!A@C ze`gDG7uhRze9P%a^O(cMz_epJU2fbI%TCBL>LvW>5f{jf=P7bu;q<~*%w4`=o><20 z{R{IN*)5BOtHiKPJz0KE0#k~r|rSsIef=)xo}aG{df|25`R8L^P@oOXZ2 zocj;v9UfniTeM5!jESUq^r<_mI~J&mDJ`S^do zn(bnMX#l6^XE1je!n{iKugM4{EaCj4otZCWF$ai#<)1m7Q2rA?ESG&c1 z1Jck)DVQR>W)sUxbX zyGFiP93Tak%aHo-WxWng=0jtck4og5A^LMA;?>A9&RxNJDKF`cmK&$#=+##4=@Noj z;m-dsU&~>>APw*C!6W1+SF}~K?mH}Hy>o9cpO9sE=%1XfJjuL6>bs+T3-dotxH_e+HdL%#Sc=Qa**H2-tYApKCGEbFNu*rwh^BZ#c6B3FOn@G87%n5N|v~N`Y zku$vSGN1SZ^K9XuW1LQqSG7a2T=7Jix)534b7e%Ffh=F%l*^?}XCBa&*;@==GDz0{ zgY_(U(2qG$PAsV@oSrz7dD9kVe_6+g^ErJ=s=n5 z|Eq3uftvp?m+IJz%cZNFejuSaTtah|@D3TVRbqhO3#?x?mN`Y@Lx6YW zUv0fkvtW~i)WkiUPLq4TiEncHnmARZ#P;P9+lwW(FBc~>RkHqIOs@$TevY|PoO7at z^fl!Y$rhesg-!BCGvlVDB@#{)!-~6b{(W(_qq{_}7xSHE%mH!~a~E^ESVA}kLK}48 z9p>_*ZTKNX-eOav;Cv~#N(!Q*y5IvTxI+wiu!r*pY-FA- zOxSB@;W};Px!f zmsMhyNSPv=l6@G)Um1`lF9;!0z(0@kFTBlcjby$iQ)3F{bcnp;4ff^q-XP|wr9w1tk>lt^XyE`R4~6tWKH4|JW!W4MXDfY`3tZdEyyOP+#GcH<<&9~*G`QCj zA0)zU>c&%%FPqaU*_=}T#^n<$m`fMS`VR``jJ+~+iT~zwv20FDCUg3<#PGx@PJ54K zzAx+lK^3Rx&t%>$7Z%qBa{5sbbGXzS<+=ZhDrSNAKISy3V2AW{$2qA$Li2;qIX%Ol z*^Bg zbLJ|kARt@xB?4ZM2zX&O=Z_3z4!4Qk80J!mfaRP1$r*z`V-Au_qYiTF9l2NJ;v*wl zb2?m(XyM{3x%WB$j@+26myV>o!ufk8RQrW<`Y4}(%8he=+{3DoESM{i&?(38H4+KO zNhC~=AxxA=SgMwh8X;MZx$8NdCVRlR(VXrekuX(WYW99=KLJiYkPR|u*TO|?HB&%r2M=T#Hku+Z-Y2pZ3|A)leizSq{mD{Wi za#l+dr}CCL9M6$tfeT>M=KzAm{$0vMTcB8<26|uspGhd4OHc|7r6$Bm64! zX|cHGube(0k-z5Wtq13+05spLwCeS%I6ocAhjp+ zn*U~YOMwou-R3{X`6=R@hooE=>A?MSED!Kue)J#a`?8D=$a{f*5a-)@bz%L7aK>zz z>q8Qob7jt*(!eT_pXQ4LV~wy|-i8x|OJ#Y@xWV^LO<>UUzdNm&Bm7A3)*|e%!uzZvF(tRvv zef}Tr!xjzb#R{g?%!ec%q#clgpG&^XtzC9a_ejpSiuVuB;&hEn!D*S2Yoh0t5Wl3S zod3s3j9)G>{?Qq(pjcvjS^%flOJIqTiUOpeRii~;rY>Jjxf7>x{^{qL=SxR7HQ@Ax zXVHH(7xqx*0}EJi)WYoVWWM$%<~#D9a7TJ{PNptsI?H$b$Q;s~d7&8o=s2ezNyt7b zQ@q>r9~q~nutK85Y|q8yR5{s9oWt@5GEzZdY_RDa&bN8_cS}z%Ok};mVa#o%okWQv z%a7>%a$|s%6)t@u9LJn0>)x)G38pA~ICF~J|DCwb>3lh6n@)0ieL3?E39+ROIXyu1 zI=sp0g?bf0xvfN~OMhd5RYK}=Iqmk6^?(0EmZ$!adHqYwrLrpg|C`eTzGgmsNc0vl zr-;+dkSQ!xX|!(yiRE{sXV-q=0*U*WM=oWycVfOHBW6nGshca2FGPIkf=o%e|SuMTA>5ybu|CLpovBbeVQhGe`FsH*ynAb}MmwY+BLn;oJO=;Ci&YzpgT>6Ol zKsxgbo^!)nLh$ZBvj4AH#|jU=WWFSd1DbOW^Sg7t^=0N7iGXg=yCBPIi5JT&B?9_O z1RVJ(=MP`SoF=>DdKboDIoFbn%-*+|&&l@a-G|cyWbQ-aIlW36^p<5dS5`}9Hp?e& zW=@ntX#Q+YACME(p`KDtxdf7`Wt=hlFUdf;7eA8xfKi-(;YF@!qJ&a^c~7W1 z&GMtaW4x94`)HK#QyoRt1Xe;>ck0_-xos@ z|G;VYo6Nbg3VO+=k~W$1Ppo0y`xW!lYs@Li>0n^xOU&gX<@!BD0?ph&7F_dZ-Ye;# zFF9?J$QLx2(`ntg$BD8xq~7BEsS=Q;dP2B^^OuWZiM+Sq|NoS*z}=7esFS&75cA;f z%--#ocgSh>=2=d!l1;|ijnflbGbc*mGQG{|M{Ajv3$M}jVp!*wv7o9Eb6X6L8lt0{ znJ~B@(WhjeN9k_`k>sZRHN9vKOZx z^kfc@Q}MzvoK6$(-4V>`-TRn_i@`HQ?)^FE+j}$5ctO(lnAIO!((6BE6lb(e;<@Z4 zu{~8{d%nbW?()4SV>FL)y0G|rFu2eaQd%x;M{cQ(oXe@B+tT#3~W zn)d1J-eeUs~Q>d5NUAY zaaJsrm~9ttUnB8hjd=Be8PaefvwuEwTiKLyBX~rX_;LOvarSHCtTpAIi9pV9bN|Na zUJ`=S#LJ7Nph@2Ky2zAOIaq(a$U|hcr2dEVk4gwWaD~$$q0Cjsn9D=n=LeI#-Ojko z>HBikvRC$i6xjo6WMn2vNS!DrphPiXq!?ED1=lk}eg@2ahSNdsFz0i-<;Esa3^~Yx z4id?Z+BiL1BIE&aw&B+~|ENUB+>@LRk*N$2->^%^hD(D>-ekQhIjs8Yc2H>WDHgb; zC*ji5J92w{RF=zN**tQ`vcB^rp4)2@fZ9q3KPq0o@H^I`UF#>Y5ZxpKs z6$fN@OO-h~I+F7*$@g|syK>qtbACrQqf3W5zv^A)k>W!OrThso(4Efm3kl4dTFd(P zJIWa~X6{j2S)cditT!W!<>9hDhe)KX`HAxr)0pr4i}|MKU9StLt#0NAe`cO5<$8I( z|Jyy21>+==*=49oWnJIQX1TvaxYH6Tt#UEBN({S?aa1FD^BLA3;E9|v!r>!0f23S; zkL-;2rwVv~#e$44eHRZiwduQJb-Q}Fs2PT!Z%n$VQfH^sZ}NQAsFi}MpD zZaBpm*KlMlH=G+-!6~8joD>WX;C!nXHuyfLNB)_)QZ5|UO9Zvb$ZRTPd77l}dtSM| zf8zP6NcdOU;}=^*_vh;?;AnaM~^UrN=m(CIQD!cFzEb53A&? z=Pi+S+*a048~|49zl-!_>Qxq$O2AkpL$+ih=kI94&RQcq%zd8ob0vc29^~}k@yvTA za{5VN3XxUiEywXFL{9iWz9fbfii>|_&R@%X;2Y-UEt!x0oB57}&8tbZWhJzTbLXG1P`Lf$b~HREzibVS7b&z{N(HEGN<{)_p*6y~-v*J)z8=~vF5 zFX^CRoWAB{-YXGuoJ7bDa>e5<5wgPvtheMJU`(&^$kUL-2|dSP5(dY61N13nLaN1LgtCfOWurZ^ZTEcsLK>FBchMKps#6OaYDnXMt+qHt-Ng zhMx=qihv4WBd`lN2%G{g0ylsNUo;A&11_Kpmz^0~Q0T zfrmgSR!?WZ0Sp30069PrPyw6*ys$7D1Ff1Ft&Ipg!~#jcbYMHMA2<%2r@3ERnwJm7 z5o0m12WS?A0RsjB8-ZQGLEr|^7~4mGpb#hnwgdYCqa_9h*aAERd|SajAQ>10i~wc< z3xHEVE#QSMDhcQx0v}Ds!*pOCungD^><5km=z`G$C;|2WX93?fFcb&{Is?hT2p|V2 z0xE!mfLAC67AOPe0n31Oz;?iBivb3Dv@M4(;bAC{0c-)Pf!n}Cz_%S514aNjKoL*@ z>;et~r+`|(>p6@N5CJ3s{efk`I$%3+4=}>uPCyGF66gW+Eyq7Yfec_Vuo^fE+y)*3 z&BD=BzyS;bMgX&b1;8%g6mStpYLBS_%7A&mc_8e0Gy?Pmh5~uO6ksv18aNA-H;X_6 zKn^eqSOBa9HUhhVRvpkQzy%ZnWx#Y`94)0g)ZiAdm-?00%q4IN%0Q3wU+L zlmITE5Lnk4^S>Pr`+?)YdBEs`VFFqJkw6ciFEA9?0_*`E0?oR@aG*2b00sdIfP=sd zpcZKS0;U2;2V6iQPzKBcwgdZL!2F-b!&ShDL?gfy;0SOQcnCC$LPLN9NCrj#IY0$4 z3s?Yb1a<+nfLAmY9gq&VfOWuj;5={-Fk;X-APmSW$3KgK)xZ{D4{!wVjYY#iD9{-g z0Tclhz${<^uo3XGqnAJ{AOdg!^MLKZe&9F|7Kgq8J%9|L1lR)X0m_fypR+(Ua2p7X zM^AxdAP1NQtOPa!yMTj$7mk{-Kz|?|Z~^Op^T0ho{T-veKnXAfm;)>Zwg7v8Bfwdp zIsxX2d)D50HZe= z0_FgVfg`{}!1pCI0)zsc0SAx_tOPa!yMS82D;Wa`v;ty*Bp@A_2OI~^16PyF(HI_# z6f_280C_+OFa0agQBfIUDpa2t3C_@<(9pffNC$N`Fg1;7oUaX$<#-~tMP z>A*Z-8L*Bv?X$EjFL?!h0~P~&fFrb9S^*KjbYLE^3^)&51?~aHV7M~S0tg$78SjCIDZm_HF;ETM1|9;w zLtqFH3KRhwfnC5U;3DAl8X5#5fLI_2=nuGn?ZAG(7>dS#Fd!1>0rUkjfH^9$7+4K# z0jh!9z(c?{4UGfmhrx27$LlZ@m;>wqj?mowmRHKB4@XCVWx#geI1u>;)PcUh6krap z7+4MXzKLpqP@ps50Fr?UU?s2-I0&2qE&{P5;I%*@PzG!V_5;U(t0ORj_wZnhL??kB zz#L#Pa2B`?JOq44p-~_dZ~%jV5kL`80W1Jk0tbOpK;zLESRfs60cF54U>&d>*bi7T z&}K$CMivhlKps#6ECyBsTYx>l5#TIP4Lk&zIbjIU8E^o}z#w23a1b~JcxA!}pcN1S z!~#h`I^Y5dfihrvIsUl{+yg9Gum~6mWB?_=9AGi98aNA71Gj-eE{p(>0~7%pfnC5s z;37~9c)4K&&6vzRJfC``%@XA5sKr0{uhz0rs>3|C;1or1({?Fr~MJ|j0`T|3N44?#<0?Yvx z1ABlYz*(RgcnJ88fdN1fPyx&W761oUF-*biI&d>*bf{B&I4D0dw}siIs>!-!hlGi2hbN73M>Xz16zP<;C2rFc?g7- zVV;3xU<6PEQ~(EoQ@}-_7KojQ(E!qcLZA$o4y*&V1N(vVz*XQLU`&ERKnC48Y-v;8 z8U1wt3sk>>i@*)Qs{(xmB7j&R2}lQAKp{{DOb6xx%Yb#jc3?kn955=;4A26|0P=tm zU<$Ap*aGaSH0bw#wfL2XPR1+%4xk8_1uOt|0jGeAfYx0!ctR-~tMPGT=CH z6^NXIK?eE)LxBt+57+}70nP%|fMY7gcdAif48p?*paQr7q)$V|KpC(fI1Zc#?g7RJ zs1(QmN`O7U5#Tn^Y&s?m=nOc3LBI%L0k9F+1=P~=BRCo-%|Q4A<^juqb-+Eqn2A9H zB7q*jP#^;+0j2jV0O~ z8%dKiN6}`@(c7+kW9ee{Q!Ze9;%!uHYjx66Ycj{iP~a&`S95GE_0epn37Vbs`6)|J zb5{JeE2r=`v(1hKdgCnGanj7Q_zSj~^z~V7!(EkfQP*>pmtn(%bCwqxXRG^+aDUa3 z7m!8k?^)Zl%)+}_WMpJ~eDo9XZ6!9|p+DcV27P+p>J?O{6!S!Bgh|yAa=(5Zu}{QD zlo)lixo-`kLR8YFt`fVtWnx2mn3Yy)L2i-yTf-f+aXOFo?z1*6Z`?qMUvn1~7uJb6 zPmGRN#ki^>t^4kHXW{55N92?0IA8P~>JQbj{`n{Rxz)IMOki1L0gp_=6MK^} za#=X7U@NLq<~(V@`9wF#Tj>tX&8ycp&J*3tC&sk$fi5lo+1fl+KYAu5>q&LHl#20E z-q?5Cbxm`gROfm!7NHGQb*5jeO}ptwPj%>|XXK|V6{Blb(b(~I)p4Fwmrb9agXd<^ zw~Ab3`xcJnrf%QD+p=lQxA0DTBrVb$MTft|UnI9jlldPiKZc_Jfxmhi6-A>oN7GD| z9~DD8HOJC*&2|btk7W@RM*}s-)8zB0-a(tsqp<|~PLY$IxnPN*4*#??qP`a_9bnRU zWWc1)6}jo#3zipQQt)>$Av%(VXpW+p-&qElqoe6t%`w#RpO&ZwaglZ!^-oI&JjBsV zeu$^7|3pO&y8cfX>58Y|i@Nnb7qu-DIJM#;bewcXr83EU38^fKyJU%nAq6VsrWKd; z*qpqCKDi^w=Q65uM^W5mm5!z{nqz3G&X1*ImtnBmPCnl&j-#HM<7vY8+M2cBqwWN{ ztjI~h)p~gktJdw#tX7uB(#~oObF`hVsC0B31=gti1nN_xhTlo!YfyDu6s@g6v1t0P zMjL3mqO>Ea=M_~tipJ=4G%dPfIc9cb(U>1Bao+e6$_ScYX=@sypV)<>oLE`yWCd+h z8f5*+(q^!J6fbii(0CSEDAsq7@v^&U(Ae=s1D*M9oN7FajAh!}qMT8N(O#%{ko3>un!*=T`dhU#*_Sev5 zCk?xX+)VmNQ5Joz$VHE@p`@F7UbnnR*RI38reC*&nd2jA!*xqHb9@wCzm9>*jG^Ek zF?_K!@JF<3r}uuuusNgYbImbyQf0@|W0rQj0o^znbp!3j(?=@hpnW&AQNMyL2oav) z8ARi5T3S;2O^X%AW#5FG=iY)HD{sQhU33f?u+Mx8`9VJ-Kk1ew!kigNV{XBtGNWjz z=4d*3%hJhOFSa%Frky|GFRFL`35EWC+hR4B_|UDNEbT(n*Du|9Bx7S>iDxdu5DvQ2 z@d4)M_;p4chjo@m6|u@QKgYFd*+6s4I#r$JQAN!1s8;x@T06gLZrRRLtIqPMB4l|C zi1ec?w=M00BmL?bh zVXCu(^>`1+tT*fGOQ8R&JciLz{x$t=kr)u4319F`fco~RyYau;_Y~CMF4Y-c&zF;% z(XZ&389eH~CD42?khtSbg zS&`RU3uR%dPS0HDxU=3?^{bh7*4fKCGSBtuz8yxbf3~z9sJ;R6Ootr~;<5L3dzGK2 z-Kf7a)16mu>{!P3*x?i&dlx@XGf`(h_03ORomf+zHBs9^*VkwPnU+Gx$eeW?jkI;`pca2rAs(idQ947 zr*5^D;NV@loXFwTp5;3wjtXiKcBa6_y7u7B9(yX{X+tgIdj)K)lfw-?_S{qXbSc}~ zG(p8G_b~F8=RoXK^q!aU&4{*ZUZZ}Y8(>1z}Q~LYmTMOn(cJg%i4)@ zeXNZr!rK~--Fu)nif7U^MOpNfw^g0~?s{9hV|VQ81HysS$J$lx_lq>+KtA37dur?_X(aBLin(Hu`pH9P3!GfJL7wnmDb)K4=y z)d==y(Y{8o$3?$3LZxo%Xn{T1G|B>_amxPGf;#Q!lm*7)l>MvDN2jbR9ZQ*3CAZV3 zn&arO=6HIns-%8gkLTKyBV#McLG@xf;Gm8m1X<8k(c&E6p)c`sw6trX*iJ(<$I)cX znY6iu^^DmONi&1s|M1bnL1@HDKL^47OzId6%A!$y!eHks=TB1gDqi0Lq zjcxC>v<@*Tw?5X&`X9)Tg{Z;Ct4C{XZ=9lR%5JUfKxZ^Z(bp%K`Ndy z6*=hRHkkbcI;_Y^=1^p2Qgo;`DH}w7ZLtJahFZJ8s*|DGRi0^!R$*0d%~AATTay^u7GGp7}^dC zL)!^7Bup2bsVIi_h3TR{hoMV$iVjE0LD`DndEv;!o13CcYSJE*MFSPNXl8q;VCEEI z;uOVF`{ywqnKa~it@)867adlaZuuvJiZe&95hN1 zE`t;~X=^7`nMv0bWl`(S7!nr^ROH?^sk1e>iP_FKdL^5kqmklm^0|W;-nf zQ{QB0oYxxh4S=}1q8orjia-vsA$B?*3N2y%~Uyk z`yuCu&Ox+(S?SuTYhT52l&LwMKGp1?!xa+Uc5lI)W$IU>;~ymms|dT6@y=!KiE2K-86m zJ!2s1%8I5YuPR1l(;Q1HUPYZ*mYnTyST&zHjio4%x zh7$}`>3Hg=*+G*vV+6po{dJUlIMf<4 zv~lB%ji)uEG4IVrA`H5y_ef*}WgugU%E+e8BjFhz zWLT|qZ=|(TgZRiOYB$Pi$3rx|!4EO?F+ar8VLZ?mPH0<3YwbAdHd<@P(|CS>EARvE zqWA%~Q5jkXF){-KpG7kjVVhKhjW`3tl1*_=jA2wHjdx;haTmB&b2MFcA^_knut}z3 zj0c!7?G%WI-}V^&t$2ZaIKYvV*sMq_$(Exu!6GCP#k@ig{?lG z+PN?dIB+ORpcO87rjxF#6gE{i2sc}bT(s7$&jz>LP=TGiifozlGKlVyWj_i0C+Jz6CWL4OYB`Vlh#4@-0kf3>H`pip9iGpB$AROA~TXEXGco zRXP(?u6t`kSU=3)@Bn~cFOfZmKj?O47m z#vnI=z8#}hX$-Y~TQOqE+ZX{SEqz;Q;TWTmnG~D{lZSH6b5n%dP5OTmIWvjN5={w^(@pQJ*iNS^gfl!Ci6JdjeV-O<|vvx4sAQ|4}qX-w- zMQUOr>ANB|kx>*}tkTgmL~{(yEQVSveO-(y?DV)8UJ*xqCLj|R(i5z&pv_|wkeNV% z@9H)OD#FqIUGxgKiHcn0Q(}D;Z4N7eESo+mLD#Su?JL3HJEO>_6tkX{xh<~L`mIUb z4mWup#vnosd>@k(O_Se8B{;_*MZ?RijXo{In~$B^mq8jwZC)EXPpC(x`Ie$mC7VrB~qC8 zN~BygL8aXEc_nJgrpuKG7cr68nkQQm@eoCCOxDeRI$8Jnj7r5)liwkQ{d=1g(@l^B#(I;*i zbfc+2Q4D=P4Mk$<$~5TOsoe*dqy#5re}LRL`uqa~@Ptgd^?{Bn(bF;a4tj4o#sG(s z=_rD@G9C3~Qo9*&k1Q&f0TmZ*Rph3}Gthawh|EOGxMt7RjJPrr6(Fq4M6EdNeh4Le zz4xKEVDg8k4%?8Tc)I%`?7${83o`6Mim(OELh(%cZWaRmjMp&HqMtuYWqiL<882VWeBJS^Dr=4d0UJvv!m5QgpIUpQg=U88% zpt-1j%N%$F;?^A9)8M%v#1ut1H_wGJZu)92>dU5QK1O5sa`O$%aITNhH+=K*v2L{e zC#X1<3O+$5PM)7&AtYqcu}}2*_}5Q#ue#0yWl`olJ(DZup@f^R&(q@=JYOwayl%}` zvlK;(=3{2De7~KqrYVNneX1B|Tg?c#nh{7pRr>MNlh92ZDG1gi&@q*AQj-OsOd7TT zEoISCm2%PL1!&$)?H1~x9JNp_T?G1tXb(&H@)=0E6Jy`@q()hq_Vj}*CRgCaNG zTCDBpxCH&jxiVXG6s^#VNUa&)PApaOSQ@6;P9HCY-I;N8MyKPc$sbXhgNFPOGl%yQ zmBMDAD3hL92Fjv-iZH8++;n)EI%KSX3s{!pB%T#Xam!WoilS`I(e&wZ3Rny><0$6<2q3QVhmzEgy^_|HI2>hqa)s7Z?OZTV-I0elzp8D<9u$(5K0 zM9-Dz0uGWVS7K^$kPKd>IGQq7!O`$~zIhdf6vxQBn(@N-IqY-c82>qj0>{XupTnNm zOgi(q^#z)tzBz3C1uku}Df$bm`VtU>`GqwB4;W2;z;J${>)2*nZQW8tW}Q z#BSU7C+lNxvmoxD`_xN7-A^cbK^q4vx)5r4q~DR$w_ z`%CL#v%^KvyD$$p8;#io^Kdp=s?)e7+yyZYj?Bz@C_gUKqd*S=JIyt^T@W{9L zQa0q_Tk6Tx&s2EiE_?~s(RiuvE2GD|C(x!t-T`#%-xi+;&gWjM|F6(dzLQa3+STb7 z<>t|*$9_#|^f`;)b1ae~_)fsn#i95fuOohn&YAT#y*cl9sA)7i~nK`r)%oz$X^f}u-!w171w${6tS%; za?>-*t=I86i|KsqyiTb~2gwfHFFd;KKU@}PKexQ{;PFZ1FAk{X-qlC zu%+OYaoRDglk7P9>KIh;%6RJ-3OcCuH=qO>sK|*QG138Kt4d|jm2cp@E^2oibwlMi zD!^Ve?YLImdK~uPt@b#UozqF}Pav5^Z=6sYpNp1i#@qD?T}A7Ykh*EeNfgbd$tPg~ z`mp&VYD9>>t~r|8{Y}+{yX(KH{22NaOgX0!fzJL-y}{e*nNx^Sh?)IP!A{(Yo^!g-fD%}J-^pSm6_jTC&BUiyat;S?k;Pzi5qIPiPvkOf>*99nE0R{F!4jL@ZA(L(CmgQP{!TV6*Pn6 zckmC2aq8EMWB(5-pvBOJAJ9T9T~=hLz^kA*>Zd54CMm+t#9Y-g_}x`hh=_O%lt}}x z>5-Xq4Jt0$tTJ(KQmJfeeI0w99edpneu$!J*Rko@aS^cZI(na#O?R(bJ0JsZdq1Lb zd@1px9`9*Cq5|CUs7(AI+mE^@fj4xm{cc#hG>Ap5@7+N4vDiU3a1M4*euyF4O%y~_ zzX@{?)Ni6Z!thN@djbwwH_=7{wZ4V3hLc9!Lamwf@h#nteYf-sKfVR?67b#5PY~j2 zT9Jc3{Ry?YY2Q!K$)?9YsfokRds{J%Cb!ju;%IUk{^!Ojx(#ip-NpdpHMip(#Zfd& zGY0++)bX0T8B7b3;GQ?`;H(pm!N03C)vH6%BGKh zMx{7WfBmzyBh@y7c@KZa-W7}W^$Tjj&j$|t1seF_oynT<4*d(v#a4Vpr(-F&7Omq) zgND?i`Z$_a3o))1x7K1#>~yOZZO2jT2ik;z571~Fz4t&5_Xd@6(6lvBwZ?uR*!G?dMDV#~Z(;Q8gTQl>|32W~FJT zk2K>|&TPY-2Hxe&XvIP88lXwU-v-b||0Xq1ZQ~13kdwY^02^?>?FA!n7+2(?Ns4f} z?FALQLVKZle6wToMg<6-J-u!E!1e%yhN{6Im}?kJ=D-R&=yET0&G13^NrhDjGqDrs~TF|g~Esqwh-DIU`q&G zWhCLJo7Cq9ews?vke>dru3=c0Xi!Jk_iS@?;7g+#$2;{Ik;@7>QbQYhx4Er*;0H#3RWCjp0rj{*I?#rGXl{Es z@V^WP>{6c|7(ms8uj+vA;TtV%j=-(@fATAZ5^t%Y3Pu(N*@9_b3tMd9Hlt7m(SqWt ziHHL9P%E?#g2Ftbvna%h!UAO^6b1%Nre_9%p|Hr<)14J=;N48upvGufu&rm{IAcyLmU-bPm{j42f1z`j-xd@aYx5@m zmbR$CWkw`=raq^{zN_z`h8taN7{rzs<<&-yXIWvWg`3EE9Y*eHi4J^jRO5%J)Tc9= z(oHB?MHgErCAYH01%7O_^7t5>Q7IhEn;b@STG{#qmKocnWry_stg`QRD^$GBn4^^O zxrk1wew|g$3t4k|I|RPD#b^v`)aN2zJ(NPN8ah35$3kq8ffJ2bkNZo%7O2{fN2B-4 z+Sy^_1{JH5U3eQYGWG~IK?=tEW_s^pdMSO+9B&er`yNPRSjC9Lt9&F;8%th z-l^2*B3RY1Ou3L}9O42$H5z01)n_$qQ8k42gu;!saG|fc1oCbGN|sZkI@iuNB=EnD z5>*>MWe_OYZB_B@FpSKecD6o&M~sIuzZLKSrEpL!4IN)%orj0A7<+k_=!;=3RA$U zo$V?LL19ARCPV$4r~35A&n>FjBUBIJ0L|%>aKw-$bxUxiKP&i(12m_9hocwMj0_0W zr&iWSiJIi(_85XS#+EiLn;yo6OVki7Q?i{#?Q<+E36*}SinRwfc^)48jZwsM^*>X! z*%5UL1<%`(13#?m_#9DaF&4J#8opBsdyEnpy8beBXO;J8g@F+W;J-62$`n};h*a2W~J{i&GV$yc*F3%IgsL-w2#)WT*^$&I9T( zN7Z?xgRLNNx3NG1UVkY!T?HG2^nQVxjZj(9zIajBv!u2o%*4RJ1IB*jsn1o+mXc*C zUxO@!qB>z2{K4oe3Z7Wvs{)aZb@Mu5p)WPc#LHu)r#WgcJ_;oA`M$-NL%r@}BQc1(jEyfSF(OT*45IQnz3xAW#ELomzm5&7l^1A*e??+j zK4u)3MR`w}@YOqi6kMT5|Arw|`xbOWHQz#lMsxaW6lz~+C|_0|U+H~>TJ6oE;kSP^ ze5K-KPsJ)!42nX`ni7p@zQX9=jSI)V&9+Zh69YFH82GM{CnIwn3to4;Zs_{OVCZHU zg#XBA)NS##ns`2FLt*OnSNEUycAtCj6g$P9enQ0rEGW}$7>yhC-o z(1DFQ!U3=QlW|bx;-mgUnR=YA0yz|h1eVmvR*TG6Rjdows=_mjgEH>(WUDIC`&sYT%!mJhZr=Ah+NxqqjXW#SxYAX@ISL;5+))X(>TYC)b7szi$mlACOO-jPPMB)HCsXk_-1Uq@6t-Zg=_yQ5* zFl3x>qW2SR&qIA34#!O~DVz=UEv&Bof@EvXMl~k-k=09|%7%JaPhEQz@;lX2f3v5q zy-{HOY^cv;btm%W;IC`{E35zgscfiwy{Ky+(A+Ryu2*~a7j^CGuUTU2zqo}=_)qi~|-$X5wbnS&WI6vtU)Q2W%W4?YW-$WlO^>@QswW>d0 z?}pKSR!@H_-$egr^?6TaLp`>aZ4{ zk1^$`HoAG5KpR7i4fx6?XQJ4CsKa*$@P*@EE~$xn3N6rG&c zFdAcCwb{(2lC!KXhd9T3>62nrlC|qe*54%S+b3CfB&!x#t+Y+v&7LzE7X3)uhuS*o zCcTr8*+OUfq~md|iAD{w1^So~drSG*`~CKHRS+Kk&Q+A9iPb)l5hi1==&IkX-ISa2 z>R9*K9FHc>ZSmwW2#>*BS<*0goiPd-&v8bH&hW)=UoPj2jmR(?KhdUPxJ~(Cm<|7- z*%!YMG=im}udDJ4kujJv(sjo2A$9Gpz++b}^FEHp5BTx**Gxte{pgd6$NUDm_uglQ znT%Pik@>pG=**8F)jj&`#A6HYG8LxVg7M25en>Z|UxKDT@-C#G)%pq^ZZdYtf#M!o$1eSWlqRG|37363r%%9 zCdwhc%SYJ|4q=gORS?p1Z`hv4(mOETWCT*wn+TJJ@ed>-Jc$PHs6`->mh}@cNObZ@ zMj;X9N&Fs()}F+ABs%H@b$rv-3ibOHnT&SiKLTO66CVG@kB{-VjZ8TWn)XtLR=sO7 zzL8M;B;50mPMK&j+WsH1Rg+Cd3fFiYkKObmSw>({2amwAOdes2!wKZh@8EU~Y3T^u z!7dnq?;zeDX|rxSKEf7lf`vmqHW@8xZ$zV}v~dLPxI#zSg5Nxo>c7aOep{jbG&Pdt zN!b))^n~o6GRsYkj&ha3_J%A*b#>*`I}3kI#-P_6kTs)CqYxPTFQ!o=ZNcVr<`5S| z@+xmM)o(GLVnyykT0aV_zKm7zBg?jqp4}Qs%8oBlI#ztL*;A!m6Mlj}%7vrRj4Rdu zs&WmNVOk}xnGxzw+eh2l_rq_zLVl#=2R!Km+B%au8?vT#vibwlY3MS@21%C#FfbI6 zVT-dpsla3u6jEM>4gWF2Sn-9)h?jbB1oNi_88}#mMO{RG2@Ov5Qs-VTBYnNem>_D+ zVWK?36vH?M**Y5Rv;}lE{NLMPGA`9AMtaQGif{heWIU@%;M3d~pHE3nTYChH85>P? z>$`=K>1GWc(}j?Ede_1z@!Tuv`Yu2wm-HChqI$AW|Lc%#kcvFxu9B+x1)EGpe~;|x zVCBxMhA>KmxO}eHQ)gblX8o(&wKV9-c%srXsq-L%AB)UmvTCr?&_6)ti5)?|@znBO z|79{hsw?=UR+G{9m2V(hP$$cA$|EZE@_K6vTwF#oNdG1>ma44DRhYfHa`o#pj9($E zeIldonYKpHnT@+!O-8S}?CiJXQ4d(mHj@!RQJFec^+f{byDY?#SMk`IPPp)xuXCL) z?AAt+&ej?q>qq}AlpLG25eXZy&R2N$B?y`)eyy^lxnPWB{gzKDwL00%x|L%>pUy+p zMpxI)_&1(C>pj>=8~UUUXF=e0WxcW?)NFJ@;z@<|r#CD%W;=~?*@7AvefXiBF&x@` z>zc2x{nqH^kUdW!Z=v%C@knCH=pFTY#K!zi<){DgRlQ|sv)DrHg^|~mBNx@?b^>X8}1dlUR z>E?;1FHMHryTN$%dvf@L?!OcX*&;~?!?-81Eg6R)o2{$xetnl`G~Y1Xcy5II4E6Dh zg?cs_&SdY)I6TAG*E}ny=x|;yO$I&ik_N{7jD7$x^ho9G~l+$7(#n^g4^U zGEW1~-!&PyX4apUhWllCMB@$oU65fX5m{YF^f0~$SrP6F)TgBp<~eI=*{z0V<8@JQ zMGs!GG#ZJBRFHyBdV(;TQujmpqawgC$QDcbw}W;UvQNY%pB|r%{!@d@IDVs_f!%%n z3(wL^nDkDeRENB*x3@ecYv3_M>sJMlZHz70`y_Ni=+avlvoonbsYIPY^*4bK!xC(+ zTXMhknh3}|J$u?~va;quhI6C-wERtYTnU-Ss+IwDO)D?(F{&WUG*Q(S14^UVyA8JyOxEB_i`^{n+-swr1lmb(V?~BW*I=FD14!BjWgvu{Cd-tRCys z>IMO7VNtKtsd*34kCiClJsgkz+WL0>WANdo#$?2I^;sudCH z|2Yz#bswUC!5AB$I=CM)r}Wh00ZNJ!Tx58-x$gD}GS7rT=5l60<_Qu{%ktdWkUhsu z7$MmD>J`MH3BtD2HXmk=D_)C4Yr0fm3-B#+9z??QJQa+!1r9&d-)vkGvs(Y=+_rY0 z*?3U~__wlaL(ImXr0Lei*nD|}$)W!9UNal*X?Y=94)x!OB^yM8$6|p0mW~xid(o_q zfA(;cS31qh{YRONH|nYieX0|0L-wdn<{1Ya#EhKLW+S6c_H?;}kgcneJ-slCGR(%p zx-J{^=2)B6+nQ-Mtjf0L-obeM8(Vxc%WS;Qxj8Pg@jLx!{t^Fqc`R1;+HA9Nf~D`j zWj5yVQ{)` zeeoUiFg9aUsoA(f%ip!NFug}hA@uojlG(WC!!@p)YQ|fd8e!9$1BgOAt!zOV!d+ zYjsg;i~i8YQvJ1-^8dc)oja48=jq?`9P{yg-}9a`XU?3NGjrxL~X#$Oc%C85l84L=~P>;=H-T>Mz9ju_ACRp4+LKMu#F+d>Tw#2Y0d z7pMu_j{tGP(lI*+#A!(Qm!k$OveoLq)9mm+U<<~E@7eW_1XkoKbX|;&CDX>DFwkOl zZ7Z$Li+&8;&g#4+8Xh32az6rwGUfxHVY~sX##m~peYh(C8?f3D=w%!Rv>I#)&}!JF zz#rIQ>@rQnaUGApuZgc%UGjk@mdW_vOO%t-UiTPg<4-g(nN4ef)?TNspu?`t!yPL% z(Uu(^0?#m>_*4@wFqZv{Mhmr9k-#O4hk=I}=daSlS;i5o>10>EZ@x^Mh~Afo|8M0o z8)I|r<{1opC}ZD5qps7$7`A@{#3YgqTZaue(^-8XkD8js2J_5jO`ua#7l_qW$Vd^dK}VcN-`&YMb}EQx~Bolm@;lM>XUJd?mSec-N)qDl<63x2J#ztnh$}W zOK&nlu0JlrlksHY{&Cq7Tl3YEbdk=4$s7W7Db$9ZlSwtYK{dy#rQU`F=IZkkwWi( zfvc_YxR$l04GqH!zNN8A#rYA~jIqoax|EaZ4F&eIGS#-Ww4uz2u)WGTz5zC6)W4&H zLz&%P;0;}-Pw|9kCC|#N6pWsA&T8UkkL;d;D^bbonwaNOY%aN>(QmD$AX~;wP0ZI= zu2P_h=ap=}0&K;&#KCWYjahZyvavbP#cB%&TLO!*8s%VTV7N?6Mae^f!J3RnMTL{^ z$dptZzPGIHY-^igZKbu%vbHO%?OJQQiMQtVJDSMl@WbwE;ypu!cR%`{CQRG_qA1h# zH}xN?fms}ARi+jYAC4)HXLKDkk4l3_OJFC3dYZ1wHffj?7XbPL%vq+6Hd20H0!K1N zxOH4sl$r&s&-gVkl<_jK3Zp2dqXNn|9N3hx7qA{= zO^!XhI-dTkFh5q)#UG4EpVq}4#$7da(S^}nTNg_?Xf|*Ut8sO85zp!#U^-*Bdb%jd z*w?`XU^!ObbksDUo7H!K!HgdOmr3tzRJLgYnKBcVJ=j3U1v_mf&e@0v-JT&w6gg+d z!PZc@nK{5gjCwh(%33$%PY0=uv} z9~h|G!OZI9%ceEzEW>A`vV*(m;+n21Wp?dG{fI)jhXd*C>nHjOv zEUr25yxT(;A8K;lYzznUd*icem}m5%K)Gmo_s77JY&LWIseX!F+L3;8%p7>8VDUg} zd6@$31Qxht`W$rK)dO^KSjpPBf${=8wI2q`2b80IJRR)Vxi}166Y!)9$#*C*TmGwWs429aY@iGfm?Qd&aVuJd&S$P7T#EsrXtZ5TWqlS{n(+l-1Y@G3P6eV1QKS{XMA?8a zI9bQFEj}GZcTC0y<_P*Lq(w?Hlc(sS5928y9)iKq{1I4+@hUKyvB^|j^it@a1uW^3 zDd}j~g(=jRD4)A#DynG7&tSo63(hzi7_3lBn$n#W-*ljb5%y>|XKNGMyZs%+oP(A<3PS zu8U-sT$h1*R?g6I6RtcPWXQ+lc^*=*lFYlnCUPD!nKd(Y@r^?5k4!lx69=p0Vthl7 z45b$9;wAR#3k+wkHy6tbWWBIN$K-)xxGOBx#XU@W7NFqLAL(Mfj9q}xJAqRfTjZc` zG9Cl=XRPzF?XVJPsjlT1qu8MXFhimH46ugDWjy#y$FwMD5z2UaH4PuCxEjDwj2Xb* zGL0Or<|3a`wG!*3XAx??Xg!^MD$gkg%WTjwU&~pDnbHQCLVoXmu8aHZw`jADsRJ1e zP)Uw=YO^dLzXQ9eHC4R(z)Z$Ddvwu{@fRRYUTTx;z=Nvl-u3%%k+sI)=ZcKQ2Vtwv zIqm{~*U&nM*#i{lJo?zX^6R_piwTF2{c<Zh@ zcT_kVSeYGG9Mi=YtPVR)7jET{2*eW5&T-O)QtOH!8RQG;h0M1J6ocl;U1Mhyg`q%0k;sj^h z(!ju#H|j$~1C?U&4sb2whYX{C|c_r|~^#?`=vj6VX)G5+TG z{tgURs=H*QAr@Ix$!=ue%u&%wG&XQAqHqb2oy{%4(yZ@UQr+cS8e%T4)ztfzw=zU`cD@6|TXu^3+4BZ& zadVa-7^sO7wPLMhdKS9Evrz`dLA7Ivz<~iA=|mR;r>)Aqv#WubqQdLI{W9%+M0(M{ zG8H8r2ZkxsetS`l$wpA^CF*ixvr%|m2YUe9vbq4+kZ~VyC}XW|28Jn>?PUk&0Ws~O zU~3%p0?^Cq6JP@4pzelQ13O-2G&4y%Ry25fn^nH zXQE{mS)0WexG3e2wKEV+O85qFhrIJKFrtTn$1+Nd0aj&9bTGqq&^GpvDIepuXJsEl zT-W9992~y+{S92dRsIXWC>2$!@~SL=r&&GDz^q1DTRIr);Ba8La&XTCPOQjL|4A~$ zi}K`hs`ez>1BLy7{bk-KIFz6vELNCI`=adM0;@9K1MXtXOE$zt#)K($tnm)M4a5xr z3Uim8YKStLELe^`tCnhD8m0nA0ZU2m3XG85Qf2rG>{)L}vy^0>2Nq|%W}|j1Ri?wy z-EtZR9YeNWfsiHMHZXstIA$l{01mnGZTXl&E`G$vQ{Poo9$g?6E4HY8Cq_T4+8Ezbe~E;2{<>3|wASfV!E6_(S6WVT%k*0hRB3 zU>C+8fKyc++`SiLfYD?)>SHXSCRDz!IhX=0!RjpFMXvg=Wd^39v={E2_i^r7_5Cu7 zh8h*3eYPQ1GTs2rQRp835eCWtu3Nw=12?(Kc{C6s1vSd{)rQDswci>8&ta59g|*lx zd3h!FJ{RMi5;bqGOj(82{dpsG#XGBz`#!KG<1?FRR3}wyvPl+@V+^FKY)u3XQ|SI4 znBC`q=K(7*eg+I@JP54FcnR2o zu|mFq`Im|?9oUiaD`2of?Lxj>w+0os3MoM5twB-01D{u@)!oY0Mq8=&%DMzNnDG%X zlCl0a8g9rzYq3qHuf>h%i`(RCY|Z7{X)w=Ri^$u6Jo=`*W-bteD&Zwy2gVwEs9}{_ zANU;OFkmIdw}2RRDceWDs*HPqEg0_uM=~btRf8(|<^h9QJqX0T;s*5CclQ~hpDw$v z$9a48O9Qi*lX{jiIbWtO# zc@cpuku2T5EDI1&Gk;-ItzT?YrX_8Hbez54 zy24(cT(P}8S6Pa@>XXc6K=gI0-1cj9x1g$2>{kO*I)%+09081Ebt!N)W4r&__`8Gh zx`B5fD#9IL3&y%PY)o+Q10e32sSX7|tKcd(ZH#d+&B2YpPMqz&gKdAKj;?}z0<;P~ z55%+NjcEAasS7H5Eg%L2Dz|k3-3}50AJv+bAgzm(f(`(T79a)A2hZrH5+KDq4#W@ z?_jY%Z8a765AWrazijm$a5Sp}@6)+Paos6Ets|cc)7qFcpyi_rFKZ(U@^J!u3n@TJ z<~iUoh3?gDO)*55o~;;91KZ2Et?(?{!NkoZWj1R#*c{kO=50e0fax!(C@%j zjCEc#G2SUP7g$k7ZG*$1Xp@F#@;wKvA~UxGAKIu@jFIWvQGqEjrudPqy<@3Va&%7z zUdJ8!b__S8dr~NsKMmMGj@^OwT-Q^M*@66rAYm9J>6j(`>PQ8aR16;xVSt5~=>=j~ z1iIS*H@Rf^4wQ1YH|^YOJMrSV^nXnIy+XA8w36B_Obmt1Lk);O(M6WLqI#FZ%YJ=a0>Px{ZnqK%6llyjJl>%<}@eki>s#wvZ(BdCGs1IzpR`gg= zcyR^(!?b>;XlvUhj&Ler80}&6twD(`vevK{Y`&Eku~?;Gzs0BK?N3ITv&$3Q-w=Ze zd#e9tl*^#ij3Z#1Y?toe1i!#m&9?a$V7?5SuYg+kM|0b8KsyU@#0_HrY%^_}e*srv z6V}qB*dlvy^%YYrR|T}eUFfT(=w=5gT!0>Q1~%V1hoWuUFwVq)hGqz<7Bm(-){f!7 zcHw8(hLK;W*=2xUMr)I1EtGf-f^D?ne*>nY+31vZSEu=zfK=vk!4 zh9{Wz4)-i_xSxitnDp*b9kw3+VXfs8J;iH<3ebZ(`PuwWr362ly?93LaVpuUfKc!I zes1=812-Y^9k?cpFuR0E2VZh< zI1qEd12|1*0vjsSHV=~p2XK`-52-v`{{-%1>z3hcy)fJq>)8742s_MbAa0&0;x6Ds z#wH_8yuKjSeI8f>i#-nFspzkxOi_o~Ec2R)7etwdF}Zn7wmyX7%PA%55biL7Eh)s2 z%3D$eN2+8=l_BB9I5L{mfp}|7*xXUuIBG9P?Qg5@M4;P{affh&^5$5RUT9N@R3P4t z6E1etY^A0h#hsxe?r~hdbJUBD`ahtDV;SR2JUdWfzXV!UKLV`4>J^|>?n5Bnv{Mzj zzG3^u0s~m>2lU7wstxFQ7C&)Z*8t1Qpwny*m0q+sd0Ij1jJJbE08QIM^#IU{@Lxy01;iQy+Og6T>^eLJ43~MwP)A2>p+x1{$5G>y>OJn~ zIvt`_)=I}USGiIE?Z^Zfal})JqFbfkcKrTw)ZjPmI#mW*zAcsN`U+)&tbztRuA>~+ z*^ZjwsOx;H3SdP&tweQTKv=p#jS@1^u0R;jDyyxdb^=-fhB)eIN1fxSnYOB}pD0s~ zq5+`P=dXui`A0s;_Cpde$fbMbUa#dwbrl>UT7$9rE zDk@RM_X4eEZR4mNfz}}y;i!p@y3kRV0iWi*-R-Ccl$uH1)e&z4t-?IX_TB~qt&t!C zXthi$AXe>A-x%)rz7Di@Vxr^ww&R=U_-=K4_d34E9N!0yuWO1Ow>U6VHadlxgW7Qw z5`fmh8R@u=16tLc2DGZX*74n>eDe-*EX(yPh*r0AO|`=Y0C~^cWq`5xeip;C7N4T7 z7TTZ`Ip%v@HTq_$xiB@$IG|OhNx%R(mQGYhoTWr+K{@cO$G{Kx5r=;P*?0F|=z~FZ zmvfp?ifb-8<_FZPS&rNdPi=ONJWDzHEvMP|KFW~< zY$Lncv8r+iSx=7;ltX*qETw8kH{kzTMx-lwbQMEC~!`wW6bXftZsZrn?!ioh}Q0!i9VC7V3N? zYqPecF_YIl2iKueK(r}i?sSK*nA&j#22wO+~dp@2NkikfX&xSi`qK* z=X1W8q=`!G|C4b5Y`#fm(V(Yb^L3q~wr^o;Y*nzR&Am4jhx}iRb@rNK&cE0;!8Y_? zY!&vIqQk$~;$ZX5OI2l>SdO&!i7@)UXee6KG}wHf^$wCXE_kX`S_>&aO(2kD-FIpc67GUDg1K(HCHUS@~9zc2l zU%RctmnpRU6yFb(#-ueIUz22n3b6}EmA2mp;-@0<4Chaz+Nk>5NU|J0%Z68t z01v2MhJP#`hqx<N4 zhVKJxDK$kNJgF9CF?E`WL|aP9_%`nv(n_@76Qs+C8C_n8^+;*h@#t`LGy+O}z4*Ku zsWZM!+JMvuHJytz0huVBs{$MLJO(}EMFfk-5!;LOC7ut2q2*{xsWvK0Pqut%2s9mO z1M&qujY=U^MXbq4RbRqi#cSdtLLJ`>quI{DcmjJFfu?VWJ)%?zm79#FzJ&B1^zY$| zWnQ8HhiwfGM=fmUz;BMsz3i!1EF3%hIhMcgyVpOz@z0)Bn!NbX6Hwg#1tRJC%hOw~ zzvU^Of8~njVMvJ>`&W%*yb;(d|I$OxM|> zEMj)&Q581yUEFT&gW>VlCX8tHL*4xFfIwGW8B#XzY(9d{U(7wnZxP|yumS^ z4SbXr6Y2^(jWTiA#48c_bt`O#{e{2q=Tt0OErwdy@HPLE{@kuG?{_pc{@oyZWg!$>x#v1VRC!(z{w%?#|!n#Z;#sJ>q5j_io><6 zn0(wPuw%$ta4yn1r1eM}klZ4_phaMoYvEJ3n#iOUfmIh?I(<05SF6CIE^{*SC+F8_ z9e6xs;o2MRi%&-JlaP|~qk0Fn(H1uU{iTJU-!31Ohd3LNHX(hEv>9m&Qa;jFq-{vs ak#->MMB0V48)*;HUZj2bQGEmVxc(0)LFEMi delta 187094 zcmb5X2|yK98~8oT<-%1E2wd0{H{2Bz5fv3&u@pBncX7cbcg3<&xhAfuX)ebM4a;%~ zx3aJ@(^9iCL(^6>EA6#1)3UNM`+m>NT$bMd`~AP~>cel&d7iV(+2_pMx!&dNy$9Q^ zsvoq+U(>ubHS1GYl$IC#hQ7LY;0wmDhJNuy-Kd~H?hdc;f%eZoE=){sQO<m->r; z`}-T!9(`*gbO{!K#n*D9Z?Gofc>l^3HcG)@kw{%!Rse^+|6YV@hVqoW4@ z616XFyZ%Dw^uUk}(G9PsHj8}keD>#AW7ft!EQ-e~r9YG2H!!5nj`4L`#KaEGPk#35 z(BiL~S%I?Bs{}_yc6{&H&3i9D^z4Oue*G!BX!xTVNOttFJ6{aiTj{fY zzdw7s-)kpJB3&65@^sf%H~rH5g;r~|$c~TZ{r+r;?&W}x;In7Gd?;b_xLfOLj&54( zw{%N)U-uWgAO0seB-wBCM@K#%7}wO@YuM3?jq2`8E7Vo&=t`~^13s$euP#mr9;4Ey z2B*Jx;)|<>nmr?Udr{+=!FzReH77V$h0h9Jr3z;SCl_6r6&$Xwe;_zhO?x1?nxVVa z+<$q%n&QjV)XfKi^VFQ#!O<$8KWnyrTTLIZ=Jju*)Xmw!Yl{jV3=Y)Q(T9SssJ#yd z7pTlR!F!7W<^~Vci^j|gj@H-I`Ei=Mnj2hAue)a7k5Q_QH@ME4>pv!|CEnnZFJ8Zv zWBLuCdhcB`{pZ^1#Mt1(HAjDLtQwCC9_o?WT#fGWHJ+O-a<5U12MtYIgU?#zKOA2{ zzC#9>nzjzV^~k*(4@3qbqma?a5@ac&&~HGVKsL%Teix9N$dkD9kzYC91UDnUar`@S z%hYnUKREakc?v}VvITh>sY*UOAl;B&$i2t{BoA4LEJ79|&tSV1S;Fy22o`6!Hr4Jf4L}j9b&{AT5!0NPqkWB2%QB+^bg{ zu^(eT(C!widslk=R)DMbJ(T2;TfLtddg~tbb!RF^h`_hW^^>^#8im9QRmK<_$(_sJi)xO=HgqowU+KG?}?QfNF$M4Rq zD`~G^oSCcL{LTN*r@qfpBk$JVa=p=K>Jvrv@6pfdMfH2?y-nAP-iiIyoZfn->(MER zm5a{y)(c#&S!ZhvEt=h5zhb!d&dLcZ8Z%IL>8{Clsy9`W24ULZgHLy>ql5HMT=^YV z{-g>9>**?dh<R;ruh@v@)W82lwS$Zw=7(r_!n-MC0q~6qja6d^mOl6P6tOaJZcc_&k^^}tEr$v#7 zqTvqJbfa0SXg3N)OBB!TP#eoCcA)T2La}RypK8{vV%w6qDvu^eD>MgpsP?1FWOA-3 zl2N?1Lw)w7S(^LHqG*lc(;ceP7`>L?r#t*KT}?k3P(u}0G6K}9eAA`!PX>gmi{o+b z#i<`t^T+5lz!n=vY}|-8#8c0R(V`}w_dYFpcYzD*} z(>2Ra{AY}uGA_Hhrd7d?K91eKY`rRRzLTw|`Hu;+i!yX9d2Uahqj#w`WA)@}P95Rn ztJ_QhKe=6PZtEARwvN?P4Qg$7ff>1eoF3w#g2;`o4OjafHNzNq^g@GL5xu%81`VYQ z_%}!0=!8M+c)h@&5-fxB$NppszyJ*h@yf?`q!r3Rdsk>uUxcY znm#KKX#d3Umv2nFVkD2Ua(Bx6y^U3<+iAnp>nSp?bOA%3b88hIX&F{ zDc)Oasm;&nP0g*SKUk{wavJm}s_r&w;WI4!>ZpuudUXR%*{0tl%Tt%?mDTL+dU)XH z=u_($lqH=}|BKGJXS-g{X|JEDFShHo1J7gA)o0W0ufSM!@nb)iir=9J8eQwC_B-_6 zB>~p$Aki-fFrkh*w4DG&CsY*Nb3}b7pqTxIB0lMUEcaVRiDt=xcXr$Ir z4GZ-okDaKl)m90Gw8lAwdbB~j*CH|WextjJ4ixG=bmcmzN4q=wX>RXs6?c#h?%nND zQ@82gsrYT43U&=OaCgCA@oqKc^^#uKS?zkA+;&Cr*lu;FyOHReMrRdz2t_v(CwHqh zhsuO_P!#DXKHROIKBU)b@ZoNIB&(vCq5J6)E@q=f6lTC4+rPTgqZX*?=L4!L*BcBu zqpg0@S+#zHaiTkswb|oRZO7`ZO48pVn!C|#M)TC=iXBQcp@+%9J!nqtQEd+E$xbVk z)Ato{9g>$K*i*n5xAm|dVlKv2Bg_?{iVstSob0v3`dIU%&t}>Y`jmYlx;9SrIZt8d zAJLb1$d}d6#wdLleyMNjsUC7<`Ndl!vdVu`Pc%=F%fE)|5$fujdXM%pSsq2sBe#%{ z0Oms^1<6DvA$dqXvL88#Tt!?SO^f!dPFuGAs2=O~xHb2?87l6mUfp~*!%y84Yb2I@mH%+P7H@0-Xj zipHlG{{sB3BlGaD*UJv)tFhQ3Rs+ zwwHSOxZd6)IhVRT6GbozS8sK#tfI*Y z6d@=o_ErN*AErJY1-amGHq6q6Uf6G#O9d;X8n{!O&*Frs~@w~BjLuNC@^6TOrsT|(QY zj=X5r(6_0YXZ>oZPmbw@%#QR==x<1&yaINN%WZZMzCR z$t1X4CD`b5lH_+g_F}|352K}MBev_M^WRjw<505(Lw$r$#POX3ZrayQOlDA7Zf#dJ z-`AtiwzDw^#FUL{!u>raOqpm;xfQGct8L3&@9Q-}yF1ZIQAqnE!>8zh*WcGeLT8lG zu^_Z{_vjuq>=Y$XMM|KbT69W}GvN2{>DATAQ+hzmjxy&lIeW~6kp!(p^fHg{P&ZD| z*6p>BN45Kah^i7%!%Q{y1HEZb!_3mN)70rxdR33)Op0=+I`V+-J?7f;YGkoqHRAa)x$%{%)aC65Urs7Z^cwr=4h2s2LQdYM<6a zBYj@dLhDcvlMpHTpE6a(X}yR4NT=s+IZc)#i6gAPdiONbKCE;`uM!&5zsy+?uu!!; z!!pL#Uhr_n}@% zHyANip4I0W3=oyh>4ObM18Y^1caEhBBY@@Di^Fu$xxUPI#i)ztm|W@V*Uss?rAKf6 zh;Z91Myl|S8Heo-rfbRSbS`V4X&>v;Jah~z7mMt5(d~~}7cK5nwD}YLPeU5R#?Oh3 zI=%b6{{#+Nj4=`EvTBf(C>WkT)4Vr2Vt@eLK?VDIB+)Wg3VJMd{PLq<;@J-?IG^u$` zld7l^ZhES!@Ne{L#?lPc^cy|NSZ~o<1w|WVW%D9?`9i~zr2%gq&3lwXK-n2_opE4~$q_cC;IHpOshUQzA_JfwLm6S1Zzo?O+f7z|^!>-N>&{ zRqZ8o&_pNSa)zdA_njW4F8#ono5`i;!}^KX{I2SaLN}E0rmsmNSFIRFUe#-d9xtP% z6QNyqRqsV{T}JCZM{(_IqbmKVHw@j^rhN44q>Q4}w8{Z4eVv*fZAAG=^y}nev#Kii zQ4dfjzSjq?zs5m*@~v*?R|r(G*BHr)+o(f7=nd6C96|TAEsfVtwIgq8)iw4K)~R*Z z^xB?Lj=GAP{sZN=p`|NCO`GXzqC$TngCCK>{cTm7pUSkR2T_E7jN)x4s5Ub@CvEnG znJRU--q2Yf6sxZ!{3n=w)>c)x&H~}Hl9aams8><9@iz+p z^C;$|Fls#RM?d>n4-Ca+wP|Uo(oQz0BeyEl&^Jgsi>jPVyWWQg8%J@Z(44qvjh%A9NsG2j3 zPBf0!f8hkaAfH=O)wjRUIJP*Jl0%8*327WP^e3cURQ31@=?Sazs*{|PI)6p4pf=vr zD}}z`g!T2Me!wy=4ooyIsXM_{Lw#Pp3|>~3e`hW0%TVEvzq${MYg$QtH-7G{-L{K%Gy6Lb;iUAQ^r|gxRN7< z({`92|6mPQ*0Lj7$-9gQn^nx8dew3f<&2mx1&tMvj5?cDpFgd{C;v&4jO$cdo6_7j zD~75twf9ek(aq|WKT8&6#avR+Vc3>+Pv~k-v(D@(bCqxQoJ17NRMt``Qf*mARIC1C zUm+z)egBs})^oq33s7H;LpSL*%dmM#Me}aUVy#E3qLqK^*9>D{o0sMpJ9Tq^Tdt$- zt{9;@8%DIr5M#UM;4&CVHX6nZgF&K_X(X9x^kU04%S20OpJy5!jX5brZ<fygvuIkFWwh@3^PBLPg5u}CtKiA+M4AO*+)q!_u51ke)eBdJJM zsMbuI&B0ov5IKolLR@#T96?f%fk+Or9NBu8`ZLIg^N*nRBR7^?YOwuV$zYL>X3$1e zJ=&?%O!Rga4O7E{ zjoSX~>ATN9S+1pp;pJ;-vx$?eSS_uC`l^6Mz|~-5j6o*)h8Pz-1hsTE?8@yCYSgcC zkW(o}t{_^Nrd31Y!&ax=zy2;G*1r<5k6CA*oU?B_gSDbBLD{_=vre&D8L5`vWhA=O z2|YAyUs@Y|eYg?p9${+k3&kof+=w$^M!0dG=R&c)zgI=ojAoT_Hr(jQ(rv^!E}$D% zHp1OmgfUL5u9c0rP~)_1>l?N{P;)CAQThi;kLTP9F{x&kk0ew!QzZ6%W!gFsHLYT- zuarZ+)*^+-3G&xe=O#d)3amzgQi3zqskmxJEprCv`cqTSPPL<%r)^Pugt1;HbF!zZ z&PQS!j_tg4>bFRvbWglx6m?x0#iQ%g@F=5t=%edOtC<4QUR8ZAQ@^iTlaVTzYxouc zVd_^2TZOQ{tdn+9EA*E#VP(pDO$N~#`fCzaz~V-*#l{gE)=v6s_D=e1%GybPP4$Vf z0!;tbRn_Awzt`027|QQ8wadmkF-C2Pt!~Az_0>xXvuu;9Lmnuc_SKDs1}DyPKT_pY zH=;fEN$T2o`x5hDb)$#DNmQs|yjuMtrF;ts38#M{sYoU=3CRmzomPE)tnm@$S|iL; zMg16StY&99x2AE!)Q79-bq(2Qe!i~J-M@N10rn#&kt>K+nY}wC1<9 zpx{rd&Fze)DythC_sf%v0n%L-n3dHnvCPIYooP)vzeLTY)gz$4U#dRMoX-JM)gfL(o5pmB8qXu)8~wOH`(y5 zg2t%O)+nYEBKwSL)7tRei5jEkiefw=)EV_$>yn-_MqL)g1QatqRF&Eo4MS&qX!q|n z&f@2^s(IWKuO4h;R8$)(8x+PwcO|vCjnUW{2gj(>ZHVJO;&|ml^=F$h*-2}QVj_y` zAFBJ>mQm~z#UvEH&#KSb8qGs{pDmy289UXUDMm&8jM68%Bh-wPGD$w0LIjhEVAol7 zDutO7-bpcfl;o*TJI3ZI7<_YLu`84IKz;9SZwxjwsHYBv9_GdlMty3pD5HbXT=&#JBe~bL2F{LmDswVb zb0Mr^q`I2QJWq90NHYd|lw+8n`mA$RQ47+H1dm0WISX}K0#MF zkK9CJ=_1KU7BU+tKn@_EAlH$QstgcFDl!n6jjTfUA}5e5h;*;|NGdWO@gf_Ly~tS= z+QfKZeYz3r=01S?`z|Ujol*SzE-uw8+!&^|ryGH0a#viZ^}6bOx{)M(N2Z$k-RV1f z3DdKy>e$_gi|X06^v=mZF5n9gwtcjF?a=o)9c7O?*PYg|kC542t-CZ%ElT>nTHH=J z@^bgx#%_c7|Ge86>&dp_*R{J;pB{eUYVJKoy~h6ia$j0G>XJds#Zoxf8MOJGf+H(Vst09GJ{EKbSGa~+1D&9)R7Fsx9PfB>AkSu ziv2sCRKs3nBAP6UXHnelq}G>Jd@73PP&DhTjNT=EceCo=8^tyhJv*xly~{-Pk|?&L z@cv6tvk!_LD7JJ~)%%tSu|gC(QMkIOWqnIVrOoPBQ9O?#u}k?7Bm1H#M3MHd5bua$ z7mAE7>gT=`NJf|P1(Km|^fRjJ8LFL)nwe#aXI(!+bDz$g-$fnjN9g?j51}LMb&fO% zUn@(em96Z^t-5yZp5|5#rlxRNa6Z#WG*8;D1l74eQ}xY`_C2yxd&HR2pH+FHRfW3N z%)aP2+205;sNM_xX{zryx)!!BYk(2rxn16GIerF}wRr&R0_x^n=<#;8)2X?xPsNC^ zj@Io}SwC!X{72jIrQAzcDk0-uqoJ8dSMAV(L1ZnyW}44+7?;N`Rb9)l^L_PR@@epIv!P+{2&#*=$9%cEE}rgktsiCt zRDPdGZaazimV32S%rKUFwN&e2tOaYSK_K*($LyTQ<*{s))KW`_8MQ<6R+oB9#%ih8 z#k;tSx2&gXsT<;*@wja*yB2b$wN%~VMx)U7>uhhiDJ3hUT59BQqaGbDd(fUFt7zS zA3HhGx@G6|o;o8ZW8~!Qnds#1Odd(a6HdbT?BqlwirTt*D4y{aZj3h~g)he&sR?%X z^QGR=NnM^Ylh1G)*55=@e{#L4>LnO;gT|9g7Di(5q&m0O?;f>kq3$y3=xS$z5gAm7 zekl5G==ZA0>)67(nqagUk!{_R_a)cdN$!>`8~N<9Vf}4Ma(}G1i(TtCdPa8klz!u< z=2#~x53(I4jM)2ZJ)3kQU>jMYUEg>YRqu)L%yzPr1v??3c-@KvMb0!JjsNov`WgAC6{iO_?PZ|+4-(spgH!4<+IZq0y7>NO% zR#v4ZWwfcU66&zqR$uk8Q8It_520ReA{9BaVP!%|3iZp>+U&`b9+)v9Cwm6|GLbAH z%ypzU?w_1+GObDh)mOtN7*P=tb$zzhqzg`Yy0k$UDs(K3=6bdf5F<7LWcpjeK&qqX-pKdOSc4*J&uX5qU+1PVHD>TW1}^&0=S5isI|6ROVeeHC(h}ZSXoQK zBnqzyWlRF>ti{hT5=$D+-A==~iM@R4+OYnzx^yqzs;W#hdgqpJIKD}Gud~y!ObW*N zu%2`mI;m>+O?_}?&Vy3_K)TePQv)?#6KRt*+_ro;ElozJ@B{tAO~xL`@SPDPP;iXsM|YQD(wOU!Ht*ks}LZK4;5x zA+A5%6Sg^d>X$uZ!pKQ|vqz38Y3C=%OR6la3FEVq{77SJWGzztn5j9m?!ro6Ya|<$ z_6=D!&E$|d2HzucD1D)kV$(9pkKvL-9s!QBmVb@Z+^Gi7V@+mFvVAJsd5zRDJYsm{ zLd)l3c`4?B+wF|{dI-U%IVNW@c@UEcJ8TnQ4{4;@O*5kUNGt)IMhYf1ciJY>T_x#8 zdg*vYFg`oqz0t<1=7UC*bvsi=_{M7bbR(j6vK4MG z;d&6R1BxzA{J#61mSI#~-#Lk?SFU+5U0mjzr1dmbUu83~h{=9TWWcUnSbEyh0?7q; zVN1GKUuS6OEYb04VZ-{%7arV6g=*ytBPrs#M2C&&lbk5qXiY+!sxM|39rPwDW~Nau zqDh&0n2{~ZSi9LbQNw0(McqWrnrWnElwargdg(zY2h!AhpU3E>6P(nvlt~k2GI~!L zJ9WnBNfWZCDlgFrJPtQA*U(zniH(SSFN>bJmPWR+GEQ26t*KyL~hq@2=7=Cj&q;weMB4at%6A z4LT4;hcH@E#)#!HMyKsu{75d6$|f;#^yutqId+doB!*;S@F#}WyGxUiv7?!;sxRVU ziQW%TLS-Y6nPhUdL=YP)i=Ad_`U6H-Og?cX5|>nuxu>*UOFM6-wme|ej*+uETvOBb z(bgwBCQ=wu(3IW-R6+fw$NZB&gYo0+LICRiC^EWv6n z>T-FVJatU=Bvg_L{SK3Tc0})EX>f{Dh6hwpw`Usx)Z6K&D}-4i0NKP+Mu2*)ONJ}S zd|oYX*`Q2#p|q^3TgD?9J*4Wn&FB|v`D{68@>I`*hRcq*YRpm2+)D(qD41R*0=!6V z*F%i7l16%MJB^pinBav81yt3KX3AmOLsoKPqT7J|BJ7u!v6oSse01`!8k3L7T1;NTOW$7_ zWh2XE^21hEmx6LtGit)PaWV}`)ikv%kJy%9*!bgNqmk7!&l0tqP}i4A8&!f8AZ<>W z!P2(?U*!xdG9dUq-5FNKy`*-}F*3)MUxxVR?txN@d{*1A{@zWfC!Iun^GVCV1&UVxke5)WK56 zM8+wXWy0iIwWcgRB+X>Z#5(RkX|wY4nY9~dKU4hgC0?vFdp?bASbuv`JmZ~6wEotz zv&YC$*05uj6A4{KB#h54jyy@==GG%wWrD-mh@E2U*5)!Rbdc!VWG3*}iruO3K855!U~mHU*j z46rQI7BD$%$0Ps~X_}+Un0PFc=?k3nI%6U$jnS``rdPo-*|orEH@bYC_^w=gH^G8W z7aP{!UX+g4iA3u>)vgsZQu$so(CKZ|;Si>VuDeFyYdXYO)y|Lfj>|a&m z>ug7z#AV9xeR`Alu~*gic}C~|(dp02B*}+o&PzUh2=(==YWPAb^aQbP$42yDJEtKP zDpOdZ{cz^qg@#MroNqYa1}rXdUgxW4>UxPYWGc>(MLy$ramJT8_dZo2FeXvA`iqql z`?AR%m8Ap{)$~QQmPA?9gsFl>w2wp{qob`H=2)$Lgj??yZQt)O6pwJVcZV6sO>mu> zSILWc=B99g5ma}=46FDx2KyfIJmf>{V_viCS^B%QmP9Tx?{Qa&xzvmXjm;DIO?7Of z8%uLZlrKow-B_a9N-=Gud-pk58kMwrGJe3UR*gssu<&9rqKrkLYC;26jh9&G({c&z zFAvib3FL{>Uj2G$`>SL}wgmHl1x9qldF)nU*9-ssW$Z#!y9EqVjZrN}q@}-IMjdKJ zb7KkpMPfLLNjtorI#im{U6x6MrI<)&^2ztBWTx&LrDrDVBFY~Vs$niLD6;m^tYP*p zHC)}x*5ufk_7Y82MrHlSIBUO?Yub>0SB=$r77~uX-w~g`Jr1^1O&+E2#AK~w zl2FD(T4EWK6OKvGGA2feNo9%UHWG-}13nYAWf84Wb`mXpA{iu~+CE1gsg79s4|t+7 z_Gka5|6}|wmJ13#eI-ZErynPO)rm$MJzl;zJBdHDMvlw28vHbp$|szJ@!9$2$t0^Y z`}q@9l68r%ya(JaJxS@Wno+92KE5H(uFEi(Bp3Nr+eu+=C(;c>nna}jZwwhFUhc)#tKNn?_!xomc3OtzD)kL_}#Ci;tIqLq0%N&UFO z=ojy6cfQNT^Kt>l=N%i?-%N_W{ag0gtNGDE;nwVamWa1wEtWp56u1OwWv|Ox*@b;^ zB}?5_YPCE=)=D;0Seh(wH~iPA?VD&i%XK54IyS7o{mFscV42WTkXs{R9y`e(P8ASd~1;X6<{Fl!EU#rvwKe{# z*j8p-eEA94Hz&?<@+hOV?=z4*dXC#Spbo4yn*NVn=$lSZxv27e1`+hG8FPym_F^Okc$REaOX;_9R;52u>uvbhv0JbdFNL zt}(vJ-9siGWHRE5_S!@6bNDcnw`*EYd#;bwRPJ`I0|*M7R={R3{r{g=bL z=*Qx&21OqUpTpeYvCL4S$G(pfJfk`@J)Cdz6FCA>yE;BcntDDwRSw0gE1VO zfU_XugLe%)2e-nHpnNIz6Ua9pv`?WQE3nTYU$&H)(%T+N38cacxYHbW7x)$Ku8un$ zeuFy`UWOxJm#Z915CixSWQO!EfH&Y%kk;cp25-VM@HhA!{1aY-f5V$9LK*Y*wna}W zqk-;UhXyD2@#R5}h`V&nTb;`vX@!)sa|d46j#}Rm%r#KUOv4>CZx!fw2|@@3+_ zuuDV!bVCu1^gtRSEs>a#{Bm!f{wlA7kheXIs%yo^+y#S)pSyP6%8>g;vX5fbL!9I0 zVnuGbd1Yc_!`Yh(rJg!MHa@+59rpkz;fKO_9!N+u;vy?+6LGN{%e|K%E!N7;D%^jp zSMP2xBD=T5UWOYcGB2B4S~8S$+rV~E(&-LUa8H8m;A+?&KJDmt!!*_838RIF+wIm_ z&a)mPpWFp2S*dh|(Xbnovq*>Ousa+M?}pRiJ#a4U0fSh>*ag`ZHgP1`DtV7q!8((C zZ0)=BI^W=uul%>{L(mYs`$1_4-0-m)!o9FI?m@5-90H{Phr#Y@{*y+SXB3AFDcWe2 zmT%Nn(>5C69{V=Et_`uipqe%g6N!BSl-MUiX=an5#6A^D?9-vdJ`+mu&4PpB{pzcY zMl+9ne_q$-s+t@9!*U-&E3wXj5^FB34i`Xayiy4g>q6X(9d}c>1UEC8-0bqE!sW0l zTm}2V$DyRU7EXj4;2ih_46+(T0>xTSJ^!T9+GE|qr}CUL-Gq(g=_x3A+5+WFpMi3w z&qB%5HYjJx7qhK1eI81hg;I#kJl1V|V(n}-h}Jw2ZN>TmlvwveiS=bDu^xaDE7t~A zLpcaL;eK5m%QqT%?A!Xfwn~kB+X%}&f>x&dw_pT34y6&FfX(2$umgM_c7vy(ud`(0 z{t&ke0#d&B!jEu|f}g+%@H03So`(;>3veF12p`kfJ^fm(*ks(3J5)yKjdsiTJuEN; zJ1&;3&$rk!#A#PxefT|W3)$1~roij4C;SaczJ7<&EhJxA@DJQ09rtMX7jDVdZAgA{ zwL2UzIcopF4UXYPs2iG>Inmm&0B2<907+KtbN9E zFbt1La5&6?S#Ta43G?7+xD{r@7ojBh5~P^Dhv9wjO~?NzoPzt9<9-`X#r-jy4rNJ_ z1B0}h3?SG*(9mlEi4GTsi(FW$2|E@*&U*xs`(FN+-%HcJfYUCp8YUvk9!X6 z1?NI(^Q`l%woRp4eND3I#eV_r54 z4G-YH55A&$ZZ$^d+Rv@%B@emCz#=_BK8G-sVf84K0p=K#0qSiiQN9CZc7G4b1o1w6 z9DV=`;W_9VFWzw6C*h~~%Q*3wG{P$!e2&LIP)=H>Fu%mj(#&$RG_xWKa@?H~LIy2wD~Ej@e;K&q z@DI|KXsYlz!~mJavB?(i7A8=isp zz;9p=c%2bZ>&bz%nhYq@OfOgi_J)limtx*_upb--2S8R{@@7WwY&aC=LMg*MI9z?V z-B@7oq|THbMr6cv)G`FkfOX+aC_OeuZP{VeGk7Y;GGiLB%%n!e%33d#`lIE;jAU^H9@rCwQlTk8u+t_kiKXRvb-Z8*S_AxkZo-5 zX2_nfm!+G=#;^A4P8KY+)fMkhD{S#xObzzBE}_JXJ25W2F)RO@Aeu?p^f zcm{Xbd7r7*yBhzG;Rg5#ly3MrWL(s~gooj`@C5u1lnsI_@Dun0WNgu{!kh3qlwS8U zY)Hk+i#xqZ@K;ECu`-eaZ{rsIUvPutzY*TSoewn^-5;9ph@}ujmI~(hxanf#w`Q> zIQX06e+%BHrtdcH_1F*S=-fk-7YH?&ij_>EGvHlt7OV#EhjLN-Ae0XHunO8^)HZqG zM!olq9>KTed+uTTpND1c+e3F)gjq$*%Gry%7F^{-w;Hy?y#|hiPe7U7 zHbPm(=ex88>tF%yP4H>B6>fz);d4-W<#xz;m8CXS_b<2~ z%JTSS7y%DJF7UNiU;=y<%DD9!Apq;_(rg;~`V0aEjLDq3rcVZpq_2T{v zE{EsgWAF>O21@)JSczF4&%iHH>~$2ZM=bv%@N4`}!uR0Ej{XX~f}5#W`yOgE_a9&d zcokNK*I;#c9oB_6U;_LFwuisM+%6pa#=%hdJ7nCJjY#h@_$Pb;{srHLe?vwQ?GC&Q z|ABu)&5!*R7xO%fhAx-@{a{z56#FhrBq~y9`!>G&C(3 zJ_ES};iX+@Velnb*-u+K%8z*+_e59==D<4eVOSUD!Fo`^22eKY8bRJ;Y8Cw+*u;;O z&FdUALva+c?dLrO6Cf{R(OSTtU?ThrN}cf*CXF}bczJ7|#`|x)yvj^o^6TZTPa3aU z@iu_%U^6K8iLe9ijxY^&haF)**eRETEDm`0q&Ek4h0?7h;3JSXJbE98J>VwT4Q_+H z`N_K*_JaGN*uMh%;Fj+$^@F!zCUpBV7(u>6ZrN3XgK*b^xq~^V%fV2{+hw)kuoD~s zGoeI02#&-(366#jz%g)%qvwfTZ9H!IZp#EH?@YcA?uS&5_ZXZ6{{tt(f8bOY5J3N* z&OsRC?F=aIfTSM1jUXGX-q!Gb*bzPiheGPtI~LA?GvPcazJ_l(1~MO9Qpa8~p7hvHqc|ETRGqzqTc5rZw9q4Gw*^Q;0}kMKyFZYzk6 zOvm8%!WwWJtO<8Q(MvJK;obx5!K1K|yB__DgC=-<02vRxUqQa+=VjAQYYu;at<^iP z8EXtLkFXpxA{(@GYk9K%?u0rPa)ZR$)941}lAqzz+Zo=iwj4BSdyc(ox9}LdH)fy> zMcWHXf9b7m9OQvbo{y>UI;)*byqPhz{*W%M4TQ4x8w4fM!LTkI3gaO|vsD|TU_d<0I0E8rBk3Q8fdD$3QS;qe9@GvIfSG2hGG7t64kL)ls3 zE|0efd>FQXb6^`d4@#@fg>sR=Tw$$p=EJGDC7~QBZnE zgcvq778XoyvU@4F>1rVD5blu`Z8~gh({t^IdvxnTA5KfFjqIhZ$)^EfrDryRm0)8S z4x2#fp-rK5?08rQ^4fmua;F7sjGMRZdlMnA(D$~1tZBTdur=%o+xSxp=^Uis(Hrs> zdaFx!fJ1So!ci~{j)5$OtP7lOP%d!fBp-y`aX;j6k>kGv-i`k<*aJQeSwwlCg8W{F zbpdoQKMG;(`?0FBc5a41*(l&U$KLnhFn9?Lhu^|1HT^9^8CQ>}3P%~jvhkJ)V;qcw z<6&Dk5zd8^A@@(Le9D9%?#*xte9m$2arDRGH2hCF?qbI+^TG`LKZiN+KX4Yj$;#D= zSSASZa8Yab!$2tR%1{cZF=UnKO@@*{n&aOGKCCVuHKuy(2W)ih9ku0iJ#0`eR#Ly* zXtwHaKJ15k0h|r=)njluZaFP+pMWdXJI9Q+rvFh>{ZQG6 z2z?xV5dJ)iVciB?s}hbgLGS?0-Nz~2e7t4;;CDo{L<6W2n--9x7iQQm_li~Zg7s69; zJvalS==&jiTemckakY}`nJ)_^ziu1h-+p<^-nR7jC=;=j(b7V0eo~GLcEh5~Kh*jC_LJ zM#Agla*;`e^+3iWQh5c)0i+nYg2?xt>L97eKqLoQjuawCkt>K6$5|usNDpKTvK-lp zoIoxjw~&x}q=)oC#vt12&Of|-))>yK)rxo-Pn2PdR`5CT| zPmMb!k0k|vVazmmU028#Jhr>x3uAbRBk)2QhZhI0_xbXIF%|Us(!v`ynq9P9PhB(~ zMh7aZ_^*tyzT?6&$MwIq{2%+;cu{`;!b)`DH^wQ;A=yf~WYn^L8YAnnF;5b_Y&>A2 zvYPa*F^c04zAa5B>p#Bus;DpiV`Tf%9C*d@f8&akvu5Af8MG1nz2(aNzRZaS{7~jx z=ah9^$3ao{y2{=+xh$G}&B%$%okK~lLbfAEk@LuHB)mSgf%HHoA$dpvasWAx+(fE1 zpjMGgWD>Fp*^Zn48i`mLP@5QRE7uvFfgaq#&8dBxF^*{0I^+9)C`c^}k?h?g_o@hx$}rH8b4JcC>qO zFSWUv*)()9cQtfksm?QpLc@M=@A?9M0p~<5eh)&P*mK?yc0qNCFl)On61+`6H6_BV zZorih<}I4T;z+YW;8&<-_p@VE)Boms@E=5)p`ku6Um~Wu5y=l1nDRP;dUrkH1c-E= zm^5{@vb%p*{i0eOMRMG}c8~3^UX3#2g2whQ&8?yK#Z`<_SwHG7UhU3vhAtHvZPp8Y zz_F>~MCVcoukoJ6q0wfbXQ!j9rSy8dwlU?4fDmcJ{7&I}J6!-JHk$cI$1+E<@99CVAL zVtigwF=({;s?S*e8v1;7W2`$$ShE-wO4!4yTK+ z+d5o5&K>3FZyyc}i1G`t4o{1($3C3q=DpVS%!bwMZ-=pcTT(oiusG#bU)M8#bKm4V zqMPqatEI1RXvVr(%($PvPgQDUMyrku&HDa!=&NdaLz>7!wEG?H%Vo8fMY{;?aZB6T zNtCObl0;>$C+6La_#vdcMrM73h;Vc?2x55#HZ~KhBsQlDBRPnCTVOwOp6u<^*Ecm| z{nrrTPqz$Juc;Yh%0aK86=PIj1W&w9YibUrdsy!|yV%qW_g{6_m{`l|L8?I3co0+x!*Ac!Q>OIZO22mW8gqJ<35Q7T=!uQ00-{bPV@NJFi z5>HUB`rJFwOpP}i_;J8j+`f2-UyI89Eg)0{JnR>&atFABRGo+Y!qig(+@AFbW{Bql zCkdY07yrfyW^`!XKYhvCqsHfIP=Z-I^rDh|tpCXcwzYX<3 zt1{8QB$@&=ZP9$$%B&m3ft8N+B?Tf(sbI}bT0abkv=2WpFg=+-TL`oazbBK+ME9v^ zo<_34>)0@WlCXxsiwCh5&LIP)~I1^N#t1)d6PsIwS&ME5_=?WJ~{+cuKj@DDAa z9p}bDxpTXy=FjrfV0vxR-mGd|)YPe^6|1PB?ak88wxT_eY$uWmnyKFC;VSJLH_*6w z6u=#;smKnd?}zVX#Pv<9Oo!S}x8z-)4B;KjXpcRr$_qlR-`zUc!Cd08M@n6rZ2yi+ zR;pQGG6WWxY32^ylo4r9M{};pIH8(#GG8&J*Z;tQhpx-n$hNihqcDd%o6}6`rys24 zjo&@Gn28>GrDajWe)nj87crClF9aiyj!>e7*9;S4g8jtx$ zsLXEWT4UMYYWOuKAXhrMw_Co>cPOlvU#Fy-V?1^vmYXBi&-WcnHw#T^u)%lpdt`at z%_XL^EL>YWcJ1og4Ey9y-p$F|H6ni2o7<<|V-7T>q(@BPh3J>=Vb-H`EA=ola&I!R z1@M$cERu}$My4T4knPA}5y?a*A$dqX zau7L-Tt!?-q?x3((vmsojf_X;Ao7){?Z{z7zHW3C!Az@$G)6ijLtEKzQ4Ux2pRdHv zV`P|Zm~w|?nBRa7z04z(adhvWnK3bchrb?+@}*Z;W*DV{Dmbi1Gd)b?RO--I=74 z)u)&Ras$Bqos$8zx>-9Z2QCawk7InJ>7X9B2l*x%J^*Jy=~BXvP_^oK^opMAI3AU4zxUL1se( zia~%q(I>lA(+K9+kio>$1+#Yst6GDJ2bPQHiNVCv6@$xz)tiIOS_Uj<&~gX{+;nmC zOOwNg5Cbe{a83-;F^CzW?hGLYSk7SjPz<|u$;kgs z(`6hRqFxXSSk9tu7Ey3N$^F$3m61gzU^#-G5Bbx zI+V>h!g2;J$5PNCBPi&fhpORYv4G_)&SBvmOca%dsXJrI1T1GTeH;cuFlabTZ5&4o zu$)2YcnpSO&~=zbqny*bV8=A*`+Qi9d8E_BHU}l~q z4n|bVu~i%lnU>?cI2aQxNB9&R40@KMhd3D3EJvO=7{M$@@jQO)_3#w4nv7PK&rMM? zGFgtsQ*kiY@jsNs^9YS%l2Qf=Jjl{ComW*T~ zlaM7y0df#Ii`+uwd%lTC4`dp$1Sv$0BA1ZcNO&7o1xPxQg~&a%4ak1vBytJ4jYPL) zcQKLsP(6?_h}@Iffb2(3B3BTN-HB>QJR;wZ%|d1)tB^wEC~^_Gg@m^wVWbB#2FXM6 zkpoCEas`ps23AAjk>2eGvdZEh56MRkAjQZPMC(8fkwl~iG6u;*@{#?>N#qKmr4k_$ zkEA16$n4bBX=m2YW?LkRotIzurI#{4V8^e@%w}a1jiyQdzcj~06NBdNe`^{%h^9K4 z`Ty3e5KRpuIA{~;7LQMA~k<~?Lq_iM3<^^m$ziT6&N zf1^TxI{Z+{l}VVoA=ccVb*~|shfAgie#_=z6tz*jxJfN~m~rjJO+~vO=5-u3?1cpn zkClu%vo)Suc~VwgCCmD&b6D0>1eTxuQ|ziZfnj0VTr=K730R6&&JUB!HG3HI^Hqg; z<_zORzM41BTxQnXN zJk$3xLYGy$Jc|B5L~zhacz&K4*5IHMi>%G_xNw)RQ1>C$lO_K420(#&JKy(vxSYzIu{8>#9E%F4&|9uRQ)^L0XTS- zMxCd6`Um>9UoNXzODLD`iKlM5+PuU}3ay)7S{ky``?OUW>z9)E0}IVy_0ub6kct)O zC*pi;j2@&?#d&KXE$QGnzYvv$Q-4~`f5{AE&ZxPFP5b3b*=0%R+|^ZiUC7?0W`G(m z&f-O;pW0RI=dX(KBh;r$Dc`4+yh=?~T4q-Aw0ANTsctMXtEqO&%rMWX?sg_4Rp?@3 z=l7{nspDPCD3fjU)=GDm`%x-s*}i21*Hqq8um6KPyCmh zh>S$Gq0ZM>tqq2P$IWT(i$oXr|4{ZO@Ht-j|M$II*CpXj1K@gEdv>0oPT2d8_eC?&hVC+>9#n91WMm3CXN+&wB+G>l@PPN)T?{h7=um1kO z=l{H(yk4K2bD!^W_WfMvbS+H!sr+l5~8d5AUS`HP_k^jG%5Bw>+bF*k?mOz)Lr+p{=Bx>A7>0h(;PHC<}F@H z-@$1TBWdUV=poY6c&_g;C?j^t;lAVuxTC^`B(WDpu+;%)9EV%c@l<>WZTHUCcZxo|~*L`f3Q>AT-(~tyjDH zfm}uC4q@ajS?wlVhEVBo2;+9?a{uF1oK@TE(sK@E9@%LK^XuwehxJs& zlhSOxKQ{iP*JHLMsxah@&PW-Ztu{8SYidqP`g&T|>auM;vFb;xzIa_88sqI~msfW& zQCnsd16n7q$L=LNzv6H2qX3vsJQuve&~o(7lJ&3nd1#PK!?n4OJi55SKg&m!m|XcA z;TpF~zRjd%*|3pHO3Is*tBOKuj~E9f>QyK!c9lHzs{eCu_!qBR-bUN?eUrcapp_KT z9pD7G1nz)9H+En_A{Y$vK>^qbj)6b$j*x!wAjY{MS^LZbk!`yW?Bx_z_^SCJ@sQkv}Z z*Yy`Y$%WLHPF5G`y+z~ zUE8Lr*)U|>esg$WK2%q>UyUvB%=46dwcp<$s6MN6x?2PGN>+DU$+Y5UEiW&P#L=p^ z{Hs4&^5f_@3f}P74hC&GRrr)QmDFuzEE~N+{b}H$`7K3%_17vs0I9i6Qaz$(lHw2G zMtJ&yfUlG(k(?eSG(YHR>>U3rDqTF@YdmjB+9cxtvD*r zRl!oHQrI(UOUyw-2!(?$OiIi+}s+|YL87{|5>9@mG z0x5&LxRg=fGH9@B(bNU^tG@aWy?%QNg+x{5hP`En{91gtH`KwboG^(Jf{0diB z_r{{@U3B?|43nW0B8hsF*6SNra8(q;)d7Ke!F3}-u~3lykup=r9l;1F^v{uVH<*edV z*(_W(MHOh8XeDg0w^6ov zC8TxQQ5A***ybo3RL(dlTZXb7Q#O;Y9Gka_q#vT}RguC`zUtIQ??HH4QK4{RP*+Qa z{na0cD6@SwORRJ{s79#DeNnmmCTIM&{awz`qL+goK{Op~ zOV9(Pff=9(>;b31k07ci$qy1iMo)F<;lO$3yUr#_=L>#yWNpm_|75zTs_*;zXpLvU zS_F20GH@N-1JS)$WdSK5U%b2gvw6alVt3IW7s+v00 z*Dw#+tg7ho)AO**{fsi^J0B|7sw_M#-+bn;7o#e1J${aJkyYh4$@c{p+Rmz$sGjLz zY5Z@7OzmXizp2T?2-$}7Qv7d!qMbP0%~4T`?!mwLoP7Ilf1TM;nss zg82dFeVG5|9IK}}mTzswpD^#2RagB_`8S-m?z`Y_&4_FM*vMt1{6SC#Zju9kFTTxu zG2(N7bt9PyGU}u>`P|>YKk6i>9Ll{9mdyFwzrEs7+r;bCKfcyCo;@i;uUCwklV#O) z600wS-6!R(>kJ}xbH#+p1XVFrYM(N9re$z=l|V$sNcFvuRbfv_(p|2sOa8KA(IHu; zed%vlozrs0Q+&d$lz6z7epJphsXEeopM4%FSuVq6a6^ERc1nz|@G{NjR$kJKaeDjQ zG)_*j6^}J3ymGym(|k{$)TzI`Osi>E`cF&YSN>YRBd6PBRU}T!@&8GlY?D>Ta9VCb z_MVpTul=#VQ<9bWKt)%5S|0h@TBuR$H- zG06=bu3x|QJFl81OWPa7y+3i!c~?F)0u5vaD+kqbxV}S0M-^oZ&;Q%ng8c}x%5JAU zRI_ffzRous$0Bb>eB&PzZe^jDr?k$k6X{2tb!x z{#mWUl0BXT&=I77OfUzm1be_KP!4_saWeN~27k91rfbeawJcG64}s6ZjP(bk z`A8R`R1t1K*m6KVO>+gM*$)IV=X(OV|A6#OcTrYBF}_9Q@B#T@f{PITU-oUkgYbzR zNbz=O-?nO&<`n&FG7TQ%M|gfXARSUQXYzVYt|-D?2vtgCy_?YUM+iQ0yLyS_{a7)l zz9w%df*(SY68Y3ksDBqiO$ePzq}N@S#EXhh3&PwIsXM`y3U?KuBZRFb(%>h$EzDj& z`BN$qcH>VlB*F0LLHYYnE|n2KLwF2ApM%ojXBT0bBK#4;po8+Nn{W++wE3BY9d%G5 z@3}H&KPanzb*Z|n2weGO96Kn+Z!U>Gzd?8s!li@q%x^AK|+gQf0!KG5y(3%7X+v=RY zc&fAw)2tUKR1KRdxrWwI&P)#v1T!Y*XQk(d7AL04UPF7tK45W8zK78$MD-O^SJK$a zE|u<;w0RW_=PJRl9EPYv@)HdHs6$>!jpxPV&S6@Vcbf7lIxr~59FnR&XPWYW!EG29 z^G}mSVOlK4<}jC^UxsN7D{VvNc2v3cPN?hQq!(8?8Gm@wN`46@lU^@}yVC2p;^FQe zqucLzDpl5kLB~mTMl}h`bgMI}Wm?slU%j^F%8_3^#OW3E=g6i`+~3A&Q88emuXdq|8!YVMQa!w#Ql0sPoa9a z>2g{*pLaQ{soiw>ML9ot#Nt+7s19$sv<+~%@O0@Pz^Bf~EUNNJ&E}>{;p3d}TpQ4$ zgLy7mm`OXXL>e6rc^_^%-woi;WS4Vg(>Xmti;c-4(Nwy9F~&=x786N0Z@8#YCbhqE&f}A7m3k^Y zR7X2q7DZ|;fZ% zIbG7LYHE{Yo1!vHF;d>KI6QyMnv^YVXKT%z20$XBs3tq%dFmbM5T!K;f6C^qDYyO< zUOl4svsTDeaHh%JC~|U|Y_yEymT@IYORA`L&4TC~$&6voN$I=T+uj}rJFUWP)HDM0 z;_HK2bN~JH;vC20uv<_|^!MS{?hX7(tfocz2RgK@YFeT%?||&8rak7Pn{8cFt0RHx zT9l8jwQhB-gO8rnbj(qXbe=e}dR<+M^U+}*s*czv2jo{c{Xd}e6>g7_lxSK3CcxE6 z^cm4`($}qy)|!VmDN%{#^;EYW6fTD^yp!$L!*UDMz#G+})zBUb-)hsu+Tfc}LreD2 zWtri*3M0?%rbpvRR82ggXM)h&JIZp)S8jAYCi9M(Xr;S33WJZ{#dO^BKGU$UT3W!n z&=P4=3lVyfzO~?@S$7&JgOSYT+S^v$is%UZ(g0&7=(q@yl%v+e! zzqqy*?F%cFr7yG4+NL(?9$sqa!Z3dMqDm#ZHVH>hVCBs*#nYHyuVj%^H)?C`!>wlB z>se$aLFX8ffcAKCjMmpj^LsHyTO3ZCX(sE7;(diB<~en=6TUyZsdU$ov{>TQ?ah)| zvD(?nzLa;QZxbR%iJaa6W|i~5k#fH2fBi^6fOvyilqqbkX83-v9mM# zGjauM!G2H%t^;iV;Q*b%K#&g#zz%Q%l!G5Z+!KTqq<~B?53B{pz(?R7h-PD_BS-=H zpa5(I#|C;H_FTep2Sg2`R)Nl7Aeai4f&JhNC|xs#^8o%nMnt(kX-oa>}@VlH3h zA?;k`m|>{S2L)gcI0Y_&J0R*Qf(QnK9Iz7X0cGGih~nTwQ_vL*15?2=upgWOH-I*T zG#gTwbkuqcyO$Piq_73{$!=-VORMYuWH&FBt69O+URp1LXnx-D5nK=UhwGc&>J4%J zvaC1p)KWniKQrk62Sae^s!djG^Q3-ntrmN%oqE%dH{4@MtJYr)80JZCZ(9F(lFlBc zZ0N0p`Q~}$*O@#;ajdtdL3q2j*09+oTTCfci(~V=p=l*kTeDwKJ>fjY4ER#&Vpp9Y z&S$;7y(zLHnU-|`vFNr}jwWl)xrr3Hs|Zg(czUli=%Y0VKE2lps1uF(>MaXrj~GRL z;O9CWV={^q|K$HWf7`zB4}yQmUK!fAV*ZdKs~|l1B!pGA0?)YY$)oeE=b<++B)CBT zPjo#FU3GzKq_Du+4_hF?e)J~`q-{Uaae?&dNBm#6bvdcLK#ug|W0ST07`^n}7s>%O z5HV>g=rV}zt^u?|tM-;$9H4dac4$x8>jBb0J}3Yiz(H^U+yG%iJ)Q*6 z5u||3p?j0|c@I3PHSkd!`5?81bR4WL$Nt+84iA?P*3@#CY40&a8{q5ikv4f$u{}ey zz7}DuL!U9!I#vlQ9&Re_H$0@F zY`Dp?I}L4}N0`;xwC}L&X29Z7P0f>1Lz-`-hBOaOb5y8LW9y}B%6KU~&W8qTPSVq;+rtfBe3Pzg&`q$`?A8BJk0XpNdcN}ZFzce-^ z9mq7LQ!_(Omn^6I$C+V&#WJdnH-F8xjPJ&WJj zP7DR~UXFU1DBH}G)a;P{^6U^#@+8x4#{1x;PzfnX$k8Hw-gLP?Ph%-nUdh*LmTb$@ z2Ko8%+muk;W;|m?_q}IKCo>Gm&xXQ(@Yzt9n@+6=XUWQ`+FJ&yOo5!)p+H=kt@M@L zKSz5YOnqCuCynAdbzw;I`a;d{dNWGCTcka#`j+CMFeEN9L!qKkvULd~KUA9q?fOz} zdxe^Hi5(761W4R)6fNyK?Ya|Hh>f068JG~HZe$t z33LT%U@9mAJHRPW4(@?yI+&KAD;NgyK>^qV4ucEe4hW2b4|D|?Uz(TMA90nJ_O%OH)KF|@QfJ`t4tOPs232+JA z0a0Vg29O8_gV{O!TL?CQgP;st2OgGLYlDs;1>}H*U%E6BydK|F@JwO_m0gAvL za0*-n_dxCO9Pa@=KpL0|mW}uH_UyrO3S0&EK->fdaUdCF0CnH(O0XZC0XKk_#monE z1_MDBn3q+Uw7B?;mS8kspCE3QG&!R+@W;*KVU_MxrpU1~+9ofj_t+`NvnAAo+sY%5^ouuFyh_JB-FV4$)SXbmt2eU#q$;8wg&RbfGF2d_#}&60@=kB$ptni8(=3S-lL zfu&V(sG?9;;@>ByqFv60>8x^A(%#p!-zitcNQt5m(V6d)<#lDn`>b*_kjwA0D#ztH z#;OIsdyq&~DQ7%*6FI6CgMY7Qn_T%?ojm(MyX1R&R!Of9wa5HEvUcf3ZI_Rv?ed9s z$j@O&`K^>?g6K{&3I#!_{v>`ZsicBKqwg{*>1vKMR*3n!BKM2O^Ck&;aLcW zMoIT8E>(*ZVJd_-N69`n;d@1x2I0sksr#8rBKJ_5N1L6VU)DH zs`ao-exA%#gxL^&8714@gu4(PoCBd+hV5nRQTdZ7#%fmRsYL!z+6;=bLs!iS<%lc2 z`>WT|N?Z@9l~@m`mB?O;a?UbtS%&!nJqnR*`?)FE-!gJ7qp-p-5A%iT0h9OK=d7z) zi|Tn2^99kEOK59n%41)+B0g6Uo`X<7Q?|PaUn;`$5ISZ`wd*d4{?{SQgOHRd)7^wp zMVJp^aHf3bCe;5D!U72CnbPY^m#RgI@B)OXnX=DKxTOdSAaS4oL#>p0(>~He( z44KtIt66+Q3q%$`ojA_U)ycB!>x$WOo(#Hy_=_+s7$>uCxC-rYMOX@9-8lKmO=$HE zgqI-P7$;AD<`_k9ybx^=0juj zcxiXDVgoTxra=f4LzrRflVBDbh`n!C>|Er@m+;7juQkp0kMUCNmP>lbEu>c>ecq9t ztE5}pa!H?t$5;i=#qo0cma8bVy$xYCge&7^=xrBa6$DB72LH4P^44uvD(L?~WGy09 zCP?f5xCpt5unt1I39{NvxU2~4A#|D`#vONQIr=tVm!{p(0>$5HT38y_`>Jt`+?q%P zmfUegp!5#eya5$sZ642LnSRF=-e%vE3L9Zq>?ldkM#+TlT}oEL6ZtAUg&`$FzjrAK z{{bbh!LZv=a!x7f{ew%%G218&Q40UY=sh`71 zoe6hcO6uPwZ??nJI7_H6OkY{{JJx&$&(sCp@Dli zjee$v zo+|?0duZ4L&njEPnV($|mG=e|idT0I zC*-X-uB)ASs`^v5e1RS+0-d}lcoPLv90gbMx%TP9+phS(0grJQo*5J6Q?DKheOn*G zM<5(@2}jG!DSRmOCtoNCvJFP#D2#tKHPrcESnB)H^;cLv`<9Nh(*?ol_dz)=?SZ_aO9eg!fKkZ@)?vSH$0j$0&p6$w~5UW!*Vnktdz15Seoj z*4x6KvGQpZSI~CCV4R0x^CbD8ic7M70B`>ZVW;Em#_5Flf!VIIUkHzJ0iHJ}$)SKN z%p87h70H!}G}h!Lt`0;}dws=E%jWE}t7mLAV5A zN{;l6auHTR2waA+)6sfMY5iA}%jbw7^`Weau7&M)m|D&JpGV*8?P^;wH zS(H92qP7I0U0L)tJO;Ni8`W~<+v+aAJ4GXW4Z?$t@ReD#%nRMZZ@^=G4o~M?`83+q zkhHCV@D~u$9O2yA2+yhE@_8pb#&vkcn!+*iT@Bs2`zKGD)kMRWP?tCwymM&Szpm*@ z^^NctU%|6HSEXBR8DCRxQxW@^T2Q}+x+hm2tK~|x`HFA@LP@UdauaST!Z#4ga-~jf zm&EYe5Wa=*X|61A6HY6_cMvM)$?e*%0^TWx;NOH0%(Iiea4uD=N{lP`+u$*7!4s1w z=VM&LF?A5W4dFgV*!vv9UnAVco~%Js3lGk--S;}H@sYapI`sD+c%I0UeRW)#?<&oA zAPjXh=PJ$rsN)LOxLAVqJv<}xWO=Mh_+toxA0Xs7!dH~=Ut(RtJ>wAmFFb4WBrnb- zTnZuZBZSu+;r`Dfyd=&g+$W*UBX`~;a}j1o-EbsxrB$*L-u{w89+BP(~dN$PS!930~7B$o#XL^0E zq292Pf#?1yy1a6&%A*x^HmMQ8ssu%wBI6tB4T9PfE6>!zNE{xNnje+x@urne9b@&n zrgd%x=hNz$){V-VU|RW#C|0j;TKV)bR&QWh&9#z-rj<`1WA#R+wSPPejZG_SCb4=G z)5^LD#oMu(YbOD3sjzNRD_n)CS%{R^EKZsQXMk@%NE( zrSgbn47ZG#ma)zmNDEiW?IHN46b(719IsuABvSV)x+@O*c?vDOHxBtPm`O`+GaLHQ4ThAENW)@y3I09TgI2o z^!vj9Y%6Xcw;HHBB%32yTS;Q8B2PEhW5UCpwKBPm%r%w2tcS_U=6ZDSE#9wDfl(=~ z7OYC;NOQeKFm7#$Y7&#X{BOJcy6|%jRs{(%s zAy^qg>vrQPyNgXa~bDzh_8p2Sc@tlIPm#<9)u`neuIW!cw1AKl3KP_76htXu5KX z;DdxE$sz4gq`?-cxC4}QhtjeGl&QAR3`joKA(wU_s4Fw&(+&ik)y2wx&_DIDh-ijP z>qy9~HAAl_#ySnsrla1}$1>rkPcVndhr!3v;MpGh*w9f=_OTrJZAXI2>YvoBuEj|E zPI{dGXMWvZlV4e#5MX_8RwsRokL5h&P4PqcVy)b%Gbif#J8Ah4x>%MoeJO&$H)Fiz z%P~b^$u06>d|`#n@@3$|dYq57G&9%*55v#;+4_g|p?+qw2xdQ~4wWV<>O z*2K<*1hytS*Iv0g+UqWOT$#z*60zGjGdsAaLVox*caQB9g0#oL5@BG`)=E@ zeHW6N6)5ZAW?C2cFW98RkbIv^kh5LjziT^oeH4Dyi7ft{N8zuVW%+ytl8@D&PalQ9 zhwV5p5&nJ-|C~hlC)%V-kbErHe47aWa?>$ZMknc2{i_`QWl8Xt*!(w=;8#m4N$_8? z9rGWD>MA;nrl>uyMWW;<@e(f_66OIbJgD`m^szp#scJxAksVf3weEuBEhs56aP&vo; zA*(k6)%ayrsZENOz%MfnWxerYFmtP9ykJ&o#UUdZiLs8v+GM<7(zq)bFLv5qwCRHy z=7N^Mus%eZS)ZA9MT+z{NamsBV|_^0D>f;vFRGZzweCwcRAF{vws^{s*_m0E%KF0o zpiODn4+>MSF8yFnvmN*2=pUP_%kD0|7%A@u{}P+jIR$>^N_|t{XI5mYKY?R-i8;wq ztx{owa4tPa(eLw@p~Fm)_WcoK=2KU-QEB~A$ZW@yJ*+6fJUQE6@8FNgv-uMS;Cf%4 z#h*L?ex@Ny2atlyI;;e_Fn|;s=?Da#Kp@8y80uryCkXoHttfccLx23dPr8vK5r5K?H>{x+#-22+AP7U>T%$ z@D8`Q%W(5E+_v)m-XJ~M{~Eu3Tgjs7=qG6b7)@J#EPImR?3-M&>q-5r*XN%ivj!6` zZA!`Z!TQoFzMqQZp$vKgI&IUlO&KVrqqc<0G7zRq{x*XoY3{hTAFaoQ)9o@E@Os)= zm$hb%)-z^%vf1Ya?Li921oOaJa1fM%8$g@n@g#tbU?9i>3&93(7+e51K^Vih1ke$r zfK0FqYz1ZDI=Ba-b2*xl%hq}iEE!-1SPAxkGvF#vmkQSg?Ljig1nPm|wO~Iu1FnL5 zAe!R`Z9or@0cL=eU=KJ0t^!X!`apY-3^McC+E=fItp)o*8MqF#DWnSM3%j9Yx1z;060WN`iAo@9YKr+Yz^S~x>7+eB( zK<($rGB6NiJb84LvZpaARuC%{#34B*i>bzi^@+{UArFj0U`Q=cSN&GA8{oJ!_PCd}0m`Kl=H6-N&rdrmKlvW!T=A za}$|@y>Go`F=vmVVGm}TPJGm+DCP%kRZU(#Xj3kH%*IU|Q@CMdN46f&O`Q__p3mAY zWb4r|e92oE82TiWy|HCU3z|WF#X`|6S*LjB!qdg!S+|gls^9U%GPCiqpZP+(-pNcjIf!MXe<95$>(0@cSuzcR9Lr(hJk#;1*lxje6b>%>rb83XgS?=|cI5)gw%v zwmGH?<;VJ{|3k^OTnYz=DPi;N6F5;<`V1=!DK1}BaYiT3)n2ik)zS-v+4G@?&&Pdr zYD^_0IaR1MxbdKpSp#aymAib)cpsQk4)9?i+IK594343QX$IkRB7X#C8bkYEm%S_ z9=zd`79TU*yf;-3_zvDMQ(PKNW9!no5ObCcpGJ}wzcsI0+mUO3<9tKE zkZ+YEwZMF_AaOR1nP13=**H?TO~*aTQI+1=`eI+h>m@_y=wtlhBr&n~dUUD(TO~dw zeO|xhKSKJLs{(x7#^s9h^xA$i5l{Jg8W~|8&%eJZd2GHuD{OWTn%!X_9~6L1;1nna zf#viSAQ@zU0A49I6(*lzGvR=E{VOxu{LYm+W zEsd(r$erq&ATO#F$ByR_oWU1c<~p&enhA3JWxcnznM4#()+w0%W zWIhz56_is;WLJ^iBzTJIr3$+Wx@sHhbDEaG)wiz|TcK;%)#A5#qo%LESI!2iFiTrO zh55TnR_UlOGgp}YpI(9gyxM9+7ueSrr4&=;?#HDaE>@K*rVr$o$16!;e7LiH2}h$d zqllBLEq1kTEkRLD01Jkzms%%dW2^;3mBUUwO2coJ%T=p#VeJNCM*Z1>l5a(C=k@J= zp`^hoy@}VaQo>wF%vjBI)QYv&lWabBDa%&tMZV|)>pr8LHM-_&S5WfI8vUX-9B)Y< zFPG%pidPqDt<$@9Nu;n11X-W}YyyYD1#k~U7c&R}JwO_m3f6-C;7qaHUPoEtZCYa^ z7uA?)(PKTS$*+o>VA#R3OOi_VIqS)S&el224VK-^j$@X6qv9#I?8mVezhbhh-3Upr z>}oqg5-q#hkB~IWt~MlOj%8On60*Uvt1SsRR$;f!b4t18pf)Dt-Ycx@ceZvSQkt-s zp0L66)!CZh{yCS!GR2YRa@eCB=C~Znl*0y>!%gLI%;mtIMVORZ4)OQtvBeur4zYy*XS`}A$oyBSI-O;+WxQ<}*DOPS&7?K9jBb`O+A`)_#%9ZS+cK_MhQ7&? zvy5(*G1@ZbTgJwdbeT7sR#tg(Ym=TJm;Y!~vFyWX@%nAnn;EH;w_sJ7wOMcA!yIv< za(BtuS0%dSW;dgeR}%iLFLp-7$NsEG8)@)AQB^MfS+5)ML{;mPMb$=dbKQEqp80jd zBa%Lc&ju0?SJAwW$lN(Rn31+sj|#>{g}!j4lkh;>%AjDV%NbXk`Si4wt{RR<l71r)^9p-dn26`0aY@;1+JOQo&QB8w^hu*|wdG-%ljv z0t|K|l`7$XL2@LLouZ}PUn-6%q{@6n7zJTawCwte-aLE|mtrZEHD%*=y?R7`+qM<= zLOm+p9Sqs6@l2}p*+IjXfoSC#n)F+)*N}o8v=aQPXeCr{lxXc&s_|l?*+}S-rd72O z=0#A6>W08rJ<4=dErhP(k|^eWWi``k?pIbft>*oZYj?6in5gb;jn!+I&Svv)^)JNx z&Q7K(i4wkxQkf{tb}=hS^oIJWXU1jZjUHunCn^^bC4CnI(+uwZQqgug$V6F%f*7}C z`Y5Z1Q~8o8=XU80tKH$IFem+0K}z(lSRJS%3A;&$-fJsA zd{eWvM47Ui;peMdFlMGb*~zFEXFezTBN_kwZgQ!JKBla$)ZJ4t{7;pMdl>$YCJ%1e zqLTg+Tjaagfw0cKWlFtVeu??TeS7s5cCVW%L-xW`3{R|!r=C>Gub9E4 z%KPvbWALkOJ^6L7-a5Rk&C63wJDKiuz7p10ChlWPGi(=|o954L`#6l_6qw8V@I>%r zyyMC6Whx-Ay8=7tbvzl1Cv)n_tk)|JVL61qR{jSnE zZ9n|u;HR~Db-&&uTu-oK-$WYk*Xzse{T!5WLe}gJ4hyU$WUXu_`nKQ!O7x^R^q8RI zsLBS(=Xp`)zQglIRyUt2R}ePF<5Nk3R6gJe@}L6{CP4T{g3LOgH?RK>Te~_1fTQRujH@AuQ{nv??+g-sq$KWJ7t0o)DaGb2$UIt`a<`tAaJ?Ao?bvZ(;+Pbx?2OpV&Z? z79F(S6-jd!j!M~ZENrOBqZgUsbS~8c&G=;(Re!K!EMsBtcl>wUofc`ny~qBYv7@Z zvs0-u7ak)Ao);R)_Cu~z|6UPtA-vp3>b^-5y=*ISvag%7vhw(w z$mSvYXk+>6&5F|`snYf^gvk)rHI|`=T@`SfBIHB(XJa{k*d-Bj1i};u7aGfBM_dwx zitr4CaBg4+t0A!Fym;&EHYKzP+U{tTG~WDJ?iqX@n0cK zgYZ%l>HAk#f~C^9=i!t>u3D z3+Fkjknhrp*2FrPpGF9##BOm{S&q+3) z%w0h~CLVX?o^nyO&O$nN8Mjo=PjK!rzjrjLh)ni6(QkCvN}ye`_~7zI4x zEzUfgv-wrAQ&D_edcH+4AD7W@QB$qg4pU|4TZCsOem%tC+$>k#Vj3XVI!&rH{u|+$ z1<&AS()Vu_v-DIcRD{_OMmLi~e{&_g_XLDF5Vkav<|kYUKSdGdLO9t>)}NrkJZXDd zQ;z3T&pT%_<=QN{JF(xKVL0yrrb?%`5qu88;^s2)ZI@Tu6ybRY>srWpHzDR72=gF> zwUo!+q3mFe=vS$>ME)G+91Nxng)1;0u0c$_%=n)ZbsFm=i$#N4O5KwT44fu0_aqt@ zz&pN`tUl=q!xadD7a+`GmS!qRT8WZ}qbe50Xr@jfybzw_tz`Nsy?L|aHm_>=ikf>o zQ7t^4Kax+sRJdDB>re9TDZO5J98)u;x~6r1eb{NeGmTZZ(`a3U)}+>wecF}KrHZf^ z!qnFC*=bi;oBbWa5(v9m%YeVTB-SZH0fcL<<(yc<_Fibw+RQeNfVmGC(_V##N(# zQB2EVI)A@3dDkU9@m&ao5WH=q_+6&L-ZoaUIE`x$dG}qk^>~YFaOYjBL7L6rOvHOg z{8_V|Pd`hhEl1TMn?uq|Stfk_tR4(HPO7e{QAbbJg|MJ-mX4>VHLZ(!&$L%u-rdIf z9lE?b#d0tQXM42D0R*|XJ4Tkir$>gDIiZp(?=ns(c%R_Lou$=bFUTBlsT$rh^g2jS z^TOoFg0^&L?L3}_P`_y-N8hC>>|CbD1s`r3N(Qx<0e{6)A#=(YdOcw?s2Hi$y`Ji+ zka~pa2rq`j_w7?TSiLMps>eb!~rM$R?yqxq;*Dz`wJVr4*Q`*Zr|0JAKY+j|`C&Bla z61I86A6CrriClV5uPj~Ezmzv<^OybI8|LjLNf(&#%&^6rcD0vEYC6pY+?TcNg5HuO zIRc*{c(tv)e13uccALv9Ri1iF{r5@z-jZY)>6S5<7hqy~yYj**4Qf>0Ta^YS!#gpt z7{M1=(5>_VJ;Ud&5UFz0TUvd<5^etnLpf$h?giqPsGg3Q@d4#*oJ~}b=Tq_v^dIKy zDdyWTy`}U6(<}5aLis>%Pox@uNTgO0sSp1keLr+H9IGG%RzaxN(N6sScLTMh{6jse zj^m^nx$;h|usp=GDHPBK9i{R|`at`YjZ_)^5z1GiBQH^wex!E^<|SIX%*-K9$*Q+w zjae0>WUJpzR{d^uY5Fn4B&UfU@-ceWpl3vqJO?3sM3SY)n!CxVkC`PsYNg$GAM5v5 z2sXZm;93NiBuU?kG%QPOK@|X%{C!ja>T#!9|4S_6_mQ_Rl0tptnq}yp==FjRKW6)d zh{}gP^57@B^O6V^&UW5qkZ@sb5>FzSRRQWGnQW? zxl5Iq2xbGxsA?pHTayZ}XR+kQ;_HU0Mq+r0IX|cnzE>6DeG#XIT3B}kghrG^?G*5xfaCvUbK

ChyOuz5z2^yvP5HYm0+=gZS=xH#SY z7OcN1PUR&twpI3bksQZGt$1X~@{=dWWaiGNa{2S0Gd~Jec3A%cd9XMyhfv%YHVBbZ z%z0EA7TzIF)JM+yt z;V_Bu*JU4vON{rHdxD2++j{WGFV*C7CCSXker8S%WcD7$9Osn%UnCvaC^0@qVtm$* zY#1aRnk^5L3H7+4965d;$>aHXIc9IlBixwZx%`zo%>KgOS2;c7C)xie&#@v_xUH<| zeOarLg`D40_zH3Q=10sqJ(*{8WDXME8p-Ko;X5ImPN>7Y!(G-Y$ek5ETQfJ13df5x z`HM4+l+gP`0#-K(SjjR|ZgSsGyUz9G%V}34+i|2Ec57uIck<+Pi<7I=ayj+7jo=Ed zf6RPmC-X+Bc$hfV6Pc;DGdVw8-kv8*04kPH>?_W9N76}Ov3*{+cym%`R;0-YN@jC< zwgjl2vc^3n#HPtiWJR;xrGGJxltUmCDRP*kLNfKUvRglkL4DT&1!8!{ks|B0U@? zhsx{@Tp&S4obWxTH;!j+o6YRJ&Fn3q`pNs8PI#I5zAQ;m0;fyl47sj;yjt!50|Pi? zl6doVKThA=!#q`bzE$#_pRs<2oB`NvdW2hFV$PB$r35!lU+KeqKq75{#Qx<7{dsC? zc6=)aBbnzdVfK)YTo<2M{wC}FWuNy^BT(hvV|@b&&1wJUbgV?wc@mg{WFSEf&JS_@ z5a13eIKCfeY?Xpexvx)c%=)$xQb)=Z+R|9>D`!NBj_LT}AqnZrrJhN$=3c+C{SK+m zyA|eNjUZVXUMn&FzU+!niSaw6#|NZC=cU}*I4++chmlQ=XJ1+Kld?pIC3Jhq4ExG1 zNX}cq6}U+tDHbOi(uwtxPBZ6AJP4PE$3A^oe)k@!fCG(1B(R3vd=tNi@dyi;s{<^glk zJIqViXY!0Ia>wf_7m@20Hh3cYd6I|Ao^flAqHEX|!+TD*>D!=Y7rsPCx0x?B&i&v$3hz`7%2t^!l#i^mTc?o`l*| zeKW+D4oE#CpRk=tB5Sh0oc|%>o%7nWL1)>o*X8t^B&VNA?s7eY*{++M^T`rwy(JRn zbmROWnXyN%XUb647f8fy+eOa*!|OPskA&PY5^~SW2yTw!{N;O?vt%j@Bo2(pX1%G1 z`HAfF1PRHZ;)D&P!~W9Ypm4-LHC5g(NX3#dL*8bG%i1}2O2zLo=U3-)UgtR-D@$1P zHm8@YWOmB#*de~uXDjQE$@ZR?hdY?+z!)hQyOGnrvYoOXbNY!qvkj45GUgELLnWZV z`E@-v8*s<2ROIx@H^okt?uz)*Yzf_Y1xMH*#Fq;uEamil*}qv5pxVx0eL@=Z>v|A|+IW^jew)-sQjko!bJZrX9y$4SQ$B-CE1 z!yTXT1?SI@IAN2H$4O+pByk~4E;I-9BOUhNqp!GN$sFdS{>)iP%wr_-jS=4%X=c6m zU(EL<#M&gpUJ77++e*yGB*OM=!yPS>4mmF)U+w?po7gZXnYlo=OMeNy2c!d8uF#vy zb~6IGLT|Ylx&6-ih2qQw5?RMf2fFp-{9!UfcdohK|B06;?`H$A;mk>Titr=RvRgJv2a;~E-diFn{&*)p|9h2iMv@$t2@;S-#<9Mn zn7Kf<;S!0E#qvtUyCvrzmTen*fYT;l=0{P?omVmY$|d!1EaqQtKiM9WB=#SUVf{#i zNR|Icwo{f&wU_uz!7|SG3Spid%sf?`Gie&9lf#+MOXRb4;j}4Fyf&l*E7r<3DUiq) zKA!a>H!$~a!5k}*uJ|`j50glDcB(RCy8%3#hLRw3OVEY66Uqy&A$CO zoiDFiC&?Ojwz59wCFW!GnXmkVxj+UoTb>tYm}Ps;;{2)7aW@`Vp0Pw;k(P)-+rDfV z{+K!RWv(DWB43!1>#=s$FAcz?$z;s{%uo5T)9s>9ieue{x2L=P90sL8J1Akl8 zI0sw<3|#L#fv!L*Fbh}=tO9ler!BY>`~)Eoj@AT-0dj$Hz;s{%p#BU}A+Q~=x}i}Z z9+(0w1J(fQFAE(7&H>i|Pj~#`8DJtX3s?*s0!{-z0k?t2KuU!whS3{qsQy;TbYMG$ zU&rsSi$@6P2n+^B19O38z#3o+Pzy0D6<7uQ1O!$>-+?wjZ$SNVn*G2DpbmClBcKN` z8khpi1(pG8fGxm1Aj}hg69DMyiAhO?FcH`d90DE#6>V4@pbd}$^alC?g}{E`1W?tE z27yL^1BeHD0GYsGU<+^!xCa;*do5rhFbh}=tO5>Isg9X~a2u#t6^#N-DCZZ?+IjmS zo&YWaH-LvgycY%rOabNs=YaavFd!fiNCh?khk(;S4OAZkv;k6pen2ju{zAueU;%Iu zs8a*u031L((6I(4rU!&&z)|2Fa1FQz7~W_QXaOVwU4enX2H-T%1gAr9pdYXu*bkfl z9s+gn=-UGr4NL*{0!M*bwebhKfJ4Azpkf_FkeE8?IgkSM2DStH0V__AMt}nt4NL*% z0&9RRz+T`Sa1FQz)DJ-Azy{za;4u(b7aav+fHpvHAQw=7O=CK+z!U#_2viNkbdc!= zT=g2n`au{x&;m#Vx&o_!L%?a^C*U^l7>Ef*-9QS^8(09W1PXx@z(wE&V6BIV0U80B zz+hlBum;!y>;;b2!-`yka1Su*W8VR_fDyn%U;}UnI1Ste9s@NRV30rz&=1H3rUNU1 zLcrP(lL*8EJ%G8uQQ#VI4=`Rp8$cM4_(C2=3t=&^8#n}1Y=j1YHb4r{8|ViV0^5Oy zfHee@2-E=@0S+J@mLFz!Xn6tEH~1hxa#Ca5D1|EmM^05XBWz-V9! zum;!y>;=vN*MNI~5sIY(5`l@pVqg`p0oV+w z0?Y;W0_T8x5mFIiOZ7W)Nrr3>_K zKo1}j7!0fdjsoX^Ye20QXb4CJ1_HBypMcvylQ;|jXal4Gy@7r}F0dWg5BOii|84*e zf%uka5apz13a7tjO91m*(EfGxmL;2LlbFcR?}&^6JZf8FtH5Hv0c z{sk-m_5&w?i@*)Q+8!0t%{!hi=8fopVF0s$#lTO%ZQwBw(-HjyQh?q-KVTfN5-0?= z0~djZfHfJ@2Q&gY0zH6CU@ou>I0~Ett^w-rta$?UI~nxRUC)rblvlB`z&Kz!umC6o zwgdZt8^A-rnu11vMt}o|2RZ^%fMviMU<p6zzx9h8X5$80GYsOU@ou**aGYYjsn+!#I9Hgn*CqT4k5c= z$AkipfhIjLsXz+Q8|Vk*0@HyTWV+{BJ*h`e)DDaWrU1);HNa8e9ANaq+yS+KFdz|F z46Fh+0FQx+Z(w6m+C3bRg%EE5*4|igpb_8z;(;l^8elJQ6i|QG&J(BwgaIvpL?9KI z2%H9f0&4WdNPrli4Uhu#26BPvzyhEU*xuJ@Z=8T|5wO0A4gej29>5e}F0ckT3Y-J3 z0r!9wsc0DJ3d{l)1FI8fj{mrQP?enKTaK3E(1d189_vp#kwg4SOeSx)L&7o1=I(^fQi5?U@@=?xD8YsZUh@OhNH9Zq7q;YP-_Gx21o@40wd_k zL(jV19z(1+66*;B0!@H^z;s{%PzYQEZUEL%=p#@EZ~*Z@N1z9=1~>;?1MX4hM+n6e z-$U1c#lR}yF;Hl7*r4R00skVfGxl|;2vO%g}(t| zKnoxdNCgH0BgPsHjfoIu0Y3pv@-Y8E8z2Sf2aE%zQ|KR_^=xa#p>AL=aE^NZf$q;5 zkFEo&fS-WdK*b5@J`f1R04YFkpdXM6oB%EYH-JX(V+cS;U@$NRmqpJqyAi;56_Pa2t3GRGfrHfqpbt={#=m_)xrT}w+WxyI> z3$PbB3Y-JNreSe_L|_)M7}x+D0!{^)JtttfoxzvD#iTWl=jt*)-g0Yif>m&}UZL%cktj zSMg%Tgg4GXh(D#}AX!R$Ax&AUvo`mY5-PqP==s{3ovHN^C?DpG@#N%2BkU4JdQOft%9 zsT!x>9Z8R%#-1u2N!>kdk!W(7qA1$wiE5+i7f)0h zLw+_8+)_~*jk2Kwa7&fSpvyMh0lOWPLCx$?X3_vfS+od5TdSb;6Lz%j2&1QVTZGvW zP7zhmx+8+ptDtp9B+b<9plwxjFK#J{qTs5aXzH#ghNe}8i^tNzs%Soq%wD<|&Ae={ zqTOkVGU==rEVId84YfvwQ8UfqlwA$2Mn=%0YUoxr9n|VbdQi<4YKaPqpoZ0LArK;| zOLbc~1P4v7j^Q|IeRbWBtJQ7ML07ueKt-`Mp$4+kXp>5%(^ZwqAU|(V zCUx@GQ!v&W-OQ#<-nJ-nco^N%98L{=(4+7O>gA*Kku*oMgAV$@4V>g&Q@7i!Cg$&c zO5SPAP(e*3o0_q$q|a*FmMxVYI0Zh8P`Aw=`q2{gE9>ef?3!K}!`m>4HC+ zj3Rr0ZnAvSbC}yX9BP)@xit_%B%YZvscdvwl$+E^=zJWI@lJDsw>sggKVz|d#fHs7e)IN zMU%NcD27_r$8^Nf@cOn67~P)wuuLa&11PbZ8elxwO$`tfvS@t+^e3CHHn6ocXGBuN zhKe1O-4LUMPb_VSPB_EqxaJ6Qe*s$p`}zgl_WT!6ql1pTVCz7S8euT?8|guIY6N{W zO>U&SwnwF6=#NHdDVCasAeBbhA$m3DhrlF*j)x#GliVAFvZz^Om}Jw?#)xK7VYIF> z);ublE;L48q9Ul;i)b9%>O~ZF(99Q6k&||+R22Q8Qn8yGH?h6pfmS9vp-rbfPQ9+T zoTxXG8b*P#sBaX!Et^(E>B+gw6da9I2Bj;?q!rO9mrX~a(SbC?nP^N(S~x|;D2|{( zG3ah2t%%VbxuD2NezE956t!1`EfEWo7+R+&mM+KYvHLYcUOKgJhExVkP^nB>-%OAF zDpIttIp#93xh+sRT&w0PmWIr%sw9XhIxjG&+)YYKC{l=`KgL1Vz!%mgrA3t!{}LW9V#4-DUgBy36feMhctf zW#nbhYNgDi%PN&c)#8ztP3_{*SWFm=(i~3f;xTJ65p+RwB-s;eO)0Sz{5UZIUgD&o z2`CpupDBu_vk9m(hN`tfR7`4(@po+nE8JIFp^l*0n)ZH~FAEH0ubT#zET=1I>=0&pM)H zB%M{{AbT>%Nv#w`(ePx%hG^QEjPfybD_IYtaVMl=saGf6#rd7k#Z20xQd#s=Q8qPu zRgZ1#tG2&Td~Awd(M>5R=b)>KoaECPgb7p>O~Vz%&}W@(&1qh!y$ap#j2lKKRqFzM z7Pabv8nS6r7p!A;7_IMuab;tDyI`F$1fSRR5Zb>6D+f(b2z78vdE_gD4W{%;HWlPb2#nM96?Wez&Mhc z^@LRn4N??KD-@;Csh%7H%)L++*Q=JjwC$)~SOeVBd%?&_XM3r8QEPjZ&9&aJ9Waxx z9}bh-eQ=l{cG~-*2E@*0njD@>8lszsiNr3P2aTnRa5(^{SeGEZaiZ( zhtv8Yn19@OE)PMeNb(t~>u9gYNn?j1GXvXRC1dC^hHWzc#> znRHcA7Ww6ZvZ+%p+C#*fpgEj2<)TUq_o`+zI1GmqHcR(m@MI^=AEx)>o?&R|(QsSk z`NQ>AY&;y5#Zq5IX*5SsI_*=GL4SZKWCVH@^Dd0DDE(awIh*FZt2!S>d)~E0(8Ccn z&-o*8wamapb_BYFbFr^x2hACQdYrUR5l$OL(bRM#D2CEOR4@vaFB_?cd~hVZ0q5>0 z5YAminKV=pBK0Vg$)*dVP=96^ReMiyIJMIpL8CNB(mF6b9F3rP<2_p_TJ{@__}G68 z8tFY6ifEdq6lav;kW$3bA5dW65o18M|DdiN}UHV{Pr! z#qX@<2nx`?i+!a3Th~@_n1bob8~q@1q8sZWBRK zG(ZvVj*4)fn5bKBHc7WUY7*uX#{`HTO-5TcCSf)*$#1fnuMbq?lcC6_X_IYEOEe!a@W^e4w*1a26c2;sb0nTqG4mk>3=AsgYArSLzhp#A0a96ig=`9u(o>VJfow zPeXR%RAgt+C@9c{O^UMUuA*#eIt_amm-Yc*I{i-!ws4v)OkLYA>zqgm_@}aPP_KVt zWKLS7D2mSh6UA{Io({sZ!gM|OIf~Ng_;kz&j+Pl9L?}g>v|16GodJ_)Hn6ZVkFpTLRV#cCqn^JhphT^eO#8Bf| zP>fWHfwQ1UqeV(_T`A5fMFv%x4Mop6P;{IPMHY=xiUUfqeKwjwQ2Avx8jkr04L6yi zG+6#Q2%?dAY|)IzmN}SKCz(G|b>d03=}*JY8;o3Kc)@Sa85y&ouL1~vQ`1u`l9 zV->X`XpTyz(UFglnNCkXMl~7Kc(Jz0UW{HK+$=_=*>rg^O5kExZHcb6%M#2u?uXNs zz$l%LD9WH}OEDkO5!7j^?PVJI2?o4isebS{xD=H*$ovWV;-siguxm3Bsy;zOc<1zq z9@#BLG1PDwY;ajnltwd`p*hsQ43=mcufO#x6%*Htk%FuHeq{U^yl;26yZg ziX&+F3K&PydPTT}t$?wUntqCo;==kVQiunNV(6}-Sc+Jwo6KH`+S6(2O5NmHMYuNR z!<8Q8V?;gj;Y!&wIUk#_-)C^bL-}w*EaD&e=tnGK!DlFsNT3LD;4_p*98iQf@GlVF zAp8rp#jaBG^DoQ~;s6vFt$CGhy4fmNWzcYy%A|Fx^lp5hl-P|0w)X0YVr&6i2u~FI z3eYN^D4rI;IFh1PV<>oGqsU2{R^yo~irha(UNp7*9OH|jp`T+4VrkRoSkTN!y81a@ z$;7R(RW_ZVJD=OCQ`j0jhGtRAHE@P(8n8yWJRaxPz(vC8h|)&TA1W0|jn|@L2c@q? z%1Lt+MbVzMdW=uk>eeFG>A4-cPS5RU>tK>jr&J2d`2|v$)a(n?nMK)Opt5XQ`UM(P zA^r>a5<EKS%3~sF={EEPk6_!hTQ&X)Gm%Ywzd{!fV6DAonKoOob zcA_I$ba^N8vMFE}nnXD7wF?Uz8BQ~Ip=kv3eY=nyN#@-s!$ErtmmZ}#Yk9=ivrOxmX?i|k*+1h@3B(S*9CYYwM_nj^@( z7j5ANy%!^K(4f6A#^bR5Ig@Hj1SLd`_XH7>3+Rb z)AsAmA6JAs?g3CXr60ih;ikFz0G1WkBkW7aW6;clC zH-3W-W3h1STyYpd7PrpJnsMhns>b*gMNz_z4 zVejmBdhk9+K{z)R;oMY|Ne2~Wk^3=FHnlp2!QsL=`540P!{aLK9>YZsZ>r75v8K3k zHam_UWZ_Z$xNdoyBHXhTMN_lyK`}JydyEvP=J!~fG`jjdRv?{xPJl9~-3jDn(pW`V zv`G z!hFY4%OCW#Pxt{VlTHT};mkY@|H6rU8a>RS6^d}$p4P8|aonD<#o`SxUc{WyElfV6 z-Eh+xtQFo0ozVmFIg2^M{3*ixorOu(=ACD4Uz;dth^_MG>E~=$Ow_X?p6bS3z*90_ zU0uL3;i>b&1ym4D)&8TSddvSH6-h(?gQnoZDupHd4{F89bx}`buZu__#45sz1rQ}& z!gy<4!h*toFX=8!z64`zzDo#~A(!!dbs0}J+0^(lW)ZLD`d&r@;RJ1KoF!*fDw3-G zh`Of!h`M_GsAKCiDA4deMR+~=6RM1%RzKlY(21wEs+-6CWb-v)#ui;c-(hw|J)d1g zaqCrEgLr%eS`yypKSrYUGaTbY4Oam z>K{_)pKbO0A3mFn9qAg-z$&_f>f0PGy1vbcp!Gjv>7(fK&w9!Nu3=_ksQoo4V`-F1 z;myJ|tZF))y`~q+=Q`#dUk+SXE<s)Q7h+zakY)6I3dOHvNi?UT^~oe*;U2hr1idO{YPM@D5NB4qruC6ns;+ z-Q_0QMtr@AUgE)rl~->fs$$ps+=5LywYvo$$e_u$w9R^@bkgNpD2T5)enZO`$!|zy z(d6Hdhmrio4)@D%7zy5G1mDI;@Ghh8ZPXiuuX%1Oy@U3tG-Anv+j@?I?|=}~72#P- zQ6_zMM|bz~9X&^WcX35<;I7bx1>A)1>TztlYul$H#)SVOiFdRA)unFz7jiIhkD(5DT=0<50Mu` zJ0HRl-@m9-_GZ6FwlB=8`afZlO;7(s^|*OPJVy1nd8R*x8nr)$G4|hM9DFz!?y6iI z48cznM^Kk1y7943bmQxupbXYb5guutf}*MYQ{DKer@HaabZYadr?&1E)l5^fT}@pt zvptHYSnQs(*le$_t|)uV_NMBJa#wRC1zS|wL0v3%6^o}??5bbeEOzCX4=lQtU@P)a znH8q!>@=%gzdPA!wd=QIf9P}sHFdMABXp=DJfFCs3apNsUEK~Ex}#nvbq7)Z3b+Bx za<{8z%bo71I))y&>-HilAQejk6s6IM3Q*!((F%4I!vZQoiThYZC^Kn}N@0>gRN#U7 zJU#4T%IRBrpi_9aGRgy;g>$a<(A~J|f%aoJ`&6>mwxM`LO$^LIeHCHQiqPYl_70x- zmb$5Yi@cbMYuW?oLVhI=a@4YWqZ93GscL9cEetA+)+xgK##*{(e!i$BliK;hB#Vao zA}^a(``YoU1z#EZ+HoY}D?>kY5BKtPKUm?>TM;fFelT{@1C@%xw{xfu=YDM{@y-K8 zJ?mhIM{C>F3;I85qn&hWSO?h|)JqZGYb(m4J&LmFK^=Rz#fg2^*xw!kA)LDV+nw}6 zfZaw5{4w$PI>TSL{J`HH>G{kz``5@BV6W?Yt&w50;|S>t!x#Im@7z{VPJq33-l~vi zvY+{0-}6PKeT0)nS{L()hloJ!Cw&9;`pgW3GMe_N6dr?BDwY}sA(ckm6{XYU zAQZp@QxH}%lYUW3+(?7r$WH1NjH>Z1aIn3lx=fr3#%{tFA(iUEVV!tmTu-+=ydKKn z%bI$q9q$np;X+;?)#7$vA11in*N0~$HGpSqs1MJGrVI5^CWh<{kc}_;8=y?u=CKXz z*(P;=xY`gdh;Sb8g5n5#r>Gd=`~^E+RpVRx7xW;nzMvcSX@t^3l^9x}oS4-cp6?ZZvF)ZosrlQ%ncW?P*Q1Lve2JYl@A+It^E;4B8Z-%iW4Vfh=kqi2?|~k(d$0xS5&}%QfQw zjzm$sS8!m^c#7!dKr)JEswCb$?Q~#(cw4F4*{Gw@cPZ-Op_3SrimyubDKFJ!&TBXlnpdK3Sn%6E+*N!7yRQxxw!jwF!U^R>^~^0v^v&{ zJ+79nk)JEGFSTWz*k+g6j;L5#H`R`|d-$?~4P(Q~=Ib2AMceDn@hI%X+cLPfNJ^SXfEfw;uTRJ7wcxo!G)5T+>;jva)TOfk;W;^s(9Otk8zhnX&XB zTDxPz7&sULOZONKEHh)^o(L>^VzfIxP~@P-u`ou|i^ZmkqRA?Sqc&D=pt~v+L&43E z7fYR*!RN7onjsHAL(mL)8FW`sCIvS~Wm(j{IZU!?W^=Vy@e?$f5jvWqW$f9A7JBmx zZGjr_T}}%am| zt@|=MfUiO@H zU?w1i=RlRhbD&D4;Tw1motVNR4JE!xX|21mO_76sX^mOK z7rbqd!lOhRdvqd>V%K)-flZzGKbyL2Yj8fVeZ(`z@qSf~(y;g2YEd?N1WsRpk9{DHQU$@4OJyMO9^|sff4-@Tet;WaW1L)$L zNdA^+PqGG%LvGdfb|31JWbb5M_G@Je?e1gur{W}g2kT%}7P0%mYiFc-tAydwvLE%C4cTU~sbCkM?x5 zx3k8p4(VjWWF%{;vPh;{Qy053ZY8T?Wj*brlJ*4ww5*dozD91adMkpTBgT)YV#^q* zdFUHPSc`7=v%8VktM=B`S)Q;?$-t@i?yGiZjiY!2p+1Z8s>B3drkdLQDjHq31X4=6 zJ&@X@*b}X{Rb8`E?7gkaRC~8mU{bXzOEu}O&X~d7s{eWhk94-TvWBUuFf(;1tc$&k zb(~7-+?id_>so3m;=7}7_qw3^!Q<65zJ~d|riKkEgigL@f6cl~CcZ9p=!*F*RBfPF z4QOju`zzLX>0|>6>1Kb!ny4#PO|I;QCR5c|Z*;S#SR1KDLu;AVhsxx3545|xyS;}s zPz^ylLFDVGKE4Vk^^DnQ`Rkami)!R35lwY_*b}Vd)S@AoL~DE4U$$OUJwS4bwW2tN z56$Tb2fCe3m`6Mm$_xeF71^ zl&hzxg*=)KPdJnX4_v02(w^{Aw!NK2Ez*c=dz%_63aO9!r}e7XZRP$bmTDbW+PU`s zuy?WUS97`SAIP{}x{!YT(Cdm46MSe?KYK50YU$)*SEg8ds9Dux>eU}(x~+2c0`2OL z1xit^RU80kxu{kybAY{%MXkIpaCQLJ$0%L?)^8ym%~Eaa{k{1uc*6)a+o=OF$T|bD z7KN(INak7tb==Cq_I@}JTjipf%J>{?kW`TZX@3qf0`*u1A;Tyg)yzTg$3WQ!wdTJK zvoKXLf>lj=^KE-KYoY3_?&FcSF*WgOP_En>^y*;jqei8(0+Z^rW3b%|E4TURV0*e( zsMB!ZS9=Ur^Nx?rz~LhwlM!aDMBX=&wizwx%?b7w@b8+(d6{sC^T)3K&9ZzSKqo>tiw^jE?vn89#`kd`BaVdiebsKb1Dv&{Yhs*Z-Xg_&q8^O7lvyv|GB3 z!0$kPi|+hksgB<<5*GF&ewph(O56BlpUc{0Y)Ea7UjWmfG|!-K-^ctJ?h~QLKVHxu zITp06TKp7wuDLCrH#DmldAPjjPx(AIV?Xk+aa?)$w;lX38M*HqMc!*NoGN)n`99VQ z`nyUE_r}PpDHWA(5WlDFZ_B+sH1TiC;ctDsS-#*iJ$=W>E?4kWQrRf*%dyIpbL(4{ z=Wa|aSI(8gapdE2<@)F0g32E?BP;&4V4&C5as_c&m5(a7`~Oq!hjQgyrMNQ}g7Ti7 z(*8NFY*p#~as>yuyh^*><8lr1*D|WCDpwu9W2Ve6(grHM`lviVt^AEcElD21fbSId|(ng8dule?wf zvuoHN|J>45FfF$d^6E&sicx-7G%Q!HrK=d$-rWdAUfJ49mTF)1v`x8!J-WI|nv8+D z9m*B7l=F-9a^+m5xX%9N%9US=aZ*l?|M}5>P_AJ4N|*j^gIPoK|F+zzr0wO(wQ*Id ze%Dw_VLjkMc1Y-MU^vUfEK(a(MJlkSA9k{05!!yUC-z36EgvgYiE% zdZRWn@x`V7JYO&bd9_OOO8bIAoJvYS-fFd$_*5}UM~J+6p1(FQ86!*co*AH;|4jV4 z{%1x}S}WE*YaH@^&{h6#M_R6_++x-bv5mw{YQK6Y5W16{CFYzWGe% z^D|?}@19d7s~GBUq4LLMWWH%Cmsj4|%*gW-+vn=cbFYKU7ys`};}zu9`#qOq09pmvE`HKE#O7GzJ zl{PA^wEVvJ#l@t5X`TomRn>$%WOgpie0JZb4g4N?n`QXrM`1Ol;RYdnQ6qe2$GnsK zPvp67UR9pEUu;EQ*{qeFKdLhK_^z&P@xRm71$j9Z?rHhXyc4nOb(1l@bP(kOREHj> z(ko*5a)$A44^yLOGRv>wrznU^q5hyCeK5oR0ru#aOzhyGEm6lV#o`F9mtX%VfCj5i@qM7!Z z!7mLq83+E)e&HWazhg2=cuuho{wm}jDC3Y#~<{@Sb;p(?(o9)EX!+S z97LWgqL$7X4Ac>QxqM#PUd2?p|A9vOh&jUyq-IvyCcsvP%oT4 zu8%sRbCK7$w45u4oo4BK@N&Gx*Prq|g;%0ru;f)UUc(DU{+O@=caisfX^Te_n#)CEhmxp+`d6xGa7;_ z+>P^)-_>%k(RF%REJYb9&0~8PdEUy-yF!N5|e+Ci+YMRU&rYB>*9%?ha(*sWV37MzNdRX)U5v}nFj zNb6K?Jsge|IJYrG{PwCeD}L;9K3ZOZs5zX1=G$wUYi*{0`LN!**<@VOD);;?CZmdp zTF%EzZP<#3akl(^EB*xnEPsTm4b4Vjw->gV3>%9Mi0fFq46!4NO~1m%ry&H}HzDS+ zcmZMsEt;=H{&Ty@n8~@mJ52aRI=V~|#M;#P3lIDdIicT&cB*mctTww$#zPic z?8XZa7RNxu#zA|gIaKtqy|&vzXacD70%$g~W@o9!?Od7o2SmHFt7XMKt)edBRu!UF z)^rOf(>8=ymkruNL&jY z*KLzAOl#d8cT7elGqqfTxZCo-CZoBP<&nRmD%QKvBa_jEE4dDF3Rg1ZPm>YH+I0|p zv}oS@CkFWlFBe+zPCT636#ghp?mFA85Mn(RzlRv4Mf1I;bOeUxYA?|*szCMbW(2rP`EZkaubYjRspwOPk-g2v z=X4CMxLttQkhRt{v*F9O{^@4pBW++V#J}nL6g9o^53|vW%WQ=BgvIs!%tk7U)%u%_ zH7xFgxR7gl{Vg+srEV${;`gkL&M_PBNevL+XVE#xZ0wTGzHK&+v9<)iFnBH{tj0tR zF(a7jx=ust04bD}vmgesSOiff z>@q~@*N+fSv%y!NnvK5PMc;h0aX@R$m-A`n=Wv_RYt6#jU#eBsm7dw4Hn=v}wy{+F zcvI=Ltb_O`8x(9d8-rM^xkUvcUBic4OLz11ZEA{@yPNCoqMd6os!_$IYjGB$ti|9x zYAUsxjlu8m7LWUMU#Zvs2Vw{}Rq-3;FXO+!G4>5DU57f0_M45_WEyY5C3PK6lU9e6 z%XxhPr`-gxh8E2S50U)~Sbqx@;=9TXJ*=Xm65TsM^ufh;9d>=%F?B>}i^C9W&>dxb z31SS3zQ@h@b%;u9EOE(XB#+=6{`~BP#ogv)W~l?N$h}3LR78t}^jRnRvcTyaBN{ z+a~_oY}BWsBD6j5-?Xj>mCn_wp!KL}3q(KC;&F((wP>Dmjsn)h@T+rb+&cF=h!HHB z&MS{rT64sCnyC!WLG=pf*1KR^&Ox>^EGaDb8wa#tW?`B*$ zR57>p5V1#;c&kio{7{WUYkQZ8Ga;H-`(c?l3t|P2A z{ZLK2y$O+f;XVeUXJu__p6W@rHevc^;dkD@LU%U7@&|}Hl(5BK%gtsn7MaMt8Qyup zZo%wm1HUR3V*ra2Ar5Bo9>gXr23EBo25Q@Ah;>=)4l#hmT!>LDu7>y`izgwz%3^&l z3oc8#hERyjs0iJ$LYmFWhY&Ma>|L!?+zoLkYa^XvSe2XA zY35eU!H&8X6;7aXI|$Ll;$jN_DWyFzu^y%j-Z zS3?T|xvt|P#71mYv5^HqSr?cPVnLwN;;P0L;{z67YGN_|%VKa-i*bj=>R}cmiN)UG z7TjfYz4syRV(o@Vi;>1!Z-)gBae6$TI%wxt@UC^tZd;Lse*>k4dPr11K;_N_&qKuX zvKsYWh>PghPKeW^EXFMI+5xdnv<2s{63r8%Y3X)Mz<#J+;@saMA}%V!o-t~swBbVh zxc3eiZiLEHtAdLm?vT6AOV8bT#>QHVlW^Ych-9y|q_HUKKC2BD$gFkl>)Kh24i&WQ z_9$6Rt8Or;lUgM$21B&77zWY7VkX1^EFOXQ5sPWBTCh!Zv3?N6b}_^xtu2V)VBd`?bn#Kg4V;1~eUjeW0$D__$u!DOstOy+uz|Bc21v zuNXB{8)PxskykgoBMB=;BRz&#jLYO-j7FN}(jaB>-7qy?rE=Ro&ELOIOO>J9 zM77HpBVr5DzL8Tc}mD4G$`N34`TY^e0|5Wit8@7Px ztws0F5MRUbUxHa*Ih~Fu%iS|AMr%sghk7g@TJX?+OjS8+w(6(Sn#1Q%%Y85`nPb6^ zifF^Ik1TiuEJCjP8Hf+8bYvf@{B8lQgQa=MLOQ5Q+*oA6EgNP&!Cp@w7b-WxCszO3 zewLM2t^HW_P*vx)2cm;!e}i+_>jC7$O0F6A^guKe!5wp=1iT~o8F!gC}41J~n!+7PO@;=q$3V~klAu(GeYQ}kfYcYCq5tJ$a zb#NB)TyNEzKlg3$Tgcm|rn)8_{nl>nR#WO|A*@JsF!3-B0?{=$o?W`!H*=A9<8Nj- z^*amR52*g;S&e)o@FTqX)BL$TvIlv!OFdbPK&aR2{7H-Po2Z_j@k6I9#{aA9OyHv^ zvOiwash-3@W*8(SfM7y!l|u-}D$6k>gvb@bxkA7VL=z4T3E{>lhupUT{TGX<;L4$k zumK?gB8OaZ$|`>ZKD!)(M^G@_XcqTZM^{bH=d<(qK!5waSFc_jU0vN(lj)-~ch`8m zZz9NLCtZ!OH81N-1Re=Q+v6z+qS-^;M%((Cj4S8Cqo36I3s7;zH0%U>-8MuvJ60;g~PJ1HKN}kdiIh zz1zxeM9BfQUKB zhp$M8PcUqiGtZSycY9Hx#n7P_sC0zwIOdCKvlv3BV|P$We&7|d13G6}Ge~k=z2e(e z?7?wV2o_-f7;5Fd^qznYe;-?Xf_ik}-o0cKbTveU1P=h0YqQX+D{tbErznY1T{FB+ zhd)h89S_SshCy>WezWUK;jVq(KT+b$M%@)#IPx{`-Yx%hRz#{0@3m1uP+E9|M zBXUL$*)f+v_mnWpIu2B^p>+ID_R9}nj6MO~MD4zsoHW`3JM@<*p5i0c=O3G zo5Wr~Y}*wdT%Y>m!BCpl5!aG5D+Ze2a&jFzp7K-ZrgAe(UfQKmOgJTv0jnncfQwa{ zVAvpi0lLSvF0@xf1R^`3*|g4G?%L3a=wdrinv9dTwV}HOjzMR7uDb;)q1(pe<^5s{ zzUMMuWfCNVLpBHGl9Vo#WD3Ip34uj8Dbu;Bp%3T0HqyINy~7|FcGDaMT`Qf=R5!nJ z-|xzTU;Ape|7Qlp%~pOeK7{P-cquQY2PH$)P28lGUNW~ot9Qy*JMmozov|u4ES7^@#}ZFr(qNJ6I7#6r zadxu-sBIxn@{(+vIG0yySY_;kuBCL~C3l^Zxb}^*%mw4lwBMvI&^gnc)Uex7F?5N- zA8sfsaPopGHTrGHZ6}}n4xKY0O%0p;H5u>%Un zUBQWyO-Gd-Kk$LR%OI-vs6ZDI0wF`7tFG+b=^7-D9>g+F`{I)*`5IPEvb3yUPP=sOi}YHkj%A(p#dJtcwqG3tNx|hTPH#xdGiA6>WOhKChSOQ_PIvA~v#7V7hY> zXDyh|g6Dj->U&Q^_N8jubdobl`9Uc8Bi6o7@y43xZ(jxumZ7ATP=W<`@ktLGl3FgM z{D%&e&i%;QAG)io^c?P)9p5zbm~_%3N2TDI=BY3%CRbpz`gE9Cxbk0OIUHnX!bi$_zk#AA`U7z$CuGug4>Opy5L>5(k z;NS{MZd&ZxSzpb>?e9|JJP)Ru%tUiGSxND(Pqg7U;H$dgLMK3D^KPudJVW(}^spiI z{@>8!xC;!a(eEpcv+Dq(ML2^B`aOn|^V+wbTZs_p8cNz|ox3*&*Ww1IE12qwoNwpN z`H*5-BAWjqaE&a*?7y4IbGoaBaz+K#V>D4u8tG(g$gLMYpRh&`RCLnx4m7Bx@IfVXMyj zV%udD*1|~}<)?F4r|k=!iiLCzdmQMui@gJ9S)*X%jGUcaH}dp?(aV$; z%E2cr_o2g*WGk!+4mt0miA8&;-jLpz@<^OS zYX5rRM4ARI#zNOtrr8LrBXG)LU_G6}-5Y*@PL0v1iO}Ke|GQeBo6Dv%3B45YJ_NcK zwNLjZ+||%MqjjXZ_R6dLDwMIJEFJK;yw8-S3(3n@iBOib;gQfe<6oDs>%$LSdzNz% z%TeBpeJuMT8ow`O!?-LqDLr>PPI8sEE~GHz!Jzy=z5STWaKkt|6Br|~-XNeez3A$y z2tr2gX9F)`Znyt{c~I_3UI=*(EgX3cx_Fj)NzCnTIwx^Y5iU>4?EtE&#D)6&fLBm$#(`_6xvJXLsv(;a~FOMbXdjx7VY6B`*4yVikx*B=-dms zxn7_ZjIDdrbn5WRoDH4x_M@9?$ROktbg@oe zFw;8sR_&_CSmqU9JnrAMVKs(3t2xEH5bO*{-AO@n<1Hev7`hhPn`0%r&mQQKv~Hxn zQ}DLE44v~{q&pcIG8dq<;JA4Z=}wxt9}vHW(rL-=Vbj!FCvYk8p!ox0W1Kh>rtT!y zm3uqrFd>Iwhn#|8I60ug%n0krPh!53rS4f7uFA*5+E)~dB7yI*Gx=XYTXm!iQqW6z zLw!?v=`5b#{Zf(kBtQy5&yHmi7b^j5ooj&rdV7k^q&|^j?mI|1{0`_9gm_D)b(nEH-Y(5 z>WQ*3qH<@}qfzYIHB>-iri~3dIoHu~+5+2190!aNXuX=rvae&ky?alaQISlN_2L6H^iXnQ8O0O#i z*kqU z-#xv7S{)7%cF}WDp%Tq8qQy$I4x-w^%H9jCC(wHVxEWiLZeWphX)epW34a@MZIZ=$ z-^3bhWS&iY*oJ)*LBtNV`Hpai?NlK4s&gC;#Bjs$RbUm?{1)PvGn6&Gh0?w$kM?`Q zimU80ZDsETM#=2AF*kqPKYt{(-Ayfn~>m{4~O==tF+ZfwKR^x#KC4LF)D6#rTn-oc$ z4jd-29Ehi`JE(?RBiZpgaB3B3QPlz|stwT?X|=F`1@FS@^+KEPZ$(0TFEB~s72r0B z?~Jm^5{b!0Hr~t%+h>5)B@O`MIgoo80enQDHM0nRg%$o6K-7|z+=F%(&@0f|FSVYd zEbtqK+#lqDvI>5dAP?AU#m@%F!&rHET^`oU!y$RNEDwa8tV99?zz?nEp`ScpH!l}1 zkcV~huumQ?$U~(#*zsd|8AQOX4E8dZ55#rBOEk?$-!{0-;3D6K}fA9 zCrVGdhZV>-l0Cm88eBV|CJ^tBqeoAr)@uW35?d|)l9 zp9xgit^oFw(yPYy1~5uWe+5dn>~-5uJ?*79{Wb15wJNdzVP?kbCl{#v76W^-Jv;*b&opq|v~~rN`z*+S*758|hGB66@`UOCj{20@+0`9B$A? zo-I=Hm64p4l6yw-yOh+Op~GkZOkyQ5aBYN{K&y>IGCiyFc&`tSAzWK&o%e2euZGTA$BipGC>Us{2uW`b3Jp?CeL)Blc~=0bhKio+q_qP;C2eJ-ZGqU(%^P*F zkq$M|c}7|SRBf_xE}M+7DJ1H8JpmNOi|4{7(&a<*boSMNss-YKswVybRJMJLZI-aD z;MbrrEi|TY8PoTKsfhnWplaAXz%&^Gov%Zv0#qS93{)W`0#yh-jBP(-`<$_T5hxqZ ze$Uu`plz+v`K-X_#{^>`AHYwdf7_rtkFx9sn6ceo&!>DM*oQyTVbunzu<9FWLnCbt zY$1|aFMPya^uvD zhptr+*^!l31vp1a zNA40gb#5?oH@`n}18ezicAR_K2~i|F$?v|`|NH+*&`|bTg@#0y|U_~{O@=$ zcPuS}n+qxIaFPG4XE$3t+TYW&jNKmXZ(Dyx4MKL~eM&|Vez_ih`QU3fT!vSbDR|A5 z@(f;{lBLUUK5uzR+2Jw%e|whBxEb$xW$DG!2iJ}o@2|DA>h)?5&BQC{8TdE7Z0=%z zv9)w%MU67L#DCet;@|Km#~#Kzqa*lt6#tIl-*NmqQRZ3V|J}2tTFft=&B=F;dj1Or Ca+z2F delta 186628 zcmbUK2Y6J~_Q#FSK4&t?z@!X`KnNkBh0qhJLVyGT=@3MkfC+>W4Uju$>8t4|L1+)=$Cc&UTe3t*Y5kA zDLB!wU~9+1#L)MH9S&z5hxK<{yd~;~W&JPgH2!O-Tf3CuQafEvXZ6LMbNeYodUt*3 z;jFliyFd9(^5zi})(qZNvr?1l5k>u${_E^Ne}C(@PiB19qf_@bJJL3*o%OmK5gBK< z%{b@u{<_=oew!uUUm949#O|#lUjKN^(;;1=o|VB}H&r?jGR$IRbZ-*z;eTa9u?p%@ z>8GC>P9AjNDb08$tb0U$;hFq@MOJ;PUPP@Y6Am{XVFf7c9v0yo^;_58hdP|Ux?|&Q z_v8n^v;ySx*wth0UyUQu->3$~>ye@*C&wldJQ?$E(T9 z*PTD&-bm?Q0-L1ig76sWy&!y}+*}ZzBUuZ>lXe~Z+-b^+#o?Pvx-SVYRub}bc)TP% z9bPEMo(}I`5>*%;rKHKS@PY0ir^Dd_!ONHYdy+&v6J8|6&xF^MQvFYv{wHF2_{NfB z%fmfNuC55bB4<{Huaz0A!i!6igzQMs>hLSO>Rqd+WaD$;)t6^okC4*m!jr`LJb~*y zAD*$R<_{ic&{I^~0=Z{S_+VKv2f3o3a^0lsIE??1{uQi>HY-Pr(l_!S`i+Z zewxS6z!`8>1IcsXt{^Dx^PnTokAQc;1>B#5o-T(Y9gG4GgZcO^1TSj4UtW3cd&u$! zE%7e)TvI!5g$!_wuXppadn!v;H!6k)5l*e$^eDUrcC2NPN&W5U0^7U}l zL3vP>Yrx%32Q}i55w6f`a_>mhAg-3fgU5KM!(}*JjvsmM4s1c?h!wBbh%6}@sphKS zOky~=KS=(%-)IqRhwCDl8LF;p6r8X3%c2a`ww&>vW{igM{eJl|L)9_ACum$}Gg^`| zRkPrffjZqTGA0wTEX2AWkfoU_r9Av8%@_lt-vMd1(X3!}7zJZ2jQ0=7bAgO4FoMUy z_~<~8G{3KM`|`N%8cmS#a4sE?j-vxIIa4#TVO%*N=Uy@^a{q75co@d*0}_^{>IB_B z5advjcP1oGN~;?oQn<-JpZik~Pa`RpV5I zn+hT~$}v*X&l{1_WSrV+P%D}*H?=@Ntpom>AvgM%WOKY)YfuT6z=iQD!uaTbTpy3o zp=Qf7X>gFs6K7df3Mr%Hk=d|sA1GO$t$HdW?QqHUht=K6Mca1WPL_lm)jj(ETBOeP z?PRCKjR=Y^S(~H2GF2_<^sc(g-L?`e{@#>zxvIH(v*c8+`e!gI95GcjfXth!@{E*$ za%-w;qSB=PG?hlsann?6q=z2E|Cg*BuFhFXW}kM)hUQnMA%{8~TA;HWnx=jYT8z>U z$^Pl8dC(XhKa(5N)eti?CtrF$u9DPEnfbVCq3Xzv$JOY%?HrA)iaQZ*N59;k3iNIg z>N`%!@1MD2y-{Hf$7+PM0G^oFh?%N}Oq!*&MML9$~OwLVB* zIOEpjlI=Q)E4Dvztst&0#Pv@d7gSpdosVOXsI%^B(SsZT29<5ILo9YOY~t&2*4?3X zvSmz7$)~oN&c3o-^qJz-)jQ9rwuFDHW~(^)A_ z4VD|zRE%U4C@0U}={y(M&zVoEYEsa~8G`?^=_>B7s0fE+GqH^(wv6$1xoXI=S=8;- z0_BM%O_Nn^q*#gU_{AJQ1Y@dAs*YeczY!e(ubZ@F_6#Ea%>sVCq+3N(L}e_7rnL^ zUBg4gJJ%=Dh2%cN=HKv%B>0p|EDKbeTlZW#|3hWMTr2K{b5&eyOX5u>U{3=6?hB|T z^{_Wo(iU2hm+Sy@raL1gVxDrw?j}?Up^lM-!H@Xrno!zEhf4B1auk1;!_gLzxri+C ziD;d;Es-(vES;?D=!}dVh-6Eh1tfR-Bzm`=GOYui4T)> zTBbEq8732`Y&A@lEKo7Y!vbo`g3%u@-mMfgp{uNHoTCRLO|*Y+^E zgc-$_B9f1YfyiW^h}O6s7luh@2X{3|TBMv(HcwR#(iKao7BTYbER+$h8(!}-b5)|| zQ#(`h+#c^-{I7z$;hna4r*yaU$s#pyK&emhZ^QHdwL$UiC)?R`q-AAw$;{8}XX!hKRbq}j!ws#5q*m7sfujHgso{FPWc>MRQ7|7%MkjwyB`GABH= zx?H>zQpJ`&`5FVtW%jpWqL|`N@}xHhrDH;Zl2vij0kboeNsv6_s!2Q;TQ= zB_m5{Z#omjh;+uQ%qODtpxgIwS+Yb8u5q&#&-}e+6YJl5D0$YSa(juY6ML252a(bI ztViusbaA!d29i6JqP`(23ht|o}?1ASp{^@-Pzyv6jB_goCBEX7Mzqi}or zkYaZGN27SNs_7OQ^A z_6%1?q({Y%b=9fu^dV!9IK#npaO;GD1xqrz5rbh z)d}e3|BJZw7JzoY3|*%jb1p*R6-+>@FJSkISs+Cm_Iv%Ra@-Q?3_ai>{1ZX1e$Doa%y2hG7S3_GEj%EdGcxZ*k7HDhe zZm5n3Z8_TFF7dhFfVPv^b!zZzdt$4sNiM#Qe&8TBs{fch7U;)bP$#qxG#uI&8UgJO zWk_)hfYyON0IdhrN$Ro;#;pxp``_)O?V-bQr$I*;bTtp~FcOd9&fXOV4|Y1EWZp_} z6;zja9rPvWPUvRnUg#F+yU=XtRp@KbpP;k1@o<}m?a&}9dpEQSv;=w=^bKeN^i60R z=v&ZsP+h`K&?C6hp+}*Eq3=NT#^G`3OVAV0x1b+D--Uh%{SZpOS#Z&GRIwub1`i$a zPtcD`)JAomGMGvCe2HF$jsI3 zzJ;bkzk_NUqx1!%q1U1QhLwx^N8B$#(Mmxv^k?W^-OK#S!x23G3q1k-9r`I$Yv6OA z`!e(|{C|KdCJqkjHW*qT>W21(((@POLBpWWL&KqZrNs=b;8$oQl%C6h)(hw@9Mzyn z7^owfhwgaj1Zjef7~HfJM=TUew)|&8<8T*3YeT7b%l{Qz?FmhW>N>|B3Wh>;zz2QqEa*M>&xB$p1*?4i zFG984c4!Cu_dtoW;4t)FXsDx&Bh--ungIPA2VxwO@v^$?wrB0i@wRx=f+A=4Ab{>n zdqHEMeV}!qeWBVG`ax5n{h_);BeMmW(EFjf6MX=xhd&IqU>0-;l;O@X466H3cE$@{ zgR(1Lum}1O^e8kF8tP~+Uv5@iXWNSbWzYO!>Yi^O^{4;FAs7M8hU%Vh0#x^W6QMnz zxzHD&lcC$7`KIHEpP*B5M-j&~XjQ1zSas;*xS7aW{(5ACKfB;Q9%jMN#`Ppr&xPhe zpM^dJT?<_RWg6pH2xT&1MaU#V@9h^b$m{+60>)R%pK;Z4Ya?8Se>k?W9NGZ70@@I& z{nHL(^^RE3+^FhuPUd}{IQZ>UR9M0Q&0K7JZeNs&21_~rAYm4Y+)A21CRkBPR3@? z9b|yHpa|>(pMYB+B8c%9bOAYFF4znXf-|5DL}8~*Ko{4tv|+1?ReUfVm+PTMhF;lp zkg{(~mo#ftsfNrgR#C1m;LU6#Yl>Af1NuR+>hIgA|6JAOSKGN2Q8 zsGBTUCKao@Wa>^8<+%tyx{0CtABQA+Ib_(rQ#J7I!+$BC?^Ja?^pvhRzsv-0XuP$O zm84x9T*Nhzj=MLcnL=8aT)ohs^v{R z?zA*rixsfe_+nZ2xF<$7zo|U#LLaZHcrRCul$;sH-N8MgJV>n*_rFwK?^|~W>3utYHGC`dCHC<~;Zmnl)}~i>%HlUwC3$n7s;ZXADMD+qUv===+&Z~uzp9(? z3Nfzm#pD>6os&-)^qxj4=6xBA#l7NvnZJ)ynmSq&a#BZS$c=p*j@Ya4b#m7MGWRM` z{r0|eJiu|(Z|^(huWq!y83)weW~?j~qsz#xH*eiI#|iD#EORYf>F&wDf_JoqZ9#vK3l@MPup1l$7r`wM;ilgKUBD2K3+93%uoskq%is?X zRS8*;T4`C@N2}gZ@vd}~mv~4L-l3in522SG>N`3JcO_aC=ROTx0}yC_NG85pZhq`bvMRz?cj@9i24f(M{6o_2SU`wrn(+XP#}CQ+W2#QW#}C;CtIdm2XYh!d^eF#+vzl zncVj|sj~~B9OKvm#59WDR}0+a%QBZNyV6rns8lyOviy>)b6zPrp<0@ck;~tQt7y4; zLiLUwLdE2R#b7fy2tENDXQ>myjbq`KdUY53K)d$pFYnQ|I!)QtPK-DsT7#$?N z8X3v5w#_)Moq3Xfv&Yd=tjsmk!5f*ChHR8f7}5U5s`K3(Lm+35U9OpkOWgubP)>6L|9k(U^_p_vLX?g9pmL-~T4~)uV zb3(XDf?)lPc~tsLWOhcjl3)H)RqX2dDNw1-h=jLZ*Yysa52FdB}L>w%1>AHnDV zBWa8b`Y0f(m738J#w%mwz(V)`-F+Mf* z&wO;s7+X#K=>|`LI;g|X*J>)j?-+>2|C9e2?Vm*JN+sIsV5MY@t`PyeH&O6Z;omPb&Y{~E$8erLHD#9xP zJiU~(c)e6>8F2;;+^aP(Ugn=+4gvlCQyR#LGn`r$2b5#Nn5^tfg6eTjYr0r&oWa)Z zL9VrQI7>ubh^Sw-j6JKGh4#y?D4j!2ol(`?I%l*T#|}AkR^3w`RGlMeSArI0OQUlt z!CT}Ds^t-P?3B!Ns#^5UfZX`Cs&leamYq{Q%A>nPbe?WR_lqwYNsA7Rl)C4Yw}#(K zTWCELkpr~qqaK#N=T&dtG^MqyJ5QGGBaXJ5h@R)(05t4^s_O0ha6qXDxJz1HV5s-o z+sq4u>rS{WR=5N?aY5bfyXfL?<3AEC1JFZR9bj`wJ3>7reXe>NwX#ZPeXhckL65QY z3x-cRh_EjiKIsjtYYlV1$5 zT5nK6*S}GVj9;>4`nR~zO06qum3xb&72W51HxO~@6}5n=AHy+-z!vL)6v_Nf#XNjP znUvq&xc*fkGbvZnMyd*#9mu$vB6DoCocmAt)Vqag8x}+h}QaO|>@uWl?J}QPUvNHP=)l zQ>S5xUe=;lM%z|X^SY|p>;fvf1tM6h*8?e_KNt_@f+DaRoB$UicBDP0R+X`W`;+Ox zeZ7KYlJeXoDP_uITCN=`S!R@}cl>G`azjN0-$phQSzVS8dsX#kkZil5>bU-b^?WZm zeM7aa;8gt)4z1C(p_g?0QPm3C&%-hVfpOaHR z(qTR)*M8)3%5#$Z9j9;cKhfVE)Im{}?pk#h@tmanr0z3Ff6-5*qDUpLx9t3h&L*$7 zEvmb4?9K7KEX%DN6NFjuSo=0DGroxt5`?aBbIB?u2$k@d+%q`FI>vrp(t8GTb>t?a z((`)AV$ySyOg=A{^z%NRW$TZs?W&(G0dgKGHGfu~Xtu&CMu|}mTbX6VB<{4IDHd^^ zVEL452b=aYgU|DFV{4^qQcUR3LSMdh5l!jv6X&Xzf2Qb(eJaYsY?#=Beo>9R`vbi7 z*g+z{STSb)f;s;ufU6tm^Rn_6)lci|n_tkEfxb@nldxY^Bk$>ccgA0&mBgWET!>Q@ z$&TF0aS-&xeS=>)bw74f4Ow-IheR?he{8Mfk@#C^=V#gfvuZ3ucn-~F5}|8LS3!_; zAYW2=OX=uV-cohlPx;tYCGTf+*ZY%7A+olUGemM{I-BS`R{1Y^G|A)H{?hKhfi^WA zPLvbQRbL#ADP!`}re;r()RC%Dh3$Q%W8n1J^;dtX^cxd_zsl2G_p7QZy?#@TL+qiB z^kyO9av|M5T{iLTZO^n>7eJ4V5XTysvnwb@ZvI9Z<)IROCsZ(@#->Z(-&IOQ>d$CS z2%Kr@^5z|!+i-&2aMq;htFw%Qb4pl<$FKUa6xvMQTcoBRF=b}%t zhMf8h-R=8>llK?pt{XonswvyfyxHS0K;hHE%OETPl7i7p907SIt)`sSN>r6#h?iJEcN^iNq1l`2?y)d4Mn^OD3mjcRv9l>bo0eIwoDyd>#PEAa_VBhK54m8riHb(i>( z&`m{3v6CBSTuX2oX(2tW9VJZ92r}vfb5+{4^g(+__06~RSmhr$bBKeHia3>{hOF~2 zNhu66h8UT>E*_(%N#A0-X5cdDL7wv%lMVWYuu!A5IhK}d$!3JYrG?K5H98yX(n}79 z8qEy1-AmApn@W8NSc<~16b&khQbhZcCE zWv$m}>9#FRG0D=Grlm~#*#@K>bA5~MDn_c2Ke*(HD#m=LsdY8!BUbYDsu_v1Z!x4r zU=xWT1q=kaU;!usyFn?q0z#@d9PuCp3O0 zaAs|nS_wu~SzF!kcxP>|Xcl@la9A??(On)E?@*^EY57Jq+1$X0ken5!N0OqA1m9|+ zi;Rdi>IQSU-u2(&JFKe@7KCZ<6~vmXGAUT1FqH zZq}x8lQ@EnA=vpd(k;$NaG&>y*N{WRC=26^aP_gMb`)|e{Ob1jrV|Rx9f^G(hn*8k zvv^}wXuYabFc=P|>WubNF0Dd&MH1>5bxfhKKeThdB3s(K+m|HOHC8Edq%T^_g?i+u zE3zA2kzeW=6&K}O)u*z%!6<%3M%FiKd5hVv^>=@0$Z=42e=)0`HJs|8d`x1@b2AQwa(0DVp5T$Mg2f-Oo2AtfsstH=krG`c)*Gle!&D$gijf^@5 zv}Yq@G5U>*b61sXjf_awD)@UgiK{WA$evBQo3y865XU1jr!>f~yOlDpF}mZXk?Ytd z+1A)-<~F5X&)2Hm|0c>`RZFU3i`~Yt~#Q8#PCDcD~e(PiF z!ssPvj!bCA0LeH+7i#}ao?@3(FFJDMg=R)w@1xwH@T)+N-#Kzhd*2N3*6WZQ32JWK zr&daz=5$U^W5!!vv#;>^hCW@}fvs_#RYS^=B!^<1%m66L1wct1nC2xhjKsoTn}AbUi6| zE|G+`MlG{*iIRSMRR_7aon5=Nl`03x$zn5DA|`PkJ>_Lq0ted~o&C+c`aJ~SK=1)2 za`!!$DRj_1MsHtFyk554gWWwtVON#NNB0>1Q>*n7-44b^LT)IL&h0SZ4JEc3{WG~K zGOZnra*90L4y&6Yd)gWP)0y@1rw+{&$CbWU651Pgd(*i9~>~2r19P5{rW$hS4%Gw*Ps~@kX=QCOn{wnB>8>MtiVf?04OH+((28HO@ zK{xUedANhI-XQg`j>fk7HM!xD1iFI^FclPm-Jld)0TCsaIvSmni!*kYc~%lqjamkD z&3#5Q$w+rqm&K{ZAl;!aF*yZHMXwJd+2E`!O=HH|Jk4nC>j<-DOd6$s1a6weZDv3Z zq#0Gsg0qJ7J5TS^=N>cJw=b404Lc*go;pzHWI$)5dwD$TG$V(28l98loy#jHTfFze z*g%Mm=cL`ehW}lvY?-MU+zxQ%o|8@YmUrvf@^8)Hx`3pUv!1Eqb)%k zpGxhI+(|O6i&0s9D(X>Jw5;i3H1Qcqww&rh1e1v1ne*~nmw>#ab%ntN1lN1#<>9UY zj2)Vh2czKyIoH*=+km#~Vsw%|-HggIw~J9jCU*-+;iYcKbA!P(|AKtbjcFY8cDHg{ z&6f20XqZzF*mr^B?(MAG3hy&K#=Z->lIBu1*12`t?nYEF7a&~ckb3cgd9QD%*8%;u zGmrvPx7)fK!^{TMNvFMTCT%@vtZ8RU`t~sHR&I4p>qj{n`c6`M8Z8Z~;fwl}Ysl4} z%pFmErC!D`cdkz`S<+v0R+T4v8Od&2xyo^$JxeU@Wu%(VoHu0q@Ji9rq&IU$lr^!p z(c0aR3!XZe5t8>4ciWHlHoEI_hxIW!n^rOR(O=~BA@Oq;O4j!=rkfKJ+5Jxe13>{; z4Gw}cfF*>ZI%o^}gIurxtOa|)8BhiyxaN`wx`Pa`0IUVaz(sHiMAT%UtEneX1B`gr zUZ=w~aEK%fU|unBh*SF2GDgVe0fxt1uU+R=eYr5eXssKFJ|<7Rp9b;Nb=lhL> zn35qCM{z?iytP30;fL(dy?m`#i$luY| zsjhOj4l*51!*`-}VGw26jC9xofd`Qogt^nn2mJc7+vhSlG{o?4@4qZ+DDtl%--5OK(13_0XvQ`e zV+YBqK*m|k*bd{_L1GLmZ>KLyk6|#1VU!G#FNOs~wMR2{!1(@ejM@*v*a@TZV5v1c zAjA^Q*ac(aU|BT0y!&}se%6fLFxLDnMCNc9dtki!w-E1X#_KTl4wfH>qmaFW?^MVD zxiP}1rUpm{o75f|pq`Z@2wg&G*AO`{g3zvV^Rw0Yzd}dbvu90X@T8SpU6s|UJ(;a~<>0gAyfa2fmos&iR63G@b8Kwn;74R(VQ zfVVK1Y{rvti5ksx!_|S>8M00ivX~1ES!e321byV<{K}q^wONMKka{oD`Y%dlk4miA zXqJm(4X0*Rm(s_b&Q;@Bzs}|=nH~W3z8J)jD6!+1$Rx@=<47k_hC;lLt+$2z)8|B4 zIF7laYh#7Co<1kae(gOVz+2Cp6Xk~XF7DSh z>6?dt@xw-S^Y_iBeaq(Z!(2eJ8%zg@eZ;8iNkw)lH}AAkCA2Yj#YR8E=A7jvGqah= z6-@{T^PUcqMwrl7d|`St4vmq>9Ku*$|0B$_9Kv)a%y@s8g*wa;9mewdA7L6!pd9xS z=HIW#fC)ykpnvPI|3mOoE!YLY)K}&91fx+<>Z|`-aOOmE(G|hDT0oaJtx0H<9GqxG z1X*7HBl7x_h`bwNqP9xkNzA{Zw%TEJ1!`MqY%Qy$@G|S_#fUdP?TECA>dZ8j2Xc+Lra$|<{oB5cm7{!-^w^lmQ+UhIGJU-$ zB)wehblwg-CLKgubz@QARIVmhbB(sxL;XBTa33Z3&kk)51AVj94zdM?hkK2#ySQd) zsY5lTQW|{6ev*Ac)j?`cMy3ZcRsAw)P1(Ku`n~eYgdJoVGQmBOnX}83?QYJ(N+;7! zaaplyMd_tt6G?8(K2sA(x5*roW3_7OJ_Yfu0pds_K4uE*(T=6giWStp+#IZ)w1R!bppEldd=3%+W2<2!>QA2Cdt=Ak|cC0D+b?lkEy)y)RSdQ&JSNKX)(>y4op z>s`<0!sbv+kY3w2*BeCk%dE|1|1={`s!yfoyE4tFshUgBbo$o^xy|d(zOFtJ)!uvm zWqbRpuer>ePKD*}tI(!ykIiMzblSu~t^)g&tov@VpgYZst(6-272Wi4O52apF5WML z9;dX6ePR5EJxQWo4~lVXr*2kBd{%&btO$_8*Y=JU*9@bo_jEw2I`t%}oy%5#4qF4c zdZ~)nAGAZun} zI7fUbYQwpk_*&T2-NJgze1?PIme%7O{n*NSw5q$c^=MUh8|%@k?zYw=)y*00Y$L+^ zZ(r=X0$~yRsoAu@7IJMiI%*M6rYZT8$7D{h4Om-13#nbe*iLo|tN)YXLmA#KSm#5>1Itmzz7 z+CsX{!KxMl$dEB-s_&UGN_LUg5qtT zci74-d(v>CCgP|jp1E}B2LnRZvE;7JHR?+5xolMiydmFx2Z#^WAO!QeYcuJ7NK$xqQAeea7xH%DS%_d3nLgWoc62fu@O7Z7wH zK_5RR?G_jbL609J_5U%Q*`oyy(HDGjOukrPbSWQK8ZKm@XWipEr$dsMsALBEM;01h zuis1OL-(bvtb9mn0k;xbiS8HdPl&V9C1f$eSq)3sMkS0)$%OETwimCUdw;&lh;|&qgWd`)xaGm z3;xLC5xH#w~;-IX*+Es?G%UDR~K_4+eUs~Od)2!Uy)I*v^J8w zgvQoJdMshoS{uOCqiGwNvxHt^XMnfvsoKbnCB(J!L`7V>Z)zjgmKYUt3Q!>ms*MeqqMpHqKnBB|V|KZzp!%bgjT zn_KSGpGJvos~lF2b*>-H&C1NDC-vJ-TiH>F=G*E~AW|+CqU*MjiQZQ&Bi>II8`UMA zCp;T2V_AhqloanWJ#5>iEg{6zWo%SmU1EgF%4J4mm0iBV=;(D7v}GFhfUByME~7Iz z;A3ht(-qNHUmxY7`7@Z{+7E0k=z!Wp+DhJGI>3}?3{U8`0G>xCEXHhep0V=u=rdI0 z#SbegQXgqhq-QXSw({OH7=>9{!PR3#TT#m~imCzLS~+bcc{$S81H3t5#yeYk=bx&` zogP2h%DUy2*7ieK5J<;_kg8I)+;Bz*DtoN&{6&u-Z6$OC>9+W&B0Ef8@V+saPsH?J zVWiNFEm^^=pD(t#dVg%n^EG&(qI3nDy1hS^FIF%U8u)QVV8S}?kqIlQl=zkO{sjR% z-6`0-=o!geJ;hlRz}B-Gi(S|Kj^A4@6;hj9SF$8_eBvvtD5_Mhp59z_JZtn}>@5|a*CLE+E4ehKMtrQ$~IaNDRN6i>nYd_!6ci?oxYbR+( zx&B{OjIgGI{AptbupI4Fh3P()J?0-M)Vk`dd#QGkE=F_raeoj=UP*R~#Hi_Ye_Byr zy0q2%`JPcG7gUaX)o3XEmMp2ui!eCm}oTW`TQj zHF5d9bioPZXkRgyw3oaeIQnld%WSevugoHrxEhs@4ojXzjU$OT@3g%BZ2A6R2l-hu z9)hv*wA6ZzMGo}zYNMN6e99=FXzzcHY-J#{<1@RglHP)aX7KZdx1rxl7g1-cLx2{i zjH+n-9VG2}MvOOnF=%nEErvebF5}b8gz`Fn13_0N$xY#mUvGfidfsSOUX-Rq*zG8| zGtQXSS4CuZ5qmVF@p;u=sz(`F*MBVsUNBnvw!ihZmw!|87L_$*T}h=i#%-s;hESyq#ws@(GmN*& zG1I;(v2TNs<+gWYlw+m+)=0`mV}aY=ZBdQ~?d!@HHyXKadpAXgt-Udri#jhEd)?M9 z3Gw;lQa2%IZHVC4#ZKeICepC?K$N3U)@`R%_kP(ZHKMkb)Y@zucDnzw!_HJAsT~@^ zR?}AFg2^s{^;HtN`5HSK_I`lkI6Uu#;K-8rZH7k~b9R+9+iu+rdR=PmWV8DB*Gs1F zG$txz-d_2B7l$rKcym*iwxfN(lCj%Jb=%8T_@dii!ENHg9VYD`m94Ptb4dYy}`*mx^q?jpL$G8^`8HsLt7Nz)< zq;s>GG7wUqM8FWBKZmm#>;KvY9yz(6n+6oSp*Ah->NajmwmvKdWZQM4Eo>3CF~<6zw+1{XUbXz6zH02! z-?Fk29dgb1z;ft(rCc}aDC;v1v^0J2f98lI7fsQg9=(680G#v6(GWC{`pD?=# zYqV4_1muIoU@JHZE`vWnP1b5HL4PnFECw6FF>nz$n;-*H!4NP5tN^>g32+rSn_?Is z1q=uIU~N-OcrOo^!5<)zrCut?0dv7_Z~~Npkmf`HQa~4Kpv##qq z!rq%D6YH9_4CvCj<}J+Nsd{EZ&-bwAWZBWly2!9d`LLepHRfc=2X)L?`3na#eQ$lU zL6!ABF+F#7@E4+F>HWdoc&l_-eG>T(F-;mPZ`L;xypzUOWY9p=EjQ|$aS~CVD4Qmj zmE8qCfvS>LpZj+yZ<`@9Ji+vMclj84&8Mu8*1Hg8&vWsnD8Wo3wUY^EUC&igYctN5 z?-x3T#z{;A)9dwn`G@~Xa-$w^-c`~ih>@ucOpnohoU}_YYe`OIrDoCg>rPrf{(-(b ziE7P)Y5|gl7p)1Ij=IyKjl0JIDZwTk5YCf2CF>nem=gOg&x>v+st;rH;(6?n|ODelP#DZ=TdX z;Eq%CWXB>W({X(paGv$$K}ofrGr7~FKWfb#Tz8=W^x90AJ+r#2^@g@3eKy{>$C^2tq#rJdP zwlWh9BEr$xAc*DZX>GQwdYSBa*wm~CdV?&mxYdrdSCsEU7Y&H7T)1wzxzI%;fcBkO zxt4h9G8N2iYYwA1STE9EY>VUzNdD!P-;j*?%Wd13e$OrhgX|Bu%i(BT$^1XJii%|3 zJrrmS!MjzGZTFasYILhq5nO*LCW6*L$L1JRNosXA{jcd2N!NA+WaN6X-{%Q)!vNop79C$TjoWn-QH~AZC2TzxZRd6%Fy;^ zUGL@qZ{0XA%98eGhhY1*SCO1T#`kHa zRj2ZgYZpoVRKjh7@ph>6O)dW*c9ATB;dvRx*P*sbrFLgF>OM?0y*2z^+R#dAmn@JS zdO`nF=$)3*CymHicetX%#SzH3Zp1YjC-+xqVl-xzW-~v=U&r)Gp0zU-HZHI}CT^4m8c6eE8L*(kcoWJ+Jk8$LWE{r1uzJS^oween-y!%MVe%GQ%Msy{i zZ6x%5xXkZLLht{7NGP!z30?mGpU}c?X5CiXNvL^*T@v2gnwUj~bUhb_F&znKyut0~ z>sI#vuB1`kLB2Tu9}2nWJ_=b(+Up|Zi~H#IpwqjU3HEC=SGw>yft2njta?{ecjkG% zDKNadS<%XtbT{h;vzT;6@>D|w4>E7g%h_hF!Mg7cFgSPlZ zKXaJzb*QxKZ>}<BfCZmuwwfs4S&)UzgN z33`JpFaxXx#oz?E44j9sFX1XVA^&t&mqIO2TmL z6xwaL*_)u&?b6Mf|1kWW6Xo!5vsuHP6YX~#bQ`)z2Aj~rb@(d}=tr?hMyvZL;hjmkuJ)Zb*MWgaMvrCd3jW!5pEcL=l^W7d__ zQKr*K$d!>}hyr?t#HUEOrV&NwT)91lD4=%;o2nCIUNiW%_vX0KG%tniiOazz4ZfH5&ow9Rdrp z5txm@_qnoD3qbD>sQ)km1qitEr0>IKf^tdnL#F@h64~;$=Ffp&Cy)29;Mcj6Kjsnm zPr&b(CrclJ-|Th87AD9ULDfmb7WY$FZNABd`(EJ7Pzs!>w zlgQndck)+Gg1->{?|E`y62<%dPJXLg_>16In=B)9;a8J683F41RP+A{zr|#^olE*H z?&Rm?!RPyDu6~o{xje%6yOZyo41WpyM%J)BL6IpPDSEClmguJNbR4 zz<(P4hRO2S6vA(~lmDIO7s7vQvQ)_@{9AYO7v{rX2LJqI*_luH^LO&=KMMaD_`gn; zzK@!<)US8)_rvG17}Xy+MZVDjky3lC*~53CS9j-ubAeasK&`nz!DD7kgN}U7V`g82 zj`;dxW+U@Ies0Tuz@>XVFoS_KM?2_0EyqUfpo6p=7qo*O&~ijg#X%QmIeKdceVFB# zs~z-LmZNk*kW&s$HLL5s$@00W+4Mt}qscTJ^fs0wOFQUUEJu-c(1}=%Pqc#$!*Y10 zk{PY5G6dsaT<(>)6jH z^fPA{+TS^YXFk8LpHuYnWA<}C&jwA1uVvJbtut6Yy=*hiXrUwabHq%ZzqFsb>*wF? zXFl{<6Z1Z#Bi*Z?TiDNK`njL|oH&c;N9^Ye{rr^uyjnkRu%Aoy^IP_F$ZVd^+s~=` z`B(dSs($88t!boHJljm1UBG-`1=tEo!4=?a&(s981^qz|mUvm;qLUV#zBoV`dNU zL>izFYz9Zc1@H%mN@W@adV}$x0IUYZ;25|F9BIs=KugdYj0Xi^H7Eurz-90Ui0X_S z=nb;KjLr_1V>J)OTx>F{ExWgL)e~lXaBp@_s_*#wi^ESaW$6QFz~4D3 z{PF{8=Ub<)OTLunEHxt=Uh>7F=h|}(lx^}RDY4!t_qSK_FU$U=W;MDUuFOTsm8C3= zV}{!q(92UoI$oB{x6S)h73uRdDcwa%_YSwqc)ed}u&jQXt*m=}Ve~SX{R+os{T&+n zQtD>?QIKePeW}?@;tS0XwOJY#vH`GJc6`YWr_+)?^<@xWuqkAFV6)6CG@E-L_eH4J z1bP#6v&=cg$7l{NR8F~2NG=NlQq)_co8^Ub#1XN~N+Eig**x^8fP%QWb3?5Z{>j(Z z?1e=Yd0`o?q$=g9If74E)$r7oE6Yqz6V}U~sEH$gD1+wE8RJB0*#CZIB zC{^UqXHZHtBI!9o);wdj_V)Az*Q(IFvs)}xtXj@*rtN*2O}8J8n4uD{ooBT3=`0m0 zsoHt#Y1Z@mz6^?x44i6<%z4XM=ZKP?tIef`sgtul266K_GqKf08kMsvjSh4N8DK6b0>{8b;Oqt; zbO#w=s-!<}e(2dw-jiC}J2tW-G^~bnD>4&(FD0J{*yqswk1ePi`|S;awMAxbP$6;c z({XKI)<1>M7{t3y6J? zYfb+id0-z{kFapJ-4j$piq@JnU7q{M)O|bBI_vdyluUiX^aM{Pim`|PK3HV%b+0LK zo;>`wA0AwfG3LWqbXa~|Z`ScHI$UAPx>NZ}GKaV#rR@gO)Qz@?QbU#u8f14;+JWJCuNy_F14R`l=1TV)tBk- zijVr*kFSqF&j0I$glV|hjEOy|99H*1h8&Z}Wc432(Y{(kM@$YgH`Aqdku94kPyq$< zyl4Gxq0dwU%|xGUVF6Zy^9_qBTg;XQb#HxyZ}AqkHWnQ&S+m9D+5+{3ZzF^1Irj>? zaMXq+mH#SIOONQ^D6AoCU!`%Pbc=IYb5JxtPgp}Dw!(SyNJ+b`<~PdidCyKZ%Gb`f zu}Rk*BOMO%C2yM<8C%9<2wAKLQos<93l@WovTmChx8vTn>h)sN#m{kCFNBxW+{rm+ z@RJle(RBEJ_@|`bZgZs>o7ID+3<^OpI0kM4Pft=PQG3le!}SsY*PWAuH_h%oZDj{E z>_W7)&i9(}EB5V{wQrgWf>MZqufOg!KemsS_OUnh1L4B6C1Iag%M8!vMH=OPW7U51 zpz_!s{`BaPtAY0};@54*zdhxVIXiCP@b{5|7>4_B>#Qd0Y5|{e!1RvJY6} zy!9!O(gP%0MzW7*%l8M&I-!sI#I@k5l?hq%e8ukQo=c%a@E+tdbp!c5;xrsn%yY^~57gZXDv4=M{=4 zp4x8C-VU2###fI>*g=+=-4C19Lp$VD)J>3%B1RUVk}CZI{9QUKE@5`!mGgZty*~yp zgROMV9;TjOo@mFVt1iUy_8zhHlX(RF{D^+uWdrhvnGpJ}Pg3iLFE$;d)|g*VBu=a| zb(Tw4aRIfm%+b#mU*SU&a}Sx^ND;#oY|kmeCG#j%5N?0^r|>Ale~8Z7*om3?O$N)> zbXA4x_a&$zI#%o!sM67Z;`6W@yRFmvyE9V^A zAYy$vF~WNEe>u?^r2A^G{Tl4SV=P*{dT6i;$jK(gXR!4?5Sxtt& zM}d0za^i3JUg@B(C>Ls;GvCgoHgsKBuXTMnc5x_cN6wNGY2VcXM06dJ`S;Aa4Qu8*XOunsQQwW0jqlTa{esW*N9Dl#+-RBpXodQ9C-r}CwD{J3IvW2B z@*skAx7L8hr+W17?G~QkAm;Jxl8z_Y@iOK-QZn`fvy$Pq+nI8FCCm13dv9^6`G+#L z|4oOnJFrz#Z2;JNlTGU|9AOhY9&5?CquxHo* z3)2}g%rBJpDMH_VVK(r6q*bTy*DoWlLuXiDg^}DZO{e?o_4)#+zN4A>n>(_k@JqAU zaNF5cj_Q)$ktyNuub5Lb-z3++qHo>$6-RHwEXTz9O?sm%FdP(s)nF?)3a$W09|mWc z^R@Y6*vpK~rM|DF@GZDYUD-V7df9C1n>kbI<+;ouVCi{TblIF0ltK*SbquqY_0PA* z=WopG`UpyYe=Fi!PQ7c%=x@!@+*f<|TZ~iRSBwA7>|(?g5Of9D3XXycpbUicrCrJY zkF$3V%(?#m|F7%X^?Gd=*Jc;P#>O_xStdk{=8!|?6bd;l!;~}C<~_6JEXjlia+pw( zWQ8GSM5$Et);noLZ+hdcqBoV^=y!X*4!d4`KHu-}kFUD#^}3#q!}Iuh9v;tA{=Y-k z`!iS%T+(wAC`JQ((!92DPKL%S62N(korNG|Aid>g{cXi?Q2zxlkc)= z-qab6F~_MM2$k_K<0x+_J2a^ROyep<|oW0QZDuwj+~S& zU(6`q$=p}Y!le&@tL+J)W={-nYjLX@oesb+wCH_qGT6OIuq84s%pdcaBM?(E&24`w z5cI)shE)FxIo%?geeOg5lRVWTt2+5JxdEBZyYE&=&A%uamwCUj(=W{6YIn=vGB4V^ z#fbYeIdqE=ZOMC@ZfwG3FfmOxx3KyR3CMM9u6wsa>~n(pO7gG7{c+;n{VO?F!=ETQ zztVN-&P7owI;zO<_&=K;tW)n)Zrh)|8km#wHGX526~A+0@aPZY2CJ>+%P(S9ZE{~MC4@1ZcA=*0oBnC_1EF6dB=0u?UdcS5S@ zSE*jyY-PPesdASX)ffjZ-wD}XUa0O;sQwLCScwe2TVANH%Bs7>ks44>;sW%kUi;9j ztKz!{;YSEf*?a3GWJ8Gh2||w&6?FcM88vPAw29MAXSYgun#}`tv2yXqg zdCf_<1fe)~k^iE*IDV1;Jm*8E=-uH5xB2SPcM}cC&BH9@Hm9ArP9dn$kNG*@C1ZerJSDXP<2)j z20~a>Dtfp>qGvdSCn4-AmFL185_=&;aL=NCq0}nBQ#o?gYg^i{O1%gqhr;lEsq~8Q z+8aXoRuq97y!0!ja@a`-uS9_x4&gUTrMS~+|39kaC~*1k=p*2{S1Ma8IketVgyj&D z4@s>^Z&FC|A?~_u$SGbamAzrc=417h<;dhnZ=JXtN9CF^b=tV}X+f(+jub_D?Hh`& z$}RYHZa&oap*Y}8^6=~u@Xod@(^utW00x2K$|3nfG4SjX=}n~47#r!0^$eIKFGjNX zr!G1ltFny+eAZk+MTT3z-@RrN*&I$QoKPgL(9S2|Sn*7q&4oNGvW4K@VL zh84Zbt9tABnsIlf(F#a@Wk{#0dZPnx*=}f2gTq|83v1xMqb93Tu3EBONv_7;G6Go5 zi}ix_t4fjT&ZrSYt`ziTVdk1@-l#wi2TiqZxpGK}+_jul3#3L7xpKQ2{-k|u1qtU0 zhI4v#Z_SuVB$Z07A_uvmO|BF8%Hgcq!(7>rPIt4cI@!I0KY=RT?`p&pwc&qZhz#_x zXe#g#2JJ3h61A9U!gg67JCXm8`dDa%>Ksc8IGQ&gn7UuI{VyrlJ;6&KiDha=1E;n>ay|7kKTP z8Lmor4L%C)2i2Q@F0E^L6GNJR&e54qRg4Mm@qBR7XNKh0AP;BA2J>;qd|asEwf6{I zm4-F>CYI6TUhsu^_@>o|RE;(IjT_?X5Lc(aczw1p`Nq^SZ}JQ2b;WNy&XL?ti zVT?7ySeif@?kctJG`xO~``xZ5c`3AHpvWmHdQ6Qi(dUh&sExWLex0k9+&(!fQ^id-kJTI9Cc<0si9>L%; zK9LBHs7KIieNdcR&--}=Ps7ipS99V(!JFRPyU(-W3z_gGdDkb|+hFF!-ppZxs6Gsi zL1&Nwa=;p}6C4K@ftpB+1}#Av7zbv9O<+GL12;j`W9R~%!4NPFECO3VDJTOsL1aJn z{WRzYBNzg5z%sA{90M1@9T3fQOLLG0GC&?!33h_x;2Q7_U}wtyp` z4BQ-8)S;1kcS~X zoCY_6|4E_%Qb7jD0c*fcz|gLr_dA_AL^a!#)ZbexWY%HhTDoM(>hFD&pcz{*PWSgl zwPIFLUw+s;e9$#+VtNM2sK(bPcxKS>snaZNdinT95(aqHv})S{RNkLj(yGQ+E#-Wf zJb)U1zN9m4DTM>PVV?PJxwn7~^`!&oC(M_l1H5$_rhQ;~s+218*?f0!pvpMa*aV?k zzxfh)9ADBM?5g3z`Lw%-d#EgboZ5LfvH0-=DS5oS(>7FYE5Zl}Ax9+f32$N`N2EmY*ZlwIPaX*WQ}Ew^LI5S0f}1xweH$e3c7MinQ3(Z637fSLV(s7~m97Oz|v~=02yig7d zVrpy6Ao?o5I%sO#Y|uKym@|W_7}#x#8gQzj@J=hLtLB5f4Lr*a7Y`mx(GL0X1FyL( z`p%Qy20k;Xl%>ho4xBm!R+8oEA+!}lcl!`3r4C1m&kXUlcelPsnfo0?4xwy=6wn7` zg4tjV*aJ?0%fL01Z+U1@hj-oT)cImIy;n14n$*dvZJzQjrF{N5k`=(`pYkdzlJVYc zr1vqkL$Y}e-`9?j-d-kQj7`tUFnGVn@IHeRkE+sVlvkZ-Y>4k4Wsob4_9_X3ylAvR zHr{idsu;FnjG?smn4pFeV+@veo<>_rrtwW1@7v6GLv!p{L-WM3LCx331~m_S+E$_V zs@8tSs~#^u6Z9i;oXt>Ga>fPyxaN2tGCt^j+pi`OYbl+4X?CZ@(rD?{mndal?X+h5>JsXTr z*|Wibr#%;Z-|u*D^1R`0c8GTw)01y!Fnoeb8rY=dk>c~5q*a1_T+_eK~y zjVUT>i|+bdZ?)n#bG!pW`0?k=V7zkjjHrH*XE>Qk^MhgElOGIkgBQxfSiJHD?_nKP zhQOo+!BCVfQ2L7RTj;$%Ozm{u@iav>YiUsO@=~wv_S|2k`1&i}2UV-GA_I=pD^kcXUi(%hmt7HT+N^(^hLUn?+-G&k$C&wtKPe<8#d?DN&^`n z53B?`!EtaIxQ5ZjgC=tFOK+9%ExeY3GH_FF;M8=|aOzgD3G4@_!FAvt!N(0cgCQUX zER*EFd#lWhOs6dZoxu>01D1iE;5fJpTvX|?pe5)J#(_m(6F36Oz#R}Z60X9-I)fn@t_W8aFH68Sa70f2-CJkorcneRl!2QdYBZ4sX&?jSft6q< zI1a7>?--&8Qosn11=fI_-~_k~yx1ROK^xEqj03YlA=m>>fXkUKnR?0_s5)dUkpPRp zCQu4a%c@h}#yu}TO`1GII}h4`Az&I<0=9r7pbY#DA~C!-0iD4JkOh{3ZQvL*`?yMQu+_?CYhF1F_jC#OH+D<*LjxzQ8oytEL?% zSAx2Ss7|1j!`Wjv8z)xzPkYtD+Q!7ez|-C+y&2wiE08Ity@}!7EE&~AR+aRx=_0F> zV42e^IOD70Q>~%$AyF=zrmakryXGV28*k0HM0c=9!KFpn@EK!j%@F7d3j*WK#{%=Q z`5T6CiIV>cr>dy|GkQ(JT^^o9x11YEH>UX+x-oElr&ZBZd=sVT8TvzsGU|*WK8Hu( zXGh4x4W?Zt^{X@Ve#R^fCQ&6tb%Zrz>~lsqBMqs9Z@oR-O=bMI^fvAzW!kTh72lFF z?N^u@RLZawop_tO&03yeKxU^)9dVZt%{mgtL!!UoO54t5-pIH*4(~{svD2molctVL zHf3HaEAJgOmCwrXzd8P&Um?Gid6NR?9sUzg*Kg*YX?7z2z!Z`?*~T*XG?nFNkxfSS z$(2%aw%qX6RNUtvw16;fr8GK+(s3(;ky7bjSJKaUYs=+tz2WlGId3I*U0HjMn8cP5 zlOyN6k-`82iy)JvB)d0sh-#+IGpW!ALzR8jmSIRSNqkMCPXm5sa zCQCe59fU`&LUr{Ok!k<~@sxV{5qRYey z)0~%bZj=r1>D%Gcv*nW?%lr5n#rG40cOcZvmKHyG?OQF_8lnh0AS7nXRwv;$gjPim z9>})5bWA$CLTNTAXF4U=rmGK|jAXH62m3(71Lhf22h2054oHzYit2!Qgsdvr2jqt7 z61Z*DgD)TVojS_Q%2)s);+s%-UHylyUSA_QZU{4G$oEb{!hawXLzp{59{rC))dEG> z17Yn9?%;F~ZYaWD2(QnO8aEw;K{p}ngK%JmbHyb)C=}s+2%pZ7t2e!g9-a}mywySi zxm>$;Qj3w)Tiz75TFkfw<9--l%$3)1vhMZUs7r3Dx7vzdz5a*;P?zRf`8id#-zpz} zZj=GPB3=T+Te*_^tE0FcQiOvL4(G~MC!y(Y5K18gX3FEgIV4s=h&TixdSF2HIT+pFwDzC(Z6U2$L1za|lo5$!aIztRj2?VOXB%_nc*= zOlj4QJt*W@tz&uO|y2_|HLDY73{&L-@ScAsntD z{2e^2EbsehT8nZG3!wVXLoK#7+?YoMdgzV_xOFsKfTzULa9ndlARDUxd#Gi$hRO5M z@KC5j!wse3pYZ%MU+#sG1p9S|hOwb&xCqt#f>khYC=HFn92zdbqhEq2>;+T9wor$L zL1Ae40cvAg!{i13GZDXnNB*M-uIsRb z&a(1?fN?g8qB+wc@wJXDhv0*=aMFAV-aV7Ou{DNsuO z>r~RPGD`jn&-I{^t4<}WV9@Wt@cS$|T-gzJhJ36Nflz6-G^^quOorgU2VvN3EB7Y9 zjJKVJl`oyzC>NCQpYV*DEfu0Pduh!^=^KSGoj`rOEqvi+ro<~&bwvCqJh~g6zs;7P zqBMIE!bWLZmB@G?d|(N?#>lyHm{R?6Z;q_4?hwA92w@N& zm?IUU9YGop4Z#QDkvWpkYBvGXpM-sJ*fu|xovu&R7|BI&x9^DVm zqB(LV#^H0l8W6%EtezviYB&h1AowF7d}(VenyNky^11!q`}HwlV~Lu9?K-Y($(RXV1c*SAijXu9B=SadBGH z^3?AeN1&phHn+s3U|D!H*StD%=qNmTRd^nlD?i0K{BBzd;c5^D+rok6RL%39!n@$n ztHYB%SI*UPR3pi?5srp1#}?k8g!5`Ue101qJqDgdhH#AhTwAkGzS$@ZJD2& z@(Swpf5$r#eFHptO?Zlp*hkCL@mllp*vBM5jfMKvTOWQ-B-q^OZ1tGUgG@wYAt zvgXOVbsd^-E6w#F%(OLcP?|rj>j>7^dIT#8o_X_RX+4MVHxT^wAuP9r1FH~ztDZx+ zdlJG8;5jr;rX)Fp_d@VDgmBCj&R4=OCOL!~)=@W=4z&Ec6kUw&~4w{3)QGKA^2aEDhBuGq*S{3bkl3wU0bFJE#iQ?U3p zM)-aROKjmHCH!xv@B(=Bmhc>#FYh*X2;YVf(F(#BmN1RvzQ&G5a%>YMTf^}6d|BE= zOKSMF#i$Hks`!*R3}GXaO+%Qnw3f()CR%kCsN8O%)sAs;VZARm!j(vJQ-iB}Q?7a{ zk+J4uK~t?O1M8DbwK|~>;CX|EnykNF@!|4FcW6ei+CXWzP@Zn4B?cNUH1kXuLt^pZ zpkWL#R%;zJ@7AehxEgy!Y8$T`)P|RM8gBS}py$#}(3Qd6sMykab=sWmWOF_={MsUS79nK<#ix#s6g1_Y|eB**&_$NLV) z`w7SUb;o;TvY{s~nS?ti?aaqe^D)DGtTi78%*R>tao2prwJ_z($58Vz!+fmeA;+3% zeklv#GJq2;v@pE*riE5NFwsh9mHjH44@%&Et$KiUJw|E3#We==VWMidpciWB8V6C|6oL^4`Q@>WrvY^lZgnl3W)xQ65# z%GY9yUD;BL3jAwHF!TLJpboUu8V6>tu=ok9vaC}k)}q?qN{bFWEJ0c&n^s-YT50}3 zSBs`HF4CZlZDj;|K`T;Vt3y&5^*LUnl~$9uoi!h~dBi!>Q z1bVhMw2n7_EifOOO~<3HwSIg7F%M{UsjhhHd#U z+e3JQyVV`H%PL#3ZPr#_3wC4nKsO5cCQGwUJ8!E+dawx_JEP+t)FMO5Y*HG(JQ#n6 zJ&3?}w(BP4ih(87QacX2f6Go< zY)Cx6?u+NwxK0RQ*vsvtjrL&2Q{JrTj4!6iPA%Usj^1d}8C}@p3}2SP;Mp+K^rci$ zFt$ZJf-l(COkesxqQ!c!q8Y(n^a%V|&elDm4Gw9TM}{}^)sU)Pv`QYVW81qB*3>Rq zst1c$v;JC5S*s{m!JrKG%;BlBt!`J8EHad^daWz$?^u*=in2RTO1i>+%5rSkjiko@ zWG;Rj(GC9F7HK~uk1Jn3?*@OZd{cer?(kzLGWjQUhrg3WIu6N$_2*o7_{Uq0{U3#Y zn$4g0DEvz;QW+!<=9-@#g}>NvtSO^JzpD z!=@)Yp?Mhgmh`8zo$rSqADBYj`Xls-Ei|n^LJVb1p>5DS3|bKy&4r^E((oj80Q~pO zu{;?!0R9K~WqeJW6zvgy88JCA0AILnLP@oG91259GbS02BelquS_93)h;jSl`0}O6 z-~0*q83>yEL!QuLWqxn|EW=%Ps<+Z7v{Z@g!&~e?4&AJ1!b5l-#EX zQ^SSDTc6SvSM=20Di2Pe!l!LEVzFrgN@$oX z0~fRV(I6EJ1bJX3*anV(^HUi}{?1F(G*+5`ZeRq+0n5M+a12}ocR=*BEGGeJAVcye zX;o&P=k<3G^&BcdH!uR^fMs9@I0i0)J0SXbRDd*)0rJ2~uoD~y*MK*RiFc3!hJa~c z8Q2Dnf%D)Fh{|T3zd6(O-9QG&0V}}{a2#9&-svP3NCEx9G_VM414qC`a0kTxjf4mN z!8ou8Yyw9>8Mp(Ya?k_%gB-9dhjj)=cqs$^8H5`22jjpRuoIMln; zK^eFSV$szSWB{di8#n@P0)HMJgZ>}~ECc(&shRw7<&&(SGZ+G9gEim?C%sj%Mi{K83okI*je=rU# z0-L}wa2|N)!UIylK#&8Lft}zuxCXrQSmXs#K?cYHg?uSK<*4^QJ?txd)m6Fa4k8)>YL&T~_Xgt%N)J)GWe(baIR0(o`DJdwPV z%g)_rb?a`n@ zLfm79Bjz`hFstSCtly0#Bg_V<}WVvP_zQ`R}otVC2AJkxg&X6Y+#T>F(nwqH}bUlmA6>V%BVttc9pqg-BeGF zxGX%MRFRJix9Idp`N$et&MK&0Q?$Y~PYv0Tuld7YwTNn!pC&hQvHPFT z*CGR39PYZIi&@>qftO z$~!M;ejmSFDspB@OWj#aOPVJd&Xb|D5Lu4Mhxa@(Z30e zRQk-Ok`P?3-IH}YST(t5HpZE2_kww&d^u}=?Z$O-3~mZJgXpaJwJ%XO%$=1Y(@A~p za>8`FVLEN7;8)D*-W6FklcIWXx*je&^T@5^FS}b?=jN&~**1;-co_bx#~ePU%%un0 z_}Ajxx!U7yPwMY7A&rE;K9BBP*WV>#zSi2)%W@nsAIAZ|bCxBJLo7#*zm4^b{9S%h zj(iV>c(%J3O%xmS!Ued}!RI(Zd z0QQG*3gKccI>bm%j!+5BAoEDQ;!ZDXGs0&6PL1qeM&%7sK!1=0mVo`>6u1MTmO}^q z!ECSw906s(yMm?-bOuAfd{78ZfXl!olv~gS^a10*Y_LXLp{||0oR*>v``jy5Yw>zZ zRzxPRlBCsIt&n7vFB&Iyy{f5=9sOR_8iuxlJ_`4ry}mdpd{y&%My-OcyTf-;b8Wk;8ORqJ2;w@GO7m#YOBpLQ%S#pswlO!9~ zP&p^bA@gy;`h}5Lb}Xg|Ns@%M21AFnTAhXuTdHi6Xp%c<3ssw}?XNmXURsN-J4tPO zs$y7$)d!0&YqcKkmJ+^>58wfU_~^P2Ssz!itMzHLlsQoJHc)!3lkMxYq(BcYv{7YW zee|lnsLujf!c*Tmz-ztcuuG?V}0>$C9r|OAHY-? zx4~EdYn^JNvfKWuMxaDxd8GsncrDz3rD@cv;-5BXE!>_KtBVsiYDw-8l_!}HsD$TI z!Fg{Ehb4+*gu`Kna>#QyoKOyh4u|W?q155PJVh8Mr5V1&C2KWTyk)$$<5l9#_o3=N z)qJ0!-ba}4Yt?(6`F=pX7n<*9)qAP=epkJpH{Y4lsJUXBsh(GfH{Y4uK)w0S3Ez!fX*B*EK z;`8rlpQu&XMo+o4h=y`3Tn7^5Op#VA{6K=afzjx{a2};r+t{Sg!Mt5O_4A5ecL(!! z@e%LR9hj47va4=_YT%*0%dEi>hcm7?Q*l){PAu%e&Gc~GaB!%42#!A7oErTeO8>NI zs#aE?Lx=KOnS15lW74KY9n)9EpejOqeUCnL2PwJ|M((~xn(+QNPfW%8ITPGG;lOkd zeW&&y$8&YqN!9W+@s3QAr*~@20+C6A9Qwb3CHc z>U*X48m+1<+D)~Y7xe(suVOe8tJT#->a!b8n3EKFwU=I zU%TS1Y`7W|lU0mY;}pg<#Y_cuR!5xH)T$cJlht>BaToEvSOZp!Ae4jTAhFUd`on;jYVw{rcBh98w^%OhH$vt#NhcynS zzbZ(b-4ZdEqg;1H`@IssSG67N*->eyikj+Kcb0a0@$M)aR+O_Uuxbd`S)ScXht$tr z5ap~|P`bf5vk|BhIe%*}*>sdf<-ugBwXb|6kSXK$F%paZ|HKyZT8WnA zn`rSTNxc#+L4GM=NsJw`h6h;|@EIW!i-|deKq*Cf;z2DY+;&vC<&q2iI0|LNdv1HV zY^Gd5TAzwn3HM8dQb(8vltP#Wq1FA8TdFmx+3J2fgF^xoGu~# z&mYp_13#C0Xii^ulfYq3m8b!S(f1tszHTYGhqa`TuUmShajLgRd79jYBlLMVere^E zhc7bPN%=tYC-BQEqalGdHR;lVPl$r;UPB6gWqW(h2Sj9nq_^``m+SF-4#zkUOol9E z`e*+KRCNm^kl?Q_WglpbtV7H*CHx5GBMTo7({oi>E1zv)Syule<%^>@Sq~mP8=f1j zW$O_~THjKH=@9O=mRd(ipu3h5BiB&Y-KdCGsCz2A%j8L+_Rfw>Idl}!zajeO19J6f z`D&3&N&XN*4usG)GWbKsXZNNe%z)6YjePl`Ln7uQ2)Pj2w~>w?IV1`cVJ3v#ZDgO5 z;5!B(55lE3(&Cub%)@i*KbT_3IaWT7%#>Yn4B-U`x7$dsj~(f; z3PPn>5USJ1Rf*{uGf~{{g~!Q=cXh8^`a({dPim)6)?+)_eDK!Jtfny)S!eYe#m7~Md;Valy!1i1RdHO5Zp0n9@IN2^K zHi2zH2Z{KH!~X&QfUpw6`VNx&4<^TW@>K_u`L1GE1w%?lN&4C$IsR)1t06qoQC57- z;P;u1W)iAWuF6lEeD*b+yl%(&3~qkSXYh%|V2``gB<{3P$ETkr$6iHM-A-1H6?}o2 z@V(PoAYePGZ%uVIdKyP1%k|SVIz7$NTjV#!d-=iG&CTDzgR%RV4n~)3M`Q&*f}DvR zBa6S$B76^8epZtUU(-2YC#hdzPgCh+V}Jv8{sZ_&s*Ls#p7#h`R6BVSK-i$-n2bl{9uJ+7xa*asZ<)Hr+z zcFKCnjWgPPfhms!6Iyl3daAqox>EeIza>l7kdE&>BCmZ*)AEkRsk~Apb+57rU~A-D zQTJZC`>kdlo{}l;%E*JY$lkSNWO7k>eHs3)&OX~Rf^EAiT`Exj_hu^YEUMO_YG)TK zI}a3*ofFSGx=(B2(bvQCT^ITAtkx*}JBwGT_ekIyWfGm|4qJiEM9RL=DoA_&teEfi z%92y=Fn2HMaE^h_50;c&v-VPn&352(T65Cl04#bTo>b{7Kb#{ys&q92q&!iDskbD2 zN7DC}4(21>e6TOPdQ5M3FeB`upgQ8cRZ&nf+@DgDM_<9X7Ms6qf+5}t$%qN zH0pblZ$wAgW3u>rt$m>Ev0#d+kz^m$)LA8{kJ;w-QEhG&Y4A^aNOt8s=%47>gq~yl z|m1UDmitDp3`NUd_q5>#2HlE1GCKy4Pg z^u3Iczpos?rUq|@tovB%<*qW8jMRXWl6 zyQKL;a939x_bwlFH2r}d=I8XfzlCyet>=F0)VDDxv2A6|>$+SOFBQM`gVwsPvId-~ zppW((NGR@DQO^zWnFClL|BL7l`G!5NwiaT`_ATU#Spw`-T&h+vSOQ%TS8Osik~ zeI=c?@xf#j7dIy`^i4p}UtMqDGlx)aSCl00#>m#EI_Hi~OqL1N^j?~g)eP*B6?b;?MTM_3wwe(3II<*sO>$x8Kus^9MUDgTldLs`#)Yb9&b`KrW zM-vDs{m#V+L{arH6QI+ftdK}Lnw>;9vz&eRhgB&alBmyi`^>JL+x3i@xOeL489uZ7 z=5{SMJRwM=a@5Jzb9|M5cJ<=epc{dtSLFrxf3- zr{eBvR~%7aPjdT0jZTa5%gE$D4aj7=IqMqegXz5#|It9D2fdYh4GFE;IdNlMF><|6 zBLZf2Lfo!A>Chdk--$+gj)$H^ug0VX9f!}=lYT<4COqjDeBOi%rrjqsSd-UOZ|R|R zM>%T`n-V};@{*>c8x8k_W~3MGbV)O^rf#R=t@r8w@c7Ku!R_j0=JJ{rdaCE{BXX{V zJ|%>zTYml?v+lV2aix;pen01qR_R*YrKSFd$JfEAVwCaLC?G=~fGOwE;&l(`6TBYk zj))ZfOY56=yPBG1_f86B*ZiE_t`9iDnUa;-PCwx@zeBgHj+y37+7tM1`^%&4_31O0 ztzyLhH~}sL*J@@yKoighWP)X28#oRwf;%AURV>J$KbQs;%WbHQ-(Aa>cJ@RYDtHGC&R}1be_~a2-Uh!vqaFgCQUbECGAK32+nm*HhbqZXgrn zfi0jEoCm*y_(B2$Mu04^2J8f<3uodHFVP!N0)~KTU=7#_%D_z!`x`js# zq=F$}8Yl#Nz==1DIz+fvbkyTRQ`AY&S#GKSxF;?|y>KgBJ2~O@hsmOj`h&KSw(N0F zRA@VRFTwI>KaahGDMgYy>2>t>P{Olia3{8Dm|J&JWVs?d4541OlyqXdgH5=r2&oX- zWlK_LheUd32pu3~X3N6PdaXcawyM?5t{o58Fxd->Z?ffFO$ruMwfi6Bekk+mG=lR8 zIy$0b6~TE#uT^uE%}k@78A2k0ICSAIwL6CND3`pXBs(EloGlSubbE_RiVWxi0o$Q| zAzO00=!qVlTRT&M?C+vSd#+~7xz2i8v=so@?8dGezI?&L?yh>T5S45bN7I`w8|JAc zhr8<4Lc$5aLFII_tIo1s`&WE7J<`|C2(;VPSWdpmv`3$Adh-wxLmu8p#k!`OKG0`I z%k8RVu6>T|PBluvhjpi}CwvRL>$zPnlht=X)K-cDNCo}DI4~a+f<52_xCrimsJEy# zKpMyZId2&!*zMrHiGLEYkxh*0?RIkghY+qo`tpYlj=GWQapf1#gD=&dJ( zywH!k3HS!oBt@!QqWbEa+%HQ}I=f;*5r0{3G_6=OZZ@TeEr%|4O1KvF3obl>1D3#J zdhNhU%h~RAzbqXdW2*jgPo0e^M}7Xdc%6z59a-oob}*wF9R-i+bpi(+s=bEug%sMn z(~s%?z()?6X3%aurmJa}e*N@@{vT9k4KM>HlXqhx+1O7H1Z*eOQB>yoB}U9xY|Omy z65~vx6$kXNIF?Tt!xuPQ&rcdYB|XC&<*AQxi6r!Ak;oG1U_R2#M}B|3CXN^8>DA*l z5v$JR_f4X*zzT#K&k|w8Pa+UlVL7YRQR%uw+ye{+Cy)B7$DJpqR#JAN@Nl1lQx&Hr ztXkFUgdcV2tssXUqn(U=kn0%M4A3LPuW*#Q3aipyQC=e5W7Z(shA@SB2$w}xVd6@y z#|ZKX$SomrBY^9ULt4#r5aY-72Lkzng88gwJ(fs8zj8y_C3*XCO47eb_SXi;z4Adh72cHZEQI!|?29nsw`OYROW-3#A$p>(?kFpTB>hRu zmA!}PKKF8Eykl~G2>QBPbd^*p%FCJ8!vJ15gedoM(9}n|Tn-J<>oncra8`-V(vtFz zXXN+{VUu~;P<*wWjADfP z6_S4fgQ(e>UXn+K5yPJm%^xijhOrUKCKM^cbqGzz$eCf}X45gIZhMMFBrsgB<2D}A z(sQ_O&+U*q5cC_!ewZm+hwJtx{7Z665q^R2_e`lZf-?K}OjD@}o%%Xgnv2a=%4D_X zY^4;Kk0SGNa)e$zhGhxm=`(4(`H`xmUdiPF6!4bADb4q#lP@c!Z91iQ@z|gj>a$oW zW7GBefsZU_yJA_X&Tp?DNPIfTttyt4@{MwS%yL%Tsu@^G+oN}-ybXGa82yJBz5cYk z@D$~Z=k}-cYMz}>%ZE?tEj*W>mOs?9@-xzGq@Gq@wDL!iXEzZ{c*gWm()VIP{a~aX zXlOerOTv-rw7$#^W#Vfii&d2_e!5mkQDe@$kIc}+X!-qvrDph6n?NgRUbKCJ|Cqw^Nk#D#+0jHN5K|7T95XxSIJzjpu zP{ZUI-ZtntFq&`uH}tfeK<}Yci%U9EgC0mtbG8ge;|o@4<-%&fl>Yzz)aOtsZy*uHRG{v4wRYTy)98jDge7Ny4~NTV_OFqxl861SXaGnuBS zwSP_GA2W&mY781(CrY)kdXm;v@k@H9URBOyb1UtMN4Q&Xov6DQWXUoPOI#=Q*tsFFV z1*1&4)-zmhDAy$Ob-G^N_aL5=Blwu`rLVa(9j8|b^s@qH7vuHPcO31>dKqs%7VwB; z$X5QDbNFKUg&nGjTrY=A&a>v@w)vR6TCc9DuXDX5k2e(d98Wd5UON1Z`Z;I3?hn6j zN-)nV%Av8iZ^J$CfaR`&q!ucym&qlJ4a&xo&r2ON)t;}HyQcP-35F-FCeYQIIn`9G zYDcwt0Z-MhcmNu-HE2ctiB6T0RwUWaSQRBw&j2gD@AV!Ir6+=)ptRtrIJ?yqaEcp~6Ny%sKcnO5S z^69~-s8+R5HngXYTdHVlESgGTRc;F9>=dKHY&w+)vJP0Ul`D@=b+me`6yXkp#<_BM zDlu=IYpPE|1sYr%BtP3LxAP_C?)#_02qCHbJ0X0I7v zfWMWwNI~^wUlaGUdSlI+j&MNM&sb$d^j-Ms&A$dU&75CTV?z3!XHYY-lkY=5+-eO^^qHck2}`LwQdrqdt`e7@QWl@x*ZIK|P^rVUy{cqv%OX(cESg<1Hc8QZy^dT{w2V1HIaSy< z{q^JMnN7p(VqNq!i%&LGiKrqkXEQ#so$T(+X0to9+3e12Hpi`-&2j5ybKDAxS}hNY zD*2nuwey?Rm!W>0G-<|Hf!yEp+S+F2t+dM`4b%QcG~cy?VW%&eXt}xbxFCykS_6wG zZLaLgqAk2Lhp#3zntNL#zr_%L`ETUg-uY&1Yl%A>{>U6X3V-Y6P`sKg2quIoubagk zPj_PyEP;Q$7^JBxmw-D*GvDOsby~Seq@jyUKG(>J6Go36!)hibN18K+N@mnbkK3lJ z6jP<+b?N&97g)dUXck|W$uso&;k92fHK};Iq}|`>>y^$RyHYK8)iF_B_}As^45MpS zFPEa_Aq-KArB^O}oT$a72IZIHe8XrE#aKQ6hUsDHMbc#pYUNZeCx6%9>-fA;+CJXC3@`ew2GBTsJ@ z^3DIz$D#SK>9EDWEOYbq7J>Me|6ilq_XSjiqH4&?GW`X79P;x2DUR-0q)HfUvn-#) zU81(F%+dp%Sue}5S$Z|!9gD<%h+K--u~{VTnpreKBbEfSQ)R{$IWWt}Hf=VZ`_TIK z5@|M@9ulZLK66QKD?&vGy$d99j)O3H4g^1h`~q3+BwT?I6%OIO z0y7k@KI76SOc*tV9Zf9XwtXBrmk36{w$ox`TACe68|U(=+fH_W`2V_+h)}fWF;3qqm_@2<>buyg2Ca1h(Uzq0Rn=)* z#oZvRicwK-m8Mi-fi#OleI}~*Lf?G)4O?Y~qAqbz)$nGks`u^-)L3Q)NU2p{^VYw9 z&8-#?fk-0Iav6Iw^kyEOix=p9$`k66Vjw{JsAUqd5C)#@7wXjl&pH&N*Y%bh_}bT>vAjFa`I_z>%H?LXAGH!*h|uC5n+o$-y6$i*dj9R z4U1XT9>_ASmQaFuWt&-X#H*!b+suwos`+l%SR!B2o2$-t3Q8gH(QH*cGrE*|BbuD8uj*V~RxmnC*=vF=CW zq*}gsb+H~%*}u|MuZoBI?A~_CqsO%x@YH*mDu1bitjgEhGW2Ci&)bsyvhi^qdYRx> zC%F1*x%#r>Q){~fLNtUvt5pf8F4;8lA$?Y}BS#$;yln|dYuBci6z^I_Mzi59aD3tE z1rTCTvV65HET9TozB*Vg361L|IW*8?ucx>q;Y;CPhoT*ZA|~jTQU%*z?@LhqHPCj* z(jsRMGY5Sd3vs}9vcKN{p}6fUh}J~3%oa`ffYlW*zM==hZ6~7~Nb+LhT3C;zXe}4( zECdLi=zdA6E+crcXnE&VX}`?T%gk4VI0%L+R81R;3&U#1LVd!cvCtAKW!SqtO3*T}kB?!t26xT*^$XaQ?LhoOmNUI?D z;~|V(Yl_OyBb-5Zc?E}?*$G)y5Ke&SHo~Gm*zmT+tG=hq9?U3#ad=l_UC?`ex;T|x zu)x%^ob58VLr#h@WQ|*i;zSfLS|?prGGtw3aoW9sBC}#NM#@Dpxs*Opk?dWm48RUf z71JWQveMAmY85)`ptH+*8Mexiwwo29E`&kr}`fyd)>l;ZH)xMvI+wq~WnEMui4bvHPodQy-S2 zc=OO`_XFkWTLeXK0OiZ|a^_WsxvbtA2n`|pxt@(%jvyB(LL&(Ag|crARwtf+sgT>P zB|ME`=v!!I>xB>hx_XwXNAWa)=P{cn;UlbuH`h{-Y$v0$MJl`}RoBscjIlV?XQNX6 zJ?XBTmpPnODSc07tRs&~9nPvUdCxQ%m9C@LcFaLj!;JT&!*C3x*Vh@Nf`;n}T2q47 zXoFoUKT=zP*VFLYPIl0CO2K-{e>b$sp7rET&N@9@jWQL3@^+_OfWf^}?yhH03Hw0u zu|Z+^QcH|@g(PP)yqo`;yimxfZ~kkhx2hbfN_dw!-evWOGNtnJn-#g60BC>KL4a#oWyb)7En+;@S`jk=W_+l9O zRgu^&7dFz6lsW>cio|Y-*+kOqmbT_&kom~w5wqK2>Pa6r%}}K}Cq&5PI=PAb+butu zj~ny6Rg4>{cT2)%aul7LF&H_ujGHhfW9;bBh9+fR*e#Pc8@?Bqk0SGNax(_(-Eyn^ zSF|*JU9W^wyVsf2acUen@!1K}(4;b|nyC>MI2XK5Nq_xyGh3APN10%D%ih-w)o0Cz z`wfFP<_*1e!^ht+d6gz*mUH@&o@M%=Y;@!sQh!ODrz~=9gIw@G$toXIiA^xbhu+W| z2X1Z&dX{K7-!+4R?ka}$ZnreuVgwF#RSe7BZW(I2paIL|7UPTjcnc-5IVJJmTjiH6 z)HpnAy{RuLuf%q}2}3drqu!EpZ|X_mquvS@Rga{TU+t51wOXfCbiz8)5(*YFOp=*AnX8H zZ&5g(-xkal6u9F z&0a_FGDoFnjGe%cmL=^dTC)vBcGylTMJ-XZ^KJQKo8CTT=i9~zs=9M6_9ZEJ8@5)k zE!Zym-gY$0RkuTE4dK)6(tf*xuu2ggfN*8I9Ci}o-l58D10nw%Gsu$siCPf)4ppY@ zWXEEk6uiS1#bbva>`ncM2E8pBy6uo^JM`9pZaYj(s-&vadtZj`psri;jvj4{N#6gf z{K*~2KZtx{k^Heke=v|(WXh{DsVd_As`FA^h7@778M1@wdQuUVgyj~O@J|=XmD~qq{BAus!&#+7shT>kDV_JwCAnzPltPs>rDB}Ka7o_WL&vHE zLB6-!WA075wuiFAFQen800XvGU6RlClIb1sNo$ao?V3U11dECugVwI4PjQgNh9#Y~wSOb7YleN4J54Z^H?yRu}_ayYd<)1&Ub)Fwt1iOaQs$CgtR}PSHM+S zkt>dNDLc9f;s-MM5EjX2gjx9|2S~pr2Z8}n$^U_6$5*uG7ERS(Dl0#bvj>dMe!~)S zr8B|1QesL=_s_x`t4dFk`6YD2Z1*H_A0Qo@AJ8MDq=a*b?TY#q8uUld(4Cu@4`R0O ze$dop*Of=5=Rwwg9Cc)lnhCUv^-)Yhr14Q%b=o4g z`su?;xqM#Ax`~Vr_~4%Uz>0@eBtDXY4+!ow%UPwciUl5gU}SdS2*K?}a4R2?2ahmX ztb8OGTvaSM8!wlO!R8*(Bg$z?3nXZpkI+$zc8I7nJSJZqF=mA79iQTK$tdBKc#LVrwAnDs#6dnJ)zQ*kt zIiR@YpV(tPtmpag2mMP=&%wp3|D`|Y@vuCm@>Tsc-=g8B*ekLjo_suURbS?*J)(H@ zziIf@vXyl|u^PDUsN&W?>r369gwgWJbygU&PNT*R{XXTdbf-ct&3Tl|XEIrg-{q`r~eEF5c}rDG4|5{MzsOHV;$g zt8eR9edg@9o3kwpTHznin8fb&U%YKLskqu5y_)99$u4f@4n5-zsg>)IFE+90ylzNn z0}u0Ny+T4q`^?!dx9f3pq4 z6gtp@>DyrF9|;3SYlES_^leWRcSMG^^qH1wx2us9_4HQR9Z&(l&dl`zy*!wehgA-p z;=zi{lUr~qqY=xo@nb}l(19UXi)CUwJ9AG}361ob7GSq)u%wUiRap@gI^Pqqw0L1u zXcv#KrD240yOPai>es4;a<0cR*%Y3G#(e0XL z1hV*Av9s>2 zb^AgLBaquQ!dzT`K0Y+VXBv^*t`(-+hy>hBW0BgHVU(ux38C9O*n1WyhQ8+OVpvPu zt}5p0^|U&n4Sa(vx9V!8dXyB@39adwv|hH?p;VdH6*nhr8#^_c*QLZAT`z;{h7R_9 zX~{J;SGb?38yf4uZt_!I;ul|Nri+ywsr86pUrZ+Th|pt&#rx`oCXvD$*|Mo=;^z$cyxo%%DNirOm9ZgGqU-qS?CHi&X{{&=&v3I3AxS5L;Chcs()qXA&1#7 z^DWqJx^*;DVt;aIM#!hzS--NMnWB^y6vZnR$4WCl7PTNu`R~Y?78G=P;DhfEUEwo( z&~DDj$*;`^<8K+-+^u@K?OTN|RQ*_@#fisq!&=r+5dZr6X!tpla4 z`5estpxZUU3{mU@MJ!nM{d_$t4OvDUFP|3aq*XJLq~`Ff1JGw ze9ra%|9>5}>w3ShUD(B(c3?B+5E@A;M6Eu`Fr`8cn==i=Dl~RsGD4Qab0p!TJ}NPx z3oRkl)G%jCnv$qF<`UM<`HKPt8P{(%Kse)>(zYG9i5bn6yIAPB|5wA zlID*&M`bVgkim4Y3!DX(HLP6+tw0};3Fd*-U^_Slt^)T*tbqq@K?)cKa=~&?2o8aA z5Wbc*$sh@&g7IJ}*a%A2vi;yJ5AJnX29iJ@;05_$J2(c)L3jb40?8m9PD8~`a`7{~_& zpa_%#%cnR1+JF?04st*NC<3LR97Goq5YPjpgV|seCrLTJ#}2W>%5kO5YKLU0whzrX^}2V{cTU^_Slv|WS@v;iq#*sk>*YgiYh zTHWIAmPJoG!|g@9u#2I#G=0+fC~Ln*Kk01jC_ws| zJ+kacXFbm|d(_rAvu6{+Ld@9YfBzps-WNVz{o%D&&UN4oE0 zaxW~|>G1@V0*zKymUC{5(JN7F($!f~Ue#WmXB-L^syaaP%u{AmH*KD}7qq5v6)lP$=(H{f~gnBVip&g-zQcs`({JYN~(d4}hWqj2&JzZ*y4KQ zsW?@QN4y>tTFrPg_Fb2DrKON3oRGu%ns1pfEKVjIwYoWL>4nGr{^am&f{=`w=i47l zwLrHjPhRTggK%H6aLE`X_XZ6%?5}dBJ4yZ7UrnRxQ`j)dD))@A zDArx5MCCpefcv^WzAt_%_ms1 z=Qp|ajI*U@&u^x9pu00r^43)JN7u280C^ws7Y+G3Qq;p4VdLdw4`&Te)bDp2o-d)# zl4s-m$|^!sNaoA^DA%5EwWx$>{00pkS~1NsUq(Lb?2PBOJWG1tjAQTlE#SxrMk2Fc zayFC;C9Kk4Cl5Y{$QDFG%S@-mv%gZTnl1}SY(m1Z6^TJ*a`HK6V5z}6x&L`IK1Jh1 zne=-;NMn=IC`99)^K$ZeXKT+r=kE^I|A>>pJ(2$m`7Y;WZck@mImtTt0S)&yG<<#w zWXu6N@Avg`dLjc#YUZ;Q(U1cU6BTF9t5U1C3Vkn3e~#(m3;v*44_2xz*51yVo`BN- z@|A}7#^`p8UI;Q8Em{>0$moI=L21DT!|#q|QA?0ND33}xO6$nQjc;zikteB{Im zc@|<(cFc~jSe_*W^RTavv%tUpfg-mLp7{cUPhRqeWB);B5VgL}a8E$#e+x%njPAnd zivgpaL(JZ->+1}hn@c1snJv*R8VcHxRC}MBM6c&*rr#b^$^w-IxRJ^epLwo(gVtt;NXn3yTB&~IFS;>5Z z%`WAA}_($ZWnQqXszx+d#-8XoT-a!jIW#10_V z8sUf0ICIBh+&@YR**7F8 zk=|5tN06)eXRrtUOK!|iBI77>o&0i=cZ|rm%dTILaU4Tt!km+Ri zcAP+DRk_R>;SB6iWt9jT&L7Y?P#z-tp0LG8trshnF07NsU&P!=v@dWbFB(x7{7$H1 zFejc?ET}=AIr*2-o($}YB_F0^@<&XD{w+e7c2TG9J<}A-`V+UmL8lZJ@4YST) zG27!NQIp|}^YBp7q$bKN|A*l%85ll`;Svo0oZ$={7`;v!j6vs|@)A1T#sul)DV^WY zDMjbgV4a&v=XZ3@qSJ6}keT6Qo$(Q6=v?yqjf~c+f0rk_O2%R)HO-MwS{;Zv&m&fj z1-FAO=r|6Y3+PyGg~*HJf~@{X>0CrdL+5C)PVG!|E};{S&SRO*2Db29(j=9p|I(4R zz+y4lX-e!eVoxLXYo;@B4IahAOX&Q8P8K@PzvK*@C9+OFLdSgtovXL}iR=8yO7$1L z9F(M+y^P_jhzz-n;g_9(1BchiyGrL8Iw#TD_p-BdMfl@h!P@KSJZCZQBae6>r42Ld84Y>GlNFRjN{rdNKO~ z)XzK`hh+C-{bLYc#OO`}U?SYhtcHmr#< zR%nP|6{qSdI5vmbd@ja&?R04$K}RKgk)-9>l?uoONUJt#{hYbS6iR z$3|sPbtc$&IEetcC(>0bn#4zIq@Ie8vf-<2661aJktdTP|G}RPLqpZ!)WO^5S52mW ze*?Y8LuK1!XLHZvp=NlM$JN(fY<7o@Med8u?r?@W2!65Ar<8f-^9t2vE-;@}N-__N zUu>MaDwj}~vMgtWlw{MvT+H@8QlRQcFE)=|Redt-=Gax^tFzZoJ*xf}I~3KU`nHQ@ zf8at$)zdYE7?t-LHe!Gokf7&FLC@h+?#LttJ*NacXPD2ErjU*o%iAV>X3`HPaoljn zTIRf;ip;>Q&J8>>r`Y%0R3|6LJhR8wdzy2qO$|ewoX+sKeZOz+YtBzXY}zs36R$hx zYP#7^v|9R#=ijvVF3opl**^Z&H)?^Cqj~6$?OjX}R=ALn?2AUH%xdvT+HtMgCyV%) zy4fePTKY4MPJb?0oVmK$393-LgqnR&8RhyXj1@1)XI_E6PMyWhwOo<5Vj*ee>|(~f z>9%Zp2dA1Y!3wiqqAvSO>m5?fSF*&JZnYI(koHTRkJ>I=FeR5R#VYy@h7UWujU5v& z`bNCX*f)n@?pch*YnC}1Szi>-5}q$DbLMg(mZ84j9n}9c)sMY{Eoqm11C}%UW1}_P zekFs^d*OfMo6{?q+_-JLjMWp3Myb`3Xr3}r{BMT1X_a1BgoZ0SE(=#3q->_JznQgoZwdnUzGuv}YE$-cr2pRdl^FDoo z(Z;h{{$<`vRro&hF5B-`OZ*_6ugM=WXFx-XlFw?1 zHlxP9hN!tv?(4lq&3n;UTJjOo7G~SXYKf8k=Lt^PM@(tZ7ILjc&uscAy&X@6MM&SZ zOp{Fb+c$BoN`~A2@vU7)dbS_E5n`SkUtB;dpZ3ei0_SAAYK!z=@0?^;?TR1QJMXuv zW`uEdLgL5HXuE1Ubo&@()lx8&mn&sj2lBa6R`tK39KHc%Rp;Nk0cBOi8_Hg#tg7{Q zHaG|CRNO{Txt`4UC>xy}?5fH(l6TfdQm|Lt>YDQ*|+KD{RkM zr0XXn1hwU9Lwf%Ov-i>a415zF2;YK7!|bE-X2WcP^3H?V+T>jdGd|{B1GDic z+q;*@EGH2WInx_d}TN0p1-j3;VrCVOHsT&%@F7Y>U@UKZJGl-r6wB=)L#Cta|r8 z4#&bTz$|3#n_D!cE}AFzbW8XJD4&dauJQ6ZAUk zGvxr+gxh5E(1-_?(0SXyEQRxSgIS^G9RjmB%liu40iFRT!TIpx@M@U#BHqtoR%CdO zz@6b=;bizvI0cSr!0CK&bNFevJ^T#(6rBA$4=?c06Mhly1y6;0!;9g5@CR^zcq^O= z?}yXiv+!W}FL(&7Cs-^a;Og*;c1zA+ID_|>;W6-Q@L2e5_+@x)0uw2(@URVq@$ffr z7W_Rt3H}|P0^fkA!tRC^%WH59JOge9=fX+wO!x(O4m=c|Yqv~$AAXbft?+#K8+ZYH z3eJZwH_WC{!GpCChZDe6;kV#A@KU%r{5Jd$yaG;vSHeT!f5TbuD)>$KU3fM89=r|y z54;av4gUzg5C0B-1mA$y!tU(GlpZ|9z#HIZun%qzZ-%?Vg>XOkGk6rd4OZqphu?s= z!*9Vm;E&-i;hpeT@B#R1_-D8Xz5?%tZ^PfflD^;BC_AGGg#~Y~!AIex@GHi5quF|17Cu7!k6J=@E`C6_zE1- zjM5E`gs-VWAd!dbC_DlG3HO1^;j!>va4!5eycqrmejmO8Z-Q^a#jrKR;{6G>!R4?W z)|*r8!L?zg0lW=h9c~S~;3wd)Xda&C!43C=E5R?pH1)l&Nwb5_nzh&RT8r1u;o9&% zI1>I|`W|%No1J_w_tNk>0B!`2ha1Cl;U@4q@ICN4xGDT8oCp`gE#MRI{qT9XHGC6( z2(Fw+Q3Th4+rmxYc5p|yBm6Y{Xoy9^4mtJg3B3FZ#aVDCcnO>ge+YMhKZU!)#qiVc z3HUkq5BPalYe6vt*MWP%t>E79L5{3g5vo)52w z7r;euK71Tr44;FSsPAKGWw9)SJ@7kl9K0NE1FwL)!7Je*@O$tp@PFVLvgfd~PIk^o z-Zz9;a;*1L{GjfExA5Ky-o|@pcqiNk{sQ%ExCmYe??L@zcrWjV;e))F!AIen@G;b5 zTT@`bkHJ5o{tWyx?=Qn=RSeGIp$v^>@OdI2wKwZVEpEw}bx$cY!;@{orJH6x;=#4tIwa!B4~Q!Oy^-!Oz2c;hykG zxEFlwK}%&zUmhF}QR~Asz+u)sgT`S2g`V%Xk}3ba);7HM|M+qcC%@-rr##{13bt z4ts=*21mhL;fC<1@O{}l6!P#G{2AO0-Uj!9KM%F!yb3dImU9f=4PS+sgUJc+Kn{c( zz{lW@@DG^l0-uC?!9T)-;Zpb|_!K+^{t3>5e}=Q)=7EuK?*}jg-P3D#qzZF0^ z{{qLt*WftEGbG%{X!xU09ZrDnfg8eY;YM&W+!*c&H-m@6&EW~~z3@yp5nc$lfYjI2#}GkPDWBB2WsnJ$x+C38aEtupI0HCxB%yi2<|)J-~P{4{QX* z;1baGQB;E@kO6YR8n6qLfshhBk6e_%{TF~HAr%-YrGT{{DcL(&?OlAy*~*cE#TiHQI{v-r4`(c^^DT}o zX_D}Vvz~oRTBte)wU?~=!#Tn{2Dq`KJ_3i*r2Q3V9UI*5inB({cWHj78Lw7;{2*wk zJX5T@tu6e!^WtUq73Sd@U`Mk7^2e2mS#XZDzKRCf+41l|>3y|gt}kBRRT|`P$IyYY zH&~&m9;VeB8VWLvVNr&)jQ_q2k@ixpo$XUvp;IaKGPm=XLwTnEi2= zjYYSAGMI`ROa62YF>D-tAf&cLmpdCZ%O#4IgUz5AoCcO-d~?ti^Z?_*Jh0j~rrdeW zrWWEASgZT8{&7yU+S>Mz0;?7w?whPHsU!PtJJGqx5?uewqT9}L>ubKhZaX(wZBIrh z;gnAt+I5>US#q0Ed$+DFQ7t9gN?I}%y-wy%I? zT;>D;$F)al@s1Sa4sv!(q?TYmn8z8+>#Z#$>xR9Sg#U+Al-z@Dog_6%OSFHFW>jy6 z>(@kSZtEcP@V8@8TEz+2jiPb3JJ!X&dDjWpDKaSO*=O)<_l2^yjuu!!kRsQV zMh`T4iPWh}D0<1AP$-Lr82bh#qprqXBhgwF$xe0XGP|y(S%;{zX*h_lF2PCn8w*TU z4v{grAyF}{@Mk#IJcv!jei7wG72+Xcjn(3tRc4Y+MVm5dSIV?GAmcY~aQa|w>@#+4 zg`k3GVzs(@g%Md1!@*XwW3^hIfSR)1VTfWoyRc&MT(F*sIK$;?i{{!w7R70;tSNGT z9I@~$u@IRr{o=I1ikB35UuistMnb+E2-b+Hr^UOUN28_R`~S5L*-Nh(&|vLCKwc#z~z@`iD~JSpoOE}3-zjnOYS5| zl^?L7{Q_GJS&oe7iMQ@(x(qAtO0S^}@q9l#zwj+--cU=hE|i!CT0`+>v1ifSPz&L* z7vlg<<9?%I<_68}raH$am}ewQas#}SK3{V=%{kR!>eQv081>|lG!h$WZvE$gKV(G% zf}PF{YKV59 zieAcea!z<-!^@{;YUU-%Div}yU1P0bXt!m!AYBshQD$Qek1oGEX1KrX&IxTPa;`Bk z)1R1maJf`%q6JpFq{y>P&`3pN$a0z7L`w)AqAZf*4Yj(`bSBw#xa>!y>hPfal{q>y zE!`rO8)-Ep`W|vomfvv|1{K`lk{89DL4EGg+_rC*%WsXeNQrICL5ItqW&8iUdkEEV zxj9oaR|pSR=h{Z0vgaPs#c(-)kJeCcyuu7mq@*<_I?8f5%Pzx9oV0C9)@_AFof7FutIP1S)9Xk%^hZ%XAh+HW@3 zeBa+~H1;xfU+5eAu(r&qo5j7AUDMrT*lgFdop#nnA=tG&A3CwU7Hy;8V>@fDbUu2iiuU1Ly-X z!2+-b6oFC@a+1CiNCJI;7vzINa0rxx@E_@0fn<;YazOzo0;NA%p0||q5K&6w2y_Ce zzzg!hE^q?e01>C?4S*Do31))=Pz1_A$WPb-l0cuI@;cU7)Kych&KJ6Bzte>Db?TYhFL?0513c(NB7sYv^egq--;k z7p7|Wc)I$PRjFb(l=mx3GJ~X5>6R*?Xy8)=&>)-8nk=Lu(}iSN;aUcqN_S42Z&Xjhh4*Xj8l&_jYoBgLuf7I zQ62tdL~m{5)i^Xe(s(ou&5kl3)e#=iro1}BBgS~_sE$+07@}#$G28>x0m$Yt+&uEp zP>uD(N+mv6Xq;gHRpX;+)_T%qpcZAg8-GVDgUjbb>)&~wr`~xb9B&Whvk#EZASoY6 zW9IBoEdmAOM&6`BTDa67#-G_}-T&gqbfcY2#8?Idecf@d+-In(Z*#YLOLYX!AnN48 znl8;)7dAjX8b)2ND%%0-Dw1j)14-~MlY_?&PfH&@aqw8xMzVXNu{w!wah=pLWb&QV zpcAN5iRk06{DN5ulBFTuf zLFtzuhbkK)>xXM~4O`k`Ykd-PO|R(}<&M;QwUs~N9(Beeb%WlDR0+P;KE>K7N3wx1+z zubC#xPS~INFZn?#*!&(h$@u#e@_TY+?u%MdYjbUHAO{6pIp#N|GF{-;8B^60ZY`VSgCJhT5}>B9$_S@8spcEX%8 z6OdE!sSFR4kJ7bviDu{gfBN>4-!YXJ0zai@UuTC?$HRPsvZ^^uTWp zZKE@c8mP8W?YoWrflMk;mDIlX)V)h1wPf4<6Mc`4(ju+8S%#~%el5Nat0v<|YlE`K zQRuzO?8pw-%l}>QRJa(2MP`7rq~!1wR1Kfgge2fS-UbT)gG&1kdNaJG>Ac z1PeS3UJP@hu4O5_2wp}<*t?8}JQV%|uY_6SWcfF|NnXmJx}GWPGPGxFw$y*5Hm=VRavAijSoFwg~t|BQMLd+m$V9G(gP4bOvbz{}uUOn8M+U{$g*r3Y7r*&1i50y80M35WlJ zsaw6H$k$cj3|M(Mi#a#L$4q@0QOpdMh3N9Gf}`P&V4}^-43nh}%t)>!4rT($QV%YH z>%(Pm1Go~WTAFADD|7(&fYE-8f*XQIK}U@Dclrp20s8dhaZLSg}cCsa8I}eJP>XPkAm-mC%~;>V%^dPCiz?1 z!tcTD;7{Q8@HdR2TOQ$oL}2Lv^YJVlVU@1D4MuM)Oq&I-*49{N^57)t&Vr-h*WrfnZ1@3q4*VEA7iRs3N%JqnE`DmPIg&7A!=+cNffHlJ_vY7(N3pfmu6Xd5f#-ysCAx6oqQ= z+i)bj4334D`&zuBy}*KO>bdb+WZWv$RmJ=+teRqcS8sFpeK-mJP94A0e%qPBry|cfSI+F)$)p5?qaW&wgp{PlW&Dp75*vQ04{_RVA7EH zA^3CnVR#4pFL)O`7*++-Q1~m}hxy+}z+dzJGF&8^CTNe?zo3HJ*V|RQPBH5BP~QWq zY^+;c#yLfasGXT9%_nM)c3t{29XwD3PJP5F2bFhD*q^j+kaJmDe8MKwn#R~I zWDW{~ftjPnnoYe+ysjbvSAv_y$lQ4Qduo(EOL|P!X3^{WakAFf@d<_>jFHOOT42ND zCh3yR*oF^{hhpUAY(^s=^4ngAmVy)8&KQk$*`Cdi(iu^$b}2QVjlCiFrJP`Ho)3p3car9MwMeGRF9f-w7oWVu<8<=>?7mayiscJ~fk` z6Sqo-NGStT%9+SKdmTxi6q0D$WS7Z9LTX6z6wU2mIiO==9qBiPuI$7*X7tqaH+6oM zyouJjF_~DYI*5IVx=nr&)c{p7`K#>M&Y@$!O0)U&*nSo3RDAraF&Y_DfVnKpsaDiL zYAq$NJg$8Bt1yzNBri|XY8sNN^Hm3(Km3x)1r>|G%8IGlzc{h>+*IOw3*L>7m8#RU z=AQW2J9Z*yIV;_#sZm>krLHb<$0TCD0H`XVxnDTo@w2jGnigN_lOQ|n(gi;m!@*~j zzv4Y@<4hNnA?53{!2_3@WOxof+KP|*#L1gES`$wnzr0ETsy;erjz^!9wE0@KMbqi~ zpECz)W2bBGNu~8=aHT*D&dgzhhGM^v_B6IV8}O*R+UAm1$b2kEI-QNnDN= z*v+&_w!B7=KPAY`>&s8CY4t*zD_K$~o(~#n+$6nbAjle1N4NSibp`{H-Rj$=?pa!^ zj9zO}GJ}BrZbrtX8Tj_OAUBoUze}ZDzQF52$|_I%E*+Kf^9}C!Q00T)@BT1bka2v5 zlu-3=uKfL*wZt}h)P0OH%ohl>RBH<0cKn?NCQp4PB*$1{A4cmf-T&cilYT+y`T2k^EncgJ#&%t}2)yiuD_b-Ykhaz!Wb`TxzUPjGPMI<{C{ukj58v&;cX{{7k$LzIuJZ;yX+-dB<@dZOkgYgL*429rkf)N@bS@`m<&<=J!_V=3ZV;h?Xn)S0I>m&7;Ge@=SM)4Ei|LEf9V zvJ+RPHj}MyYRzr1El;a2mFH^?>t&-Lm+@FEZRYbQDNlM_Ck(1Q zynJ`IJC2Ow3tafNxy<^4B?{3C@INoVy-8|OvsTh|0dD;vA2C}6ja43^R$pQ>28 z!l~+7&DvM)E-Q>Aq*B8b*?~6B9$!Q`aYe2z(mIoKItqdMl0e0`kP$*P9N)r>02L?| z5m(LgTa7zeuF4J}Ld?;JO`_*x_AAWhw2+qhTFYiRezPht7`0pr@=KSr;iI~wWf&P= z*?Ud$^0mMr)|=$8vg>Q?s@hU+1fp`wd1PZYgt@1i5=$X?%;u6D`H| zR>jOQ9(oIn_Zc8bZYkT|wzaBdj*qBzVDQ{gdyi~;i@Bpd9$)39+BVHb^KS1d?NR%K zF?RFt#Efs5drf?oMEX#Sul>6kYg{JQ@ojxi>u0mY$ND1Q*KS#Ded2tPA8HqDHmW?= zTI}mq-`9Js_KB5R#aFdJ8M>U{o4a1)D7u=Be78Q1kowc{5wh&p`B046ri{Z?CPS5}Np zW+_{8vDPT27A>zt&y@&q4R%S| zJ{lPv_R*4y+Gskh^c(@bcFw0F+`J^oyZeZ`o_O)2jk0$i<@-l|`9M^EX&mn*u_g2q zzmzc-NmHEVJc!mtpAs$6nj~{du%Q<=Z2d$&DbW%tZDp}{AVF$kEurcR*^f^G>VeY# zD|(P@DlVO83kg;7yzgiFg>#-wnzElL`AXh4Y04b60eL?OKAA=2Na4c>dsm05Q=N_M^|j17gfG9A{YU&OO;i^ATGSr;id=T?AQtz*Vr`35Jw)qM zW7&JaV)admOp8-@avZm^R)!ta5~c7EU96&@FF$bDi$*S2ekqb44lzl!{Ge9LmepG&!69=_7VKp58<#+<JEUb-boY15`6F7CZMRk0*LT-Z+^@d7o_?Nu~L$ z;tzzAdijV}cM(^9$$}$VEm@w(#g~~!m{l#^NXJG!E!yONkl2c+f@50XV3j2K>qx1*J{+@@+t`zeH(nek84kHX7NVfd*5lCQ?T_DUy~oS*R1*lBXy{)>c%eX z;*(kjTiwmR%0DtYVbiwwnv`mLt+pSw%HOA0#Sr$XujNnLcUBugs(hOKuN*cOt)@0$ zK~BkOt$x?jWcCooyrV%IkODG5E?5pWgF~PUxGzvufKDJ4j0f{T0Vo2c7xFr8TXcpA ze?|=*y_oPn!-RjYiFWDS#MV)A&oIVZN2*+LR+rdcDMZ^r<(Xll)%b^+R4gUh+_V!TNWcMoRR)BiUsYP1C9%=W zsv`Z*Y91Q;V^Dzdl=}GH)GLK&wOS|~Hr210)ct`l^QaHqwB?)@kIa+}p;3}?j;#9W zt9KfcDg|TVIm6!d=QK`I%(|niGICY9e2(;eUo};9{VDB!Bb@&boHw#$$Zr)*vp;1$ z8g6zfIu`mZkhs4ocCY+K!beG7bh(C0#_u$&KF*TKzq4@TPdWZOmfgh63zNiFMjm}( z(jCVu;a)ZKV3XvjET<|stHl~cRyCPYhJUNciZa^H)uhFF^6kjNP^Vlfqr5Z~+-Yi7 z-i%2@RpyrkeZ!Nsn_{r1L(D8V7Sq z_j6i|vz76p8833{n%yC(7qlkM$70Qh%DX^(+#+nBXPaS?JQW`YFVOrAC3%8LVPhO;>Ncw{#rT!%p zU!CY{eMz-T`C1n)qq`6;)j8ne5ACY$g-O09S2T`v_&i%iT-AoyuV>rk;s_dziM{FA zU%jd|eWINF;bu;$K4=3{z#xzX=7H6q7@P(n44g)Twx9>d1hc`aOL-lasBu||y{_F- z3v^=t)S9zI+}EvK`^#3N5Sc@u41`~1Q4(l-Ij`f&MK{QkY`b;5Jya5IX!Y!G549T$ z_l?yBDs_e#g}8C=NSJh2=|4=)-!Q1sO~wzxflx6PBzrgG_~=JK~D$+s2XB9oW5hx)4CqNH>5!0+k!eSk3z zO_q1;D&=79yUxW~n4?EH$b^ocN*6BEn|ppLRmX9gjY-8v&E8##I`QVHxdK#O{mS!> zH>`mgZlVmf>hTUTo1^5S%(d!uZ17sEzSDY4#@JZ%dQ9?6T5nPsOGX!EsMB(6y4zFx zlIdumVQ|bi!*dY_oJy=6{fC0|m8XtLJG;&>n_pSQkE(TX%dS65@%YHs*6MP?PRPh# zj=q=Wx?Qhl?|a!M?}WLYtfG;n*m0^h7g&a)_-B}_yERL`3?U4YG4Sjkav?--689`; zLn!A|>8Peq`T(^O;xE5?J+ayuhD#3B>w8*peuOD&_KJ_olu*2w!f_G-W#vUfnL~p@ zb#2OK(!g4~ zyvW5}lW!b)6MNjX|Gq#eOS(Aqc=r?)8ysw*d?YPy(iWKS)ID~T)Wy7aUAdGcH1WM+0l_&B!JU2_z11C9V$wwN-reW;cfU%F1u|JhDl>RqkeRYiG zVC-hV*m-3v=$N}KIgE^BIx@Ge$t_(Eth^?0E)2hh#_fRNF}DcZBNMEF<)K-!0~zOP z3Npua^WF-7?ortyP?B{bUUrpA<&D;-#2coE*nTSYy%wg|2qQWBmetVTwCW@xqR(n6 z7vnC9TSvsG<5NhjRI2on4(#?3c(nmBFSZ-HpX3SbG zElsuXXw=MTt58ct%}$({BLW4{dbs^o;Ozu&w%ga_LbTpmCs>A?PT5h-Nz*?@Z#yc7 z0$?fF2#$eEAmk4UM$iVNfDDiemV?dU1h@)nF;0{SdV&m)4+_9Ba0x^+sox6p1Q{Ur zs#*k@sy3O_A>%QP@8~g266)x6>^-J2pyA&T(o~ka!a`+Ff!!$ub@Wl>*1C1|#tvE@ zj_K35IYCcwPAB=0M8)R{>nQUMQQy`Iy$7SnIy;RE&ZFL!en|Zsi+dpCFIE3SiPPnfn=w0gsK6R9W`ZtLyD}L zVvWiQaZWO1xrM#{lE+wyoX-eyUtWAxpNcUlq7f1T4jI~>Hs28T_)ujYO9^NV} zR|P<=JBKCL5>EqrZ95%WX%R;`lF>*HVfTXW*7x}hMRH0W?zH_rv@KP`yY=vR6xsy^r@%Ul9W*uV+3K+r9Nh>Vs_kgdAYuxV1xf(%{FU5tW?A7*VFA1 z^_tEOum;2mZxykknthQ*luKDW(R`yJ(X7?iD@pA}y1JgdStGsXq6AF+;5Vf{wkj}L z;EseOD!tQwJynIMkI0=rjr7jM+TsL!AAt`Jye2yn_}m95C<32beUT`$?`4c%MoD!( zy%aUT^|wdb0(YZ@$%KY_{QcFjW$+At6u*>_K00lXQ8%bFwb!_eWh<6|zDi90FCmNf zyy~~{u29wWO!X`OSAc$KM1X4Gm9e?vXsp)>9h-}nWW{SFxn;R}W%KC0l*YQdlA)s_ z1JBU?nn}>oXOY3od519B)EKL_QYLovlzg1q>C#YRsmg&=cA2iXQ zv)U4Je72@!VBJjOR?G9UVjbP^+0FD48%eZZbG?bJ)^wTGTz^z0x4q5vvHCdUGg&P? z%rn9I+^hGreLdax$-VkSt8RW7bpeWbD???-!X@AQou0a1^HkN*ac32t04S3O+AnV`hf9Z9#{>w zgF~PUg!uAW>6IL+-MIWAeX`nGShubIZ?(RAS6ltM;=*?N8O5vG>&AZ0NAz(>O?yPo zhU^{mY0!)gh8bVej(T#V=c50lCE!VI(hWE~|fUZjW{CEZOj7V0u}z?~;~ehsca zHJ0LzlKrO27_~T8O@WURPr6}vy;6xaRJx-=H;}oDtaROt#be%cRFmz;X(^7973q}N zqk@L|M~%BvVq-trNS!k+)ko?LJ?B|ZqVlN96RK%FN;-}-gnEtCqwcb5Ed5uNyvcsb z^R?YkvU;TMZd{p_C;=N(4>s8OA%5po=V+9gSmJQPk$T8o_Kq4o-f+FLAya9TUNa`x ziuA!lGSM+a!VQs*h!Bciql~DTVAA4IdK8MAMo~Zy_4`Qqwz^?NE!$o+n!@YFk4?`i ztr~__cL)8v^jTDW9Y*V|NioLi{@J6cSy{m2@NAU#M(YV4&qmXrDs5C~N2}|ujXTiY zR^z#*L}cjU6>>&FV93pxWBr$PsZ7eC1XzZRGq5oO8)pRBsLHPlV>e=`8l=iFZ!t7> zB4((KYEf2nGuf|}GKRuto8P2z!zL{-D!LA% z>sXH8B0iB@hYB#l`;mE1y6E=n5G} z6l;ZKeyGFNF#t#(ZY8m+AwZ6!g^_?L$QqReW`d79YjE%jjbC@SF{Xv%gn{I># zk5`fXy<8EpevVOCK`W391_3X~2L%$Bt>1RC+{*Fx zW~(%;qsQ3Q!~fL?oI)dTF9!B*mabE%ruS~X^VLJZPTL%^N!P7rV2td855`O19FpSGer1)CR5Xm2yd09^9yyM# z;{fjEZWY^fa&E3)Qn{xjCm8ODJ4bINv#0BB+u5zsHHYz*V|!fT;@)iyv;+3g+s3Yg z*cJP!M81Yyv8>2bF{|uS8DOG$t@lLZ+-`MyrS!x`S^64zW};lqCHb#b3ehul)-_RB zFneXOV?%4dMFHF6ItnZbP9A$>ob~Q0D&s1)-K_x8Lv`Z?9-ix!RN9 zRVwl8{kPwD%)}2z@WY3n$!{}hnSJ=#-F{D;rH5BC6!Dlc|KE+WJ+gQfsdhfux$LvM zva`xff$TgU^KWmK%CGB_ZDg3auj?mmUAD-m*)+L&Z1F9bt+VHhgt&JO8YGalbM*td z`BBvtKjY}zrElmQeM>aE^7KWv4TZjyd8##Mde3U zFD=r$^8ASCLrtnKg`z*LwDa|WCRLZ*e0{4r$00mlkC2{=4I}6y%d@SHMYb>3BYd$- z&`|BQjJF7$dMI70KVmcYSF2iD_ob!&U?86x6prTTLrJfr)>KOhj10gpF14sm& zKq?py=7Ck95R`zk;0B0bHG3n_0Sp3JU==6?r@;*nahp}0pc6<1Ik(lq(KFUhKA_Sk zoT}FMC4Z>53aPvl?E+8)PT$V!ICjx82Ho8Sve>N1}1TQng=5J%I!?k8hHJ$U9qTJ)bThoHwwymW)}iuXAv4kfT$7N%)w)d#C

zs4bD+%IFd>j{k? z;Bt3WT&ogS$8@N;p4p*$JOL$D zi79Iq$&`}Nz|2Ome1=iSKD}%Y5+& zn+6=`Tg%oj7=u6WmsK87t=xZY51zNU>+fUfnXe72hw(q;l8eWtQZ@weT2 zWzX_Q?|4Od{if*O=>jLFer>GBO8I*5m2lH}!Y@K8+B9S_ALf6MStXno`H@&vm3 z4U9*R>iH)akId3Ug*G%FUGAvRM#iJDA9s6^T?=h&yfZLh-lAu{B~!-Io?Xg~dex}i zDl#y4u8$l&Xt3PgP3>I#EkU{^$G_F1VuFRnWll&RjD_m+sU&hsJjHY|Z%MOax@xzi zOEG=$U;`QHX`=?yl~*yW`rx>3O0F=?eP+J>z+3HLb7{z`Vn+3}abyoA*DYzh$8cnQ zrnQ=}?f90YnJQCET4B6e5&&2ExCqr<6(YfWw)B{4t6sge=2b`OmRy( z?ll6|ckllQk%}Y)3`sTRd`t37$&dEx_jv06>&^$SX6T;Vi*G&(Qm$nv$Lu4Me(G0N zuGTh`tuOO!Quk3V+>+t@Fxl(LJK=~jM5ZW_f_-|lXWUb!o+@|a480%r>GyidgOux; zj+N-$NdF^Cs8+=g|wOT!7)!0j`|@&h`K!|2TGEROwp;QSQofcf{AxJo1Ty{Rj9{r?`H}LC8=W7+DrEXdNtbzon`J}J=s5?Su9%)VC7Lv z9_%bX9ncdZ5BhCTRa`kAyhBZOXbGo8c9uGiviPd)L3$m<^3p-f9m8C^WLb7lZ*GJ4 z9@J~-?Ko3h6>&@?d`m%KEHc*)QNMKzXb?Y2;I_FzA!AZVQxzMB2*Cz|R^k_vnDEL` z;ya`VCZvkx7i6S#KeJ3nlcn-uX6}wA`@=TjFk$;C`R=ftI*cE`!;fKI#C0Snx}H6P z#`kFS=pvJk=uJF5x|p606g?JmgxgrQ#2TPCxvWuTFpErilcQ$BkCGxRQu`=LY>(fh zN;E1|EZO^xk|+HrAujdnspPH78;i_5Y7~9@kK+Cb+#lFg{ywTV2_47|I;-@Z#Mu4l z$ySf#PGVMQ_GJESR!`%PQ2;zA>nB@lLT?`<|2-$C%(p$qNSDi%c^ptKsez~G#Cn_& z#OH!al(Bq7rLD5xbJ7BB?0E8cQ296KIG^ALe0AM#n{@QhGB|i#_k$^ z!X_(z(BrE{K4S(^6&-5$)Mk~F6gTqM4|-VDcY-vln3{D;=%E$M;FCnvk3?0K9y0f& zKGs>vbF&_7lPj>sNuwWiw_Uvjojv!X%=r;B8_8$Ao;M~i{Hs@0TRG5xKaC@_mq}1o z%Muy$72|!;rOZ(LbDxjZCzY)>8nw4h=__@!1!}e2>%Xq#C%va`HX*H?K44sblK3+d zv}QBWYUyCEAM^gKcd*j}l+Uxc!sNuydbF*6Yx(m6+|NxnK|`YeZSSZDd*552d29;I9VP1qBAg^Aug-bUA>gO+?n zk2XubICdy)zs8*V>??YbZkBFV%LwWIJ&PmDuIOu2$+hIFe!y0eETgXBrctQ)jV0SC zJ1Sq-$J%;y@lCz1W^u@~-~Fjy*UemFwcKY84wRLv!GXppzTSW9-`MP2&!R45e^N4T zQeHLd;d}X}{;|#8>v{kDOZa(f$ihyprrG5*s@$Zj`XCAP0hwSnSPiy=)8GcE#Q;$v z=mRpra)i8M%~T+Sw4dG8($nEc}lRU20|u;uN7q0j274!~d+jOs9U*<1y1r4aswk1R&0H&$STonB(C3w1)qMrcT~8CC zW=LzbFnsk$OEmIZxSlXH?sL897namkE{<68ecH-(+c>kc@BvpNXD+$Fct_yuO<&zM zuJt3bYf+;$1xa8S@Pd3$0E)qBpy{LvkPHTa9IzB@2giWLMG^%`pby9aOFuo2uK3s!8}k14uOzLq+O5<27v`&4LAX=g4oJdOB*l@ zc)@D09b5uh73>8`U_6)yc7YQhJe*zXjl%IY$ONmwc5n%>cGJ=dBm*zV2gTqt(5m7n zNCtyIJ}3Ys;4Fw>d16!02V{bIU^UnUPJr+T+y$NL@h25{K|Uw|MW76XR43Hc8QjRT zE_%-u>o~<^bC+C6c+XYG26x?TZ7-$kLOJlRVx36%Xsg?|>OB%RDZv;Zj9%@E@ce|y zUb!JgQ^C?LV=$A1cNRvSk}<1Y+-r$UTCOZv?W&`v`DN?Ljst2{1?x}c(pwzulzhb= z7)U-P)!)b1X^frAmG%;3y@ql|b0K|ut?Jdt8*Vp394qM}lwVo;)DqM}lo zB4C~qg;KYen3VQpiHV7LR!U4vOe{)EO?sq9d$hE&q%yy2-D{0t|Mz>p@As#c*Q~wv z`LOnR-`gA=oT)kW#X=}T8oux-!?~xv&BkwTHUsn!-b+Brvveb+EGMU@>yMx?07 zZ>h~dr#Uei=;G9S&P z!Odi20IUX_!sg9n8tAoFiTpd^1B5qOWiSL5Slg;b2v$Z|bT+0Vv6nx<_Q@#v<(G>& zFlFXsRaRhaX&jZOf%Rn7Wd}-SvWni}2y%w5s?TB?8zKZUt`TEOJ>~plRlLLTfO8ZM zCc4Urs?B6|eTR|8uwtYU-^sJRm8(V3V8_?$qfE(v!CXHM#W7dRog#N2sE!{xbbKmNTa60c1Ia40#}h3 znySsa99DNSlXb+AvV>|wDo>4$Ou+HhRQ~8= z);=5k&Ze6loA`GjWn0!U+*eo!4?QPNm{f?smgP=0Y>Hy*p0i| zsnj@dS7tXVaK4024TmN+a7+=;CE0#_iwCSlo~zIXv0*iQ(c)E zT8jMn3CY~MRt+z8xMtF57$mp>L5WhwN*(R2C5p1Es05+9?{Rd!m&1Mbz~W6gx?QH{%1H%Imga=ibLU z;eE2%2T#}{D1;S%z~Q)*2<1Ew3TEV>$XfLiAvhnIOK zwb_;cqk+zJWo-2!c!=-A*pl8kv*Ib7dXuTj^@!XL0Or%<&hg9YGy7V^qq;ZImtUa0n!HOSyQB=`%0 z)rBhLBhU}Rl>*UFAF40${VVQ=`=Ct!yW0W_+vDHb%#-0XW^57dV{7rbI#0^ z@vu+sD8tf~`6$#zy7Ff*&R-5Y3Vo5TvJc~I$CRVc2~WJmDI{0a;32ER$mPf~+zZ}B z7M>LgE_If!4jy%MXga%rI~ro7n^l|1cyU-Shnv+6gtTFhu0qQl&p;(-mm`DmeIeV- zx7B;)=s#w@U0=$uXnL`}&%hxIR67i1 z+%Z^P`2=NXSK-GT9hBd3hi*UhjwAwefAm7e=Yj_xcl4wLA4j-%5$@@KsrQaMI$2Nu z3wBlBCn&~7doTi$&O`-Qz@iDC!X5Um8dBltWC4D8yn%MCAPZ(#`0ZWwbA_W_;BW7` zvd+!v-X7O5Ky#21mpQgOD-fGOCmdcDypwlvh7Dip#F32dd^D2=#k7FodLVU2N4Uk` z85$DEp9R5XZB-{uIDCERlYAu0+RDLF#!-`)Ti+z+D*sO%t*z7~=JMc^mY?SGm$6CH z&E)}TQ{yM;NGmNe&sF!D!(9HHG3^k}Rd>iUT0w`uC-D>Os`!bo6Sq`7Pe66ia6*kl z@|52XIJP}kC9QVjm$<2J%vHtYh*C3GRpDoJF@DCp=gKrzJaf(U1BqGFu#kitp@rP@ z$V~eBVF27%-miBV9{AuI^3goz|K~frEIIWL;CQa{*s@AV0Rm+59H^>KGkFo z!_Ue}N084oi2H&a`$2ssQ>&b-?57+-;r&nsi@=5zvzT1d5TjveQ>INEpEN7U=)tLB zB3n*5TKmj~)6rnR5T{gp)HIPz7)YuerySj#t}4-29*&%@Zk}>@+uTqKhVN94&m3*S zcfp%}p*U>-r^9!;((LBE0rTE49{}_8d*4&96!!LD#z4^)2939j%r zgw&nE85x|Zu7B=mx%P8(CYjXi@bEsa{P%K=j9Ig| z9xxr&l{~}i9}LF79*F7lC7fF-q61dVSAFiVHugiJ{9v7|K3}3HpK-J^?!Hl`Wl>G# z84yJ%i=xoloTcnvp#EMtgD%nQb8Ju>;{}y>2AMeQ3rDAx_s7Zg;OIb=_l3hd{dkn`o3#BPq(=_^86uyBn++cvU;b$qGUAWmurUGExfihdW%h7wSE{_r}^F z*xdmlyDm9pEji0Ju0zVYGR4TXuG}5M7-K~N%Rv0{!GJFvewO&9YTTEOUb5PNB_Te{ zzT->BQn#y1@j2<+Sl%7^mBY{NXBW2uoaOOlrSE;^u((@VtW?{-!LXR8$MmuDz|FYO z)9<`vk7eh|(%;TwMa_=MA4cC;XXS{Vay?rC(oh;E9o5>r0>h!QrsjLuoLJ|KtnR^R79T+KrJg%%b@_ z~~C3rqXo#AL$GgB5y^Fng!PyL8?!j*+G zf&GD>0|x`o1LJ`gfs=sW0;kg}o|o_gTGQ|_3wRm)0zsTgH~6=J-^2Xhz$?JJz#o7f zPz(PBHUVA-lHU3e7zq3c*co^O*d2Hi7!LduNKgF!27HQM@w|;6alkqtz3KZWke&y< z16%;S3#z%CL`3DpNO@ zW7FIe2K*J+19%tM6X@-Zk7fcp0DCvWHvtFZM_(AE1N#Bb10#S}fc=4305ClQ#O%uS zD9{0QHW1hr_&D$(;2_{5z-VA3a4>KPa0qZ5a2PNRI0CpB7zd;Wb;mTy#Ftp{BM}C8 z6~iA;tPD}j`g zxxo40-vwp^KLsw##E%R3u^9M0FbDWMa3#=zmYWO2BP6ERfN8+Bz)ave;Bp{&yc+lh zcpR8CZ2)ctZUmyqnl=H^!c2w0Q^2=?Xc4BjfoK7y%+2_L3TAo-*sBpfX$?fSn~H(R zUekxbk-!q*BH(V|3ScP^ftdCHw*x66`+x_*?-%|s@CbO2A^!*n%Bln&1Af*BgWpe7 zpT8Y#OK1J<7-X>w-?`?H<{SDAgs@|}2&5w%HNYU?zkwJ_n7#)-54@txW-Z9h12nT~ zh@m7ie}oiSXu1KU@#ak+O?-a=V&B{JE0BhNw}1};ZvzJb{{WKe`x6)oybDYPn(g>N zG0+XT8|V)F1c;~Zvq&@9fS&_BfM;pQYsZg^FmM2`0zH8@fQ^B5KrbMzH#7xe$HdeO zi2Vao3t$kiB`^%w3iue%7f341Px)B1xpp4%nN4pRH`6lPLrR$y0;I`L2Oyo8=?Dw~ zh5~y6I{_ns4*)5dU4X-YRC2?CVc;oK9|R@?djQjc;lS5{y?|?g4*~Om-GBu&ed(*h z+_a%?7~QF%(H5V~Mp z0G|e8G-(>|H;IqI( zz!VkZu1&P_;LwaG;|f>Uy)&mmO39cGq-4wj`T$=9(lBf`kfQxE@Co2N;85UvU=k4b zCykzR0dPL}g}`j!BH%(GWyfORQt*_o%YYQySAl0J87uIk8U{JQuYjw7)C1-LYk{u= z{|j6Uya~ifP^&i44TDSd=5^eDb+>69EiddY?P}B7nKOH$h7AHGf@XnMfHr~lfUbeu zTVM+fG#E4&SUaU07R^%gih(@^HXc35*&sm-lK9);SZny&TmkQH0Z<`rz`edtpy4G9X z7`yAH{?N5{P75Rti*Ke8Q<9Ta(w|yry`^!UT05H?EIpd77UOs8N5wKtX=vN&aSLn2>p=*lMPs;khx=LCs()jxU%k%@NP>MRTXwd3uW`eO{Xh~MBp+m} zrcD}3hBtx41Cj&T>Sg@405>+#2Fv~l!uy$QG=h!G*~-@o1$P0S*34zX_yZ@l&#t{)jGNLfuj%lU=z|S$zoHJn`#a>WD-B1mfKYGvmiINH`OM% z&4TG85qMUuySL_L&o=VLZ0f3Rw#9^Gthd(D?E~28My+*|H{2n5nb;iHAxa3a$7{!w}{q>b9-qv;kf#T2SLn zm>d^Za7^&ZMVLQUs;72pY*Wflb2?oTiX(-5-(mb{W%k#CY#4gmf={SU{+eqCD_W(K z04EP^eNL#2{+jE}k7#ur0uLPRv-Le;Q6FqX73(TTUQnDrHNJPHZnxGNE5{RV zE!0_Gt%+*;GK%I`U#*q8)Cg-6qgvyQhqG-ozoz{fIH#QW)THLWX?+rDjBShXaLmuP z0pS@JN6xl|YQqsY+df2Xhq;~qX^ajhVSv#Bx@O-$Jj&$b-}K6Wn%x{n_D-%c_mTzX zp(;NBo);nmPoKK)aT2O~t_6ogLhTbx65rp=h_j}6hbxfyA~`7WCdCA9BE>F5qxQ#Z@$ zQz$^~<)KT_BsPF{fxZA;1GxvFd4UFk#)7gy>p(|9XFj{pgAwH zVr^$Fz&09*+f}XBchT?x!OkeVUDfxO-Dh<7xUKm!uE)8n-QDpUr_cHL>Sqeom>&^3 z3)l8aagD1;OEmAbT{J)E17EU-Eu>z5rmFg5fx6Lbb7wqHoYnN6_jL1^BoIA-@#U;92~?x6*l z-RQ()dTL!g=RcT~n zY&gp55lpx#K+0RpA5HFRS-3_g1*+h}_HRV3G+zA?j$$emn-n!WY+6-VFN`6qDwZLQ zA&;SqPSrFvtX0889q)-_zIS?Qnh#C}-it4tm8Fa#m0?wZ4{0s$6HlMUPj%5C0^vM_ z+*le8oiY0%t(Eh-#E0D53=7EUAZI1&w<`ys7~sx6i#DDgLQM}twIdlhp&5zwUfIyT zR9tVQ_%c#Fa;%!)8z~++w%#im=-5=!MJRZis)kLE&snPO_JT%k)<2N7d4zITvx zu90`?hQ3;Nvn6g+>8Xb`+^Q^%FYO;e`e@|XQp+RgjxFT%0Bwk6;<(bk2WThEUA)>s z8G!nM5<#;;t3lg9$3d4sw?ST**Y#AfQQ8N2!^W;1s0El8slb6+2BMGeY8P1tLq4e# z@*+A7cK30Ojt9Q*gaKbMJT^$9d!z3gQ0g76#hAO%ba4Y{7w9zT3dp@ZbQq{NXc%Y` zC=0Z%J&vcPnb%%K^*+0-vFj=Skl;QRsb2E>zu;B}V z_g?eEGBO)uQ%~n zdsT_5%?edGmma##g0sc}GRw=$1_0=NiMYdr*4u zF)C>U(vpn8o}Q|fk7$tm3J5$VKrm&hRegKN+(YjEjZs}jLNXDO`H;+QtGh0}j!|n! zG6|AZklY<{?=x#u7hMgrJt9ig(O3@mIs%2zDGnoSs))w9@nLZo1$2BtO^w4)oGO}O zy6FfmVH}CmyxgdQ9X?`yTfO+S*241P3u@)l+FSPBQ>X;!1v2A-)WOea11wjjsFlxX zqb(?c+c~?;rq^hTp`}_qN*iQBsxOYx9JBus)1WJ$M!{xN0B8Vc6lgXm7ql640CXC31!M}rfm~2e&|pv^Xf|jCXfx;t=q%_O z$h`xaHmE0PP-)?4Ez@jUjhyQ?Q-zF0m)dQn(TF4DsOegJFRTx{TjY4@`LS9vk2SC! z18bD`QeLZ7SOSW8EhO`1s?iCW>&?~GY7Ge#1e<57Ll8(yUu{!e7uZ`UuW_30u@2$` z@Nv~BOLNs5CQfih!=`=!WogP&Wuq*8WD*9qPydCR$@y@WF-sj9cdtgRR(HlBxb+Zh znWaLW)k5rB@EIIZ4NwCKIN~ztS*@9Kugi?;FJyaE&a+xe^B%S3Sv1-cEosSbwYvH& zD%uG;Zr-Z` zpTmjReo30^RPAb&lB5NNY=nzH(>b1|;rJ5vtYkwI(I?#cp)GDjeEv*Vf5S(0I!W_# zHhHl=dnf_>)XgNVt!E1{Ho7+zn1seSDFaWTtX8SdA!2VLn9VP$`OhOlJD$VHaI?!B zb#nPH zxS}su-5X211fB|%V!U5ve`{^&(@;D|#MF`RS9hMrP@|#vX^9N!zWu7p_;H#XTsJYq{>lG{+8m^e zJg1DPiX~a({`TQcumr_Sw^I*LzAHY(ontI zK8bVHSa)z&jZ(B$_Ju}eq|cJYeuQO)eks~?3o79D6!?o8GwQI<0)BXsxw*p&0joc7$S(vDdtI zDrQ0qx(zG;4PqELvTyD`!qB$KjlnA$Lz<4 zqo>2j*=t$-kdi7gWNE0#ern4!Ey(k2ky4X!S79A+7y8CDtuMwfczqEEbf;r&3mZ)~ z@8xRrbc{H?m)DOtX@Kfav1x1e=hN%{e1M2*kw0!^V^rO5n%1-NbcBny=u9CnU$$J$ zpQiO!xoKDtsavj2Ow-z_BWY;V6JKSoT?2i8Rg;Dm{MS^?p=>iS0$AR_0#$Q=6+S~7 zY7SA0W}p>zL@c|lP}^r<&8^#t`dGpuW*iOPE)G$lGhsgz_Ghe6!)GE@GaA?@<%cg8 z&`XbPRpE3L|A5)HM)+-#E?8O;_9Pg^2fc<8Op&qBDj8~93@-&WPl!eFbdDm$t1_tzYT zX;?bK`ebE&B&k4*u%1G06+>$4gw)?%NzZEfdSe6HbP4_y!q#1O^?&`uCJt2MT}=C! zRTB9B@y=$5a=wJ{A3*q*4JY3US8^$t9@y)b44sqiS!S## zeR)2H3YNPoOV?*>xGT45Rq4+QFx|0pXl5LMH(?2Mq!x zg64r%gLZ*Vg06t*E1<0&fDZ66^Ghy^F$1SHgqNyS$YLl0;E=`IZu2P>S&Q}&utcMG z;Ebn@r!0Y8%sOpLs@38pT083!TKiC`zv8UV=EJtGqGTJcNDM-uzf^5ekMzSDYx|{I zPYc|RUaGBa(j5^Q2ATxQq6nGIYnMYQWg~k7DpbgFt(|88K9Wk^8I>B|EPBTcvw_3b zPXEKlLP(jjZEPE``aZc_8|<+TzVCPdYdSHScAD3Y2{Dr5yRxMq~Q`oN4sC^;Ig zck!fZdJa;EN6T!F#p6p@T0i5~*$4|RyOH1^1S8|sZ#gLWk@0j?gri0{g4^^66}9r- z%w)e>wo(hy55ZZcSXX(yaHagyl~|f|8BrsK2d0s#>~$<4t-?dEBb9v>)ZR!Hx=MS% zIc+otMHWd3j8w_1&;s`~Fs7-)NR__|i>h^EOkE-=fsuSCc)#+=Mddw=xbz*P9?jJT z$lwx@B*75~#*R@t8w%b8nrZTUB<{O-^d8v-8FsJfcjYXAL zTvEyFI6NkT7pljuMt8D#tXjSbUH;%(@O8y%q~oO6rgTtV$El*#D1s&l^#w+{Hcnk1 z3QzumC(cJjMoy@giBmpnv~JF`4U9?m#;N!<+QZJ5$JP5pW2-n?1mf?u$EmV4D4w?( z*dRSD5!TlttYZyi)bAjhZ(%aqZ!Mz!lgKC@H13L132PDcj?dNyNUK*8^=;(c7?F_^ z8jHoLinWOP`3A;bhOu2~W6b+ivO?83iW;ypQLR*3SLe<|_MAMRuH@ZCs+?~-wMl9+ zG3SYKJf}7izz2@yXO9Ye!cC~diH0+J_+5qHM*c-^La^%(<|Y)|5mL+sgmerc{V-m=xB+VRhXx_x z#{L_K6g_u`wQ4h-q6UoPl!j4xL3K}TIz>RQy9Im@fR8MYfposEFPyxZ?6V<+k0`r>?oPZ!TH&W28AcAYUxDOmr{p@VjNGxfRa@ z$f>JyPDB==S9q^bn_z#;P}Im?RWlKlZn{4fe!9Pf`T)h>|1Io+WX6}i^OknVVu2bx z^$yfQ))sBB1*-GZ7VHbo8>5E21B5n&aDwH~n9^SV(w4hfb|#j7^qw}u&CbPYHVsuZ zLGH~|>~?LMoeO{-zcZf5JHK7SEqLVVlRLCC7UWW!Vy%}2nF91x(~GgXf{a)RLpLM! zbVJ^2r{->XZDMJQo!UoDGLNI%I}iF5Sp#bb?=5@2q+P>up4^!eDm7j z7Ek4Q6eIp>czK9zBKyh>;7pm9)b>5;(th1`B7@ACFO0C*bzi9cI^kifUDR4Atl> zI8I)m8h@faXaP<>runIHpJ0`N>qWIH_yo4j!q$-m>ewe3z8{ewsLfJqN>De0abYxp zzr>WFB9223|643klcVqxRN8UuBUG!sklN0{yWm&UcgLXxgI}p{*VJi@Q-KvoEKbcb zBvoh~z%65LYXv-iT%3^lAyqI=U4YaXC&pc2Oe27C%JYQwEW%7ZfiS;Dn3rBrYfnIz zTxt*|EaGr4a;L3YT7f3|*9r81@6xYUpWa(ltX8p~!jEs@hiRdD`BV5|T38=%>bVl> zhEr?)kaMD{`53>A4>=p=-fKM_jg;3(ER8}&x1Rz$apkk~NtAA)3O|WqO$+hQm1Bu2 z?Iflfi7MwLlH8$zl#&cz$@mE|rktQ8C#t;9Q0$E=(LW7sAft>;RKb<#pSCwJCf%K= z8hnj*r``<5e(26hrdoXmI0I4nxW3 z4MM#0IeHl!Y_@g9q4~oFmL4+oAPwf~J#rC%-Dv%0(^EW=Tk!=Za?ntYYOEYV$&9YX z+BK^YvnkoIv-V3^fl8SFB^G_qO#6NXtEPpe%fHg_hU&qErH9UH_>LH|f5_L!{`Ozv zs2H*p%%gVBCbKDrL)-Q>ylS(!w9_}(0kb2fn3$MpLhi)s!j1FVfQcKRg?E8Yg06ww zyW@}*XdoyNG#j)DvRL1RI)LAju9prfEmpxdBk55gX3;DeZDrC{?a zz*dC}`xEO*7g3~t8qujAp-kXWOl~|ja%W$}P|0N>M3udZ`x%=qYLB+M|8@(V@}c=1 zy!_*$Ho;>oLYqyY<*&V@1$bcFz*b)FuJBqzbJg#Xrn?zju{lO1#$x$u?2CFpgI66+ zU((iNx@WxSkX3`;1Uodg^X2OA5f<07`V>`NgPMl@1e^acywY=T33`f(_zr?h2-+M| zj@kMEIkrV{p!(ptIEP7BiQW5wEExC2NQ*iI(?oiHbS6C*VXQvyLRS(1&4#gw33lkK zcz$YVt=8ioUb=3l;IhZRHSh3O;N?h{mxgDw`swDxq}y~B6o9Z?a%%1r@~bN8WgSmR zUWPt;RfS*HBIH(%E84EhUGqq#;_np(%4E@3Gtl0h;@+4Bx_@jf>uD@mQz4*8qH(&o}G+bHlu9BXxc!w^B#gncqd1gim z}!4#$ChS1a#8!Yg&jWExNJVF(Zqq8^}Z}$ii%hT7z-an~=_+6LvC1n+BU=p<|Ow z<4wsX3KB2oh#J8rsnNVR#*O4R&QTj@u493LusBE${{4U%*r#MQSP#=aEg* zfjB2-ngR4QgGE$bEQP_!)zi8+Tv*}@@euWl6Ou?fl zvRVQ^08$q108;tx1X4@irBZKbK^9U?OLbqLy)Y(c`+!v4_5-PdJD~EG>aE?NcvO>J zW*?s;Vy_I?6!MRNn@AM2#;IkxZ{|4|Q=|PF zh@~UbH^3%93f2ky7Cd=#3D^$!9k3JdGLXFe9@qnT4M;_D9T)-p3HS(*{GlSc2_Ef{ ziX`hP;053?Tv9Rph99G0a9eHpSsP(5GSm~@rYWp7d&l2}lu~2HIywb!0d@hBx7~o4 z4jVOs_y@t;!Bgy8pyo|77#%FKqEoZK}$g!K)XO+fUbc|J+VLl>JAzNN(9XYtp;ra9R-~S-2gQT zho7LHppl>{;pS$hh4`@nv;%Y;bSWGI!N9d+v398chS403pxJhQsX~6k+5&KDv3Z|z z|6S{D|HySHQw4U#Lfpg|eC7{PGF7RB-!b#7QgZyOFoC78l>Zn3_hFf^l1)qZT~D4|aJ2F}i08;kI_~ zW0HP#TC*kzNKy+tlul7K4V|jmerfF{>+fS#dL0I&<6xuBS+%k5-eTHVRZD_rA!vJ6 zHU2|$y%;lA#r^?7A_QH}s+SuI4w4`Vf{3%~`-XzhKOuMyg289i@IUX3hR3Qr2t1yL zV9Z$@PWI6IG^Ol!O^ntd!aKh#wf&`SG`k@Is;xgBl{|6>%U6i(#XHy>Zwu3(CgE^> z`@b>2L4=0J= z&I6xOZ(Bca`QHvwf2g9&dXTLIu2)`DQ_Xrix0Tn-bXqS$oi^*;RlrVjBWyEysoY_< zR;Ar-dK)@KIMhQAwe5zZ@@s0ohu#;5%JzD|pHdig{ZW1Ap}Y2IN>pegJxJdJ!P`G_ zywsgXaY23>K1&|zGNNJLbkx#esC_Ajdy!aefeMM*MwjIe+j$>3i=NDXz#jh-dxpoa zHd(QXV%OU{KN2%?MH!H#3Kukb0&&BKR`5w)M4{-0+HTj|Ig4)GpGDbx*4%g=DO;s& z!c;q(&;RGrt4GUsxf+uzuj7H%jL7pQ1m@8*0!jA?~|hKLK)GF|WC zd{2xi+N3Yw$zgmGs6;tEk$L+OVcYMjucsbjxBV``sVWUql6juG>p)+LDj~}UV0qN< z>Y}IaYPuyVurUM&A-Hr~J=wTH^~fW^Aqf2I)V_uSa}x*-L(rp6b!wuAID6F9XHg(x zxKJfEL2)ePNB)BhlR`Ezu4@DvCN*r5HrvV%voBPEUWThkFTJJD!Uh^MB{dzxZ_cZQ zD(#=*q?yx=qt*c&ke43RbfUzFGM@5mp-F9@r?)Vk5?rWmdg-kZJ5Q$(Tol z$Wof>4>N~0NSk{j$baD+r^|hF z!#J9Ze`#P$H?bC~3~$4)d~f)5wNbqz8nG`_RV=;E;9Q70 z?<<`od;*VRPh%~VPBZv_!L!~K4SpA@yjV;Ok2KTWkz?h}bl0L_iSld?C8RJ{`P+-# zsG9zsJ}R!c?)sbxv;^$fj-bLdajNajp-7vc*-)bUB3J+>Q^v<3{9E7=Q~4dwzxe|Y zE%eT^;D@8OE#O%hJbT}%zHXs+a=tH~(E=fjFP9h}oAO`MpaM=xo;V|Dq*g=CDh zX6HbbqZoFy(!HE7w5*rWh<%BwA}5D^>V2Xr3gblNbAS&@?hlbsvUEch;e+~?+q&Kf z4Lp~q$gwtW<5s~E`sQE<=M+D-K@Mq1xyt#oT)#+2wc zx0ZmI*1GE)V~NUX4d)-j`IG>)yR|-8MlU7G?uQzMp^z+`d;+Lp8 z*lC8lWwvs$V|rrPh#5E}sv>*iYtGaDYpJ)J-Ub2TvYD+WKy7TJyY7pXsH-Hv-78y6 zpnAEj?mB{Ag8N$#diBQ?Ow(BUlH-Aot&JdZ z2I{Vr`Vtivh*+J1rz%Lz4{Xqpl#}2y2;K}*KL$4FdcxX4a2kSlgVgAD4O|qGpbCQG zAa$ah-qo!*2=Oe#`#bZGTf5&&MobW_oq@HW_UgqTj2?p8a{{R9(ztlJN^-|zLd)yF z^>zU1RO`OLbGa)%wtBiJJ(oO16?}|O4|Qp;H-W{7_Gs73RYH3-=;bQAz3%!xPl>98 znf^IKTNBKosMu(H2;q@Vj{35U3Py~+fSt9$YHG0F)w-7KstZASOQq+yH&RD}^+rCg zHc&0oCX6?^I{a5vO)y&8*bw&Lr5|2Z{vpU`UcfFNP5Q*j6_`V&*+HwV}@e;t)qIUqwcx}S)y){0CN)CosOza zXahlNCkF$2 zc5L6k+n`YOM<^eC5%H zm+5F$fd7s4kU^-9G(*5rMYKBI8Bsp)S?QOZbxR8i#`j-8sxP;fU!xI%*_5JU58z%> z)?@lYY`qu*ZnG&Jm&fpQQb3eG-SYO2rLRTl3oMqR8>KA<={Ws&<=4{TPwL|=G6Xc6 zhO4w-d<*vEV10lEBfiEl`b7%{ct6JIkGlESnbqA;d>Co)5Z%wxqpo!F5WS6V`P)l1 z_V@5rn@8(@cJ5&@EymSCsDksO^--4hou$3T=o9P~DC~{n^%-tc0_0onos)GhOKO1X zpR9MXObt+zll9T|R}Ix?#+g?mDwmS=0d`iI_ssfDK=jH3)cgthXbaTe*Aw7_pgsqT4tTcBTfF{xMPaHH)gEC!Avakm;KEk_Q0;fcH_9k zl*vdXG|Y06L6I1q&*1DlKN;B>)V_4c3;KIzH#BViHhr^Hq-Sk#X-KNR*lhVCq;&gK z9aqD8pk7Yb&sb1#@tu0Sa+n66QCSUUATg+*1~ZQs)JcQcMNCsvP|DqF#Gt}CX6S1z zs7Pqlv(61o9H!hxmdV_|6rh}G(wt3v`iGypUTG#iu)+5tKax&kuw#YzaMCul5a7HA!42k3NPypePTKlF#;5ojc63TOjp z7w8h`HmH3+EYE-@fwDl`Ku1AWK&A*R%YeFr27wYm^FXUXJ3z-l*Ff(5u^bHQ4H^ZS z4qDwGlg(}TaTIhOB=+!pgCcp4$fJ)#tsazed}9FJX?| zl(q>DG~D5HsyQz~L3l%u0YUu^ACCQypgjch@rg?8@X2-ug-H6rwLOICnei9EVEh{l zJL?aqA7<;lpJlD$a^+h5r(^2$H<7{kw~9XXBDwUIylf}A!hBR-Y@9-)VEoNC0^r}F2s7}YYV)!l;*Z1Wrrxka^1y=} z4_^sq0qq>N^gj(NJz*sluAex>R;b4#A7N#lC88xC9B_s0+7vpk@}70`);l4%d~sL5 zhxq@JN0(_fhQBu$jDH`12PNV`!#%`Hh|~_)C%Z0r8$^r>=N03&VvHBW+dz-Q=*tFi zCx2ft*Dv*9JnqAWPk$oLl}cA#*hJ$O{6#Ss|8_=80zh8+`xjaKo)hmn&DTKgnB@-C^-(SC%x` zn#8MP^jwy)HEGEIu{9aS8-oAzl{Wb3k9GuHe_;s1>&SiklrCqkD*3B8>*I0*d=Sn$ z9pQb-o{%2_k-XCpX%4b)eBVB$?3lXzcV!W7s%PomoqE8_=f(Lywii9i2v2B~Jd)s;<5|u|9?neI8;z^o{;*XXi zTz`0e%;sIjyODC0!R72{*hvI+KA@glfd2n6LvPXRhsLht$p!jgw+!fIG8qU*MP@Bw;q<14yv7XANk^mm=uS zRAe-)(KPibU?6ZXupMwH7BI;BIPgP&&j4xbBp#Ru90QyH9H$}{>fJ2Rfm0V^i|08Q zqfr>Uj<44(E-pnHuyl1V^PASkgcc!7A~wKw2&-~u3iXRQFv1a1PR13v`L1|9;^ zUds{S%izm|{}?zI{893DK7Lff0G=7!oUZ`C1iu7$1-KO06e?&LFbGH<1_LoY$qE7H z0MTt4n~hHa^T3Y*z6P8Cd>!}_a1FkCt-oStWsGjxxJly7hm_U{-T<}+7O23*dP_TN zRI}*~e#fj3QfMvHW+1AgfllB%-~)m00y_XHZlS>U!9NV#2Bgf}3Z!#9+kuI|4}i#E zV=oaIVcG>A=`-yHB0Z)(z?FiCp~bXURWH_u+F51Z+bKN=YZNWy^L;y|W#B1M9|3)U z$Zymv9Qg)z1Re%<2Oa~`w%jMcNZ@haDP40|c1lq!#;&5P?r$(u*u9<7GZ0hop95*9 zlr|HorB(we7rp}a0iNTXQqq*zDOI;$#y7paVSWj6QepVu32l)=0rD1UEzHT^?}1d) z{{tj{uNYgT7BA=x_!D|fto;O}rAEqpT131Fo}xoMrT%9Xxl9kTvqrnOBl?@T{vAkx z+y;{EI$&4eAHd$gKY2$K%F5Ug{Ts%lIPL;Hff&2owtNvkMwwrL zu7OOCVn__?4jKfS1j+(!0PO-D2VDZ`k6~yH8VDK-nhshD+63AIIt{u4avzB12I>hK z3`zve2CV>X9%%M89mS9HpkG0Hl-U#j>J1vE%q#S_*M8KfS<``tqw5dvz}kN4sX|uj z14K!mY_Ru6IuO$NEA=7PN$_N8DLmE+RE6zERAQ^3+uofpt2rC|7{$>iJ|8B-=v=@>uLZu`;xSX*7t&sTWP}TXMCjY^hAB_AbK{|RULLW()KWaVkMO;Zt5hCvcGcu2MXAFj#Cq8u@ zqvvakk_w&9AbY&2ye- zjJ&|O<{aZK2ispG=2b)3+(#-|fyR8;6O8`X86%{~VsNqq5y~_bf6IdMK=$wsx?_rI zWH9q{eq_E(B2w3t%`aeaf$Uv)gymhDFyE(!`QT?5n`8Nf?Bz%fq<|qlAAOS1{*&9X z!JRgYwLKZ5r5#tIVvCQLmxZ%FCD`TEF`?riL zXC^$3+Q@>sevCII%Ocvb#R7ES6oI5oj1~PE!$lFrIhj8wl{h1b`G_WrDbkE@MKgbW z0;6*$@}E48luC8gj{_`}T3sSKKK(X3IJlb8e>3BqNXCTk7^6gk`urmHMAs)tGY%iX z<|#oOj=c%ePZ7x5!h&?^15%|DW{A$OT*~qba~b1%u?GpR_AUx5Ln>W@ zxJJwuiTRef$bX7}wKHQ`3S&(PV?`8WhUoSj$!vWqO4kP~^Rpqfkp0wW!qN|(R*nE!E>Mf$0<1yT$lsLDue2rvvl3+y}F&A9+ zHuL_H@ zQ&@)kI~Mlm!T`qLa5ldwmDer_-1@Ne|5oX*Yae2ZsSmTmbg5i@8Z+N~4$G?o7|TVK zMw2Q<#OG{e42xhqD4H~0nqdS+JY=t~Kg;VrNB)yRw0K;SB)sT>D3=~M$mUxuj9Yp! z7E4M>M5UJOWb>jn98ig9)G8^;KB7r)?qWXh7Gp^>#>{MS7 zK9w={0mdB3sr=o{&yjX-eVqB2R~d`{#h4=DBu5)O+W%S>%#rq4CmOM`C!1GG4kf(6 zymJI&^j^jY(UgIu%-{JpW06$mHPTGyNaqxHljSK!Ye4yLIlu4NT zG1h5}8B!GItjtH1F-8Y4ZV`=nD}(tWX$`5pnGch`pxjr+|9SX9F-#B)6)X`Ce5Q*> zpD^x~l!VV`zCu)T**DDBzQ=e=H0t$0=7Xj83~$N2&tKC16Qt6le8Gb2ksP65se}oV z)nyN|dBp>aIZ{`W1j7ZLGIClb1Dkx;8BhhxXTe(_B-QEsVt#_ zIsawz!0#Cgq_U-d$9(e(jAc?+_I|~Dw$%EFBC#hqbTv~dgLyp*ZYsvQ*BSF?GUBV^ zMg(ieFwTi*JogM^b_`?wV8)Cm8Ka+Iy!jYoxnRCvW~%&%6wL0+7J~)1i0&?z%Gsq8 z%fqFzCHV_4XcxTT$L7U?p+3ytY{6L9+`zu3RQ_QKb+Vw+i;>PgQIXV2tuJ#h-$k$j z$5i!}nbk56@sW%R6}53k;#rW*&JJE?EE&m|9l#~NtiA9uCXE;*Ji?~n^JVnE>|5rq z_GNclhZ=mQsV0gAro%s^cbIYVl$!X3hO%km5 zgY6am%IMz;Nc!uh^i7^vTB0l~kUs33Ygiy2Wc#j+Hu`beA1eFK65;!-?`s%%@3~rifm@l^y6$`l`<}Sllio3jC;cwQ)B>?A@dZoD6GgWEU%Qx zn;;4%$%o6lunWthMld#)aZh*-@hJbRGSG?tfi2vU&avVM^Lwu{rgdXnGlj8YA7hHN z`#I8Q9bC!gMWWCu4=`UKIau`=N30|l<_O>9lg1V@9%4-UlrcukBYQBP@5Y!U#{D3MAO-kbUC7K2}BjFsNZn#X*; zL?C+r$GE~OF_#G5lFD{R6jf0_c2`NY8xbk#!uAtHWmmLjbLU0_GfitmX9o{rfxkE7 zxtolEn;372DlU@NaBDc5TibI0)=A8VeaILsDmF$mY=KkkFJ@e1Xjqhgn#9~+RBTEl zTiE*_#vBPKbpi7QzcZfug)yO!G4Bz^7*WmsQb|)v*u3OdMxUjO5zhb-zUkHHNa}=VJezkJ%vko6 zfw;@wgAJ}r8RdmCUn7blLT8>nG)R@KOtRYlW#&_)?9eDnT{c|S6Ck-2K~%gm=s zpOPL(d?wBkc(TA>vaT+j`6%fmg5#LK6~H-F5X5|TbH)T|Jy8;nSq3205};F719Bv% z?u4L)z19J_mZkX#c?-*`V+`W91gc5?My9_&4)gB?4i;FmIJ%_1+TZZ^@YOdRq=~ z+0SfVyPh#l>O`!!n0Ju=Kf#L~boq`2b6PNNmAc@Qz8+Y?V7`y^a#a(VzqONbj`VWP zrI)J`cNL3Ro?XXSzJ{@nbarvl*=1HriqfRr`@4E6NpXS9W)mJ^4~ku*<3Q%arLu;l zFyBS$!gcYdP|Es_RL*1>LCxWWWSS}`u)~9~jLrXM%=Z)XV~iEu7-M8|86_HUjWoXq z$r-CFhs3`EDaz}e*?qS3hE=8@srs6-?;M^6)q$!Mx_A*9EWl0*%e3^yoOpWxK zH7D4-i`4!U!Px(>xiyTjQhLokQpdJH9lysA6GE=E*!sc<(9B)b8 zuuD!^gIJy+3arkZ`MN`l<H{PA)i(H+M8_T0a_s4w6e7sb`0tu%$)2M}bGE!#`qC}@BiN}3H*x^>u z=~hul{*SQzdSm#cTQo6 zsOFoZNWxt6f58~33zeb)GlUP7UNu~rZ>6-7Vo}xMhJHc$7mChK=*I!4eZ|;EbobUb znGfsFXl=<6OA(cw+=}_gb}TQD+Fc-usOUpBzbcF8H8M%HH-$O1|BS_KAzE~`buIJe zw;3xV8N;WExuhszJo9D4MJ_5lUR3Y7O>CYfD*VnP%olZHG^fb?|D0rP-clBHk*vHf ztiRgd3Gsd(Jg8J)sdWqR?*cF%h^Kh zD~wkqXX1M?pD)ezs!T}Ao?-I>#hA01G4wGpZ^f9}m9dLx*bLHt)c*5Uu%JlFHeojN zbT6Ld1?7y%GT`Xbo%uDQQfow|*2pNj`AU{A63tqa$NVyB&KKTdJ|XjC`SBoQ7dOTz zQN6*^jy-eP{OSzGbg8V@r8y;CV)GaY@Tvq@CW>jVxJ!_cQOvh&KePHQ|G-@pBc&G( zGn%I}=7{cIBOZoH|L^k+%j4c-ys9&%z0P<+A`~j!b5$CfNBozu=%|62rchBNIe{#= z+MCgNld<^Uf+HC1?9g;8fcePABB$;YMO8VHam@+Fa>??1snlh%2$gf5d@DQWw&tsFKCQe6ep8jcN8|`@vFVQLC6wlVQ76RD1&2NBB6Y#TL>X zjB5rm-uavHf($5{Ut<2M=u zzjYKF6!qs6B}s~s-)D2D=z*kaMu5lvYhxtOs|Ji6JF1I~|R^C%l*^LdOZ(wTX#X1+j*sQeM; zgEODxAMsKLYCADsHHopXgpppppcKW4iVl^rUz`LKlg{!S$>QJ-m@k%YJ+v)HG(%Kz z;AEC(MwarA3%3}fMFpFeGoL3@u4Rpw_y2=&uc%%h$=V88ZclE>@|Z&5U)@ zOw0Z<_)JqtR}n}hwC`iSNIXsu)$AP0=00yTmP<~pna%v14UCo2S1jtyd`5T1q*TUY zQPqWC5s&h}AS!dsPPX6~$Y?*tnExQ-9SdWzjE+lW5h>P-&8ww(t*H=qrHos?6uvEE zn4k}-ZiH`25D$x_vN+GN#YOInd50OpMI|SRN=^`!94o3g^gXtBy^Jv?pV40wQiQ1H zP$??w4C()u{mK?SrS_-&zc7hGX1lRhNg!TeRxj5Qw27m4bv zxWIf~9Ao8BEL{qyP5XYIAuUi-fGe%})(%<(Sf z^(x?@eq(|}zOB;2BI)4;iCodrla>GGf|2rMGyDjrv)^aFl*b&sgV}c+bH-fe;lDCJ zh-bFp^`1Weow8al$Y(W?$JpTR2h1-%WzOrvd}9=Ioc!K^O&&VqkF)+n7W3_~%z@H? z0lPW9vj+2ojdK16G+>3V?1sv*oQ}udRNFI9hOSU5zAfkXSy?j(Xxa{c09bRp#Qr#$ z(&779?=K@6--XjdE@S*v1y7~Nhh)3tOQfsag%^=4jO_x}GZ$219xgo`E<<`$%9$cK z-`0pZx{C07%sWpD=g9V2FCUN9mc`=JpA8D++&(KKg6}rc4R-y&Y?6xelQ|tIt9y;u z-7n<+1;hwBK7`M)iXT3K?J^ON^^kv{C`!S~F!hcRE0ic@6u7dGXQ z+WH6Q2P|j4Fo^loHRhxL$DHS$d*x5<{|COD5g?Il$)B7)B)8$QR<6KwlJx^V6t2yD zsT%WiS?$hfw!bSK$&%mw@GoY&f^6o9P&xneK4ZnHPnqWk`$&bCVq`7IOXCY~vEBSv znDb=>?#fi1I>q`7^iHjzct2(jY3PgBIGs=^`+rUdD=x_6ci~T*K9t9N_Zwz!*``?w zIek?YS7c94uaQu^GK?E+>%jW0jfG`*-H3^|7mIR355^5(%sP#R<`3cR% zk@RrqLr$-ehE#4Z`R_9C+0Gm{nz^=cwCt*)9NAWp``F;AyfDmulhXlxm;zmCHS^^jG2TRsV0|C}8!dB%MA z3G>)T%yT5t9lgitt#_Dj%aHmDPrt$XQU7A@E^(myMNZE@4@Uh)!a-K-l*1)s38(YM zF#F14+A3?}QX=bZvg%XhD)u6P^>^zsAC>qJDO^yU^?{zu(eR_se-Ck(Cq4F%xgR18 z8e54A6pUp)70%pUVtMTRif+dl zXQd~R8JvzT5(mFaT249j&6TQrLJQ_mvMXF0Io(|jodj8YzGCM+lJhU+yu*Uc!F;$P`SMo*a^ZbVAa8V&@}v8M0P}|H*zlI&(*(2r*NQ(}Ov zpoY@)26LQLlrIf9W`ZTxgA zr}JmY`JW=MQf~L*j2AM5{_Md(0 z!^ZkcHD&*&$j}}Q<&2fmgQv2cOk-J}(UUn|E~5qEoX(a=cxoJ{^Y$?>k*Daq>zrPH zlR4p^%$MBn|D3Y85`N~4$5W($tolm{oKD%q{8SoJBoXe#S=ReYgv+kW>8;{tlmxQ* z62P(~faUm3XTu?N#DSf;@(AWEiC|AJb2{O3W*>Q%b3y{iko}S`Yh#Fv$Wggb`AZ-g z{+R6^@QV%H|9i8dyTt7MMVzke&pcLc!58GceZiZoH_0)bB>CPF+3re%vQDzyjY-Ux z@|lNAd>CL-+Y?#Zn1d4<_uLS%+i?34$FOEQ;*a(HA3Ur6F|1EhlWGROW4 zSnr$4oY9xrTN)IP$f);!_dL!hn9ICGLS*D%P9Ke6KJ^E)pS)Z;A=~z;EG7?`+oX@! zE<)B&id6VQ7Ww={&M%6P{qNg^6|Td~*|Puf_b+v598oA2VH1XP+9QrR z&di*BQ&`IHM5tBuoRT#%T{<#0M?!7(F*exx0dwuv%=uEW|8Y*wlm_~K&*`{9%sz6j zpDA`rq~eSM&Yv$mcb?(&1SfNjb2JM}GMO((kMbq3XUL$KD zD~6{eUbwQ{|1Zg7y{|l5&Xg(4*LTevIF|>D8*chrS;& zUzIsdkas#x@l#tWvc1K2hq`e2jABj?$d>Z=)cj)#&bDOEm!20{IDM%a7rfAf`Osq4 zpYUSNPG(M#(0xjtA(u$#Hc9CAm3nsmhwXjkcwUlIn-wqIEt6OsD0A&Er`6S;*lv0r z^C58C}7TszsW+jY%^b3Gy$@TBV=gji(OG8 zwtu0w55Dn5c28v)xv_6>zAcye#$U|7vIgQMa1~C_dhGu(Y;Z^_ifqQ|mB*Pc{hj%$ z#DgU1*$bId*KE$eEg{yw6Hk@zZ=#pmbi`3k`$&YHpr-=Em?d-fK;C}mNl3NHV)T>6 znDhfXcrlR~9nfnhTH?WDX=vPMtk3v_IZJkl_qUvmKg@hqH3;<^g-cn{T^8L;nZqne z`^X~7ml%Kh54Mjyz&vC*v#SmB1G(LJKKTgj7yU$q>kjOl}GV`c$ z%roU|Sih0ePyfk$Ro2J@iS37~vHp~vTf7f=mD4wVX3h}%OR~!ftQdc_|NSLIZgu~* z>mt@CtzjM@$E9~Vr}uxwZ2O%#8&@giCqa(af~lYp?nfa=YyqNzy z+2@BIbH;od^8|?pCh7T!NY?L(6$c}kXUgKrlTaKdcSB!UODhZ6t}vN-i1-^DjI`SS zwdD=v4LJjbOku;P@*v_N`aQyPWHFuS%XWcsp}26G(|dB6v%4~%l?Du#2CkItXu{c` z&;RNFV#BRtnKLBzkCl*|ag+5oB=#RY$m!a0$McmbydZO1AdhNAb=fXIo;mIo^Pz^! zS0@-P^eXg`)tx5|$d^#+l7{Uh=SHtL%tNlz)Qw&(>gO-v@&UqIiPL-jLAy43Mdi$q zDSzN0c5-B_kylDSGDCM|;N$AC-4KZacV*^$rTXD=q+GqtcD}MQ9vtCx{0GeY2WieR zEHKP2(FGWf#w{!}{CaQeM(N5(iDPB7725 zKGxLJj=ZU+dvSrn15nc-#yO?pBK#2BbX=nGOrxRY~APlf|=)Y>f(c^4bIEi_HwD^J#r}Jc0k9~{N`Eqx?AeZe!GPI^UobUXV zxv~V(4B6!midg?Z#WU3VB1Zz{90`;O!#HE66!ehGaZ+p6*Y3(37sGrhnR)(3W>+)r zP@LRh*GL>Jn8NvU#LtarPUrYah1p_wD3vn`WYx~^$!Vt?qNY4fXG_DqM{#;=W3G5j z3+4j3mRz04`L|`N4z1#JK0jdP81sK(MRXtL0kRt=NI{c4p#=`*{H@{4g_7?p+iJ~A z)?W(a2Dl^;`!r_#^h3;f?=i2`@do?vkVM=fc_CuEC5|M}UihBV9)B=r7cfUk1BOV$ z^1fjG%&Odg47ry0NQI+5j3hoX(g0$X1-5AnbiZ?zC4IbH<4w%va@*oZgPpOC;2;T*v8% zO3Xz8+@Se>%tK@?EfGI)($FM{sOx>X+znZr-OaN9{bYYG>B5fgHf2M96Q_M8q~7?Q z^^pUZAN-ejzO0?dKu%{Nw5t8x{VV1Ry_l~`M7<#q)s{1rGsYfZcFB-s$^MSdlza&s z6Yg`mP(p3Q&zydY>Qseyt8n^(1g5-}oE{>tpiMG09(!4zbK(OQCdgg(>P1dhmO09M zm(!zGGkeIYpCfA~a3||;FJaDbF~>`}%3CF0rX;#EH}on$xaAl#Pq2Z9gx)NuycYb5ke@RW)q1lN|EU*V6e-&&pdsSNeb<(xhw+tRg))3xU)#{Tn8Va4q)nV&Z0 ziYG`2%{aySOWDl%;`q{RPDe`QOp(R*B9--f3Yk+Ra(0)+X_JQJsWV3H{~@wS{AJ(I zlolS6cTh!R*wIsYHeDit>F7UMpTB_FXE?Jfjyb-euq@szGpBF7WVVINJMGFh#jr7R zq=d>s2`EE!sKjr6%Knd&hIw3L`?1@kTs-q_*$rp^&1r9Ue33|+J%RN@n#lQoLwYz| zR;&M7Hb@x9?4QJZRYqvkZB7@+YR*2&=^GLm^ZYqIY6J5jSsN=Ga60l&=DU%y|0hU@ zoGu}9&JS#GR95?RX^4-U@7WR&kIL=%>Or>mk<-t+GNkaq$ zUm*Llvh*ZFBHjaucqZ8e-J9^@EQnwSwdI;V;8RZDeSG*|&swkF1RovYIbQ19ld0es&`B?YEgH@P}r`fd6pX&&nLx zo_S?+#n^var9hVSBt`D~Lu5_VUdjcA%wtZH9-PhP^e8#3@+H6aP}a|X&YUL^Z@s*# zij#mBsREwb|2}za7$}jfKo;Q(Io*mR;sr>=>n?UP@4G-rw_?UK9&eL zKpJd%#`*b3WBsE616k2Mh1pjwlSd^Iu9QgVe@gPFFc!PxyLqQ&Y*-H)B@%`CXZMz*^Tb zW6s>xD`wQU+RUxi8xudPS>31X?pfAj`h7JtgsF!lj> z?_pp%4eS~N(aykIJ|h>H4J-y$19t%YSy2Oj(bB+QqcakLbYLT}1Hj)NH1G%Aj7NZB zF^pJ1{duHiz&ccx^M?gJHcPC&PFb`M;TnFw0&w)y>pijVHU>GnPz#p+Q&Hz_{J3t9wMaZaL z2`jueghXI6FauZtYy@@y2Z4Hs4avY3;5yI*cZhHx1{e$s12zM@ffB%q9oPy;1k!;q zz+_+sun@QiH1|R$fLJfA@cs}c0_%V+z;)n0@EmAsLuEh=&=*(?YzB4%C4d!|| zpcT*s=nW(SD}al@E#ML0RSg{hMgkLoX~44P_}@BUA8;Hv58MaZR!7A^UtloJdFa(3 zXE#KvH|hX-1Bt*2;1=)*@T!510V9EFz&zkM@EoXA6SD%e1;T+Cpf4~O*bH0&?f@l# zwHEpWGz8Ltg}{nhn5m5rb^r%~M}Ye4I9@KeGq#^tO;Xq77%+zcMi-9vh31G$X(Hlqv(t#PkLSO~3 z12_m21L{vG^#|qw$ARlWrN$T$pb5|xhyexz!+`OC`b!yS0BaMBI537>kGyK;Jc8)( z!|DNIf&M@;un)KoJO?T@g=?S*Fbo(EdZsO67}fp8!O7z~UDa)I5z5#S0?0$5w1LSP24 z5ZDOZ0-Co(9Y8G59~cQt1D3VSL1hr018rNO5sw= z6~IPd2jCTfP65flNMIds9k>rX2P$>I>;P?na3BWg3v33i01Z2$GeBZTtjBZ+V}QxP z4B#Me3wQ(=o$w#fA5ee)Y96o!cn(yGgkzvDFbo(E>jxSO;tY_5sI%TC}pnt3kq1`>f4z((L8a1nR}7_pd5pg)itYtYY6z5M;g z$H6%;8`upT0nPwdfD*t;zR$ecgEU!aWcJ3tMJCS^*)zWMBob12_mg0*oP;BcM6p06GD&z{nv8 zHTxhO2c849hGL-rZGmtg1{e&C2XcYMz-nMOa0IvmlmK1c!rTF4fXTo@U@i*0C#|p(U=FIH;_n0f8i-)BgBJ1G2nO? z?txgKKadPe1f~J=fa}10pwbw$6X**J2F3%qz+zxEup2l6oB>Jz>sX8%kO-s$V}KdJ z!LfKUDu!?ocmx>vLu}1*rj0{&z%pPTa2z-fTnA#_LzTcVU^Z|BxB`>_*72AYAOz?F zBm(KcMqmeU5GV%fO~6P3oq+y8GOz{M2OOV(o6&g)P2R^62f~4cAHWGv3^*oYPXH5v zY2;_JHIBayu~HU_0BwPAAO^?YaP2&4mJfEmC+pcuFX7*nw8 zfqFnEAQtF9#RxJ+LYN3l1LgtCfcrp94yGL#3=9Kuf!V-f$}roSRo;;c|3ES2o6(Kr zJd_010b79kz;mF|R4gE%Ef53r1qK7dfZf0m;0#dxZx|^c1n3Q<17m=NzzSdoa1ba4 zE&{iJM}T_HkDZ3Vl?-7Wum#u$90$$=*MYXvF@``4&=*(?tOhm%yMZe}?~hOka1gi% zH2)YY0O$n70{ww?z!u;*&}0Vu0)2t;Gt~G%m<=ojHUqnXJAid2dI$6d5`lDJ3@{m( z0W1Vo0JnfgfH4ad0{wxJz%*bUunyP)90$$=*Ma-MbD$ChT5WZs7XKan0(JvO0PAd2 z4KxH=0U^mN_JcIDlJ4`T#W|VZ7u2-S3|zx2z59d&fs9fXe#;Fy=kf4 z*0lb0cqz>fQ4gT(cSj96XSX$~zoSOEd{Rz~7o2~l0Zplf_MIu8A71AFjxX(nf8RU4<;q8>zwpfEOBz8>`&Zg(`fAbL z#gsA^V;U=y2P2MzVMy^5(_>#e8uoVP6uDSHi25cN zYGS^_Xe_;6SRIrdS=ZLw9Gp%I>Z1PO4B88(5|#6)t}OtA(5RknP(MXM^pT=q+Eov$ zG=!ejL+@P_5R^{G>T`p%I)hp? zumxINndvmJfh_<+22E{Xb3(|ZZ4J;L2VHBR+fk<>>I$Mh4Rt%FHiVZD`dX!2bW^25 zsg5sFVboJmI8E_|GJ-bwqFf5y^tFYW9jVl)ku8*BebLS2Mz&UFM>@@d#_Y(T1DZ4G zStGp$LL0-2lSVYQwWlR5?Nw=YV|>+Z3LS22Ye%tuHm^lZY|UwLV_S6!X<}<=4$h>0 zO;A+`&1#|>wYQ0G;ypz!YUHQqsHY!NVKhmRi#GVdGL$a+p~f((-xMn%Jd=7hg=rAI z-xM~%w6-ZSgXmgQn1)cDW*C1L4QvLJ2%6dqA2y>&N|{QY%|Te8&C!Z9nxZI}wl!Db zC7o_IM=wJ&sFATI63tAddoAH8jT*I5Yd)R&wL+y>{VOv;+Q&1q3 z5i}wY{YasufrtmGbS)57rcs@CwkUII1`X7lNsHQ{cOmI?vK^Wbl0oM7iZdy+J@$ix zK57q-4m#W(9-Z{EJ*o+!o(|o)DGn$RMI2~}lO7^PaSn7f#EGtk(oiR|!)TEctq7;X zPFO{dIS55lC{z))R}f6nXjKrp?MkQ1L6~k=2HAtr23IC^4c3)U4b~Ox4Td8G7nKU8 z)*(oRY#$V2d$TfX*%k?HI6aKi^Vuj0ep6_mqEwn2g@u+zr=#F4lxlR=)K5_uEl?Cr zr#quu8olg{21KM&yDk`%hz!cqoJq^Opt%k@-9M#3Qs`P&-S;}(kV>N--Bbikr*WDyXu0N0I@S#>!m3i_q^2=g z%}2Xoa0kcOvf=BO7_=dU>U76Qg{D$Z&Db}Z)9LH(whnYY27#iayUn4tOzR#f;Gj%J zPFmFiEefJvdY}!#ROMB)D1@S3h0;aus}utDtH=wZUz8G2Iu@x2>KcnY9Q(1THY}Ak zXilTcu^6|obh5`O&Y&pGnKU{M%YS_=n!Pa&Yr;wApg_Gtzc>)jfK_NtRMf>jft%w5bKo_&!Dqq%)iJe>CSwRJV8WRf`n-43M= z3AT7WI#+kQraM)b$ZMwIT4j%H-ix&A2Wpeh4EPKr_#MB@}8N)JGU2%&oeP#(d4plboVyBVfzckHzlH5IL;C=e-UkP<}^vN`J<8^ zNpKWQ?<)$SwTfJHE=gBXV-Qj))KyU`jT;0HX|!Pw<}o9kt_?!JGBT*fo0w;Gp~suL z3zOc2m6N_!6hyy)DC-tG^cKn@bdGon$xvGLmM(kl zE%XcY*r&CM9!(+ol=I3``S~u|LC8Y);I}h!ohlXt|Hxc4Xmx5tKpKvM>ihnN(wvF5W|tlO`z&qD_;K znTqYNlEGBtLr@6yP=x!QqEOnTD2%Qt!qdZKPz3b^QPzhT(HWCbPf99%JsESHl14Wt z!zIFDoovM!)FT_m6}tXWHdZsvp={mthuLrwL@lO(f@zSV5SpvVMF$jNCKX{Ob5K*# z6x1{<2XlwX%t4n^=s=EYdMZ84L62MIU?Lp3Xh|xrw7F;r4#>HhGwDDs93c=Z!ttJ` z{N*ZtdGLo59tu=`SP_o*JiQcxrh;&pRTNIE6d`0!g-Ht8{|5hQsnk_-8ojSMoi>2! z{8Y5$*5A;QG>rK)lygu|MNXQk2)6)5!Sqm32(_NB4&7;J&dBLl{h_o}DRwHwMWw)n z_9GY~aDRmHOQESBVK~!M>A**}9_I8ks`9a7+;KE#&{EBrbnRn3+)ZbIoRq2v@kvoI zT~ic7O=p5!lsXf!1E+-|TtF0sQ-@g~-0)_>1YJl7Pmzz7y+lW*5I*aDN6Y)MX64o!VR8WK80eYQfyQT9J-%kFz^Vm4CJDI%aA?% zQ)Dk(rrU8~8MZa?Ghgu4mKf^#`mnur5sh?q=;EHkVGmI;)7*$p%#?#IUWIJfq3Y5Wv$O_Cs z5Y<@;f5FsaB?dKwrmWPF;cKM~rE4ouNfL5QrC(OVDQ-n;Py)|RUDv>? zi>9u@%;OPi*BTgw(o02Q)O9UJ0=L5{Yhi>N%33&b(6hCAIRt%yh6GXO7udFG2vA>O z%|Bg>F~9!>#yo@?t<$X^xDIBaG)qw!?Omrmy<7)R5!7M5ZrS_mVVO#s)*~;C?yW~t za9eD#0fUI!Vy0%iMB1Qhzoy7ZjlP629;CiRLxX9RN`=rhMJ{T(5fn`|zzoC2cCg=qA?LTo)u;lo1Ijwx)tNpU8nZi1nMmMU`6=}jn&XUVTX z!PHYx2z~Sw@?5l6r9$bMN`+C-W>7ed*sMn7D^##~Ge#waE^kJ_8on6{M-f6p8l@K5 zda8$tO+{Ekc&K<%go-0FsomFbfE)SO=nG!gD8ie#ukqLwOrhT(FN8*agATfA)i-+1 zZhnIqP0OG)RlZ^3hDI*mpy?q*B3s5PHSC%0gwIOwI);`rK% zR1gi?3imj>R4RlHD8iAlRd=@CHeF}xHa*0vR4ReemiwHXQ`Bn4)4@e zdhSwNe zA++CP4KDM$;lM!ycf)~`KH81ig6M!!2Gg_Ms5FE+?9okle~)g$HkHCoR4F`8@5S&( z(EEFlN}+9vQt64JGz$Gz1#&#TY0jWc-(qqdnRN48WIL$EJ~+Ywswjw-?}IX!F7MO5 zuCpKHqCSd3>7)I~3!}sPVHr;51K4v|Gd&JK8$ll(;H7i&09t}O-gk&IsWj+2j6@pE z{SHlVA~t=8suA1G2eICqnbhYXtQ@pRk&`YTMCY-v59wa_P=wfY2p(MY^&!2!o*aTn z7_~U8n~-`KCK0q$Q3{bk2%IIaqsu28n?tJD%(LpM^FYa z{0LG(wDt%Z5KQ-uU}fVW^C(^+xM-H5P&%h5jG7*U3HH)4J=#3T6pkglJ^<<3F&AGOb}Kce$NH1$W_kz+r?8QvoP zh~Bv=P1aSo$rXRr@(V4SseRKFDB zevMv2&a(&$xo2&@XvFffm?~U5PoG85#RmX2&MC&tPjdz>IEN|4rSs%DxJJ)^205vZ zq9B^9D40(EtQ%3~yzY4qMWHlR5#qk0aC!!!%I7h*T`pkrrqH+x=qzrW+b+OAZk!J< zpkCZKgMPt$;^p;-UsM_o>%ZuFe^Z1w^{cLTgrZ>D@GJU>;Qy;$t#vM9{6ndSqA+^@ zBI3aMUs2(Xi&zH{bQ22H+vpPfXB5cg7`h7624OeXucnypf zGFP?xZCBCQV7hq~GZjKLuIY~SxQ4O1T@_Etv#;q( zP}QoNP-oETn;1d7nX~^Jr5)7u-#Vg?Rw>-g|BZTZOHwJknz*HBsOK%T3MVsCH1igQ zsQ8u+sOH*!-8wLYc z)c+tAL|y*_Pxw3mMA`p=r-T2oIcX=PMR(vbl!ETSWf+aSgZIuy?%Jwv-+agBV?yP} z?xOiFdU6+)gi`B!cxe!D&sNoS$I~!s8tLzT@b0*G)Q3oQ^j~tuCv95K9~Om_`!FWg z3-M&)>j4ls__R3 z;$w|JbjPNsR0M7N19|vZ;}5m8@Ptr;uDH^uUkSQ`cNcR@;1}59H$d*iUmNP4$3F2W|4uR+l|cCWvZyg7EC32ybRRRo%3~Q&)aYrGmG6 zzG5F}F-N4)&?-=;(5xzU+&l12p$h!tS@WT0)K^udQ6HFQRKZK7*;Vc8q~29k*Z5mi zyIP_xyx;|M?`2nOeU_JMBtF~pLYL6kdtP?D`bwwPHkHn#p*FiZBUdSM(oLJaBklA; z1Z``#tM|(T?Qo69c18I3$PS-)uc^pIEvo7IQmY|_7bS|q=(JLXlfAlKO=h3!P~y5( z9ZI~nP$^8GqBIKfMoX{=M{CZY4c=%e4z6FkVeFtfHBe>9_8v9t4Qz0j+8DiZ(p*J& zX`=|?zp=fS7e2^tCl~i+^q{f55nWzir81>AvDZc;CpCc^go7p+|1i3&2=5a8bhCQ; z!3$o#`@tlY*7_kYjeha7xx^num^hul?B%=l+nW8*k?;C!|1`0(dEEL|L%|G$5TNI zdxMvAR*ptG^B`@_GZ2f1Ix7ozailMguj0~=yiFB8Y zp)9t&D%vh>{JY~yo5(t;4j+lN#MlL6$R4)TOQ>Bdj4~b;TIn@2x0Rl&y-FEE4^;{e zz5z&u(!cu$E_tBh=&ko-Dgib4^i#(l3;UeL*x2G%zsv7CE`=Qr!l|F=aDZ+uqRyBfcF15c-br)h<|ZIt|r~7rwzNisFTDFwC)l72#$Q0t%y{A==|y zm5QJPA$q8vsT6)K!39US-w$;`8%~Q{y4J&r5PeZ`#{GJ+$ z5yAPrD-;_R=l7FPy>Hru!6z0$7^V-`Iz@Qp8iqN*ArlT0e10Ad&v;@~gik(|GMw%y zil7z|AiQ~uKpsB%jL@@xOr`L0TIFFRJHRKdWF1gZIIUGF+?qS+a*aBo0G=#6q5$s9 z9Wf#Zd3!bE&J3m*9TCYLozNEt4eErRBP!48q#M0gB}4IorxUt}S5NgLRXT%uM%qKY z!^(YfzQt@9y(lo=UN=sQ5(&Z`W&0=50u$r4F&U%F?trZ0{S%I;;l8m|w<>q1;t@Ht z=yr$5;ogq9%Eai0C{X5(b>a>Y!@awkc(`r5W{uA%vuC~7BU-ra)xYdw-`!daOTlk8 zy6>!)w@VeJ?>6$?_sZJHI&r0km497owX)?4vliXKG=zqB(aUgd7c3)O3-@;6 z81keGmL+0H>u9VxJh~}z(t>Ch<9Rt65dd!+R4SMnb=4bZP*ZBTRD1(cBoDLLI(vE~2x;(u2vfFSbxh+WhF$Mg8mzO)JQ^pZyK1 zu{5{|t;n?3rBC|VyIc1?Tb}j*OET(Z%?r9P#IlDz)Q6OaC*KT=QgGf2H4}R$q!HmiZ!Nx z53na$OC+}r4H{_gX&s|lFy;+=eL67E-ov`NG}+<}Bui99$W69(QC_s&y*E&-p0oum zO+<3Vr>a|t_Aa%i;kP)|&x(eIflYwlp+*jRSdZ?HvwM(tlD(UCM}2thI|?oOAj$5k zm55)9RX-!~`oaV*R#ojwLZuT`EqzDYn^4Rkd#rUwcO>TxvJbY_8;X&+KL{rKmcT!x zy7bPQ7{R`({dxpXzG?4j%~iEyWEzrVusy~)=Ds_3?qIaKMEUEIjJ7=*4EOgJE8`&; z-+9UlqyRcQ#QwTNOPOn<%aFr=3IXuUc0qr)Z=<1-xZ{(|TTYPFK15EmRq< zhWpN2_P*AMN0gkA)}DR6&Z^~gP9Hd>j25pz7^5@FOh z)gEn~p&AYcaa5RU?`%CH$r;x0(gn024GXB1UKq(3oIlgxdEz3BT1+~syrSB?LP^DH z=JbHo$iRSAFHMflun)AZEA@9-C6iUdwQ-+Jo~K zhU*@UK$SC8)ATUSd&h32eIrmTvAoWMu4UM3Qph_hLp8{4+}9c_GZ;X&kr=;9YFsdb zldbiXRIDV2suF8-m^Ha{NKTK!mN+kauMP!`#u`dgt(uMHLc+5}95Dc51{%#Wx zkFKbVr1$ss30MuWYUY#QM<*M;kGYtqoFF;gnybg<18nb-_pw#h=?(G$HpphZLR7|) z50FuBG2B<5h>Tb@kGw7>Vm;1NkwR^xMOiRQR+}9msxG~iWglR5ly>=K7KY}&^6Ad4 zMXyc5KH68_q$cf|WcN1vTDBKYvZs0nCK@65x()mjApK)A+KQxR?hRu#^1d(48%S@> zwzte_W#oFBaB}mH9cJzyRb)Bxl5onaAG?vn0{(A;>p$>~4zG#Ej(_0i{y_<&2fnHz zR;?ENR4f;0%*A)9MRS&6#wpz$Lz)jyO`KXzjf3;4gu2sC=*dnoDN_&WZEg(N8RQ@k~ap>EUwi~!*l;#B+ zJ@LgX{-t@H>4!NO%#Ox1sPXRx^iQ?YZgTrSN1l72s~H`|O69dT_9G8h4Jn6fnf#dW z@0E`r54%YJR8#+cS$<50%P2

(aMsITbR)jAnl2opy7VLxpihYvk1xO*Nx)xx4@) zxdu1GHpb2h1#z=2Efumg7pQnoH|JCq-j5n$g$m={ z_33F^P@!DKQCnZ3oNf&F-(-Xvn=2G7-^1?4_Z143Ux?j}lNHK!uh5tq70Q)wOoVYq zmy_|YhPiS7m<*?3X;yv?%MV+iQ3ZJo#kd+`ocl+G$QBjKmEUS%Mj-Oa=3Y9X>Q|9D zrb5B;E$wXds!*_eW1L26g>vObCc+qApJ50zV|L;cZG7L5m9}MX{hmCg@WaWG|>2^Lc#J44K%JIuWTxCBPwl-zwrWj zxa#YlY88$pmr=R73D1J+2mP;RlpnSZMgwHx!$$p6ab&t10m!RYnpb`*!i;F-ZE(kR z1T6QD3PS(ESMp_*=9N2?bBqZ_ddu>?C>#m4-CuVAYw<#H+>Bw@zga+%c-=iNUl1RL`8c}iDt)Vdk&KYYh|j=?LU~T$)#YWZD=Hkf&ER^8eT8 z7<{GPu+nll6`h{1kXg}b7kp)2QR$GDZ)gYO0sg>Bt5T=s7jQR2eJ%6w(!BC(roAyW z2bl?_ndOh)NaH8uZI|v>GdhTsiWg2}7H$yI7WA;9)4wARpQPxYYPhJle@wW*>_lGK zsC6tIB{&N=y7YH%3pH#NLuo(cjk36%x+hFErnB+w8zy76)KalA;YP1S72e$C%8y!i zJ@Hl zPNQae*`QRfFkslZ$a4>7bquciM=imw$n%nZSI_yM_1Wiblktzz#>BYG!C80XD)Rm% zUaK4V-tJ7LIyf8+EiLEc&O*7i#*`5zo>GC%4!drfnyCukLq}?^n-3}R_aq6Fn?(nBYvS{>Ddwq|ZlT1ca zO88VY(*^k_vBx=)E23^@r4O+y$u!MUGg=Mjx7jA+t_K^`C|%5|M}3Tqe=`|=rFmW4 zUXa(#I57i@L{(Qesm4rG>F)mD+Il1J11VV1eHG(7Vvc6B|PEif7X)A9ncZrxyOvHa#}aG5R;^rZF{n(O z4$(o;pV{l0x2~nA&tP~2s;g9V*IJXtz=6m5Le)lP;&BjSUn)}8wKmZvW&P$RlM$v> z9t$A8!r~H$6Dc7BKKiaeBfPgzqZP3Jc#Fx{NPa8eD|oA_Mv0!awwa7-CW=~tfoirL z55#QI6=HQVt%Pwuh%qcKf@ssC`Sb1cQh80-VKRDiZUICmja6k%Ld?;kIesUNUJ1kg zJ59z~&V2@PE{ijEneYV}s*JhGKk2eE?6_OCU%UARVhM|1?!h&i#XAsdvuN6@y1joD zidWi8dsm@&i&B+GAjC!#z1CjOB$>mZv1@ye4;hr{noM%Ah`dKH#fz)AOnc{(5_ znOHsZM>VQ?fR{r=_+E##xf|l?h7|P$3eLrMj)rNq`OqDj`vqpY-93{rL90AIhggM7 zs!-v5Tz9OxkondldZ{cu|1cT-*fJ5~44VH1rt(S&q942TeM+O(+3R}-KgC&Bn``{S zZZ_Va2OoIVtgM35OMKy}H~XmOZ8nx^(eq1)|FCm`s3vBk9b1fqXku|xnK&AvFKho^ zCaxEv#A66VX~bxVsoas`re@=NHlSu^ECOx&8N|vgt}7FZ zAdX{gv*t?FLy_-a+TKMFqgZ>Uh1qzE#bA8R>vvr23B*@ed{HJ^14^}3%fuQGrM=A{ zVq2?Td}=F&lqlaW%wmxlGz9vvG>GA*0RsmNV`D2*ex~Uwzk% z6IwfMH-<)k1*enoE#<4YrH!VztMq6Cu{#@%nL?M9;eMzFay@l(&Bjgk_yXbwy104# zbn3GihC^nXan(`d=22^|8Q=M(ThSL{Jc|Wo+6xe0Wo?sBN^J*2Y{}ZcL2S*=3g?;e zou%5D?|icn#NumZVqTf}4MY#rL_ZdrtSB9>1c=hAeh|;ILF<)fV<c7qd3+D;2_Yjj@}}#xE>3EmE_s{lvZZu@d?EhH2KBa@jnOQA z1aTsJc)6`~>;AbNQJZ(n+}&p5Olp#Dx(C^J zAri)&RcDh@n?E>9LwCXQW2gctWtY8fhb<7@pS8FjEYuT%I`@X1!_H6%{QPg;*XQV@ za#iQNI(4G|i6%9IXwss&@p+2+CkCXQaHMc=W{)>vI+#tjpQlYQ_4pO4R#c=MSuU83 z=H#~G_Tv+@_(pvv_6RYfY4sb_^0 z#&$;`zQT6Jzf%1@unWLfmk;6Gk06G!xEo?4EqeX}@iz-a?Z&_!yrR?zdokYEAl|dn z%RTlw=HlP!vhp?Lff+Ygoju^8+4#h)vpudqGUMu@)MmfO)Mqb7X$Z5&lE0&u@^T^ zF-|L0dyFU($Cil`%fuXrg}M%N+ov>TAMR57UziOK6ZQEPqjdPCS|F+k=94dV>nwL( zn(6m_b|3tDj0Md*wI9v<3*xIR_NZbpMrqOfO%)otAN`2O>zGcQI}_pv7XJ%z3>&7| z=%h0I#AZRP)E?JDY|P>zh`3*t6OlP(!N%fi8Z|~xPfbJ0L0o_G)H;k9~xqk27A*6ut!^83*z_u z@6e72h$bzXJNVK|l{=}C1ve(sLF6`TV!`R6#le0S<1|G-dZi}q`wqdmU2_Yfz4q}M z#8zzefxiVITNilH!h(3J#k#F5#>Xr!53m^jWpRERi}8TPseu+Fj>R9^S=60IwJp89 z1y>brh|^-Euyz{6xh&QQvKUoa^eq!xL9EHzj%C^&5ItGj8)9uOdZs{Jif8oiv2Okh zwixqhP9+|J*oDPPp%z@GwYE7#FD*85 zK-|O8tlS$?4s~}!Y0CFlxd%F0j7U%20?)sqv1-gL`^H#|UaxS=hV@bdti8{Jh#0P_ zpAXT_;%5*;So{g%2o@uITX6Dd+hT~Xu=q1Xv8@`fhFuwW_J@c^b3G7geca_dpFj*| zwK+5;rF9y zG)z3#kF^;2CTjEpS{U`7s$ZKAo}ffulr&G8K$l@@PMSpRPQdBglPq`$be@3Iv8AH< z!%5WVIC4Lktg1wAJu9Sn+Rp5sO?#1P4ik=J_INW}?eB!+aP@7D1!slwYJQTVD>7Si zsi&$iEYD(?X{D+#qEs|@%%kNhw<}aZoI4&Oe$`4D=0R-7;#Xzb-4L;wl)-g~V<=vU z{r_gc8J2evRZssL{#7lUwwPwYLxECx?1K0Pi{8`KQqtOb5WQGz4)HY>--Fm+i=N*@ ztZJg=Co!(4KT@komGjK_7)=!QxEU(MXm?*itgS`!z8Q4#M>L`4EVZwqA6jZIDn`(0 zKigt-qv&F^XdJ{jr8(xm=2BEK3at1hN|%(3%n6AaB!i|82G z^U5NN@u7)M7Nd!8F1FwbuFO0}Lfp(^!zHR&TI+-uLcXVAkOA?87CnQOT8w&D{L^5# z=($|&Pi@f)Vs91+A{G+LnYS*dm#0v_?@FqF8VycdX)zwrgR}NJo<{F=7UL^&o>B6j zkh4XexE{+>WZMRdx`nuW4(4qngatbs)bZ)_ITzShTgrxosB1Uu^z_Jc|;3ve!o8={qcVg6G2DmCA6q zliHoJ`@CZ8*l97&h?m)WEXGqYp1v26MdTfjt7`cb<2%Uzt;Dr%`(6z^TeWlk6rRaznRK(a#p+ zfMmRPUY+}FG#PRuEx%$cgt|8}CN z^H_Nw;x8z5CBO4%mshI~soW<4o1-t9;a6w$k+8-g}&i5-C{BwvE56@bB=(6G~kaaf>gj#We zYw-a@FBV@w+(-{DB2I@{@j$BcUkSIWd${U+Bt#R7Q4lAxxDBHCx&g5!YfH*(pF+g- z9UjbeBdFc47||~~Sh2CR(>fikxWFjUw3@tsRhz^(0G*Aqe}ov#g{ybs>2P+k8b5Nb z5ouNTYt_+LqDozkgBZ^S-$Ja-24^~#PTg-1*{MgHE>JPwbj5mQ5<;>&QX}np9j;QcSAD!f9W%h9#vW1Z9bLu`IW*3yFQ4bg6mcqdX=K?Wl zA%}dU76UOyCbbOSmmk159N2(yArKRBa#(6`J+L#YUN0ZJ0|&^YA~o#h!-!UfYgu3S zlAVjxP+kPNzl=JmeBz&TaW&IMcNle*fuV5%j7|C>Sp0owU6bA}R(W);7huGNjPbuW z7Wi&By9;1kMMdb}{qa`ybFH(b{&(8^fi5NuR2By4Vi@$Wlm6Wwr0!tXa{nN${ty{B zi4z!qvguPFCY)HKhR}hbA|A4=SukGH?}*%AMCnN`{*o#E6b?mqU=-sZU~k4k;2_3F zCZqirPXOZ>tt{8t%(xl2igCmgKiEVcotabQxKkLwW2d_KaWk253f;Wk8!m1isRm9b zOn;Cpo`V!F4^pL4fNwCK1>%O0)GI#LybTP!Nt3|MsQ#yBOL!9lp({I|MKKk#T`UKv z+}(hE6?&_Hmv9439v{B#;_5{n-ge+GTF#qAL!`K-*f4fmiB8tu)RX>6fj*^A?1A<{p{25 zcrl0CRXL9}I2{UU}s$?ca3Yk&lz)pg^UB%y136(;d-p25t-0QT_-!7#hyO) zxr;@E%wj%IVKfOD=`ie&kpZJ>$e0HsE@W(kF(hQv*i4tEqQG z<%u(-%NH`ESdA2OzMz)WHCOH^@ay#Z9ZP+Q@$?VUV*XEBBcz31PPODoiE}rRoRW^kx3WP^=oPA311Q|fg@F_ zSPgU-*8;I7i9F&o@FB*CJ#_sFjJgcp zZu?x^KV)83bzOEq1}>u_T*rg`)A%|Ubx`&d ztBWMXx(LkYu#118;Z&6%&iObHIEK}uKwR%ATix@1gigSrO7-%A6>Khd?*-rE0+2mK zuZzAq4*0doXSc_VFrIyF&E~dZI z6h)=?11@2Vz%^du8iUE#Ts$ySzUzTlF1&^Sij-LAI*AGg0J}1-1?pmdHdyI~ueLKd z7TA`v6&eh?NuvVAwNqu{RfZ;mb;0c3g3|=yL)1YniXSRtJ~(>W_?cP%RO1-S4B9U<>Q6Zl3s3ArEg8@Fgw(NeG%lp{2bxKqoI4qgvxZz zUyZJe9vEupZ+S z;Dd~FfiaA0fU49=;u0`Rsotob!m6SJXZIEu+$frp+gskdjrE(YycI=A>M!j(*!%bw zgmr|mY9A_-RHs89Is6WqsZn2wp&Z)*AD2ax=T%^3g-&)~`6D^bG13Yxt@S0bA6SL+ zo&m-x^t^t;T5ZdFchIyOQfSY%+(p^n;Ok%RqOyJs;3C$_4&oxF zr6+tzv;>Y+sorWJ`ggJ&tSHvKBybg@OyUgiA;vPp1a6F#`Xz7{V~^nicce;v30RIX z0~p2l4PU^xxwcRjy5<8h)D^x(#J;K zX7ISd+dkTrWKyYMjNOPgiM&bW%{1QR^5zTP{J@(VyeTgmy1^JxeqgLN*>8O#8Y3aC;PH5>TUlJ#QVJe0w23BA! zF{(G#S7U&9Y+M=Vw-VDLm^_(NqjY(BB0T7dX6XVqv{WaN0K}^&gng76^&tF}SQN#i zJ*OJa_mro~wAiSdfdLM+2Uy7XR)$~qS-{GyE(Pjhw*nJoPI(kI!FP=YhO=uNP=~Dt zY{qJ;@qGmt&FXZZ4x0l^Wc8Bqy#ds5ON{DGq!B~yPi>%X>IOi(=7gq^g%Lq|a;`j* zeOXK~&NF~`Z><9M!iejDc;ZHl`wgo>PS@fs<7#F4uCYK})+0uZH);oqrA$>c%#f?B?k)L zGD9oa$5=T9g?9jrno<@e1t$BEA7iDFQIc5cWt7pZq(ga>+cy`edr2O!F_(9i{VqYl zG%0{FM)!_jR;YK_$ubWKVh|MFGll_mtk;337?^~okl~m*)S4a|p}pF`>(ymJ`Cuh?3C;Udq^E)U zglq}a?a^qUKM!V zTP8bT>vdT!tOHo;s)CxutrS?H>{JE8TC9`{$t`20+=#8X^%*7QAW1~$(fvSF47|GL z$v_NJM?iW?Nn$Y&H*-i8=Yh{LCaj`)k5YR9`!TKuV)>bTzXKjq=&W5WFCeIszgk9A zMGcp)!G1V0P!%=YxK7{+!ojM@aUoye4zny__4UHS4<8VQZxDD-P&pjiNON>joidx` zeuNUUKc}Hvr7qn}moSy55Qqs}H8`H!ESpz@V=<&;mf97tlvp5e3#h#IXz387AWKDB zIs*xFJ&JX&0KW-`Sgp2FS0brKA~5vKvY%d#q7AJg4MtiuIWrbHCvTP6lyf?y^(?jC z#!~xjg5IbmuW4G!h7@G!JuNMQgl8b+wQ-vqULCO>*hRNSN{ZVh7grC~ak6&hAF3Xl zRA*L%8$F}-%ZXHrj&1r59a#Ne?Iv$;_(`8(3w!2Q?HIgT-`R8{zufrXLfalA^U@LZ zlV);vdhmNYT7HxfOtd5AwTxiXzns9Il}l&hYn>+IGhuaw pi+IfRV7`4WuS=vY7fc97&%X2P!=-m1#7=y6$*6q$;><34{|j<^{DS}h diff --git a/Tools/ArdupilotMegaPlanner/georefimage.cs b/Tools/ArdupilotMegaPlanner/georefimage.cs index 39f0039bdf..bf877efaec 100644 --- a/Tools/ArdupilotMegaPlanner/georefimage.cs +++ b/Tools/ArdupilotMegaPlanner/georefimage.cs @@ -117,8 +117,8 @@ namespace ArdupilotMega // line "GPS: 82686250, 1, 8, -34.1406480, 118.5441900, 0.0000, 309.1900, 315.9500, 0.0000, 279.1200" string - string[] vals = new string[] { "GPS", (new DateTime(cs.datetime.Year,cs.datetime.Month,cs.datetime.Day,0,0,0) - cs.datetime).TotalMilliseconds.ToString(), "1", - "8",cs.lat.ToString(),cs.lng.ToString(),"0.0",cs.alt.ToString(),cs.alt.ToString(),"0.0",cs.groundcourse.ToString()}; + string[] vals = new string[] { "GPS", (cs.datetime - new DateTime(cs.datetime.Year,cs.datetime.Month,cs.datetime.Day,0,0,0,DateTimeKind.Local)).TotalMilliseconds.ToString(), "1", + cs.satcount.ToString(),cs.lat.ToString(),cs.lng.ToString(),"0.0",cs.alt.ToString(),cs.alt.ToString(),"0.0",cs.groundcourse.ToString()}; if (oldvalues.Length > 2 && oldvalues[latpos] == vals[latpos] && oldvalues[lngpos] == vals[lngpos] @@ -182,6 +182,8 @@ namespace ArdupilotMega Document kml = new Document(); + StreamWriter sw4 = new StreamWriter(dirWithImages + Path.DirectorySeparatorChar + "loglocation.csv"); + StreamWriter sw3 = new StreamWriter(dirWithImages + Path.DirectorySeparatorChar + "location.kml"); StreamWriter sw2 = new StreamWriter(dirWithImages + Path.DirectorySeparatorChar + "location.txt"); @@ -239,9 +241,11 @@ namespace ArdupilotMega first++; } - //Console.Write("ph " + dt + " log " + crap + " \r"); + Console.Write("ph " + dt + " log " + crap + " \r"); - if (dt.Equals(crap)) + sw4.WriteLine("ph " + file + " " + dt + " log " + crap); + + if (dt.ToString("yyyy-MM-ddTHH:mm:ss") == crap.ToString("yyyy-MM-ddTHH:mm:ss")) { TXT_outputlog.AppendText("MATCH Photo " + Path.GetFileNameWithoutExtension(file) + " " + dt + "\r\n"); @@ -258,7 +262,7 @@ namespace ArdupilotMega Name = Path.GetFileNameWithoutExtension(file), Geometry = new SharpKml.Dom.Point() { - Coordinate = new Vector(double.Parse(arr[lngpos]), double.Parse(arr[latpos]), double.Parse(arr[altpos])) + Coordinate = new Vector(double.Parse(arr[latpos]), double.Parse(arr[lngpos]), double.Parse(arr[altpos])) } } @@ -285,6 +289,7 @@ namespace ArdupilotMega sw3.Write(serializer.Xml); sw3.Close(); + sw4.Close(); sw2.Close(); sw.Close(); From 90fcdeadfd76c2d77eead8fbc06adeee9ae46bf9 Mon Sep 17 00:00:00 2001 From: rmackay9 Date: Wed, 28 Mar 2012 22:00:57 +0900 Subject: [PATCH 32/78] AP_OpticalFlow - small bug fix to ensure init attempts to read the product id 3 times before giving up --- libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp index fda2472619..b4fb52ddd9 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp @@ -75,7 +75,7 @@ AP_OpticalFlow_ADNS3080::init(bool initCommAPI) } // check the sensor is functioning - if( retry < 3 ) { + while( retry < 3 ) { if( read_register(ADNS3080_PRODUCT_ID) == 0x17 ) return true; retry++; From 2ce597642ebda5d8958e9c8b6ba546377ed319c1 Mon Sep 17 00:00:00 2001 From: rmackay9 Date: Wed, 28 Mar 2012 22:02:52 +0900 Subject: [PATCH 33/78] Filter - added FilterWithBuffer typedefs for int32t and uint32 for ease of use --- libraries/Filter/FilterWithBuffer.h | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/libraries/Filter/FilterWithBuffer.h b/libraries/Filter/FilterWithBuffer.h index e86ff6b81f..a39f5e109e 100644 --- a/libraries/Filter/FilterWithBuffer.h +++ b/libraries/Filter/FilterWithBuffer.h @@ -55,6 +55,19 @@ typedef FilterWithBuffer FilterWithBufferUInt16_Size5; typedef FilterWithBuffer FilterWithBufferUInt16_Size6; typedef FilterWithBuffer FilterWithBufferUInt16_Size7; +typedef FilterWithBuffer FilterWithBufferInt32_Size2; +typedef FilterWithBuffer FilterWithBufferInt32_Size3; +typedef FilterWithBuffer FilterWithBufferInt32_Size4; +typedef FilterWithBuffer FilterWithBufferInt32_Size5; +typedef FilterWithBuffer FilterWithBufferInt32_Size6; +typedef FilterWithBuffer FilterWithBufferInt32_Size7; +typedef FilterWithBuffer FilterWithBufferUInt32_Size2; +typedef FilterWithBuffer FilterWithBufferUInt32_Size3; +typedef FilterWithBuffer FilterWithBufferUInt32_Size4; +typedef FilterWithBuffer FilterWithBufferUInt32_Size5; +typedef FilterWithBuffer FilterWithBufferUInt32_Size6; +typedef FilterWithBuffer FilterWithBufferUInt32_Size7; + // Constructor template FilterWithBuffer::FilterWithBuffer() : From 599cea21bb0b0eb535ea53f1c33d17e915768a07 Mon Sep 17 00:00:00 2001 From: rmackay9 Date: Wed, 28 Mar 2012 23:58:58 +0900 Subject: [PATCH 34/78] Added multiple new tuning parameters to the inflight channel 6 tuning feature: #define CH6_YAW_KI 24 #define CH6_ACRO_KP 25 #define CH6_YAW_RATE_KD 26 #define CH6_LOITER_KI 27 #define CH6_LOITER_RATE_KI 28 --- ArduCopter/ArduCopter.pde | 30 ++++++++++++++++++++++++++---- ArduCopter/defines.h | 21 ++++++++++++++------- 2 files changed, 40 insertions(+), 11 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 936823a67d..debd62fad3 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -2044,6 +2044,10 @@ static void tuning(){ g.pi_stabilize_pitch.kI(tuning_value); break; + case CH6_ACRO_KP: + g.acro_p = tuning_value; + break; + case CH6_RATE_KP: g.pid_rate_roll.kP(tuning_value); g.pid_rate_pitch.kP(tuning_value); @@ -2058,10 +2062,18 @@ static void tuning(){ g.pi_stabilize_yaw.kP(tuning_value); break; + case CH6_YAW_KI: + g.pi_stabilize_yaw.kI(tuning_value); + break; + case CH6_YAW_RATE_KP: g.pid_rate_yaw.kP(tuning_value); break; + case CH6_YAW_RATE_KD: + g.pid_rate_yaw.kD(tuning_value); + break; + case CH6_THROTTLE_KP: g.pid_throttle.kP(tuning_value); break; @@ -2079,22 +2091,32 @@ static void tuning(){ g.waypoint_speed_max = g.rc_6.control_in; break; - case CH6_LOITER_P: + case CH6_LOITER_KP: g.pi_loiter_lat.kP(tuning_value); g.pi_loiter_lon.kP(tuning_value); break; - case CH6_NAV_P: + case CH6_LOITER_KI: + g.pi_loiter_lat.kI(tuning_value); + g.pi_loiter_lon.kI(tuning_value); + break; + + case CH6_NAV_KP: g.pid_nav_lat.kP(tuning_value); g.pid_nav_lon.kP(tuning_value); break; - case CH6_LOITER_RATE_P: + case CH6_LOITER_RATE_KP: g.pid_loiter_rate_lon.kP(tuning_value); g.pid_loiter_rate_lat.kP(tuning_value); break; - case CH6_LOITER_RATE_D: + case CH6_LOITER_RATE_KI: + g.pid_loiter_rate_lon.kI(tuning_value); + g.pid_loiter_rate_lat.kI(tuning_value); + break; + + case CH6_LOITER_RATE_KD: g.pid_loiter_rate_lon.kD(tuning_value); g.pid_loiter_rate_lat.kD(tuning_value); break; diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index 7d827948f6..8066f79d6f 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -141,21 +141,27 @@ // Attitude #define CH6_STABILIZE_KP 1 #define CH6_STABILIZE_KI 2 -#define CH6_YAW_KP 3 +#define CH6_YAW_KP 3 +#define CH6_YAW_KI 24 // Rate +#define CH6_ACRO_KP 25 #define CH6_RATE_KP 4 #define CH6_RATE_KI 5 #define CH6_RATE_KD 21 -#define CH6_YAW_RATE_KP 6 +#define CH6_YAW_RATE_KP 6 +#define CH6_YAW_RATE_KD 26 // Altitude rate controller #define CH6_THROTTLE_KP 7 // Extras #define CH6_TOP_BOTTOM_RATIO 8 #define CH6_RELAY 9 -#define CH6_TRAVERSE_SPEED 10 +// Navigation +#define CH6_TRAVERSE_SPEED 10 // maximum speed to next way point +#define CH6_NAV_KP 11 +#define CH6_LOITER_KP 12 +#define CH6_LOITER_KI 27 -#define CH6_NAV_P 11 -#define CH6_LOITER_P 12 +// Trad Heli specific #define CH6_HELI_EXTERNAL_GYRO 13 // altitude controller @@ -169,8 +175,9 @@ #define CH6_OPTFLOW_KD 19 #define CH6_NAV_I 20 -#define CH6_LOITER_RATE_P 22 -#define CH6_LOITER_RATE_D 23 +#define CH6_LOITER_RATE_KP 22 +#define CH6_LOITER_RATE_KI 28 +#define CH6_LOITER_RATE_KD 23 // nav byte mask From c084a72723fadb5057d15107d91ca1e9b88a2b6b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 28 Mar 2012 21:23:12 +1100 Subject: [PATCH 35/78] pysim: ensure Vector3() uses floats --- Tools/autotest/pysim/rotmat.py | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/Tools/autotest/pysim/rotmat.py b/Tools/autotest/pysim/rotmat.py index f108c8818d..c7ecc6ae65 100644 --- a/Tools/autotest/pysim/rotmat.py +++ b/Tools/autotest/pysim/rotmat.py @@ -29,19 +29,19 @@ class Vector3: '''a vector''' def __init__(self, x=None, y=None, z=None): if x != None and y != None and z != None: - self.x = x - self.y = y - self.z = z + self.x = float(x) + self.y = float(y) + self.z = float(z) elif x != None and len(x) == 3: - self.x = x[0] - self.y = x[1] - self.z = x[2] + self.x = float(x[0]) + self.y = float(x[1]) + self.z = float(x[2]) elif x != None: raise ValueError('bad initialiser') else: - self.x = 0 - self.y = 0 - self.z = 0 + self.x = float(0) + self.y = float(0) + self.z = float(0) def __repr__(self): return 'Vector3(%.2f, %.2f, %.2f)' % (self.x, From 17290836ef34f1b1e7bf263c248255b7f4cad45e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 28 Mar 2012 22:40:32 +1100 Subject: [PATCH 36/78] Compass: added some more comments explain the algorithm a bit more --- libraries/AP_Compass/Compass.cpp | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Compass/Compass.cpp b/libraries/AP_Compass/Compass.cpp index 4f485b2705..a0a294a65f 100644 --- a/libraries/AP_Compass/Compass.cpp +++ b/libraries/AP_Compass/Compass.cpp @@ -250,7 +250,12 @@ Compass::null_offsets(void) length = diff.length(); if (length < min_diff) { // the mag vector hasn't changed enough - we don't get - // enough information from this vector to use it + // enough information from this vector to use it. + // Note that we don't put the current vector into the mag + // history here. We want to wait for a larger rotation to + // build up before calculating an offset change, as accuracy + // of the offset change is highly dependent on the size of the + // rotation. _mag_history_index = (_mag_history_index + 1) % _mag_history_size; return; } From 16deefce31b5f6e7f2904a183684fb6c86728601 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 29 Mar 2012 08:56:22 +1100 Subject: [PATCH 37/78] Compass: fixed a comment --- libraries/AP_Compass/Compass.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Compass/Compass.h b/libraries/AP_Compass/Compass.h index 6fc9a937e9..ef555dda13 100644 --- a/libraries/AP_Compass/Compass.h +++ b/libraries/AP_Compass/Compass.h @@ -23,7 +23,7 @@ public: float heading; ///< compass heading in radians float heading_x; ///< compass vector X magnitude float heading_y; ///< compass vector Y magnitude - uint32_t last_update; ///< millis() time of last update + uint32_t last_update; ///< micros() time of last update bool healthy; ///< true if last read OK /// Constructor From b549b88e5e98e9d99af1730ae0447fc2ec3e9839 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 29 Mar 2012 08:57:53 +1100 Subject: [PATCH 38/78] AHRS: fixed error_yaw reporting with 2 MAVLink connections when a user first connects with USB, and later switches to the telemetry port without restarting we were getting zero for error_yaw in the logs, as AHRS.get_error_yaw() was being called twice. This ensures we give the last value after the counter is reset --- libraries/AP_AHRS/AP_AHRS_DCM.cpp | 18 ++++++++++-------- libraries/AP_AHRS/AP_AHRS_DCM.h | 2 ++ libraries/AP_AHRS/AP_AHRS_Quaternion.cpp | 24 ++++++++++++++---------- libraries/AP_AHRS/AP_AHRS_Quaternion.h | 2 ++ 4 files changed, 28 insertions(+), 18 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.cpp b/libraries/AP_AHRS/AP_AHRS_DCM.cpp index 323d1bb338..b6fa2e1f45 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.cpp +++ b/libraries/AP_AHRS/AP_AHRS_DCM.cpp @@ -495,25 +495,27 @@ AP_AHRS_DCM::euler_angles(void) // average error_roll_pitch since last call float AP_AHRS_DCM::get_error_rp(void) { - float ret; if (_error_rp_count == 0) { - return 0; + // this happens when telemetry is setup on two + // serial ports + return _error_rp_last; } - ret = _error_rp_sum / _error_rp_count; + _error_rp_last = _error_rp_sum / _error_rp_count; _error_rp_sum = 0; _error_rp_count = 0; - return ret; + return _error_rp_last; } // average error_yaw since last call float AP_AHRS_DCM::get_error_yaw(void) { - float ret; if (_error_yaw_count == 0) { - return 0; + // this happens when telemetry is setup on two + // serial ports + return _error_yaw_last; } - ret = _error_yaw_sum / _error_yaw_count; + _error_yaw_last = _error_yaw_sum / _error_yaw_count; _error_yaw_sum = 0; _error_yaw_count = 0; - return ret; + return _error_yaw_last; } diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.h b/libraries/AP_AHRS/AP_AHRS_DCM.h index ee5b3403ac..5952380c7e 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.h +++ b/libraries/AP_AHRS/AP_AHRS_DCM.h @@ -75,8 +75,10 @@ private: uint16_t _renorm_val_count; float _error_rp_sum; uint16_t _error_rp_count; + float _error_rp_last; float _error_yaw_sum; uint16_t _error_yaw_count; + float _error_yaw_last; // time in millis when we last got a GPS heading uint32_t _gps_last_update; diff --git a/libraries/AP_AHRS/AP_AHRS_Quaternion.cpp b/libraries/AP_AHRS/AP_AHRS_Quaternion.cpp index 03fe02869d..5148aa878f 100644 --- a/libraries/AP_AHRS/AP_AHRS_Quaternion.cpp +++ b/libraries/AP_AHRS/AP_AHRS_Quaternion.cpp @@ -383,30 +383,34 @@ void AP_AHRS_Quaternion::update(void) } -// average error in roll/pitch since last call +/* reporting of Quaternion state for MAVLink */ + +// average error_roll_pitch since last call float AP_AHRS_Quaternion::get_error_rp(void) { - float ret; if (_error_rp_count == 0) { - return 0; + // this happens when telemetry is setup on two + // serial ports + return _error_rp_last; } - ret = _error_rp_sum / _error_rp_count; + _error_rp_last = _error_rp_sum / _error_rp_count; _error_rp_sum = 0; _error_rp_count = 0; - return ret; + return _error_rp_last; } -// average error in yaw since last call +// average error_yaw since last call float AP_AHRS_Quaternion::get_error_yaw(void) { - float ret; if (_error_yaw_count == 0) { - return 0; + // this happens when telemetry is setup on two + // serial ports + return _error_yaw_last; } - ret = _error_yaw_sum / _error_yaw_count; + _error_yaw_last = _error_yaw_sum / _error_yaw_count; _error_yaw_sum = 0; _error_yaw_count = 0; - return ret; + return _error_yaw_last; } // reset attitude system diff --git a/libraries/AP_AHRS/AP_AHRS_Quaternion.h b/libraries/AP_AHRS/AP_AHRS_Quaternion.h index a5b6583903..91c41e2ea4 100644 --- a/libraries/AP_AHRS/AP_AHRS_Quaternion.h +++ b/libraries/AP_AHRS/AP_AHRS_Quaternion.h @@ -87,8 +87,10 @@ private: // estimate of error float _error_rp_sum; uint16_t _error_rp_count; + float _error_rp_last; float _error_yaw_sum; uint16_t _error_yaw_count; + float _error_yaw_last; }; #endif From 4c4c38f69a6e395b5aa21f40c87399913db185ca Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 29 Mar 2012 12:39:28 +1100 Subject: [PATCH 39/78] APM: Added MANUAL_LEVEL option when MANUAL_LEVEL is set to 1, we don't do accelerometer levelling at startup, and instead used the values saved in the EEPROM. This makes it easier to do levelling on the bench, or once for a series of flights for the day --- ArduPlane/GCS_Mavlink.pde | 4 ++-- ArduPlane/Parameters.h | 2 ++ ArduPlane/Parameters.pde | 1 + ArduPlane/system.pde | 11 ++++++++--- 4 files changed, 13 insertions(+), 5 deletions(-) diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index 60056b6fcc..2cede18da0 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -1083,7 +1083,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) if (packet.param1 == 1 || packet.param2 == 1 || packet.param3 == 1) { - startup_IMU_ground(); + startup_IMU_ground(true); } if (packet.param4 == 1) { trim_radio(); @@ -1188,7 +1188,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) case MAV_ACTION_CALIBRATE_ACC: case MAV_ACTION_CALIBRATE_PRESSURE: case MAV_ACTION_REBOOT: // this is a rough interpretation - startup_IMU_ground(); + startup_IMU_ground(true); result=1; break; diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h index f508e6c38d..5519f0cd22 100644 --- a/ArduPlane/Parameters.h +++ b/ArduPlane/Parameters.h @@ -49,6 +49,7 @@ public: k_param_num_resets, k_param_log_last_filenumber, // *** Deprecated - remove with next eeprom number change k_param_reset_switch_chan, + k_param_manual_level, // 110: Telemetry control @@ -300,6 +301,7 @@ public: AP_Int16 log_bitmask; AP_Int16 log_last_filenumber; // *** Deprecated - remove with next eeprom number change AP_Int8 reset_switch_chan; + AP_Int8 manual_level; AP_Int16 airspeed_cruise; AP_Int16 min_gndspeed; AP_Int16 pitch_trim; diff --git a/ArduPlane/Parameters.pde b/ArduPlane/Parameters.pde index 4b0bda9ae0..3619095c05 100644 --- a/ArduPlane/Parameters.pde +++ b/ArduPlane/Parameters.pde @@ -23,6 +23,7 @@ static const AP_Param::Info var_info[] PROGMEM = { GSCALAR(kff_rudder_mix, "KFF_RDDRMIX"), GSCALAR(kff_pitch_to_throttle, "KFF_PTCH2THR"), GSCALAR(kff_throttle_to_pitch, "KFF_THR2PTCH"), + GSCALAR(manual_level, "MANUAL_LEVEL"), GSCALAR(crosstrack_gain, "XTRK_GAIN_SC"), GSCALAR(crosstrack_entry_angle, "XTRK_ANGLE_CD"), diff --git a/ArduPlane/system.pde b/ArduPlane/system.pde index 0dc50c54d9..72584598fa 100644 --- a/ArduPlane/system.pde +++ b/ArduPlane/system.pde @@ -318,7 +318,7 @@ static void startup_ground(void) //IMU ground start //------------------------ // - startup_IMU_ground(); + startup_IMU_ground(false); // read the radio to set trims // --------------------------- @@ -441,7 +441,7 @@ static void check_short_failsafe() } -static void startup_IMU_ground(void) +static void startup_IMU_ground(bool force_accel_level) { #if HIL_MODE != HIL_MODE_ATTITUDE gcs_send_text_P(SEVERITY_MEDIUM, PSTR("Warming up ADC...")); @@ -454,7 +454,12 @@ static void startup_IMU_ground(void) mavlink_delay(1000); imu.init(IMU::COLD_START, mavlink_delay, flash_leds, &timer_scheduler); - imu.init_accel(mavlink_delay, flash_leds); + if (force_accel_level || g.manual_level == 0) { + // when MANUAL_LEVEL is set to 1 we don't do accelerometer + // levelling on each boot, and instead rely on the user to do + // it once via the ground station + imu.init_accel(mavlink_delay, flash_leds); + } ahrs.set_centripetal(1); ahrs.reset(); From 9d193f06c9a4d3de04c486b9fc7e3268e7638504 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 29 Mar 2012 12:40:28 +1100 Subject: [PATCH 40/78] APM: Change version to 2.32 --- ArduPlane/ArduPlane.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde index 77ce236731..dd5f0fbaea 100644 --- a/ArduPlane/ArduPlane.pde +++ b/ArduPlane/ArduPlane.pde @@ -1,6 +1,6 @@ /// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- -#define THISFIRMWARE "ArduPlane V2.31" +#define THISFIRMWARE "ArduPlane V2.32" /* Authors: Doug Weibel, Jose Julio, Jordi Munoz, Jason Short, Andrew Tridgell, Randy Mackay, Pat Hickey, John Arne Birkeland, Olivier Adler Thanks to: Chris Anderson, Michael Oborne, Paul Mather, Bill Premerlani, James Cohen, JB from rotorFX, Automatik, Fefenin, Peter Meister, Remzibi, Yury Smirnov, Sandro Benigno, Max Levine, Roberto Navoni, Lorenz Meier From c1eede5ef31c8475f0682026127a132519dd3d05 Mon Sep 17 00:00:00 2001 From: Michael Oborne Date: Thu, 29 Mar 2012 09:53:56 +0800 Subject: [PATCH 41/78] firmware build --- Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml b/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml index 3ba0affdfc..7b8433162d 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml +++ b/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml @@ -4,7 +4,7 @@ http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-1280.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-2560.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-2560-2.hex - ArduPlane V2.31 + ArduPlane V2.32 12 @@ -12,7 +12,7 @@ http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/APHIL-1280.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/APHIL-2560.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/APHIL-2560-2.hex - ArduPlane V2.31 HIL + ArduPlane V2.32 HIL #define FLIGHT_MODE_CHANNEL 8 #define FLIGHT_MODE_1 AUTO From 0efb0e5b4d39309a4cd4d684691ac7698086c8ec Mon Sep 17 00:00:00 2001 From: rmackay9 Date: Thu, 29 Mar 2012 21:09:41 +0900 Subject: [PATCH 42/78] ArduCopter - added CH6_STABILIZE_KD tuning value --- ArduCopter/ArduCopter.pde | 4 ++++ ArduCopter/defines.h | 1 + 2 files changed, 5 insertions(+) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index debd62fad3..b0fc2449cf 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -2044,6 +2044,10 @@ static void tuning(){ g.pi_stabilize_pitch.kI(tuning_value); break; + case CH6_STABILIZE_KD: + g.stabilize_d = tuning_value; + break; + case CH6_ACRO_KP: g.acro_p = tuning_value; break; diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index 8066f79d6f..9f446232d3 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -141,6 +141,7 @@ // Attitude #define CH6_STABILIZE_KP 1 #define CH6_STABILIZE_KI 2 +#define CH6_STABILIZE_KD 29 #define CH6_YAW_KP 3 #define CH6_YAW_KI 24 // Rate From cc047f29445363ab2793bf400a0baef0a8fd3ad3 Mon Sep 17 00:00:00 2001 From: Michael Oborne Date: Fri, 30 Mar 2012 06:17:06 +0800 Subject: [PATCH 43/78] APM Planner 1.1.59 fix possible issue loading stream rates fix tracker ranges add more ch6 options modify mag calib with throttle --- Tools/ArdupilotMegaPlanner/Antenna/Maestro.cs | 4 +- Tools/ArdupilotMegaPlanner/Antenna/Tracker.cs | 4 +- .../ArdupilotMegaPlanner/ArdupilotMega.csproj | 114 + Tools/ArdupilotMegaPlanner/Common.cs | 7 +- .../BackstageView/BackStageViewMenuPanel.cs | 33 + .../BackstageView/BackstageView.Designer.cs | 73 + .../Controls/BackstageView/BackstageView.cs | 225 ++ .../Controls/BackstageView/BackstageView.resx | 120 + .../BackstageView/BackstageViewButton.cs | 150 ++ .../ArdupilotMegaPlanner/GCSViews/Terminal.cs | 6 +- Tools/ArdupilotMegaPlanner/MAVLink.cs | 2 + Tools/ArdupilotMegaPlanner/MagCalib.cs | 26 +- Tools/ArdupilotMegaPlanner/MainV2.cs | 10 +- Tools/ArdupilotMegaPlanner/MavlinkLog.cs | 37 +- .../Properties/AssemblyInfo.cs | 2 +- .../Setup/Setup.Designer.cs | 62 +- Tools/ArdupilotMegaPlanner/Setup/Setup.cs | 45 +- Tools/ArdupilotMegaPlanner/Setup/Setup.resx | 2377 ++++++++++++++--- Tools/ArdupilotMegaPlanner/ThemeManager.cs | 13 + .../bin/Release/ArdupilotMegaPlanner.pdb | Bin 1025536 -> 1154560 bytes 20 files changed, 2962 insertions(+), 348 deletions(-) create mode 100644 Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackStageViewMenuPanel.cs create mode 100644 Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageView.Designer.cs create mode 100644 Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageView.cs create mode 100644 Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageView.resx create mode 100644 Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageViewButton.cs diff --git a/Tools/ArdupilotMegaPlanner/Antenna/Maestro.cs b/Tools/ArdupilotMegaPlanner/Antenna/Maestro.cs index 26c73d8adf..f77df09450 100644 --- a/Tools/ArdupilotMegaPlanner/Antenna/Maestro.cs +++ b/Tools/ArdupilotMegaPlanner/Antenna/Maestro.cs @@ -96,7 +96,7 @@ namespace ArdupilotMega.Antenna } public bool Pan(double Angle) - { + { double range = Math.Abs(PanStartRange - PanEndRange); // get relative center based on tracking center @@ -110,7 +110,7 @@ namespace ArdupilotMega.Antenna // conver the angle into a 0-255 value byte target = (byte)((((PointAtAngle / range) * 2.0) * 127 + centerpos) * _panreverse); - //Console.WriteLine("P " + Angle + " " + target + " " + PointAtAngle); + Console.WriteLine("P " + Angle + " " + target + " " + PointAtAngle); var buffer = new byte[] { 0xff,PanAddress,target}; ComPort.Write(buffer, 0, buffer.Length); diff --git a/Tools/ArdupilotMegaPlanner/Antenna/Tracker.cs b/Tools/ArdupilotMegaPlanner/Antenna/Tracker.cs index c51678b57b..53bad8d3bb 100644 --- a/Tools/ArdupilotMegaPlanner/Antenna/Tracker.cs +++ b/Tools/ArdupilotMegaPlanner/Antenna/Tracker.cs @@ -120,8 +120,8 @@ namespace ArdupilotMega.Antenna try { - tracker.PanStartRange = int.Parse(TXT_panrange.Text) / 1 * -1; - tracker.PanEndRange = int.Parse(TXT_panrange.Text) / 1; + tracker.PanStartRange = int.Parse(TXT_panrange.Text) / 2 * -1; + tracker.PanEndRange = int.Parse(TXT_panrange.Text) / 2; tracker.TrimPan = TRK_pantrim.Value; tracker.TiltStartRange = int.Parse(TXT_tiltrange.Text) / 2 * -1; diff --git a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj index 7dc0487396..bd24ec4529 100644 --- a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj +++ b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj @@ -223,6 +223,18 @@ Tracker.cs + + UserControl + + + BackstageView.cs + + + Component + + + Component + Form @@ -230,6 +242,72 @@ ProgressReporterDialogue.cs + + UserControl + + + ConfigAccelerometerCalibration.cs + + + UserControl + + + ConfigArducopter.cs + + + UserControl + + + ConfigArduplane.cs + + + UserControl + + + ConfigBatteryMonitoring.cs + + + UserControl + + + ConfigFlightModes.cs + + + UserControl + + + ConfigHardwareOptions.cs + + + UserControl + + + ConfigPlanner.cs + + + UserControl + + + ConfigRadioInput.cs + + + UserControl + + + ConfigTradHeli.cs + + + UserControl + + + Configuration.cs + + + UserControl + + + ConfigRawParams.cs + @@ -452,9 +530,45 @@ Tracker.cs + + BackstageView.cs + ProgressReporterDialogue.cs + + ConfigAccelerometerCalibration.cs + + + ConfigArducopter.cs + + + ConfigArduplane.cs + + + ConfigBatteryMonitoring.cs + + + ConfigFlightModes.cs + + + ConfigHardwareOptions.cs + + + ConfigPlanner.cs + + + ConfigRadioInput.cs + + + ConfigRawParams.cs + + + ConfigTradHeli.cs + + + Configuration.cs + 3DRradio.cs diff --git a/Tools/ArdupilotMegaPlanner/Common.cs b/Tools/ArdupilotMegaPlanner/Common.cs index bb5aecd2d0..826ae2117d 100644 --- a/Tools/ArdupilotMegaPlanner/Common.cs +++ b/Tools/ArdupilotMegaPlanner/Common.cs @@ -381,7 +381,12 @@ namespace ArdupilotMega CH6_NAV_I = 20, CH6_LOITER_RATE_P = 22, - CH6_LOITER_RATE_D = 23 + CH6_LOITER_RATE_D = 23, + CH6_YAW_KI = 24, + CH6_ACRO_KP = 25, + CH6_YAW_RATE_KD = 26, + CH6_LOITER_KI = 27, + CH6_LOITER_RATE_KI = 28 } diff --git a/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackStageViewMenuPanel.cs b/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackStageViewMenuPanel.cs new file mode 100644 index 0000000000..1a9ba58375 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackStageViewMenuPanel.cs @@ -0,0 +1,33 @@ +using System.Drawing; +using System.Drawing.Drawing2D; +using System.Windows.Forms; + +namespace ArdupilotMega.Controls.BackstageView +{ + public class BackStageViewMenuPanel : Panel + { + internal Color GradColor = Color.White; + internal Color PencilBorderColor = Color.White; + + private const int GradientWidth = 6; + + public BackStageViewMenuPanel() + { + this.SetStyle(ControlStyles.UserPaint, true); + } + + protected override void OnPaintBackground(PaintEventArgs pevent) + { + base.OnPaintBackground(pevent); + + var rc = new Rectangle(ClientSize.Width - GradientWidth, 0, GradientWidth, this.ClientSize.Height); + + using (var brush = new LinearGradientBrush(rc, BackColor, GradColor, LinearGradientMode.Horizontal)) + { + pevent.Graphics.FillRectangle(brush, rc); + } + + pevent.Graphics.DrawLine(new Pen(PencilBorderColor), Width-1,0,Width-1,Height); + } + } +} \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageView.Designer.cs b/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageView.Designer.cs new file mode 100644 index 0000000000..07546e1ac8 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageView.Designer.cs @@ -0,0 +1,73 @@ +namespace ArdupilotMega.Controls.BackstageView +{ + partial class BackstageView + { + ///

+ /// Required designer variable. + /// + private System.ComponentModel.IContainer components = null; + + /// + /// Clean up any resources being used. + /// + /// true if managed resources should be disposed; otherwise, false. + protected override void Dispose(bool disposing) + { + if (disposing && (components != null)) + { + components.Dispose(); + } + base.Dispose(disposing); + } + + #region Component Designer generated code + + /// + /// Required method for Designer support - do not modify + /// the contents of this method with the code editor. + /// + private void InitializeComponent() + { + this.pnlPages = new System.Windows.Forms.Panel(); + this.pnlMenu = new BackStageViewMenuPanel(); + this.SuspendLayout(); + // + // pnlPages + // + this.pnlPages.Anchor = ((System.Windows.Forms.AnchorStyles)((((System.Windows.Forms.AnchorStyles.Top | System.Windows.Forms.AnchorStyles.Bottom) + | System.Windows.Forms.AnchorStyles.Left) + | System.Windows.Forms.AnchorStyles.Right))); + this.pnlPages.Location = new System.Drawing.Point(147, 0); + this.pnlPages.MinimumSize = new System.Drawing.Size(100, 0); + this.pnlPages.Name = "pnlPages"; + this.pnlPages.Size = new System.Drawing.Size(243, 189); + this.pnlPages.TabIndex = 0; + // + // pnlMenu + // + this.pnlMenu.Anchor = ((System.Windows.Forms.AnchorStyles)(((System.Windows.Forms.AnchorStyles.Top | System.Windows.Forms.AnchorStyles.Bottom) + | System.Windows.Forms.AnchorStyles.Left))); + this.pnlMenu.Location = new System.Drawing.Point(0, 0); + this.pnlMenu.Name = "pnlMenu"; + this.pnlMenu.Size = new System.Drawing.Size(150, 170); + this.pnlMenu.TabIndex = 1; + // + // BackstageView + // + this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F); + this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font; + this.AutoSize = true; + this.Controls.Add(this.pnlMenu); + this.Controls.Add(this.pnlPages); + this.Name = "BackstageView"; + this.Size = new System.Drawing.Size(393, 192); + this.ResumeLayout(false); + + } + + #endregion + + private System.Windows.Forms.Panel pnlPages; + private BackStageViewMenuPanel pnlMenu; + } +} diff --git a/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageView.cs b/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageView.cs new file mode 100644 index 0000000000..2970e499b6 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageView.cs @@ -0,0 +1,225 @@ +using System; +using System.Collections.Generic; +using System.ComponentModel; +using System.Drawing; +using System.Linq; +using System.Windows.Forms; +using ArdupilotMega.Controls.BackstageView; + +namespace ArdupilotMega.Controls.BackstageView +{ + public partial class BackstageView : UserControl + { + private Color _buttonsAreaBgColor = Color.White; + private Color _buttonsAreaPencilColor = Color.DarkGray; + private Color _selectedTextColor = Color.White; + private Color _unSelectedTextColor = Color.Gray; + private Color _highlightColor1 = Color.DarkBlue; + private Color _highlightColor2 = Color.Blue; + + private readonly List _pages= new List(); + private BackstageViewPage _activePage; + private const int ButtonSpacing = 30; + private const int ButtonHeight = 30; + + public BackstageView() + { + InitializeComponent(); + + this.pnlMenu.Height = this.Height; + this.pnlPages.Height = this.Height; + + pnlMenu.BackColor = _buttonsAreaBgColor; + pnlMenu.PencilBorderColor = _buttonsAreaPencilColor; + pnlMenu.GradColor = this.BackColor; + } + + + public override Color BackColor + { + get + { + return base.BackColor; + } + set + { + base.BackColor = value; + UpdateButtons(); + pnlMenu.GradColor = this.BackColor; + } + } + + [Description("Background pencil line color for the content region"), Category("Appearance")] + [DefaultValue(typeof(Color),"DarkGray")] + public Color ButtonsAreaPencilColor + { + get { return _buttonsAreaPencilColor; } + set + { + _buttonsAreaPencilColor = value; + pnlMenu.PencilBorderColor = _buttonsAreaPencilColor; + pnlMenu.Invalidate(); + UpdateButtons(); + Invalidate(); + } + } + + + [Description("Background color for the buttons region"), Category("Appearance")] + [DefaultValue(typeof(Color),"White")] + public Color ButtonsAreaBgColor + { + get { return _buttonsAreaBgColor; } + set + { + _buttonsAreaBgColor = value; + this.pnlMenu.BackColor = _buttonsAreaBgColor; + pnlMenu.Invalidate(); + Invalidate(); + } + } + + [Description("Color for the selector buttons text"), Category("Appearance")] + [DefaultValue(typeof(Color), "White")] + public Color SelectedTextColor + { + get { return _selectedTextColor; } + set + { + _selectedTextColor = value; + UpdateButtons(); + } + } + + [Description("Color for the un selected selector buttons text"), Category("Appearance")] + [DefaultValue(typeof(Color), "Gray")] + public Color UnSelectedTextColor + { + get { return _unSelectedTextColor; } + set + { + _unSelectedTextColor = value; + UpdateButtons(); + Invalidate(); + } + } + + [Description("Color selected button background 1"), Category("Appearance")] + [DefaultValue(typeof(Color), "DarkBlue")] + public Color HighlightColor1 + { + get { return _highlightColor1; } + set + { + _highlightColor1 = value; + UpdateButtons(); + Invalidate(); + } + } + + [Description("Color selected button background 2"), Category("Appearance")] + [DefaultValue(typeof(Color), "Blue")] + public Color HighlightColor2 + { + get { return _highlightColor2; } + set + { + _highlightColor2 = value; + UpdateButtons(); + Invalidate(); + } + } + + + private void UpdateButtons() + { + foreach (var backstageViewButton in pnlMenu.Controls.OfType()) + { + backstageViewButton.HighlightColor2 = _highlightColor2; + backstageViewButton.HighlightColor1 = _highlightColor1; + backstageViewButton.UnSelectedTextColor = _unSelectedTextColor; + backstageViewButton.SelectedTextColor = _selectedTextColor; + backstageViewButton.ContentPageColor = this.BackColor; + backstageViewButton.PencilBorderColor = _buttonsAreaPencilColor; + + backstageViewButton.Invalidate(); + } + } + + public void AddPage(BackstageViewPage page) + { + page.Page.Anchor = AnchorStyles.Bottom | AnchorStyles.Left | AnchorStyles.Right | AnchorStyles.Top; + page.Page.Location = new Point(pnlMenu.Width, 0); + page.Page.Dock = DockStyle.Fill; + + _pages.Add(page); + CreateLinkButton(page); + this.pnlPages.Controls.Add(page.Page); + + if (_activePage == null) + _activePage = page; + + ActivatePage(page); + // Todo: set the link button to be selected looking + } + + private void CreateLinkButton(BackstageViewPage page) + { + var lnkButton = new BackstageViewButton + { + Text = page.LinkText, + Tag = page, + Top = _pages.IndexOf(page) * ButtonSpacing, + Width = this.pnlMenu.Width, + Height = ButtonHeight, + ContentPageColor = this.BackColor, + PencilBorderColor = _buttonsAreaPencilColor, + SelectedTextColor = _selectedTextColor, + UnSelectedTextColor = _unSelectedTextColor, + HighlightColor1 = _highlightColor1, + HighlightColor2 = _highlightColor2 + }; + + pnlMenu.Controls.Add(lnkButton); + lnkButton.Click += this.ButtonClick; + } + + + private void ButtonClick(object sender, EventArgs e) + { + var backstageViewButton = ((BackstageViewButton) sender); + var associatedPage = backstageViewButton.Tag as BackstageViewPage; + this.ActivatePage(associatedPage); + } + + private void ActivatePage(BackstageViewPage associatedPage) + { + // deactivate the old page + _activePage.Page.Visible = false; + var oldButton = this.pnlMenu.Controls.OfType().Single(b => b.Tag == _activePage); + oldButton.IsSelected = false; + + associatedPage.Page.Visible = true; + var newButton = this.pnlMenu.Controls.OfType().Single(b => b.Tag == associatedPage); + newButton.IsSelected = true; + + _activePage = associatedPage; + } + + + public class BackstageViewPage + { + public BackstageViewPage(Control page, string linkText) + { + Page = page; + LinkText = linkText; + } + + public Control Page { get; private set; } + public string LinkText { get; set; } + } + } + + + +} diff --git a/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageView.resx b/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageView.resx new file mode 100644 index 0000000000..7080a7d118 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageView.resx @@ -0,0 +1,120 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + text/microsoft-resx + + + 2.0 + + + System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageViewButton.cs b/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageViewButton.cs new file mode 100644 index 0000000000..7f384a5bcd --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageViewButton.cs @@ -0,0 +1,150 @@ +using System; +using System.Drawing; +using System.Drawing.Drawing2D; +using System.Windows.Forms; + +namespace ArdupilotMega.Controls.BackstageView +{ + public class BackstageViewButton : Control + { + private bool _isSelected; + + internal Color ContentPageColor = Color.Gray; + internal Color PencilBorderColor = Color.White; + internal Color SelectedTextColor = Color.White; + internal Color UnSelectedTextColor = Color.Gray; + internal Color HighlightColor1 = Color.DarkBlue; + internal Color HighlightColor2 = Color.Blue; + private bool _isMouseOver; + + //internal Color HighlightColor1 = Color.FromArgb(0x94, 0xc1, 0x1f); + //internal Color HighlightColor2 = Color.FromArgb(0xcd, 0xe2, 0x96); + + public BackstageViewButton() + { + SetStyle(ControlStyles.SupportsTransparentBackColor, true); + SetStyle(ControlStyles.Opaque, true); + SetStyle(ControlStyles.ResizeRedraw, true); + this.BackColor = Color.Transparent; + } + + /// + /// Whether this button should show the selected style + /// + public bool IsSelected + { + get { return _isSelected; } + set + { + if (_isSelected != value) + { + _isSelected = value; + //this.Parent.Refresh(); // <-- brutal, but works + + + InvalidateParentForBackground(); + + this.Invalidate(); + } + } + } + + // Must be a better way to redraw parent control in the area of + // the button + private void InvalidateParentForBackground() + { + var screenrect = this.RectangleToScreen(this.ClientRectangle); + var rectangleToClient = this.Parent.RectangleToClient(screenrect); + this.Parent.Invalidate(rectangleToClient); + } + + + protected override void OnPaint(PaintEventArgs pevent) + { + Graphics g = pevent.Graphics; + + + // Now the little 'arrow' thingy if we are selected and the selected bg grad + if (_isSelected) + { + var rect1 = new Rectangle(0, 0, Width / 2, Height); + var rect2 = new Rectangle(Width / 2, 0, Width, Height); + + g.FillRectangle(new LinearGradientBrush(rect1, HighlightColor1, HighlightColor2, LinearGradientMode.Horizontal), rect1); + g.FillRectangle(new LinearGradientBrush(rect2, HighlightColor2, HighlightColor1, LinearGradientMode.Horizontal), rect2); + + var butPen = new Pen(HighlightColor1); + g.DrawLine(butPen, 0, 0, Width, 0); + g.DrawLine(butPen, 0, Height - 1, Width, Height - 1); + + var arrowBrush = new SolidBrush(this.ContentPageColor); + + var midheight = Height / 2; + var arSize = 8; + + var arrowPoints = new[] + { + new Point(Width, midheight + arSize), + new Point(Width - arSize, midheight), + new Point(Width, midheight - arSize) + }; + + g.DrawString(Text, new Font(FontFamily.GenericSansSerif, 10), new SolidBrush(SelectedTextColor), 20, 6); + + g.FillPolygon(arrowBrush, arrowPoints); + + var pencilBrush = new Pen(this.PencilBorderColor); + + + g.DrawPolygon(pencilBrush, arrowPoints); + + + } + else + { + if (_isMouseOver) + { + var brush = new SolidBrush(Color.FromArgb(10, 0xA0, 0xA0, 0xA0)); + + g.FillRectangle(brush, this.ClientRectangle); + + var butPen = new Pen(PencilBorderColor); + g.DrawLine(butPen, 0, 0, Width, 0); + g.DrawLine(butPen, 0, Height - 1, Width, Height - 1); + } + + g.DrawString(Text, new Font(FontFamily.GenericSansSerif, 10), new SolidBrush(this.UnSelectedTextColor), 20, 6); + } + } + + + protected override void OnMouseEnter(EventArgs e) + { + _isMouseOver = true; + base.OnMouseEnter(e); + InvalidateParentForBackground(); + this.Invalidate(); + } + + protected override void OnMouseLeave(EventArgs e) + { + _isMouseOver = false; + base.OnMouseLeave(e); + InvalidateParentForBackground(); + this.Invalidate(); + + } + + // This IS necessary for transparency + protected override CreateParams CreateParams + { + get + { + const int WS_EX_TRANSPARENT = 0x20; + CreateParams cp = base.CreateParams; + cp.ExStyle |= WS_EX_TRANSPARENT; + return cp; + } + } + } +} \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.cs index b11ff009d1..2c4897acef 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.cs @@ -201,9 +201,11 @@ namespace ArdupilotMega.GCSViews } catch { return; } } - + try + { comPort.Write("\n\n\n"); - + } + catch { return; } while (threadrun) { try diff --git a/Tools/ArdupilotMegaPlanner/MAVLink.cs b/Tools/ArdupilotMegaPlanner/MAVLink.cs index 15570796cc..8299c9e585 100644 --- a/Tools/ArdupilotMegaPlanner/MAVLink.cs +++ b/Tools/ArdupilotMegaPlanner/MAVLink.cs @@ -1162,6 +1162,8 @@ namespace ArdupilotMega req.start_stop = 1; // start req.req_stream_id = id; // id + // send each one twice. + generatePacket(MAVLINK_MSG_ID_REQUEST_DATA_STREAM, req); generatePacket(MAVLINK_MSG_ID_REQUEST_DATA_STREAM, req); } diff --git a/Tools/ArdupilotMegaPlanner/MagCalib.cs b/Tools/ArdupilotMegaPlanner/MagCalib.cs index 8e88536308..e94a639932 100644 --- a/Tools/ArdupilotMegaPlanner/MagCalib.cs +++ b/Tools/ArdupilotMegaPlanner/MagCalib.cs @@ -21,7 +21,7 @@ namespace ArdupilotMega /// /// Self contained process tlog and save/display offsets /// - public static void ProcessLog() + public static void ProcessLog(int throttleThreshold = 0) { OpenFileDialog openFileDialog1 = new OpenFileDialog(); openFileDialog1.Filter = "*.tlog|*.tlog"; @@ -40,7 +40,7 @@ namespace ArdupilotMega { try { - double[] ans = getOffsets(openFileDialog1.FileName); + double[] ans = getOffsets(openFileDialog1.FileName, throttleThreshold); SaveOffsets(ans); } @@ -53,9 +53,9 @@ namespace ArdupilotMega /// /// Filename /// Offsets - public static double[] getOffsets(string fn) + public static double[] getOffsets(string fn, int throttleThreshold = 0) { - // based of tridge's work + // based off tridge's work string logfile = fn; // old method @@ -76,6 +76,9 @@ namespace ArdupilotMega Hashtable filter = new Hashtable(); + // track data to use + bool useData = false; + log.Info("Start log: " + DateTime.Now); MAVLink mine = new MAVLink(); @@ -95,6 +98,19 @@ namespace ArdupilotMega if (packet == null) continue; + if (packet.GetType() == typeof(MAVLink.__mavlink_vfr_hud_t)) + { + if (((MAVLink.__mavlink_vfr_hud_t)packet).throttle >= throttleThreshold) + { + useData = true; + } + else + { + useData = false; + } + + } + if (packet.GetType() == typeof(MAVLink.__mavlink_sensor_offsets_t)) { offset = new Tuple( @@ -102,7 +118,7 @@ namespace ArdupilotMega ((MAVLink.__mavlink_sensor_offsets_t)packet).mag_ofs_y, ((MAVLink.__mavlink_sensor_offsets_t)packet).mag_ofs_z); } - else if (packet.GetType() == typeof(MAVLink.__mavlink_raw_imu_t)) + else if (packet.GetType() == typeof(MAVLink.__mavlink_raw_imu_t) && useData) { int div = 20; diff --git a/Tools/ArdupilotMegaPlanner/MainV2.cs b/Tools/ArdupilotMegaPlanner/MainV2.cs index 4d70c588eb..ecf883be85 100644 --- a/Tools/ArdupilotMegaPlanner/MainV2.cs +++ b/Tools/ArdupilotMegaPlanner/MainV2.cs @@ -72,6 +72,7 @@ namespace ArdupilotMega GCSViews.FlightData FlightData; GCSViews.FlightPlanner FlightPlanner; GCSViews.Configuration Configuration; + //GCSViews.ConfigurationView.Configuration Configuration; GCSViews.Simulation Simulation; GCSViews.Firmware Firmware; GCSViews.Terminal Terminal; @@ -188,14 +189,14 @@ namespace ArdupilotMega if (config["CMB_rateattitude"] != null) MainV2.cs.rateattitude = byte.Parse(config["CMB_rateattitude"].ToString()); - if (config["CMB_rateattitude"] != null) + if (config["rateposition"] != null) MainV2.cs.rateposition = byte.Parse(config["CMB_rateposition"].ToString()); - if (config["CMB_rateattitude"] != null) + if (config["CMB_ratestatus"] != null) MainV2.cs.ratestatus = byte.Parse(config["CMB_ratestatus"].ToString()); - if (config["CMB_rateattitude"] != null) + if (config["CMB_raterc"] != null) MainV2.cs.raterc = byte.Parse(config["CMB_raterc"].ToString()); if (config["CMB_ratesensors"] != null) - MainV2.cs.raterc = byte.Parse(config["CMB_ratesensors"].ToString()); + MainV2.cs.ratesensors = byte.Parse(config["CMB_ratesensors"].ToString()); if (config["speechenable"] != null) MainV2.speechEnable = bool.Parse(config["speechenable"].ToString()); @@ -339,6 +340,7 @@ namespace ArdupilotMega } Configuration = new GCSViews.Configuration(); + //Configuration = new GCSViews.ConfigurationView.Configuration(); UserControl temp = Configuration; diff --git a/Tools/ArdupilotMegaPlanner/MavlinkLog.cs b/Tools/ArdupilotMegaPlanner/MavlinkLog.cs index 14543ae9fd..73f5cfac07 100644 --- a/Tools/ArdupilotMegaPlanner/MavlinkLog.cs +++ b/Tools/ArdupilotMegaPlanner/MavlinkLog.cs @@ -853,6 +853,14 @@ namespace ArdupilotMega MavlinkInterface.logplaybackfile.Close(); MavlinkInterface.logplaybackfile = null; + try + { + + addMagField(ref options); + + } + catch (Exception ex) { log.Info(ex.ToString()); } + // custom sort based on packet name //options.Sort(delegate(string c1, string c2) { return String.Compare(c1.Substring(0,c1.IndexOf('.')),c2.Substring(0,c2.IndexOf('.')));}); @@ -872,6 +880,33 @@ namespace ArdupilotMega return selection; } + void addMagField(ref List options) + { + string field = "mag_field Custom"; + + options.Add("Custom.mag_field"); + + this.data[field] = new PointPairList(); + + PointPairList list = ((PointPairList)this.data[field]); + + PointPairList listx = ((PointPairList)this.data["xmag __mavlink_raw_imu_t"]); + PointPairList listy = ((PointPairList)this.data["ymag __mavlink_raw_imu_t"]); + PointPairList listz = ((PointPairList)this.data["zmag __mavlink_raw_imu_t"]); + + //(float)Math.Sqrt(Math.Pow(mx, 2) + Math.Pow(my, 2) + Math.Pow(mz, 2)); + + for (int a = 0; a < listx.Count; a++) + { + + double ans = Math.Sqrt(Math.Pow(listx[a].Y, 2) + Math.Pow(listy[a].Y, 2) + Math.Pow(listz[a].Y, 2)); + + //Console.WriteLine("{0} {1} {2} {3}", ans, listx[a].Y, listy[a].Y, listz[a].Y); + + list.Add(listx[a].X, ans); + } + } + private void AddDataOption(Form selectform, string Name) { @@ -947,7 +982,7 @@ namespace ArdupilotMega selection.Remove(((CheckBox)sender).Name); foreach (var item in zg1.GraphPane.CurveList) { - if (item.Tag == ((CheckBox)sender).Name) + if (item.Tag.ToString() == ((CheckBox)sender).Name) { zg1.GraphPane.CurveList.Remove(item); break; diff --git a/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs b/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs index eb9a933587..f695ace3a6 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.58")] +[assembly: AssemblyFileVersion("1.1.59")] [assembly: NeutralResourcesLanguageAttribute("")] diff --git a/Tools/ArdupilotMegaPlanner/Setup/Setup.Designer.cs b/Tools/ArdupilotMegaPlanner/Setup/Setup.Designer.cs index d4389f234d..0adca95f80 100644 --- a/Tools/ArdupilotMegaPlanner/Setup/Setup.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/Setup/Setup.Designer.cs @@ -30,7 +30,7 @@ { this.components = new System.ComponentModel.Container(); System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(Setup)); - this.tabControl1 = new System.Windows.Forms.TabControl(); + this.Tabs = new System.Windows.Forms.TabControl(); this.tabRadioIn = new System.Windows.Forms.TabPage(); this.groupBoxElevons = new System.Windows.Forms.GroupBox(); this.CHK_mixmode = new System.Windows.Forms.CheckBox(); @@ -116,6 +116,9 @@ this.TXT_battcapacity = new System.Windows.Forms.TextBox(); this.CMB_batmontype = new System.Windows.Forms.ComboBox(); this.pictureBox5 = new System.Windows.Forms.PictureBox(); + this.tabArduplane = new System.Windows.Forms.TabPage(); + this.label48 = new System.Windows.Forms.Label(); + this.BUT_levelplane = new ArdupilotMega.MyButton(); this.tabArducopter = new System.Windows.Forms.TabPage(); this.label28 = new System.Windows.Forms.Label(); this.label16 = new System.Windows.Forms.Label(); @@ -180,7 +183,7 @@ this.tabReset = new System.Windows.Forms.TabPage(); this.BUT_reset = new ArdupilotMega.MyButton(); this.toolTip1 = new System.Windows.Forms.ToolTip(this.components); - this.tabControl1.SuspendLayout(); + this.Tabs.SuspendLayout(); this.tabRadioIn.SuspendLayout(); this.groupBoxElevons.SuspendLayout(); ((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).BeginInit(); @@ -193,6 +196,7 @@ this.tabBattery.SuspendLayout(); this.groupBox4.SuspendLayout(); ((System.ComponentModel.ISupportInitialize)(this.pictureBox5)).BeginInit(); + this.tabArduplane.SuspendLayout(); this.tabArducopter.SuspendLayout(); ((System.ComponentModel.ISupportInitialize)(this.pictureBoxQuadX)).BeginInit(); ((System.ComponentModel.ISupportInitialize)(this.pictureBoxQuad)).BeginInit(); @@ -208,18 +212,19 @@ this.tabReset.SuspendLayout(); this.SuspendLayout(); // - // tabControl1 + // Tabs // - this.tabControl1.Controls.Add(this.tabRadioIn); - this.tabControl1.Controls.Add(this.tabModes); - this.tabControl1.Controls.Add(this.tabHardware); - this.tabControl1.Controls.Add(this.tabBattery); - this.tabControl1.Controls.Add(this.tabArducopter); - this.tabControl1.Controls.Add(this.tabHeli); - resources.ApplyResources(this.tabControl1, "tabControl1"); - this.tabControl1.Name = "tabControl1"; - this.tabControl1.SelectedIndex = 0; - this.tabControl1.SelectedIndexChanged += new System.EventHandler(this.tabControl1_SelectedIndexChanged); + this.Tabs.Controls.Add(this.tabRadioIn); + this.Tabs.Controls.Add(this.tabModes); + this.Tabs.Controls.Add(this.tabHardware); + this.Tabs.Controls.Add(this.tabBattery); + this.Tabs.Controls.Add(this.tabArduplane); + this.Tabs.Controls.Add(this.tabArducopter); + this.Tabs.Controls.Add(this.tabHeli); + resources.ApplyResources(this.Tabs, "Tabs"); + this.Tabs.Name = "Tabs"; + this.Tabs.SelectedIndex = 0; + this.Tabs.SelectedIndexChanged += new System.EventHandler(this.tabControl1_SelectedIndexChanged); // // tabRadioIn // @@ -931,6 +936,26 @@ this.pictureBox5.Name = "pictureBox5"; this.pictureBox5.TabStop = false; // + // tabArduplane + // + this.tabArduplane.Controls.Add(this.label48); + this.tabArduplane.Controls.Add(this.BUT_levelplane); + resources.ApplyResources(this.tabArduplane, "tabArduplane"); + this.tabArduplane.Name = "tabArduplane"; + this.tabArduplane.UseVisualStyleBackColor = true; + // + // label48 + // + resources.ApplyResources(this.label48, "label48"); + this.label48.Name = "label48"; + // + // BUT_levelplane + // + resources.ApplyResources(this.BUT_levelplane, "BUT_levelplane"); + this.BUT_levelplane.Name = "BUT_levelplane"; + this.BUT_levelplane.UseVisualStyleBackColor = true; + this.BUT_levelplane.Click += new System.EventHandler(this.BUT_levelplane_Click); + // // tabArducopter // this.tabArducopter.Controls.Add(this.label28); @@ -1595,12 +1620,12 @@ // resources.ApplyResources(this, "$this"); this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font; - this.Controls.Add(this.tabControl1); + this.Controls.Add(this.Tabs); this.FormBorderStyle = System.Windows.Forms.FormBorderStyle.SizableToolWindow; this.Name = "Setup"; this.FormClosing += new System.Windows.Forms.FormClosingEventHandler(this.Setup_FormClosing); this.Load += new System.EventHandler(this.Setup_Load); - this.tabControl1.ResumeLayout(false); + this.Tabs.ResumeLayout(false); this.tabRadioIn.ResumeLayout(false); this.tabRadioIn.PerformLayout(); this.groupBoxElevons.ResumeLayout(false); @@ -1619,6 +1644,8 @@ this.groupBox4.ResumeLayout(false); this.groupBox4.PerformLayout(); ((System.ComponentModel.ISupportInitialize)(this.pictureBox5)).EndInit(); + this.tabArduplane.ResumeLayout(false); + this.tabArduplane.PerformLayout(); this.tabArducopter.ResumeLayout(false); this.tabArducopter.PerformLayout(); ((System.ComponentModel.ISupportInitialize)(this.pictureBoxQuadX)).EndInit(); @@ -1644,7 +1671,7 @@ #endregion - private System.Windows.Forms.TabControl tabControl1; + private System.Windows.Forms.TabControl Tabs; private System.Windows.Forms.TabPage tabRadioIn; private HorizontalProgressBar2 BAR8; private HorizontalProgressBar2 BAR7; @@ -1794,6 +1821,9 @@ private System.Windows.Forms.RadioButton H1_ENABLE; private System.Windows.Forms.RadioButton CCPM; private MyButton BUT_MagCalibration; + private System.Windows.Forms.TabPage tabArduplane; + private System.Windows.Forms.Label label48; + private MyButton BUT_levelplane; } } \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/Setup/Setup.cs b/Tools/ArdupilotMegaPlanner/Setup/Setup.cs index 0b71ca9ea9..1bb21aee79 100644 --- a/Tools/ArdupilotMegaPlanner/Setup/Setup.cs +++ b/Tools/ArdupilotMegaPlanner/Setup/Setup.cs @@ -100,7 +100,7 @@ namespace ArdupilotMega.Setup fmodelist[no].BackColor = Color.Green; - if (tabControl1.SelectedTab == tabHeli) + if (Tabs.SelectedTab == tabHeli) { if (MainV2.comPort.param["HSV_MAN"] == null || MainV2.comPort.param["HSV_MAN"].ToString() == "0") return; @@ -312,7 +312,7 @@ namespace ArdupilotMega.Setup int monosux = 0; monosux *= 5; - if (tabControl1.SelectedTab == tabRadioIn) + if (Tabs.SelectedTab == tabRadioIn) { startup = true; @@ -340,7 +340,7 @@ namespace ArdupilotMega.Setup startup = false; } - if (tabControl1.SelectedTab == tabModes) + if (Tabs.SelectedTab == tabModes) { if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane) // APM { @@ -416,7 +416,7 @@ namespace ArdupilotMega.Setup } } - if (tabControl1.SelectedTab == tabHardware) + if (Tabs.SelectedTab == tabHardware) { startup = true; @@ -442,7 +442,7 @@ namespace ArdupilotMega.Setup startup = false; } - if (tabControl1.SelectedTab == tabBattery) + if (Tabs.SelectedTab == tabBattery) { startup = true; bool not_supported = false; @@ -501,7 +501,7 @@ namespace ArdupilotMega.Setup startup = false; } - if (tabControl1.SelectedTab == tabArducopter) + if (Tabs.SelectedTab == tabArducopter) { if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane) { @@ -510,7 +510,7 @@ namespace ArdupilotMega.Setup } } - if (tabControl1.SelectedTab == tabHeli) + if (Tabs.SelectedTab == tabHeli) { if (MainV2.comPort.param["GYR_ENABLE"] == null) { @@ -1437,7 +1437,7 @@ namespace ArdupilotMega.Setup timer.Stop(); timer.Dispose(); - tabControl1.SelectedIndex = 0; + Tabs.SelectedIndex = 0; // mono runs validation on all controls on exit. try and skip it startup = true; @@ -1697,7 +1697,34 @@ namespace ArdupilotMega.Setup } else { - MagCalib.ProcessLog(); + string minthro = "30"; + Common.InputBox("Min Throttle", "Use only data above this throttle percent.", ref minthro); + + int ans = 0; + int.TryParse(minthro, out ans); + + MagCalib.ProcessLog(ans); + } + } + + private void BUT_levelplane_Click(object sender, EventArgs e) + { + try + { + MainV2.comPort.setParam("MANUAL_LEVEL",1); + +#if MAVLINK10 + int fixme; // needs to be accel only + MainV2.comPort.doCommand(MAVLink.MAV_CMD.PREFLIGHT_CALIBRATION,1,1,1,1,1,1,1); +#else + MainV2.comPort.doAction(MAVLink.MAV_ACTION.MAV_ACTION_CALIBRATE_ACC); +#endif + + BUT_levelac2.Text = "Complete"; + } + catch + { + CustomMessageBox.Show("Failed to level : AP 2.32+ is required"); } } } diff --git a/Tools/ArdupilotMegaPlanner/Setup/Setup.resx b/Tools/ArdupilotMegaPlanner/Setup/Setup.resx index fb3d0b0e1e..0524d1cf2e 100644 --- a/Tools/ArdupilotMegaPlanner/Setup/Setup.resx +++ b/Tools/ArdupilotMegaPlanner/Setup/Setup.resx @@ -117,15 +117,1656 @@ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + groupBoxElevons + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabRadioIn + + + 0 + + + CHK_revch3 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabRadioIn + + + 1 + + + CHK_revch4 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabRadioIn + + + 2 + + + CHK_revch2 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabRadioIn + + + 3 + + + CHK_revch1 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabRadioIn + + + 4 + + + BUT_Calibrateradio + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + tabRadioIn + + + 5 + + + BAR8 + + + ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + tabRadioIn + + + 6 + + + BAR7 + + + ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + tabRadioIn + + + 7 + + + BAR6 + + + ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + tabRadioIn + + + 8 + + + BAR5 + + + ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + tabRadioIn + + + 9 + + + BARpitch + + + ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + tabRadioIn + + + 10 + + + BARthrottle + + + ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + tabRadioIn + + + 11 + + + BARyaw + + + ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + tabRadioIn + + + 12 + + + BARroll + + + ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + tabRadioIn + + + 13 + + + + 4, 22 + + + + 3, 3, 3, 3 + + + 666, 393 + + + 0 + + + Radio Input + + + tabRadioIn + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Tabs + + + 0 + + + CB_simple6 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 0 + + + CB_simple5 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 1 + + + CB_simple4 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 2 + + + CB_simple3 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 3 + + + CB_simple2 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 4 + + + CB_simple1 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 5 + + + label14 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 6 + + + LBL_flightmodepwm + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 7 + + + label13 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 8 + + + lbl_currentmode + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 9 + + + label12 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 10 + + + label11 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 11 + + + label10 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 12 + + + label9 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 13 + + + label8 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 14 + + + label7 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 15 + + + label6 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 16 + + + CMB_fmode6 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 17 + + + label5 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 18 + + + CMB_fmode5 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 19 + + + label4 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 20 + + + CMB_fmode4 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 21 + + + label3 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 22 + + + CMB_fmode3 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 23 + + + label2 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 24 + + + CMB_fmode2 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 25 + + + label1 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 26 + + + CMB_fmode1 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 27 + + + BUT_SaveModes + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + tabModes + + + 28 + + + 4, 22 + + + 666, 393 + + + 3 + + + Modes + + + tabModes + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Tabs + + + 1 + + + BUT_MagCalibration + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + tabHardware + + + 0 + + + label27 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 1 + + + CMB_sonartype + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 2 + + + CHK_enableoptflow + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 3 + + + pictureBox2 + + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 4 + + + linkLabelmagdec + + + System.Windows.Forms.LinkLabel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 5 + + + label100 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 6 + + + TXT_declination + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 7 + + + CHK_enableairspeed + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 8 + + + CHK_enablesonar + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 9 + + + CHK_enablecompass + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 10 + + + pictureBox4 + + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 11 + + + pictureBox3 + + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 12 + + + pictureBox1 + + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 13 + + + 4, 22 + + + 3, 3, 3, 3 + + + 666, 393 + + + 1 + + + Hardware + + + tabHardware + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Tabs + + + 2 + + + groupBox4 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 0 + + + label47 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 1 + + + CMB_batmonsensortype + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 2 + + + textBox3 + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 3 + + + label29 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 4 + + + label30 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 5 + + + TXT_battcapacity + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 6 + + + CMB_batmontype + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 7 + + + pictureBox5 + + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 8 + + + 4, 22 + + + 2, 2, 2, 2 + + + 666, 393 + + + 6 + + + Battery + + + tabBattery + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Tabs + + + 3 + + + True + + + NoControl + + + 228, 170 + + + 212, 13 + + + 11 + + + Level your plane to set default accel offsets + + + label48 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabArduplane + + + 0 + + + NoControl + + + 285, 199 + + + 75, 23 + + + 10 + + + Level + + + BUT_levelplane + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + tabArduplane + + + 1 + + + 4, 22 + + + 3, 3, 3, 3 + + + 666, 393 + + + 7 + + + ArduPlane + + + tabArduplane + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Tabs + + + 4 + + + label28 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabArducopter + + + 0 + + + label16 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabArducopter + + + 1 + + + label15 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabArducopter + + + 2 + + + pictureBoxQuadX + + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabArducopter + + + 3 + + + pictureBoxQuad + + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabArducopter + + + 4 + + + BUT_levelac2 + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + tabArducopter + + + 5 + + + 4, 22 + + + 666, 393 + + + 2 + + + ArduCopter2 + + + tabArducopter + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Tabs + + + 5 + + + groupBox5 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 0 + + + BUT_HS4save + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + tabHeli + + + 1 + + + BUT_swash_manual + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + tabHeli + + + 2 + + + groupBox3 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 3 + + + label44 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 4 + + + label43 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 5 + + + label42 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 6 + + + groupBox2 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 7 + + + groupBox1 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 8 + + + HS4_TRIM + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 9 + + + HS3_TRIM + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 10 + + + HS2_TRIM + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 11 + + + HS1_TRIM + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 12 + + + label39 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 13 + + + label38 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 14 + + + label37 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 15 + + + label36 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 16 + + + label26 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 17 + + + PIT_MAX + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 18 + + + label25 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 19 + + + ROL_MAX + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 20 + + + label23 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 21 + + + label22 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 22 + + + HS4_REV + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 23 + + + label20 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 24 + + + label19 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 25 + + + label18 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 26 + + + SV3_POS + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 27 + + + SV2_POS + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 28 + + + SV1_POS + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 29 + + + HS3_REV + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 30 + + + HS2_REV + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 31 + + + HS1_REV + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 32 + + + label17 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 33 + + + HS4 + + + ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + tabHeli + + + 34 + + + HS3 + + + ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + tabHeli + + + 35 + + + Gservoloc + + + AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + tabHeli + + + 36 + + + 4, 22 + + + 666, 393 + + + 5 + + + AC2 Heli + + + tabHeli + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + Tabs + + + 6 + + + Fill + + + 0, 0 + + + 674, 419 + + + 93 + + + Tabs + + + System.Windows.Forms.TabControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 0 + + + CHK_mixmode + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxElevons + + + 0 + + + CHK_elevonch2rev + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxElevons + + + 1 + + + CHK_elevonrev + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxElevons + + + 2 + + + CHK_elevonch1rev + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxElevons + + + 3 + + + 21, 349 + + + 409, 42 + + + 111 + + + Elevon Config + + + groupBoxElevons + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabRadioIn + + + 0 + True - NoControl - 13, 19 @@ -255,30 +1896,6 @@ 3 - - 21, 349 - - - 409, 42 - - - 111 - - - Elevon Config - - - groupBoxElevons - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabRadioIn - - - 0 - True @@ -450,6 +2067,9 @@ 6 + + 17, 17 + 446, 185 @@ -597,33 +2217,6 @@ 13 - - 4, 22 - - - 3, 3, 3, 3 - - - 666, 393 - - - 0 - - - Radio Input - - - tabRadioIn - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabControl1 - - - 0 - True @@ -1455,30 +3048,6 @@ 28 - - 4, 22 - - - 666, 393 - - - 3 - - - Modes - - - tabModes - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabControl1 - - - 1 - 405, 25 @@ -1863,33 +3432,150 @@ 13 - - 4, 22 + + label31 - - 3, 3, 3, 3 + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 666, 393 + + groupBox4 - + + 0 + + + label32 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + 1 - - Hardware + + label33 - - tabHardware + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + groupBox4 - - tabControl1 - - + 2 + + TXT_ampspervolt + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 3 + + + label34 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 4 + + + TXT_divider + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 5 + + + label35 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 6 + + + TXT_voltage + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 7 + + + TXT_inputvoltage + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 8 + + + TXT_measuredvoltage + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox4 + + + 9 + + + 31, 177 + + + 238, 131 + + + 41 + + + Calibration + + + groupBox4 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 0 + True @@ -2175,30 +3861,6 @@ 9 - - 31, 177 - - - 238, 131 - - - 41 - - - Calibration - - - groupBox4 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabBattery - - - 0 - NoControl @@ -2430,33 +4092,6 @@ Then subtract 0.3v from that value and enter it in field #1 at left. 8 - - 4, 22 - - - 2, 2, 2, 2 - - - 666, 393 - - - 6 - - - Battery - - - tabBattery - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabControl1 - - - 3 - True @@ -2629,29 +4264,53 @@ will work with hexa's etc 5 - - 4, 22 + + H1_ENABLE - - 666, 393 + + System.Windows.Forms.RadioButton, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 2 + + groupBox5 - - ArduCopter2 + + 0 - - tabArducopter + + CCPM - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + System.Windows.Forms.RadioButton, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - tabControl1 + + groupBox5 - - 4 + + 1 + + + 253, 6 + + + 120, 43 + + + 137 + + + Swash Type + + + groupBox5 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 0 True @@ -2710,30 +4369,6 @@ will work with hexa's etc 1 - - 253, 6 - - - 120, 43 - - - 137 - - - Swash Type - - - groupBox5 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 0 - NoControl @@ -2788,6 +4423,78 @@ will work with hexa's etc 2 + + label46 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox3 + + + 0 + + + label45 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox3 + + + 1 + + + GYR_ENABLE + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox3 + + + 2 + + + GYR_GAIN + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox3 + + + 3 + + + 433, 309 + + + 101, 63 + + + 135 + + + Gyro + + + groupBox3 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 3 + True @@ -2899,30 +4606,6 @@ will work with hexa's etc 3 - - 433, 309 - - - 101, 63 - - - 135 - - - Gyro - - - groupBox3 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 3 - True @@ -3013,6 +4696,75 @@ will work with hexa's etc 6 + + label24 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox2 + + + 0 + + + HS4_MIN + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox2 + + + 1 + + + HS4_MAX + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox2 + + + 2 + + + label40 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox2 + + + 3 + + + 433, 181 + + + 169, 78 + + + 130 + + + groupBox2 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 7 + True @@ -3127,26 +4879,98 @@ will work with hexa's etc 3 - - 433, 181 + + label41 - - 169, 78 + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 130 + + groupBox1 - - groupBox2 + + 0 - + + label21 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 1 + + + COL_MIN + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 2 + + + COL_MID + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 3 + + + COL_MAX + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 4 + + + BUT_0collective + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + groupBox1 + + + 5 + + + 293, 90 + + + 80, 209 + + + 129 + + + groupBox1 + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + tabHeli - - 7 + + 8 True @@ -3319,27 +5143,6 @@ will work with hexa's etc 5 - - 293, 90 - - - 80, 209 - - - 129 - - - groupBox1 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 8 - 535, 279 @@ -4084,69 +5887,6 @@ will work with hexa's etc 36 - - 4, 22 - - - 666, 393 - - - 5 - - - AC2 Heli - - - tabHeli - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabControl1 - - - 5 - - - Fill - - - 0, 0 - - - 674, 419 - - - 93 - - - tabControl1 - - - System.Windows.Forms.TabControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 0 - - - NoControl - - - 214, 161 - - - 195, 23 - - - 0 - - - Reset APM Hardware to Default - BUT_reset @@ -4177,6 +5917,33 @@ will work with hexa's etc System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + NoControl + + + 214, 161 + + + 195, 23 + + + 0 + + + Reset APM Hardware to Default + + + BUT_reset + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + + tabReset + + + 0 + True diff --git a/Tools/ArdupilotMegaPlanner/ThemeManager.cs b/Tools/ArdupilotMegaPlanner/ThemeManager.cs index 75bbc0804c..859cd8e7d4 100644 --- a/Tools/ArdupilotMegaPlanner/ThemeManager.cs +++ b/Tools/ArdupilotMegaPlanner/ThemeManager.cs @@ -1,6 +1,7 @@ using System; using System.Drawing; using System.Windows.Forms; +using ArdupilotMega.Controls.BackstageView; using log4net; namespace ArdupilotMega @@ -225,6 +226,18 @@ namespace ArdupilotMega LNK.VisitedLinkColor = TextColor; } + else if (ctl.GetType() == typeof(BackstageView)) + { + var bsv = ctl as BackstageView; + + bsv.BackColor = BGColor; + bsv.ButtonsAreaBgColor = ControlBGColor; + bsv.HighlightColor2 = Color.FromArgb(0x94, 0xc1, 0x1f); + bsv.HighlightColor1 = Color.FromArgb(0x40, 0x57, 0x04); + bsv.SelectedTextColor = Color.White; + bsv.UnSelectedTextColor = Color.Gray; + bsv.ButtonsAreaPencilColor = Color.DarkGray; + } else if (ctl.GetType() == typeof(HorizontalProgressBar2) || ctl.GetType() == typeof(VerticalProgressBar2)) { ((HorizontalProgressBar2)ctl).BackgroundColor = ControlBGColor; diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.pdb b/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.pdb index 9761640ef172e5d1a36ef6edc1329d4389aaf619..3a1d3667b732364a3e9553cabf75239267dafc1b 100644 GIT binary patch delta 355820 zcmce<33wD$8va|=-RULWq0?kf2uTPb>$SMtxlb) z(+TeB9o#WsRm(>2x;1Tc3(Yv*c5m+x`KJDq?KfNP@U%N^-`wepjr>D9f8K%F9;^$j z@O`O2<#yN-hkaf>Ovm%(>c>ioY6o5R*#09mYlbztcYBk_wvo}7x87Kk-oNSdbFQ2= zq3D*t_-zH7^*b9CMnCsT;jX5~ZV0v=w0h7Fwx^ex{?D#&eM`*5Hz{V#ZJSFNwU zq4=qYx{P%DBl=TK3mwq|64#yVd;gY4=Fac8>WQi?y(Pp`%}Lt!>e_o2I_l=_Oxkhu z&)Y8@W+t&R`tnJa{QaF@UVmkK$-0*wc+d3z=JpR>9NBTt`5rk#Gml5V)7glqePMd^ z(#@yiZ~ObLM_OfXN-8<*`@}E|EsXTXO?a^Bfsd}!pSZWB&o(YwWz={M)ee92&iFyw z2aP!&75(Xq0YiR1+4GIj_v|hH=iOss%#^kq-LYud9}iZ{JNNRZOByAQHX@u{Xp3H7 zH{n>yYt7w1ym8gxyz{G%nE^VynSSP)#XZlh8W#0P*6%YzRq`~cOgZn3ZnpK%n#^~u z>QeICvXVc}FX(Rudi?OwF^=EL-oErMck@#xy%gm$Hcp&e+>t1&M-1gPiVwb<#&M-V(*vM}?{nS+p?9bn@J$mbV4|LO2!4-~|YKI?_ zrX7Fk;UOo!yXTR+K7Yvm_4%vL7>VQmaq_W8=6dxmw*(IDn)T$jPZ@FTrVV|%?*6Ze zUpV*d8>+>gw$lcMn&X>;{EMG`Eu*>q`}*SSjFSAvW*hoYeK!{LDV|@O!_!F*I*vni`{5A;;cm-^Rv_R#a+2Jfi1m-f2+QF=T}oylT}1eeWY;p&Li_xUafyjgwA+kQ_E`oJ=E*9{!y!&e;riM-RW3GhAm!KKw`CvlttKZ2jYX>bPo41NJ;!LQ&q@H_Ye{0TJ1YaQ5t9XLP)Z~_-_ z0}qG-RcKqhDovOo)v z4O)U$pfzX%+JbhVJ;(vMpabYw!#|gRJkSYr23>&MXu87PK!4nqf}vmq_ze68M$`1J z19QP$;4Sbj_z37WG7P>0-HD?Ih_`cbAQ3D9J@Fgbi+^t6b^3KGBT_FlqH1D^YGOz>tw9#(ua9epGQ$#O!K6v0 zWu;Z+(@KfCUvb&giB-kbQ&ojuAKj48rk2QytpO$(0n~_WeT;gtk?vCMdij0o#SZ## zHDsv2v1;01A6B1kK;7u))V%ses!5K2q}toZ@7?bF<7T~H7v+%rt?qDcmNS&D^5^&` zG?=XgJF2RI;^64YWegT z4W*iFiDyb!R2~*xSfmaAP}O4%&EsAx;pxI*k{KJ4|)@8a#|!s5DkNr&Fw*N|e|UvoTYdd1A@hQf^dYmTQHcB32*Wzr?`yXZ-EaRGh*|L8^a zm0jQJ|7$%#q1Cy6j%}!cR3mGlA?H6kwp!HJAG5Z#UYcr+dHT^tcyz5 z$5`UNAY^i+US@>!T5_sZL=vCmE9HX1A9ul-D)Z|TFIoqC{rcGdb2PO@Z)s@%eatr+Mz4N;S6yx^UH2RLYkt9n8JBs5+5U!l8k0v(8|VLa5fEP1f4m z?u*?QI^_FDsfu3Q3}^P&rzP)ak|oDGIZRk`L+&5@YTB57wFSvF_Z2fIoEY-`bAYBT z@6E)skEX3_&eSYR(<%lswUou>O#%b*H0?of5WjS0Q(M5NMNHW;m}WI&DmIoW9O%il%JB(FECh1&W!m|$s=Yyv z>G*jzGq{#K7?8CqQ+N>YGm8asjEmB=UBEmZrN{!4Y73gy1l#cF0M<0&$pDzgznBEK z9~L@0K7xxKX<9=34i_SG>7{8rmVg$GxF{gU?PHkx7Eyrkom7TDpLLr|CgxPi9Q@xy zmlMia4)V}(vKtfF?qoTi$BY6^d-igk3@8yQOw&Q{o|?9?XKlfiQ8vouI*=EyX}76; z>9#cIdaCr#@wEj5;(A}IX*($FlsHY>jeAc=9vBo$EHNFY4A-<*fFq!3mB4zG4B`nB zn8!U_+V9L*lbv~8n4fp4Er_rAlD5>p&{Pl)bvqff@2hF6zysv|GTPuK5XtOaX8Jdg z^^v2wWbh^K$f24x1q6C9J*RljgSiDf4FWlar_x@)!=w{IehysCqsldgDO3ToCm{x1 zX-xM3^SC-u)7}6ZTH@2n^wqT2X$kEu^*X$*racZ8UP6YXToU5DCTZG3z&wfwUe~I& zpmoi&cr_u{a-8l!Pijx1pol`1_>lqEop-a{w}U>?_JY1+TQ$SXDN zF(AiSn(PNHLhgUICN3JH<)|GRRdZQm9)YQ>hfBGv$(lCN$Kx>gGM?6+U=ib-PgV|s z&X;LgkODpgdUoa6D4Ot~4)@*InQn0`urd zOReozThMv>vt%xh-u?1bJe!RP*>g)YZ5fc`IqIw_qlg@zHlrtJhTQV+7A~gIbq(ip zX|Nvy>(PiZDFKn~=t%A8uF2y(sK5nBCrz8si56O%KY@6G!+{=Hk1xs7pJO#`8ZD|n zg(=6IxrC%%<+#kt11*T95GsHi=P0bP^h5LbV_QL*zVhY}G_}uexV%EN(#}OIHncV3G!7{pQ@rMdjsF(0l$waeW{p?| zAyccKh?y-~8Jt8bHmi0ckcETD+<4bNc)9qLrR-jZ~r-tzx;SnBq_S58ESRxz|X<59X;i z$LQT_8t7|MJwZ&XvJpL${1*B-yOBZxHuUb zMZ2j6hgB^1Z&Q4~8g3M^+}A}cHmg>q1E#k5{hzue6Q34^v|_VrWr}2KXJ+jhC0dy} z)kwr*w2EcEV~QVtZ1++T%RET5VzX*x3Seqq$r!Lqv@$git=OzunTwg)#q&BZM_Z%G zq)o(Pw2EcyHpQ*SK2RbN%a|@&v01e;Ei|?3+Wc*rk%^p;R%}*nz|z~sAMAPKZV}6L zNFo-aRV*_=GveL{*H(*GW`?5u{tETfXnK&$98Jx=?e`nqS7wx=5t}u>FE44(t~&SF zH4>lPh(#+lt5zmcX1tr%|9ygJWs)UYv4ypv9wgISQ+)kbz5gjNVYfhnlhakcErm?2hcW~}-(aQ8zv|8AMJX&(*|u}t1Y zEVi(iGaghJ15E8#-!J@HwDJHWTCrKR@<3*4^Y*TJRJ8J-CR(vw&^2X}XNu26&nOkK zO#VbHHfzK(fi$%vufOq2(aOY9v|_Vr5MJqO|R#q!a?d6Rw|6R1QiXmFDS+(-~U}}qw)qH78Qsu!y#A39HG_A~see zOzoB@UyKl~tW=0rRx7MpSphP&C;Rl&MJp>pq7_?68ybI%2S`)waJ|w@#PVP%VtKf< zMl26|rZ(X3)=ISU5GY!)S+!&638r?_uRDrFD+_a?6Il$&!$W zWm(7?@qOtH5qJ9Hoskl8cl<;vHmkOles0Eleq_skh*qA@MO!0At5_btO>xP>r;UlN zJeG@CY*wwTnV8x)npPUawydRyR%}+SEY6wQZu_%0NG4dct1-l4w2JGxHi#!@r5jUx zS)`DN#b(vYYLyvr!FA=!C1P2{60O**T3O&Qwcjponlgs;jg=1(i_t2U^+8kow;@lz zCK1cJp=iZs)ymSPseS92*}X(7OPZn;n^h~TZl?BNO>I@ah-EoW#A39HWfj5{XIHM+ zDOy>j5Utp(T3PxrwU7UF=1cyLH+G&%BWnoIhvIu1r%c8Lv z@t|F=WQkT5lSL~wt5z0UP3=c@OO5J~MOe{_twBru%Tlu`Ui4vczs`UoQ6eMJr41q7|E=C4J+NHBM9fd+I5dh-K|l#A35X zEK8WCwsGGxXGAMYo1zt)Ra?i>kExA#wEKL~%G#x9#a3e#%UZN4zU!Zhjfii@PsC!g zYGonV)UKG?<_d{e7KlYFHmg=v*-h<wi;FB|s*Sud1` z#b(vY;=8GRcl(q}C1P2W7p>T=T3J0dwdvy{<$73Eru;=LMyps>I!*D7&vbl8#Igb^ zTCrKR6KI5{wp;40w~AH^H%zfvwf_7D?XQ39?H?ocFU$WDu^6plSvNN$)|W*bl89wJ zU9@7eYGobW)aLDet5&qKzAjp^S+x(_8nlj@t#|*dhF_yMscA_VGm6un#ThqDS+tcX z#Ab~`mfcP58_OQApylBN{)yitIsf}E8k8ux_Rb1*+ ziu{mR-guPC7coERwZk22i}ctSO0NER(WN=}JndBHudrR>8lW)&)}B+viMCAFOIWjIJw^>qu{Ft%W-dn}NC$afFc9zgU`=hothLQ->8|HUsrgo?%5G-Mu#4k| z?w&{0BRxDl>T)w}Yju5q>hqc&rw%l?#k&51I2X+?&23%k%cWBm*YHm)y|7HkvZV%a zkRirWiUiX3se%$cW$oQIhrUl$R=5i4!=90_&lC0`!cwLg0UY&V9fW;P!lvo(smc~M zp+%vyjUn0aLNp@V2v8ZK+H6}2!5Dqw zdUMj2;^@=T*2*r|oO41?Qj1&Kns`E&r)yJG!7G&aj+VB;cFDiDmF@A?X2GWuehb(Q z4uI3ZN1>#Hu3$LJ_)XX5+0$KoJLhbFl|%VE*;7>CJbO#q08MROYKv9DJbSE*&+44{ zrukW``Lvk%;?6lTWbT&~YCQRlhRf(lvJ&}|o$Tbklf9)~;^M5pE};x>UuS#E44Ht- zAq{2<`CA1xgT3He5M6hwO!w1U)~`KoPxrk=8h`uBVN{h`FeWNR4LoiSWSCy@nms@t zHm>yF@Yb+2Srxn)5u;WdwOMG>(-Ju1g z6-2-v!A|%qW<8n*$M<33Z*U`Z_xJXz?2`Wp&)Ab%#bA%p8W~N;ja?qH+73DLGp|P*3ZEnj}dy%TV#Su+X zP8tz1CK~-TbdpG5{WrV1|A2ka1~-kvn4W511)i(2cMQ90PZSo5GY=uoc`L&VzfvePB98@KQJ* z9sw7?)=b_E${#)8NnSm2I3(fNz=rG^1%cnYw!p>1ePmi-VltW zq?k7ZQ{drn8+ZiV2ObFzgRg)mz@y+B;4$zlcr1J~d^LP8%>6C+1U!yOPVhw>w8!9k z@U`%l@C5irxCs6eE`jBqO|1vz^H^r%!FDjS@nCOw3Op2^3QvTuhpXTl;G5tw_;$Dg zz6Y*^ABL-HaJ+zH2K)|O4Sx>Lgy}fijj+w3X|v$Q@NBp#Oos`!h8Mt{;f3%JSmL`D z4)VWzL%RsR3BC!I7gsmK55SAzC*Yc;IR1%a8T>DJIs7Sn8+;620sjfFgd0V$b^|ws z?}S^!^w?l$cnv%Rz6%}?uZ1gN1uufv!L{&u_+I#4_>ld;-50mM_)!!Ex|=uzW23J}lpRe*nuj)B9oh zbompw82%KV4SxnNg%7~%;e+rN_;Yv%{3TrTI*zY!d;lMTzk~k`%WK}RVZVp(^Wil3 zTQ~VFz3UGcOEQ!%lcH?1I<8UU&n{gdw;Uj)Hf< zjdc3|>p1*)9D<|aA7E~vLA#fm3LFE+!)b5=+y+jB`@%`^NH`gu45z>|V7@vD-VCS1 zcfc9&{ctn*F*p;hgPYgjcn3!o{5jkL{t?cG&%0;9D@e z6@nkbSHfSxSHZu)V_;V!#&S3Xz8Y=`UjuiAC&2yTB6t*B3>U!@;WBs<9E3~YRd6Z1 zsS*8uGLCI{To1nh-vECAm%&HiY4BNiI_&mqS~;8uSHR8TYPcIb6V8Wkgh#;K`GOPS z+3*Z_4!jti3*QCLgCDNJF&{@Aya0Y3UI>2zOWTm=^C0{?ya@J18y{r_Q{kIAZx1hq z`@l=!;qWbRF?=gr1#{~S-V85;*TBo+hv3`bqGxfe!0{Tq65bEr4j+Z@fPaHm!QKF0 z4Z%&|JK=WlYPc)B1|9;lxg)InEKO*3XL?Z8lQIk*gT0R2H* z&=K?m{~u{;E}EER=KqwTi)mUDUM^|?XafpBE07EFz-X-|iup>E)(4325|9J_S3oHl zDUmC{Fwg@G0;aziZXkYtP0+LzT5UC)v45HO!Dp~chX1(OPO)WgH@1QhsID4^k|s`$TR|+4%v*4nQ$6!$%PZa z1{-TbU@tfgd`yDV?b`~j*I8BaDPL1htZNhxNaM#lRCZHOs$CpB33X8O&)M6m4Uygm z_4Zb~OKolHna*NMTAHVoiydap+tCe6^JE2ZXgpIGt0~McwPtEpBnwQ7I-z9QA2C)W-de9OcXKMC+LUQX9fvvsV$ z&LPc-=^A31PfW9#Q)M{*AH~!zi>dj2&5Mdzu(!l{UPzB>mc4FPu#< z>DvC=Jab&k5jDDP-D9miqjfu-sLtNjGfnq|n!c`Gr8Yk4U>U5PXRlq_?u7Q9R(6`I zx~;vZz%C8)-S(bJPpBE`^vsPuTZ|f);~8V8E!5TJc;@JyQ1$5AYBl0(S@!MVS!$pt!v*3c#CS~nGVkg#Q!c;?$B`{nOBl9VIQ)1*e0Pvn>ay3+dwgA%Y9tOv47b}#rA zXfzepg|uAIAJ9g%YOn%q20Ot4a2iBYp)El^7z4_{Vz3@qj%`DW^|jY~(p|6UnzO8r zO=Vy2$+C-M*!7;n`YhGq1{&BbH6lc(<~UO#k_kVH?H3`#Tsw>Y3>bnBCdlBK<>h8)pQmP4OnIEvJX{?$=<7H%ud(?i5wF zoLx})<(|&mxh5RqmB@;6?svPX(IfqB>hI-@g*Yzge6!WQV%q*mV$}_If{Ly1MAz%g zJ~&&gT&WM#Ur`Gx=zXse<<*xGWd%{3S;8dGipQlDtdoo*{u*4*Jm}hB!X5M7jpQrAvrs2#} z&s5WJ=BdMr^@IpXdY(E(Jb~5&L&-?RNfpdfwIiv5o-=7Sox(P=m&{XocYA^=y3&zH zmLHl)mYs~NKM%B7$5j~-%yD%GMZlm?mvWd;)zt9F_|-QVYVblons@YsCM zQBUY{b|+ZK4fu}j2%Tj&|mUB0fABNseP=J$ecfrA`30rH99a4-ePTyQ<$ zotw7DSzGY=+Iu3>ot1XYdD&>y;+}}6_RB`w)swpCA8Y>>F_M;lMUuCbi{(@2Li~Sl zcv97dB(E>PS$+9SLGCk}h1z?m-Jwpl^EOduQF$H0wMbY(+Q(q?#T)}6PH@2PFe9Vu$- z!`!joQ!<3Ay&-q;%`{MiD95IFvjdK+LJ>$MN@I9W(e*Q3X(4Y_{)?B{TZ*?yAbo5@ zO43{2Q-7p*hv}7SNE2^nBbNP~i?0qTw4SO%sy9YWZ{5hLR1h5$df}iMcJ~%XLf@k@*%CxpW!XF)3EAhWq5b# zcIv&ZN2YhG%@ZnHU8@eg1m2nDZDN;lJe1|_WS3%-S4vC)z0saf>FC--HR3awRL4-1#ww<@cXBhz^d1@oYxog7VV+UmOLog7{3UtI6#OcdWC z7`9q{)Y;K2FpOm&sa9!){8 zb?;neT${T%e1ZGIv6;7t{%T`yZg2aoHnUUpS7*97vIBc8L8Nu|SH+7W5>hu&@-nAN z!|Ug;L_$h0L(-LyLs+?zteb;>e|0zznV`0Ib>!;D)Zwla#c{4wtx=KP9NpWguv}sx zl)T5PpJB|XDyb4bGjErw%5Dr5`{(j>v#y(?bGU$ysSmpm>j`4rzefGp&CxNiKOC!+ zpNusFLSxMURV+i!0F@#AYk=C=-H`zOqq`#o`Vdil8J6?xAPzB~vIng~GZrn*d zNpGO))YH)hD(*=p2C6wd9hrfeaCCCTQtSiO<9J6c4SP$O+SP~!GB@ezhz_is$0Ipd>}lg7UXl`rwFy^ZuM}!qeWoR-3=Em#WyH);ZkISjLsJ!H9bgG z_OvItLRULT^(x>J6Kfp4D040?^*2aOD{!PF4YD-qV!S0MautKr#sVtFe@{aOWwalp zJ{0f%7H=5@2B}j^=+gO#kv!&yDs6OM^3JOu=kfJwVP8jk8~o`_j#M?_Ynw-X(AN>| z@!T7ZTy?JnPYw-`I3=PUXH7ZKRk{oMn6hh*SH7srgG6Ao|w8-{T*v;9$DI!|Awi3om^bT zKu3jb*y_5c20CuhZ43w92RYVyLLFDv7O0KsJWw1T@Eq6+ zjspjeOX;917ze7s8n6ZI1{}2m{;_tPH{Io?h%)j2mPnWHgkC~ zb-?t}1*Y~ldE!;{wO*gghkX$CJI3&c)D@oqXH-{cB$xc&qjrt4b#sTlLn6g1&$*hp zq6ii_muRo`c4^4WpVyLNBTOAJWl!*C1#nyt*&Ay71aF#Wfa$F^e!w`eZi3gRzo8zQ z;O*sJV$3E<=hy@y^Ap(@M0QO-r{&6q7GdJv?)($etRia`o)r_1z0SZqr#e*RO%33< zAPaA*sA6w|{-(;9$O2){VsDFvYrDSK+pJS#LN5&m(ngk77gv{ZTeAl$=%hXAk&jR) zraeA9?!BdU6?@YH>n&+X8NQ`XiT8tHZy5k&e0WRJzTCz|PM=72V@R;We5b0JTSvFm}s9bYC7vVlB`6uMExQDOYv9flf3O4uH?!|L>x=RJr)=dXL)dh z;#8HTdQ21#1PDdkO(pmPX7yfFV9Zp;N@E&#IKg{9KyyL^1TKbo) z&Ec}7?BrgxM-9OoWxcSuDr1tjUHFqb>7V9!C$~E3qKAetQ{7wY&G*m~DNS9=QTlkw zsO@BLzFoRt`DE`9yV2n$dt2G1XMH!>`wzSH6--HL=XKsZPpDVu+7qE^ZuAtUxzfsC znnD<9(`lC>UDcQ`liX9iiJnjs)>$YS@iNomo>RRQc3Pl%aw<_v%emot?^rt(T=&}b z-YC5$v55R~$jEkpf; z05}VxS>$Oe3q1|TwxN&f&wg&ZmWgg1OD`!l+fC7G!xy&Lx>bj5*Xy>pSQUMQv*@pE zf7)&FoPA@fvhisl9IMuSW4pHg#P_Y`B*+O9wnN|A%AsLL4SFd=Ime8%`;Xb?VT0mS z?svAyrhALU-SW8Mf5&m#c3aA*P@-c_*xoTtBwszhw>8t{tmp^ZLP_uk+pG}9sj`!{ ziMZcA*^o}rDKox!b?}s})J${CkB0wCKN>m9`6-ma5cy9VXEmp7GwQF^ea3RF^Q|W* zIiW0v{cOv&k*~VhXKhnj)X10fa&%>+k=ONOKm}L3OJ=g<| z0Cx<{3iJe{z*4XQybitqzF6L%fZ<>YSOd0z{oo{M!pdJB7zN7W`jI$}O<*@T0M3C} zmQ%Wd;h-9<09(Q9;5cw35D~}&V~n5m-JT!0Q(rrV?_KX?igV<1&H8cmXjMGMp6OhT zCHjzBKE~cG5Pc~0J2d86!6ho=MV6l~2|b~u%eTar$Sg5Ijoa&P9sX>3v}N{GMx~LA zF@CfSEudG7wU4opz?)<3t&`5lw2y-_*DA>7Vj$n;KW${UE`5dX1AXmD@;iseaDS0q zWuLTX*u^pInBJ)_c+&o8{WE6%k9>(c7hNXiYkstwFQVqCyMN@X)OlF0!Sc$F_KW}y z@)Uafl)K9Zp_dU~eCBWmKCsMXOD4+ux!N>_qQMcKST*=3yZPPt95v@BduGghqO})? z7h7gjS52yzquyPhXNM=5bJRgpt_7%k#dhU7P2xD}6Q{vyABG;OXqPxEcRJIOKD1<^ zilI#ga>?$8s`j)!;R17U*esLL57n-}nrDQ~as&HNox-ets61!vDHlXiHsul{4Y#4{ zb;eLFYRTGi#TmPs5WCKBH+XS-gfl{JRv)U2YG;Z^o*)@QCD}9fOjGse8GGCCbL$+{ z;b$&>As63dGOHlTz6>@0XS=U4XGRH_bBbC`y?DDlUawW#ekSc&H6+E?Eqrs5nm2Dw z^1@guKjjxbotA2z@Qc0F6RJ#I+Z=k!^2IOq`F5&AO*m_3)uq^8r_S0Rve_jIeSWuB zc9&nckRuoDp|KqS=Rj;C<2&dN#(`?E0&D_1z!!=9-c0C)@;I8>L8s>IS}n6$d#YU= z1IO7fXGARD%9r|^Me#X`J{VpZXK$B^BYe&Fz!#+4mI_UW2aCTN|Gt|U+Gi1+T{ju; zfe)(U@f6)5VyGg9+s4~_gj>`>^|n~Pz%m=lFIG#pYq1>0QiJ8C8ys#3hYNzn78BI;`X52(6chAof_i6$ z%0z7&5EY}IFXmcJum2G=bs~k!H=fSynbh?}dujm3#maS>Oj!3!wEJA&5~?4e4o$RY z1#ny})aXehbCduR2v9T0-YS6OzXS+RfDbxV`z(3HDIuL>1e-^&%o5VU@n3?~*ZSQh zr1KpC6aii-VO+v-u>hS)32>YM+X*nCloW7WEWn2n-~<8QCBXSoQowPs0F{#o@I3*( zBf#G#lLC&51qfV6fFB6py3wh6Tt@&L7YndW0-Pj3CILQ^05~odV8j#xoFYIU0?eDj zHQ=~dfD;nnM*>_!fP|?8z;Uqv%cc^5Pllbd2(VoO;J8?Ttm_GIngFW_FzkA+0msDx zyea|C5a3Ay{2&2vTr5E84Fvd^0B;fCjvEMo<6;3K$_Vfa0lpzXP8n?$$Hf9XA^}*o zcG_nd0pirRWprN7E*5IYG(!DKs5C;&nr0ai{~?y&u;gL+Y8r)z<6=>bo=$+@2{4=h zHPZ=z<6;3$NdTrR&N2d|lyiwVE*9XfasvE8fTaX@shmQ@aj^iMDhTi=0X7j}LInYE zTr9wc5`d4)ojVC|zJhDOaj^iEl?2du*gHUgzg3a~j*A5dR1rWYz*z$Hs3HX%7Yp#X z1h5exmPg2st4IOI#R3eOK>#}eatSbN1}WgUSb(Dvz(Ih)1c<371soR(u&kN@5d@e* zfbG?!fa78TvSt#%Nr1%!7&en}9>>K3ydVKw1lT};ZzKSY{}LcPp^+;Kx^ z2jq;KXy`0#@T#1lkwO%ds@z9ur8HF72coN=~C&Sdm5&K&bOlcC8t>nUe4?igp)awg-+ z{j#-i%Y1vZUB(b>o$N9;7^3I}h@|7^EWq37&{F6@@s{3tzj#Y8G}I@>Te_HkA>Pt; z4DX_acuT*i5pQYlhWB3amd5;pcuONSyz^`DmKHdn25)IuhWA#yYvi|EP)*bTk_XF+s2I?x}C1Jz&!*aCKg1K>1>&Oit9!5B~hmVyl#wFU33y@^N4 zo%Gm;p8f0o;+yEpyRaPktL0U(yo}}CUoEX}#_|f5OX~g-+e)$Q#xnP>mQ!MR70dfr zQWo1Ab~uk-jOAZg{*9$(F{23%V>FR9RgL2V_4s1D`FiI$bxH!fMu1D7BdR6!cg5$_ z_$63g$5M*r)+LOUI4&5Nx~UhI*b`E_S)Mni&z#m#QZZL>yYW)So}zbCQMVY>3i@k+ z&Sn64obRTJL&^oW*n6e@=ceA-Xef8`p=;g4Td8lcmv|^~!!K0@0z7Z;?ZH@7ajQMo zLxCHHF5#`dx7r8WrKr72?Ui;Z*_x&HWp*jZI|i|s*nF8i+7l`>T`LNO8NQ4#Qa<-D zV?>qWcx#z`*+_Gra3NWGj>fSE906xRbTisG=m~~{DPTTW12%)5U_Uqse3@uLK7S79 zYU7*Z9zk8oB=jOV*08H#)4i$cz(>3U4sO#+)TXYs z=4#bPj!x>0A6lOZnViaA4{aP8 zvA-WqUzT)ui=)Mb-u+2@amL~U53j{>kqPqcnbF!LGI>iKuMS5<#zf7)DG&a#rX8nt zxqWG=vKey>(Z2yV>l3;>X+4swI8`9uA)SnibP(~r9A1=|SH$@4Xse7q(}#2clc&N?G~Su-ZfSF@qD7Z%hmC=V$FY3}hV zv`})??MU5261gPNfh2krgp!c(QZMmpTS8<)3u`pS-!c#ruUux+2-*^K1?R68sDHX5 zle6SStJrp9laDzouzeVgRtgv|qBY-{_N*_F-r*9-mrLVdTUGrrfD$S1s~%2_Y?dk? zh4NO+u$T93C=qFo2}X&mO`_fsf)+=*D=pd`a(#jLj;YUCo~& zsIDq6n;}`2d6JZXgkaKV{I8NgxjEq-pb0U37++P2q+9mo#V@)hm z-r(2+K_c9Z?@mdMo+lAXz0({J21Yt#lH6hj_u&-?OQa4RD)1fe1&8z2+V~JEQ94PA zp4iYe66TNoNZak7PX+-AMd3if62cuj4!C&if?!8>I{`7}=nLi>L1wx~?uJP+0 zDUO61iG+p`Yz$LmLEIWsnP5{G@R5BNO1cHesNcULQ5~mYga%-}ez4BQ{|jj_9L?B= z*AZ?-9Nd%HqQ!1uxGl`M%~fbYN~^~BS%YDCbim_E_!4*$oClY~+>nEF;I8nkaCi6) zn8<=_U?L0N59h;=!UgcFFxMS?7ajl~hUMoIz7C(ChG|y82=>3SCx|`m2(a%cK;gx)mnlHd0DF)ER7rq>j-$*1luv+N z^8u3SAU{aJkxZC4&f<)4;?4mbK`sdS*Tfkj@#v!^vC%G-h?2N{w>Q?5<;ND9gGA~- zw9!d^7a?@Z(d%zdu_SiRNYeNP0HfY3xfrSUDmWjmhAClVV}CJxBj;13{%7M@fX7@| z>UBQ69>y>DEKCgrUx%gG-VC4bhZo`hGkg;)qw~#hAuRe)u;`__mT+DP({_Rvmadeb z>N_~HEkAQnJ~%ST6S{He{07LPr))7bw-G{m=SrBaV8oaiK9{H6TKtE=YvF5P1sB72 z!(6VR=Q52g|Fgp9(vmk}CvL+|+{XDm@Wc2&2XBTykqdbQ$G`EQSqHxf3s1swX&x@= z3H&2rId24S;z-#)ki|;lrGtf!}~-H2w;9!r#H6J%QHF*F#-3F0xmg+3=~A@O?(t#;J|} z)?;d@3!{OYf*WK036_TP3)~WxdT9;+%6S|3cen?94wefSdm&6-f{ZT4wti_yn?u`pK}EP-XDFNe8esjeDh$d~$( zA%7K2WKv(oNdExbk@J7RGU8Ju#)y9q?!@^qxHJ44+y$0uA``(>xF_5S?gi(=atDwd zQnaaH37ijC%E(@TV-X&GVfJ<#w}egbK+dQ;5d^vm;mOFym7Wx^M zSXk~1^0O;6)?gR-3V0|?-5Ec-G8!)D{7U#{8QE#g!By}Wcmqsv1-HOg!>_<{t9Tct zwFmzV7r{Tn#jw-P-hDV3o&;yZ6mzf(TnhJtC&PRlZ~WW}?;(w!Talk#DPwqKX@-4q z2yTI?mtZYi0Y3uM4uVg^Rq#vj4ERl0M(KUpD5gL>W;Dz{)fGOl4 z+ak3f|Chjv;Q8=Pn1Z+BxET-m-Ic}gy)f+|xCy=m-U`d8EL$>`!u;5hwhaCnUJm~R z-wxX&*oqIwz_g=a8e9wKz<0s&cMoY-!C|n1$H9LiYe9J^SdYhi_+EG^yb)dpKLBrr zAB1HC$KT=I@Mib}_!0OE_;L6Q`~-XseiD|SVc7~dg}1>u@KbO;yd53^KP^Qw5yvy| zH27KgCb$k>2|ov~f&U3dQD7nTf@SBk>{#v|Mn70~Hp?z};gMm;&UpDv0r4LUWOuUc z6PJz7on^bdM0QmeB9@5c#|LCfbZ;ODT?hWUZCZB8%Vu=R#5F)7m+jO7+5Rl?$i8lY zWKzP5Mt05DYnpKKSCJ$vTdcdO%sV67=>65@P>t-;?h9nr(*ekCe%YiiJFF!+@y`TS zo4FHPv{tul@HY3*cMIF(as*N?qLYyvyL0dN{5HYaj0983YLz-F)$><8ySY!+iA2p`)n z8?CSXr#&{2`(^#noZTFb*Fv8fsBKY=lGT9q_Lkw#R8CvIE0|4?kWklN2rWr%SZ^U-2d-JO{sdo~J)U{CkZbCEo`opmw7;ol7ZPgI7}eZL;1b~)WS&?%=oK~Gj57oJ1a zBQD|}s`k0?yha@r&pXsIw>uMh-0dDDpMmW?@8T*v?nHf?%JR5#JlnYS>O|dCZTpDd zjH~dtJBx1kIdnVF*FeA72FJCS{uf6h#X=sk2;kIB* zk|gotoG*b-!IJoo@WZh5md!9dCCK1uu-x6{{CW6i_%-+!byvWB4ej7mz@1X?JHAo) zo`+*#N-UTr1n0mKYX{iQdB^a19vs1WKI~LO8XFB{L1SWLGHk@gWY~y}$*>VyG;EDc ze%8nu8#7oVwm9{P#5PnJu_fUvd1KCD#MTs+yrsd`*fKb`#+J#sxlV>j?WWGm|%h z<*5#_?iBr1H6+$OO#iCx-dOh)HhsG~74N>JMt=EMj->*+`+D#+*bhzucMDBR2mQe~ z5CrSM4)6gu3!<}`lYzlt3J8KtUUX+Y8KOs08T5!V)y*!HxQ3)$Mp8%D$+~7!cXZ%r ze8cs*4Vx@_xk8IxGt`o%s;WqHJM{8~ozb`#EM;kYOPbr~X%`NYtQM8=BN6kLI-*na$YV4SFeYj%!*(ft zn-Qm;?#}eQTOVv2!2&b*tIU%ac0}a}rJU|gv#1VBT*N}qp!#@Et zN{K@Xsa%m#%-Y*+j4(QPI88-MdRY_Uj5YB#ZVmC2Va$QArc7P>Zr?Z51lDl5ONWv)m3_g{IzFWs5hqkXNX~S+vj! zrMECBgWVXM^$O8gJR2`)($ET}GZ4J@8e6>D(1IrF;!mziGEy@#{i-n5W$T-0L^iqS z!OeMPDy5W7L&R}G?kkP1rGnWs#LCboywUvl0&Zhd^3IUIvB^?a^HmeJ>8rBU?nu?K z($iS^TDpB`1GV(~T-5=x#yR z3G;;Zmah5;79Xp{&VuHlJgAl5F>L(M-rX>4q~;KMDViaK9++bZT`QJlSjJ*`-fD@+ z#j+erDVCgEOPD!gvGdqaiN*3GGjiuOzu76I5aho5L#}&>{Zp^4u1^Q|Sf|~%jdpQY z+U2I_@9I8k=hjyDdsp{No1MEx-HaaYdv#Cf=Adi4xLvXRuWc{)w{{swhxK-|F}$~% z?^Hr(o$QR2A@2?1Eu-Q~z1^McG6)*#=stMMz?ahpZyDzd@1S_g*ml2oGlJE9+{eAl zZf7*8o7B(!hr>ggr$OsXnMU*`5AzG%d3G9k-S$HF2%Cp`G^{BhYx?ExJP#FT__4=O zLR8>qm)bHC+<7?(QbX#{N85W1MbcuUa_8;rM@KL0jTUmqAB2;G zNxRmw6^lcl46Fj1!ESH>oCNOHOpHKJFb-6MRbVsN1C9V6D~HWNAt(Zi!FsS0><8yS zY+IIoy0+yp6U+vyz-F)$8~~?5bUW7SKp`jsE5IhO8yo=gN+uEX1f#%gunIg4_JGsC z$Go?Bj(j`*vOC?^gVxpd&CqWlsoFDqeB9?{cXm=}KEWzaeLG{tPD98(Uw4w{jfl{y z>04^!%iJi;U!j)n-jnFZ5U##l@raOvkcir!6 z7X?$Lp&bza^H&i*Qs(-kM=@5Q;jZJ;!@|jbpgQ}I=m+AWg%Z)7mNuJan zeH$gHaz>{#(@P$8D;PJ2Gd@m56AVe!OF!G=)Q*=t?g%>pm&peSZ9Hv*p?KK2@iY6Y z-5y`_z+GWK83QGaWoqM1?t$cMiHCe0CiUPVrgk1*MgT`c(I8zOx^E8uh3ziORpkbL z_icITmbohAwJqdT9O*MGp|g#lvu%~k@zUcQ4s{^X=WBfYrcm6H4WeerPTeKZdLqWj@~}fd#iVU)qPpMWHmp^XAbEH)iWYHf~?I_hJ`4fd3!ym zG8$oF)z-OvnN3~Z$kGaG#qu?llUSa&T68~_Z?HI*+f*CBFDrnfzC1F>-%3^Nr|egT zHm|dSgwMv1kNm7iM3&)mIOJ0~J0c|_+wjSVHbNCd`w~>wmh3p4I&G#gzmg(asVebL zT4}kr7tg3L?(6A>d1JIMvvK!uR;0Y8s8(v~iTS?x2&W-A741tQTTuZcopu4^Y!H-c zjdt#JbE?YGOB`M!+@g^3-VpsG;L9YIgQ2ruIScf)Br7d~OON0ai~fy$Y=O9=p>$;V zZKayp*w-fTVr@gqkhZr{kxD{DW5c3@Ly~jXHiVBeya$Q* zzbxJ|9Mr&@7FgdQw(LVSYOJ8#m^6d zNg1UY=E_*&-+Es|D0z#tQq_)N>a;V~=b*%1jrA3TC&&j?R2;*MkI{GE#!wh_xOY^N z8Xd=26&igR4A3~grKx?nQ9TjoYajSBtnE&+M6cbUGT!s#^7)d_%d(l_9*bLjJH*N3 z@=RwVwJ_di?teO{w#5_QQQ}+pfciAv*E+E9fl%5qiMBbkn^IafRgw~k zw5U~TL;}rcm8uL;Z33-fm3k(0_F)25`)D{;b8uUw0*Sr^M6D7jqnjTLr72cv*sJ&} zDtKS^_lBbLgwk0~Wo%9KMF)CsZm>lfwtW)h&PN+!l7_lU?JJ_R)03#bx5GBcw$HHj zN+N5Mcy%M=kR%>uco&Rw#zZtSocs=3cA(GWA%z6w(Sb-)1~bXjjKEXr?;v5n)>?J=isOq_yY#c^rzI^G+)Rjw^Z(-Ry#u2t`oQnoz2tJ6Tp&jaA(cRY(4>Uk5GV^^&0K_MA#@#Ow6s1ZwniYzfJm&4%r4-}IdFmiE}QV2`V=rHLb-0bN7asV7T& z>`gw7tDR!-2L@x-sb5Na8WyCgdLjnbF?eE~>XjJaVyPJXi9zlug@@b` zu?qsK`SA1s1Ba72Qof~DE>NY*vNhFivD~t(r03}RUZ{lqAncF)SZ%5l5SX_z)vXYLMSfzv)0VWJcJiXYfB6<6AN3uX z{Z*lL+QaHVWlxZk*Mt1Sl|5Psv%mjcQ_l>8zC3qEa|}@(H@J)D`7tX$OyXT~UmH)VQ@V+T z+j@>WrB`^VttZVXoxt14t|;d8d19RO_wt9e^Tc}egG*JR*pO0cSuanFVLhBR$0C(k zg?|3AUY;KMldt91?(KQZ&}rotXL!aqo2=%=B>|r*5A;OnsjF4vfu4$b+G;g)pr@Dd zh}m9hj#w);rv`db4Xd3k&};aZCskj#T0QxgroW*Dw2q4h zVJB@({*6JNQkr44Xqw|w>t(;%5cYVWc`7y3Q`;CL%?1AqRee28+VG*C7@dY_rkLgW z%@|#hjf9R3^^DekUzgu*nCBhMNxiqyQ)~q38L~dV+z1c*3%!+}|NcnNNKJQ9I!AlH z)G5Bd#2BTNCljA3vgSo|xuBSu7n9|JqG?{NlZziHr;@uD<$`h-I>wWyQ=VQM<2hka ze9Ra}TQOcV){~Mg#}vx%*QOQ+Q+4I+_1VZWWH)jOxsF6s<24v*i1b0SkcG%9WH)jO zxsF6s=e-wcj$|N{kwwTlB%Q=3#F&5=Hc z4_Sz;LUtpU5qBL@gfvHnBe}?OWDD{WB9n9~AgRc3Bo|qQ>_&b<meOMKlMa^s`+@I#xqYOF@e4Q*O1hMyDRwcx&w)^K)SR|MrQLECjrtK^ z=G(sfk3+0V)s<$J-%&E&{++||%06oGG3UdkM|Nu?BO6xKGzVX)*IU;^ zmxP0088{eLg}nCo>cOF~IUEMtL%K=kjI9xHAlD<|XgCV8t%o^5OD1e(axD|K#z5IT zJ9{jOw@_rkHE-m9X<MMZ^J*~J21#)oy=7juHd>9d=DnU_o1BRwGuXft6&Sb8p>3%H88sm zinS;P!F6y9`~XgY>)~{m4;R1>;bQm^d>eiY*TGNV$8a;0MJrn%8%Q{|LfO7%8)P3f z$97l&?tqQqPO1N0Q0ziuDEt)W!rkzBxCg!q_d?mF^)t8w?t_Qm0r(R<2xXSfmyqEL z^CYh*c$n)Xcm&pk-@=ygDC`5jllngd#W6G{!c%Y#JPlug-^11L4BQ0I!M*S&cpRRG zKf?=9Gpxxhh2TZ5{^jD-50gEEC> zIV=h{L7BpG2r?DkcLA1wjxg)Qt`e{$*VUj*YDtBqV0Rb|GhhrH4P~;650-|q2Vx>z z7DoP;LGd9PW#JB30Um%do8=6Y*(|?7navX7p_c&V&8iA41FOS2P^Pgw1Z5gaZcCcaD4=OqOlM5g0i7nZ+IE<2>0EDeW9li z4-uFM2S7QY>rvPaX21+M5Ke-RK{=6Y5PSy?h95&d4)_kjp)mUd3ZBuv3vf8R0Y}3^ zg?U)OI5-B@fJ}w)HG$0K@U@0aaqv9?C&H0%5}XQ|qTrhgC&O2v53Yqda66m|55uQ4 z>i-!Oe8BWwg43ZMK^qT?z?rZdoCRyb*{~U$2fM@ha1eYBJ^>fNXCQqF-vYQ0z6oE1 zav;}Ba4&or9)^pU&FwpfVhI|z;8IxBOWO>S;p?yoTn4+rH{fINO*jR<1!uzLFb}>B z--L8xd>_O2;a<2Bo`9?11-K6W4nL5y$c!R1wJ-|i!z%DYSPy;#TfvR6FWdx2z|AlR zZh>>)4)`M630J^fa0C1l9)P>yakvNm3_pj?qSSx7RlX<``{4ud0DKT0guUUHFcW?S zXTd}8W%xB*1HXZr;bHh0JOaOi$KWM+9NvZ}V9{dCC4>p^46Iy?`hONh6EuE+?ctB` zQFsoHhCe|$_x2)`J>Y(Z%iu5YLrDM6w-f#b55lYPEW8G&v6(8r$aiHzJ-tx0pAK30zZPxtM!FiB5SiU8&1k8t#a0g^@m+t_Kf~R0Cyb9xB zP$csQVM&+(lVDj`9VWr%kRGtF3oH)@!wN8a910eR`JRSV;ES*-d>cLhH^ORgFHC{o zz*_J;tPTH!bzpc&np#*2)`JycBiI-=hV5VzH~^-?k+8W={hx&5K{V#T7Vs5Fm)y4+ zwuGBtEBFO$3%`f$;IFVfbVbp>heco)7zew;>aZJ3gWX|Q*aHrLJ>eMGSEv3@NAU<6 zi(x;w4)%w8VLCho2f*LqqtH`|rWPi`fv_HY47P%UV1LNFgKq>J0w=UB&1Li>4o8oCW z8BT+9;WO}6I32Eq*}Tp8Hlvsc_rqu588{dI2Is+$7@AsG6utoCVIHgj6>JI@!fx9Bq5i*tVjCK7!mr_5@CUdY{t4fP!F2EO_1r)&v^j=|ccnK!M%dj520^7o0VNduw90>n_6X10?9sUUy!5eTn{0n{vZ^JL3 z!%5Q&83^{>fV}W#`yxuCk48Bd1RFwTD)>4<7aR;j;AH5Av!MZBhpd|Lt%6~21LRN$ z-#!=tPeDG|`!2&GFes6h7J6YMjD;ng)cc%EQ<1VfzdD>#=uON0H21X;R`Sk zz72Ub_pOKJ;Wk(Sehri153nNq6IOz*GIU;H30MtQgw?ZA)JIVRwu3ccFUV>v-(#>Y zoCta6_sxLy;VZBKdo=d>;SW1M>rF9f=gg$xE^+a`yi*n_`Zi6?Bcr)yTd|BG_^1Z_Jp+{%gKCgU~kwH z_JISFsQ-OYj6)+G&VU2pi||qS9?XCr!@+PD90I?EL*aQi4BmpnVQ4v~UBgl^6IO*| zU}HEIc7j>3ADjS(mCL3{Me!sWli;)P3HTbE3|GP_a5Kz-U%{#H415ay0dt|VJWVPr z3}?VZI1|=@vtSE28+L|s;G>XX7~kXBD4s*{3|s(ThR?&d;6k_-z6f{0m*6+>Wq1KD zf`7nQU`Pd;R2U0igEisnuoYYe`@uKhIQS-<1>b_%OHnLGkq_U7U%+?Z3HUC&23J5m znO-d{1mA~oa1E>h*TSZ79qa}_fRDnD;3)VpoC-gI&%q7wO~^P?wr?$pO=xU~+u&ii z9iD?b;9qbjlsRpCU@^ECmWQ9gI&dFs4L^rHASb^22E#AmWcU@F4G+O3@N2jNek=9= zLlj5R_zZprzk|o%C3qa(gp7RoWWwC{Fae%{)! zLzn~`!FsSUYyq3VZm<~~2Ajh%@Im+#YyqE#55YHJOSm4kf}g^N;Styxo`;Nn`fjjD z(a{z~ST%aJFb1}VRbU6$7eNh~RoQUcB0rrEJVSo4+Oot)WX_{dX_$Z8p888_RgemYb*aQxO z55vK*8yo`D;ZQgn4ug-w;X%~@sVGLE@hlt(UxcIJGRSmB-%6MXKZaxAE;tq*gd9WU zI|j$Wb8tNT6+RCChKwKkj2blYuo#>Kl_jgP#IzP7t6_z*99NdGioNEDEQn1-WJ#+mMU@q^ zLOCs4^zLU*mcjmmy&89UC>Glyvcgsz+&5q~YC&lE`^H<&xNeQea#~4`#OvPpNDvi} ze+x$JNq+o;y*umEeyE2q9&5E_5qcuR8c4M);pr$O>o;w;(me{1jFeDM1xdm30b zOFWdDEz79uBC^z4C>bW}lv^NTR|1uc{kMSS=1V~eEI8u7KVW~jAyz4=qDDO*8l5d> z_l6}mFVGJO|8765%#fQS`hhq5e)eSDbfA9$aVm6IW>i%#zu>PB_r^&oLOVp(W6Sbz zN$35-s^r)Iw>TyJv%T7P#p!=oyxX37K;kZOx;O4}PycW3oy6U~_fpaA{0%IGa*riS z|6uP<-2cU5LEKGyR=(da?ou%V^Ih(x*t<7Q5_i%6U-@oF=^yOSo|-04OMm?GnJps3w4_<)4hd9wmS&S zhk(j+mtT?ysTfjOWg`TMhqw#8QFh$^!QP!4@Glnc3OGrf%%kA9BCPv8#r{9K0skHM z|EoKyS}Wo%`EhUDCEo)ZEy>sW<)`GkopyUqi~HG=!t)RI?tUWt4~uu_J040JMI`dJ zR73qwV%w2O%MKP|ue*cuKSPh!v39b!%E(OwGQh(hev8vBG63sXUXRx~?nx`ST0#6m&|Hm%G*Z-%n^y!!!f6n%5sG{iK$a^C%*{xoyRr*q0tn+xPXbJDV~ zTaX%b!QD*f{G$USFxi5Mhc^t@V!scn^bOWS{dU3a_1anzB!05<-o((*c(pJp)Du2- zfNZE_O`DBZt3yM}sL}snwa_O45pkMsu7rlRR=$OLg!<_}#DcdNS4Q_B<-F)l_M#|= zcDQLfErXflZKi5&4PVKbU`bWH%DG5dU0bh^q5j{I68sZ_fz$Z*7mEJRiyJCGyDWu#aGUY3zINCuLNEJ8LQhmea6 z=BK@6?WC}qg0O}4oT@R$-S2jnc8Y@I?gy$>yWQQWw;_An$st>@aSnqzd)(E%C<=;- z#A>{nxW{cD9lS+t-NUNUZ8)gfL|6aWQ&7jZXzGhOVI@?3rPFc~}$^MF;Q5(_(n zbMaOp^73By48safW3RZh?Mx0${mk9QDSprW%)L|}*hGzNqnA=`_PJv!PU2gf{1T9$ zhKxWUDM%kA3z?2AK|XA_I&GwucOtBqIx?e>C!`3Q&?kHztjd3=B{@aGlD-9`-8?`3 z`iEMvkfPYAh(XbhvN9!7OB%Kk`ea>rGOGPCMkO%n zfKk7XwOB8Tf*h6Nx=1a3g4yrOKh`|P62BRT@?Djwv6J;0Zfhe3A`tqCmgtSdtL=VU zj?M$K#;Nqb!jkVqWh9ndC9$;gb2YR>Slv4&-(V6Fg~=bpHfXU13Nw$dR|NsMQ;&uRs04_8iAHuw!e(>!RAI z)$kw9f}iy_YKgU?@pGBqD@T_hoGos(IXOYLaw#`dX-??-wR`WM%(b{5lkT8O2 z=+Qa2QEPO^>k^xYZVX zTefPc`X8UG#SgOTJZ77g>XaMQZ<{v7Nv^4r+q9l$(i?2o1{$Q1Tc$aRSZ+6L$2y72 z_s;fQ(&Rj`Q`-CvHS%_7J)DxTSJx8PtQ}fv@y2Z>+s(OzjssMf%ZOW5XC6VPg^l4MYC&ab&2bjb zk6Giqu7&);-bfXk_TEVO?bkV9aK`y?@I0~t*@v7(B2wvxAgQTVy5@H%Y%cxf%aW@G zll<>q`m1tRX~kT8ZE|(^MD~NJszccd#$T3#ovPew>PrYVR&P-4R%>xOWGk4f#LwJO zX2Ke+n8%Iz#SKy7!4XWaLt+ru>ra8)3)72-h*J5=1{iQ4xeLu5X(}(M|l1+=0!b5(~ z_OQr+prc1B#Q>R(tUz`kN07@%u{54DNFO8%nVmL2?U%fp?gUqHo|c){Rk@q)L}%u8 z4ygN3>shc_MG-~c!rEWFh}AVKqJF+fx1xv&zr_l=345F#Z-%+~w6(-hx(YbDMVFw6 z>U+zyIR$uMW{_ONQ2G-t(~|cHy_UMILMp4vx7?xrJi|&so@H^7c|E_#-|k6T5n1dm zKj}j(BLN#ozyP!KFb~N!jb-|jp1vyg80VKUBgwT4omY=JTWPb@`D4y9<>sPyq`XxM z0;iQ<#y@7Uu)ijmRbEQZ1@5{LY8Rn~C!EDROl@*q_B;NsEnw!Vr6)L?Yd&_OEBK39 z=GPRnb0?hT{mGKh1B=46veufF(I=fj22nNZeu_%JA%`-bbgt43E3O*baGP5f^!eVI z;v@>{()S$TvEqAYs*}Lvs%L$f!z91;tu0mnhsdIfNKjL%9FmH3L53sqkmbm}rt{OD zlq_^TPp)U3lnv1yQMt8^Vy+j^c6E0Pq8{(i~%1Tb`oKwdGjIbVUbCmmTFKl%b~bis(v56zh{*k!Bf`mzxyj zebgNtEL~mGq^O$b3-RDv$4A|kt-^PV4p>Hbz)9=@>WCcEiK$;LK;0ogJsP#nHr!9< zgv1FK`?(1c+{Surp_8JHTexK*w!W#^$imjSn%%p4UcFJ@C=-%LMxKt))c*QLtP@54 zrTWGLveiI*LnApvVVdpLRQrZTk{5+pL+nTCU8@iC)SiZTw-5)ti)z;DLr){aV{m1; zQm0>KrDz1D}c0oQ1)f(FZ;5^8O1`F zjprKOinob4BUT^Xs$dtj%4$hySg`thl`}-GiZez^am}H){*L{n*l(X>l=h-1C@oIn zn=Pd!Qpr)IYC>_&09lb^6!YHl+mdEq$`rP8j7Tk8wS9_>8Lp`+Q@MZ40(2!jtgHQr zhJEQpl{ zb)8K%)Wuxxj2YlmE5PYb8xci5u>dzRhN!yfX2$Bh#u0n0u6Ym*v5=BAU4p z9e1~IHw|}#rqeEp;@_iM(pcp8pQB48dMg@J)OwHx@9Tbp|BB<*8HDvWVLjQ7H{2OU ztQW;SaWsobJ`KR)eW~4vW zJ`0(REJHRRhmebiEa{?y;;4qSL^6=c$UO04|uvfhrRxOduo0diPlvGFO8);5SWWRj5{U~OMjzoID=nzNsm*@}) z)#O7IW=L%5E<5@;2qgcj4~?g_ULSUnykPD~PmA(GF`9dki!4GmAcv5PNDziGND9&h z$v`F}&m-%QeaKnlCX&!eoCCpW)vYDs5^K37_JKmH zBxrtpLoCYQP1uRAL*1*SmyTs-ze6?-7Yk^b1y6jIp7l8EjHM!`Qce^Kmhi_}=Z7cs zce~Z{2JDv5qp}{MjZ;G^>t(>4%6fD*PcO#=d^Pa3x8GO$5i!nOD~d<_9?cqVrtbhx zEhZt-(`No@fPKm6K>Jw}vK*2;$rEvt;dkSzYsFl`AlS$Lrz56kIbOl>qXCXw_XIR) zP<1nq!Pwo6FzL$iNq~LHPSRRMkB*gi1QAh*``89nJft0Un^tbwR+z_QS|Q8KOcpEh zCNNGFSYiH%Y2|o;6?sDluyO<|@>QWR>qW_9;%E(Fk5eP6>XA`_c{OINWh}1`ZX)h+ zGhpm^b#kUwuaaF#?K6HDo-}{a7Rg4yef~I_`3`DuUKHPN2(t2(;U^5x0N0l z&dfZ%DO#HrC##>}v%Tg%?AI zEEbes8rJ1~tSKxBn?cFK2VrUW5F}u8T`&`<_@c|aVJN#g22!+qBVZO}b(Fb0cM%j1 z7yGYQK#Ho5w#_tW4UlR64V;KRD`y-}KzBApZZe88a0+DT-dwNS6B0LH7WDC-H2{vO z@E!OR+zE5xDL4%}oXm8B32-`0g)?A(I1BpVY`6qI3z@cQF2~J2jY4AnBb<*xXpprG zSK4`Qhp!|Qb0!Iz%W#>?XD+|34SA3BF*VOL=gXkE{FX0(=CWI6wwcRr2f$ac$AmM- z63DzU(?0XU9Iuf^AM>#s%P^P+-+&6f315Y8!MC79UrL=oxD&2```~-<5PTmV zgJS!(T3C|LqG$k&lL)IY9yQm4hF{s_+w78*YHI;CLf! z0XM<6a5L-*x4^z|D|`%YhtewSfbxXd33K76a1Ny4nhTJB$tI>Rqp=r__uxLb4t@?l zfnUJwa6kMEO3DtvgIs?Pzk=uCA$Zwuehq%Zb%=}iKv)QV3;Eh%x-SL4Z?2Xk0-<8lB&uG)h-tS@;L60k6Y)uq}KLin~7WM*e##dbnOXjnj%!5IF>^ z5z@vl^*glu?)$wqgz$w+ybM$5-4SYJLew-B!GKBZHA#WD&9j zIf7hnwYK!{M>TUJ3#s+;3%6kYW%{CP6q6!NqkA^8=z^x$#aw#K<5abc&KPxewN^|m zn(eHcH&Bns`zs_^&2Vx~;eqk&X%&WT={(7}cJu`5y8IY(Dflr<(lr_Hnnj0}j$MNP z&9NjF&@|&94@t3IUgboG7L7fHl~k^FLP~XOI&R_*~Ehe;4ZR@Z+JE(U4pym|HoueS5G^roDzk~tGThE!LeHi zM&5wMs%>m%RI*wf8yd+Rdvj+*bt;x~B9~(itb)6a=gT0UaNfEClh-7mQYtxEU=2y^a$OK%;0I@<5$BI_p*{J%| z2(fQxnSB=HF@Ki%-yE^QQ-&;SI6g>)C4{!EW;=M;pT|<+z?vpdvMI}L3Drzxp=U^_MoSDkUdWSCl6$=0Qn8EVE$#wuj_r=gQfrCK@Y=n z`AmQZ%oTP;@d+-O(Qgdp`tnb0axUGTCbmc#;@_YHapcI4bk3A(S} zPC%+_-<@i^xXGRZ@@r$k{LACtwZiX%dGx3GD(-)yv$M^P`xYt0{CKJr{Fuk>x=!4O zB@y@CgfJURVgb$j#$8SZosKNRPEDqx%S{i6`#pEeKBYCo-^dp&2-uuD?m94$X+q^f zV+-%V%W7B>3!=Hw%_NgmUk6vcr@6Aza@Ox*)c_A?la@37D5;#NLS<#t`<}e8o4dh< zEQf*a=iuHuDM-yKAKLjJoL%%gYY-6Zvp8#lv%(er(b;HeOZWvkn~SqaI9q_Td#bw~ z$*cEqMn})}0n`7@%C@=`ZSoVDdii^zYv)o{#D9l79}g}Q?#s!c?eB4BhkN}#&Yr_r zr67-x^+EV^Q7>wgF>Mc$|QC0j86K994>I8zlvt4B=` zf3YMM&@3pHjyvC#|H11n{_;lesNnYkUcZ6Y-7AGwkFATh30M*fXcl-axm!8lQ%+@d zrAk~yThVEqG(Px-AU(xi#!mDQ9op{*kCuDf>DcvRZWprW2U!p@uQzj=LQ3dNT& zTgo1Ic?2ngH>R=bSl=kFW*!Kx8+mufz`n7&P5(j^{(Ur=qF0sL8$lmT_7xCc&@4#H zKWCHOvP>>63E<^Jon21%@rllw#O_R;>zl$+Pj)n zCyRX2A)q&4zVZ_-b~THq%UZ@dMh&y&h}E^!94}c%WX57m9?JCFd{L0Q=SzV}uoWy1 zJ3|V;Zw#yipM=tZ_rWS$=lH4o`n*{(W0tK9%oP~@n1uK!QXeUcbVaIRLweJtRr~g# z#hua(UD;BPYE=_gw8Xp$u!0-bhQv^AyidwiJ!s7-7oW-@cM{hHbF1emXD4fYwW5iQ zu`YR%3dP%|uq12_r9^NN=ilu^7Yx2rT*wyT}#@|Pz71Z zP=%V-Ikbjh^$rWX--t8uo+4m+zZr`6TcLQr9g6ompm@I%iub#qc>gIB@Ao)VTo=5z zdVmGqe~z(u{{@uT?}y_3K`7pT1;zVAP`sz)ncjZ`#rwlhy#Lmr)^`c58X}!Ax__#0 zV?C5$ns`RpuqS@E5D(U$hN_zf);`N`f0sIT5!JCjO?6?I7!M`Cj#6eB*&48N5 z7#-B%66k~Ek#=)4uy9Ubw$A={P;;3$+QFZthV>TM$P+FTp zP%@%0w3zQ{B4bK)QyvyN5gfKFy3m0P|fe4dVzzMcZDF`KQn|{eh0Pv4(b#*XnvOi>G+ur8u%SF z^gC!&;Gk8318Etg%O|Z-d>R&{HEL>FOufsJbnrI!pvh{1VFfHbWLoM|U`a}x)hp8+ zSF94(8Y@!b7)tg@iE9g`#I=V~;yOYpah;%)xXw^Y9D_$@iR%ib#C3;K;(EX(uqTuf z*9%IC>kTi%N8p_j*Imu+8CokuQb<2d?e9ej2Vf%+jSSOf$AZXyLozJ;(=mDx8a2RqZ4@L9*)0+s10W?!K@?8al=HwZ;9EXW?Hy`g+L zpwsa5W;lRrwxlsT32Y@}b`oyEf#@?s)$AmcfJ3>i2#3M?a5!uSN5I}t`V7P182C6G z3!j2n*(el>aquljQ|@D@2=f~UJ3pA6gTrt#`fR9Rb_&?8OZyu`3ZwT83zU3$18^;TlxgAp_m0ff|Pvo3&1=mBmVQ@MfecvPUm?U4uXrI4A{Q{WuSgBoCjZpZv~V8ucKIt#xl4U zz5$QIH{mbvE%+B)4#QmLr-|GOa5dLW;2IJw3F_(=y zcW`|U?uNg)$p1YkLPM-C1*PC;TvvrOF}?;+p3JSGJej-0{ct3dC-NkC2+oIJ!=>;W z_yLqB@-}z`ehH7k6Hp$;7vKr_dp3%bDA)zwaSF!5(=Y{o57Xco*b$zEec=x<3!aD4 zDqMiG;eX)k@FH9b~weoW?x#?m#iyYQUV$M{W}~{HY}jeQWGGKz*|3wRaJH{K3V96o zgUm?qjfKo@^Z8&AI1kE`b`fMQqHjGc33tILcodd`=b$`z|A6t(8Rl>#z*4X@tOyff zV<^wt*03y}DSf?BR6t`8l;`S`P@b#LLV2#f1}nprunOD^0R0OcWe4$8ypH<;ZIMR*~Hqd$y==`aP# zvnvfgsyT8xLU~N}h4PrnfL+oi{O`V z2|NLp!fWs~7)&qxbr=PC6#L4_f$49cs14tQP2pRxCwvzUge%}=_#T`M--k=!O86dJ z1vkRga1UGqPr>!@BFu-*BG!JJMd3$Wmxmw2Y#Czv1VwYW0d|0VT=xxvTj5x^4bFty z;Y)A_d>`(FpTJ%4Gx#Yy40pp{;68W*ehv%K8TkUn!TqoXJRtSI35tVgw1;0q*^u)a zI0znwW8o3_4Ez=aq}Sv74TeK! z32TGSNLZNbvM>UsKo$-AQek#+6m3wHfc;@491TmtXJ8b39+rad!Z;`!cE-amU;;b= zOT%AbBD@Wmci}4>NfQgBVG^tXlVM|65q6EF{#QaV5RJ-kBCGSobu#bN7YW2I1*;SQE(z0tvkHFTojpT%z|{meQNUD(Dn8D@H(D|$d&@K zO@XZ3w>P7yhnX_Vi0F$)k~^X=sglikM1~<^CJ_^TNq__*IVS##e{vHfk+O$JbEHx>f5syBb0{gl zpT2nhzx3}-CE4sqN9rRI0l9tlE;;Nt7S5|vIPY!YOzN{NbcAv*CG`?hiR8bTORDVR zXWzPT^a5|GT`VO`zy94jTgd(^c1-P9N_N_j?2lSvE`>*Kn*=Cs?kziZK$S7OUj(FH zNLlG5_rD1W$xhioNm4DPa~#qIxi=>y3ng`O%Q_);BqbseNx5ZGlSUy@mO3L68S!6g zi$q%P`{Rg2tc7H4CB%-g+}rL*KSXu~5{H3>O&r>0ZSP}tztl>^{wXn4?9@oW5?e`; zcp|a2>$ap?a;E>CCc`ccQX#}hoY+N0^z67eH^d^>I z{%x*LRHvTNgH)eQMs1d?nOj0E--I{uBw+szwQZA8E_weBdmXaVdxU|p1jeT5embh{ zwDl9b5~V2X=-{iW>t>^ji=97R{dTG+HyerGegQTmOKz*xn_1F!Th4H1TZPRm%FMN` zsGQGOfwri#Uc-N!>s8fi3;wZ#s4Hxj8neYH=M3BBRGYsHjtU=vXNfYYNWxcDHgPOv zyIYz|ox+y?xV)<>d@HL~5=l_~T~>tEEe{6?cHU}uy|z}I|1*9wb4`SQG0Ro85vMNp zEOjl~rGDIMl=Cj~dm;8EP)$BFM{4zz_b{<;__I4njo4;XDF}P%Ho{IK>|=J=tHTSG zQWv%v6$%20+K!!a*ts5HCq`v#Ck@tT^{Z+=c3i9ncWwPteZ1YM8ou>YD=iWcx4QBz zH`EYBswM9*neOVh2Al4n(sb2#WoUG;hsf$`%1S2S&D+6RSKZp(X3q{I%u?4>?wzdF z+voSUzPfVMPEpUDrX{jBTKTXPKAe>elKK*oYicVN6J=qA3|q^*tL_+`W0JI3Ddo>7 zosA(oxk{*?b{d`{I>Vl}Aq9#LKgzYssNtQ=3Jcp`h69Ok`eeOPK{=SSi%ek0SXbUY zwSE_OBhPPNGC}M+&5!Tt*mb@=rrA{);;?l$bj;_3NibqS1f9Ute`RMz&SkZImoB z{NNqCL6+TKyNwpwRkd_C31Q1y*H>Svy}PL(U$MilgeVE2b~%Eqg!q;R2eExYW;s1t zEwR)&87vXsVyQ_|v^s@am95EcFZ1@Wx-&=}tQ{6l`qidAMhUgNCW*Vbf)a5N(~vB7 z5GEWos%BVmwc@zpRxx{xivHz#S5@1+#EUI>T~`jN@q3Ba6?Pi7<5h-u1)K2-mUb#w zr9T&DowpsVazt6q)RjmDmp7HA|7Ic|v2q7jxO2T_x6>V*Y+h?J!@~C&vDlqLG@t*> zh=>i==qLMs>BF;RvZq+J=5_kDLdU*OsnM5l29bx*M{$X%rIVr3XdSE1mk9~YJTBcRTImFvd zes53gGfLG6w408()Ct~=@Akv*o>y3LU-5GzE-KL7WB#bbin$6uZbS#inaV1nj5n2S zMVVkK53ZpWANib$l=O{te z$Q^xNttGs;{YIR3u3ulm;LVo|$(*VeRsHuHZn>93_fsyb9KDln-YKzjMeMBFZ^RUN zh|RAhJb5mZw){P@->6z-Ux0q1r5|^|Xh(G%aeyU@>^SXec+9EFPt@#1msizsOkC_i z?aDZ&Tn7#NL}4CD2Qes5n?3ND8gtNSUeHi)#K6PX8`oI&-j-;n%)%^@ynWE{I?+;v zHFsmx@k^tq{^T+B?AJz{kPm^7|l7>vf7$D#d3A zRtxl1=|<8-e`VAq5#zqXxr5Gx_qba8l~GlPUwmbh@Os(&+s=PnJ6vjY4teE1M0-%& zGE=u}(;l=r6zWz>ny^B6^pv2=k}royO9c|S%i2IG=EYruGrF z8V&Hu5jr!EsMFTf=SPe(-YmZ#Qs|{IdPHeFo1-2Hn8!Ybdnv|JZy!kW zyKl+=U}Cn{@0&{V(sB9fTRJYbmSm4ST-=g9@$6(Ft+J|ilqLA?J6WTH38c4h$5t&&WFgqwC~727qPr` zN)7#v-A``$ZQ6~ip?DBP%doh^FrQ_?(vBJ`hbOW!SA(`pa(Yy;W9+zrT`IC+hi#ZG zKDwvB4Ps+~V@6P{q1|~v3{M}MH9S4bY@4Mp7;648vm>G_JAJ$)Z&>9yiFBPN%JGvhS6lmL50C6#3 zMaG`JV_4WS^tUwwPmo(7e&;<=KrXp7PNo{&XPw~GxNMGNcl6aO-=Czh> zQ}6t0^m1m<1ory?9}<2uBAf%cGWQ5;^P3T4HIJpkqSTgabO~nvW;8dfrcQGVRUN-0 zVi$iiR!F<{(pBS2ec5p}@*1I;4UXSg8=ZEg(C@|=y~2t7slOZS7)7l<`iJqmVO1E- zQPbKh;No@m3eazz%I|f<*sD9woOPNLD%9v(Mv$)kkU##Gu|{`R`H2Y1CIJy_BlSYd z(307ODw5Isf~1qn?-bI5_psqeF0u^SfE+?DBJR!(M*`9u>4Qu_<{=x9LkQy=j*>`2 zqzf_{nT{+$K12>6KOyd}_|uh_{!|n_kjcpN$U0;nauEsY#%E3>6&Z~9RA!B!qBV*U z*UCs6Bm;d3B+M`kJV{a{qMCk z!iu>JBGL3GRjx)@oUnE$;l~QTtI3|2BdYDhF z85VD>@*9<)3BqVaoiMjbsLP+2&Mx-Tsu@Z;jxs{m3&@RObM&%P3AZZX&|LR zlXQhy4H}>IQJS4|-!@l}7N)cv&PcT-CCnWj7SKwitLo*Q#npwBuo7aYR#-HMtrb?r zJIwE~bakYu4O1O!g_ZXfz2Hv;+S06rsTsAx9@32<^<}NFL{}J5n{`3ms1;VuJIilX zq9z?ZkE%}hpC?pD3z-(?Ti7anb7`zR=34^RuG9{TjPe9TR+>}0_4TOIb?z}9J<8g& zOddG|Qirs7)QCD^W%R8V)Z$z2Qj)PHgO_q(h^Cg_bQf1evh*VAa-A@bH<;5yBpdC9 z)T5TN8Lixe6iHjRx}?oR+A934o~%pSDsak(o$d0(30LVSg5p)lO*|}4)uqG#mfwPS zC>Fz&QI9*l&aYicrElU+PtTzsOOHkZnO2WL!U-hyl6t>h*qD$)s2g0O`90=r=5JQT z*lt#v<1fXHcxaAuD*anGyNuKitETD6=kvd45XK?wvo7Q}ZWOjn(<}U(uQv&MN7KdY z)UbAXgG>2;r-rT9nttqWGgA8zNq*IkWt8y`kpsw8#M6_ii=-lbkSt_2vJBbXb9Gv% zme(TeZ^meDw+I^shCO8Bu!UwV!v>-Gu8I7jt-{)BRZrpaCQ_^yAtEi23}iC05Lt!n zMouBud#z3zqvdtd6GB+Y>pIn)?Ls^0rJbT^AIBzf%RA{FZ`B^wCYh4ol8z`@^BAd) zbsc-F|j`)7Qx`lhp< z7*ZOadgD{Tu9Ol#`|d2qABke?F8X^;3GuHk`alB*geV(BcI*~hOik&kN0$z2BoU^m zMIw5W)krGR2gyRFtF+ER51E_e73TK0xWePW+#D~_SF5~BH*I<-s}(cagwu~w;5wt5{h^!4NZi)lH`onB9u3YMYL5IQ48s43E60TRmjaCy#Rd9^BQd4#jUjI)?<%;soa#7Yhkz}2HtK~5xcct(; zt(D6|bC7W*zkUU05vOEoyGqWPde>|DM=LpXO()SODx(p0T@9_`9MjaCA&T=i#SeZ` z{g!agKST~7R}l|m!wE=Tqz5t@nTIS#4)u|}H^0~NGN>NQh|}36Yy+O5$2vv9TI9Cs z)U+^9{*nxxu0t)WKx}zT4?=AYfh1Jc-RhL3VRm{CJP{O>H;5V)w$vIUw(nsr6+1|e z#$CNZdOYX}y!vaFCAl-w4%SjL2I*zI&%J&}TbkoqYNKeM2+)>?M=fd|tXJ~3VTSK5>{=saR@Q`BS2e{Ra;#N z)RxprQLU|#hU%@gWh!&1UMA#Cf`4XtkZPZ)7gwu>>Ls0WWp0Igb|^!}*6QYEDt4G& z#zO$Eptr3ks_;teFZt*&-D}udrBu!=I+cq?1i0HH?v~^3McZAgO5xF}=y2TGTK97| zaX9X9;<{?Pn<4JDi#uEEe(sV-kf?WXm-$YR>O4ZPVxTbd^nSL#7TfP)dmpxMkI<71 z6#r;@%1Gk00^1Qdk&IVqmBSeo9;rtdw$}YZNg72c@8NFAyJYkzJvkgj!F>)^)o06a znS;%L1t zMJFkf6unQ19$#%19hylQ&~+?RZ)4(FiOJG6mIq3!!hI`$UblxhmZ{QXutStwui19e zs<7eunLXMaJM*y42mnGKU@lu+CdTKS=Msr(RtroXz(JeVz zWgO`xJ6r?SvzBt4-o7A5-xCue?Ro~2!{hWMrzmcZ(~B2*$M%Y}5CAhL)u!+DhU$@L zG#7pj8IQ}_yybd7WCi`>dW>2*UawT(@o6!xgK>MyxGhe4K8_xVbIn2TsmJwXFN%U3 zmyBs3&2gkr-ydWH>$6Ar1U*dit6NRbYvR?E33&AZUN!$HNWC>dPYOp-;8ln^y^y=+ zR@#ezQ3^q*N_&xecxtjHoqsGaL@|+EJ-d)kRdOSD>j^!{i^5Esj9y5{jg+=NINCfILaI+AIfI~*HzB|lx|Vj7a!uAt zcnA2+?1I@ys&r)R@JJq>^s=PZ{~cgO?nNW{oYRcFeq%E6$tOPEO{|cZtfz&eFym9- zQN`Ot#ZJ+is0uIh6d5u_kB(}r-Kqa$2Htr;X{=tEqDN|t)dy2_dlT7Z>eduIuS+>; zj_2i{)E_D+LF1mpg!18PkIAb~Qd&?H+~OLA|0sq{#b=5cwl-pXSDfSn#c+%y1ENeTd>9aq!k;qJmh_aFyA1MK zr=Z9emsFMh6cP07xD!G7`jV=aK4m&h%hDr*6D%F+re1zZ55h_n8*m) zOvXN=Ck3P6HK6(^zC%2mp%pO~ZpW(3(IIIC)z>>6N3?;ikljJ5!E`;zKw(zj`}JZz z5Zm==2KrisRX^~s@OkQ@D<@y$EljtI`=DV?TD&m^DHRHK=g#_zGBX;<doT%&MsTO6P;9Z00)eY}~~cVE6P*rO_BG8E5l%XIX>oY_3FnyC+FQ+1lDw1aG7 ze{nWn6q>1Pvq?tSXLq71&!1+h`W)(7Gu3Ji53R}prf$UKV{H0xQsFM#cGJibJT_LLqT=NlT zY%K&>XLRBCu>hUqjb zJHc|7&9Gu##I(QXO?Kv?DIi%5vskk--0}Gveq?1`xKiQCEV4TD;Kc>jdx4fVQ<{}j zd$KY=Dd1U1ldJG?wxBc!%J~kXUHyf~)phV>;S4Wb7K01TT#j4Fr5k$Q5*O8CVx(vb zX$HyagM~DM`3|m33dzc~h-UD*BUr9qvZ}g>*e_qm)|KB39xTDy#q1o)gpsV)FEZ=o zDBz}`PnQZSsO~Oudt$KLneBmCn%wk}T*;J?ta2|V-Q%_<2^N!3vby&?XJWTo?5@x9 zWbR_x!#lKxFFxU*lvs|Uxv<#n*Tr{bvAaO{)lcl~scV^>sy%)Q%jtwA?yzwGry+*x zpv?$OtcnSaB+6v*5^Y|gK!;Em*^t@)8Ck^_52V|{atUQ%ct&o2VJLm#tK_rJqGE%) zlsujykMDo#QO%apW^rV-S?PyOv#r!k9aie5Vx?yPCKl_a>fT5m+>oBuR3)9J#}riV zJQcrlqz_AL>dLOn7de}j`ZNs&GB7n&?UlQ7_;Z)+OQS{|q2#NSyGUS3D2!sr@~^4N zP&As$ipKW3&65itC2y+!Qe2nA4iPDNQ&n-9yCaum(lW+uW<(?AGbo>95}nVSL7G`de>Ag>{%EG?q1-E;Yn02HROT+H9+?k~zdrM*%;oOTp~xH6 z1L3>}C-FZVPqBg;#*tOSl2G&PgqoXERcO6^bOpI(LNgkCZs)drb#|4$mF_^

_^d zl(cYVSMHcT*+WAMm9&z!@QkfNqDv*VuzGAll3psSEgT}EOohfjpWBv^hb!HcvWi%7 z6>R1jBkT*_8WyYO{#96V82^n@gq&aHuIR4<=}$^+g}D8L3mx;-^Av314k3i8*k?Oyc582_@{v{fy==O zAg^ngXMLOoU%~$sI1&8Wm1e!i%gaGzg?Bi(hLb_w<J_b*Nat!giU}cc&Z@!THKG+xk2cW!& zd=^{?asx6gxB@dExj9{zkSx8T=0aGq%4O zcpZO7@CMim{23es{sPK@o_E2?;IBMeA6$duHv&$B55SAyAK*>!G59n1H~1U)PiD{c z?nGCd9LAZ#z)%b90agP$flq! zRl$N_GcX$L2^IoJf-xXXUyD@_Hn_{%##WcMgd@RSk?rH*=7XCE76glfabQWXI9M8# zElF9hF<2gyyjKLdPo-4`hk#W;`T=J*P1@`(uJ&wnN7?pSm)2dif5#n}RFf!@)Kj1& zRR@%$>VcA!99|(wH3TK8Bv6u~@0&@n=G(-~W?65gI?OXqn!^>XEkV)R29(`md$24h zl`UF3;;&%)D}m49uLE`k8-d-yreJT7q0oFMR|?n{zZ7sFDAhO!v_8)(kL8zEw>P=# z*f!#&XRa1Pi6Ojq75TzJdE?9vvf^}9WhX$#;6;L01fG2jwV z8mj^;gUi8&puAZt&1xOk0hIde1ip^Hv+aK#+=RamxCI;xz5z0Vn=jNdGMg{bz6Qz* zv<#eXZLj)hi@U8ZHtqPW?wGWrH)qR$hw#?}0;Bl}W_%0|3z6Yj)lA*rf z8T|ch{{ZkTex?fTLvRxK5y;4Gz7V?#ynufPco94xlYuB=gw#GIfC19P4?qe35d4hr zuWkQj@Jsv*BjyXSGM`C2y1e!+;f2AgU^zRy0(c!iZC$$w$~-3Vdw{p__mp`_0%(5L z3$frG7+enXg;+|j-NR3!<_oYtfe-Ni3H||=bXzaJ@}{Qt1b-v&FOU}>wSPd~Pn1dz z^17h;e(OBYgWsoH@3orqhh$(f0bwwv*fq#5MtX)_*= zZEE@PCo(eXoZ@c;&cUB#`m zd>Jej;BRm98P&^aiwKa4kq9Z^68x#Qzb~lpzW^>%AMA4X)#dI{<=u=92_8z|Gn4sap33zSi2KX??BbdTHqbKpV3Z-9ruo8a5vKcK{OQGdtq zGq_lzlZ-B+C^sk(h$GQu~!`DCf z`SzuWv37V7@B-nbZGTNrXXEpfjUDXpPM}vM?sY%b<;Ge3K6gxF1o7hSOOOcW#$U|# zOB>Cjy6$twn|IM(A%0px__+utZF3$bZL_Hq1!dxj2it&&pv>;Yz#(99a6DK7oCTHy zmx850R{R=y5AFxcfbW83!B0ST0>SUW^59+Bzg55?ZKWcZ2do6fgOx#jO|n_PfK9nh~WGid%wDfvv$V;Iq0m zeIzK^lL@^m;fuiTgl`A?;b#KZ1}N`a?&`YSF0A(!*JTLdVT2C_!@*%-K5zsW3626| z!O>t5a4aa-`9)9`Ad+51a3X#gdtL)&#TW!PfXtA=H^8ajVQ@P5EjSbWLlzWsa7b63 z3(DZh6lz|NMPMiVOTgaXGLXfawgOxOt^(f%SA!?OwcuIsb&z8`v`rv$xwZx5EDCKa z7z1txWxn4Dc9$-@3&&Ujq$IL&-HZPv+dlzh4i9F42f$@uCMaF;ZIFRUI|iNr-vt>* zG@eur(yO%hLB_xr6nGu~Y1@AWWb+#&4eduz-hs6aB1~jq9R_a-gg%g+BxO-@?^9e z(OLFcVi|B*L7C?#b^;6G?+lg$yMQuBc2lzsxr^&^mv#3ccZ};*^}!*&;AGuWb!l?? zl>9b9XMCnp>yKyzPAO4ta3KCXHcE|%zZf{eP6FG2xq}@IrV>6Llv!^AD2sd+cT<*t zY4}%zlRT`eHsY8cd<NOAOTZXVfox5+ zWnfisIVeNh3a|yZ3Y4|=YH%R9#*;=4ajYd^0=N#G2fhxj2RDK{L7rm@9s=2Gn|)4d zgq?=A1HbgSouI6>CHyhSax7@j zEJ930(&xm_qC(?dP;ieOe!vbt37#bU9Jmeq+~zZtYVYG`M%1t)1~s|>)EP2KmfhepAokl}4-i{wa14ljGdLUk65I!V1=8WQ z%izc0H{cH->+s-T;1#fdhxs2Y0)7ux1+RlN@HFiQ9Nh`{5$prr1c!h>fn&j2APq&k z4bBFC1~b6_f*ZiQAeTY=6?_Z4@6l%U@iO1z9|F3(mXS#ZWi9Rjr-BBkybObU94EMu zfL!1T1M;PNEeb3K z76!|L>@b3rL5W`@4M$M|8iNU73osEBYgI8Y1uOxM1xtd`)kRRORcuj$eBDng53UAF zfm^_e;4ZKdxF3}GhrlZMAAr?B`T9(CFwLN^*T4}8O2k57ZT!W+I$%k#9#|V}05$>n zI#93^DDk_3jqncz8-p)_O~9Epe=f*YDYy)54sHNjfcwFg95xty7e^}segs>C|A5be ze1=kM2S$SJ!4hCckazX9P9XP+H9kiaYz%e<1+lCPDSH_wTeVa0k0uB-sZgA2e3s_HxLXkBibr_I!3 zl3pcTRwij+L2wc%E0QUoXrBhk=3@pZE6Q15GjI+lE2MO_=^gAv+*mjBW~hrlyCPi& z)V+7yg>~+rtGuUJ4`mQrQdtbj;JySb4lV^{&!xbc;BxR8a0NIOl&X>S=^Fg9-dPKZ zedKlUJ)8fb?Y{`p)y&y#6L`nw|0?St5qM+=JOQ`j{~M%F2J_luYe2?Y{8%@&U0?!8 zUk$be*-!^D+i82j{@{MEHf1g-8JrIuA{?`pb{NE*Wri;YkKteGDy(TIaO@!9BzVe> zAcOoV?zOpB>T>V?%4v6E+4sHLG^y{8hzGEo$ft!iwR?zf-KuwKcht!>uE?~DM3ajB z1SA#hGf*m){kwUR^XFhg{9k~wp7!SBF%;E!Mi_!GDaybW#ye+IXM zj7jER@*a3zD)u)VU%+?(UITvzZ-P=Wvc7nT|1aB*u~~b9KM4K}ZUHreff1DWQa@h& zyFmjy4dwzdqiKHdJjge=g4e*j;0;#_%zN%d?(XMQ-BYgEvPBGSs;saX z9D@m939uSi3Y1+uM~ViM!LlmueRuJ2o&zx3Z=BU@D#8uGtprMMsH}#)?~YEh9tGeV zvkY+Z8wQnORF+?LqB19HH9$J8_7o^9zS^KQ5a!LcCU5K9YA#?hL9xnLV`0Vp*m3!k?5kAv;OpFl?WV16n_;$e_CQMLkI z@mB=-2wAW?*d443_5`Jga}UGZ8gR&}xsG9$2#z4!{KgyRV@(2NyWR&(2m665!2aMS zkeeUD1K?0lF5z(SXK)1gD>w?oeyEKG!>BT*AJb+y9()!*H%)^5!B@bM;H%(dkokmJ z8VB=Ja2+@Ul=TarNek`<=YXyhgAb ze{UT`V67CZ{3t;cZz#|BW=AsfLvpa?tyH{+Le2@_>7(qo0o`eXwsE>0J`*fU_-wE|xDc!kt_5p?vX`ml zt8Cf!SUH)7n!2DE0yw}p_z_qiybd-1Z-5Qe&mXx}xb<9!OY5LAKG7r7lHtm%(G)BN zHUsN{Ex}j8*5G_lvMaNK_}74Kz|FRQx6OYKY)kmZw*P|dm&u_$;a`It!5=}^cftEC z=}g5kOGto+i`N2)Ca4aB0`gSA)}f5lb#} zZ%{5{3fK|s1C9s#g0e*%2yO)jf&0P1;3;qj$mFK6>@@e#l8dYOIR)CB23yAd^oJlsS6}*cF@#b_b_}FM#RbYv4RkvYi2b0xkqEfr~-O<`VD+P=VCC#%kG| znpc2c5?%@Vz|~+umlkW*y381_6A%MRdF8IsMwM~V-CgIY74^$SGP(u6fx@kzOnGmB zxj>2U2e;vu?zID~5AFn|mq@&BHp&#b8~-$L54aS36Wjsr2akZF?-+OhzszvrKPk7A zGS#e4xQ{1~y7Ydi$HX5df@I_fC})_37Ea9xGaq=74})Lzu?qOYliBxE_YXc@9$jhm zwfo()yLE`f@4IFercmHJ(wBSE@1Yt{YiJ}i6WRfthVDR~Uc6KdB}0QCnZP$fN1&_F zL#R-1Hc3!FXd<)`Is#pW?)PSF_ouK*fjU7$p_$M+=nQlf3QJ`?ff_+wps`Rov=ur5 zJ%sWx=+uVVK_j7=&=KeobQcQi%a{W-g8D%dp;gfSzR^q`IBr5=j93X!ZK$0(`KhOH z4)Lh@W85+7 z+~=M`dP98gk8vlekzaH0k^c*iyoW09s*pEqM?$y_JyY~p?_Hr^QEV7TqVcD zT*Few%WzNMvL4~Bq}me&fngTRvS8Dfd~~XknzV>#z@;Oh*JAty6m=>bH>Q7bDlI@1 z=9ZY8IMFw(pm~}G3a)q~(`51K6zRtWkzz#sD}3aLp%aD<9^Ri|ik~3I7w3>0Ib7bd z&;wJc7WT$+e@}a2SDom~^Y8e4y1xI|(cMyIqLcjP{htveF+H%yV{XK?H>t)=L#^u} znaKAqnSO&`G}`%pS2SFrG&j{g*xYT$NSaWv*jo zRR@T3#^j0*rafg{@ycqH6?5)oPo06*tBIi!)UrPc%6Mn~UNN(4xiN1VMMv2s=$QIq z|4>VXEu~fT`(g->$`s^rNJbCaZE60pgW_=VQ?g?lJ{?EwN z*Do_bq+j73<&-NPPma{2M@ni^_$unvE1qbww&aSZS@}@?RI)EjigZSP(ltUqzSv-N z8)H597@xC#WJbRWF`SWKm$pq^`-8)ohFR2n*MgLP4mdyv{@uobu!90I-pP6W4uQi&`p%*RP~f^zp~H@E@Z z3v$cKe0=c`_!jWj4P;;-ZnC#~%+~1WSXTf_$uxm1B`CQt97& za;b&id!k&$)Q0apr4!rpWvo;!jx(+07e|XLz{QV|2Ei{@OI4qL?|DmS*i-Ybdt$nN zgVqQ*-+~3eD_}f$6)X#014Y*lU=#2L*cSW|><7|F%x67rfwS?`Sc2=opOxzePd%N1 zNj3bz6VvB+!fE~HqmGTizwpyI%|{+z0RO>HTQS>F5Ole$2dH=q!F*)<)hW#Sb-ARLj=`BXY3z39B%y7hrvzgH`l4 ztRk?6!fJNgsc^Qi*i9S5V7-}x^}DdxU>hS~#ouvC^|=F!J-0Cu)|?!ykA;;0>m^u! z?Ap2}wB`Y){F zu(rag{$Ecsd#aSmmc>cvyQ)vr-k+H&OAx%9nA?e&t>h6(s&X&HI33DJrM_cFFd51O zuleX+v_gXx8RDB0yc)GxkC!(a)Z)z?+>s!z{o-mQu1mOB2j3%(%c}xg07F$3@Tv9! zVQQ2B$D|45QhNm=)Wt2j95~5m(Iq5WRjI;}qBrk)%4KIa_8w)%l3|>kY^WypoYgT| zSfyco3Tt}~)-7RS?=Wt`iu~0n)!|oIm^_T%V7-!q^|r9e!OAtoP~YcZ75fbq1`;C@ zR;%Bf3TF$e0<3bd-h}n9s}fo=_E3SLT$PH%tWM0r_nk_*-A4%@hB8{hnv>#kT=jQ^ zRT)+nShw$c5_NIpec&meuMs^B!r7Gk>8WMD1LCF&z4icsDhL#sYN#y_oNf2DMxKI8 zfA{$FRD~Ts)ozJn)UF4f8rgOJ-0vu;MvU4hNc-KX;2mLMATrv*x}Aen=?_>nV6B1m z{2xxK6|nMPPBJ!SC)w){XOhN4gliFFC&HBnT`=VXe%;`c_z2rHqHLe1AHn zTK);E4y=D*jrr44vM>&_<4HT8$x`kT#70z;2w9aFW_?GQTFmtb1z5U_=xKDeN1le+ z_46_;e?3^0rdcXg(q!J_Z1u=fIy=%Wk;gJ-yo!9}W2bz#$H-$WGp2^*_lkV^$4>dP zMDjgNq;%wed+cm1)tj11%Pn#$blV0|mBCa`Y9^8M|UI(CtBepCMT`2CpnjQrE>x=5T#S?2uhEX&(}bN!zoQj8sm z`-d<8?WvtzTjlCSe_O{8I+}CNnLMtPL|w41tv*jdPv16RH*VUhYr=vg_2f8nwzCW z#kw3?)LCNqTN7h@NX<1-6XABMsq01!=1pT?wwgyd)NCV$|5;*O2&rj5o%gwh=uS1o zbZ;>q#!BP!>4s|P;VAMuZf~XRx?KU^-wytxkdlkjb0?@fxxJ;bBNgdmx$BR5BSEH0AAEVlNz16an%!cpp1V1^XmVN}Nv!>Qy2A4A0oDQKuck zk?#TPn~=O~HuCGjopt&#k$gRgbUl=be7T%;+ESW3_GiOA)4nhnvnfeLgtH{?5Xpye z+6bR%S4Vm-XG!Wtpd5!7Z98S^t{E4&Y9Uzh~l}MFPawWp+C`mOx@))~~7aa0Y zYUiBXKJ|*ks9S93cHzJ^G?{zO_C(v*`Qn+GKW z;2+AN3<|RpGv)EE`qgJjRj20cZLx z1B@fXi1f4_iQzR@z&RYfO$jz9H|viz*z_H5y{704K33}+z2t+&9>@L8>qf5;H{q> zV;3=eFA?K;gg-Cf6fRbf#K*(xZ40Z53&?!+SL>h+t;eyW0yQ7hR8P;1N z`J@cqA5P}njqLPC6Up}qk&Yn0GTJHsoveE=nedN>GMBM9cOm63 z>b!365y>};NT*TqOPn(Yb&DcD8`h5@`M?qe_?bE64-m;Whe-cL{z_5j=u<5o`E*$M z)9ov`UgR;)INHrFBKhVLDJI>NFQk5n_g2p?M7ac%aL3MQ5K>ZgDHFu)1m|UVok+g< zL`p^p)flZ_Nbpw4RuY>Ce*yeH@S7w$d-il;WxyH?Yj+OTufpQypfMR%;bKmyUd3Q7 zg0%qFj2x`9!deXL2&~_VIXgn#;*^EEi^i!?SxzcCVnlIgS+)_$x0Fa9BL8V|r+jP) z6C9-3i(w;dKURHrJV9_!}70& z)j1?TN#y60a>|!0jr^iVh2-~&{Oug_vx(%} zN~F%nzggZX{|Hu|H(>R!<(YurF7KRxU#NiaHe&Qccu@s!$+9@??WlGCpUPd3CLVH`;Yx{aL{qALESG2X5#F#(7n>q8Y12MZP_AUJbTjRz+_!F$sK9k>t0N z{9E%4wf4^l$L!j;609At4!{~x$(tC!VdhK>Get<_f_d76H_mj*sng~+LN3TL`qno> zF39l~g}n)8gp=Y-G@a(zWMZqlpg5bXu(!DBOcZAc)7ic>%1WBfQFlFsy`@ZNhB!-` z&b{I+V>&P1^+bnDmc&GSK@o{#Q>u9VF55lQ;a=cy?{T;R)9JSyZ3;wbou9_uhK~D=_wP3Xc7j^F9U8v>_L;si6yqu|LSF&6{xy%<- zpt?6YhTF}UC9L1Tkvz)-TWrc)gX-Sm2=}*OR&_JUH!S$Tf}g6RxGN8$i9(Tdo05q& zOi7@i>R!Ve6L>qriX!(*WpG3JYR*nsR>K<=7|Zi&B5qpcOy1EN-tvLKs%#OlY1<%V+Wi*EDlJt0sAUiih4LG08}NlY6qJw=kvr#)3bA zIA@jg89i>ypz4-DK~tb=EmNRPEmP|-%Qwq{O;+H$wY;1b?NhN&d5aa;NlV|c+e%hz zJG?{xF@s<3|1T5lWFq=@5%ImJNdm;;Fia^cBqZ~9wL2) z{42GcbKfyx?S*w2){i+@|N@2=x5tBdj6{G`GC zI^KM`*vkp#0|#~SiHY3gwHBXP#e3I9L~P(@@J0z1v$rX7L40EAHhE9PC&ul(^$-zL zcD;JuHadoDwR;;!^=z!?%@>Y!noActd0$o}DpT*Cz%x<;*Gd zy@TDlm~(%58vSCtJ->$g4mBDQLF}~z$Ec|d$%L3_P2L{iiB(p3OB=xwJFLm7&9|7UNBmpo{awz=UX^cMXm?}O_GTp>mL^o}g3HXLKK}5`yX-&NSbumgx zT1%5j%CbJXcyd_Yby5|QQ74u~GpWVI&@m=jNu3a$SPk<&LsHlXt)x0VLsDW4H1nVS z3?gFxTl0;BX+{qiORtrzec<{RF*y}7! zC7PiL!<=ZsYSRo6jBpljhw!krspHKM!K!8j*Jw^K1~hf0E$tztIU<9 znK;&+F8X%Se z)vyB%5Nm+d0H=1K0m{zbY_mr?AR?Q6x<`MVt-X~%yN(3Q9^UL86FVZpw%tl)zwl&# ze!LSc?P^C-VM{KJv#c&VZ&PG!Cq&q6TOvC;AtJkKMEdLOp{-OJbtYIg%cjWC&WOnV z*euIN;mMZREX#$?q{1#(#Xm~t-We$OEyTUt|O)pLl*E_U~Gq{5!nN~Oy41hYA{ zM0z}ri0nemid-x_*?5|5;KcJ(GJ8#nSELI(*;iKXLM5|-w1PKEu@>mQ?8nTO z#)lFr@jb?S-MpoB*@&5?t;Xnqgsls%7CL6>?^L9)3qMf^PxVLu}xU3J;BSoJ2sY*Q?e6Fm`;{RmB} ztj_L3Mf4)J>@dvO!Cu5>Q(?v4(Tmu!doUBYE<832R-W?pCQq_6Fy)5!hR0?=rS+y5 zvfwvGE=VwIe5+|Z=}ps+#r!|7dl))W=uE8Nt)v#DkQ7Vw%-t#8k6gMeo74J`Mb^fd z+xvLuM(8XeRK4L$GO|c86Wur*?W_wd4Ht%^K^6eN3`b6;duzfN;Vlx*3~yeZYSyQa zhK}%dN&6~=xt-rtZoM`i#5500gqA^jpmWf5NS===1l53ALxUhWh-MYEAG!eDggiXr zPz0(CwSxvh@+9vvXbXaTeXIt^Wg9zsz=c`OrZ4y8a7 zp~cW1=nQlndICiaBOa6t^?=4h3!oj)Y3M5S5Q-X3Jg7O8GQ0;0aV&=RKxd%q&=aW8 z2yzIuhWbHMp;gck=n`}v^0QX103|~y(0FJuv;#UbQhhwaTQqIeC~6401l@uB-1II1 zB||-+iO^zbKXeYd19`>}2dWSCfaEE=#n2Au5_AWO;(??JP!DJ4hCorCT`o>z$j)lcIu1sV^ng7!mSKzE@ip2MjCwTAjZ zQ=wJR3Fr&x2^2*EYD4Xyu~0g+2RZ}YfjmJTdVv~2{h*1^I_MyD8A`j)Uy(_a8tMU! zg_c2kpi9slC~7hpfjU7$p;gd+=sNTSsxXDpLSvzHXg_ogx)1rMk^!g@)B_p|ErxbL z=caP~ujBAcBNI@4s1r06N{4npr=jc66R5~^G75EqhC=DkM(8wj8F~Um%^(ic8X5{s zg*HM*pv%yGC~78|hFZ_0iu&Q03ax^UK$oEVkbf4Dpk!zeB(FhkgpNR$q5DwOY~n!4 zP!DJ|+ONhLWA`AAcvP~h{d)GSNFAmys7 zHz;JC*D7@_HqBp2zBzQ{PgS>>@vJU&I${8yyt~}XT~xi(%qXZoBIvjT-EU^()AK*F zeF@EteBtHHG+bJFb#W!%Lu}XFsG?I-s^JD-j9S&)=n`&~&7~E!_BZ)j7_HqDrB@51 zoSU4_Zefh>ke-(u@RN)zpjm8$jzAZno6r*|DxF~mY7V79y7zUf z@M3c!22lbXjQGG1J2;kLY5L1lQU{|jx-PyO9vzopP}wLL4{Np~CVGjP(ZS$@Kn}f9 z)@ABieXMg|bTIsZ6%L-)>}Ztr=aI{H!^)K!b%1*l8#)?+KqyGAlC+uS zX0g~YaCGo;^Xu_Tj~ZbGmOCCIe`#dz(W(8gTd8X)2K(zyMifz#IvMdmDxhkoa@Ep1 z8Tr&8aow3=_~S4qYstB2QIw{Koe!xU%1ojc5epw|2gj<5sVMe$Hu9m-teUG_r)A;P zFI6))6b)&DkZ#|Zs#)exN;(A7IiuAov;>a)Xcb)QJ;LNso6&Kr5U)*Kd0X{;JBsAV zZ$`P-nJaeQA(`6@PJGUID$wax_VvwUDeUMDec3Fxu68{~6Us}KkGrM*gF7(J7La-- zKHu-0bitcs-}*tI!}AE_Lm=U{dKq^h;kK262*}l3soGEHgiVi@3PoqpZs^R9&fa%b({4uSIXF0z;rMt**ZB3W+nj-{N9^F-5Sb`A zs~@O5-HmeI)ep#rN*!qM6@(k^JnX6{ckO|8J5#~#bcGWVhcrX|Y_*y@*Og>{cutgd zM`;0+{(;gSMzQceYymzSJcy>(x`*L+tx=;g4L1zm zF@HfadEZv10tdODeYqzU9tsLIrzZbuPEC7JK+gL$I{l%B_cB5^;3@h(;S_?SJyc)y z;<{=Nt)ht)o7`w?RiL*~++{)`)uy*m(H z6-}Z2ZssJJP;-%9x=yuEp_J>?C<`(y*lWSX6eBv%I!7gq9Hw3y%8~Z|R2t_x6_-lm zT&L=!(j`+LWowrDTc-x68l}Tm*ue$Wy`fx&9jQit^e zxmrb#yl*R4sfW0+b*irsC>sir=OIr=vve)Q;*WIyvZG2f#jCAXd&{%r$=8n--F!4H zdeuKZz699M$mbsPL=7J;owcL8T6Urf`;px^5`F23db^)dF7VP5t7M{4+Ue_R)Bq}@ zQ5S=E=NK2lLlLN@F);4%feTe%7_WpR)%pp3IlKfrk{hfv zj*Juqlo(Ugg1|BKHj0*wMh*dWR%x^ zny%)IH&}t?sQ>>CBC))@F%%0wdazM4fFrBf%LUjhqa-VzXZUvHX0>;=r?6VE*dy*y z^*N${>tF_#kc>1(M37nkv`p&4OSJWcMzYQ7!C9A{v-T)GNajyo#zwU(`#H!q@s>4i8ZH6&&Zc$0EFkVj_Mzy(h zt16^QWy0TLRp}1l<+6EFr7|&5-ecS+xIBz;wZDTW)BP6pmz6@ya5JHr!&zx`@L0-a z#LQ<#O7ika#F@j{A{;Za6PAlfwGC&)(R^00q?z9g{>f749l@Z;g<8goWC>e!kGFuO zaDLq+AO|(7Eb_W$R%OLH%1JP#?`>SbE5aEli zj-|@zk+h>?w4=7UxJo09lDTnYY2zfzAet6j=iP(kAbq4AOAb{cXhfNx0u+a8H-Ya2 zE(nFIl$pGQuqVsQN7BN00Rc79iqE8l@iAf3y`VC;Xmi`);?85aFNiy@xC^RZDto;y zHiECw@#`}ny0%(#atiLiEJwklt8Gb! z^(H8S!^a|662ZlJb*07{aRD5rU|j@d{@P~t6n{8fP@f zUZgdCkqnn2!?*G=uDocJ4dBQssc73SAK)qO72)mHM|f_$XygwRq^3i8fd$VT#)>dH z2VxyOiL+fLHDmqMT6jfmo)lBcfZPJwO7JD4w#*uDzeIjYlb;I#U48$Ok(h|XPDl^j zFV8x+0%t#vn^1VHN}NN3DUuNurW%c>vUaHUL(!Nrp4IXW)qgyFcpJ;mP-dk}JM001 z!9TFq=7k!_4z+itQC!^--cu~dLUMBPcKoY1Jv)JAKpAq|%#LV%^mqOQ_FADJS+vQL zXs5L#+G#C`cFMRM@7l>)But>{%cifruuIYA)buiB%5O>`f8$4tR`pD8dX@+ zNJOpgh~WbU4>Vtxx>|+JV^vKKbJs%r&|YL0UmkGBs~Yndpk#Vgo#q*ZtPgLdze<*W zwe?BCMC~qXsyG2JJd)LonJML(Ppi54s!?B>U8&b-cIC*+k41IW_BErd7Y7@UlZzM* z<@+hF-PUw|;yM+xV-Y5bPhK->XLtPkX|#m$C@9X7M-osMkFX%@m}UgRLqSC?^VFr+ zj9S@(#}M>YKyYNdu6|52DtdAJzofh?hyvc4HFluj^Po{N9EX{O|CwH|Nkp$i^xud+ zW0FzTi{t+#y$+L6P#Fc46Lj^;WYWX&|DT?F3Kdg@=+D`)ly}VthJ_mr(7Le#wvEGm|#xKV8XsBUMw@PQyWh6u zC3P7E_9<7Hut;-U-=``vL6AdvAna5 zin=%&&Ze<6x8+0C_@+Ag9mYxd=B#w(ZL^WAi{uzfvY`5Dwh>(xpPf&RTX-5vP(v{Z z^5%I~xHVY(OB?s4c_j^PyX<&s=Lwo`<{TrC7z&b&-a*u9jm($uwOHm;vr5#(7kK*R z$sD6vSjR})DpD(*?A1r%%cZD~bS^B89QCnZB_6}}v)>wUgU1Xtrj-vk(c67d56>%6N=tA%nMdzl0i|2jAZqjf-tX>YI0R7g1jI`@2MPBkya4~sIM$hC5bdbf)W$a{O zJp=17tnG`PZR1yAHHCEqR^cT^+1xm?+J;+A+Q3B|Ss}vj%9M+Z!Ep&oD^6SQjUjT+ z63TbkjxXhtOG~^ZMiXh01(%|`8M^;dksK{GI%Zec3RwQ;uxc>{iInPjny2q?E;T|= z-;2CLz6FuaRYG1Fb;{zfuM;aaaJ*d_zmPPmM;LwzDP+e5kHoE9C zRJTNR@5;Jrw#-P>#nE=VQBnmby24zC)Tk3Q_CxB>GBHsz%}FMUs=eD8q3e1G3(DregOA zs~xOOu)bbtgx-09RcaNi_OL#I)pnIL;|qn=0oHG@4zFSu!C}>l-EIEo2>$eH^4bxx z5=_zNrM~taFM4!3o%N!H_%RQA8nT#!^po%(71GsycH^8_pg(RjFl&K4TREbLNlIO{g2g7abb}dN zY*H%0c4K~0jV!lVrBsUTmhhnEPMX5bW!VPiqho5*1|vT1n4{FGe36^P%ms%u#AE8( z2KFwC9Ql>XIHqDY()W+4Iu>-bU;+@6L*3A^rYczkQ7$Xi#f{YCG4-uCBacl=R||P11h0gBJ>MH~Y?h`dSd1 zt@6KxE5Wpa$zHUA>FvTzx#Nx|IA+}Ntb@d)u*cQjZJ1%QRxQ78Bf)MY7|}pi@!MG? z6LCf09l?XdZ zCPp$o>w_BWYVA=YQElDJ6tsrLW2o`VRX(kfrm)z$yw_UX=h;UheI=t!boJCeqmC|) z%5QQ@ciPN7r-z2jde3R~h!%RI?WACaT z-gLIga{H<60Z81nBdUuZV$>M2pV|%ug_fxASzYTrt7|p75axC4S>7|pd2_G%o^|U% zX0rFJTMuG4!YMZyWJpDW++>iwBu;KJsQY_dj=uSyw8(BO6dgOSHlh%NnzHf$60$EIDn!-DC*jjPJVzTFb-2f%H&g%-XZO~jXZue z^&RQr6)=jo%Vc6bW9{3|$iBU}z6j}7r?}m5?!$0DyrTpL>aqL{r7cT~GwNO@Q%=wk zEH!XO@q9sHm3)xpPNvP1CMZ>MMg@+Co9pRq2g&GQGJ3HYUFA9tEZ;fE!#CpVeHt6s zl?faGlyC?g1Z5Qf71{?X=@7|QVZ|-Ek+EO!1Iv!P@Q_hg*6SZ1;xfO0{*Uc=YUjD! zrB&~JhF6t&n^qbMmwJ(hEzVjq`-uT;N6)HzFY$^HAnTBIZ!>+LRaM8EL8-a?wB@&r zu(-31v2f(jp|W<*x-Msx>oAk&SrunN9UzAQH;Pi3bIplEYVE8Vb(pF0tjah{A3bXp zCZexdIx)0b0qVwKtke@(rb~&XQl)X7RpCcy;nPCTC_H}W?Yk4g(^uwRL&@0@*76cXwfHD^c^T=v zYUVLSL*b!266dURj~_ECXZQKv(c&A1mLlz#SB`T(0!LPgXw^PaZH}{K{m5~F{nFsM{4VuDHGL=s-GK7MpwMaw$SfzS$#k)Q>w^nNW zeVyU>1oq*tY*9%{3iz=)d4e9d^}e24?R?tfQ+G~K%((X1`IS-iW0g@jB3dP!WD2Yi z;;D=GS-3YpX%x!+oE>If4%PmFUR2FFX*?tC{F9SZ#t1TfyaPk_Nrr43W@Uu3dfv+F zd20|0zC&X^&xp(t)%?0T;XJ^g4$hz>SW=O}Pk^ATOd`!IhMP{aAiQk{OW7sS3+l7e){U`J@3K>k z!s?OOSsh#Lu2IOccSMkm^O46|M^&Evu9ij=OTY1dThuCU0= zgzt=1E_baPna9324BgH1QSaR_K5-}9&Rp@M@uJ(!<3{;!8Lx-;zH5msQtK1g6J5Av zEO!5TH*>&kqn7UGS)eulHI};nc#v7^7h|EzegAiL_O9`)o5x*Z?-}p8wTGGC-Q)Sx z@a5)XC@w8GYa*^g%5O#y_vSw{U;B-LP9E-f`+;%GegCoA{5zR==}G3xe;CiX!fTn& zFu1gfD)AnP-+5^4aQpsIEB-WYgNTldJ=q08<6wvUZ>b#B3DMn5qMcy(@~ zW>$9jzI3_o2*`gZDKcl)O( zH6>QIw(-8QI;OPDSK@swT;W*2%oJ19y*xgyM}n_kxMlisX-loJltjWT1D8u%WHqy^ ziM}1CWomvg-}-ROOs0}Z)jp9LYhBz|CLH^c85S)qJxXO1_Z8MLBB|ZQX>FEu$fXst z1geyvDT+0ydkJ6HaBM%OWJRlwTqxlyqKnbzmlBlIvg~ACoJJ)nDE1pQza+)NAd`8x zq^~6PP0;tHe1~+gQmifQdsk=kpE z0%$*U4!Q$*GI$6MY6J~}TAL;>(g;qiPp)a7jP@yF#f;vG%p~cV+=nLpBRA?!D zs0%a_S_bWbEIY4P_CRN#hfuy%D2KX0BcYkl zR_FwD6?zCotwsmb1sVy>gw{c)q07({C~6IF#6Yc~u~0g+XARf?430aHXD#gjstt94 zMna3B9nd-GIuy2!I8Zxi5VQ_D2;G4^>yd@pK~tes&^hQjl<#$F3F-okgw{a^p*yb+ zLU04u8mbTVfW|_Lp&igU=sKir+SgTS`x>7DD&p-%=Rod3(eJ=@^F9e zxq4aOG=w`@!Ziap7!d3tdlM;01mLOGZ;Pme5%&(tKh zGpD+#F`aL|pm|DGxMds3R7dCO(cBB#JBhoSH|Od8z)nXLB)J!q`mWy0HC45lPg0!3 zXM7e)>c1>x)Ux?{z5qd4IhS4KL3Q#d$JUD3^q{(Sl=r3c_tf*NGbG?Tr~(T}^Pnob zfCFw1s=ZfuX3=BDym*CYoq`K^;_{%Hwm`2O$en8Gm4&zLKMtx%7b6(XXJHt>ynx&m zvm?mLS2l$Q)#|U%kuO6JLq|*oI;PoCWXUai%7ZF(qPu~wK$O_hrmEE$6pNS6ja{j{ zVjJsER5vqpe|~&+4O%sop{Zl@^n$JowfA>&pP||m_Sea}4C5A}gp=2d%P3j9P_G%l zkyRs->LIg6mM)@fht#!GJVBaZxhF~EXk@viDpZOceq6U6^O1{iNIpSPSR}uc+v|%c z-65-_7cBRei>S*(%9R*iK;>Di=LtNp)0di)ia~?aT%*NYt!aI;YgHQbA(gsVZ^b3v zxtLmVO(N;A=r?_RsOE(%(ju4B*JRDALhhw7x2_ zpsRr)_S*=5R)o+-{6)3o+lV$Xoyyj)T>b*8{?!P-Zu<7R+NhNFm=Sxt=;uJoToGRN(H`BWE?kXR!N_2~ z+84YQ5#{5nfW|H49k2FXR-avqDDLB1T}Js2;9QG%%4corE~^IL!TAMF1vnAo{SC7? zJK^~6!fF12RRt=eL7qtU%Xbl_v*N^kkMup_v_!hu_YsM?ab(q(rq)->#hoLUyIhvU zNs+jZL_Z{Me;*MSz+p;Avy&>}jg^;qD80h$Ruit1CB9NfR}wKjBP= zv-VX#jrsOQhFw2Yy<($F)S=dzE92t>OE!8ulX^9--kR8hXFx&%TtO3Fk4K z%W(erk*dX!L+w4)-r)U4f0{ou9b8tUZX(4O9gRmw-Tojf^gbw!MmT)H&4@jRzMBzc z12}T%qu4=zVb@|6_y3Xh9`I3BTmSc*X~|3`AwvS`ozRgYouC9!Y0^PJN+`(t|9$6^mES&l zt-W?H=j;}+gmC@WxZ`d}cYoZy@pV|5Lkx{_7wta)XKhgIZYR>M{szMn4Eu5ZI*RbO*YvUtz$ZULaP(=+Q z+?p-M*hRVF+pwMvsUzQh8#dh`Rbu3&um%pP0S{uZcRi|hw&P@%6PLmwJw}1%N-gF0 z%W|GeVJ#gL+45Vz3yaen6hzhg`>@A6Mro2ux66F?sFEMT20NtS-1kFRnL|p!pFiM( zWO}2^VPhS7-YqBhcU(rD#&td~XE~6Mqal zOirO;mJ1auh+-NwKK>I4mg@}cEW zDRclj1zm!i+i5wWmQYV<3?x^Ntb=w#N1!v%)$O(nTj+B(TPoBE8Vuz@%b^X>i_o#> z_GB;AN@&DF0_0NL{boxy%ja|P#Mjs6hr^iFOJ?Wj{8_%gN#i!#*C3<_>E1|N+O>e1 zGuxLDvIx!!;Z(J20d-zDkHT3A$I`9^RNn$$hL3v>-Oq?`q|<-3YXNl-nUKej*^29L z3o0vFKs8`BbgOl6js#uXdgqOuiWX^Jc(=A4g2wY~^38r>n=GWRr)^XE{(+wVsT`37 z)KBOP;l@RG(*rJ*GS}DKg@J_7dWXcQ$#Z?N{(%RLpqgJA|7IPK1k~xdM2Y)$-OmQ) z{;ORKsBZIo8TFn(=8d3?wOyp2vZcCddkHvv71l2#Q|+DSi}YWx_zaUz6sPC;Qv8=J z){=&gD$ji1-5RMopSWzmn-QDx(t!F%I6Y`c(+(L8 zY4GJns;IRgmFn7Kk#DSrnn)}(TYICCI=0By(;; zCHGQBJ1q5m?J)|MX1kNwR($ES%(vYB)az=eoLY5Z8No2hiDv6y1T=Cv0o6;uavu{j zq{A*TNFM&VoOl_zquJUS;(-;2OUl#c{^TLq^eEk>wBdMmZl$l2LlR6Mgl0YHODvq< zMe2ynRtjC9wYvsI@1U85IzfY>JZLqv6*>Z)gRVi*&m#wQf+j=7&=#lyIsttJ*>>_` z1~r4aLSvx$&{}B6PFo|}0Su?0OOSIH@5WFTGys|m$=x*TpxwL5{i}RGXlwe^C^;0G z8dAXlc@Mt8*14(!A$aLI6q*t88k~Q@NvUhErAiNl`useR48}XBylH%(a(joRXdfv5 z5U#%aKxOB1IN~^nT+xH#X?7j;Th;E>qyj-{S>RL}G|NJ! z1BO{&;B+o%#=c~RuKbFudrA$OWllV62CEf^D*tFkbHgyl4Yf?*FN=sL-Qej@EuQ#-zu6v?SUCKwV;@#C1+-6u}N0m%=|f%#}ZBRMH=sBY6)m*0#x&G z;^=Am92l*feDt5G#UM2YscQQ2rcIn`-lpf%CHEkrikE0L)n_v`ceQ|xMj)A`ZiGEF zpD*0Ym$H?tJ|;AG%-2$Y;rV)K=I~T4G&5%#GjeqeKl1g^W3xZN@}B9g}sbdtg^fK*`j}u*ADGU8KlRv=K=X zp4uIkRw%)?uHsVQ@`jF5gXI(@FG!jC;k zN%>*a_;AV$9UhjI^)wX!heZ8yvWQ4yI815t$lYNoX&%aksaEr}3}6W0|1l^l z#Yj5lVfs$Jq;se{fx1_)O1)r&T|`23k%RNJ9;99PeA0sJ_}n8ds@C&qjYeFoilulw z+*p-yg3ZUO&MK-5D^^1Fk7UD*#TmP0EAnt-DGozD97v0#FS;3SEX9$;!YE5|q$&?L zmf|pO5u-FaTp1sViWLjA6wlj1|7)x1;@jZ`TJzusGBR!f`7?mPMt`ZPKRzLUoRPc+ z@R}{3=drBJA5lI+tL8%5ntd(4k{z0@m(T83{RVSP5JO%0D=i-#ki z`TeGqd?FAJMj8tQMoLNIt6PA^nL}#zcHJ;jrbwkW?6cq7g>N+!qUa=NO}boK4bDlj z)&0tdx>=w`N`cDoXIZQzFGortig8I9;T)tQnwsqv3BF-SNQx+CBh`W;O{&)MB4RO! zSgico@Ih^iV6}48B4S}$Ni3uk=SWH6AYtz0)pFDt34Y!ptzl)gD_cZS>ynihww&Q~8 zB-E{iE*x4QLHuc9}Ef$mj)Vc_6nVQ-ViF9 z%SX@1C0e9E>D#I#mr{_cnlHh(K0#|q6e;YvYU~m{`1(H9bxSB-bAux3h|s(s^3oE# zF0m+-<|9`&PD;S~uGBJAv!zf4i0UoB^gp@k{8HV^lQ`9Pk>{$oWm=DhGPIFV)NR4D_WLA> zGscdRg2CTlWZHhO9$u!^jZ1_tytdz0<*)>5l;m)NOTLSZl3Y&EFC`wOHzY0z!6;b^ zV;meVz04>h*D+z7Lbhq6)I-aO%CDoz{1=yNk#VtjwFj>z1ig}MmQan7Y_6xejzMs3 zG4-V)o-uNw&Gr<9U~5p=%;r%>Hjh$zHjh$fHapeo6`IfP{6TFW!|IDHvM*^BWpDy| zlF^g+Lsk4Fw^6V{tLJYUv=;T!5{**19cf&ett2mq>=F`Ja+uhy)EdQYL7Ak;V^^wj zmu6dBvEf<|cQlc_3#;8h5m6kWi%gl$p-)@U5Q#_&to~sUkuow$9bKvQ&NXw;yifR; z3w5_aqMJ$04$#&2H?dy+=&}gPC_D%M@#Xqy7hXr z5#!6LKBs@QrNm91I5WRMT^S#mpv_U?6GCGeh|OFShzG0iU@aaj;dxy!AX3()CXUwE zw|U=$dW_+z9O;+) zJ8L`6tk-ti?ISLhKfFO}p*dv4^yx3$J$YuMcEy^-KH_O@lUB%D{{Wj9^c!h0+gNQMU@^XqtliY@^FY>( z2MU7EbA!)|K~{bTHh|;7mxA{DK)K=eU63Wife%4esRqu2=;B`9HnwnEGpMoZ|EzW} zsun3NKff*0R^Qf1j4EoY)+GD@CZlcAxZ}LyJfep+9C14A{r97VkSAyRK`Tq&xb#N8-;au1q&XvmHww6#AXlQHsr&CSt zWtN}c_5jp~C^XmaVfNU(`iYOC+-Q$9+hOI;c10DgL8pZMQBcM{kAdl63D^KsU?*@L z*c)6AN*ta5r+^#58Q^AcAy^7N1U?CF0=IxtBhVAW1uXi3{|1MHUxE{Kfg6EI;MY9gAAFty zexrtL=N^@=YX5evmB(n(G>)q%yQoDCz2dMfYfCcxj-yWCA7EGT1}IJ1pWqPC<}@zR z)<7wXc5o%g3z&XAbSU^V&tC93(C1W>p5x3yy-}+O>836}r#bD3zm)&{oaVJVr1?2} zi1s6Kr&ho4{Rmv}J0c~E-)d;UZbmmy09ps_hK@lOAm<+1Jtzwr08NI9p)F7abOE{s zrM^HD0u6@pptaBr=m>NUx&}r6ok^XnzoQ5$fL23Wp##tb=o%FL;+pJnB{`a}!(}~y zHrw@u91f7i4bopVRuKYj*# z@x~ZqlVikM`XSL_x=U6Ew|b+R&m28t?AWO@#*WVC#n9{$HCmkDPdK?#$4?$RVA>s% zC!$_m*{wAhZFFR2Sj~>|kfbKRj9{3>+=;OEHN)C_YM)#_z=^#KR(2q_8aEw**M0wZ!c?+_c5*G~zZosNd|Pz0O4s&PBm^Qn!Tv($E=wnVRf6Bx$6UI&)KS5$D9!sli<>$`m&($=B zTlvCLormr|#&=3dj8NHTZWUmvZ}h~;hVN3y%+y##Y7idVr;ClkDIUvvhSjZp$qshH zlb4NZJUzzh#%!&1BQs~s0^H1nFu!2s*Uj1FY<@Ab#=nPk2wt;xv$G9<;jA;x9>Li> zoHeUn=FQvLawNU@#TuahzXNC6i&fprA;}#}QQH_9;cqWCVw-Gh;-{(iI|8ZL-rIlV zor6aX=$GBAf1m7rclH`UDy8a$dV2CE_~H(ZS$~D z$e?zhP%9`C|GGjgYV)rx)C^0b)31YLx0-&ZDGML}sOka9 zeENO8%WVQm6qoJ#g9^YEv0dKClLBv{u;~h`TP>%dZpeq~Lb}Yl3%y1l4vocqiBm90_&@ z=P=5WmxsU-EbakW8Y@Hj0FAz_4|o9V2fhvV2akgTc` zrJ!Wua?ntfuKvsjspT>1pj?0?cP$mJhA-~dfKulE2Kp&ueoCF3w0RY~P_e(AfBZT@ zjb8+z!B7FT8rlsVfv!S62Ap-EENC#42d#p(K!+g9Z%?mW+>>i*0Qo!(5nqmq4S^ey@l0G3$ zmFj>WUR1@GV4YPR9i9w-!=SaaXB0oIr#n0Y&H2JJ4kE|++}&)EL;d3Lr1>#ai(RTZ z*@TJGRO1M7hJ<<#d15OCl+kvwarnB$F z8K;Mv3nRCvkC0(=kj;G(J%4&UcUMKzi|d_m-Zx!Ozdp>?ovyv2LuJ3WRx_4(d|*vM|pacX`w*-*;Mh>MGwk=J#)Xxu$1>Qz}UL z=GvY$n#U-W8b?Cwo9%kWde%B9ROMg9dM>h~O>!&Vv%+KKmS)Q`c8cXCcv^alY^bz5 zAa+KQYql1KTx244MtWA-xC3gL*=F z&~j)ubOgE#h3-WU)D_ByRzbU=BYSNQ+qu1KvTK)=upVviKO%e$9%E&5k8#Elh?`$$ zHW0Qkey+6zs~Hd3LSc4O>CA=mTM9DCWMCh}Whfc~F*Bi(u9SRwvfSe*Wq z@hhz5r9y;YRMseQ`>L@L<5lI)WVy6EH>_snjM2uJy$()}Kur+a6m%xdA67W~?h@-X z)@^n*i;~!xWo!UEVxm%Bu*Wkn(Z^$qTr0<8GMI_vneh;viwt^XxFqAM`t)<{EBiSH z(ZQf^)*s(F@%3S^5TNLpIyTYW)~v zQGNG)jtI_N7h&~%il?^9->2{5&{vn7*oV)p@p&p9e!I_+=EqQ(nQqj_8XF=cm11Q> zM2yF5+GADPQAdi}GCM3%t=jL1^~+n586qhMv1ri>^ux`bI)ZVr10pY_XQ) zjnmX^w>xXAiq}byix#FNc$_-@x}%=|@!Eze@j*&gobtb6B+#fgNFd&U-LKYmst4a7 zfiP4ikjTcXgKx0GB3=?lKs%&EngQ7c9DveYl&mLzDq}Pd;4J` z(~ih&h;ynB4igy+m5~wI1VyeHr*h~k*OF786bOAwGQtu_$-D%W`IaN4rZ>JS>=LB} zO)ad=MKpPDIT}k0HoZj*+7pB32~PFaTWqGmP#FW>C0RXqknKe(vV=ttEJ>8zG|e!p zt99`@=LnmO5>@l=Aqg%TG=%$hXX$O=s^-+^KoceU>>)zTaB$9Wpl4spdY)*#YD&|N z~IbsNCS*R%{Ez|6i};=Id(W`8q04#?qKUN%~1LHcO4$P$Ea_b z?Q^x}B}Y{GsuPZDnuBs%{^0wLZkmJqFaP8N$92u22U0$jItW*Jy^kILa`cPm zeO!LGWf|BB7)Cdd2Q7!TKo!s_=rZJcm97Np1Pz9kL#5DO=md22)jiqUwGz8G)lDbl zo;5<%wR@B8;P>r4>?FGTHbYj>9P;ke>xhxc<{9DZ?l8~6qx-DV{7P6R*|)r{a2 zH>Wq!Z(7Ni*T{JNAdN)J=@f~oOwQIIGi8e2$iVZ4jee}ZQSj4Tx=gkKxds#g{!OC{ zU!`n`@91`U>)H2>Qj?;oT@@~GbX-f?oh9&QF^~`$k(H*1lJ54_^Vb_=SW7uHO0Zm$ zr60$t4OAQ5UY3#&zv40KO}97QUmO${EhyoWiGGfMWQf-nveMwGX|=qy)Z`Fvq&E+Z zsYo3dqaLqCfUu19oHKn?Cu^~HLkh$_%ReezBK(99u<+I9t^_|(@Gpk+^W5+s;|PlKL3A$t|Y6GKtz8@9jLnb z(93Ae-D7+(>}64G%X+Vl!=+aHaB13`MLA6-&5fmJX_n%gChMwX@Zi(ZB>nYqgP8R) zou;qPQ)9xZ8>@pJnZ*c~tZL9-;5Xph|D=U4u}M?YlUOQyBHZglU3j#Y!H~#BPpm33 zl2mER6G6RbAG9{J4CfIz=@Wt1PCiqKO5ssFMRkO?KdE~-g7P(tRCx4$^?iibT&*}z zwWHF2kHN36;PX~2NI!Tku2@a%_x_pXHAn8Uz zMV{8p*;3)<15vtB_iGqNua9YWLqcx=B%jjd2pi6|j3il6BByIbRarOl>(;C=CV3LM zKKUAJXY|$E=`5~h$@jy4Z-oD0hVW*jWu%d=uGI9#B+1Qlmm%U{+Y=O#(jiHiuFm^u zAKLLX&vYr3(r~Go)g<+Y2YF`Op*u-YlWS6$|7~&Su5!0Q+xJX-U(S*1~%S`C1l5F3~)@qw>_-QQj8* zDBeKLC?ROekOGzAw$Bi2wJ%9Fn?!p#^;owsN{S>}hRT+Lw>sL}47CTvO%7_0%~0P& zd+Yk;Zd6e#nJ?k1qu&^yx@3?kkx8r@DX7EI{F7^uUv*TGG%u?#`{gQCaVCis>&^lH1DW^7yp0#)) zNm@rTmn%NnGJ-lYPm}l@txbG#iO=PH)$j{@yz<51@N#}tq$C?N^%AXxsPh+P&o$AC z%hX>U;qjX}Zj2rgiBP6QGR0s2f$H(gRC{8)FW_wOL6s z_4vr;23Z7kK`cR~-E@zdrJjlP-r^rMt16VDB}NZrNgT-(6I|JkSxpWlEA+D-Pdvja z+f|`-8PgVX`kGwFhNN*N4Xv^(APSY{A&sa{p?br#TNt}^Mv})Ht4_yx6YSs3QoTI% z0+*ju(R6C-c zdL#)Arj^;xG*EkzyfO9$HnnrUueLguL{_wIN@C8Gi99u&Vyt}0REq{GE}5ZD1Jw>t zmk?27lIgTVn|Z@!C?pD{^fpirCDVE}uoOI5TTdC+Pmz<_-#{Hq_GX~!qM^~1;;qM1 zlN4_w|DZWli79Fu=eKK;En=Cj(70g3Q0tbUXu1w9@W_^VQE8-uB@K{|8OOXbC;P z{V$r1)*+%a=XE3WTrR3F>Q!@ZJ~O+fwxbkcUOc##dN<{sNx%XdsZ^0G=xDBcV8@2B@Ml| zgivWyYtmJ~5)sHKHPQ z3(A?_yc(+o8QyM{h3=llM2|x0{xc}2(h?aiKib&qZ(v%P?MD+!J*UahM{bh-P1Nzm zv`kG@_OD?vB~85MCbfa8NfWeFyxg}g3MSt0MB2A`O}u`WZl(IR=hTdqCtT)T$OF|y z+_)(u?m>%G#4Qx3K|#0wQ__^(f&+?zd(I;D_ATCqjya2Ls!=CroIfvjM(&grMtdaz zZK~2}B%xX@HCMOSwf z9Ps7dihe@me!p0)ywy_KE(!xz?(iilqNO*hvXu9231bP2h$U)nOUuyzpfHxgsIf#X z{Mmk6|_p546HH2dZJ^6ovnw`ulKv&vWYM9j`0>-T%SuX>CjlE!7dvhYux=;dAO zc%i_ic6DVLUZA(PlgAj@$Z<9L_TMwu*?%f1PwwM=SF_Whf8W>J+GF(Mnl0N9>eSEM z$w9BJ{!DUmp=3Wo+N! z%>eICJKfde1HJD{Co^@Bx0ij{LbY#@cc`5{1B_QK?6E4ysSgM zb&+~^DCtgX2ga+^`*1mDQTc86Nuttb>>NgzjxSatUUG08=5TMM$Ef9+Tsq5=S=DE_ z_mIb^x*Cho^{wB{MtJk=R69Ln6(a~4RZTRMjPyp@sa?9Z#_~Xox@{!UZ?dHP;gQ~- zJ3FK-?s|pHDt*$MSa?m|Hu&AR%fM2KqwgO!TPoBR8V2Pq7ruCsQ(0r&A+6$e5u0pB%Q36ed zilN=m5$IPa@&EyV21CoCQs@Nq6%>7tP7@jiL0>WC?8q{9e_?j*P!Ub@SwraDrgII2s#6WzKN$$A7}zp z3~gw|zrD~2$oUo?Ls`%OC?8q{ZGkGFbI`9)AHPkpXFEhy(^UJ4czc?7XiP5FKf-J=lmpEt z;J0Y{`qz938bAFTnqjnkOsn|NEyhlXnWgq%0T0>Pd&K@6ei>xD^nV&m; z?4XHbXRESdT89w%DB!dkyVJGHD*L)4D((|>Z)zIU-DTp;ylFGXinpEBnmYD+>clW6 zIa?OH6643%jnF)8fd2m!jw_m~O=lckf~R(gIx`JkM8*iVX7j6}X3nTW-e>}Dtm!XV zcxAIifpx)XuoGAdHwT&x&43m_Qz~bfyP}AskP}0@6-wYM^mNf|66H`R9FkDT zF9o0E3tK8Ey?-4L-(~V%UkpdA^yTsOz#iDw2PI*7XACgXmud9CBJdVafec#ob@~ik z0$Zq{vc)S9&h8y!v6k$Jkd=DfA=x3(4U)BBw?ZA%=FVZY8V-}}<=3)}fuxyj?GZu@ z9e_?jm!asRd$KoaC6_rSJN%j>Dx@a)^|?y^(U-YSlwYYnrvmgDl8WIyZga9 zJINBJ#~M1*L*n7&!0COzmGd~91UM7m{PKW>qr94vtGZz=3kFs-AI2pHHD)>MRi(pR zghDbAdJ^|-COR!i^trI=!YYTgxf-jx8&*?T`(e#=TO;wZu$sYoAJ*Awtn?6Acfh&` zt4D~{)x*N-0;@?MyGnV$%KBYcV_^+|l@aR9bcms8BYUFieKG9Ts;E2}iXa<6+~2}~ zC)BDV!UJm>tlwa@@mN`Ng_Q?O>uXm}Rb%~ISkqzEfK|h5b=A)cYX+kHRg!KTdmaz6$W7&PM7Q)Jc)yQYf;u*p!gf$4(6F#fL z&x93#H5nFXXJKXB(RagAr!J4p_90Ou7*|h&%$~Q zma`w_Bhs1a$6$1B!FQM?s(DRk6rcI~MskGS{77ePttEPMZL}$4X674rZY!>Z;Tv(J z)4V#5fd3qc_I+r7NVNN%nN2WM)85CbitV7HR9-J>xw%_sy5E_g^-)}f#9A1?)4a_R z&F}lsydTXKX#NAuehk$#FO_g7XiL@fNN2QfV4kj4daR{tPb53J12vtYa90>YPuFys zm*=4Uo0@3<80~}l+x7EnswJPMMmNd@?=ESkml^w_>D@3gSD2zLtJ(#>%s5+tE)J%=k?D7|FO!KF z?lGw4jP%D0Fajr@NSv3c>{`xx{*ggzNnvcUo>Pk(`BZ5wXRKcvXt*=K0W4ET zYdJIg3oX`8-Q9JuwhyZE#id&}ug!5igtRuEeKpwNif17@cTHbz^4(C|8SPIVQpF3^ zc?ZSGiJ-N3FMZcC^;>QHNf}xdD*2L1io`e*;_^r{Nw#7OTRLE!o#EeVv6hj=GF6sK zIXV-=Q3|{H=l{1wKsxd&fk=PGeN_RB(0SMKlBmVS63%rNZluobE7r-w3`dgclD^B- zidbhO|Fc1BiB(PA`nOn8{ah?z=)iU|DeJ;x=z|k@gxzAzNC@jDaacb$qDq>95!ShJ z&b#fD*zIx7bpL5e+_j*H?T*RQrmE&EoDHhVZbUrA`kx3nM$%fxJJT9qsPrCvwxyQp z*kg9^yQSExqIhz4sVXzzpaJLOo!P-N(FjAs1k`(2Vmd5`rk0(q!8N8e@sU4$jVXg7 zn+z>BCpa58Wb|;hH?Q3n5}chJGGN%Xou^KT&Pa!h5p>?z#(AbXoH-c<7+?00oarJCKGx>6!FhfR}HCIo0JfXB`JUlChPz zSvmsJ`{=naOrE5}nU+qH(Y+Yf2gF+XkLZB9G%K)CJ0c z3ZS*n4(JGU4!QIqGTilHq~1#}9!3`M_(E~qP%^WJ1)fMG4P7dio5g?uMi zaSU~ZCPT$gDYO^*5V{0~p0wFgp_WijC=Xf=?SKwJr=ZJ_?|o7O%6flKc0-Mo%Bdk0 zyvQZRYN}odn$McW)W^$x=6&W>SeIBhf7&&X?(eCK6Urk^n` zy(WD1$2mUTutq=D(U+&D=j}a$vt|{l+j@2^ypEpHrk-)Rqh?yS8xTHZBKeBpo@C0f zcT#^L34W!mQ2xgW=pjU= zA7@)hJM}eBaqTQEZyrv>sk|4rQ%N`tx3XvGn>K@!Ko#nNCkVq~!tj$3hUR_@)x2+S zc;8;Uk5ax3o=~m5>bubs<#OOdd(~tEM;x`c1fcIUBLLE=w^v0-s=N&zXEm8V!9Ysa z-d^nynNnoXe14xg&es*(De;BW+G@x+!h$Aa^8ljI_}<-^A`e!(bc9(i}GablYr6krkT> zA8+06JeHjPeX}RigTcrzRn*2A6@Evqp+bsxmeNY`Ap(yn5xuV& z@T4cwUME&pgVLv<>5GGy|`<( zIDH?0YW9?8u!CxCNNhpEK?OFRPKdlwJ2hLe%KeC0x-Fi`4yiiRws;=%P)bP*&6a0; zK~H_!Gv6WQX!FyaR~(XI_dVk&b4c3#iJ@>(CV}K9HFf~a69rbq*eMYFG(r1J^>hB-Mj8I2?t({uEgM-#O8jJ0A8|K$`(ArK)sw!vV zE8=3Eo>pZouPS(DuJ(+QNSOsD2cE=hSIw|ERX>dzEJ~mEbaD`f@-Loe6H@%+@*=@6 z5{e~#8be*6oR8LI&oH)TwB<|gQI2b=)s>H1ZS6@8F_2Il)wx}+P|Feck<(ZKoAoTK zJr1@iw>lV=?Wo$;j+0447!gmz!3XW^ z=1KTRRa|>G@1SZHoIBd{Q5l1g8S2V1+S20o_GoRsTHoHD0KC-RZk}OyR9zRh?ALME z=|(g<*qi$?RA!{4;R5}vt&+{m+$}K9+LDA>ptg0evwY4XEcviNo$p}3Gj6GVgQ293 znc`hxN&?-UWxvNEQGO)L{=7q?a(hR61BZnC{*LxChXkX>ZT7Mj=FwpFaacgguY$Hf z70`#!uTUhPt{X#LpvfQa$xha|AR$_vS`pz3d5?`kee$>pWv`a$5Cd5wBMdpOLH)W{ ziw-$~#84PfuW06{zxUi~&?{Pc$VpfeU=_ZinV)1}y(z5sVa0mN@R8=WKFEu#$(Qhv=G@SFvL0iswvmj2LwKDbB+3 zx$h^%_dofT=rLsF`;YlMgR?}O$zjXE*KRXSe?&(5QmIg9e_(w?ZxCDaqjfeN6t&<^MTbPBo*g`Q?+3gWltt|rF(Ue{pKgzMJEKSbQQ9C)C! zZaUvaEJYT+%r`oinld;U?ap|+nLvTB$4ieo8k`{(p+&Rd^xC zpC!pQ&m4qA082ewQpZHFvwlyrs_5*jq4uwIhO5-|Y_;!ftS9MYm}R#E=N5^uewL>U zo;z1v){IfUVoIg&Y%C|2=wK9EDeY*JMdng^FtWPDBff{}kDOR-9J;G>qExeHu27dG z5Por(wJsT9I^;!0*fpx2SIe`E8G_Dt%d8|V&p1P6k* zfjQvq;Qe4Ha2A*i7J;3?Rp1?**AY+{x?u4ncqb_55#9yv1@8vm0K0!&RT{5O~j{tS)j@Tt!@x!0WNLTwx>W3^<@hf2W|y3!EIo3a68yV zmJB|JVE`68zzN{_AgT7FX(gfqc55WfDDX^&wvZSe}NBy z=fS7I&%sx~FTnS}3*bfYBKQaRZ%`&zz69%oUx97Gufg8nH{eL{TkwAH2dV$FFN$Rd-#Vvw#S@F-YFJ094K zp%wTX*c#jqwgKM*+k#(!?ZE$l?LkL4Z9Etc(*75>2fKhn!EV@30_hI|3&9@X!(dPN zJHY`w9|q|siZ9AanV}d$>Dxxahz0350*%33Fbf<7e)=!1``{Mvb8sv8J-7}09o!B^`)Sy~I^YgacAL?&2D*Yf z!NK4QVBri5f5)&0d=V@GUjm;2Uj|fp>w2!9n1g;3V)Za4yKuuQ0F@!!ayMz~kVP;Je@};CtXv@C5iT@Fe&h_&#_Y z{225^*=(PHwZKzgV~{aIAPf8_*a!R+%mL4UdEhy4K6qa0|8fkUW3d_h0^9{&0N(&F zf**kY2EPEm0e=9$1^)mqfi%hpTQ;IFNGK$ z!|*G(4g3v!1^gX63f=(Efq#ORL7Sa7nOd}LU^Hk4>wvt12ReWuU=J`990@Ys3rqvO zpd4co0hWL@z-PchhDm`}F))`OcpGF!HSkZcHu!Il6;Xj7L6$!SINrh*2gZT%U=xtx zRiGotqNPALFclmKrh&O&I#>X5a${gQSO?qyW`a9vQ~w#41@>am5Ih7n0#AUA!7srk z;4k1UU|0+-7?=Py1M7h;!CS#r;O$^*us_%a91XSwXM^p)Wngl^FdDoUYy`6SArhg5yD^=L54rCf)a2gy3{s$Zn{s~S1 zYs523wcC~~1gG)*H!zRqS_w3{;Jx5{?8k!(zZgz)!$^;3@E3@U$e+rxG2i^d`2P0A$nt>VMf53*|Rj>p26W9~{85|D&0!{^g1q;F7z}4XI zU>W!a_(Cf6{~Crju(%F>2;KlMf`5WPgEr1A4oRcM17ks6rveQ?2iP8Tf;~Vc90S8Z zH#h|h0T+Uy;3J?1ECs#b9xx1iJ*|*29)=IF2nR2Kyr%_z0&9TobjEmK49L!Lt3i# zXG0>@)UzRV)aPeI5)0+1$99mMEiOxa<*e~8P$Njru+k4m2k(L8xKZKX0SRA7j?d}< z$+@7ymr%&jq_;tJgCx&#WcdK757ZHo<;5**;f4CTVsX?El6A*-L!vkvY5w0f~JUBmok>8Au6~9AnxOl10(t znecCcBxa^ZcVV^$LQ+V0)gtJ`qQ2_=bx1UI}&9QIDe3==_z*qcf4Sxi9<87 zyJEH`wly#}^URq2Rjeh`O`X*;3VTU)ohK{&Z&oTXy4mi33xs&|zscY1xs*yXV1+j` zCBIGP%{-}m|6h4G>#Bz?>#TeW#|8`8!lZBx8*`Z)$DIWI(Y8ID3R=@c6}T2RugFt zM4bdf;%OF}`k1>1Nh+bVh)vZ<<%(%1O@|bq|7%jucJ`%&iw~kveCwbZeHYSHJ=r;| zX2X7bq>$f-bq!=#X={0!!77vk6+o+@7f;Knk&nAlL!NNj+^?c?zp|0i4xLN*|91$)kSO;V*#xO@(I+VzC1mOpvDoQ6dY75skRLN))It5q&P!N&3y z`XulZDszL2Yje@DZ#^gHZE&UeG3c(6am9x_+pWgoTdObdt)C03H@H%Og9e-rK8=yt z%!l0~khW15$lmD6Xz)%@Rc%yBKyKA&Z-PHrOD^_y-HV4dx?*rVeV{W+|BUa{Z4YjA z_23%!@J)nq6Jh*#qf>283cEYFD(eZgL^zw_d;(|JCRe5(LuKeibxWmvMu1udj~SGS z@|MQzYo|vYPJ2sDy_*~suW~lKxO>pzR)X77E!eCF;OJ(&DaD(NO~EtE`jon&L&~tp z#zrPi)T&aKFPx`J-!;x+U{3i!DVt-LTaO?vRsJ&c@y*Y@t&|hbs@Bg+W}8zEIRrrR zyG9zTAWF+zJtbeue<*V`*BoR~dB#&Njx>`L(Qk(tv&9wZF(R+odK%kMS8s8xb?8Bs z6U_3Sb~zmcuzdE@uG5+auL-K$ZF{92C(7kL>uT1oMLRs@_hv5xI|0Wij_06Xq1b=& zq6c+_a-iiI4n`RQ=fBc}vJ~&VXNY*rnHWFu>WJ zQmn5kJT<@>-RfP$o;qwC3vZh|Eq4sw%e?dnkhde-U^2zzOVPpFwoauDbjE1wRJ(z! z%RU`+9Um-M>!d^_z~wGkR;>+mhT7L@>c$FIk{uYxVSek>;epN!&(JpwPiw2Rxgk;E zqtGj*pO3ca_YXqxG*bd=KCO!NDXvyLt{xlY%m{gpfdBC(mmd#un#&=NtKWok0*?PJ zm&&-;ndZl!mku-R>(!Neo#p~MRNae%lQ?LAgZ<(F!~f=>`CuHpkArL++&9>1F1S3d z*28J=0i51J4Yr9>XO5jAHO}ED<82>Ov-#3y)A_1zVMvNP5o-@stL1E(`Gq0T>T;~z zr#-Hk4`BiOwS^&GHE4)4**`I;&rIOQ)oVkXF>1pQwjwx>7@-v&a~y1jhL;^@9Q7eZ zz%1HXFr^giYQ@6hW<#Cz9pq~HeM6l~H2WWKsu2@8qw?B)&iWoB!OZi?Ri|NyO5)r< zj78oO>0QHEI!qkOKON?5u64fF9nJjOLV1+GVrT=j8#)4=fv!T4XDFjk7ibui53Pc> zoY|B8f<9NPe6y(F+hx9zQ2+XwJ5qKUy7CV0q2bcSO><@sGe6>X46CgbJ$;B`YO%ndDXl?x6vpKxl5jeZl3S^>RMy7R8#x`K^fRPiYj8}UWu&sCerOI`cw0{`cq%yiCK8ztudbT*>^Oc;+24_p1(13n-pH-FdNe3vMHIW%%b=tlhe`w#e1U-}~VzAEcyyp*k)iyz?y9(mE6A{hWZm zOTDs)MB_Fp_u7Za%r978dTo)*=i$llR8MAAXR)hAa3$X^HGHuv!~Ggg)<2?_E_Rvc zbnH?`VTA01QTB*_HNkMzr-xO}7u57p7Jywa>iTNA zs^Eg!V^~RDS0@asD~45>*C)dIxqFhu808F(mUnOvE~iPhjy2XZNvO=mbpT@Lma5Ns zb8eu!a*4=zi*{$tRtA_nvKO|;cN~& z^N{O|V?F7n?`vUKh*O<<*cI#06PMwNdkh)5|B>>}kGLj<7N!Ts%b&}TfZuYcf(H8p z^c5s?qp?sHGyn=f>!1VBDaiI2e5fmw11*P2p(D^aDD_sVgO(zG6Oq)duB zvxIdsXLFr*(0k|$9ovq=#ZS1{u~GFK<*e)9v9bDso1Ronud_yb1w&FaP&r&&F&s_d~auEFTLSxp*iVLUI4>o6v4 zRv(YG_)%*dj2kefZC1C9voID2<4+h%H>+pHIkSTM+OFEv)KOuzOU65W5mYeuLz|7% zvdvUG$2nV8Mrz=AoNEYd*{l|hw}j-NFzhg%+pNB^GMY?qX80U1UJt5Nxs%xEJ#B*1 z?9;BQjmShekvUrB?T87MP=`-My91X`aH_qwIyTA4y&8xmma5MtIn6^uud2-ZQS610QL1{~ zZ(%$pj4&AOOVz&nEk0_KVfbKVm#T)7EsQBJeBm$#2ZN%fPbO)0O|~S>zmSQDKxSlB za5qi1q`*B>P*MYdS*DWnqU4b&7A3DC6A_8bf+{5or&yFUnTir#Bi(CFC4Hwb@c447 zMM)VlZf5=6Pn4>+r#ib-mWf)^V6Y6p{X(g_ZJI^v0%1hMc%@W5V`W?vMlBd8N>xOj zB}Mw?!Ke-6lTtO;%6Lr}F)+R_RsXg!8cZi@u`qtBirV*imJ<6I0`52jd}V6ibW7;2 z3nLyzRGF$f!@?Ll0|whU+)c~W!&b&|VX%C`-MUQuY-O~X34`?v?t9AAh?$l$@w70K zVGJl!?^+qP@?oUFxW7!@mTz&fL>Q?sW|XO&R>n`lNQ1GWOeH^HNweGsV5GxXU8YuA z8OMc@0pnSM`+&udjj=RvN%qfO@h~jaV+SV zCgQVMmgIW~0XK^@++UQbmuFi7`kT0{596CEm-}X0vTAGrE*l}>eo{SLU~zd;7>!}n zd{X^xWptbaqX~>UPpWZqEH1Xeh`t3zizkD%yx-Vy9KSxny7TNR+beM26tV74s`hi8 z$ql*(#pPYDYdjx|Ale<Rnk2CXoeqGpHg?tbEezDhL1Xv)LA*yT1GBv@T2rzg{5JBRiK-)9N|fW6YwUH z_bK4ymMZ1qdoSy8pjTC^`S{QrAErF5M$ES)=z3wafU)9f_4<5gdV>{Dn~EI%4^ciL zi6svxTw7^xM6b7+{tUakQy1_a-&i-@T2^WW;9UWodZs84@Zy}OXu zq(5t_b@V}oku?R*x7-8Gg zxFTzr6-Ij)ncLL+MV2ZTw+KcD7=5;>&WkLJ6~f4ZF>{;Rx!B2><%^s?I}gu1?(Cj) zB%Nf;U|dBE*RWznl0u57#JHczUd&+Ws#>xb6&+FWyRM?H|M#Gzq>Z@fubO9ZK}LV2 zEup}t7CU|6u`Ii(RHpXKB5nIDcD6)YQ8C(XL))C~YI`vy0F7huGUIe5ikWeIa5D+j60-|(*3{40Kh!7ws5JW(bB1#P%i3*B>3et;+^80+x z*^_L%Z|~=RuJ^ru?>}!YzIJ%XoSJ^4eG($e#Q2=cQ9y-LFNY4^BqUAT$vlpkR^MbRY%9N z!=pM8=p@+_$=QxFeiBf_(7A2uc%~Z$Ri~4jZ~a`$^XQ}!Ow%bQR+~6r;zyvmjAK_s z=nO|bJTE!J@T!T41W=@t-x$j9gm~-PQ4h=A@O_18bFYcZCbXI4Zzok`rlUBBF@Nsg0;mJ=F2mHmF_TBuNd?Su6p!!^KXFJOqq`nuSdN)xcojFx z2rXkF+sxRg zOn|(>oz$+`M)b~L&6Bw)yWlfIfN8)Sv~#CrKSe36oz$>7ytQrTP(*wAnMv_A%qn~S z+??%`d~0~(b9kaJZOPVV^_Qt#D0wcYZJbHZHsbS$(TaNXq$+zk2E0q(tOyUFD{_JB$ro&(Z}($`P*NT1}Y19-5u=9MyuR7!yGE)ctt`)0AL7&rn6@ z6U^s+!APah*&Mz&(S#eBI-51oocVlnJDXz|#wNDTQXTm&@9FIKR`edksG^$t22tuB z$SL$8Ng>ujx%X7n1%%v;kei=WuPpF;@fV3fa}2tjRG%;4#qY)nLwRK-EaioKK?2J4>5g`>amORC|;E=>hd)P#~LV#^Fcr7QdM?Qai*0C zinpnYde7$|>&t&aQDOp4WtSNF3UpC7uBP zMlD|GmzfvD;3W(?o>lfmj&gQbX%P*czGt(8!8UcCFCz394_pj+WZ>RC03Q`S7GKKoV)?rMIwyPDtaTZ>72F&2-?bCDdE zSansomN=S{z)nkeQ8hBIeYz}%rHBQDn1S2G+i`tsEhM{Aw26uI9pLRDYt zsIGs-FJmA1KI|C#|i_jEFTk0rmzwloAv89feHNC=e_Q?+pC`h>8;K|QENLx8%39sw~S;MR^yjrb*g1`%W|yF^ch_eqg9qs zl@yE^jxbzxPr-;G2s40GG5T`3+MPlGj49+^K>!RP7*;#3!0KP7)q-mE3P&D$K#FN} zLW~Nh_cqm(ObB_pwTM-Hglp_pv&` zXS7F*=!Ba_p{p>WyKMweXB9>tSw=I&h<^35RRlmc`nOdCK(E=bT75NEf3vJkUX9iJ zKBF`-3Rz(Wki3TDc*2a{n8v+9a;vebum%g2eHPSsY}o1U&RRn-^lrahLom{rm4{a1 z1FR0Ttd9HutMpn8qZBcE+cLT(Ms!aNqrz)3`oJ>cJRSNEYiYJ_T%q1rODG4hx0XLE6Q`kM&L@{AqSVlMqZ=8rrGjxR|*wm$U08ODS?ffuTp9o zuXB{KS6itDuXEI}w^*6JW}V|}jc!@`q*TW`%}y_>(niNC_P1B3zq8SiThn9L;4p)+ z-7T9OC+x*ONS~S}_UI$b`iN|3`H`c6oqhp7UeSX;)XYg^$HyG;4fLX09S5aJy>XkP zVDdKfXfLBa7;H9fHQQztm&%dNbJ86pwBW}^V^U+qm5~Q0w(~;LK>TgHW22q+;IdB~ z$@a_*={0sZUJkX-%TTkvBG>sK?)b{_PO$lj=gLFg^k!eT@vJ*Lt+(Mk!S)7T~K{_Id$Yf+GvIRMUTtXfpp*M&e(ilnV z&VM738OSPRCvqCOjyQfJhDdd!C6b6tMphv^kxR%UB;QSP4{3(PBIA+yNE&hoxq>`F z3fv<1kd{b1GX9pWvu!?#RAfJL1$lxLxQ#`mEz%$HA`6i%$PwfkBA>1(q$bh@8H!9p zQjqO;=El5}yhD!)D#*ul* zC-CqQ9-j1_x}oO_+>aNB7pqb=^`dszda%2w3Mp>qYJi&hE7rXErJC40fX$PO)njay zJ-OJL*yCbqjnpC1ZvQJw-)s&|g6hkS{r z-F=>^%MEhnQ&s8`drQlT{m-ghUG50|Sq(CA`E7ck6(a1`@%{VN(Yi$OD||cno_bK1 z+&bv<^J_n z2fdf6*X!#weG@|ab@j$juEsr4Uk?dnyKUguW$OF-x-}=YUzKctyJHwET&7w#(57cUyn*hCwzQ0uM-=h`!7Luf=O?B5SHCXfuS#o5QTi8RxFgPB_{|g`mrM*-mo74Hb6r(zria_F+tjfo?)<8IGd=r-oY_n-9&`bZep;dXuRzdWwDOl63n^I!#Qfs*Nr6H|*WtQs_299_8$s@Dk|mJW+v+WK z-X0aXC@4a8Y^TrH`|``U%)`;1h?|993H|NGKiG>PSmuC^8L6LAE0&kZXv8#Q}wp znn+t@C^8L6LAE33kz4oK2jP6c2Op_}bVL%7$;d(^4cU)mBDWAHO9Tod)sbdMEHXyT ztsZ<+KH{|)kTL#pnK1tUgg*R>Wz3VO{(cF8yfk9>#WHew{O*4~qhtr3bg(@6PiK_W zl-G;DfxLaz-={bpR)(`kGxg>X;*(W?>tMr-+W&Aehpao#c`^r)F;C_=L>-LhMoUKm zm6naPqIbHoPUh&JbPkOgG`DE`v5SLU*QC29WZKp^iGvwB<0KA7?2MB*UWP=@I|$Z= zufuw9Dy$EaVIxQh@U1oY(`_$dlyA>G<343119Wjak2&*r;L*|o`wC;Zv^|p&Ts&XhkRYUBjG^kg+m}qz2s;f??N~X zvT)EiSmSdzg5P`tY$NH6cz-}K3f_gU!Kd(b=yup_;~-a;+s4DHZ~}~hZ@^Aa-1mlF z{tbr{;Tv!Yd0ZxOv;M*_*CcT5=TNKmbZ*T^D4ClZ=+JtjqUidC73+KTX z;C$E$E`WbOSmQPHm!LlhE`>|sdoUF)gZtoe$SUF_TMCLxXsm$O;c6HVXtS+>&%h60 zNw^l)habW=a2@Oh*TaD@6^@1*;9GDbTn0D6^)L;73O7Rz7&8vmxG5)dY(wKI8tE`k zkWt$iCun@a?-%&J12%!5!cK4}jDx%2Ft{5|gP*|#a1UG!_rg8!0K5PX!k^(6@OO9! zh9x=86E}*(uh6Ir55xNK2z&`1h27vWI2;~_;_d{T4Kv_6cn0o+XW=QxtL^;(o`;Vi zE8V@WVDli3{O}^blS-k;L{SZX0~^9`VORJa>!Jps`colvHuffak zXLuX_0{?`+!dxyom@ooT*Lcgq-{k#ofZ`?^t>7)#1Kx&X;C(m?K7h;ML%0z>f(IZ= zyu4@NV|W?<0dK=6@K5+B%;l!L1xvuEuqvcV^u|C<}8Z3FN;uHxtIrvw!lyO8MW- zUnUUQqbWJo3XzSrvI|Y@%|s+}vVlvsjg>-VXPUJ`O(=;J{SwGD*?IWCcJ%*(8;Pt$ zBI!TI4hwUU_K0kNlRa_e5ZMSPDHKX}OPLXU*$_7anTK>j#82g9@bzv*n40jP- z6vmdEnQj?cG!|74o$1aOR2*B!F`PcrZJi!lEI=Kb=`I#j0;5Y9J)G$-;z42LiZ#5} z%REK2mufQ0ZQT-s!*^!6i-nZLp}VUuRdZ|P4pWC`xji0BtDtYpC06a7=MGDr?RILh zDtI=F{bNeF79beqfj1m02%|sY|jZp|E#RazTxmTN?&s{)8z3UG3SXz>c9^x9O zV%~K}sx5~(?sw1Ib|=FK8He3m9lt)<8IaGgumTHOoZ4&Rb}4%y<6fLNrOmTka=NsW zj<(_Q(n7a0prGM04hy)PXkzm%rog)o*PPq9Dc*6a>jHOePhijNh|v&4yWR8daASQJ30pwaEBV== z0fh}C>LJO5)!xsHHV$S+)axV@^>IEk36N$8W<8RL`W8PYG%Cgl^yj^LpxZxyGfDkt0*_+DIE1;DL2Yp(SsuE#iD&_>uqi#mi=z3#4&ea)>XwE zb4MC$)OxEGvVVAwY<%mjqW>b(V;8zZP#fh!g6gfb1djFfsOV#qqdl0a#>XgKlnb#p zth7B6PyoV?#LNKsRs??zuNtinJnq%icB!Vn%7MRv#$XY@yGZR3pis>tK+XVlU~ z?gIL-xB%7WI0H{D?`uwVei2!jY+5pwp-3s{Eu|n_g)Vj%_7v`ICRpBADGI$+-Nih$ zEk13Dfs_K`igxfhOIuYv;SMu{*uIz`Y<;rxP0E2Uh+B)@4J4zhEg_>TkkO^%+3~r= zUDkslE2E`E_mPY?M-3zTXf}BrjlU7Sv$u2gQAd|h1X}r=O5EtuUdne*5MGpe4=*a=MS236 z`5s=N$l*nTc`kN>@^odr-Jz2_*dy<`L$w6;&3pbeaIt0hR2iQ>?Hj;V5B`ZZ6IF?`5f1>l{0c-q*}3zL!S9A1^$f9^2^;#B$>mP4Ck6 zdbFG`$g}7aMMt)E<+&BcNCw}((NsZbrk8$bZ=?CXo#NE`>c^5P@=aR5!krMz_lKnN z2+S*lxUYzny(`@zx_o^Y(oE3#bfkZ<(!I;BOI3b+4Ta6S+TBu@+WYuw_XM4~TD4h& zLh5786LhND^yfctzpd-MVd?wUxrgb&W)aX>?R>eogNu?kx`zatk4kP5j(f!smY%uM zov7*Z6kbYmXXuiNk(=Gm>5^qABGk~$91AVkG8=8Xt)F^hXHW|j`jOkAOM=5ca&O3! zbf_-r<8LyMLkvNsEWr@jZ0&-zS39#toF2VI<)#KTGW?J zHB*8S>aRA=z=-;OVGZ(yCGTy0RfJ1EaQ0kVwuaVMolJ}ZYD^tsn$p&pPj#uwa;%a4 zhmVrG`lODK`l!CjXzMJ5n;UJN#et`t@oS=o8vz@%b2`y7R)fkXrM`-5=M2vgi?|Wy zE@P?F>nm=F6R$S3a~2P_(wAR(>QD(?Z|5xFx$aA|D%;UnJm@c4;$yg^ z*KgU{VIpEx8(Z+;X>qlzqjQIyg7iu!=SF+glIgCOou51Gr0&=&&enE`bvF#gR8q&f zIcwCiF2SgR<0_2bG)B53Bas=%Dr6^e9=U~tGPY9&Y4F#_Rb8LUCikeIGsLUaKJzSj z-(>4{6&I^&iZ%n?%q|5$5wZz}#LovCCNiR$)H+5&b zd8Q90nV1a5q<$a2_)ZX$Z!j5!$;H)rc1nH}lW#GZj!B+)E!u-3>;00}U#5IVBehI5 ztQ2jFOgS<{Kubli*97eo`9<4A5N#qRL8JM8!1PYu8+^k%2XS3CeKn9Xhr`_e@z;R zzrg(PhHjf!7~bM{F?dHE=&MEQ@`PnEW5fgW!)(#UlE*!mo6l9V^)%+qk~p&3=mtK9 z^6LHpBjBGN#N#7z{nO zD6*#-%XHbty(hWOHLHj7ymBU?i^&rHDtT*~S~QlX3K-jL7DN64`t( z+{e;BJ_jYz&%*+kQ!CpF!54jO3XAZ&4UB{dFba-?#ni<9T76wgs6;2MB>H6-M3U&# zL8O4*?5{YL6r4&uo0B!&=_{$_gkz<$v_$$NUSuh< z1v!FTL7pJ_Y?_P0sWE7%*}AJ?n}dfW-wBEeQgRnaU&dVS1V!tj;9{GuYSo>fS2g3L zo3cR*v5~JIHPzjqBDyGg-3@xCNWp%-iquzMFyCp^8^p>sQfXgmRfD*7mmf-fc{iwd z&?0;pgyXw+gRELjsjBxdS&YfJ{(-97y`Vk_1K-Q>`RL1lCaX34{#1YLYJ zZgVXBD5!Al_Ag6%cp}J1GHwR43fYdFK&~SWjn$w?10)_9kIdJ!%`r2zWG+Nzl{ut^1X1e*CgpOd>DL{#tC~@hU?plbd>t81xHSGE zO&I?d#m-cmJ;a%>|6@68=yNthUGD7&D@k=0xH^|F5pwr>!%-tg4jDWmW_UszJDBpQAu*xP$b|Tg31fHz zOWG?o&G|U2ILJ{-@+Vci^;ZJV@>!lqg#N{|f5==;?iv>mR)SAOU@^$| zA;XPb!mV@0$$Hi_W{kglR)k+Zl=cQuDvK9gEHC~wO4a^T zl;+D9;%`wZhkv~+|Nb>frhol%CeeC1xdX=dn`FZHzdZhpu>9*ZG(K)*g72l14utMm zNE}+?PTW}bq@O26F-!);!s}a$5u0JH7us+8yesAVUWEC5FM9jeGiE^Q>1eHTZSx2x zt6s3~rn=^f@hBs%=6@B4@qH`CG4b(j)$Lr4ib*+>Yz?ezmjOQhwwf^huZRb)=JCBv zji_2iCbS$dc%T^@Y)E?K%81Fh6?c|hNw#>9&o4cRmOJ_W6~lt$OTMhL3>~WFUA8$T^ zj(jfTOPUowe~WP=MhxjQfGmh_8`n=oM~75wo-?*qPRjaA`O9O%_`d?*=2}*4>%{aK zIp8&X!lQ(Gy?gbls*X?4O83h7V64PnlMLf;feGXP$|Syv<(+xBoGrwPU3{DuGWiGiOAJF`&;%+9uTK~yCWS8~?m-3C7Sx-rt%*_x! zleW8;WeCP%t!P+}-x43fPV&Z}Xn;mD*btgC z#xkESbMJBra#N%^A~TGQ5t+gib5YAQrp&R*RH!w5DelCs%udSmrp!o|%DOq~2oW-y z8XC=tB(ota#bOU4e>8ZF9v)vEuk`RR^G3r^NRCJ;HJbZ*ArY1;*V_uxCGg7d9fjN5 z6&8W7!lF=mH&Ji~#4qoAuo&Ff5k+wn!K5gdd4_X_qTE4vxqSHSD&9EmU+9$DV@HoUEz^@PkeghmZ4PpB?kVVI;iP<42xfC2D}>>`5Jvby80iaP6f{Q){`Ena&4H{C#v4wuLomPY zRtSn6jhuRU*5%?wo9Od>(m(jVg`6`#(wgzX=G#r~8O!eY-&{B-FQjy9<)KnFc_ZOF zkSfbqKPdfhUNUbZI1}=qZL?svL=>}8kcq~E!a-0xAgP9jM9x@PSk-6*NR2I}qnS_I z!j?!=q#aU??B{*q&w2sppfM1Qg|=%UkIhpErL{)#=689xRl?NV`E)n zPq>`lJZoDDl<2L5JQ4bF;?Gd>Le|nq%_fDl1R|?NN)jDWM`cAt{N$@|4&7`u%hFo1 zV=nsX_=Uf+p4uz<{fXhX)Ggv~)f|49Uuex%$n;`2R;7@C2E*VUSPPy3AoGz_PUBFB(fCQf}BTgA^9BmfpkO? zk@-j}ass)AgfK#0B7mWtW+-Bj$;eVC`}Iz%hiusKn7C@!FECQc*r#F z1vM5Fx!^ZeKWOaGgu&Pln-0U~X4B@;hwkDyxNZK*^@yq2KYRg*UFpJIP%)2~6|K%EamKi+Wg4fiNT%vUue&$!oR!o<(WdFe)d_jwHd4;&jwWX zjl@h=qkiY!UJi>5yxpHOBeTzYn5=#jleaLrgGrvpStHz&RlCQSOv6MQpsR8ICcDIh zV?YB#F}dn*QuYr_IIlA>5|a*pWZfJ*S6lc)Bq=E5g)n&v)>zL%GMERE9`wZh zo~Dxw^MJ-Ze=1%ScNgb&&4JNMsJO7TJ$vB9D+zCu2iM1EiyBr@0y>7q&+Q zeay&s{ACd#`AS7TKqYYMEvrKUz_H(ogq6QYB!TI#-G%R z)*qv#fh`$kFpT_$ex#6zrr5>&f4HWVvDUz@mM{Nl&}u%VP5yqRnPdIc$MI-_kQr&u zA;OHsl2|}f=COvba-l`MmN!{0VlASE4GoGhFEW)-{qw?1hxVT@GL`0O&g~LJ+}ti9 zwVn|s377CC7mMnQ=#|XcF7f|gWctq+nfB+gb>6(dY=wM)y?Y?v7w=&h3%Sh576&iG-jJ(;Y<-eYJVX%>?L3*c(oPgWyzX-Jtp=zxgzKXTi52*A*D;v{i6A zzc)c?r|p0<;Q=@co`BL!y9jAgd4GbmTfDd7yYPvF=*>eB#D|4%zOgZ60W8ArWXM81 z<7QP>nHUYPdTmI31?IWViyZfGc5Y5{max zq{CJ4bGRCE47+U&JP$vBKftx{H~1lxt6JAV+GWOukvuS!-v!|YSQ2i8Rp2IA8>Yb* z;bzzpZiPvGQEWr;8kFYTBq+_fWcUeuAMSu3Lus=eg`dH1;2wAz?uCEB1F!%e+k>zS z`~ud2hhTFkEv!E9C>#NgNsnEwa+RjmJa_`8zzir?ww{4h~Jgr@30YkO!@P+Mezq3vG6HOgw&Yc@sL)V zcN(NsHtiCWZ4!@R2z0sloWP<`wn>zSd0`A>n9ti8GCbxT1ZA7Vn~-rB?;;ouH^Bn3 zT|zc~$To?KupqnxWt)WE&2k(V0cD#+DOeO%gR)JcAuJAGh9zKMSQ5&9k5W)>N|oIZ z^Pud8SOXa-@os}GsqlUUlVm%D+>|QYA+Ew_;aw=(9s)zmZ4dcj4Stt{vhCq{DBB*I zLfPfe4bt574uth!608qrz(z0yHil`i3EU4~geOACf6hYkW}@*Dya`*vr?3?a%f+-L zjDl@o71#kbh8EDs03hVWI`1`dRB(`q7=U5P{CL^up8I2>+(Bj7$b5?+9#;LRiy zub~LYLsbh4!7;EZ91EMm*I^tS2ZzD&a5|g-7s5B-Dkx=X3w#sGO{|RYQQzH5nKn`!1b^IOI!ZiMsTCip)5 z7^cH5@C&#VUWD7=Rk#D*g`dK}ysWo@`Qa|vE>#Z2ZZw{UpTVYZAM6JA!-4PsOo9jD zbodoi@Gx8lkH8)9C_Dy_!He)X{1u*p8r|H}FdUwNRpD8AW-%zv!7lJTOn?{QF!(i` z2)~63;CFB}yaYdim*D~UBg}w5!7K18ya%sAXFhhY!Drwvuq6Bq)`m$pQM5yG3-*Jz z;RJXG&VzTM+^~8N?t}N?Dfj^X0w2PM@DbFXp=yO;@K0D8{so_hPodnfYO|A2=z#Ih z@cwh4rFS$MG=05qL6#hNmp~_63xnZymeQ3zsCJsE%SiWId<%b65i&htI={kbTzP zUm;W7-lwoG%u|4>78Zx~VHL{BOo!Xy7jP%M2zS9>i|~T&M)4Gl&tOPVDpyzl?uX^! z0azOzgl*s#usb{i6X6jka|uV`9C!?_g2&-zcna=i4SWuM3!B65U?=zkjDuI;Ncbb141agw5e2*cCp3L*Soq3j7N$fluLPXw%7RsKIX_JxA|ts6#E9 z$`uxX0Xi>ONffNl@>YdGFb29|Cl~?~pj_fQ7UqUiVP5zy41=p7OIf^IpQ2?xPa@O4-kz5~m{Wv~L= z2rI(RA$?%)F(@0|zJ{D(;JpE>!$0A3&{Lc`6c&ZgC!wf>qBd*{>%doFT{slhgHvIB zxD+;kAHf)S2sVV@LYC@zAHl}ZS%S(HM#2|i1=tkUgw0?x*b;V!Nv%*MqG%1hklwm? z2J8SA!j5n~>;ylBFT>-I(-^#&unW8nyF-TOZ9QNp>u= z2q(ao;T!PPQb}Y1ir3J16HbDY;Q}}Xu7*?LC-5zJ05XE=Jp*UJU*Sxsm8Mw=!{KaL z5zc{)AmbU{uJBzr1kQs~;C#3|3B>{wn_x0L2o*d9Imp8M9b5!&!uOzFhN>2Z!R4?t zOo7$mD%b$7h8^G<*av<9N5i#nGW-zEhZ|thS`-^mY=@iR5ts(g!!7U%+zKDUZ7`@T zRVpk5x5Lu#6Zkyb1z&=@VK?|090K>iad1C;3m$-r;X!%-*P-|Vjot7N{0e>vzlKNQ zZ}1rW3m%7g%h3^sMd4{!4xWK^;aS)Uo`Z4lJRAfszzOghI1hdcKZM`O`~Mk=OK6;d zm*KDQd#IJCs)gb33aki!gpJ`(up_(*2f}M`3}ooZI~mG?>G|+CxE9`o+u<#E1m1=h z;C(54KcaX5AHj#vS%In+7KXpWvQU;xzX1P&t>9DG1KJ!k#GwW!zySC*l%>&2VGvA( zvNU=R42DM_V`1J*n8fNF?=2K8vhgx4W@AlZSQDOuFTiV+ zc>imm_#F*d+3c!J6$}eO#_GKlAmiTNy0AWM4I98-Fa{2V4dF!C2+n|w;R@IUrotCt zI&2E}L0Ry83^s=sl2EijaRt5vZ$er5{0D3W1FM)TpFOY*zYD{*urzE3tHJiL9+Z{O z&7rJ(?gVA!b1Zxr4ulM2dS8QG;3U`;Ce1|g3W|lW8+;#jhnrvzxC8ct2VgIF0>;8j z7zeMy-tZ3W1OJ5a&{>r_9_E96VI=Ga%fbHeIXJ+<`yYeiRWw?{fv_`7guUS)I0z1g zW8n}u84iWB;V`%u4u`AZ2)G%JggfCV_yv3oo`j>}H;{o_?-e-K;i8*}VjLRjPiDH_ z&{V^@t|Lh@ZDFm#k!jV2h)k)Ge zil>!da22k%fP)5P2Q_i@fCXf0KqX*!zdL)%cgV{e#7v_RP3jZ@d4qmS_C` zFitsx`scX+{aM#vN|h*KOTPH$r{tLxSL<~Xdse)qN|Zb`@a--^B^Jr2k9TM)USWfH0$|D z#6{#gCnAMKC~kyOd5NC9vqDQGaoNJ0Q1%bsAwg>S3fFPmK?8Md@7 zbh1DS*^gu*_mBd?Y*mWTl8-r~LJqSCrST``#x528kOPM6A9H#Q?RRNOH( zLZ49+Oe`{SyN5k2Aiyv`dW?P4jO`oN#Yr5JALmZP_|Id`NY6lDK%%W1+HuD@ySc$} zXQ*ebpIM+~W}TwFU9CRO9%bf118ePIci3@fNe>E}hQ*@3D4tbwhq?=?s1xiqKdXk_ z19Le7E z=7A>OwE+(8ym5L3n0cCbo>v)XongU}b#}wzic`**tXb(E3k(uF z!-I3YB!fu2y2lJ##XaJbrcGy@o?Moe@#xj%YA){2`&hH? zpWUt^&XRzWxLvp>P&GPB)}Y9dfUo@$@U@wMugwH}EeR;3eXVW)``4PPS0bdSuxE*o zVrb`xO=1SSTs5YC}OHLZ^&_y{* zCS2W1)2vg)x2qq|6F?`nSJY%@vESCm?SyHqmugILM;W#V%UTm?5mneW^MKY$nDT6iC>SI>Rz9Fk2gy6eydZ$lz&Y}?2UpYl5obnujT*}QI; z7qVQ!76!xNGq4WK4;#Svd@<0adSc{#Gp zAh}?WR2%biZuo*~m+3qgY*wf&;WdtQNot5MF4ErwN=@)0WcJ0Fg_A*cM7*YYzv)PH;5r4BvrW;T$N1P|92nek<4$ek2RUdZE~hMlAdS#=%pt z8@vSL;Z>LbZ@|9rF6<9~hXbICWDkUS;29ef9NfivK%a3-7xXF++@X2Y#;4%`Xn!hP^v_!XQFPslc!WE5x7P%slNgx|wO zP_k*U`tmzxFI_$h*Ui`7+*Bz=i~+4g2u0KE0pKB9m?Tw!20lW*beT4qu_qH5*~mb!hQ9w;#&n-ccx%dOR3oQZJauKjL={_&cntb))J<(HM_ko@*AWM0F$$@PbU}t9^O00!Kaz<&LGtmDsNmM- z#_UQ?)1m^~lkVN!)Ef`%J=Np~&U}G9y1>kCYS{y4B|Wp7O&w3u+V~ny?N!N#oFUW^ z8?}0>)(@RU?Qrlz=Oxzvw|V4zM&FGC*~qBU9yuNM%x>x19yyEI^;$h`YIg3R2z4TX zosN$lJL{CMDP@koX;QZMlcLs`sC7q1A`6i;WWPjpMe;2zDrg8tGF)gwCTSths5-Z_ z5Z(B-S*xnX-_i~ehddl5p}O4G@&ygW?p^FY?O=b_xA$O(+HhMd9yAP-ifsecx!YMM z_zWA&VpR8_U_`I zilz66=X!Nn)H_YJ5$E+1=dfhX^}`gMFje@z780@EuSq?m_p8Px5=r`cIZd&UczT4h z`i7d$#@^@5pY`f?D(&MmTziW75+G@nhB&V7k|S5{lMg%m5+{A3^(x?jR^HR5eRi7V zQ;w4dhOcoCwBnu#ex_0}tyc>kXl=;6A2AIYN#^zM$Q$`kE9*g#m3iWSs%#oBq=rV) zT}xG)hjLZ}~j75|wHus^cRPW$%<7 zsALmn4+wP5Bl<0=YQZCt5aF|upF9aNt(_13PiF(eHj` zax5nKSUw#1hR+vnW*HeXX21yl>(Pg(%i_Uktj)y(_ha@(pfGYnLM2e!237a5W*x0I zL``^%gE2Tbih~bu5RAfbP)ubUmlHof4hU8E9@A4WcWDn%CI7(5Se!h;v{@R!EBk~TW+4HJ_$F!>piB~N+nQ5XS>Cxpx8fEiDD z*EU;cNm`F!K}CD^H~opkM*bavL2Yj z`o~heg!|tzHAGF+?8QSS;^;-6WtCBsF`Ipw-Q%&eta#p5KWdC5SOui4o$y%V9yqC6 zpz2^JKomxRRw3N-_Y|q4;^s}<1a@bP!A_b`WJOXczOB-~_1yrpRkhOX;SqE=jC_(L z4~iRO)KOBiZdDU>dm(LW)-huam8RPrMf~lL9x{C3fWiF?H}W=aRT-w68-Mq?A*K>> zsg$;=A`W|a4v$9m8Xzr8!y~Dg*uCj60w3hCM|!^Tr9!ewO88bqbrz=592^9^Rej>H z#{`)NQ4CR909nw69(Yu&*#nO>4>FK1oz(+R#0$Q2WQ<%&Y23s!C&1oCm#^Ee0rrGo zK4ylY(>!N0G0+~W^Yuzk3bg0abiOO;vxDq6>^hZXdXmfjp{7e!6WM}OFB^y03+q%b z=CAScOKOoNA@*Uq)DC%a*`L$poi}X9=E7Xw^Q2t%7@Ze6eP1qnMSHOM@@Tdx$`cd7 z#bBZK{lOG{BT^yey_VNQaVmx0?XkDgDZ8qh$6i*aRH|OnLLyX($6h_yEMx3~Gf%?4 zC3(v?9PAhF08WFeAO##m21bcv*`;$HZ*Tz=N(5qNKhV|%T zs@&DAThorJ0av+)?>Gjtib%)Tte<4A#~^}c*yz* z$rU(seG(f)-|DNYB^7yT8dTtjXnq-aXN_{6qgBwnYFI@!t+LQ7ur`~7iAG5s z#e(C(h1GWz-JS(cf(s~bJ-Q7cmGHh}zw9l%lG5|4Y$bP0WXCY6th{()W$zV!n<=4` zs}-9VJ6>AJeM0)_;@eJ;&1)UI^Wh|WZZBSlcHON zaG7fLD@~{r?EH~!XUI_hg1Ss?#!k=*>^KK-#O1G9Et6%c$aPHGQ@0kuL`FA#g?pKr zC?+d$Qw9_1AViq8uEg8QnJOejqQ2=9t`rWvp%vDNsH%KJdrl`dqTsAz(Ux$R-_XkH z5{zN{ifD`1a;Bjw{F@e9yLDGHXT;Z3vhNUb3Au-aFjyCb)I>TWiO6JRDUz0#$&^J} z@)}oEP+QJf4xG+WzH3}XbWvoz`YOfc4p2wa^dJ>V-za_68dq=4%ILytUHLriaGRIC za>m=33Z_63bYhA^H+GD98{w`VTD&j$5*e>R4myG(`aYMc{u5p|HL)>=2 z?MmF%|IpPY+uLL@Vk=+ZdW=5HVU&LzMx8KvDz4TMB8sdxO4{(F)u45*NNu#)d>?K0 zd8C+)R?+*pP;s;zLR!c;Kz+2zsKJX_YP~CWuCg;sZ;V$<#T;~nb8dc=M-$~UK~>EL zgSvfyD>l8KxEy$+Jx9%uy58kPJ@Mm!$N=e?jyBtochPIZ;cg~CXv8NTC!+^%Aj>-AQ^?!^r8c;tJt(rWOj@mDrP~*& zja4z<1qgySl7VAYTp6zGth3P-;tBORkhYDqn#QWG8(odW^JN?HoCCW92jck`8(k$m zD6%{c#_sFJWP@=c|LZF5U1q}?9CJIg*VRN($C~OMn+WlBHNiymdjXMZ+Lx{nb^QWW z+0ZG$0qVjgS0QY8=ICK8`4eyVz84T4ESVvVrPo!(G{ZvkG*@xY_kQt}1md%3FMc;W zYLfY{tIcVy@*dATQ(ICeCFpf^Bh5@*wauiC>n8%c&Ewek&6GA2S*gRSttE%@Qv0R7 z9at&5{GJqN+(QwVgtI?3ljA6|oJkPl{935vRJ%_o9%#_Oee~QX;uBPRnlf4viabv`wXy zj#EWGc7@~d6>dMBu9n0@Mc|^B7SWG0uLGwQT`SvR~hFTX4Zu4S|Pn z!Rs5L{*2D;R-?DLJRYyWKsMW1(+tp@4I#L*PR^(6J`$|_a4-ps{3(QNUnZEMjG#`R9O>L##Zug zg1WJl;x$3#+GfDW?graP)O9Ir>?XHr#CJ!}cmXNT1_Y(9$Z6-@ zz1U$Je_%U|KHclGt|j8_`AdujV$=wbc#93nf5u! zo??!2o-ozM=;tjz{m^}e9Vtu!`3w)GEU7A#D^>GnF5T$A&s8`eUV>E~Z%DYRFv(YU zPf?rq@xZ32qx+~Sm=4Gqei$)!#DIAGvOZl?l(yfnS;PdFi7>#jpXzCfn)sO>t`hh2 zFmkUplP0dDC}WmE`(w}BnnR_Cg;G8X(zB4-bBfxv-&HzSeLr_@)$V7S7FAw#(%?UU zn{IxF(#D^n${uiamJh&Yhp#b?~8y|_NVo{m!d9lRAqi~hpNmkTm|$KYXelFiHsv; zihkik#B9Nb*~yfc;VZYZsFsIZ)s1{PM9c;gGqsLPuV!d?v2^nQUgwxrZ!E5qdetNo3hR1gFaooca#8r^l3|eN;7S`I(n1_V*ih_^GRN< z=_>e`t9-?}TTE@SEgg*MTJ}qxIHVuP)y5gk0m*;Tb&NP&@;Q;0R4ORaN3&I>9W$Hi z-yh=<4d)T{+!~?siFqKp|gO=S$LJm#mi&%kuFn+8h;g+P^h2 z=`@LJ!7xPcPpD{4({~p|cHcepjH@So^&w|mWrIc&snM7&KSNE4BI_yRFITwB0Kad5 zSUmI}s$e_-%M2!%!>tX@x(aJ~)!d!|l*zXPjI$jJ1e<+&RsooIyr-RYP1B{*Zd@VX z@tmu$F8y@l*9`eZk34<-IhW?prSH1wqH9>N+2hn~y;SrnvY}3q~pE z*{R|vGvBD(cdqI>J*M=qORhh)V6!J8cWT7!V?4aV_pX+@bUMa;@9G+C_8ByKG;xoE z!_sek?@F@=)6h0j^~863{g19xU0T=!e{y}JOT+o4tFDA#n!$#xFVwL2g2K{|T;(z8 zv~klfUUQArbeg8=oqur!+kgKRnw)DgIcv7@G+SqLfHCTZtBPk9`)cG3 znGIitb5z$GuE+>kacwQEkTo7=V^5=(5SPl)hzqeTZ{#s374ZqkLJnI7ECWx&8t^P+ z&4le7tOqYbSt{`j>D!UMqhk5o?`@Bfv}>rQAqc4JaRm zny@&00m}GRZCDdFfG@&^uqA8+Tf?UCRmf3K#`>I>;52@>pjPBdRN|SkUo?50qhNBp&T6-V}V>ejN*3! ztOWZ7)Hhek(c1O4K!X;ow+p0U;LU)1wY;Zb8hi|!K#t$A@h$L5KYy#zZn>5R(>^we zna6k+OYXo_%EYJ8JQK8rak8f570qNntC4$rR`+IEjWMj!O0Y?@`MaCWh_Hi(;q!(; zVM3KgbN$<{h@?{(NQ?4}VSz#h<%53?%Ez1|ue>z(Z5N;{y7(H3&zW!x{1(cCxCH0I z@8M#21*X8O@MHKhl=V5X>}9|2_hDH8bOVF4XxxNX;BEL2-hop1?m~G0;*bR^#&5>j zZTHd7_kS3B5AdjpHeh>8wy_ChC6ELNB=itk=$%ARIs|EfHXJ&TJbKrBx zy1u3_@6lIIy`C^tkO*axP-{;)rEL%x9Go&{O#)^?Z_jxALFpCPzv4as*&5+K2H88H?Kk4Ler<;xKj3TiKL!@2cw=F8$S>jU zx^TSe^k=@Y8Tt_2DBF~@KgJ5ONmcusPf#hlg3`f#0;Pld6iV5bK11E z0(OQgVL!ME%I`&=!AWp6ls31Q_(5zK^t!By}XTnGP#8{u=f8U6#e!(p3*aF585|7t zH@@U0l^9j-X}-D+eU@Wnb|Zs_jQ0s6d2+*GI1v_ulVN2z1=fTgKq>Qwuq~Vlli)Nc zWuFdZ5+!*Z3ukgHc@uu<@t+3gaLo5b8QUi!E!1=Jl%Y?ZjD}F@Ir&?PjI?P^!xAFM zd|)Y*LH;r*bE+&YA$Fuf*#^H7R)U|w>Tn&DjBbD(;YOGYC4+t87LMg6fEn(0Jqqc8 zze4eW=lCPIi{tqaQ+?VKa4%fV@qQ>BzyT;d@?rQbJOa&trrumb!R#z3q=7^=ccP!h%pgrOS8Sb@-(3u|+H3)X>m;C4!83(&*Mr04hLd3z_yOz&`PIbG1FnRQ zOT%|y1vm;;f$u?{!GV>XUp z?)iDJB;=DgZn|~Dr?3HB4C!bMOCf!MAq!H?hEmd!*fMrcL?a8nS7KEGa-2Y)Xw%}13ehHhxt#B;d4JX0<@FRE-E`ndf@8Ds08h!(B z!XxkzloGyz$2n%Yq8$go?>UzBbJ5%2DSH8i!Z^;N2!ZFa>%Po4$z*1=;^Y0!@aWt4 zla2w~pW0*oJ}kxYLs$|13H!n)%4p=P&icZH(a=^OD7`>S^%`D6Svw(1n&Eh(L+>|D zPzD!fSQ}blb7+Use>z}$7zBsH0&oOm-BkOq2|3rgJuH!G1Aj`OO@0c&3o=lmQ`cUl z34^zZSQJWkR}4Ob#i4X>k&rz=hLW%lEDcM+GB6gFg-u|2*cw();U?!;hrSwOG%VA0 zPGnR=E0t9P%JZxy41={`Sy&s^fOTLztP7=>^$K!LD2G_w6 za2p&6cfz4?9~`CH1ULsc^hFq>;gMQC!%;8;d$C$E-iK0*i7*^ahB9XP07|y8C##JU zro(m|&w$Br790lW!1v)iI04Rwlc7|{2QZUksaFLhw~OEpQjAYE9f8YZ65Ux@aEY1O@K0DRYyDS(5STX-D%Q{u8&Mn4|)pe`0dq&GQ3CLgN*L60h zSsmrkdKvi>u@^KNB9R(MYs8H#M2;f4$WtVkNmE6nDUyVYMiwHQk;BMkVGb1RE#36~uNMr`G3fY5PM*c*CLkWj8MS38kkvYgJWDjxy zd4L3lu?~d9A&JOHWCpSZIS|&9O>j8wAc5foM4BQ!kdep?WDRlv$wi(bAw?)H(i}-b z#vu!k9mpxsyQ;y$uij(UL-Aj+DEIr;t%9 z+{waxl-hEQRlx)&dpDvyze_pUGxpFgxS43^@_v_+009`;k@Td}q$;A+UZ=AsOP56h zoza0U$X1*ugff=TAEHtMon>u$VVkSDfoxxENtoBW2dLeFzOOMfSI^M6Fd$@Y>WOXW zklL@GN`CJ2ZUk$tdIk|2<3iR}#QreI85NB~%Zz-nYa!W{k&tw0DL#Mw%7&}>x@PZ- z-py5^{3L{RBI|e(YMkHqiHYWFf@s>JnU3a*{C*j{EgCEsS$Ci*Sin!yz5p6*8d<+V zGqwO<@DNAQhK>ler-0M@A?W7np@eHsxVxebc1E~x`0A2e^ChMUr!4W|p4uX$cWrkh zHO@uOUK#9UDU%9TC0^tE6H<$t>hfW+;AE3k4Svm;&rJ2H;jP)MHs>|IR3R0$={09R zvsTcCcvmgx40cdB&MU8sJuJa)r5*+8nWR|ScDAg7M3fTjFX$X^CX3mPL-+75 ziwyXXRGOq4S%~aG&LR&Gdoi}fA~lfKNDAUc79yLGqsT4f1rid$jf^ynkguT}GiJVS zjkM)w>3ecVe*W!jiZF{KZ-qQ7(@~4xF#=4Ut%H|4n?h^_2>%JeWc!|7uebabRjrGu zq%9cLq5o24ii*uN*5Ch2^|z>ALsg-ZMU_f4d4HNF!TyP;3Zm+YYIdS2%7w$z^7Iz= zi8`2Q^6rTthN&wtLWr@S7%^S_6B{O~La6>grT(S5D5}D!%5-KEO*d2HyfU@yhAI?Q z6I9o_`6swtRAH#z{V!F??x@01DO4qT_{W+hsv@ZVM)gq-Q|-KSJrPw=R291Xzhm|3 zfvOm)+Nk~=>pM|l+27g})uSF%5{`dWQZI!uhfrfL)lf%NFaIjb>`DCM#Ggm}{XL0~ zs$n{$9aK|Idz*?mXaS_oqe=gn zVq9V6IIGs~rDmrP8l_{MU-E)Z|2YwhTOMAU0lhS%Dr z=R3*dTdygfUxPlT8X4Lr$Ek{`NDpqbG-N8W7}<&(MRJipk-*|S&XG7I5lKU4AghqW z$YtaO5>kTi#Uag+6l5H-5ZR2JKyD$1NX&mk8bb^VWUCKvfQNeTP*z%v`6ZR8X}OWu)(L zxE#j$4rj|@lJ9Vn9J+mnIdYigJG?K42YiPGVmZw99aiBm^9$c;MH%Tk94?1(zQfsa znB+U$B!_O_VU8ST`3~>P;Q`-afodG)`VOmbn7Q6}T2V&&4u{KOobPb9947e=H&wG( z)VTFjEf=kzQtK^2x+~k~`qAh5%jXK+;0;&X=j!5fjq zb@91I`CJN@k?#y+A4KihNUocoumq|X8!d&@l{QuHr(QG09`Rpn=ztFfQL_kcREg*MJlf7TWRzqG{?;lg3?j-6yY*hbs+ zqV1(^Dtsi+)@A8+H zFxPm$;4D)SJUxLQXv27w&-IZsCuWV~&d7YAIzqO_3Lu;pf?{mP#%hT9LiO&$epq zR!dQ1TlLLWi}$^;9Oc+XydQ{HrL09&-)3p$88POlDWW-prWKk^+bq%1IJ6WClLIm! zAFj|S?vb&vTF#`B+bP-M>UlLSN442bLj3S*HI(Dx$$N-1wp#-E(PLNMK!8i$sjxaWUShtpoWmveICWu38F!ekQroD>2Yp<$??y)$H9{1Wk zmP)>sa%B%^iQ_Cu-m}cqaUFds6sBn^^erc%8_$i=1*pHTESP@XLLt186RxIfy3XfF(K# zhv#-b zOuF5xv(w`swSq%SSF$KQRY&au-|ECcdYO*u+(BB}SWggXX>vz*RIWo7X=$Afks6yM ztbJ>c%R^Kd4lOlrH&av9jSI-@U!F;Xt3-IeCL^g^jH?=aZ3&F#$XB*H{C;@>`HmBL z{k^HpQ|VvRY0Xo~4IQECL1bV6?)KBUwfB5YcIPQq6njN4e{HE?>!7_{m7{_V(}>u= zVQpJWKZiQGCMZmGJZ$mKhI7;e!r0i`VI5zKJwb>4F2iHdTt_nvO^I))E*!qjc8FMO*0!ksd}HyxcATSPkDy`Ch;=@i?nnG?(6yquh2|KV zGe`X5gnx_XXEfiTY4WXKoVlX;1#nZ@zNd3jtNwN&%9 z;cXJ`H^NOueeI~#)=`J38 zVD*|6$We83h|E?b>x>4x1d-!+!nLA#gl2w2+NHlH{1lo$(Y!>{d4; z-sKlCxeO{@(yCu9U*2=5{SU-`N|m|Y84a1V}QF`vkfeExb(S=qm6 zDPempP7AJH)#8Je_A{0SbbN1|A<<_fT0737hM)1f06RtVH=1E+Zl3YWZ1h<)&(W+x z)8VXNoF$@pf#wpLZ_iqy&EnXERXr7W&f;CTVpMmIaQ_g_6wj#c9O1;Fh1={O?q>=2 zl5mAk7dY>ihfe3wyh0O$CgVIQh=U%Xm9I1SM}iob#UDje?nl4KLw`hLMDrIK^&`DK z4y`7={d1x^`6G8hqPk5`SLfHg^{hWx5>>TvyXr3_ z&icuc-*v<8c)Hv{Z4uY?^ll85VX`v6n2(Xq@j|;yRhB-uiDakh#P|3y1HP zlrkSwr{7~Qf9@sho+M^7I7rCoJb zQSwq|ckSIwHT4_fre3pz;Gs2#?*F4X$Rn(~GzW=xnpJzyUYUw0TP}~4%bpX+y&w&z zyQ-ASbF5i2{k-BWmznf^?OgVDO(?)aG55M9xTx1lR_Jr<(ks_vctyhuYstv- zhNXk=nbq$G$>$@Hfp4+Idc)Gtg~L~Mayfd)1Jl!bMjxT#>^GTL^^nJRK~?@HgD>51 zK#uBqleC4DuH+lBA(<}1+O}YH0sR!{Y_4$IHX!eX_xMcsOcT$P@x=FiM`y$|U3ex}BP zI7d@YIJM=gpkh*E0qW?_mcSsdzt+_M%lc@Js`Lw)WUGdC0PCE7HalfW&ASX*wKNZ= zTl{G7i=}31ZO!6RK5IWSixAmOoYwJXhdwtq8s_s$kqqJUTU(oD0v=PqTGOFVvyFyr z>S2CX5XKd-rkI&5XWuMf4YE0y;!!0=e*I}5MbyAhYk7x0xnqq`#cpS4oDga)W@a*{ zhKE|)n3=Ju{o;^mS%EO}!R$&@{8ABSt>IuEr6uTzoEt`DnL)h@v&NfcW`rY3rG#4} z9s1-(_K&5P;oMo_);I?f8UN@n!imldCA(-5E5=WlYh=e1wZrd)*5WP&lBx?kEF?_l7jl{rYS@784~vkcjWl%X&( zLc3oYQ){{6&0sA1RT-%YhFIAJ%2~@89So_o=tK0YpHQBwFN3LN<%!OSDEoPNsU8{p zyox5%`dG(kh}ZL%P=WmELmF0hReTHHsybD{I?gOZlXfxGjf_Nc#32KZb`^2R@FJ%o z*IvdC)J?cbsAR2Smf-@Y!2C-k@+u>P{gtRm83+uoOa;nwe}82z8V~90FRED2nH>6) zMb^8uHn6ywHO|cAL0zk6O*hl&tNS<1;VQK{-qO8qs&4(*Ojn%UtcLZO$w3dM6}`S5 zyGLz;(NSeDt8E<`V3rQ3Km+S(hu&!z4VCmp{-ObmT<;5vhOgDZ$27jUhSpOK{bpsS ztbQRXHlh@AU$$yw?U%8F4p06Lb0Kae925IY;_B9R(MYa|VsiflzrAa{^} zlKiZO)IfS5BasEjdgKD~04c^!l^RGQl7=iqHkaZT{j>t%42C^PGjQoZeDpD&*10)F_AQ-23{KoLmD6*k*P=)atdko8~^N8$So3wBqDBPA#wn@fCRI>y*$z!NkYaU3y=fI z1>`|he*F(JW=_Wj&10-GZ}=XoD$|`&E*vyueQ8jd*H!1CFRs#v-+1f^z$B5gQ32^#nH{&=sC)6u0nLkaTP zaP|VM_h@ARBM;s3GR!Qh>a?&`RFP@Ud@RhDDB&oq;?tZ3ZE57BSW1BEp5`p$!r`kF z$#t}3i0S`8Q$Dq^KmW4U@pj#<{-!Wq%XQe*;r^x&6*tw$*hUNON+)!k0VXUsl4a{W zEjiV8fT^%bO=s9KRaBGHonbChKmAPJJVwj=X@yFdU3^+izJjE^)S2cNNX`(guBWpB zBU=5F&i0J?ep(rZMXQ=4oMPQ@$_RD~q*Jas{rL@l1Q#2JuUwMT3jZ?orlQ{_!U!Ua zB|?X{sR$gt2(mB`qrD)g>I@_Q>(fkj6*t;yH{vUX5iY;YC8;w&k0HY(8FIy_EhC-! z+k-L6HPTta74He*EpiO6d~&r``$d#O68Zu!R?ivf40b*7)5%a&OEi@8k|3jwk(}2! zFs~xzlEtWJBdMbp&D5m!da2AbVpQxqoa>Y)uy+AkJ69{JYztc3+th%45N)x9BRqmz zz>rIV%ZZJruQnu$CG~AGB~=uId?N;}-sOxX)%6mN&~W-wZH7TGLoy<#l15lkxgs&5 zviV)|oZ?AObTY&%sp2CY4Q&&GrK&OLIEu{h9VhErGP5btQAj0>as~!*(qMVQ!039RYlH_Rx9cU(JMMT{oR>Wumt4h~SwMzezihc7u! zYpAHT3C|7^xj(&w!5UmnZqe+V(ayRiGq*^#bF7mGsotoJe51&_-!wLyZpol-f8&Hjj*(>@448UrjkVdm2UPBswCg$W$Z? z*@2uw?jQlx=uMFZNFtJkOsz%-$JZj3%1^@|u)RsFQ?R=E%8TEx-r1LrorwGjWa ze173WXDx1j&AeIahlHL$=xzl1@Iz;m1BX^6bPY|(->UuA%AP#}lBl;nnv+vWw{Zhg zxGFu>S;H&|bf4;+_Ag^sS!C`2ashcDnKXL#U^Tae*dj3$wIqktisrTmvp6;x9Xm5y z*n%Awa%6x(yHQaMX)hI9*j^{Y!&}&*ZBaz(dx~LJ3tN;6hwt)9`&y>YESAZFLkZ(D zd0Sh6aaRF`T}!A7e`ADl9Iu?>F-`Yh3tY!fdrs-Ob(g81TH2bJBCV=;D_cohNlv@x zj72qTWs7p)&`+ypZ*nVJEsqrkf*&GyU@3wZJgbLN?Q>W>bhc*OjOL|=zF<3JyA)%P z{&9vZeR;%v2wN^$`U~c=T#%*zP$oBSmi$nb_nLT?I@#J*RGq*MsQR;>YAB z;-$<)+j13_%g=qhhJM^(#~swpR?2mPSLwVt6mkZYpfv`VqbgOUKuV#zu#F9X-|{Kp+%PJmq*MB-AIAd!3tS(V=YY#9LwFX zLasrmN_)!|>`M1UlXIeyXm8m{S;mOBy8epgea)l;r_A4hQJ4z^0sI6T+G z?CMB)vXI>rz<4LG9Fk_LdN_siXLYb?c|R`+l_Q}mcbT7bu*JG?_%5s-VeWdXcheWA zp4gEX<%#i1j}f7ccC>|<<>*>RTOn7>y?@7FsVtqibz?o=QYBKaD^*Rr!&e&f9zrSo zbbF;zO)J&VPPSHBGw(z*kLG;aJt?STrac*j;w-8-e<3iUb@hW90`h3@MoSFY1R zk(vE$Wqm=m6T}unkdgPvXlE>u>O1KuQLQehDx$iBs&^NE)pk);LRJ3(vAWo5x^Vno ztEYb=F)9q$eU|G?T`^{zHol-Em^kZN%8CnK^C`-vxL zalIEC-PIPSRZ3Tqs!CFqA9@OGJQEbIjNNRZF0Yq7v;Wrx9Ndk#vBZ7p7q^(Q7syvO zFRwQUWUEG?fqyWc?@qyS{9g+`uRAfS6Jt6tb`v8Shp$QIvQ=OP8}d7mqb!fVbPJNf zMk>6At(4kPkMThB9=2d(Bh|GB_gW+MP7m7~c6~jG>vX6G8Lz<^x<2w0`t%u=;OsrQ zb-Z5x$3picZcXBj^~QCbm9OCRw3W*%^i>H|i$Fhn1I<0l2}<{}g}A(4|ECj7??v3& z#I^nD$sBQus+-4*ekU;XCJ@%(t?AxCr_b`6N|WAn*Kjyz z`}?b=qY8c#)swu`$;FSfqn!T!t@)({Y(~IxfBUjaHvT){hym0~a{?xM0;;(esF#1I z_6vb*EeJI2Z&r>5Qp@7_AGJJhAOTwv@D%#p5>OofBVeOJ1Z+jX(B~F4U=RVt@jn9o zPQbv{1RVR^bKNHV6jbcrb>3$%iM1ijR?_%ru+6)vn9KHqsM?~sfhy-sQ-lf|;(xi` z9D=?b`j_a353!Yr!r|+8QF%rckv@_gBpm6)#6xAE4U(FV#y?VXEBv6jiwq{;>v+u$2tKYyp|m^T$nH zqj#GYZB^PLpMA_ot2$3O8)gkyOu&%tzmj9@>CAWiZ-L7161^W`-sKgGF7Nucz0XC3*#_%9R5|b3TIF5ilA}m@ z0IL3GPs#_cF*0jhA)nvlVFiI~0||81Y*oic`RAh-#k=Tyo)azGd)?8$(x?G zN*b$0C4bly)!k&WsLImalDxJzQ%gNQZ`hP?9MwFSYVKh5RP*v&dJh>u*Yb{m^)-Xn z4HdKjSz0a5%HIO1BhTLu5;*Qn;JPGme4Nb@-hiMI%&U@1B@^Q{(lszo>S_&8_VKnr z*L6=^Z{uF0uo+m;A!9%}3*pDxN*ULve&cN=BGwr5W(CZZhmIzMM3f2B8nt{p*JO>_ zs{>Pap>Xsh-rdYdtOb-74lDP=%8UE2aXu7t#!#%agA;%@6LEzg*SAgbCHx& z)=wIF>f)BCE}9V9`-gQBYj4k446k?U*gLh~yZutrQj>@EQzdSjs>J@gTB~`I>LD-w z@>g7k_8Gw{UJP(ApCd!%yBd_{@|*4M*?H_HngyJ1x|^w{#~|riZN9G?Bwedb_;rJ%YqdSTx1 zcWLYe`C&CHyURoyzyGmBmEC=kt%S)~NsXOiOE$|Y(zPkJ4Q3XDvS)u_+ZJGENhQ14 zN4EVIw!+)y+S*wv(?;J^z2|aQkCAoQ7cvyXE=VO6 zGvBt>p|1=W`K?@AihMBNHqOk{J$v{98^7GjBs^ykKWOgx*jC=bl$z^mG-RvfpX>#< zXWFV79r`3#jFPqgg=u_iWt-~IC%rzu2l$yr-dAn6+lr_K3vE-)GOsPMh|}iripsk#fwQx=7U-mV>B}X)BV>k#h+Q09_PVQ;xKp8bqkiEV}c~Q+5Kwn?JXum}OvJzVgs7owZPgu&qP6sz z>0ff#v(}dAV8HC}S9KkAA!FkL9r?X?)jDdFk+9^mjai1f8DCIE3~seJ#q=r)Tu&7- zj?M1A-qz4)mNDt48*DWl`Uuo$i12)?WP`1kSq7ZWjVSfur6>=!aE7R!8*N3+j3%?k zZj{E!;4ypCCb?Z?tk`=Sc{#C}X_*WUuWh!CH_K43_ZA#7Y`eC_R?{qlv=R{kRP~pf zN5*CCzQkKbVVZZAcr)-)`^8&ER+@M4S9r@{s>)Y*%g{;lc8j-+mX>{G>*rt)q!qY= z=i+R&RW4MT8?6{tAo6Jz!xnRo%Xp~Wb}sg~tu%Cf2xK&Ptl~v(qbg;{qlGvuM>5Lc zXt|j&jqV+ojkgS5v_PBXh;d1F{T()bW8jgh`_I{Bn;bsF_aNk_P3ejGD}lIGrQNnO zWrpJQ8Mc@BxmYs-H4(1iSfZ_i^Wl1B*<%}0#$`yQ|A;`UA{Bf^k_VywEq!sqZY3}lJ<2`mQx!v2lBJdWphG=e;V+#TUR za4>ucejgTwvmk~H-0L8A3f$Wvb_m=jA#YB)ufpQ+9^~yucRrrQ&EDIaLhA0nVGlSMz5|EADKHg&0qJ4fyWuc+0uG0lVH*4` z14lZJr*H%e;3uHBVF(-vOT%|yWB49Sgk#`9I2O)=%Y+$v8^Fsjxnr23x`DFdcpbCqVi{_dGZgu7I=PMmQVpgLB|_a4x(E z=fU40eW+VzK?)Xy3t+ z;db~7%!Yv>bf~Zx+zBheU9chC4O_rHuq)gP`@wzi9k^ev(G(m9U=}jBljRsJ4Znl+;BlA$Pr&~0Bpe67hx1?#Tmw(Reeg6q3p0Me@jH$)P}bAV z!ou(ztO(D;*Wr&a5nh19;7@Qeya+#mm*8f286JUG;AMCf{sFH+dnlVCU~zaIRte?) zzk#DM9yeht_$%xIe}k#;HXIG_!fEgxTm<_EJQIL&$?hhe5 zDclQTO}GZug*#zAcnmgz7hz-gJ8S}oMk0OiZ%t>I9Z2#3Lea5x+Z)1cS`ONVpe2)G=+3%`V;;2}5`eh)FQ z=e`QZ!{6ci@CnS2Ptn_o(M94B3Ma$za0;vgr@^LhI_wBPf=O@&OocPycqktup9$x| zrEosn2p7Oz@MCxy%D2X^LoEEc|AL=p;0TJK$AhKd5?B{5h3z1=gWUaK790zg!?{pC zLcSWVgnQvCcm{q3Z^O^wE4UgKVr^p$EDJFy=&l7fz-BOGBaSXO ziO2VF1R^cI^3EvIx!4vR4ybK?}-{3>|3OW3jgz`D?Ch!I90OhOS zec?+u625|NXkeS;9B71#GjL#A#=Ra|;T~v%C!u@>{3qyuw_!f`80LqTk_;kYVHgZc zLbh|bt3mlZcq53JNOwmV3I{{^Jh&T%!%SENW~|2{-wQtknfAFaK>2R?Jy;wD@H2~i zKfDl(gk@k9jD=-jGgub(gyrDdusoawqv0}G0d9ja@Hngpufs~%pLG9)0|S=spwjes zusEy=E5le=57vaOU@h1k)`Rltiu!OIl%1n9VH{ino5GFo4Y&`!3D3c1@D6MR|ADQ| z-2Xvk7)0Vx9JYs*;al(x*a7x{UEold2*<-7a3$;sx58fVFzgLa!M^Z1Oo0z!KWHz@ zSP_<;(90dOyTA0C7Y;32pUehm-6!|*)(2HuJ0{y&1lRDm7}7KBG( zDR>N4fhS=c{2nI2A7C;(1JfZ!Qr#2b1vn30hAZF|_$9mwzlPV~8JG*N!Rzoz29BR` zSYt3&3k$!8;C(n2K7b#>hj1x;47b83@H_Yy%!Nun&9>j)r64G&mM6g5%(4&<(f43GfJ<0)K=bz+d5q@FkoI z3st8lgcYlE|IftH5RX}~4V(>A;2by>&V}>f$8aUggkQl=;4%0qyapG;$8ZUB)}V)k zQE(Zo4YOc#xEv_>*42cGt7ot;J5HgcolvHAH%IMuqKmG z7y);}N^lo!3irWIa6jw^55RHoAk3JL;}DK@@Ce)uzlF!)QTQV~2JgX>@D=1;zsV(Q z(F4La;063U!JjxD4Y7COo(*rnEO-?Zn5LWD9Y%0G0!G0} zuq2!h%UUvcD&fEuk9#YOf#1N2@EoiPe}S>^3B+uN+g6u>2n>bwV0l;{)`1ORI~WI( zU_4BNyjSd=0C{EBJs0u{ta}Y?m4Ra?j@IxPOn?_*d-yx-1fRps&{>ax2n>aZurllc z8^fNk9ZZHvun$aw{ow>S0M3O&pu8BC3crLILvb9#kq$4y5%72THZ<1fHiWOi(Xb?Z z57vd_VN1v>weD_E3eq3C;dnS1&Vp0mQuqN}2S0=d;YaX?`rQ9BaNNLSCcFn{K}!P$ zB(N}?56eOY8^DFIHCzNoz)#>r_$izZ7sHis3ETvi!u@a=JPxzqCAb{^rvdl>3LLhE zOr>CPxEj`gYhY8j77m8%;28J?{0OdxpTZ4rHQWfZ;U@Ss+zijaE$}A%625|8!NQGL zJA!31aO}WQ3+{x?;4at&?uIFF4@`%9;RLu3&V>8nYIp#C1rNfn;USA*O0~w^z8t>^ zk8ykq@@l{oXB;yr{ENc#Frx~NA8|B>7hpU16YLEy!XfYy90f1K58)L!A6|u7@EW(- zes~KOi)X+B>p=DfPwoiWxH)+cdSv zmHWRO4t5i}t3&n(yPH5Z1iKR;yLsI`Av<&3Lm``Q-S0uR)VilZHom$uA)8p;DS;)kgbGnH*5~)KsE!q7ejX4xi>(z*tz#Yw$iyzLiWPBe}Zg$b3cF?>_BtB zz`=GixA_e^7#ITCCgv^*+41Er3)$Y~t^?W2m+1L0N3UL^Nz$YvS$W5}KtH$UQQ zU!w_xY#?xl!eOu^91bhPG*}m=!#Cgvm;m2~-Qh^s|4r`ycW{ir<6Sr&j)K$RXt)5r z2eaT9_yrsbv!Q&o<`5hYzlZO`pP*dQThI;f!wK+jI1yT!F*SoOI2ne$hT{Vq@?EbW z!*rx^cC#zCE=C$dkf9+Gm;LEgo7reArp3m-^K<-%_Xo?(RqwG8k!s#HizU zY^^ME+A6BxU0ctLd~LaB`CHdV=V%kp=IXrsiqt?7kb%f#WHE9Wxr_wX;7u%~0n!l} zjm$yzAZL*mNJvfIdqsL6GmurtS>z5)MD{I3CCz;6|x6;fY@uJL|P-GkvYf# zBLfjPl7;L*E+7w($R@lzjie%zkD&rm~IHE z>PmBntAXyLZB>&dZ&jUEV%}SS8)AoAw2~zF;)XScBxWZYy{4^pD9b7|e09cp9!-^1 z<~&WhX#RsHaV#XnmcHUqN&o%XDob&YVjEwK3QX}fTnR@zd~#g4IiSRwe~vVNz{gZ4SWA)-t}St-H6d>rCBQZ4P!d{7ye*5w@U7B@%A0ynVHX z%_dh=^cr)~h$}|6Jb3;_^h-(TH%#AaXx4%!uQ4|>?oeyjP$E9WV_n2s>Gk^?YnSj` zWW2mv%9;~_Hb4<&2aW6ms@>A8f6hS`0SlvUXEsbI2H)b?VQ9@Bi&jV>-(HK-=%lf1 zT4xR~*qJ~D4N=-w7CZGOZDrY7b9hEqEjG_dn2#9Up%kG9jDWph8JGl_BpQ-oJWPS@ zU_Y1$2f$<~J4O1!K^&*TA@FTD432?maH5Bkq;f{!@ev*);d1y6%!Z>>`*r5-W@(XH z3C7`HkR338pc{=ygSSmy@;o*kCP?i!yJuK%TlRqtIOx_G1pl=ALs!Cs&W6aWg zwG(`Ve|bXX3mL?I^-<`-hZ&Kzo%HmpUIB}bPhXA)7GaPL7xTxEAKZFW?g> zOOX~Xsw_nY!A&p%$`WKH_!XoFGi-&;p)5%z&<$#9lHKvxfyYv~6JCe1Mj6gCQPwCs zLAj{>SZ3JIF+T+v4nTgl(AFwLXxp+@$x^fyu051BN*a*1G`S4Q(&PFFC*I(E< zfF(UixCNCPAhNkgV0S;!9L6!IG) z+djgY8@I&QHD(^NhrHHQJCpt|iucUF{YI6Y6&M$$-_d`X^X_PA8ED_175I9={H&hJ zpB<@6iV2cpC1YkUd!%)s(O@+^S7m$Ii<|lJR}J67X3%jj%wcLyFZ&NhHi=#{6;h*n z+e55_2wL*Fn%CQ2)>ZPkbQOAkNQD^&sV&LuoV9As^dxIhqfIR@hgIUpB)i=>NJS^v zOS#JXMUu#aRL>-PIadWgZ>}=lA1B#k9Q8fkg_Wzk9XkX`_ApnnUr??aK`qJlcE*9K zQ?k93m8~V#$IsRK$@Y@2$9^Flgd8lU&Gen^IFqppHCR3!QbOH{v14_zkG(J+v16>_ z-@cEgPS=m->PLJeM0BV1qlaUx`sUyeEp1m{J;5=UoT*yXVz)?-NkY1JdS5DHbc{Vv zE$nL#B$0pKW`FsfzV={O@C&^jrIVK`8LW(BjiC`z4TG7m0qw6ZeOhsX(5MOGN}<-e z`^A*17_3^P*kgj4zsyU}rs88b^Wqdc))4&sr5y}bJ5%hfs5whNYHkQMm;F*z?q@IV z%Jzhm^GPv=DB~oaTtifp4*B4UC0tW%N%GV}5$#a>=1Nh`seN;$nC_IXt4QBIME~YW zam^V&iDy|_f2sp}O7ba|NX^?IG z(=6(GRMP&WwUO^Z+-y|`(>Ax5^k|}cP1Cg>tQ92Q;wb7UiLW$%$~D;Dn}+mou)P$U zuMO6r7L!_b+1vuZenapZir=h!CN+DA-D`$WS0dH!HPJax zwMixRaKZ#RO=?uCy^ITo*6n!5M5$^+s@-cwm@G(yG$KqULeZgqr|UNq4IdG-u14c$ zk4?Hi?;t3N(nuGW^SLuz{W;X$+Ens+_Ups!MU1A$&$D|Cx34prvR`KBOSg|On<->= z#z=cmfLSZrXnR*PB~kwwZEs_i?ACwJzSAt($my1k@4t+(7cFix$O2?Daumr$o+805c$y%skrZSql7$>bE+a3Hke197kOX94OZxSAV`dNI4La_d zJ&frEQ(9>IJb z)1x-_O%{K{zw&ap`5X3CCyFcVI97Hpf1?@s&>j!vk6`43#anC86pXzd!L$ty?LtW_ zksM&e><6s&oZZCt*e`!a^glNny|45(wWwc?I7`}C^|cl!fdbz;V_i7@l|ZU$|E=>4 z&kJS5So$q7SRb~&M~rX3<&-#lk0j|ohpLBVcdhB893R+iw7I&qOuZ*{JG{aQTch25&;$h!$;uf5E(FYc#zH>%9aOfvi z53@0zL6wDIKZ*)N#vbG9(&vw?ZV;9wG3F&6gE-$KtP5) zz?i14e~mj=cjK?yN)0~2cc##JY^4UMiYJ_QJZheB#<+4k>3M4`O{Je8BWY^p2}+ym zrf&f|NE5W3HGJvY*5>kKIov)taWtoOD)k4e;}pt~Sm8eQ`>ZN5NpFHF}Z}pS5kS(r)$P4ROI)RCf)Cg4e9d5hN3D-_s3iduc7H~Y_^1|#otrd zboJTyWMYyh$+F~I@}I7L{@z(m4cy7K9(TeSXpu6eOVN3&E{DQoc_K*dNI}!3{GkyI zoc!=YFD^IvCclD7dC6uD4Pu9%x0IKd;(f_4LAiYC>S2zvw#zj&uR`TXL;0|L?RlG? z+IjyJwZji2*78#^ZFibJ?7%6q$B|Y=-Y#>57#j6!J|#~RtqsxY>e0%$aQt6m9FZ7p ziP4f6_fI>^IB@8f0egwG)~Y`^z4mIPasNQ@b_D;C;OYmy3Wh@qE=_}i$PQlLNayWQ z{O;tb`jOIUlroM~mNVRRBUKq4Z|LZE##s)}nL4(eamMHM4lmDe&SrG?zfR|coh7E~ zo;j~{ci!%P4rivvBPT{fEB%$G8E3JsBz>6koU@Ht`l9aVoYNe7&tf$6(?VsQCy?|I z8Rwll&2q=q|B=w#blD&M=;UP+8fEtW3(gisvs{UG7r7FpFY*O1sbG%cJ=JA2%+$}i z{vrudC)qKVoNJ8^vaIE)g#Jd(gUiku8Drw5o_Jayo9V`nBDsic{|-aqkVIr8G6UI) zoIvg%0j+t8AaO_{l7`GcRv`zF3&@{HU>m|AaY!QK_cymq&&9A znmo=PVq;EZt%8sCyuYMwkF%F5%lydtibQfL)2?1f;OsmGZ>-(7%!Q9AL*PVmdr!IM+CyLC$1_=AH*nJ!YHgO(Rq+}2!m5WJ=HVoJ zXdwx+nJ_Z${zePKKnqIyi?RQI)0 zMO3AtHzP77FmBNc;?3oKwR{ruyJ;S8>1w2xysz3%wCjWF`-;4jG8Onzy*ta^+NQs+ zdPNPI%$b?0TdRDj=1sO&a8>zIPg$-k9jM`fiXG`Fp(@U%;HmTN_RJ{^pC4#BQjt>_ zz;5?MkaNmY|ACy7>q1B!c-;u^Q98y_%BHL^A$33@x{hm1vhpWV5lx_(IbTZAvUO-=mJUcm%^ zpGT&oD%7bDsf$1Kx_I!RJN=6uDb+CzeRc~Y0`n$%orL0Mz@a983~dtgun zc8Gb)5+KTW-&NT;mDB#rXTRlnqY+m_L8b1b!mL0PFJv(0$rzZ%?Emt@m}*s zD*i1#q4}Utz5s$e9Eo+cQ%AT>4otHLL_G4l0z;EW_Lc5TBFe+>5%(0ci%04o9b00! zHWjBc4++Z7t0Z~I6H@NfB+-@i=%k2J;g8gW=}d%T{Gv!Rdc-F~?Hy?9mX9bJJIJhu zvsLAf>}4&7C8Rq2F?FL=suWQ@{g{Sxxq>}RmCwYr`6GLn=|;9{n@QC#F3RZj0XL%S zncqp|!T+a}AXKf&v z(1yo)8`(UQq{g%8=52Ap$10g-9I>7|BbZ5EWxSLph}LYhAjVl->C1lJa(6#g8|Z?J zk5!vl%w^wX5zpJ4q>Fs~@0Ndz6s+vjv!?G-f6O9}>7MZ3mj6WWWdd1PYs$2e*^l9Z zUl2+9iDb2u>kq#($sJG3$#ll+x!GOySVHvXLh|@T&*KwyokAK(K<^K&RmiYL6cEPqK^O1X~vc}u4L(yChZ zn9C`C_B(|Xf+$jmIiic%n|FFC#9w+L{?ZFUDik7OMj?YClD?RYO@`@y5u_|6Hjin4 z^uD}wq!@qwyBKrlQ4BUqT08AiyXM&|yE=KodyDZ@icv`ApKrGspX$${r`mIfBjZHw z)u)n`Qm*$|r}b94T>7W~KF?2tvHpkiEZwiBe{C+JiY=g!OFfaiCwnGo6;f>%aI$B5 zfuE_N3%Hj*^GjY%^Gq#SU@zsk==D|y_tVJ)A8=Ijbzp@)=9G6hW$gp1(Z>|6HcQA7 zR~{>J1O2TH7&2ub@V7o*h}7Nb4Y1H5YnE!w0lsAT+s8Zr|5ndFCLeP=X-JOclKris zGb#NFKX18Of6E6{82+;)7Qk9qET{d-6GUz(=_vkIb2C{&`upF#p?2rX<@;M5M9pb` z%A}J2R*y4TsN)AGMWOCes3!;2U`4MC^B;1QRR^;8#?fnx>O5FVx(HzEzbg>YSu?pR|5Hq+TwxH}#Fn zS}bA>=K+cbp2Su9pRD1`UgTTDxuW(;n1_UU?hUg+!k9m?yIfu`sTWRb_(zrb#9r4| zhJK%L-am+%|7$ht6MNID`YN{!FJ%m0&tsaRbqR^f_E{a;|3`!g|5}+owa4Y<_EVB8 z&YU3fYqf8QsfK6KT*kECDM520yH==upW54+s;tP)zu3OdZepnV{VMzG=D>|+F(n_a z(vI^Ct@;^bgrJStjXtxFF`C+J%HH+4y_boRQ+AQH_LoLel`pf4d||(5GV!R-w~_Qp zZp-er(Z1ct!!-M~%@XNwcJ{0-_F+cT?>n+zerYdkGNtdzF1*b?*knrClRYt89G&)M z-`i^RQ zO^Vie3ZyYLn2KZ}hmp(31H|5zAFYu(NNXeoaU%W0sLH4EWwy!h{KVHj6)V6JCIYz9VDPV^A#ix>4A(y79(4c3&{V&*!jR!UEXj1 z9R4UrIVLG8B?T!ZB?T%8CB;ceFIOd=q9_VL13$sVuv>6H{Qk-s!G@BSJL5=IpzVdY0s=h&$q6` zxS|eCni8}U(M6taEXjHj-@lq^>bk>KHrwku*YP#@>eU6?d}m&{-`FMmyV~7BzD`Er zm(WLZhvu%yv)Ii$M7%hw#qNHG>v}v&E;JTsGSu`3yAtp9M&deWedT@L!f(28w!C5r z{14LkjRj`!pp!1A`CEJZorVRCVvMZr&X{3Y3f6kNp8MSU7T20ezsb%A5pe@*coaGp z`V=$*`WzJJkis89Z-UlCBcZ>BMnOM-;vLq)PoOtL{{&qK9f9J*r|$P8@mbKq*%e+fl(^_ zHWY6k7CsA2h2rntEcZiSg+2g10$l^eAA4ESpgmBGULpP_%knT3e`{rV1nQ4r&w$Q^ zVuch&Lf1j#pzEPY&<)U3=tg{|t8f!uWJB|yo1l2J+VVKm1>FqATfmkaD2{#>+{G8- zom30niYkQBwB$l@lD6bQ{{zMJ6^_Hg`xex=IlOCLI0Kpwy$bprC_k%ZKCcyLaqa(X z{G_locx^sGbqz3|rn(C(1?Cf1cYrxyrR(uN@9V5fU9LXwtDP$mb1N`8?+0din$L4R z1Xh4la1ZzfFrU|24ouulAPSiBCZG9y*PS2&+z8BPy-Z$%iSuCcEdZtsd_HV~yK&QS zs_UgYCI-$AF=rn9dmn4m{0jk-?}d>Ai@;j21?&X-z_EK_bNcvI+6Qb?$Kz*X$1T1L zU!{G(7UpeU++N!$SXG?8#hr4*V^T*}wYNW9-SjR(_RJ zAtEmTlL3+L8qFEYxhG`nXbMzYxvhndpf)pTf+Ps+wvb!x(KDscl_SW z>-2Q^PF?58|5EIaDE5p-a`fASzgFJU>>91svCW=B`R{tlkA6dO&{sR~cl31`z`}7| zcF>x5MFVQ5Dy#x9zbTRZr=o0A5Q1q_w7f_h$?|u%2Np=?g6EBQS#;m(- z@)b~HldprWg3gDgK$k=BgBsgxOfvpv+HI1bh8mNMKV5d4WMi6*={2VLA?PomYoYH# z)1e8eNd>iV8m1Au1ab*ja_&g|Q|CuvCRFLqCVU2JMB0G~z`cUL1k`0s33$AE6!4 zeyD5eXX9^iu7uje0oVM$1zZ*lVQVXka!1Li~MrULVUb<`|2mJ0s z+I{%MN51uk@m?Y0%Wx|EI1A^V0YcEo$#XFkeT>K*915brg0 zJeE7RdMYy68yp8BXeIl|k#c-!F>7;x{SUq6yMV)3bN zzL!(x3cmv-r{get0tN29!)xhioz*5~7wQ~A%5U%R^8Dg;nJZv1Qf8n`z+>L7TNitI zKJQ)TDljSKD6<$TKU?hO`Gj_vtKX#j5Ghw}^mbjg#4Fr}7w%)!Ew1`P{M6*!k8EMC z{3Tu!@zBhghX*!4S>iQUPnF7C9ZOIg_c!A*QT#tk#&pJ!fRx=xsYJ?S31d>~O-cn) zE+XaA1g|I?UZ}~IVo#GvccRJ9*yIy;j%l*yP89zUil=6Kn^R?kw|Vj9onD?_*DZ4; zFGZFgBg+d&asC3o6Tfq*m%q0OVH&@S$umzBTrtZqd6mdkXA(|&FV-Q=l=R%!ufp0g z)BlTQUa8(@l5anRUrwH#=rzYoQ-qrl>UATOXIDS2iUtoCrF0XiRGoHU#gAY5+U4f7p z!^c;6MQfzYw}$5Y13%7wWQEr<_vK%fpcT(1^YlVI1S8Km(2n3U@h1Jc7p@pDCh;2)p(yA#DJAxGuRFefTQ3X z@WbPP5D=4U^|7o;#Z6P**qf%ia7gaQ|4`Zge$%wkodc&o?Rk@b1qyqwz(W}G{kMgP zh(RWk0g>(+%}tXjccuGds{H=jEAcK5{xG2Vl&=ro&~ACb>PY6}UDFja+c)Z-0AE7m z{%7u(JpXX`9k&h#S$Ai~++CSx9UGC~JF3p$(tHHY^*q2}HK<|bA25L_IA3|3{@ohQoQ$N1s#(nDd!WsGj#9t0w z0}Y3!L2rgWXioWe;>E*=xCiF|_o;tBbOXZX!AcesA60js z`prG1IrR@h&8Z(t(S7R2S2eg#{ntSA5Pu`|Dd;WGZ{d{bKE0b`e>x)ap*hfRL-BX~ z?o&VhEZ?#f;TmWm{yPjUg0@4SftruOe-}Ck-3I+1=yvD?U!MA>LCvW@9Qu7|9CQa1 zpB%C{OYtHdFP?{Pg1!KK8fs4c<Az0iB1HBkJ8q|<%uH>dNTA!0jpAG930A6gBqgEl~4gPPO% zFQDDf1JFM~&8h#NP;0jN2=KL$02 zcPG>w-giJxKr5lj@8!#lWY#N=C!$pF!AQdegp74 z%``VD|66+e|3|v16ZaKP_o>-)pYZ>x)O6_UH#VL!=0WJ!J8F*WW6PLhyyu3<aZfc%5-8mb{-vDL?#?IW=@BYm7{NL_z z%xs%JnOjjaAm+8f{DrZ(UNa7+tht?u1g1;ow&q%k{c=3y_S{A+g2y!O*WB9NI|)l4 z#^-CdHs)%1YlA&z(kwo($>!hdQ>Zf_xj3=x0DHkv&STS!a#^4N?-2GUm@hTU-H0 zk%H$ea1L#j{cQ%|~3Xy^4<@?0w%l+1p&V`^&kHzi*xCZLal; z_pO;;&nOSx=ACTgMOZEC`JMHZzqM|+opWCR%nlE~@yD$3HuMM=iyJzfr;k||c$>cb zXN?u-Y2>);=H;BUc!>Y~II@CxumQnYmY8 zVaG8I`%(YINAca_$48gPtFBU$Qiqhgkn+}XYn;t=-b~Frm(@P;%JHuu_yE$b?if=l ztplZgfs}`l^1ZPsttJJZY8;n^lrP4nM0|vldZcVd$~Qk6Q(L)7c^xT#LCV`7Va&{n z&p)yT+WwBOO~563eh>7>@2vAiFDmhO)>#Q}pqM|tQ^91itW3`{Z@`+tS?P->ao`$6 zd(usOA>yze@iYn!MCJ5jqhG0f1eK3Jh{|t#4D)!x8XABX?pDkYW5-zDHXq)<+WNNp zXK-Cd=lc4)cD(NE=h}b5>WA2d6V~f&w~w|kI2U)L7fy`nepDw~z}aWqI<#>6Df}_t z=1%Lix;KB-Rb`UjMDkfAzt?FE4aW*v? z`D65C%0~6x6*?b1+4Zq?YQWeE9!J4zT^;j~cI;#8Oq4!@VgWCz*cE8gSi)vk=A^ehklRNUQ<=mP?cGg=w=r_ zEqD&OY`^!Uxds=Yy!BOAS{H`kEi(k!SY=(-umHUH$`G`;n!4~;c`ai`B0Do9 zD;?EegJxjdV73OkuoHNL_Nptc8+GD&@VFN?jdQK7^S6$XmP+21?JBi9}_yirqi?4L>H?H(g@bR%3L04|qlSK3@kJVr-(V6Wd#o$GVVmA^_E_y!Z)0U%_{>`1ZH&rgpIcMCjRi4( zB<=M{k@HK_~LVGo!bVy)Qhs%zAn57a!u`nLFYEa z(*RfUJNN~{&3)F*HtZmGZ=Q7xCgB%3F7{dXcw@J`_0k`#!(QHI_58RWHJT~E>rd8d zZ!=wA{K;D4jj?ro=g){SV{`RsYq<><@2+Y+{{-OpY3o+!$@_7|_=me8%Whcu{on}b z0_T7q-l7WuF<>Rw0PyJ2QV9+Md=A8N8ki4~&j54560jO<20OrB&MNX5~~6sYc} zma2h9+^m~;8y2zAlpCpm-=a1KQ`6N@4enMH{x7ZsQ;ae;%ppIaZnu-Q-BWE;!C$$^*QzmTJlyzh=K7F1P_f;nS4DPdx#zs+F zai?j*rJdBUt+?Me5y=^fP{F?a3_EJ6b*iWx1x)@n99oU${DqqE18TYQ#o@-#q}vy; z;RINC6YjsB;gLXw2mgxkHwj_87}1J5K@(2DnHreQ_##*@6QBGr)m}nvsh}2U=qp}j zxN|$T0)JOy$|Vdi9CnP_T~4iO#Q3{2;31yTf=vupYt@(FVWNr8x{mRIxMwzD>uzcg z?odrQP6WQK}9Dn9byF3_ai zP*lTk-WAlOE@}lH2AYav)qpQ<{!KVq_1n%eJwif$u|YF>lq%Y zqMFBRCO#cE@kR%3r#9pnvrvhtCwdVS?ORHk8IhF80!e!r zPSL(?NnpHvE8_#(sCk}|JIQd)>(u_ssoC#PTf?d8?NsxYwdsI$z4m|Lm26-D&s9u9 zl?+hFYGxccLT$N$8aRVmzMR^G=P#yQJ+8)RkBgcEuVlipsyEoi_(3=#6CY5i{T~p| zgfcmw@EC@Nv<+=?J^`VO55Gf-2SuhL+uaN|Eu}Wd8Kr91G``FDMEQuo4;dbu2m5C# zC|SXX;#a6?Mb!GaOdn}sxFLyJI*FPsXH^xZs!(#-GtzDU~|& zmoVd?EM3zl3`c*DnsOzzSY9hrtJ;>#_|QaZTrt(5#n&RIHJ}R!e?a+er&eXT74~1= zs2=a_m?5gtB5PU5i~)b3+NV-u|3dANW$TdB@s-nwlYuc`>tO1O#o@+i(_g70|Do2n zeGFD?|3*e6dr}rd&>@TXS6`ACo8_ zQ~VC{qkT)Oqqds?a4T72#Do=v%ouaNJEt7o`Xz5{>Z5W&gf>2FCx_pN9M@)BUs*1Ip zhvXwXBVNRjb>dsQSW%xklB%I>Kg)^+en`!Ei8^?Z8gQOkqlThpGn^(L5**8Ll18TE zMz&KO%J@{bufY7L$cZ#*8xF~N^k~0!#Is=WyDV6%{hlZ%lCJZ2t>CXj`Q{$8gqV)F%0Ygf@nUpQm=Np|;8= zw8|%BZeV-`EH3;X43K<4sP=D(d_dG|%$WT>YSHb~vOB1?@&&Cc8E)H8EyW5k_2v~b zT+u@~;)Z8tNvEn|GN=Dbvfsm8(dp--tvKcU7=q58^K z)c=6tK>3QcVTSV;;QCEZ>*Or5?qfoL)&t~C%I$@;>t zX1Q*q2Ty0XPm4NLi@MdRMb^KG8Dbx%*8Gi{uMwzIhw2Y9zEeJ-R3$Y&%x!Tj|y z=|l38^{dsZ5UBl|w~yg|8Iq>&Gh8N((ry`$fw4>T9$>zj)zo}x>OBnGmQ!=w zrWd#Ki?#n9GAOO_%#fn}UmMGCKqR$CPN^h};Z&Sp%n)Z?LyeOLNc%$>-zXiP!ElZi zcY^sfL{ovypV~7~8RUfe$1#jQ({Sg5MRqIdb8FA%)V3ySjz*$M9W%e8XzGv7r=A(4 z_El1goVq<8TEWFqr=yZ>DZ@!$sz55W^a!;~CO3I5!|6YxcFvwww^&V<~;`;*CK^d^lYnk4y2EuM<*!)0+xuAgs z)G95$o)ZY8eM|N;OsLl)8u>oM)jy>s$W{;O@L2F|#+QUr`R zzD{-`(HI`I+kkf6{=ZFA(BHy@6m7FMo&C(mWlVw8d2FaaXTM|}Py(N3dfv;_FfFdA zA2OVHgVMDqgJlQ8FT?elitEamA^aq@SgW`|w_5d=v0>XGrnlZgt&nC*9nx|QefS@l zuRexa@=dAEf;piWf75}ukEla8QWIrLbH2fF@G@$@Do%cv;T~ss0q50o$C~*DX3YMB7!de1fBp;XpmfELhL*2)B>L_Bq2TZ%}=ezcqy68X2IX zKQWxwMs1gAcQ!c~QL01YU>w7JdP12d_nY_$<1=5Q4(W>9?_l_h+;hGR(};XYLL<}b zidAkJr?N4?9d=sMe#?Xgt;VjdG zv;vp;%e2I&He;4MC_x+YM*E7CbZ*4#*fUV*2|oV)hWpfTw|s#!Sk53tJu6kg;2T&l>`E5QR0THehR}ByAFH)9qKeJmJDCwpl#eLZ z+UYJ}yj9NuT8_BGPD{cJCZx(K3}{N4Yoz!%($T)9G=UjAv|2;2VmNFTHAx+7(ydv}!;J6IL*;^p7*5qw^7hFL zkNlZhC!3%7g7U4A!sNU6f4Q9z*}B4@PZ;i~qlW9fobDSKu2@V>|0dT+#7c$>mMQ-> zs%;82tBh)uX^#$JIct{of7Ci<_&arQ7d3PzwRFwB!g3Kw)U4UmfoWQ7K{|jm>K)Kbt@6Z;%vk#eRp6i&R8aF3pVFiF9I8$G-S=+{ zcghEJUt~C1Cc4g<%?O9QR;%VJX%6Gh$Okn3Quz*2iyx<^Xq$Gc!htl#+f-kv>Z|*l z@q?bbYq@o&O)r9UTb(acnv=w#tJQi!}ZD3b}hbs?e|ViRcbubJ7ZP; zCTd)`QOtj}hPqaZ!go3|_}Zvhe$;9&YJ=uDG@aoz9W>0ZAzQJXdnRz?f>dAfAmdAA zz#@LkaNR9Xv~OwEl?U9)f+L%mq3<(lnbt_UrY5zD@xgMprE<3ea@!6Wq}X3E-#`?# zTJF0}Yo_Q``TxLa%#fyrYKIvf45OCHou+GUlkQ+g?b_#QYAE$}<{wc0qAAQbpqtv7 zT&8#4OU-Z6{*SF@M6C}sTkdw`DTW8;vZCtw43{rs*r5)Tyv6vzXllBP>MQpgEvFNu z#n|^I)B7T|{}bi4(q)@N-)4p|EyA#u8Sc^PHA^GVqw_#j3)8b|sI_v(QQu)WHIy2y z`s>3qg3j4|QJ%sKeXmf{rR6&L_)cVez3yhKG-6f1VSL&3)aVbW!CJHfdJY&UcO2@^ z_8PV_pVRg(U-ZchTQ@M=@-($-DRuZd7L3s1t58MJvlw4-Kl7!Zl4`pJev@IV+;Tz) z!`(@4by}*PVMGlLf+g-oh6_HVhRMri$?c|Vb!Qebz34$|k2;q4Cx%-!b!oB}iE_UU zk1##8*(l~eU*Tvfojg9;Wt9p@w!*vu~s3t79!HUm}fDJ;6U?KHmUp z+n=Fm-_kD|9VP!uc1MXQ{>Y)Cdjv8TS>!!07^0mM}e2 z?z;`{+wK3)+|7it{nVso)HH3cavi}c&M-c_j2hv^xwpzU6lo+o*-3(A+gW#Ec2oQacBz74qLz@^bldxB1yjPoB(r&a9!PjWE9c3#r`r zkepqO?g1mrHz%16olvV2LKd`Vga z>mMp)z8q~^XTR6G=MX1A#t60w&IhUkY)zD;WbP+XG zBT-79;k1OxY1IEj8Rax0Zr4!CY1kGreMI(RSUzCj9>&M&`JV563@6BW)qJ1ffjw07 z*KuaV!`(gx`!8H3HQ~EV7?cSel#MRXlZ{##q8trz_S?)qw1e8JsT%kx!!`01)$$b; zTNs~ukeYcb)a?H_t^S7RnJ^+hJ**0YGp=^yv&v=Hz^c=7+h*OjzUr->Yl0TREYE-Uf2E)PX zXsn#taG>`8uy(Q3L)Yl~bwlXShWp600*{{%OVsO0#rB zGK4lwyY)`(!$f5`BR3hF$PB64KIOWS!1o#7DPJ-40K-Fi6Kil0!^57n@EwK|6R5u0 zEv3&g?2MH&u&(BiRmm6hFJp#s`GDff8BUiEXuq2I>tyq@vY77B(Jko$!wu>{m>#>O zwlY36*{x1X@>E9j|ApEln_u)I!@;uoCA!jL+5GNDm0nCuD4{wYp^k*JgT6Hk=S`!g zoTU!B+rj(~{+khLG?dCY%aU^mmlJA`6H0rM6`k?Su|}pz?l$#mrq^9X&DQoU)!Ywjdq!!b zl0MM>Z;;<^`W_4RXnVBkZnwXl@u@FS1GU|3GOgKiR?&G(&p$yOI!x_QIe36#EY22a~9QS}RR|W4JV(TK#Kk(++C+%hWtMrEWPT zXIefJ0$Zr9ay}953_Ij>Qsi{1w4dYt!Swz+spgN#O~=!_sL@|i2Ro>>dbU(2%UE%< zJ09OxQ_2j!T6|&GGhF0HEzuoJt>&&s&L*rtX7V4ox8|u$)Wg?-{OFdO!lhHFeZXt491; z?f`%HTHV8)1#4e z%+jJb9+&xcy!xj~VyXwW;J`2p-$g4Cgo+U{d~pbj*}>UhT@*4OhN zY70(CPP5v3@-)M-6REXVQcL7pI@O_sD8@Tv zk^`OJV?>&Rnzft_cWNq%u48(pWA+ z+uS+)Hzp*hBjLde4^E|a{);;DIkn>vYMwe$ARmz+r&3$N^cg!eLr$v7Zbkz8 zFIa9gSv~I5oCRso72MB)t&dTo)RAiC>;E6dCo12t@-+@IKEN}DGQm~8iZ^Qk?OW1r zVnnMfQ<09x+46>AH!!{D7}Xj>je1kzG-^Z%HK1MThp0ghQLA*w#qSEb7kxK&n|uFP zy{ioJW{ye~9HCY(Wr2Q;NSsV?lR8?fjt1$3l=oYftN#TxN97w-K2;Ac`X_7u56A@j zMzcVhoJhO;bxSSd<1|8!c!m?zV2v8g)M0e+W~SRxsGZu*IX`DOAcWe`g7G)|KRbz9 zqergoFELy!8=kL*nm%BB(2dljDH_Tn43~dM4cGQ;{3*kADxaj?HZY6jI-Dv{{5CVj z-9^odq?YI|Ht{uvGhd|^-AA?VrRMAWkbPG9)Pck>HsnZUe8FOBl1AFup`kC;T$jyd z2AdX1oGQ%G$VAB5#Ql@`g0Eo%Hks;n?S?w#OVa8u^(^uv=FeouoR-FY>RAxA<{#AR zYnicsI>Uo%s7_j~D~!`3OV!+lrm)BBPBiSroFFQ9hlz*5x1aGo*AXx|d9hFd>pf-Qpz zgXmtIaq;X(z*`Ed!q6!UC#|P8$Q0XlG92|IYP$?pg|uFVuIz&6^FQ+MiQi#?{%UIJ z3^trMk>RA@QG;c&i)6AJWwN`kVR|1bHoGeHT57dSb$1BsE0)O)oq+2%89QxE2$snV zR7Xk!SV5B(QR9mYhlfxD^dPZp9Lqaol8dznM>aBFy-ai3V+<#$BLU4Af75|BZMz&* z(4Yz;bUN-+1!bzBLmexTO)r_p4z#aheM4o`J{dBHR(-PEdyevVJM{pu;|f-gErS!P zCl`Tw08yYjn{aikT8qh{p$z+o4GzDj3zF?0d4u7w1JnxbmWH1*?Ckp)Ukuk!gEmkb zbR~(a8SYM`I+jwy+64b{4m zTK6Ans;(gX6^4iVs1XaP9jmBzJ&16qqpj+Q?GdI2{)F07N{xM6`+smbBg$W*#%Zy1 zKCJjJsOi$MsSGE4OfAxOiugUl`Ek_tm#KDrh%HGEG*c8F`dI$op#ljbEMSv!DVME} z?qYn^|4;{lsafhsemBEyT687aZWZ!=CHt6eKTd7p;)QwN;7>CBOnIisUen+%S%pBWpq z-xJyywrO$Z>mbs~FIpnNsZt%9-g4awU7 z<)1Tuteg}UxqAdVJE>JaqsD1hq@QNEbOyC-H`SLNbXtbwRvp@(^|E}W{>+#!r_&+( z(2&Xa6)l&zc5j(3@{ z;cjY98nsCl&vAs|gq76#x2QD_QDb%9uaPAT|0(0kW>Xsmwf`%08qL(IZ)#+Q;Yw=V zN7UL2)S3or=~L7+8Jda(3@6Lt#mV9YzsmSdZQD?dY*wQ7f08PS_yaSx-$|`rMNN=p ztGk+EhwMQ5QHHxUf~5ltxBQCQ_BwS~i!w*|6ZR&?_bu1`zpv&lUyGOSt zmM;Hasz?^j9>j12mX=vu33{U;?s~?DYpvLCP*@k_Y}ED$oyUX@8Kgn2fe1Zd2z!F* zwI`@0x`J9+&WcFJH)#zO$#Pa)!T6|i)DiiR4q8H|Wgv$MgSV)H5^AGNWurP&D+`$? zd(kLM8T~Bt56fbV>nSGn7)biv@cf2{!Vq&DSVdNp^*zT*KZa}tmZ6G71hY(mMmg{A(`ADncRYF z7$2bq>vU!IKQcaFYoaEa9Zc_3ewpMRO+}MU=YP8zY`lX7N&{J-VaDs?$;BK2p=|B zypZux>R7ho>(UrsEE7GfdLuMK_1c!*uQ6YpQ!j>OBHN^S8u~2R@Vw_(py)DcyQX9? zp5fGBYI!6(*diNWG{|`035*}sNT0caVQ1ZB6_gF{T)=RkYa+yNhL6Z*m%q*o<+|fJqt)xHktw^E=>b|y ziE6<7rj41(#`~zPY`_w#XUaW#xYZ$FQntk8!~7>`bq>GHf(5#=GrbH~&7*eyi5jH? zgguZ~UNge@YFWfidDBjr^tec-H>kb}Pd#QkqkW70BW6gH4IlZE;nECha6NTMSJv?k z!zJIK<{hE7Ur(+6gc|Kf#gAXOM`lplvP~T-!nSws|0db$PTA@<`T3z=umU{hb61dr z&YB@EzMU0XConv$5gOdbaILmsi40BJw-_I+6H)s(hEr2K{@>1sHu>qmXBZCr0X0Bg zF5$-v+hnjD4=~)XD{qt6?0Jas5i-d|e(Z4LamLrEL**Y~{LK}$BvNf1)bNK`phqJx zqzdabbm6x$J@hu_Z{I*QU(apoOOjU|K*)sqiZ0PRqqwlK40m9*;^U4MY#e(4!iSRK!XYBcl(n!5g%nZJH9wJ6%HPD_$3ny-dBR0g8z6=v+y z71nCV12tuFdib35IPP5Y7t}pZ{=ZR+rr{}O=#iW3lwpdl zVf?U8zqOjnfbopaQTd9Q?ARF%dER)2;~JQ6>%XE+^(%iMFqGCO% z82L8yrI|THerpA_MY|;}nhljJy<0vZTJ~h{pUfYv-IH*V;UuRP+lc&g^;%V|N3VSf z=gB+vsG@plu{7H_6Lc(125PX2^|XIU4Z4$>=0i=;_H?%Wn-R68)CM~%Dt?;bObuBc zsy7W}%HQYgXL^The&P!Z$Lh`J&M1a`SF&873{j|jOd9LM=YNuzq4YLtf}D$E0xL*a zK())Mq{^ubg)qKA4G-!7Gu+AeV)>GkXBbY(qL#=<*xe(G`A^kQv zH?%6gSmCN(rVl<$&6m$e#xR+Y3Q~h9vLhAp5#hSW95ibL?OSS6dF8RvM9pQb4xQB+ zq3}fJ>rS9Hgi!M)QitT_dUSGXxX6wS{7W5FhkZX~xD30=z5fS~GNS1{YR50B_BW|5 zZ&0(fMp86V`RkNlZn!2@;~iK8W(^EzaVE$<^gYJ(f)r}GQ|ItJ4K+IEF4(STKs^e#R5HG} zpPK$YwSPV}OWrW(afWT_RJ$x-u%@<2PN+@oIm5LWTHNjs--fxJ1(VfKgc@oKVtmts z)Sy+=2HEtElMH7m-KIll;B$;G{u{Ms2Q`uEw8Y7Y6v%X@YPCn?szSNfqUBocyBMFR z^qN41efy~Po2fQAwb1KXF1(iU)pBYre=uRp|Hz$87|@)A$!+Fe&G;}a#u62*xRMnP zD}69t9eaxT+wWpHSXVrt5$Myt&)my=R&ya}-x8|r6c)jPopL%&-)6?@Db&(K)V|lL z0slkIk&|itr^0eF0h*G0`IuJu7^^yxy}KQvPB2`Tpd2#Ic9k1){+b!;mQ(AsibFM*3CdWm1`u%b9=UD%FBy*7KutCyZuWoLHSB=nJ|XGK#x@1ds3BnJd*{|Ct=4r-qc$_@>`a^=Z~0f*D?MK8ZqtkucOxgkXq|J$`=*?q&CQQ*PLXy=VNNQ zYH?gN+UGgi=PBXLP`8Z*24bn1 zn&UE=;u4wSdKsp0Rh*}Ct+Mq!AF+Jn1Zw+yY89v2X=##89=wwcTh*bVSt_`iS|n54 zxQJojGHQS-43z0j+`xFN&JEUOtk)Jr?HNZ+z=XK{f7MwQus2Y1s;CjqQ3G_kEz?L? zKVy8!TB=p|4>p znKHfAN)OfItVm}5Y?<6)8Kwl?ZlB3wdYLROevpIvKTM`JP!=mq+o(O11p;|iv$U<| z&<%Ue3z}o!A?7QQ$<0@T!H+WDS5uZKOPizJ)^xA-f0mxj4rq19-o}D0a?54fK6S4% zKJH~|=pL#=rZx3bhSO$J%bKXgT1(xsv}Fr$rfN=8-eY`|uCRML8y?aW zSzly&_7-Zpt}J3Z!`(-fE(<##3!8V+#AE&gwdhi1V(V3rL(ZdqIUCHD0SSv_g@d|L zi3($SOBdrKKBPuz=+m|`T(O=y@GWXEwx4_dN2tMc6%4wmia3Lm@IoZ7-IFHMH+^2k zflvC&U8lbAk8&2zcy{@cXZB9Az0(!4q<{5P@AzwW7cFRR4%kyY?y@7HzF{$!&%o~T zcTCv-)6%sSJLd)1_sqHCiT5UN*$JcU{Hr z0K35n-~&VGoQ(g?1S`O5upb-(N5FA#9$3850T2lmft>)q32iwA&Vh?yDt6vn5Ce9A z-C!>`3oZa3U;LyXm;e0MzYV{J4%XVRvo_+zHn0;^0`sGz=RnK^ z{9G$AKk+$dB7Qd*tOgn22sjS>{ZSEE1uDTla1b|4($G|yo5%^8UZv}(hU@tfTj)Iv1Xag(& z@n9?14)y@&e*EtUI1WyOWtZb>z&20`_JM=o80Z40z&YRtgSZmpfUie>yGGG;03l4&*@G%>}UT^^P zg0tWP@Cm^cg4JLbI0TM>$WTlbSO&I$ZD1$Z2M&T}a1JcF2BQX!I`O|=FnJc{3CsZt zzzVP$WPr_JD>w=KXQP8)A2w+vhn|CFU=`Q`wt<~sA7}>0K*$`dXb=N(K_S=yc7p@pFgOZMfL<^s92W#OgY94! z*bfeY;vb()Em$!hylAnFSr1F=3>;q9Iyba0IR_va1xvb zvm-ECU?bQ9wt=1C9GH3|7VwQuY#F@R0CGVg*a3EfUT^`#--OD+X0R2ki9%jb2zG$o z-~#ZOhYo=iU^U19o55DF2kZxjz;SRAoCfEe_}`-WxO%V+RDylrAZP|%AY=g=1be{& za1>ksKGA3p%mj15c5nzB0ms2fa2_nW86yi0f@W|IOkIe2finjGTLM;sH6Rxhf*oKl zH~@TN&=6PvGQehV2pj?CXV_;#oyA2cS!j`?Ke8oby5a={7E3uZ1yxQ$3Pc21a1@*Xz2E}yNkThGPE?E+`@tb_ z1RMt^LF6|uY+xB!1=fOn;2>xQUEmZr2mJ2F)quI65bOZEK`%H9d{*LuKs;ChR)alY zzZ3uSPsU;Zv%w;;3aka&z)nyJ&Vh@-?;dPduo7$lxnKv_4UU3da28wuGw(%%AOma# zd%%8h9GnEFf%826hu_4uECS2GDzFXg1eM?*Xa>i?Dd3laD+M8730MO*fE{2r*b9z= z6QCFP+=ul77JzuL0%U-#VAp+^|3i3j9GnE_f#sVR5wI3)0nMNboB|g?$Z8BThyhE$ z8n6N6g1z7XI1EmJUT_v%06wYc2v`9!z-F*D74yFxFOGoY;3SxFKc)gif<<5%SOwOC zEua}316{!H0dxq=1xvt6um)@ZJHP>O7@PpTVDcKQ1F!(ZgB2n8-)fKnwt^$zIIyIl zBVe|x@1p;dxQ%#O3HE`5;25|F{2s(?fVp4^n6Vc925Z4KuoE=9@<;ryb{3{%g1}yI z02~HB52H(94u}VfSH+S7_0^vU>Dc}_JbqfI5-K;gBk14C|C(LP~7sP-yV8eP$^bWk(3l4)5z-I%l9xMQ>K?c|gwu6)4G&m2IWualP7VHF-U>`UL zn!z#91P&P>;;FxQE&qEg0tWPn7IiZ0b9X# zupgWRr@?tJ<8jvqU;1C+-10aY2RlI}*ay16DR2&41b&;*5il3TfZbp(H~NM z3oZbk9Lxro3ATb=;3Tj-fp)=c5DAt&fwi;>FV=#MU?->q2SGFF0;j+^5b`8C0Aj!r zkP8aI0dN%bg0of0sFyma1xvcGxE?lSOm6!ZRW?Jn(?9woC1DNVa~x^5CfKg z-C!>`432^mpchR37OoI10P$co$N*cxc5oV;2j*tpAIt!Yz%sB3tOW-*;(yJc3!DNM zfnPqZ7R&`J!5WYY3c(Jr8|(!~!3od{7JM6>04qQS*bfeYBj6-B4=k=~t9^=d?RPNP zU<=p=c7jT<4;%ws;2gLJ)@()7pb+c@C%{?YQ-JFS3qU+r0W!d5a0na$$H7T3<7o^! zSOiu*ZCP$vix)dVCD;cJ0zXW|To40h7a=oP3l4%);2gLJ{GLHR5CfLD`n+&GyYccc zI0{aHUNHH)=o^R!tHE}#3+xBS!AWo)Shitqzznb!>;nfuGdKoLfpg#@@GHjJ03l#5 zhyhEA&9MhBHh^4E2u^@ra2CvY799ccAOma#+rb`i2pj>H@1YZ528aY3!4|L&G=pQH z3!DRf+tCRS1D1f5+hI)B;Kc^88}x#+-~#X|K?lHUkO6jqJzzhuJcmX>Bv=Gifwf>8 z*a<4ZLC_42fi7^$73zZlkNG~@2DzXR>;MPAVQ>QU0-qh&9AE*62P?p8upb-(M}U7R z<{CtTwO|X_2KIr2;27uvr@%RI5%@ii0iXIjt{LQl!{8`50nUO8z~==t3RZyCAOjo$ zr@?t(*@?jhJ3%El173SEE~8DKNm1CD^>;3PN= z&IA7!ab;i;SO&I$ouCplgJYlzoC1EkFsmR0%mp!E30MhsgT3GYxBz^d<(O3v4_1K9 zU@O=K_JIB15I6#kgVW$Vu>2660yDr`un}wnJ3%uz2D-p0a1LAqelBzjgn$ho7kCxA z-U`^^|0nAY$Js;dms`RDP`AYgY;=WAvrn;ZboKq)J|%dAiLu7L9@8JSO5EYmFE z?wsy;m%}<~if@M16dKG#Zud(|ZFY{717<9{GSNiSt>t-+3_03y%Dfz5PzEsO5 zGqhh=%T@;baDx5v37c|}Y+2)YBIB)@6YQs~uKl;$X9judnICzn9y9(cTm`G`*9EO$ zGYcL;XRlIc%|qiAuBO%Yt1l%#a_QPl=|!%N28{9|m5y3yv0S6lh3@3RYCF!J=A|bK zCc-n)=iTvN9cjk7M{YsXm{~EcC0Op>oVm&LfUAOW%xmV~({c0EJHfI(bJLT#k3BVS zv+L6ZlLCC*kuFE1eTwf6EPw=;<4gOMK?&+s^v#zpY&Rw~!4>5@X-csBr6&t6&a=Yy zqv-@!IuFy!X8fQ|Y zCXMMWX33MfV7%!{=(tJKgWWGZT|u*+Eatg)LV3m53NkJ=UT8C^?USY_j1C5tqGygy zO+cz;@y5rW%p4te#_2M!Ep|#m>Uh0w}QG;iMOt-_`RxBu-$@3RRU0RH5u^7W$gW;2| zzLbms@r>Cvti^Cw*-!0Lu6Dol)PU>v7>!kEAskyRDtO`)*QV8Rr zrEphd@Wkn^1J_UT_vD$s5JTmuX{$R=%TMjIg557YjiDOPc${}hWQKMc zP0TbVM`of1&n4qfiDc`W_E`y|$zx20+40l9X2==mUSpA&>6b41Af{oOtM3t*gwd+7 z$!^pZJdK`Ab4`x*ndOSfu=`)igI(qs+>;o&X|A*kSkuueGA^xyH5id;uBr@J)6wM2 zOQla^9ioNXd}g=?GVGUK%7gvonVVj$z-g{Q*ok2GOAX07m~>B;ZT==pV&<6ZSck>v z8L>5!Omab{eb#6L>#!I-hI7efCb=_%A6jj*0w zTNsJi@+65CTQQie^_C|yb04}74bomR&OKWTBQaZ^swz!hSLnP+ zQ}7ulC1bWc{j^{**SnJDVatyuyR9&f2bJ#Rg0CcFqC7+B<84aU&4alaEscrtv~Aw; zT<_}pO50;>pxLbJUH187+K$5fc)E7jogDX-WXz8zc{A3~dRO*WlE+xjT$sA`u8uj_ zobH#p_NXz&(kwG%nLp{u37+0ZEqLqx1@;?lu4A@Ia{^+=7$0-2@^_Uk!AZzpiz#-@ ze50?H>n-U|Wj*xBSL{FI-Qzxg;TSg-gMnrKCv(%E$h|a;?s(UyO^L0$V*>v8s#rC+9&n&UeN*YZ@Y0v7~fTg?6 zIKYP%=WWc*djd(Lm%%i5w{FhBn(~w}@7Aw#r6yogd#cPFv*+V6jOfqXi8~ zoTpR0?kp_{*!QC~U>$gpw_}{vxsV)q-MrD>xFbDvVO4lCM`8fnnWwsv?u4Zptq_jJ zlc(!ao|3QRfv52pn?kJhb*}n5?N{U1b9m92V{HFyOa%w(;q@4!(QYwb`QdRqgLK&B zcLgmSJ4moTp4QC1Sm#PwisR^LYgoFT(iS))w)V*5n>J-Wk~^kFrm4lT%XhR)MtZJ0 zo>t3vv(YxNdOclO1QU-oTz_3^556>NW0tEqi(n#`!M=``$I9~baSM)O>s-mp>{pJi ztjsYhYX-anFJavi>Dif2K7>PxXG1YfmoR2!9WrHHji_?8MdM988+0|i$vW4-*bW(Q z;z>U5P7Y2S(_iCFJjpxlrgYL*lE+x8x$s5nTm^|^+r|>|Tp0^^J1OD$prc{;Qz zz|&%qQjTSE|$n#g)2r4K7`&QVmL#Ds_W)SL)IVKU)`f>H7bkGxywkZq)zd z2RoVXnKNh3Idf+2+?lyfD~El24$X?T4s92hhSJtSlTDlF(xTr8?YX}|Yx7)Ms7Pp| zi2Z~3n%f=-C-_1@KSI3!&xswI=Q4(}g!Ts0*0eWcy+Fc*&2wp$=IStfv^w+A&001= zcA|d>o{d!o2HXPBrMTt|&cCm*t1`Z+X>NPqG0$Rd87NrFG++>FHSatS&J4Ah;~&6@ zhS^bem{oVQ2rZSqx(m_|GjFCuGP5`-Bxs<7PLCV4DKI4LA(mkd)a7=nhGs0r{ z%tLe^X84JTlR^^rxhz7o1_?beanh2Mu18F`(|u4OFO8Yw;mGagH#Onp5iv^>D=7Nb zd%p^QH+0MT__x0PcKE$e@_Gas5syk`+UKlHTOgkvVMVmFPC&n* z&q}4zi~mchI0i2f71M^oOtUutD=*1SBlxud3@?$=2N>>~2^){Qs%#vCtB4s!Vfe{3 z6<3uf#Z>R@W_agS3_q@cVl=jiZm195Z}xqF*4^)R+QLCyG}m^~TniV_t9p@-mO^rQ zDI~*#;a_6?Md-n~CVvsuD>*3~;A1i#)FE8v4jRC09vixVVz|iKN3`bEIat&3YJ;zd zF!Y3wYd)M4$*B^Uo>xSeJ&3xw&eqlzOjy=8Z}42v=G)rn;YH{v?&k6m8HZqxr3yjm z=)}3^*|~UT_h6;lQw+a8SIOI`9BT?XaIQ(1r(qR-sDJ00*?_A(<|_OoqI2dtOXkmg zsH3xeUE`)rs;5}YZ4$gqTqOlP1$#U04QHqaF3xmKA63C&4->yLFOuUo4z4N2IEhY` zYbMRt(yIVQn`m>rN7}?J{@b-bt$@iA7j2}?HK#I1Wt+Xp;gMPVx6r}Ugf0ng4AJLD zX8O`VSn0zw2g@~67euD{FuY9Q#0-L?S)<0AJqxf(=_wT6B{aL3<~UeP@L+hCzz8?c z_kA@>I}yrEMGTSIW?41U^NTp*b|N)p_bJWk=a*{?SL9=%pObED^)t+hOya;KoD>o` zmqfijCgD{%P6~+{-x|gdmyN~YG?QH!8RE5?9%w|?x-6oZU8!YNUUrV*ZI#Ny^|MRt z4l4aprE-Gx@DX8tgyH^)qp+?~snot6jw0Qxc093|P=%E%QTuxMhq&y8Y=Re8Me=-D z1)xO}2;Ntv#fMu+>86PU_e>s@ZZf8aN1AI@S`Bazk#tuM5r!9PKJX3Uvn!Y2qfhsBz}m+en;+zBq+Z#2z8M%7o$j zeRnRT2N>ylO_Pbw;`@EI$D(MAxW+|>pSs^SS|NpeVSX@=O1~0d4zCe|q)#C@v?!7` z)-^~h3ROtJ9%9ZvL`(3gSb`sGRS<22LrHN8^kaFMK8uq=0;dvX)5LBpPwd8f91x|v z8W73mI7^$_w>V~eUU+PB5mYE(I?B#5@jv3_{v6A?s0fM^css$iEF`jX4V%Z^w5SML z6xxBmKx^|{TIftfo;QT}wr<)mr+w>!&ek;x+B?nf{}>*d;R&Gv`$-};6aEKdst2pU zK9E50$^Z=Qh;a`j61*<}Lp!41c^FjY@NB%AlU50_LMTBy=mx-Q1yu1)I-} z%cqA(@!Aw9V!WC48YXhRe+ZA7Ki=}pU#ApHHXH9O?`+0AP84hNTz*ij)Ia?e;&=TI zm~yzRV)Q^P4J0uhHt*gQ86SGs?7Rcd>(@9ZYcv%0u&uj<7MG;}&hewb>X~qN4_4|v z$M9a1p6|h^PRu+D(md=`wKaE;T8{L%U_F<)8@HyBJ4>`hEDYNe^2%T892197xk)`@YhHRsW!!1mQul+B}vuTBfE0 z)8SKLdKH+N;jx0f#Vz|8rU^$DCq)=oM*8wuxKY@wyaj#P;{eMDdL#FinZORFQ;fb=Xwj8Y%T*^aK%LKf{M^ zjf|h~l~%ogJbL0^*bg$%H49Cx#B0c1C(?$FvX_o=NL7 z0`G#YCepjnctb;{eZoNfHiBBrEd%w6T=QVSiFn|r2YBepqqq4kJrHRotxHXG=H3~2 z(`PeXVrXBO_rf?6dF+dD(#jl*#>}UOhNq4$p)M$ftc3RK&9fumX!Vw^gf@o@tCI|$ z9|7%qu&OB=+OIdEks3yymD0Nz&et&YS%I%H91pvLouSd@^Y*+0l z=}J$pNTnZ?!=UxNYPW-vLV{i|GJpaVE^X|pZE9@gmRZBue5>2F>wIJ5iWtyWbab?A z;}W&)#LJekm|F%)6fvO0Tbw)0yAu$cNTGLFIr7&kO`b?VKG`f~9HlHpjMmS^1xTVw zyXIPH;i6JiNiP^znpbJHl#@b&Iz*1`(08Q?rGkW$LIR7)q?b%mX=bNJ^0GMTlF-^y zfg2h6pzKPsGc__Zi<3eE%L$hz1h`6*ls#gceOl$eg$^?y8GiY^sq{kpN^JuQb-VM zgi9^@Ri(L^Ga|=KAHd@c|1ER~Ix;G~eiX~kq$n4~9fMBX!pQ5pX!WN;xNYr#vs zN|SLrIB`-);6g%jjY$qn8IfnoZ;vEq@!vuRKN7kwEKpXO76F)5jESt*#rKn7eYTaXrA%{Lr3PU)U^mRJ1UCE(uB`1YM z`4$C~d$Cb7* zOU#F(Fx`>b3eXA}pU*H{7S^Se>W?4@mDrauPlhAOJ_}`Jn(Z^qG#^$1&=m(Irte>e zr)qzNnt;tjbG7Jy z(0e#MW&$Ur5|~DG-vw7<<(lg6U`cBrf_aapH3S8rdzEw`jBT(s8N_- zWq5UxUw09$3JLQo8B{vyr?AG+BrK=7EQ<8fP#qQ*OU(HI3j_(N;UZQIOU&?OT?5=( zYS@qEz7kWB?CYjTKeJV0t**p${9<_8B$*m;mfHvE`AzKEGLcBRCv#FrplPY>Z6@JY zkDL?|C`7pI&mk`S>XDO{BvycUpgZhGY=`}b%YinVYq-q9Wm18PCW+|JWhPpL?W;Z0 zBcrN48n~u7_eFH-GTJ+J-+XKzu8DUw`R;5n8_1&YRVh=4zE{S3CZCxBH}%-UO{Hyg zg-DsZpEW?Ee02!M^fGh)?{Rv8Qqq9NZ+&e>q#zU)Rus$@n~h7cF4tX->K0qVVhT+n zQFe%EUY;DzoG);J($gh^2R#MaJZ@ZZ0sK%`cej1syjw)leE`zjZC?rrOnVW~lB2VmICQVj0q-fuqZ~a{)TJ+Z?(# zJZ*#r7n#xP@t9B)hsTRrD8w!_hwj9h%|f@TIO3!DDBT0I(44;$59c1N;$tpsxX^^B zX&4?Z-JSLzFEmxt@M_L04eu7X8#Y~No(jOqH=~%iEi|tMn8Phav`Y*pOxJb80|nlN zki5`T1Ymfd=x{pbX$#F0)3M~{i3Z0jaEC#Yjo9H^O`^JV5;C0KtFZO`OfQooOvxLMBv2$;7U1^DQ}cZpMGR##*b!!xKz* zeTK5-TDXJ=-7%WjByG7R&CI$hoFom46~drGb46$}P4``R;p&PXD^w#yJtjsA%?o#h z$A=c02~)8ewF@K8Li5&Lx?(ty_*fAJg@q=0riM{xiL2|Qi24i7{F&iWsjg_Pa-t!K z=nKvCkKK}Kj?L5}!IMPc^u}qSd1I!sCLKKzYo41(a5$>0Nk@-FzM33@S4Opba5Q0_ zo=foFsAjGl?G(eWMtwhw6@s~xj!vS|p?qB$ekgTE^9U}>*LA}WrSv6+TT$BgB>16t zQtVEYcILG&b2k{ssATh9Pg0>NaT?VYeHt!sHQ(1|5v_)cMBAArxj;!o3*iFq2kAn) z?SzxAAFfmJDHrL5W?O-3G94_Dp1B+02OJ7~g%#1k5^2+Zc+NueZUGjVrSq&)&UBOE ztU@iGa^N#aFEon_RnJ@pXOg=6kX~r^73#X-C{j1wwX)ETNdtw5teyZWEFEPU9=16t z3V_E5n}Z-wxJpKxg1I%x@fruq5nSfN&trFQb7-*_I>91 zHf%}aq;P;}!r>Ys_kCu8O%^Vt zgKSc3SBT&Ve}j#v9;}*2FRGe&LwCjIuJ)zPALU+Qg|Zk6RZ551gykYAwaGjMmVS+@ zohKQ7B>Z?Q}R%OlI?~FnU&Vgz4!dNRZyDdadG~Vh>)NW%zsmRvxws(;R5KTWOn~EyMw@5zN}28}C?C)u4lk#cZqS z-K>@L|AS%qmnqRD=1MC)cLh#;vMX zTFjLTjwKU-q|sF4@Q-6G6$2K+u>|gBxB_sf$?QBx?~*xZTc7~^MGDa5t;rk*oaymX z5viYGsA2pk!egKLgw}$JOR*HZX2Q zu$a{XZEKJ+v;&^R`W?hF{aP;C&>&QA6P0;a%cVCj*Q63WVV6>65xhn;)5q}201O8a zIGRSK_XS{hhQPfHzZQVu83NPxE%c;M>bl_>0@EhNCQ}xGl@nZJcw+!oPEemgrC$ud z2qeP1pW({^Sb0P_=FUwf<5OBRc!Y%cV+=3;6ed*SFh#JKz*DfG0<{ES_<}sT^fG+@ zQ{kCj>01#NjBB zv{(&AJxqB0N!1WKy)F$ pl?lfPTTFu%av3~vm;Fu%Yz7(O0=VSa%-uyBOALjZ>P z1-`;?{!_Ycm|vP$pG~DVKBYAP^9y{5Vbq;sUVlm}5k4R^D<%+&(5E#E_<+C{7-kkp zBcR0QPirMAZ>X6_eD-}>ORBu#EW_smFuXw)CCYQCbn<7g(^xE20&fub6vOd7Xvp@F z2_sGPGgxxvOm}`*0=E#I#d2L`IEWC^rJnG^JxYZoa1epBCwqKe*`usb0xuDogG_Thz(RRRIv(~|JvidGS2szy z3f&CKQlyx@ph48H7#1EgEO835DM0R}0J&EM?h<&41W39%6ajLt7Ec8Vx;Yd9^0O)u zl&C;aGnL?#0T`|!VWyAaeE}G*A#fCrs!is#01VdG3)2i-LxQ4)^@KA~X8Gzvo z0&it_V*rL92z-U%7XvU{KpqO|0@EgQ`Dr{9iWkxGeSyz0oYkXY7+&D=8LSq--iS(1 zasrx(OpPHonflGYRnak~Jf#Dq z7-{z_Ptivu-X<8$$=r|T*gxFns2H&V{1AZmhx5?&t$DTgm2 zsC-_9Ejk_{@F|8@24HxDz;sb9o*x1*96{g{3||_bfQv$&QE`)Ynn)0)%Lw2H&uIDJ z2Lc~qcw+#DA4tf`MpH0feFn$VFa%=3qihf5@ci+C#>NKw*dfoh7PDF_Q}N*jbICBO z1JRBX>0b?ZQzeT7Fia_MKf_N2VAx9F@_VTC=>QCy2z-p;KL%hZUEu6lR675F7EMJ4 zx@fn_GzVZ68JyV!9}d81t1$0i_{{(e;|n~%aPqUdZZ#g%+)K=>0VhYegKB$1-`~`JOHa6Pq*|U!W~i%(e&~}0>T-Bx%;n;Z))5WSopJ;RS3O65v@fR z6H8vQ<)qtUdUqm=P(u*jGx$BJX_<(vy2X%4unUaw6)G9FXg*C_1&)PK)S25(mt#mE zvUw~?KFwN1`h!GkUOa&rn8ylIh-!x1LhxHBa5IPp!!f0%CV~gmWb@pb;HAPUb}P|7 zxPCpJv?0GQ8Rxt7%5AT5KF$u;bhba*xXx_)CU*CGLcoEAaUE2ZVGh#;WF8C$7MK*7 zXJ3xyS!ET{i(xUvc82NlpbQU&XNi6mL5e&x`=6j64~A#SU{Q~y!aTF_pD>nqFg#02 zpTH_yo;i-vJ3JV66wy{-tt^jRXMJaT>wWV*mDqe%Ng=(d6?WNJ-^z2=#amjc8|O7| z!g2p?UKxwIWnf^bBNr=ID6@(SX}w#(Eub84Hx~%r#%A+eS{0bC60LdRTjQm zS^!4lwLHN;OdjQH0&zyNrra@U=^5lkD=1X)(lNE z=T73yk|!VHlCZeRG}i+x5SPR?>Qjluq?fgP@EjSe=(7`fCjPQ+JUmBAA4n&-uVE;j z2Vcfi#1lZd&(RE`dE;f}KKW`$I)kN-JTvy&x(2w9)Ii6~prCJub3%FM^uJ>2^*)v+ z^2}4JKrE{KtrCj@p!_y^ibz8X?xK#ZxddPTb~tl_2g5O>y+wG^%X5~-A8%aH++vca zV{=3KKjXp9qg9U4OSES7KjSr_2dh{>&wY9HZen@OChe0p-}+gBiUsslh&=Nu*!i`o z2+)VesXX)HKkIhEQ$+AuJn`i54u)z@x>2A2-XgtZ0KE*o#2!S2L=rY_zAF$sM^sOf z`#kgcQ_3|8)QFZ2RUqb^((=M{Bx;;t`09?K>E^{#IAh6wi&V;mPC#XOrs@@4i}IcZ zXeiI@**O%)gkDiDPFF~ZpevxJJk$Mgbc0I)8n}gslL%eqnb5x|FQip{8- zf59S&*pe2|rSxuwkL@BU{zXYa%jZHvpND|`0yRJf0&iuw_mg0e{hjbAcys(LtsHaq z{O_pd7oy41G@2ymnVkU`tre?J!8A9|yz(7o1KKnob{glzHs5wug!w<@1Q})OD1*gXTrBsU4^uSE_}-GBR&)UH9V8N;vBqU zTqWf+|En4nXw_T{x0~T(`-cV=7dY4LVMQvi++gY%M=#Xm3f$cw^c4!U4tXGvM6e&NV z?^WcPWdRs|B=J1`0fP6wsx<{a63x?>D=-?o>RY*x7Sctu8qA8};@HEM#Ys_(a-)+> zGVnzNmqq`k9D!EU#apM>Fq?luOiy0hX{WCds=cBUYOJO8S+fRSzR{_FQred zCb;6PF0BH{%|{5{7AOtFi`yjD6C6D{G{=nkemKz#oK*vDFW~r0YqW8g{&r1T45tvfao`P|yr#Up7)~K@FT-cQ1~!n( zpH{7h~<-K=89aP{yLAbb+Hy1fLJU%26&g z6FmH!E)7SK(x)CJxFP_BxiptghH?WcxL zv&QAWUE`K0XQ2-#U_SABxYV1K(R#Y{_?rYf9c>-$E!!{$@+Ltx-%f%`l&{cd6Y|V! zuWPB`E1vx}1AgYaVw>_G>c+tyQZ0Sl0KN2wDhAR@yTJ4*1I$YQfb&X}vdxOoV}>Yr z2xNW4Brk^kA8}y{WYSRyUSqNzL`Pj?;SyRSl`z;6B6#J42!kFB+e_(rw-9_NP#U(E z(zUk|y#480$C(cv#4O)qp(4fe2}C2eNhW6T-y#V-L3nK+>e7uhZ8hOkpBFqqv~ePl zX!!INrQGIHz!iU@=00SeorOaP4~aGu1An51-=jeQk+#sey;XzGhT1$^ojym> z4ZW-~=c}>HnUk(+=xm6vyT&B(dvO5Ns|}tY+Ms=JtIXbeaYE69;RFINf^k=wR|2q# z0w)-L_g+}dE3K^7HH=D6_=skX03f1WVtDaKB4d0-px+C;6|S;s&|LvG&s78*K=giz zXwBjWp$JZjB9z^Gu|a8-xf~D%W|rFMYniJ|a=F$M3@eIA!J@}1-ic>wXm7mR+*lEW z5E^LOSwnHD-6G~2%aU(=_seb zE8uv`$?-BxQZ?lBXb>~R`_3{Ayf4#-m8V4Ec#yAJ$w!B(q@U9+yX9tYH7*nJn8Vg0 zzyMmmoLq7I4i8qgu7RH|ca}8LabD?hHqRQf42Bm?tbkWpTIz8=z0G&&mEKd}N0xqW z6YgQ0>{Va^w*V>@MQo=625y^{#Yxv#Wn7ot(lrYXwVYgc%nnWp30y+#`8<&f@=u#* zYovvCp)H5=4W_kuE-f5EH2FN!Vx??dytARI%{=^IWUQz1I9x*X)C8AZP98m`ij%I4 zakz!lyA^J`e9-L;HqWgW?jh_h5v|$zpBS>Z6jQ`#<}TdG!5`z*-KxiIWuwu%6@(K{M0on4LWd)*Hr9@6joPbP*jLhRUqwq$^0VGDQlO6x090IW?Ql zP0y!xiH(OO5lbAP$~5H>T`lY(53F?kYPwk+!Bd1Ml^WtNj3M|?1QP@gR@1v9DFnY6 z!Irjkv-1ibL0d8?C;2wq?d%m$vAi}5u!A%D)$t7rnj2eSD6b<~%xwlby(qXJOLOU_ z`Zl_$fs&#bbbM(=7dGWU0MwdblN;ZGEPEzU?&;fb;+vCFPP@4@>Qi`OSTw`JZaFnV9YtSQ%1^#KIO#S;?-@KhghYC#Wu=g`ao`e;RFf=zC$fXkI*R4K3*@o`cLswpoW zbuBRcLx-oB;U8jJ>@i0-5udBY*im5eKSa0lVDt!a_aPV*3QX&V=(HXj_hFg{7nqj< zFaoTUZb0ZSFz*InxS|ZfbXKdt%=kY{`aS0GI8QW$y8^TE|FmdqEq9kP!xiHrDdQ+* z+aJpZ1KktiHrmE5TvDd=dIioIw{JW-DI|zGnnSteP;TKOTKtrFK{JqY`cOq$7AJ)S z9E4;Kj8{&}KWQeq43W`e13L*#6Kqg!7XKb>I4NvYG^2}A%gxSZa1oCK%p^~F&m*Ll zn{(g0HQO92!wSSepeh(l#x(kVIT~~sgCeD*CfH20PG2;KFqgyG0ScH+D`lir%1Fx~ zTC4&&y{#N+c8-`rm=}7m(nSh<*{eIBXB>4#gTOA z({B;2-iR@Gr4o!gm3>>#%8kfTn@;fd+ehH7!B`xfmS&Y;XcrdQ8AOANMih%8AHK;j zE*ViUoI#Y*ftP0^>4Fj8Ahh+dzoHhE3u(9p(`$n29Rm#GQV|8iE4mZg*FfI~NEreG{ zY1%_O(q1CcQWY6Kj{cMuD39o$NMyLS+V`yzc!6-K%psWX56R9@hN2}JG1R6#E#5Dp*(>Ff0)jekW5 z|LwN06rLb-^kMsvbVZ0_15c0^(l_o$8oD0DWM}FYDtEZSH2$3*{I^sEcaW;+1?EV5 z=f|-CFZhJe6ip=>zVG8^fCi2s8m+yPXeNx)8iiwscNR?}7*~P#mM?{4NDWsR#x)?S z!Eg-exks>n6oGD>>ba$G2w`4#7r~RVG;`$;Nizv<&QeaPFO2SC7`K3DR*SdM?nfDL z7Qt;sIt!ZH8kV$gslwO&w)&GGi}55SN?RhOIZY@J2ce5u%I{DHqC2CdO;?$w@eb7{ zTI3UW1=x)=hXOD>M8>AG4BH!?DCt^OZ-y*KWh3njnUg{SC-Jy|<4A*Pfj7RCu2*Uw zfEH9n#m0j{A_kObA$&snA8(EARlc|qZqBmjkXs#aMBf|0fLD4 zyw4=Gy(qyZcQ#?#M)l{I39ImkmtzYR&|5u`K88X$W^n*k3hrfi=PF3=l~xK)x`j%= z9DtRAyBWS7V2(CP+pjQ;PuFB-dd$%tfoYL72b;{E#+PZb>>unU1^MWDVq&@?D#twa zuoe)#PGGu>I>($2z;Pe$W%!Q)7#&VZCnZqn{5s7XwiDfTGkpG0JXCPfRWEH}5RxlQ z5_$|IoD>qJg_@yM$!m3(X^9r-bC040x+^lre5hf4_-zWNau9K~Douxtr1XA<4|iau z$4R$-ec*^baFb)6U9B2PZ$X5^5r)sBf(J#s5`+zbQ!oL7k#LM^OUIgq=1pC2H(8&u zn6()VE>fnO%ixgPBXr2^5lm8rGYv07b(N@0>m#aVG`t8*Cn0mpVZha1Y529kX9%|Y z^BOzd=Fcc+lA|`V=W?KMOirUKX@in?R z(1~>3w;BGAHF)-r=IHoZi@6?palL9S#X)IpAHm#OeEMe-E?QDnu$XNv1xKlII+k3} zbLz3h)2k895xAFN^uEv3V~eN#!{q_r6`~Z(-E&MRuBBEHX*a{iZX4oXRKr=W7sk+! zr3E*cbXy!7taHrHxtIpf1zS1hCFFP-p$qM#z{O;OF9V)0;;)51N4pa}I)9im=yBNQ z*;Y_&l~&Y_AyyS@RV#E{JuC3|9h`KfZ-Det+c8W^b7+~c&A*n{=DD>YB#GcDn4#u4 z4eeVn8e&r);)&`pjJahHrzDI-F>OU_%a)NUX*__Y{-1|HZ(Hqrm#HZf8 z9&ht(b^7}_G!R6b&UhOaa7E0a;g|z@ z@E{}KW*6ITlU88F66cx+Gu`H_-Q3*Lu%@*gA2C)+w3sW9@&)pd34>mk**vDrUx(_& z5$Oub3HIgRoq@N17H|v1{pK8_0_K|&(YGd8d1FzfjBGf@1ao~NI=KtyuS0W0;X`2F z31<2|xOAmF2OAGO8i+4(mqcykd#p1WZ4D*s5C{am#xP%MEpP)y8G-8{U!%R$+JoVY z0@Gq)qv1=fJ=ppmyWcE`-}o0Uwf1NWeZNjZTN?RN>nab1|A}TR(T+x}fa3@|e~LxA ziOpxlmeAHevGg&bH@M|GZ3idarc+##o|F!kZggtmIw06QmmLftv>kBm#zEI!+dP+6 z#p>OdR50I)wgz03ZT>4730K)nmsmOMH6{*zLfGcHv~U*DK`puxKI(u^GThBcX%jp` zhwaU-!k=EAN!u!6TS#{pD{Pc<<&VS7g-1G!RAmn1yT2n`I96C}CTEAI z?kHXdNk#kpP{T^cUMegOYV%n8#p@up&>lpiiFO0Z2(8U?Y0(C8W(R#^rPJK7bxmjE zy7o@gC}pq~VnJJox~>#DNQKOs>!FvGwoSzis!cJdZKVlsfYLn}U00e+Q~#A_b^unr z6{u5a4PI!O7si#+yJ7G`6aNyJ3rwd&MC0_>QE2vk2~p33A(}jE(~@MNdHqXRhxTBI zCQ&aN7A-W%&%qx&7@`S$fZ@df7=c6=PwU~$!(#RVOXMZfg{mMpPFDCk)MChF&a0j|{p?Rwpx5Rre zdZrkPmRJkp`0W;zb*D$yaubs8{VE;M@&!*#qW z8~iH!8Ag{<)`e$_bt^G7E~NgXtgD=vTqn)6ZUFN%tF|cZIgz@f=oe|`FyK&{+1ZAp zgcm7?-;lNA3-=pZP~K~$#kiGG`kJM1DTni?nc+=1W8zh!!ub(`2Zc$S=dyyKM8TsV zu&utcy#AGZDNit*-wd00r5k*hB3qh?2Vj^?nA2zC)6BkRJjHsYmC3FV%+F74@y9!w zyVf=NYOol$DxWS96_)f(S*Xp-d=#xpdem=KKD`_js3T=l-GtUNKHD{m)>@S(}?3E7~%~UbJYOv5fM*O8T0I8x&?3+f$4%nh!}vCYtS=w8h^dmWVdJ) zD#xG)>ohaFMXL~wAvJU{ys*(E8HO`j6>~b8 zC6S;Aks!@1Zbc*z^X0?%0v}MHMDoAIAbwuUVR+v442tpe$)oJ zj9(P`h$Ox)4qLbjWBbogaYJ0MNp4JOINzr1S-b_XS|( z9<#;}^V99xg33LPGW^E?tlVQ<3X9gEODp%-!*DZT#Paix<2m^z=U~AtvsyetAGT^5 z3w~?@eEqwPzG3DE8jD#I(EZZlgBPfb8NN};KzEx7JTH~tiU5olAwEbS;Y~B!He#8_ z69_&bFn#$D0-3+rh-Du8hbw`K6!bN?G;@8U@~Z-6ee7Ft8%5hKx|;QO4lL%fgiDAo zws4sZ=IKuORY#}tE4l_;s4fzf+1si7ssOeXcwPp}~4Gp{qgrK**d z0VV9%e781uhtNNd`L(4FUZ`yIU3$2S(2vR{dYlAoso4>@f!P9X0l1D7=;8uP8@uMV zH0yX{^IdxQlF(mb`X!BsQd~kBVDnvi_|Y9svNhVg2_z90FgrHGnX)%4XVO=o9wSOK zd$a0CbcdPrgzSj~Z{Dn8d7*N}9)^!^R<209oWvFP@5=r&r zv@_#zEhAh|Xm(95fpfC9D5s;h2x633cd}Fg7)~S+r~|<&jrO&S_hKHMwvsjt5bWSc zH@hT#4|*LqyLV(V=86cn5tej?2}A@-67fBVNH>@uxmAm(;z=*Vi?=HC6k&)F8McBH z12sx#and!9K6N#~Brk7O?x9az^@1B>U;u{wMMd>@6O6kE#$<6)Dp295?jGhqTj@Ay zNn$jol&7yDh&oX-{oA)@juj1YmP?v%UaSpIOV-!aUPOr^6E25ZiY!$jtyqd4_k;+Z zU5-Y1uu?N!MOtJw2VfQ0FWyS9eM(PKOqS`zp|0>N1o;hY^F zjQ%DXqrLA%&broyrQ6z|NY5o~KD$IAtpy7G3e2RLetsuzT=3~_zDo~AV)8zrU)pHC zQ-NCqJRx8cA)1Z}c9D6vLbnjSMSc4jo-hXon!VC$0I0N?5j{l?(x=ULg+Z^C z^_dtZ#zmNlv_T!>Y&OrOg&PSiJufR-^O?Ef;l2=XC?V{@j8_q2-sdtB zvHoC56U1L)@=GF_^F0`jB&9D9>@00*Z0ztH!{)K7iwjifrw!yw%)SzA!0=eXZ$!#$ zv|@>QtpqPKJXnRF9)=T2b!ioT90ZUhW_Bswlz64#6A~<27~WWlEleH^H48kz@bLhw zY}kVCvcz03)uO?MqW&11bBUP|!*L9cIjkd2QVSPbf|q!6+gn@X=t0tfY`&|f2A_U9 zdV-~IYr{D0(c65NUIm^hqltdbvf4G9%nxFb48Mg4KO*A+A~GLBMh~W0r@)D02re$u zu$pLYWteuqnC>#1c#&q(Y*XxajcNGC8cw>-L^DoNGx_NQW_n8~)AWxDj~elS>&rz2 z=08XALcFSzX5q=^E&2+2vZaesg!8lt&r3GpcQuTvBmmZ9GB#!-eUUi*O+6JIwLL5YL0*%>wr`d^rFs zZ*D>3I!y8sOhGs)6~LpVfft!%_Wuw_^?eVpNUt#X<(!}UcyKdBMd*#qvix+Y%2NFq%CXM)Vx@Ml6;I=4KOFXgv$`9VT><#+h4u!JrH9qK#*{f;Gc86a+n^ki)rE$xuKAnr1`CqD7m$fuhc1N^`F6xnvaexckua&qy>s4qm zw?Y*Gc46*5+o@=1pzqiz0d2lZkNzp6FKu6&?aW1Y>S|n+-rV+>t;lZ~6PW8oI3Y=E z=(8P5fK`umk175ZbNQoUQ6AmPKl{(Wu17}m+G1(AY)r44IhgvRE%IT$JGn*TvI@)*J(g-@IKyyj0EQQdyixSM8Rl?>mKS~^@tEGU&M@aIu)D}( zuEI5VJI!{w&}@}aN*_9s(gasnxWe^*S`L!B={cjqf6nkol#S^*qryICcrYv?>ZA(V z&4mBPgs0uDpB|V+okvl+-K_j?jEWwt9F#um)o%8p^bQYJ;#yUq#nz=Yc)KNvp?Laj{t# ziri&lIHh8Cg(A_}`c&<7Xm-S)aoXl_8>4g^jhLB?w3-jK&sc4lm(X5VagrLaT0Mvr z=b4K6SoNZ9cdO05Ozd)$(zFRyO4EM3)y^iot@9r#Y#s|zLI*CyKs55MHrK%_!(#<+ z6+O}3w$*0RIOxfP(F`e_4mGaE*#li#O^sYIA-8%`c&M zNZ#1xhDC8N&Nrd^@HUcO9jqiab*kyK8X2uc;@NN zg2Q;SqT7ff=#}4U^GX($9w93PNl3)A;A-;$a{L15DNsd`W1a;|uSVJpEH&;r97ixbBZOZt#fgp+PJDOztniccUWuZIc5C&}THIPC36 zvSd-(LgaCRM<+S>>QgI@=VBdC44=sPTyvD-im>bO=!u7oK{n5&RcfPEiX?pXoL)n% z>1a0(t_Y8<79sT3A(C;r{mM4p9JFulM2*7SV$8fyt8FWoPd6FUG15%8?JCq;u&LNO zoLa)_+&Z_P(|riijB5ltc-m1t)#h1cm#LUgi<*d*UeJnEHqX-1-YzlbNv5Sa)clrs z$0j;j?cd*ELAMYbL~M|Yu(6JaXe-+%Pgzn zVu&cLQow52p#7ybk69JdGnCM7{R^}<&!t7R1@0DadWv1T6*0%k>?m}=rMz%(-^ zVqM9D;dWm1L2z1T8Yg05&4bYq#P^dClDR&Gfl5Uj~c0GQelV>X*{JGH8bla5m4SRkPh1yrEv^%xhe` zd4m}?3HK=343|*Nd*3HQ6PkpJl8)tKanDnh9xL(s+R|hlprqS%^_Mz^;AJ$EsOG|3 zL_fRn_IMc$;>&Al+p$|nH`ijWWbhto?zwEQjMrS7=hDKJ#5}tvy0q2p=8Kb5r=}A~ zLNq;xWPE)R9xA*hD2M7Nm}DIEF+7`Z>(s}Nj^q+O9^1_I?8ulb`=?6=Pm@}&Orctv zCo9j&GYFoYr@9?||3iAl?z;%40lbQnZpfz>pkkTrGfAl670@=%6$Xwdiw=mC&LngB z-f-TCNiM7CTJwkE$eqdb@k$YD3c~q36Pf~{=2@~L{Z{q>!?UNLNgk{OqK&`v%*H8r z{PJLUpERj~;X_jpNj!L+uVaeZ^UUi3=I|{ky_@0CR9zZgB^IKko_Qu8cVO)Bm@BVZ zkpS3P9&e_5MN}uZ`K+%Z8Uv-a8%)0xFWZ*P)xE^#yYz4`u?1>(YOF0xUTQd;QRDW` zC}b3(3q)k-LU|$rs&deZ0Sl}49BNnvg?(GV+%aM@UsC}4Y@T?RgF0x zV6GzODS^|nIO(d9j*v>@roc8e=I~VP%cz-(hXPLs6)X2MP3u(M1bC{jxG5}@e&DGB zHw~p4P#X7bP*Q|g=acj^$#D7rwg)%(@Ig#0YRv2a3{Q}LM($EgA1KessCN4q&7s9U zv{kj5ml{m=^Wh=$JsRaLC-I0@J;)twp7l=sSYC<8sA|)30$;`HejW?z!jGQKWmPx{ zvyW;M`(}cFI|XOC;?Zj#vG5)yedl>NfX4~$BhuGmzEN!^ya4a=V7QNjqMOMCFMa{r z&|Nr2%PhjYYc#?8UeL_pT_Wb&42SLb{z5k%(qYXS#x^67NuLnxQe?|O$hKGMyi?4jQJC#aTd>KcmJ>9@< zMRNLDU^QMfC-)_cHSOO?NSq|2j78YAG1{yn;#{E;CaI6UyYyvkT6nw2RF_UP9|UBA zw+p-?gJ9gQtjwuAy$(~8YI8k=%i}mH4xzl=!E~hBUXFU~2zsQ~G#EwHnu4hb^mfEo zYf*zT%5H{_ok>tfPbtf-jlRh$O}@#bRWB<0HNuglIcKrsuG)O^Mb(@}IIqYN!;ZUZ zQ~z%Xndah)N@4W6OIRFZnhygklm};H8dYtIzoMGb2$M(+2N>@A9%|_Mimm}pCT&Q{ zCKliPif#kENZ?ZpUk||WBB^2e1S);~t8};jS8HMP_R=zQP62TjfB2ao_!YxGA z2N-_gsJ51Ji^R!PI{HK97M$g}1>H3&I@`{q880c7u2*hRo=2RPy`(ByuVUIUhW7?w zc!V&|#`Lk;yc%GxhQxk`LtoR(;Stivt(aX_o3a25XAt-b!y5yz3Mnh@q|z@2U^s(_ zwg_|6YIFH(y4~;tf$6IY)h6p7H4NJe9K|fP+N=z~DmFaN@aO+gHw?Cy(v_IRVqkeA zA;qlBh>XnQzr{8xs9$Be;m0%^38G>ER!%Sk6WwaF?U>($V%mf!>g!_on<$;? zdRQ@?=#WK(rl|SskHU9lHKB-y!}8LGZkQRp`MBnetO9q{Vjj#4|2>ZDlfBZ&67IP$ zbG3QpIBvejpf(xj;GgH5gs=N;EsiQj*dUL-cyOq zXO$Gj^34~0NnHoV5TCw>hm9w-kMiq+vq-2rn?f|_f1-S;5Y8gT?-)yP z@&#plx>`|cps#kr)h>k7P2&Y+{6aX0)XG-Mf(W}SomhpI<9=68x*k>t9}$upOtSF}-5wQe>9*QB^U@ot;}yb3 zq$w8|zWjz(7Cb}XZcNha%!Hq67@i^UbWG6eOgsRq0rn!phkvR>qemVoy$BQTI`ft; zO~(@i?qfLXXR2=cHjKbUn2*<))d5&}!4Zc08_|jPCc~xrex_VXe==qqCgqUgXW^VI zv6g-i>LJ*vTv}i*{|ukTvVU4b(U2on7=p<;krgsomi^NugKG%cRw6U|E^3XyH3YuO z@aq9sdBXur-{JjD*ua+krt*GTy%QF64yMk`e^b{0cM$i!#_-NJF}QlIg*!;;rioO# z=h0y)=FK;8bE`+AeBvV0gnq8=0-q4?Uz9^EDt?Z^-zyED5VIxb5*%$AhGW?!2%P-4 z>(;bVCUo6Q_p+{qUJwaE}VZ(n58|5V(lc>6~UnpVe4Zg6s!f;X>yyV4S<6B(( zx3EFbkVe%_CN?ksLN$u69+koG9K+XtftP;LX8M+l45~3a1dwwSt-%p7wZv=lt(O$T zON9QWOJ6vM-sZdXa2t`X5043T&fEtVt*JJjxfIUu6kiPI5u)jM8mKd`T+&T|-w1qw z;ST~Z{6^p*cv!$#@)llhdo6_DhypqY<`!00J+Q`Ji7c}zi@8$6kEF~cX8G(}Dl*Z> zW(2Op14f;BJpjXx1U|uV=$E*YTm;hhlhP`Aol~>C+Pw7>TG0EY>izVlNZNIV=uGP` zl~(j8W{U8DQD^El56dw%U%@A4`U8C6NHRv!r?l(LyT4RpBzC2$-WM~^VvzXjq>A5Z~;?kp{F=k8O` z$uQL#z}($a9Na{DL=vRNoMJ$A7X35@Qup0 z#x?F%Ht`2bWBoyYfaVI7wHu*0>2^c<=8UkfM_cRcHH@4T61a_wu0t@t?X4>$+`73H+@#eO z<5ri_B8iltx7wYwnLEw&EP+#ae4$mLd7EjlqdP5&lhQ79KnWQ&w-Oud>Q3`HKyd<} zWEeZT6%3^bOy@H?X*aim(boh%Hk9Cv8rEM=A(fY!u{C&dDYc@-XzH&ma=YCKa=V4| z$seV0w29+(em&iUi>hh^r-m)YO3N>SqD7!OH0O4DIoE)%4k#tte3u?d7Wz?mwz}PE zxT}3jd*@@I2Vh^YTEHy;jfu8)5xuJ0(X~E3?cJs!27-+p_LE{1sFr555 z4MXD+cW5#Dc2oU3#2v3RG%lrYFr3|*m}U`6xoZ9Y4$$ zUkwk>vVbk1*Y2;ud5TTOb@VoAr(V0KtA&cqvg_z=9*jw%D6tRgCdFp&b%Z|;#@H@> zwI1sM#pV^1uJ&LIgCZ}F# z_&PwQ4=dLimqG9+f3M|Jy`>V*e#Pc=pfq}m1cM|z+!dP-evfH}S2vtR#J|LF@%x%N z{6pXxJlqwVjT+WV_GcJ=DF91YmfBzyl0V`aspa9^N3%QiEqS*yRI+ zU03p0exq43FN`e@ss*&Id$_@4`S>hOS_?;uRQK*<625nulP(E81&J)P(8-3|afp*b zg4T%pQ7oTg%0@&oM@+GBEI;4;-G7E>;O1x;L|Ao$F2%Cqq|1uBv~Q&@Qp<4W`2bVonw(T@vcALehd@kU~pr?(!M`Ep%v{RQWd3 zVF7Gf7AJ)S<`R+yC?JKF(57W^Qb=GjAsJv2EW%C8;-rwE6HC)ci!<%Cai)a}%OHo$ z-zg~0H2ZSG(?T;%MK5-MwLn*#lV+~w;DxbQ3iV1W>58wJW^68;+=XNL=)w{Njxf9| z7g5P84Uq(&KiFYpwIykTDbOpqS{|nyzrrJt2`f?4X|Dk${7^ z15G>=2Mvrij};p&Y6y0~6*PgxrG=ZCKMGU$#vn;nSP_cXsZL8FVFlh%{2(Qqf$@Tw z7O#U>ivYCYf5jjHY@SQ2B2qg1XobliiEV0}6n5|>ah7f-i4zGYg#`W~By^M93Vvyl z#YrJiK0-Igt*{@i;iQnjPlO9ytGmKnAB&;XYZm-Onnn6(;BGd*!ImzG!~O!3iW>&C z+U9YqOX9Gi)HEGUYOs%soD_D-59nx11D&}TQ_M*rf$@aPO(J3AEpKk@N5m!6_8Rv5t`g!Hl{%#QhF^ML0Wu};lpXzoaMpF z4QkM@8gO+hzBA>CX7j8<=$w%VG6emrfzF7enWS`dFpnSnKxksXPv@%^f$@b#*;_3hMFt2B$blEEpY=g-3gs=>ULjyUMC zgi}c9p^M$1;0%Nw4@TS&_zJ@n0T@10;;v^L!MwY{^#39>&D+$%S<*DPjF9fa9GpqB z&ACgVk*Oj#=L`M1eHES0EQyS|{eK+i)Bo$VKYr5*IoDv(o5$#|faAPhY9=p<%u4Nb z>d2k(qmT>Fb&maA_Egim9uE;uFNqYUzT{*Bpx-Q@L~vz6`cyN}41(V+iIk@9b9P~U zoqi3I9ok#xL_Y-bMN`2Moa2;h7igRs$dMeoxOkNIx%g%I{pvWb-_Ms(s zAoZutesp~1j-E?}PtHdJnEQLnQT=zFCK3w20icx34yZL#sdclf#fq}R`S}(373L#L zA~~sNodd3?$1v$94%eQup7iIAQrj7CsBCO$c8bg9mX^gZnYD)az^O;$>30bOIPvHU zNRgwYsKf_5x8Q4i4|b4AH#u{n6?01~%H~^X4mvayre9y4<<#?6-L|5$VKXm6I&-5j z`d^8a=4mHA$>o8Vz&i14wqymAcFyU$#}ZtHdyrNSR6?u0Dbg}Db)0LfAl;Xo z9&WYuD3UyplmjfyJoYdG+g>Nh_4ol8n+VRj5~P|RJ{*ar{+mPNBK>x`%IWz(v=7~K zoQc*&3Q}Ki=&Pdid)wvE_rD-O8&b_@>tLXNb@t;4lYRqZZ52JFq4Ihd;r%*j=!?#F zbVvF%+-J4WO(rg19eF7AKb(ss6n;1HkCOFd8(>q-8>=G~sfV2*u6&muA2qg{KJ0W(kt0Ps2cy%*&5Nic{Zr`WQxV#ecar>at8Qbxouy^|Q_pL`?b( zNaSSsNCnTYfeQZCNrL9-cLcH!hwPi+aCHq_@V{)G$h(SvgjH5ia@W>EGkx`u1*t!GXrD6uy5U1a5Tn98E)~YnxYHadh+qK!h@hTYFAg3yhvRVY zKR9%biGE%9FI5?J>nSzk*G6WhzV2*i*jGW{kD((7Qe|FR8<~-M-syG;cHzHN&$Ywk zV{0Rir@rFQ*-rW`8g04PxG^Wyd~O}a#vgcHn2r*$iP(nqaKisxhgSU1sRuwmTEZpn z{WLVqYk&&=pK}6_@$}oBYYX@D*iG11oEte7+nQ~$V_s|+-3aG>&*`!_7W7>8xS=f7 zv^7TNr5dl{JuX4H>piLFmqc*Xp$~A=Z;`9IKCg-g)}wL%=nS|f8iig+jT;~W%q<>B z{W~YoweKD@irUppYUO!H<_7e>&v^ZxwwDlX|0hw{>;L0b|6joOJlM0{v4V=SXvv&> z8)n~huDX4gu0kL#9n?w~XMFCQ_`1h%+IT}Fa|-Pqk(9)ef(7`(v>`Gl^^$YI)pgNii}eOZJ{?MFtXbFIL0^N-Ul1!^ zP*^4oO;T@?-Kq|vWILHZHly|{-;C74C%MXE!Rs9 z%yX9?G{M97IN7d=5-}^M!q;3wbC4Wiikc&LrT*4A1C)MO(4&aznCGsaZHBWQcWB~H zziv0wPoZdy?!GYfh(qVq=(j)HDxl^kkiqjMJ$b0X+rBomzI1L$QCUI30_y>jiZ2=K;pvVA% zM^k^|Y~`Z92lf!wPuOpqCbvr`xzTzzDG|f{L#bbL%3Uw2ccqHCQ^-{F<5tY?E;zjy z#OPO)ZKYa4g`wqCQ_zOd?v&Hux&kfZkW@)z2I`D={{Q&CdtAP#Vs3F!MVUMIx$ZQ% z{(c4$6R&y+9!Y)KDR(_F8?H_~ zds#Cb7<10GV>G_ubVDulI{~glkWIrO43lPNcEFdv?@*+pA6@N31S`lDwsxQwo^-al zV*xGX6IM<&_je!~KF9MDD%bCpyXHD*s#&-(Ql5I%Npfd$r(jWPQVlh!cOwe_yVK(8 z{St->Vm#ml>f1YEm~T2A#2P>GhI)#%Y?zOBMk-VP$)Syz{Db(!p@tgH4u`qmy{Z4; zoREgYa#Ve<$6?hbnD$?sA(V^X0RAxtca$6-3|;&ePLA8CTiw{Uxdw07Tb$CO1q4q-Y|9cMEmVWdWhA_v|^v}BxNA^2(kb{0(T_+fzc*O(L+|794>~W5|9HOqW`iKKh ziNCcOBiGlR=NDTJQ`}kiSqky>kHd||J&ykU3vUdNP|!nFfM9LvZifO4{bXG1rM_Rj z1#{*bk7GjhZHF#Wq2D?Dmy+4+z*{hBdeXy=xLA!>`0N%G{=9S6wc~!b2S!P)Nn264 z--`<}$n{WwVlVmZR*d&=IW?{W_qriCk@`2fZ~8Oa!2D-Uw=4Qd*NN-h=esnsW?N)# z>W_IANuo=;%e@+YxD8(Zu9NOY*;>~)*GN1(1u};e^WaA@BYVeVBkp{KUt^o3Lb#29@?A9|MJG1wFXXg$J&z3JxG3jsQK8(QDy)Ajx*L${0EYEnDbQ6t&8YFh4UkZ zk9p=3sAm0g#|bmCV-qD^y}089|3#YY1|}LEjO_$=$6qP;9I)}OQw}coFAw|W(C5r& zc1OZPFCp`hTg;bsqXBn6f_`jv?uOKlBYE1Ke+o@3U4zZ_3Ff`0K(VUhRcJZTFn6$a? zAz5LQGyleMGHr4plFc^x4J4nm$-D8);wDe~$;v0_O}uRrk{4~V>tpn>D9(Kn$-8Xw zn||`wNZv!a=|gt7skDTZesaH`{1K9_xc`CVRLd*U?KszM@=r(>*`^hKoIh0fX|UxK zORx>eEQ>$$3EGguxvwJ`vdJGJ`J7F*?xGKDF~N_KWD(O6!k_eLBYyHWB;nrV9W#(T zy3$(t&0o^zZkff~NKQAiKLdj&{X4k?C%cfm!|X%u(9a?HV7~dL=&=1PhVOumtNQckGU0=TZ8@?So;w>X%>0i8>pBL4*7Y zI~4xyFNCGy4}j6f_UISJjb`!-AzgNR$eUV(!AE`}ytI4~*!SFwa5Ml$osP_qgMP=q zFt113G}ZG{V8^KeV{`6uo*Wm#?nL{G3?h6P*z=}h#gH+Nkf5t4gq$-j>1_}|e#BtH z#E{eKVY(58&S!y5@vzBKjDy)f0jmm`_j)3!JN}dta=z}ONgkCAddG7^PWNBI@+XCy zBsa1RE>|(bSKwgmI51HlFx?=`P3{Ug?xYWw1o=Nw;9g+KX5-$GV}{e8Uz!<$3vc`a zJmwUVFW6)}8bVZG{6*xpA$bQUC+tD;gNc?M7A(9U@!7eQ$dV7CD?Eqfj}y&ZhtL%^ z))6DhPWTv-A)DOcC%gURPCxl^KluqixeG~*HD3a=eMq9mB02OQk^FgqdGAZ8?y09K zyW%-ye;LV@x0*+uL$>p`A?HDx{UDN+A)9UXhY&M~I^iOcPuS$L&xf3!S>ox>gz&J% z#6yz~gq)3Tdgrqt=P{S})q^2?%Z8aOJru%C5uDtLUxFZ#J(_j6zN zbNl_=pZU4(`MDqXxuXty@{U1roYn74Keq%)SL@Y&ZmpmDn4jC}=RW1<_V~G9_H)1H z=f3Lap7V2m?dSd$NmsI=e@C&MonSPQqir%5$%suBAc+|aIsZZ=zheDp==*;ka<;iX z)%t?R?kOaHW((H;L&*8AEjaPZA?LJ9{A)ZWjIk7d@RP$|q;AY&jPR2qk-XjJPC{~; zP1YcpW0RYZe9|WW2gw~ax$P?<=l`qhJix0c_P;-;Z2}2d0)#+-kWeIm5Q0cA3B4#y zItV0mq=TS>9#p!BazPjC1;lGX#fDLuAc|c9yJEZIMX-S=QUv~=nb|$(WW%24eNUcW z=Ckvi-?W`Av%BZ)M2+7^(CD$5eY{fKNGEXj~XU<0-I;U8C1Olbg1x#uwmn zD|kpr}pv%cT=@W10)IWgJ{5tP`r+ngR zo#FzRsZ&({+b8DODegWa+pOxk1FUTMHqfGjV2;MKU=@uO&PK2S*igp~1oJd50W&pj z0vl-j0BovJobxf|nJJ5?1%9N^_zQf^Z>`!u&lF#vXAI3#Lw=DRQXE=U)-Sqf&yT>? z8p|d5#XOCRz}gxg1Je`+b|m?&S2w0qHNGTnTY@!hBYW4i75)6m$casyK0!x#B`KTD zyOsQ+o8M}@iMplxxdyG%W>obvd5|eWUxCRQk3{ig6fZ_GDI=0LJ&LszWhgnti>ecd#Z+*H>Mjh#)>XZ#u(s(6kSFa$7 zS4VMZ6vstzCYYvkSORiB@HoA(32eqNdyMY-yq=#CAfrRa!G;>E8oV&on{BjsrP9ksx~tDDP9tPfZ=D|MEoUaA&`mYkj|ke1>)Li>EXi zUH#&Fh1o|yQ>NtOc0Se3&#_)Pr*-%9+mIVxCZD=sXN{9U?k&mKx!^Mz>-6x8t2E94 z^Q;rEkYEEC)|k~()?LNc1OKD(eQ=e=;l2D~okHUzSj}gpY@>ftuBM?n#S-we##?&( zIqy-qy$Ysj{1{BI3b#@6S74^bGtpSlClZ?(#kOFIPTLbq)Yv~7J31OW5v-{bECm_y zvb2q0n#SU2+E>AfI`&``e+0Yh*hYQ*qMpV9pr!F=(5}uI(5{ZJUnJH9?b!5aY+cZ& zbGR%T+bo*4EtsJb3<4`_oB~$YxD32p0kkta0VY{96BD`cvyCIqKO>zYjld|s80xcbkwam`Xs4IM zGeKv2tgQ#K`Y#9dU1$gG4biO?-ps~ir*~`X&?ebigrT~qH&DF=9>BuRGFHlHxFD44lXB;DomM z|NNpuP;uz`V}7w&r_TD>FD}#3M%Ul{qN+|F8g-maTqpSh+-!S3^p{@@Q_-Qn!Sfpb zJmnXoH4gY&p0B8ih|_*?pPk)(XXH7DivADyksW>GIlq{1=Ka241`2wPM8Qt7IWdmZPUFj1k0lV|_R*zdbFx zY%Ms*F7R0SfcT%zZ+~h)%(MHZTjhW_YUsS1)Ch=TJNc2!0N3|r@uAu^1N>r+!Wp0) z`xMws$DWMF=4J&raZt4$1U9g9TbLc-T|O#{<6u*bwQ5ChKopmNOzC9FOF_L>jPJqA zm{YOJLkV>QoX4pYEx|S#XGifF@I4i4+;mw$+-}$6e7%5}qoZf$1bD1bXZJ;efat07 zsNFEYMRJw%U@%qVM6jC1+oQ2-qp@4Sk930Dc+#?!#_gbPh_M6Auxs&YqkuE0nl}!J zdv)UXKs_!)qjCdsW-2?NYLfsbY6>q0d2ywT?F3$-aV}U(<2q0e#n7W*BOQAX%+`1k zw7acNo>R3@UGQ_2z&H<%v}-y1ihy`qN7rc<5cenOzS`9$Aa2sxwQTD&+DK~0u&^Dw zwGW7Vonk5YiN+Bf0-~eFhe5qbhjxJLbnJlqfOu15wSs{7Qlaq|c$uAXwN3%1391AB ziQ?CtBRzB+Jf{=<+$F%P^JH3MXxD(a!Or49w}8EA8y|G1zwK?H@aljVZV!eXeIje8 zdS7Sl7|(;{bPD6u{?U>6Bi}%@w}h%P9W2M|t-2z^36%6)Qw3_T>@_BMl zK&%c}nL8QAi-yVJsFIxqD``v~E?13;Ee959oDOCxH0}f|2Xz*Yj0%V;I)yn}X3=jK zh1LdJY8(zet}##;;J%tnU?hX(L)HaZi|XS8Tuf1ZJ;Cx;-m7FW3~Z!vDad`iJ;b(| zAh#5Si@~v$?{#92P7H9?zj`lt0`zJ812i@ICPlD(6l+GYG04xF$Q)LHb*v5hz-Pc5 zji0L6oig?;m|-cbG&vx4Yy23jukk!sNn`4DatEW*b^`MhX3qhiw2xW2b|?dRz|Nc^ z_iD;x9N0qRgJ6QjN5G-hb8l0Ve?Z>wAS*R=YCtsCco&$d(0Cd=7O-~hqnoXnGJ5qp z^!`@xw-oD{cZhyuVSs7J(?o}w+!kOGsZ!+J9uRkN3rnUbUL4@d3W|8%Jv%M{5^H>%4rhcPo0uaqN%wv`6bNqTOTl>ucW#TDvMBLYD8{ zl=PwZ-NnY@;k5zHYdyS*mYk#=-F^M;{c^3=Ap6iku$#uJ4+O+ig~k%_exH^3F5@Zd zAvtnX;t}9vjr+hE8k;{HV6v?e6oKg)Zv<;~vSzww%<4TZW@XdR4 z&xfxExCg#RHgeP(oC|4u6Xa@|?6jnP0r_1@nV>aTr13#8U*jRLy2jHWmqumU;F|%l z)4KHo*2W(26E3t;oN@1a?8OYtA01?c`8A*TI3Ri@=qj~6B=`3!m$9Hv<2W!y<7|)@ z8_QxI11D=t{aT(msn|_mg2v6Do%UO>hl(|FzTrq@_dttp9Y5n8@CqGmod1sV$IV1dmt+`>9g>qq3I{dO0FR@Apn#E>*kOV)Rk=f;aoKiVK_|9^ElWJX%@gtIgalEGEIu{-&+HPm+P$ z)hfm$$q3pY9Xoh`?;@0L=42rG+?cmn7RSt^(diXt9m1^0;AHQ&< zNEw$`jqS$6u}_WYHsvmGD%!X9C0Dn0RV}tlyOjJ$X}WjsJ|vo zW5x~+im|r;TSJ4KFRQ{Xg1X%7a>Ih`T6Oh0=|KILQTfAz!f&Pikdnq(WXITr&MYK2 zN-q|gItw?mz(X(EX9Ww5orRZUl{Z+(Q3_YHeq~{XM;)%cHpsl-=EHQ+DsY3w+>t>p z$*9=9;9!jzqhzgAY&Mvzu@Tru;{tGiLSsLe#O;B@^z2uogB+oxpE0eF>f6!ti-KG# zP}#i*@;InW@ixd~D!q^5Se;*_sBZa=P`Q@lgFKyfK-P0Uc&Cm{oFuEPVxIulYHT+- zD4%#FZTNA}nd@|Qb$|cs*gM*H>fG9b89}kpPVd$-X9mT5yF1<5eY1j*Ym8_;BSp&e zPa;0+k?FA6^niyp9j%;o>oGM>7O-%?vru_XklCWGv}U2EvoMr}AFS_N^2qM~qa1_V z&JA+zXs7JYLV>fehJ|X*!ZR#Pau(9(1$nr^_IWsVq3#Va%2O;{`J!spJy{u_gw zoY@)tz(QkZA@!!1g$^vVag>{47q-SO9FJXSI6uZ`JPVP=EnuO(liQ;#oNyNIT@d6F zt6iN}Viyjv(85tF-pt-cEwF{>v9Pk5wM!1io$G>}Qx*Ke7(4;Kuh7_aUrHhqVJ(~j%HdyE5DgNs)x3I zbIqXm%-#^)HJ$ey8>yB3Yf2iG-0(cz>ygVwG@g-GA9p6@UI>bT_EFHS6}=P`bv^u+ zqOGtC>|xdaHKiPtNPRgd+Iu+kiKE?#R_x)|`IVqxCZIm<3Rc+}6lWa2=$g`fp1O;} zizC{h3}mG{quDcN;m))V+DUsJ?$$cK$uPI`a%)59BChrj6Zne9P!DZ1nmxcvRc1We zKDCZH4qpCFkU95iRyaqlPApvRk>hl+)c%iVo#o7NT`BMW`3JRVNnpLSkPTop>ML^v~8Qj)43cl}vmNtgJCL zFM{>JRyuZcGr8n`?X< zlSL!I>Z@|%55XK%DVM5=d5j< zw4vT0XN|J7;b4Kr2SK~vcY+`4d{^@Iv;;ffHSHq#UI4GwDSEXJi8MRK=nj!pGZ(aT zE(RCsLR#d9IJBywr-63!H$`K=0_*7n{(?xG(?EOeHv}KDzW<9BL3UsN4ZfnQ^K8eE zxWjLaJjnxXT|%O_&TBbXtTDf9h)Z*-3fF$J$F1OAjh*?nSZ$3Hz#1ACfjsE=550Xq$b*g&UyI@~Fkih5)1{$YkU>FLgOD%tUE}qP?fe5XeXEpX6slB9Ha3p*hFK4!E)s*w-!H}WLOhnIa5z{&<5ZAqVdqKkA(*Q1JFua~q@f|P-TGQ4*f%W1%{i6! zCooH6;_wLOfI5NE6a15lW#`$_+Kqg-o(L-odnm|dtm=7I$}=i+f85!ASSe2C+P zN^mfWN24ev$X=5Pj7)G|hR*n&TSH=|wc!HwG;U+WYb*!W(AWU1r_ksJ*5=D{7pTyj zMeGK2io2rtBv?hqz6SQPQZJHmxy7=F6lQ|MHQor0)A$XzUE_UAWVfiauYfx>&RrT3 z&uh$C7Rjtt6nlbqsszSoV0oS}y+|#OtOzj|P`Md*$h}g5&rAAnQmMJ_Xn+!K9lRFcZawgLvB@qt3zUxax<<2kMsQnnPB*u5K|IaoDl|p zwxcKCBlm);7H@(43ZP8!H#na!J4nY__l3kiI>og6Bb7S^w$ib=4}`cys`8&+AsRP!Bn6|1yHiI|oY8W{iS=Dyx+)c7WRqFf*`ulCN+WX85 zV>nSf5G(UFTK^{`TH8G5F~)*jW$Q_~n^QTYZw~S3q{5xx3SD%!rx=`Nbmc~F4RNLa zIeIPx^|t$^d~t|xl_|e1;BJl6U#3wSi(X-8t8<$N?g{DKTD~fWePIGk?E|*fxE$o^ zKpDFNdEr{RlY3K7AWvpHMmH zJm>bwy|+vjN_|sq)e7rJ&|mPTwX3R`k==)=MIM=a^p;#bU&~C6f$X*(@<&ejR`f_{x} zfK4_24c69}@qye{RA!sN@fyp1D4V8Y`+yZR7J{i7XMqhhJ_PQwHc%a7%>I!4TGp-% zhVhP%!Mq?BHjKt0avvd)w|B|O`s=nWVc^b`A5zGgh=-3(HlNvMrj^OK2oOU|Ib4V() zx4>2!eP<%rI*PNw{yM=Mpk45(DAqe`$5shClpb0RcGF(_qnLh9ZqcgT`Ji3yi(q3N z`(LoS#tUG&ZhP8!br6?5-871QqBtdr%RwG^kZJc{h~#kOqTEnb!9RfuG>&BkYvXrd zqMaa$$D?>UiozF3n;6CNQLGZhEU=@_w+L*YaV2OEv!LJL5T|N37qnx4i{kh|B=(yq z4&v7>&+BGhV?+|X3$E3%qY@3Suc~}Eg8WJVU1ID8t9H|y%NKnN_D!kP=&6%nYmJTi z%EqbKE5Q#G8i9U>7#FY_SL5J0aeyHLKE(Fs=aW26e_mh8be9PVqI!EKFu`6y*B2#Ps2YoZm@o2v*bB6|_sf z4P2yR4Pyi?wKL8dZLrlUzbnC-R=MhAF(8Vw!6F^|3HXJ^X9{J>D(xZgsC7WPy)i~+ zreePY8(9T4h)v+PX{ss=WQ{ef4mHfGoc2cI@}0PDk+{%kFhhIa1afhajEr^Q3!GQf zFe|s~HJ;9~k8Gn|N4Obi%RRI+Xw|IMnbfP&1cOI?BpOq}6uxSn$)0sS?_R!Kr+5sk zr|| z5N)=0|wn)9sh7KV4ds8-?2LE8XDTGfm=X zSH;mLD$VYHcb6`Tw8LJ%gWWzdO_K5WQM)0j;7(fvNKi!S73{k2}w0Xit>Z!m9Oo z3pmEgZs6l~Y;&_A>U(HoZ!w(ni^%a?<{^`hN3-2ZX%ixTwBI@KJC2j$I8Kf@miC(x z$8V~apX~qXaU5r$IY&cxMdzV8`vkYPGLGMx7{9RF@$op0TVfpDey^h$LD`3;d*+?n zjL4lzmtRtgHCdTnw636dO?Wf!CE^u=k$LHe|xId2HXK1B+hVo@A&c<={E%ol1nrI2K zEBLq@aakO{&W@jKzuU1_9LGtH<0brN#PM6@;iu+*_aK(;8r?H5dpOEodo@mhU&rw~ z9Q6yAYQ2A%cbAqy^BSb};`lX2YfFXYr(|!_|C8f5&P4O-nYD5J9zgS|=qs^)di?8} z$u8X;$MKt3NA05iOTQoE_yv}G_h`5*;$?PbCA)^7GDh>-=eI|5E(*E*=Ef=TX0(`H zaJ2oh6^jwQj%p90dF}Imj#J>b`MOhxl*VO6veEsQC!9-6B> z-F{h{QE>_!AE&@+ar~}F^V$s8C_lUZ-6QyZM6d0BXPg3GkK=dbQhu_0+4|oQ>)2i8 zu1tlM-m9W2nwMX@IDVbcWY4Jfy9+Fe<2VV;>!kEHG_Q4kH=6VCW=wf{{X1&;78P>e&9Eya1DWYbG-p$D?&UgK`M07ibZhBoFUy2{N^11~hjAP~ zMQgA9T#mda`)%(6tD!kPTCzZ{F~<7o@vlpeEzCo7y43C14UI?8)yJ*f_W@6|XsJ|1 zpGI?T!OpVN$iUB^wY#QSKAid?M!#o|>Ie$*9-})@e>|`Zpo5|KUS!Oc7 z4I^C~*(R%1w%LIVZBVih4{`70wIHuzVLk3{#J7Yv_}`4lkbRJ7$6nz`9-9^i@YcCP z?86S{2+_4Zn-o5qxnC#4M^iYOF~Yv%B))A;-bH~f!`s+A&SQmH96_<+{8GRX?Cvnn zFqGrL7=Bhngs4CPyQV@;u<0aNM_huvRZh&A{wVu(CM zArmS1Rtnxu+6Lq+?O7UE6~8CQs~X#{w693tit>06QG_p0LuvEt@oEifXi&&5_YGl`oZM+-xf^ z-@MjJ>tGJF8s$^i`73r_jY%OeR2Cd&a_)@Hq`My4D zzCM#`4a!rHVm*7gIXqI_XzSai<_K$At~nzTSE8Dc_aj?-a?ER@X)4B4(@A69noAvP zr27)AUQNtCGI53Cy{*i$HDTGaz|LSa5P{F0}c0p@To;j}Mt0PC0cmtkwBA4}Exg*8g(#1?IzPyWB$0w^&(fXnR zmA|Wsud21awWe~`!bXfd#$b_^awYxqU2R%AD90SC#zyhT7Uq>c#zmrawjK@Il4F|I zuQLC3ofx%E>ihWKbVsrpp6jb%J=vWh{y`73y!B;{ukTu4IqOUvbF1ow>LsdJvces$ z117zrR!Z0Q<{QePc4>!FuYOyTdTxN#JCAkwPZP>qiL5?3xLd(tYG zYZkiWZtQ4Iw%S}lkE^ZW$9!{$qBZZHPg&FYLLX~hGF`W%KCPsRMN#+Iq3yi&*)>C_SkX9;zeDSdyQ6sG1TbpIA&8?`*;%@9`D%Pcp zkGs(|Ls~HyU*`#(N_EJ<}hnZnlDxN{q)Lg5I41r?PvAUQ+xM( ziTAKu{pvBCBWp#yMcy;Db!*4iF;z8Y4V8QgxZY_-a?S8eI9rcF)gXpTT`RLQt&cdW z7na)9aleq>>Q~nsuU1?2nC#uDCd3qw*@#^lJGZ{pj<$5_w>``{$xAqelV_sx^IXAV z-@nQRGx~fprw<2u@!FitV@I#<(R1_Xhr?_8q&(EARdME3W@Eo~Jb^XaWFp7Dx$@XI zX8N@8lP1h6oHwIzR^imy)~$uC{YaYXF=>hl=kUha8>dd6HfhfES(BzsuvU*TCq&cM zj!9cMX3V%L<7Q2tIu4gHg;ORK>DRrh?2E7JZSL|#9fQ)*+SA*d5{;`Eli3_z^gfXn zy}Rm`5tC$Mp?;4$FU6Jbad*`$wxuN0?`c=Lt@-Uj<>IWq=HZxrNsGysk|#}{q_*Av zpN^4fi-Xsgof4ug^2k>8;r_8^nc}{~%!V=5xMUBg)V&=H_HpO_`RKa!ZvU*qWC5Fe$W(LXB3u96w684hiOR`M?CiznKj&ITD>XeZPTl1yi;zgoikVXL=!KaH`KVMC33XXiK=W z8IvNyVov|bLS!+63bz2rhgmm?NIi;h8}o!Vgb$K?Pr{$cjroQc$y{M9VIi}sZiKHe z;h0AlVDizP@Hi8cVTAHS9YjJ36Cc9LOy8KZh!M;;h7M~mz0*ql!cpc#h zCM{Wn4>#8rjJGgJ>BRDBj66gJ)4D>!cd0;kLVij~ed~c2AF1zRl*8{9;^)yS*{j)< znlG30m~j#QO^aI*{=!5@KG3#3Im`?h=tA?R5=v&;C(@ZUO(g8zlDQ$_7z&WR^mHPV zPr{+}P-_{V&8&$~b~ky7W>*SzWvnAzeG|*esBjS>Uoun=GlsJS7awRGt)XpVJufO$ zzj~9`L|-skN=|f!c!&NON7!G^B?<4P)DDCXkZu;?5?WS3*fCdMf_uCUGisKHCev!d zkI7^T;bn}8&V;aBv~ZG_=F%Q2w@K4B2uNO;n(UwPV(2`5n^lM2xp zBFwsE^@*hzogludDAcw8yXi-IU7SRxuA&Pf<4ycc3n^PXNta$jC?~kIRcxcDrxA9d z&_Qx7zrz%pMu~>huoq#qEM8_x_#wHCB&fzhFQ&1+7$%}TEnP@>hT3!`Y=!>-LX-aQNco~W>xMdrFY~w>LU^2YHimFT zK&bmg16i@;DMrv@l8D0;%<2~d82xhzmojLnySRgHnnajPqS=JQ=*eWlmDG}9B>3$} zb*b(@IYNwPxjjA8KOZ=O<7C1I=(l!+OW0?U*`=HVySdtHY=*ogqFY z*F~!fCT5;z0blWNyk$xAGkpA~rgU_b%Eg%r%zyc;CJW3-Vfu>F#Y(Con=yncwuIM} z=S}fcvkoh%CC%(id%6=>rz8DGnqO#Q6KeH1D|Ztm$*a`+8IixRMn5LMt7a0%h?UoC z)&@z-It!Av5@pEiK#K_XU%}e$Oh>+mki%$c){2*1<2;~?&g3)&-i`AP9J1)RMGVI* zn)>WYwlREuIV;3ZGChS%qyme`D@djJ4O#JECkkeT|H2yQJpp0}!+gd@@`d>|H}N^^ zs(J<1_T8-P!>rK#R6r*FlbZI$v3o7{p{#x02PrDi`j3gOIjDCfIrvKLK6K% zCW2OUf0B&QWS8z{xXMsR4iP9e-*JxSQ=ItOUJ5U^2%feRt>9;)xa{b znphT=jn%?xV|B2)*kxEfEC;KPHNYBTmt&2v##k=a1j|cg{Wk@!z?xxKV$HD@SWB!G z)*5SrwZ+}sqx)(4XVxL+dczdvvd zHUJxl4Z;RvL$IOPFl;zB0=pI)iH*WWV})1|HU=Aujl;%c6R?TcBy2Kv9X177Usa{bT3W@B@(>#@1mJnRPSM(ieRKDGe68M_6OehaZ%vD>iQu|?QoYzej$TZS#i zR$zBvE3rGVRoGqF-B_*F{QDQS23w2WgWZc+*gEXK#5FxXKWOb(Wabyoxy}68=UcGm z`_Ha>VZaxoeZ?b|m^o=LRR4WIpv*8v{!na4@y!d(T;G}pPcE|RtT*d~_Y-*lJBWRR zeT;pAeTsdCeU5#BeTjXA9m2lGzQMl5zQex9{)_#9$-U%{*#EF2*iYC|>=^bl_6zna z_8azl0;griffLvt*h%b9>@VyT_BVDKJA<9Y&SC#x=dlaeMNH5O0W64xFat}#60tH^ zSu82>xq@N7-mie$upi&Ix7 N|L%LC$*H}*{{xwrz|a5y delta 279028 zcmaH!33wF6*7v)or)M&mWXO;}2qYvSYykoU0s>)403paOAUh-ivW3;CpkM|?1urV7 zqQ_#d6cc_W?lZ#9CFFl?7{;Rh(%Y9G?+gcPv#jXC~&wc9n!E;-U z7PIu{Z{BXj3>2&>$V*#OaBK9Mf~kQu1tHg(f(K*bb}zeg&%kXN^>$AwslTSUWvpf7 zsRCErCu3)Pad6ik^J?E2s(2xBipzfxx2E89Aa2NWPgQI6!RYZHw>kLFw)-bp z`jURbUU8$1%X{*z?&F%SnVOiC*Ll#T3xmtl{)NG0wZEpGtj@}Rbsr9{EkE&aFh(z16g;Qa zrsz+q&?CVZwfK?Xj`D&>gT=b)mxjSBk6}M8T|ceHE(s1%dzJ)isFFJ5Bkl2Ea(Uk4 z!BvKuP+vb}E~0HdqVgN)gH?hGE+~~o_%31ZAzg9bh|EFWM~)#a$!}L=FftQahdhsL zL5?GTAaA=g?Evu)A{TI9M1Da=8`vT25K@S{2)PxRj1(hF3~iG3IF7>*K0rQ1jv(s@ z`wya%x}*3%LR`3|V|{`cxZQ|}cn~l0DdC?XpCiYR`h@jCZb3#Nx2e^&^myMFsJ=v= zR9lnv_?wU8Jb|1Ddx5!*L z?OJQva^$uabV#IOElrz`Y-^xt!G^R@vic~6cpljuMf*ZNXbvx1)1v7w(y6*r@Kt+h zT1hYMX6?SFls*#q8-a&P(L$8#e~|zFwWsbsNTlae2g`8ZO9m#8*LRVVYV~yR`=exX*dkjUSYw1dBpieDqf21I_h)YP;$ksD}b9~evWtKaw;4Xarmt%yur zLjL>Lz5@l&j*L>y&*CmM|evydlndnltx$bGc0 zi^$GyaA_MgD2ckX(LO!#XK7j*<-Y~@RNC^<)Ft_~1C8hp3z5z)O&*qE6IphXru~LQbFHyRs8wCuR^{2g)MKM}aH{hzV->@!gClY*y^wOU^{*EcMCZuAh`QX!HD(TxM0 zpEO#ByLEJ7nQ*1C3s-az+)}HxJLF%-zSvU8(hGzvJt2Z@HE@S}bWZjQ!j*R)Cahnzotnw2}5k%TO|O0qpeINVmJKe$;8%giBMnLQ%8G7mc3Mt?T71}m8# zg)2IX>-2w_@*MKKgLPgL!!i{LS#*(xWy#`j@91-XN8!p+M!2Gj2SwBbpJ`= zF78hGTe(9SNtX4HLmofoh1NpW2otX8BDu13cDT!%9!nCgEUASnx=60CeI<9p{l8Wn zBK0pzOd*Rhl6(NGj^TqPKXntsvd|H(=pwnYu5`FDC-3ejTv=}lS9FnFSqeJb(wC0S z93^B~BMMoRkz`p$JLHX<-!O$M%WL6^E|M#2BZnKRf5}=S$eKyGqKo9p+8=JI)%UA* z{>_^0DP8aT)3^i(v-mX+` z1|3fIw=Yi+j@(2FM|6?)D-uadjJJT6DL3kVag=pwnYbKux5s<$LnxU!QV+!>`f zBFS>!?vNK>d2zUq<$hksqKo9p28Y94G_mmj;mQVxa77o%m7NBM+vRemH3rKLM5&NP z8A+BqW{2Ep=(A(Rutu10MHk7H`(lSX{=S4s!j=1G;fgMjEBBiY*L)wU-nZ(AVcDn=uIM7UvO(i;x3n&@ra9TT5pLd1>Zg@7blL22I6r=y78HB3 zDI^@xMcR{FcZb`2VM>&6xS|Vl?S?M9K@R!D?GtVk zvg{HGS#*(xH|AGzFCDL@3s<%mge$s8uIv&xcGJhN^9WaV5riwc>l(W36FKBByY@XK zWZ6FwvgjfWAC0JmM;mYWSh%viAY9Q!a%IoXvD^9A_jd|c_V9%JeW}&maD{)eN8peb z{`SfuAc@>$5>=No zdV|!CS_}b`-I~Y6=EpC%3lN*AYbk1Vlq+5>yE!^1C=Eh>V!j_zvNbx$@f9}X*B)z!r(-CXVs zPgAcsN)pyXjavzOBJ4VQP4(Ey=-diBM@2IUO(vRV1+kTy4y({iMzaphGm)C-MN^Ds zqr^!!E8|pKjb;j(*U)rY9g*I-qM3?jADZJmVk>j4r5w^VD@?*?7EK*Lt_8CzJeS4Wx+Xf2YaLh`xZFH(36+ZgBo|JTv@OUlVYE^sC+tsXVqg4ORW_;--)Lw#r1LMHoL8fc% zGAQPL`uU#_V}fFnUS7^Fu8 znOK5ardCbkPLfXW;=1T8Lt2%USRbr-E!9fw4%9R%YEswcsEY-z_@WrplGs>K5?cl2 zUctf!VWf*&iDt>F#iQ>CRtFjKE#&S>tAW2SSQC`-p%!=#n4;#bkM3khgO%jOrxD&z z%dwKff=`q7`t$neq{gC!}rLMcS=a1SvIX#$rh|Z{_jC+W8Vg(uhYt z7oAj^6*kZeWU$h*!Jt-;;;GBFSimwQ56SE%t!rHjNc^OV+7K?k*2IzAaz|?Astq^- ze_L=0mxz9l(QNN4HiQI*TKZfWN@bpbw*6z#!NatO4E#HUzta9l!$cMz9CC z0K5r&AM6QwY3jYeE}*oXt{@M~LJxs`!GmBw&_hQ0yS-YdGme33?uO`ThIE0SH&80W zAxQC#0AsRGr=;SL?9wms{u6C65Bx`sS!N(*w=pbb#jRb92p)_C3e z05xN#rWwN#$%&M&}SXuG%mrq@!TF#mq|t8Dj03EvauNcd^no&CFBt8A@h z{-Ok@+3quwqA*|Kj#vE}y4`BTT5nX!05)Jqne{6wE}1fI>^M!vO-c3uHE*rA7D-*c z)|+@8vt-&GGbKtLm@3!;+SdH5bU#9 zMeDqYTyi$7>+DURHgRgn?Y2D`mw!OndxX#`fv{K?#EY{U^-c;vLAJ4g=REYfRA;s~l@t zEPaE;O4;yV`JOg&qE(J8$w^Uf)YlcDRBbUTxm>zMnP(eX4pZeE^2MqB8@zFu9Y$8B zHbHn1Eu@$VkX*<>I6z(f?-V%oBP0F*mG!*0LGV+t$0OI;;qOmkwk4#!Xz$5x3~o4<572(Of~)RY&!8QyF-H;mO) z>1lULN(uA$3C6eD41okzbY>aa2C1Vj(xwKfi#7x|T0ZH%rZmt&s=pmF<9<(~PckYA z9Hf?P^fnH@5;i8qB3*5eI7vWXrtNVVGJ%>af1 zu|I^lQa6T5KjuqRt2TM#f{C};X_jyqt_P{To4h?K$k>-C$QERE(0JAQC2t*b(0G`t z_ZPmJ>gOiWK{e|OUlmn4(-SM_EVNscH9}3_?Q!e3C@YK7r*Ba*K$&9s7DYB|nNl#f zC>fqi>CO-&G}>}9I3=pkX8Oo2YT;%&z+Sl~DoLH-E$Y?H-VWZSF;aX~*=DMYGbkSa zM4P9UjHAjrZSe+!PLR~QSRbs4wov?o)x0ef&R{j=Yq!8w+qc~Iow0p~@u|42-k4xP z*svr(@-tZJ-?$T#21m4b`jnME$=G0(jT*B(zHxW(?yO=b^VO{+lljZD!b#?VaZEnO zHj?QCNiyXELsb8dJgMr^abJSkGt!Jvb58oARqYe}x2Jtnj6OulmO@H*Md7BUq^7vp zd3%acgFd09OtK5YX*ENn)no))Mg&Vs86qtu(WK4d%-&8(ua00yeGXAY+i6Qf)ZFdf zzBGr!+i4E1$iuwJ>i6y5ronlW?JG&brD}%C%$2C-Y&WCyp^~s#YWfauql)gedIttt zV<5L!9o#|3%q^}oAdBE(N`ILO8m7_#= zy)To-Vd~_|Fg326tjt>HjZqsL zx}wxmKdk2 zH+03T;+CcrUZgFm-09 zb;)@|HDv@JrjlOu_H2|zwaJZ4N3D@HL?x$4G@cqr35I_+z-cyJJ^HG*e$qK^W<=L) zdSw+$f`>~L*D@u2!=;*QnPP6ZHFTJ?Vw_uNG89SyN`mmpIDrf26sk=ht{&M%5{Ikj zfuyrsM^1>14qr#=Sduhc>bL4<-QgANmw2EWwEy-`JbhGfUEth<~#LkpTA77=0id*S+2lsQ8wa|rXsa1!~ z-kNIk5SK4WQsQQXG6DT2MwY|j=rz^6&GfVyd%SUK=VouLYPH83ua8tcXxjiyH_?<4 zbR?B%g)FBPr?kh?SS$@kv*ivuA<};&jU&}jOr&tHsudzF2|5}3d~}#mXuu zoeA1>XJs8pn;5A&?Dcm4Uw!0k8ajTPY_R@sM`@(rrC!?Wt&?&Bb6e7EefnLtNon^& z9HoBbs`@B3ucpB;`iZj_swFuGLmWZZp1o(P8fv zmut}Y@{UKmEp&smfI6<5Novti?+Mq6iRF_%^1h<`>?uswcB%AFV;I9f@t$+#7MIum z)cb)^^Aef0$1lBNoa;c^&bi71UwBvOJw}k&p|laXLmm!_e=Il(oC|WkHB=T3UkM6t zGk7cEFN1JHavExaN;&TRuPkiZASkkJegR;1v2}&W~4oXp# zfO+5@plpZS2^N8~z$xI};7o81crQrGLXUu@;0kaaC{6S}@MUm5xF38FjMbW{Cr)~A z^w~XF*T$+dC%y5di_pm!{wP==|u{0X|ItpKZo zQX+C|zY0HH!wT;h#_r%6!ux<5KvquL3*i6gJl@-gV-*3LKsj>#68JhO2KRy6@qYpC z0562Ye+m2l245k(3iZ1aYyiFrW`e?R0g4?tezzAtdkNZG-~ezxILbve2toE2-XWj} z6#p3TT@`!EJ5KMQZa?L1<+HoBu5D8Kv+np|oH}@@4aM*|k@CP}U;%g>lx}?j915NU z$AVvh_kgFshrzGGGEjC6*MZ-IFM>Z9s`hDbJ45>O=47*n$4yGk-&Ov?X>YX4u)5w; zwEZJrdmFZr!(#H2r?&E2fSiMV1xcVWHbJ@~g$PYZdkWd2@;TnypDiib_0eV_i;*43 zA>=&bHrZxJ@{kco39<~?fgD3FAW<~qG^8ss0x41HKG&%w{koQQHqyMO8AdKNamj$x zL2dCH9@TVWR82L%syo4R23;Uat*Gj5Y6P-e>ciTuzESo7blRor$GhuzzJ@Zbsp=E& zuI&P+#=9@E=Q6FftD2gX;7*A72K@_7UDnNnx_T*)s5U3K8*t1{mReuC)K>`@ISXk^ zQ{}1VZXMhbCOboNJ(a!EonINDtQrx%CBnx|)f?5^ZNej)q=SFfo}bk1g(fOc-QC9( z$SNOI-F=I0Ol#^=n=`#sN1}U(>xHJOQ4M!%pM5o5%TP<6Vw+%24R^BfG0dM^!we1f zyVcGb?i!ut(4+k16rcQ>Ba0}?wa9MdG$My6W2oi2NC8raEJijUdpLjoQ&}-9>-TPs zi}9{EHP62fxmAPTje3SS`u=V_L9wNt)T^n>zZ(hO=U`ky5&wsg8_xTBQ{D21QOCOh zmFuuumHuILs#Lurs^?L~p!)ebRqM;BUO-h7)#%GcN)U%tAyUTlO5QwJy^wY4hRa4w za8g(&bG2mk5mnUB>=0$oaHJvnPoqxoMXWs%CTau5mE56||_NNh{>i8F`mr$KWHU2LWio;5%vlx2Req6Bl6Q5h{>Ev_kkE*SI z8L7b0zl;olzl{#z7D`&%{cY4~uo;6>Kd|j+11A=jkSST}NS8T_+=d^$n*5+YNiF-^ zh|?bvYpEtZQ^R?k#p+i`;ub7^LX1vVjC4aB&E96aa?TZ_MdhVm5#m;eNguk^sVhdy z$`Yt~71cIWjZxh*GO`5j6V-N9?NQ0YsBr6+2II8ux+Lr0htyX;7&TSgKSrD(?PQwA zm!zh5VQZy8f~0*s*2R~q?*7M!Hl#^dgjN3-$%eFoH~%qSbv<%e)jsI2uU1_%+&(Ib zlGe2r>gX(PZT4I<@(igVd2F&Y*_~%l6-!6E=Nc5%(o^oCR=#s}_c%i`*ta{E->pNF zJY6%4rF_#k+q{ z&1di~61&A!0-4@hV0cAQCEz?N8>BW>31oN&qp5->;z8jc6^uhO1WhkAFV1vV#+fae zp=bu6SrZpX&%|N1Xla2vXkl)~dD&%K5Ds^Sy#;E<*K9Y8z3gfl-p&}L+6J*U3~Rfv zCXc(q+hc>&YS9cwQ~Pa7{cv=r3Qe#o8fFGhA2hjD12=?QloUc_i_-S1QRlhWkK4tV zx1nkv#*hN|uq_SyNYy~HVP(2%V4SO0m^eK?5a+XVqif?;(Oee9%i;qId?e0lNn`Dn zl$Q|5^N}nota|-dvC7IdGe)8dMLY7~<%8w>w*{ddd~2(w?KgEWR@~ zMy;wI*hl5}z0qLWN(?02*q&IIZ?m6OYE8$KOk*i0RmN?pb_tP{o1>TTRfNfcM^<|E z$J_C0tD_D5@w{FZXcw-+Tve|I)zJat>&Ba^Z;guPm8%{RO-D4}qA9Nt=-`u-OBJW6z! zu39eY?x-I`{cZ|<7>AVrXNugSYt~drTC@o?6lYr9qJp&pscL5ve~fBhJCLAnQT=O^ zo=xHS!eb4`I&UGoq)0Q<2$oHifTi9`EF%9Pk+UY*7ndoK6$g>iQvNX z;+?%FPMvITHqnKMu*7C=N)4n23&Q3kFR~;f&1r#nbs;qn7n~8Hi*vn@p`+)y1^Hjp1#|T-6~xkP*`Z zo0*&=lj>EytH;$)^V0)ySx%6%4A}O6n3W7jv~6l{dZ2BES-lQPy$Q2-7MrSZ9g>RU zx}#NH9?`7;8UnK;7sj9^`gsTh%p`Kcn@ zUP$#<`EiD`g`TTcXJDuohN@06)%zKNd_x>n>ISL>lc(4go$T&Vt?CByE4tgivVUHy0+*Qu_iB)d%dVyXBqgQ!py+EvP$WZiH z{lHv9MxH7S0z(ZMW~?Xg^BV->3>jK1-xl%7aB}LrFGZbhz$76<$j=P|o2-FiWkcf9 z#}$qwm5|B6Z}(MQYom@HWmz#jGcespH?vanpmi=mUC9irGU!s}D;ov=bQ#j5p2@-@ zm9Ba=4Xie#=6-G(SZGL*-_wi`DXG-vfu%l5z%n&n1t)Xt=1B9voKiXVE5D}@IVaK( z$wLMr#mIbQ8L|U8gq%gLAT_AB=14DOEHVdq64`+4LFD1jc_fNHnTE7S1|rju1;|=t zcRU&B(w9HgA7E9k+sNf>J>_U*x2VGIJkhiy&OS7<<_SNum!vzZ2e}uL)Ng)-d)>If z{$zuMs%C@ztqf8l4(m=T*^uk59PH0D^bVZr8Gts=kE6fg^^i8aEbZ0Xt z1{bRZryyDRqciLJ8wXWHuuNe@scTs+s!O|nJ3>o8M!U4Gzb|F?En2UavfFYq16w_R zW)R19_Lob6vC$he-1>60HN^U1xfB}DZ|afh<;p6C<(0)?g~Y2XbW*fdrqb$@sSm@3 zolGsaGc~Y2nYw8}R<)TaLlZB!%MJ6%sjD)g)(q5Ixv#Yd#s|lG2 zHXt)><#@Ia;H+DNi1s)eO*J2ycfwY*+sBpU&zg9<7C8X8)ETi54etvq_#67ugE*|> za27HvRELIsXYO>VxebZnCqlJ>rg}~y;IJY%kIYx9c|VYqOAY&D6w8_=FjxuuoI}x zG>T487n}LBD-xC29CkI>2VoCr4jYHXuCB7T@oeA_kF~GM#$kz3ofv)iD#IVm$p(&! zRLLl~Ug_V<)8BWf{~_6oSL^l4@oGxZENi@ycCcQ}&1Sq>UvUQ2t+r(Q-6@g$yQa;Y zJaOuHD~|Nc_3Ee{=f`Y+;&ql~;*u671Jrtz(!!s3ouQJ^mCt--lv=O)x3Dfgr3G!V z9yjmOM5Pj?rLR{EZSiVL3r3;!>eUwhd~dmRsKKT5mJ|RV$M8%TWzW{(6VNi_IdgI` zCYbLqscSV=@CZw<#V!3q44LKr)6zfA$E0Q{qtwx*@+3RQA7?O&m6zuDSrIbDlt0$W z|D(%bz$`Cq<9}W^WY|fq%M{awFj)HEh?s?f4`5$ZY3&4&Df*ItMeU+D$U&A$=}}4dXd~tK=lLIS8&Yc1YD6cg zx;OfhOXdAg`E5ZO(tYxfAxJSYA6bR$L=GWm5smHp8b}+YA5x6WN0uQwkR!-BMB^!X z4I~HYg-k#=oNFBy*#aIx&c$oFS`_EF(vUo42vUM9LN+4%k+aAZB#l!6ZIFRTF*3iJ z`s-!AzPB$8A!*xnYZp$gzoKV&`=J?vCiM+Al~-|KGKi1zwU;T<{@+qX9eku z1^ERW(=MqKh*QO5S+X=Q$G&rjePlT%`OJ#v(C7mZN5DQEH#H<)uKf_lEOJGZ>~YkFD5f!7neA>RafE}TDh>(27EhidgY zHQ5u*!)QjouBQZXSlMv)9`~yLhs{)dFH>8^bkIZnCh>X^?-%0HsM3QtD&ol`xzB!8 zV4wY}z&`s`0ifblfqnL?0{c|us{;F!^{T)=WxXnZg%4PdEtZ!E_Nf{2_5ktU)N28o zY&h_yo`G+5JPX}Dx>LZB&9E*>k&@}ON6$1Q`_?VU{5^WI&(5jNqhISrc=sN?mm%5l z@6|VDIxR7c_`D^;qb(`l&kYi@(}zv9t+_2=z#1@dfU z;Dm8g#-Wi-FDWH??k;>dvKN`JF6`1xmG!BsiaIjf-&{VLq`6&Io2%Ygx+_0Mi;CY< z*ze}p&!0ZMc(!$gfzx2fHO_(qi6?R3sh;Pfl2xab?v~m16fNnKw&e4l|I*$VxdwjN4e(m8dLmHv~ErKtz zKWU#!+QlRfk*$Pn;;4+&l8gZ|(2#bA5=TNM?O#Vw*eWt>6K-`y11fA>J{zxVbt@ba{1*!m&H~-C=*O)P->(rm=1OW8-m?Ixp*&7(kI6Xh-3Nt zfJmqi><6-yYU!uTOYb)ma328!!6(66z-PjQRp1Ex+rUxatKevG4_FAk2Nr=xK)K+j z;28YhgX6%Tz}vvz!13T!Z~|!RHa}V~S_RL}(#+2gv=rm4Fpt|3>gm!sTR#=-&zJKLeTLLqCFdgHfflB@Rl2GQc@tM{q7U z6ucLdb4#Q#^cXk~d;z=3IhU~(RNy*rCAc1Z4wMMei8tVX1AGDG z*_ZYrDCamff}en!K>5&}@Xvso@&5{L1^)tRMuLfQP`>z{B8M;0K_5rcZKq1f<1><5I{^w&;H zj=-G79|FGvlv=gVZ>qylZm)`a*PX1|4`;7JEzIs6%7TH-XmZ;e|+&+}3|H<*y0$$GX$t-@q^wHjxZ~80R=(um9}ySTE$*3C zz8jP57eS@KoYi#!N-48Wt$n=>DTT*c`!*S5P<6V&muW~YCg0#&ZE$f_rHyZO3wc#t zehrac)I%XM3t5b8Kn@{i5qVHq1IbI;nqONlyAYe^XEO5JcV)_K3BSdF_F%Nx3IKC(Gk zhB)557+WnEJaPR^3D1#Iqn+nS#VYfcSW1{md_2rku~p(~S+7Qi_hgFIYB=6$Sbyz= zOTGU~th1d|tb)Iy;e?XsLo~U+R=j~+tmcY_!;c>Qq)R>bYsEXm#p+wp%s_JjO_fWr znLZp=lW3>5Dml+N(Ws|pUyAkXpQ)|CxRTV0OR-JDO`=#Gy+m|QQ+hJKa;d*BMIHd4kGSf( z-?6}1O;6$}&awR-n`MaO+V8PFD-zcK4=5bt^z=qk`YoGui~op?F~mp3-cNN}$J*Ll zj!p2~1#R*vPU*V4h98MYM5ht58qlOYY`z>j)R0>5bSLL!>;4(rP^z`O@1L>Ry3ejJ zUCUJS{)$OZ%m0dPX-NH?N~FZj{}r2TNS*lqjveZw3dpRkWvl+*`l_q@|BlTzr10OL z1@*|^v3Z7+<>tjvNvg>ed{TbXuEe(T*`=g&RC>l$4#Drg63aU*gseh# zB1e#ONK`FNOGEOIA;>IbF|rdmf?P)8lIej+Ub1FrW0U2UzrLB~eT}#Jza7Rol<(+A z?dzK{hWNNwAE`Fr3$|pUmf=9wzLHey8Ec|CQQvIs+_g7sU?zBXW2a!aTXkt**2}~Z zj${Of5PKCOgY?Z6;St81j`o`Raa(kvI^V#I@xG3=LaaqR5R-&Dwa+}SNiusjG&dP? z)xR5><9tNms=8KH_0RDnsJWSDtvd2OKKV(3&ms3uA{&wS5P37<5(Uw%Y@jF2`vUeC z4(80#Ku?Mxj)*y-hOad*6v-{4b$;cZu_)zAM+^_Qq#Le*@DTV;IYcMc?C@V1XoZALW;)ngy=gaAjlaP2~TTxAE?xIsxL*g4OOF|Ze@JpcMd*c@TN~tZAVpr>eMHZ z244{sr)53&{4Z6VPf@*$Y8k53&mviSp*MfEDG9;kl(%%ASVVHXmEA-lX+KIduD0M+4h9tsZN6~V~zD*K$syNIla z{O0FG#_|7;9Nu%1CgU_onH8ngFeV_V*jby6PQns{}g3tkND#c=@tNsW5N%5U4-utIYEX5exWc%Ypm%8YCoaj>W%;ZVxNePz1wtRc=g^N|! z`q+s-f1JeIrBxBu{)9iLm33=Ri7Y^3QZ!9oziET?LdGJqkj2PaWH)jQxuE{%Jy+uv z38|bfL<$gjb!86nB(ep04>^lmL29HiE+W0smgN6a)`p=hkLvhgjiDN}F;fh2OiOk3 zR;SBiV#-&wG2JdbQ+CgIS*)Gu#_c@FRi|yg^-%K2UZ1-xmvJv{tw9mln+^bTNJ_3* zi)d|g*|^J8LjjL>osiVjdAvRJWUg5wsMg!DWVGadf>^KTni;`wB7#|b6MT_iv*f*eZ8Y;WJnHucRTL5y+`o#8Hw4(NA11`3(y_o@QYHtp8)}hHA7Rgyo6N+4@k$SxY$-5E}%xxaQ7bAluGqQSY zr0R7vd#bbh^f<-cPJ)+vI?tjP4F*NCn%dIQtl?VpqH6lKr=~jF(QM%|N2$~DX_+RS z;C6xQ+i0lnoy;r~2N_>}KMxX@<(tlOIZqwvWM;&4g}FiqTv8nkvX+g{GlQlT^nb*e zokyG-iSwruCs>s@Z%G_0s4`APirVCx2{GM>b0@D^Sl8)am5<#_%O{Q%R2e6{cF9wp z=9?T+BhJxHhPsw-W|}zu&s@yy43ljqPqmi}^;~C|IQ~y&y)H2MOoeA1%)VXB%vc;1 zm1wFN3u0=iEj^4VRkDBuOxjU*jP1&+a1|bPN2N?)a%~=CZ*7m_MI6bJGhsJT>0PPg zyLfTL2^MUk26Z)4vmOiwON)>?ZlY_}G>=oebKK0^|Su5d)ZJuyP3{1I!`STO>Z<+Uoq6??i@Ke(v234&$1poh;OO$o zYe{)zDPI8w9t#IM<&ni}%#0LSYNQRbg;b08aKyS?MY?vD+DdS2kBHzXb#c2{tE`9F zgksF63_TBLuDsa$xxmCr{azMJhcgqmyecs7QJey&wH5l3~^lRVOFcUIl?Yi z)0*n)je)NAs`eG#gY}6w5%VqXNvgkQD1T2gS#7?_Y+O-OXGFap^*~$Qnn!MFCL8*j zhHCs8OZYu~%o@hG_=bz`O0F5D3Jd*>oFdKYOU7;{V<~$KHMlPs!(nC2IsA~V^3NHy ztZyMmx5-vp`;wG;5iCh^wj5bXQl5Th_2Brh&S{$2(v=fairLec&Vn`$y1{!~PP>x+ zn{A(>$W!b3k)8phr}|z)eb~>;kHuk8+i6+BmMW#c*-3AqM)o%wB=ISPicUXsT#404 z#aIiqyuX*fBYv*D1ZuJ)&CzD?`s5jLn&s>_DM&1PjkzT;-D&Q_miAXi^`Gpz+j zMK!lj=~MVf!;x3?D7~dRQ;a(l$4mb?N|*3e;%;Sg_K3T+?VjF%haETA?#1G6W4lk+ ziSncxLAfCsQHO5;M=^ATuO@wxjA%LP=m7d;j{0!`1(*|&-`h)Oj^hI(JR-0Mxg3=~ zkO@9VW(*M&n8FBu$7P8 zVkRaJO9)oT9-bF!*j| z0&82rs|Q;Nlt<@gnjMlBm8dQZW)+vCu#u=@hA=$$kBCV#z~GNV%na3Qh#3_ui_m3Q zI zQTYbPIL{aIeULWlw?eWJ$BVbl@Gk|{Mr9Y#!`i4GMJzh9BeV>PXy+9%G<1mwmNBZ0 z+FFFIE+1Cfl2NIR`mxBY%y#yz#Ov;IE=CAA#bu8a+fDY z9a`=Rs1I&6n^ZJ{xG^*WK9}ZMN94w1A{xORV=&7H)I9sptQMUdRsz&aeZOy5Ax%uGpsl?sE#kX1MyyG^iamGh>bTQ3?5-3}5qe-+?yrR$`_+*4u zriHdjA5W8bE+SZ_1gvLH z)14Gq^0(b?&r&jJv{kVaxbFV2B}uGo(X~|SrKYk>R9TG z;NXa087pR|oCacJoxqBoaHC#2)&LyWB}MWE>R@ zSvn{0LCJDfnn|wRjzcoA(Vdt~t9vf2 zlbVp6=c=odsh~X(Q6%TNDy!HWppJcO#Hq!_bm~HKT>F@zUM%K57YB2|*4}If3_EOA z=Woc(kYi5m?ZtcZOD?y#t1{5Wt@JntTB+wL6kQR9TwfTfe2VFuq{>sjiH1kSp89A~ zr&6dmDhieKXdUd6R2{67RL)}j^{GS~L$uCcau+w%%+ADNMU(7Fw2l!ac>ArDqd`ZN zKaC2%DS|E~)zR*s)7wSWcP)*vw>93IM)t>Y5%=-%7RcpkX5|c-HJvn!Lmi7+zD1&T zOeex^gfu4P!|7&L5JyF3q_R4xy+=79-^p$rg^$xZI;qtrM^o)XZsXL_8CX5QY})cW zIswN&!p}xz@5|YWyi7&O_LqOAnOWM2FDayBx-U--WC7D3%mQx)TY@}DvA)zW2<(Gj zj#n%Khk%cR!$1X&0GETKz%^hY_zp^>&t986$Jot;8O_+$oMdl`hQD8Ax z8gua4O;L!u~E{{V;F_;c}c}CO8``0UrS6_{9H!vp~-6XtTln;N9St;631v za(-hjjz0;w7nC>7=Yf9kJ}?e^0IUl>1U3d2f`h?_!8<`pBQzI$6nqJM0(=d865J0y z4Sond1AYloN+G_UV4Z5XAm=xpCE#~Za(o$Fi~p}MN?#LyA}IPKa6SG;;B#O<@OkhS za1%HSlv4|Q<3vu>hIWEmLGBc_9U$|A_A+=4EC);Fgw#$PaxUXlFb~`XGE!Nm6sCi3 z;C}*q6I=`K0pA7pg2%vp;NRd|U<_l-ey|z%Hkb#}4nkwV_dq$-Z~%N9gikG#W7*HhZ?h1){L zSiuot90=Zkf2exqPIHRS-fq=-H&$MZ>p>H@j!zjNyVDv+h(h&2FW3Q;%IyLA@Y4mf zXmAPW2cHe=UjhSa%3WqlAKR*o47xVgI^^57Dy$f^@gO&nS^}62Rs*|()xnWqA~+r7 z(=(wtV3PXnE;cr-{Z_0kwO%6cPxq6TytFj1I#>rx0qcSpV0}>TNa&WK&LF3qthBQ^ z7#fDZDM)wLIQ?WD$!f0V-OZiWmRV+k&)&J!`F5AQj+oC)qjjm)pj@gAD3_wATbJTn zOxC3skF87Pfl^GJLAg{Hl|Gx<%--9T;#mC;htj&El??O%#VW_HtV3u0z)bv7*ph*p z@iz(kn}UPzw*?1-dEij68^}jLLj%Ckpj@>Glnjmor5JAmWBKfHtd@;5Q2&{2w)NS2 z#}zr91V_?T3`&}&f|AqepcLv%P|{QaN}=8fN=|2ia?RONh|PS~rZQF4)voxtXvJzN zC|2izV)cGdtTGZ>Rv!Xe;OD?us0;Y8GVh_{t&L}_Emm7SuK3bN(FV~j29v-iKxwQ? z!Db+b2t%E~r$K2}E5MsUDbIo6D*Q|omVYp~2LG+#I&dQR95@Yp9=r>D5oFkvZ=Ho6 zlLL~Q)!}>0zJ_dfr_M2xN_iz%4hd;5gK{5T4(5Wdg6%=h$6252ehZWfGQfw5KuORT z@E!bP!~WaA_wX}OXa_*Xd5zCLTc3nF1TMq>0k{$T5PU^uCo#nEs2wGM;nBhapoG5< zeoQ!{l;uAGevbcF@C#68HQ~9z6ZmU^UxCiyK)Q?k70?i?HSIf4W;5ZB0MFqcDYKIV z(CoAy2$%-`8>AYv|A23TKZ9IM`vruf{R;jG{sz`_F_M8f;9p=K$Ty%ueZi~XaPS{+ z5~#bh(4(LW^cr&hSqoXSh$P@X0$4tT?hoUmpoA|5qX>Tnj0V~H*J41{U|InD3l!cJ zkf}73&LmM4>6_RwmuGq?qm3-XSJ)(!vbV0ZA% zaQI%ZCw@NC4=?eb(0&}f2>1l-1AYefFYi%mD&5B;6#A~tgSYf+^xi?JWh}S_l)gR$ z>{^BS7hWlAaJ)h<_1S1hQDsZUb2>XcNFsK$?kl61Es*DzM@) z6=>7&H_-X^ix|ozV7hu>o;kqaIga(2x>8n2eC;{fdc2&5o`*M9x@8EJpA1~gSk~`u zxYFbA0cA#GWhHOzX!F3j;C-MB)pD)o;C%ct(}}+&$cNgkOp8Ac|3a5`ODI1~=mIW+ z&?oHg2h!+6{lk74J&t$}R z-&yB^AA<~A+Gil6k#-DpxfrUxz#$9f;~>3PI|()gIVTpPGij$l`igc2q%UZEm@Gt_ z)XsvF!SBFX;J-ntT{{mx0R9Lr2Y&)z1b+r84f%`OA+9BVRXcQ&#;pB;1EuyS$ax$q zhccF3#qSGa&2V@!_yOS!!v0pE&b`nLVZ1pUJ`m)i(GQq^8$4=LRT83Vra?;$*FZYx z$6qJxmnIschCayV4iDR`R{pR`|AyX~088%MYk(Ob39;G>39+WK6tFkpsi4gFauw+y z=^*zoS{-m9m;si7bwTa`w0htUus--UNQOcmfepcLz)bLh+|O~#U^SS=V1RmS0;Yml zpiD(g!46<^a3t6glpCuYkVS~r7G#-WmFj#jSB-nfyx+$oLMxjct#|#B`oNMws4rL# z6Zu~L;%>iW%c`vvIoCiJ+GKYp<1LuQZfe(Uz z$P!~A4(YG|0%bU5a<%GX2{;h{6QHaB%0QNJ@?F9Z3oq?ya2Lqr8`=ZPCngVqt3cK- z)+Z!2dc!*WUT{5_1U?V;1z!Y*OTXQSL*5gRoG?^toAKWj_Rj{l;b&B|J`wp8$mnhL zNA4{{j7HjSa1Zzv_#Vh3q!5FJ_BP1ipz$0d^aFSRyackf9ir81?Bj+S$&D&ErJ>d! zn~Wif*GdS*tFer*mLSJKa&3i^YwN3#%Ru>BWI1>m+#A-D2{MD` zkBns_EXZ-cSS=k%)l|QKnHPNavsj%!+sx-s6H487lc){KVmj5W&6nk_6i^Sa9^p5E z4M6Ft4MAC5ihcsv*sVSAKVS>uy$iNM{{h$zJP8U!Or+)s1J6<@q1Wt z8SJipTx1UR*-vP7UcHfb=Q245VNI1h;3h@P1Hw=L4XOVh@6!fe(RS zgS_Pt`VssW_&2x&jG>XUEfGormxA@cGB6udpbTbDfjz*dL0Mlv1C9rmxl2hQj^zZ* z23LUG{>a~d46O#A1vi0f!B@fcp!6~+k+(t4_F27*W1iM}Tf$jeYb;$u9vV3ZIj!%k zZUbxK=MbdTsa^p?_{*h{u@=!@1s?-|CCvL+8@gI|N)sDJGn z9K#9t7Q7Yw4x9{r50-%EK-!1)1NbobACP*NudasHfIop7!3*Ha;4f}%;jJdqJ$^oh zrCkGMyGb|g^|%X^muTFeG8yW-uDREX>)4*e*ioV z#(_VBJpBv(4NBc#1*_rb;~H8bSOcsI)&Y~iOpv>c5Z~>w_&KFGxb3iBmZ=T$;Vq3< zh^&39G_VkV9k2w<0Hv$Tg=F8V0shB9ZdXFf!MfmcU}NwlunD*W6#lCquOfwh1Dk_a zz-+M8Ltk%!BOVlD4Ul)0LUq6!zKNRGhrVxJ#O+J1bx(mz) z7lieXfH&fQ3hV~10l9q&?Eni*`v2QFdJynEcoTRH>;*yJwwp`_L zPzLuWzzpz7P;RxBf~`OW-UvPg&IhGvWJS6RzpQYUgR)1m3VbK5e?RO$3O-BtcmI#E ze*w_3`2YX$`@ZhIulv4k_pZI|I_$|F9d?~hC8>5xAuE(hQY=d<&bbKSNrckB|&yY5$jy%W%)|rZB+GMJXODk!zv~QpvAU1=IX9d@_;0f0{ot zcb(t!xa2ou)g=fz5b+-8#dab3_N=|vb4(5Ug3ZFWpe7l+6-g|f?MTU3-sMYLBX=UN zLh??p`xCp7GJN(8asYB4atQJO@;T&TJ7hhTHp8E7u{J;#<22>{PfQ|v^XRckzCzT`1Sb^D@Yft`uMY5fQmE$S zZ!oA&-7J4>&n8W;hb`E2m%kNKy7-qMB^{R{>mV;fHbpY!pnoT(9Q2Su0rD37uR-34 zWXhrBE@XS;NMr|-TJ2FT`0!B=E3!+Wey%0|r2Equ_ex|J^BR+mLOLw^x&ZW9+d%P?IG{#G$JJvk$sWVk^PWw zAO|3qAn!rS4><^V961=tNTTOHBqNBPp~xUvHXNCc{15U5C zL#tNuG#9j1C9{!_Bc&JfB=TM41f;w(@X2Qh0~4O-kY6DAj9gEO(W;g3p6{80c_3b_c`7WqE%8srDa>yS&49gwS#osg@MEJYaWS;xg)c&ta> zkKBMPL2g7&L~cgDie#FpWFB%mlD?d0Cz3v!=PM+AG|z4%T`kWyNP0e=y-0dEp8ZIA zIQoVR3ie^#Nys0NsnV-q-b#NX{3DVoTq{mR9>Yx)uH7#okKSB>O$f`(rsfkB6L{>w#L?$BJAgd$uku{Ll zA!`PB7CUf}ghy9o3Q`{4RAet?8nQ34HnJF*fs|L49HhLm$n89ctc&}hsC**o{}i$w z{!b%wk^eEFngyX zD2V!ZL-yeCD*t_!Uiv|4IAovO+6!&@neRZ#&v+;DCS)JvC}a`xWn_QkT;u?xWa3@O zHORY>G;yALko%C5iUUYGqq?ON_jkBCa+ep_rnJ;T#T9f^A=s1l=A%fx<c z8aW0z5h;m(9w|d~oK2ty*8hu?#J+$$jC>JE-g~AZCF|)ym-vbJC1e0O16hM@#q?cE zyD=LNc?*`iPC>q=Ccojo-6yMCPP{=v-+(tU^d>ThdiQ^O0?lZzJVd z5xt&KDGlj6xF1I@Ku$$2LP`;T54j8}_EsS2;_G%!+^b|>?*ldAO@9|7<{NeAY$Lh$ zNAQx4rN~%Mql!LM2mE5cQ43Q2*9Q&+c%S*kSJv+>|KWg7ma}wv*S~J;(E8}`H=wyK z`*6F(8BCLcNuU(01xElwJf0lT78HZgU=COY4uG>DHH$|T^Z-M_Brq530jEJ~HazGK z24z#fkLO}0*a!{*4;fbrct_qux2?;W`417x|*G_Vk?2gg7Rxsw4}gYIAumr8?3cy^YPIO>y$O=Zzs?eRR?I-*a60f zihB*-<+|6=ZpTR+Xcm5sW`7+7~~vNUV_Nu}D0-(VDPW)w3F9EU@bTag3X8=6oNrue6w~$ z&c!mY2b>0pJo61fS1=Gv1arW8Z~(;crkx5}fKgP%p2Gemwn?PhHo*pJmdYG@_|I7I+^v>2^4E>^Fgf9*%21hAW$|hzpPL=%#!AVM*hytmQ9m1> zMipyBmoJ7?vvl?v>DAaDw%SFxEcI$tR&%!fj-{C=@3w+!W@CR-iFR{iqCG*h>+e=) z8v8Gatan8#(O0n(UPU5IQKOpp!~Wf(qL#{ndPuWjD0&KW$XItL*C*e#2{UyZc(=LHzf$@(;hdWd>pS%i}kcKgx&a zDXwRO55XRA8U*P%WPp6o1B?Qbz_OO|yMODQ`m@0q)hntbhG{X)))9NZ3f1U)_C~*U zMU{kz<5fGFZBMWQmm{d*k`=zC8|%@XS~LcsweDI8vXiG zpYdwyOMS*`z*cZhe#JNkQ2Q-gfn#sg?3GpWqKAR-PE?U|htOypQQxkt@>8`(d9LIy z2zGF5=UXl+$ns8I?PX^M?rF(bGI)(QMP0qxTR*zXz&W29zS^4=SO&k|;g?*%e=q!U z_^)mLn&>J~UXUtMA^iX`|Lz)Zk{Z9pTi++fa25C@l=cp<_14cCPAe&YwLl`{L~TKL zFd9q&%UUfenD3ohJCtG0!v2J?s#`l$+czQ1s@O5%G!_1slf;MC4)x?2(%UB-s2xf) zXQMhPtj?jDJBi{Ws<-RPl)Z^))Z1Yv@d=*v;(nEQf zUsdS)BI~gcZ_vdc+z*bwIyHrz)k<$Qn@5*z&r;WBVB|H7w2M_kGD3NgcCnSuB&FJO zP!0Qq0}BxxS?-sTa8OO=B+sdtp?K@=sB*GeHJ)|r4KqWj*2<_~4RuibiZesCBA3NE zcWAG?KB%6}WQQ4hbDddgTPBHkokZ-5Q|B^6btC(t`ciNuXTDVjH?RZHx2juKNQB<} zPrg-G6SG2L%TcePBF_`$;;c~f0H3`RaF#lrh3z@mPOhqIWQX#s7w4YNB(_#ZA1Eg9&CR zO}6I$GAEQ3IUP0OJeqY>!H9sfGx99etq%Hcp`Q`29;y>+9WDE_d}_=&ZwV{fZ5YGxRA7W&@T2hz7GBV!zNqi9*0ItP@ zTaz3c@A&^qVd-2CBh0Is^W)Wj>bb0cAVev|&Um%2UZ`&7PR9yG`ZSi?hU{wYxZ_`G z-CndlOAV`!jd!q-6H(LayNvG^VgW>>h%$0Rb*)B`XwucH$^3%tazl-y3&dxs2Xj$= z7v;Mm>b2ZZR_0xfGAUVHg&GFj!+lox+eXgjQfBO0ewJ#MhmnOCIU7+u^Fp;FXQM{s z*W#h_999P#QVsYD`v6G@~9p=wht*L%Prt!T;ZSEJU zK}#O0eBPdI9Lf$X#?YJupISM}a!!kwrB1<^%+H%k6I61OkaIMj)Vof*ER893@Q}Y_ zIAX8~^^sk>dYNR_CrB-85_-zAYf7(dg4u!1srxhy%{JP_mKn`L^SuU@(1PZnF$NVz z;})T%22cG@NXvd?y?pSmPZ}w285-)#i1(@IYjcEEVXII}>r!31y`FS?U+9^wLiq*{ z;=Wd)o(9idn@d7dee(%%)jez=eC(1?p~3Ug=F-ptgEB8~jw+@#DYnbEm(OhU4##a< zhl(w`xXR2*w|D8~ENdMqH7K2NZ9?4UWud1GN)nFOEc*xbdWPG#yRi+oYyS}9r#I>z zdU>daPx7|+TcqRA<)Qip`5D(XboJQ(rjmX9eF%2YxE%qWOQ;<{Q_vL*1W$q4U>Vo} z&Vu+$>6(HP>4?<~72dUJGI+v?#~Wjp5>@J3Mxy0-{ad(kZxN1}VKZiU^mcW)wGz(p z`nPboa|w4p;WAv|*w|#Q5wRSve+#!w!ZG-7wsnO|REhJ5&++=Va1YKSOPDM$dkpuh z*XJ3z78e)IjkNh_k3xGS+U@5XX%-j%)Q-N34KdY_c18`galR1_Fb!c&BFz5zMjeZb ze}<{Z@0;HyhKJBDMSJYqq=$=tYFEb4_&fR%@ukGT1c$kvFxjQVz{NkqRK)O7DKU&j z`w-e|N{vj5i;HTvdI#-C(DsaAC-8T$&BaBvcZ&8Hv{TXk`yFg^aZ&AI3(#gh#%zuD zj0M={;-cD-chP2$(Cm)(`R)Uz z`;=%ui}puor<8G9TwGN9#WJ*+0yKA`y|RofsHCvt5bh zxM-+sSE0D1MbhEMi%VJ@?by&%s9ia0a7k6CUA@F5 zRhf285tmd|+O<(!QWa@e%vxMh)o52+aYDDcZ~eSVrn8ZFs!yKBS>i2^n$|uk-ts6_{RD4$O0;*MPw+w;F=3U?7+X=76%3NSFm&hD{wfTDe9!|71rxy>P!4v1(;%FWJaBm)`J7!JV?A6gPYe9+^X$pv3b z-9X2iDPi-M_xW|$$uv4%!T~oMc-)x-HXAPf2eVEXW{J&?|73DMhhd)BWQ+0(tvxHu z%`l(-lQ|{KEif4$(4cH|rQqg`Ft@@qhZ(!kNQ-cxE1cx$yUJSi&PL;kXxFTxIwb*m z5a7RJYEwmv*iqfF3FbDK_h6pfWYmdpVb@(zQ!Ui;O-9W$2A%a=kcYn^_YY>yK}I6& zF^?8(F=nK&VO8vAEpie648U8U9YBVOTc{#i^O4QQ73tAqen^B;NxdddJcBlEoiiGi9l1&?qb)bn?6pj1JxK!Q(P?5%sP zn%OJR)%%vc#g9zJs9v9Qo>;9r0@v}@$G+aV0T$VsGwr~wB3zIy(J36{zlDrf@plHC zBb92h15hA4kc5$sofM3_GmwynOIwl`#_hV5- zCXt(?wxyU#shg+9J;vFP`Ne@4wWkj$zQ+~0Oj*oR%SW-FO?*)xh>fHoY;20E$n=uT zU(A!;kesc5YO0ruxV02+?F_fJzlSeV9Vx;vu4p#esh^0#0*Kr(8 zkK26C&}2<@e_za`VkV~#rLb?HRfLO*e35wP>wKBokGq?%4yLgyN``%{clybrzKkje7eXm>X>)rjx&G|}i&lOi3h>KhijbHLk zvIYy$yo--)DzeiioXpP5S4G8vPW;gC6muJUd5&ZIUT{vAlyv9Orgia9&bc`m43ibZ zs%`&3eakMx6@Df7`J`;V-9NC-M=2>AF(6Rn^+`To^*YV($-4qQeB@GDr-6ZI4WGoQ zPgXm9PayT`p%M#!GFlW*d)X2cf>B@+SPV9TvmpLDcu)vNfk|NQb(0GgFo%{AW<7_w zssk-fsOI00yHtI$PdbYR*7p2Ow6}_J2_UPQ~pN-;bt7}U_>}jlWOdrGaPg8pa zG6LUVx@UJrb$SLakIq6Fu8itVAfX@b8MrOt92FUA6|z*2TIf89UYsG?UG zbsYtB2h20Cgq&SyI;zjEW83-%VTxgXy)HI0!bL^VmpaL#>a>qd_f3GGv4MVWpZ2lM zqq935)l2OO{t&@aKcQxr6>`R!Ix2q$n1^AqVVZQPI2)j&8YT?ukIW*N8E$5;Fpt0t zlrWk8N^2cE!mw7!d;sRES6w%-NSLuOV_?4NSaH%oN0oFvObN^sn5wUZs;eH?$A%-g zDjrO!cQ#8co$lRipF6hMK6eaJaqie=eeRe#xrrI;rgFB}X8Y8!&HB_a)paxe`pmJ- z>fjf$sVzEclK5_wtA(5WwbZdrvGI|oKdpT1Bx8x>e;lZtQ5YMGj5B+N-R$&P`zSBlaxCtFLJzcLN}BWSd{b&o-&Uq#bs9K*rc)D zb!hgVKuZ083sP=DzF|y5@(rV2m@J=5(gpGGS&sguxi_*4?moyK$iB!Tq^!H@hb+b| zW3K~{Balqm>$QycA|J&q@-fMr!CX9p$9>3GkwcMXNDjHaA@+8k6im5;qzCX%;Hx>g z19{ddmpXT@w0EO;2wLjNhmkUt`v|gTRMv}188DahNmpnbJpE_SW2#Y?*aki+%Q~Z; zz`wqyrH)1_F)7L?-V7y0gpdeCGD#!z?_FYR`lLWhz{vCXN22MIfMe9bN34{{3sLnK zk=5~5DzhuWq)cDlmHg*pLj5i2%Sg%3SCGAs%$t-9Mly+9@&=N5V7s%zOq-S* zK)#7QgJi~0FVtg#QGe1oADPAv&CH)(&&?!V$$?UNnrn*XQ$Aj4+ z{cR_cJ9;5KQ#tyZ%_Yd2X~QJrZb2@^{SxwHBtR8KH&0vj;!vdoj`U&ZdH$Ti+$bVq0zs4 zqWvAqSFrN4$cLH<$la>*jj=V0oGMm|=BW0(>wr068Q1}iffydL4A2^M2ZO*6Kub^vioxizMWbRa_bv&>n17?%8>D*_#h;ObUi0ja?jNj35WIgEglnLtPT3qytH*f=Wvc z*7U}yR>{FG#xFkgL~<}IaGF$B8^YR>WKQYC$ll@>7B_ zUN|{JJwrVD*dFYv$Kku%V}h#0_TcPGHkMC8qeCOIabZd@G14v?o!pq*Z&lg$F~O1q z^L*hvl|q86+MUDNslm9&h-e7so~o)VQpussE<-#pgk*ch>}m&G-jeB6*#$9|`HN+# zWY1&NyUx!oKSNcuJC#zE2cJ)moyM80PdJOZaXVS8b-O#MGeL!LS-7SB0``<)qrdn6!9rWg|LZNYUW_ zgps_FUoT!ZEl$DOCQL;7yHY7x6|erRO+NhL@|GKpmnCWGk$EF3?@4YoUcVnn5tyIO zJ)Pm6+Klw6?djYT7Zvv;x)FPWM7ceEnK1QhBd8ZtMf47W{*Y$$27)CS!C(@eUQxAflGrVz(`dzNa4^%#w}Q4Yx4M zXez0HC6m3{+8V%4RhwoA!Rm^7K`cXEz&Pp4*zN z;^D6LL{sDx>S|JA*=<<37yo0YR(@l-<7)cBPMa9ZbTch&eX?z?OGSQBZh{zc--~*S zRr!^wxiWot{}DRVSzLaJ%jA!1e59pOMTRvWmnY;*75qNo67F0AG8e1e(by~z?vKzlTbD>FL>VTquiD~ z(=gc4>!S>mebp%Vr`I_CfL_+FGMWZsd?cx?Uen-S-;FCWiHyG$dA7_)l+t39gI(Y> z2zMg?K|bgOMuJITF4zT5f?%P?lL6Wl>cw_f`!WJ|b0*s@Z+Pv!CCAr}NetYB&q#b` z)sE@ty<7cQJ0`o{VEpFJm0RVnaleuG4Y$|8oWywy&ss=$bzefvkE-dgn2%5ssq)u*kAOcCItP@p3Gh<>blBn~Z z9lvAz31yQqV-^~gokp*xmWm`X*3v5{rlpUV)rlNlr%H2T@_iBquG`uy3}KSLHhQ#; zyyLnTc{37B1Pj4>um_w5wK_A33c7cmTrh^!?J+9mhEQs_lwLp)d)G+Ls9~j5(^aP% zLiM8WsI+GlcQ6PA6xA~~goa(%^kZ}yMt_;wp-P6if&~#>V^rM^RciaX#<Ofh0Z*`I@7UAo;5G3%l6ZGWL?|qtJF%P7hX{_77r>K$t~yyRVwgSYS{HvQrKbt zSzF9QToB-)f`0w_bJtQ=NJY>}9lXAZGlD6%>HN0iA-PrkYp%6d1$FIIWvG>?QzXla zUJa6>J)Jlv$i5>lr_bv3Aq@+w^oXY1>*=Vvjbi24?7}J^=H1W)qx@xng=Fwrum_w5 z;T!M=twE0){>c<~WQy-&Q&a=9Q)c0rf&Crj)PBR`1x%Z=gW3?|OT z$&UQ#@|Ixv>i8$#^dvEnjXziiWbo-mT)6Q6pM#vZ3<9gBy^M5OfB~+nvv;~i!R-(v??o^X3VcRM?HVKkr=ocy@SxVPdA)#m+tDN=>~HHFiBq+YRz;b zGs1=bVWn#;KgFiX6?KtK?jqlpuZ>mFHnt@%{4J2E3TGJ3sBm}n;0z->;a1G9idyq< z2t>c352_|*Ugrpl?rJYu48D2H4MZN8N#tBqL>@=vjBT)*TsQ2SRY6C3Ta&&p!?D8$ z+O3?FBt|c0G8Ve)3o|xGyp?x5C(~`3X;ewt>`Ly4Xb@?bH>*%htt(#ETH}&^>~;P!r(|qat6pZvaK(>ROg*x^S!F(9+UJdgbqMHeN9(Vb4QG4$ z?yA`*QD=K4kIz$|05k6%Fbp3UqZd0VDt8*dmsqLs1FVQmh`bHHCyaD1m=QrunU~;GP$4zB`_nv7tiK@%Q@!tP%zUc7fd@eQ=<JN)z9TiC<7WSFTnpvf5TMH~av@CXZ%tmCAe1%`6q>G)(*| zwQr$2L3u}D_?+9Uy-MA%$jwZL37>(fyUI?Gij1wApsFsj>QzP=`Z1Ul_d810MwL7x z)L$Q4&YElP_#re*4?l08RqB#=-ORTzD)uFB)v|aae9{;2@U@3||0?y$1zOktL^m!3 z^T;Z%8u3%mIo}Y|ON6QdH3@3}1yt5isM=7kLv=dp4)q+AnGSVym8$)*JD1K$pnRBW ztGz1wn7nANwr^eP3@J~=dZl^g?Z0-65FH6Ij}V_9b4L?*9O`d)>_H~tLO8EPlg!xvC1gyP$K^E;>?E}-&GK(VEl$3n=3xzx{1c=b{;)CO^t=f6d9D>$e|{Qh-hR%)~WbHRGh)^gf|(hsuKr zoC-Q8Lh_^Ca0=>9sOz8}IOPtt6e_Ma)NnT1km`fNH0D&WWo3TX{e{4N&=^7BF24k? zsidYug^QpbiUwADALCrM{lB=A9QP~X`=ay|;V=Ew9sW_F`awMp_4WnS8KKyB$y^PU zemYpk;zB1dS-skdRrGDo1cQ2DL=ydo8g@FEo%V>UjxHWCQum{z7a-03BWls<;1$ue zgyhMY(?r0So!MzE5&Rac(})W@f@s0(;I?-6h>AX$MA$(M`;F$Tt?2EIk#r`g5^fK6g01w%8F$iu zI)n8^SWjF>7rXL2Q~9NThk6g{Rj8xC2h-H}-~Dwff3elVzYqVe%{Pj0p%W<Mh1P ztldh=F!5Nupx7_39AowOR{kV?S@Z$(a%1gJtx~j){?sZ}U+Pb-WRM&M`KT)6k6^sD z(}_eKygi0Bw|@jvB59vom?LA=gLq^2#XoreTp4AZ-r898nRvJT)D9%xGW0Q4{VCq% zQE#~kX_UE%bBwQW1LtJ)ZbM~E@=z7nfACiX{g7lRTAVmwo!2!Q+X>M ztNu7gJbPW<@>Vle75y)mk~Eauk_@|gV`Zo+4xJqt;PRHHoy;6TPiN2n81Y)jKan{u z1?g2*D#S+)MmZ_R(u?7aiIQ7OI!`)p*;ILJ(zWA`#d}ZGTk=CH(Xnd6`Cx-cf2Lxb zyQ-$W|2R)6K5(8i{Ndtc%$Peq&m9lgQW-=V__3gc ztjJ=-r{*J70|4*nG^sC@kL{>J=Eye}qyK_gXp>VkAIh*ZyGV^R0N_iYWEsAS>TTKjFo9tpeXUJon3I6k#taLE1aMBW>l2 zmo`znhl+P?Tw5-~HPdUQ`e@PB$6mtHYOB9RyAKz7iC0$x?fV_=(FWSm@Xj!-T#IIw zeDQh`?4w@~plZ>+YQGM)U)V?RqXbCzSp}Bed~(XEy^LhE&nomuOR3X!NK~b9)aixRs(LEt>XTSTBxIZ@(4xNlT`~HT4sY#!Gea zlW-a+oyZz?BB%ICI4zU*OSS#V@$*TO#AZ&+oqrLEQ78RYj*q5Dzr?7fCJNH*$giP# ziHnv--Di?}(wb=Ra`Bc1gf)tMrD9qwqfLdEF0gFOsM-d|1F7bp30R$dQYC*AuqIg4 zo;o$psz^GIV@c3j>yv5|^UMfa+zfSN*;vck6!KA+RhL9EKnm=`iPlF(@)v4IEk0)H zTHQ(=J5ZiX{`&BAC3axbO3$8XfOpV1na>e za2}-I%+wC(4hDgVU=An;yTEyncndcGI^4q8LopYl!EEp$*aJ?3TDPJEx`RRBDKHx> z13SP;5M)9s6|@9Bz)&y+l!9`w3!Dbw+qlWw78T^#Uyy&w$VN$|VnEGEG}q(vN`y1$ zjm8FYb8Vw*bhX*1s!lpDO`oCgd!o7_-KcH+o>(?SPVjQxEtX|qVFL=+RaakT@Ttvp zY^Nf%rBtFatkPC>>%se@v>;r{r#AXLAWq2POH=ziptkZUGNZ(q9CUUhlaDiJmhv_` zH`54PFGj7^Pz70ZUrOtvvI`>O5K_TQbZymdnMOTxjn-FjSsZUa@wY%Yjmb@qY{Mu+ z9LJ-^oX$;KRg`7ai?pj@r&wA?X$IS>gV!>kEMwx{&(y&za^Q1r@VOc)lx?)}KPT#H zQDduSWW?~|;RMjV5J?2*^JKGX?h5s6w&9#+^O@S2jfIU^*iu9Nm2EVSY>7rFStQLd z^Ul0ttN24PF=T6zd}Vm0l8+5ltp%(VE6t(1wClN0Sgp-5;#CjvJCI`}M&fJQ373g3 z>8x>nPdy`B4LWNyB;hyLAzFqD%)**#OdTUHwlJzL(OT-@^PDYrGLGd-bDj?+s;2#_ zU|+5d+~E&>{g)-|#t|B2d>Y?R@NtJFJq$BvD9OE&sc zoEqZLUUN?D&i$05K2>T&cXkvJL7dbPfh9=SAXM!dybzS>rw zk}*2!?c8a;T9ii3n3~INz2xE~^BHBU!pvz`;g-8Nx#fH{ESKEOSKd{D6qSFaUkcXl zT<&EH_rj9F8yfN*V`?7dI*@GNkVHvH4w=0yuVVG*XX=qW0&OMGs1)^Po>4b4ik)(t z43KOrurolij!PalJ+o9`f7sUb1%BTS4Tz?|)lnFJ-vgdxHSPs|uu%<2y_+k-4xdm9 zSK7d+6){sQlPAwgf!f)?$hIzbywyQbP5p|;w0sZM1jVo+Dc(kkzpJgrG&CCfzpIT2 zbw#0-ta|q_EVZK{aeCOpTW-U-?W>uIU`%!6ax0)wq>$ z32JPkildc3Q}3V?U}qxpzH}PM%07(LdQKmv1Mx@=Xphwg{4uew@T1Frj1DnMJ}w~R z^^J`whV?reHOhZo)WH&d`21$ZP~*DlW$!gJp70t}2yI#zQ!V>(*2lK=3@4~#EsQCa z{j7OCU#V4>1`^6xfE&JBI zo;qrqK^@qwt`5WJlx0<;A^z)&y+l!A@m5I7I`n|$3zvUQFM|Hn!Uuz1kCeO-*I z_a7_GCl`9?Y1DtL>#4x>E(p6&tJfE`!RunkNB#!gS5%CURjHI?Pcbz}4+wbm@FT3; zZ}@-}W_9Id4_NgguSWwp&mTRL2dorW7AZ22{(u!UCV16fFUQtUW%}f5>vii;L7tFs<%_N%}OJrFRb*(SNucXzYv3rn=d|gE^iob$F+ldB$Ge_Kb== zY^AGSB~>7L@Tn{#mQr$xq@0BRh4%$DG1Kv zCF7#EuTu-wc#~Dr(N=vQKW*9VqpioiKFLS@HS+mKtooLnWilD2myYI-L07Wp-ZAv| z<+k4)L)VeJDEnrN)y!L41bFVCGXFn=8spQ;Zg|t`>s9CPGpnkVZ&?xVHEP>iRyPWB z`d$vZZ9SI|I|%W5y1H?$RX6f_v?7umCN7RM>UM_7_k}a4wd}nbwySM(t!#5AfmWrf zb8{_c7Hqq^Y#zjy5bM)b-+35LFZiu{0 zHPub*6yj@$f=u<-e9PHFV!JAM8{!*?4w>qnw_U_LLhOO)ovFTj+Z9LkQi#0}12WZ> zr7q$TA@)H$lBwP-tr(`{+CQe)pG1uZ%2iq2-JLa{FVh_Va1)LMv<@ zK`kLm4`^3}ud|3Ke}qWR(&O0`#EU}w1ko%@51UsI-uEDmLbT4(qvjRFU?Gk{bjeav z-*aWiUWmBk5VvGiWd1AfxiX~l`-J=%g~3_sKkvIjE{BLa0Wq>Nj|=fP#NF9yft&bE2%b5!BwNoPRG2FI z7{UwjWVU*miG>Pc6GYg6cqQ8|FO@SX6*^ZeBl~>lyb;ymftHDs3Wax2Fqtnmmu0Ij zm$?#}ww#bmnwx7XL+)GV3i&JwrisGW*=oshSGxX?kZc-h9;^(xV!7)l>%W4KAr$`P z2Uy_>xlM>F5LS*l=O(UL2@!@!$x#DVx8*;}jFe*_ z4!wdL)u!C4om&vqmv*>AGVKuHZasxjf2VJItr}NOFXmeHa=FzY(!Guyi*y|1ZR%PT z`HU6(+f~{sYM!dtKU#;OqVEIMRj*Z6ID$)8qtfO`b$XpTXvC#^uT$O*J`v8QN%4{O zbt^5Sh-N{&&-vbEyK1$X^v7erxSqOmwJR@Q5(3+1NjJigc@1%~ z*2=uKzWQVhjWF`(HCByCU)E~baoSBQQwJY1+@#HSP>t4F>DCxWMR{|Ho(-?qfy-t4 zjkVZLz;;ru+Pv1vs*}XAUe0|SsLg#aDDWB{IZ=Q4fxK#41B~@K%La8rr?6#Q#PNH4D=4qg(>uk+L=>s&?I{|N-+4d(GY)%X(^F<6Ki5S|8Vs+-s; z1aH5lw}JZ0Oh4H#p| zxjD3RjpKqnA>K1 zAKz}(B&2_bm7U~{f6#sX^h;-kRxa3~O%?6Xv29CcTyxS6D@eeXY~~}I*@^3d+ZZvl ze}8#*mR~kkn~LnzHX7~J7CYNwu68!S$c2>)G>g4T2Ewa6t{aeX{ER$}e z`b)h1%`1OGDWRR!urI9?)%8o>0B><|Qe-vPByze%rKNc7z359y=hc@~dM7yEDO10) zf{~4vRZ_H(7-A5PeFeYb8C=oE=HwnzG}rMfTFEu-DudLku%>2> zhHw^juB01ldh(NuJO_6X+n}2&x#pU?pozSD7fmp&xB2utTc7iZ+!hwK7fxKrmeE7s{3+`ShaW+Kk@T9MimAlYw=)|gFIq;#uYnG z&kbtPZp+y(al86$H*wI0n;+ezYJW|w^HEe^im_A&j7rJ=bX`=p=c#M;6#tO&w9c<5)OY?{RS(a;spRM?Yc)M!$4RO(2oB7>U&u?50`Ab63(3&@P zSF69_A-}P^on?{;DIr~z_X7qs^@8xODpRiYg7B^~kZpg`&{Y zrge2ap#26G4IhCq`PC(fUDf10R<`kccXh*Bnx?ILti(pMqY;aa3_$!d{E++X@KP0a zRgt|s8C_*bC&PAoDZR^G!KGRxeYVOYdwF=es+VmSS(9Kl{9E@*lMoFhkBLSvC8d0$S^!C5gZJAZ4CC-OZ10vqw;)d%JGu1;ZKQ>A)>BYO>*= zb%T#F5OpGp(aDzIS}lF6aOwHQ@!!&rt;eM&ITwCwr5an)%Qk;&-Qx9S^D2F!&`hqz zm`yg_3SI;~VloeZz0KaBLzpVSrA;k6WW^f{Q*1tD-C!^(QTwo!=NsVY79U3U5l46N zVWMTE!M1ZixET)D^n1A19In^*a348bDV$NBsaAYX91IS`{XiW19Nq3epeq9aIz4lK zzz#3{b{t!UOUR0H8AsrfaoO7i9)WA-a5LcyUfmZQAr9Wu|2je(yqMd%?S4deu%kQW zN9^$GZFA+qJ>zikKf&>GZF6mZf}7`X6X6WronQHhICxe5`6uGo?C7>Uitb@Ycl=T8 z@D6O-Sty(@+rE#f$C!5x>31!!C)Hlx-0&C*b)yPuG#Umkwa*Vx zj-%Vx(H(i5i0*c{*}|1L+)3e{bhy-?;du9q&Qbf>#b)TwbW7jJR%3o9BHk!B|4c-@ zK-v){o*=;2PJrSQB-?&PtVs4G(fAXMtIC-TKOh>Gej)Sn1;(&)hU>y7nY2#Hp-j$Y zqr`S6t@=i8jv8{(y2L2RDSPvz^|jYHTBq#MUo5tbQoQz(TMd90KP-tvh)s0qsC9FcM4zbHFmN3!DVu-n`?1wxBy01jd8e;6tzj z90S2V9#2Le)&;cXqB|G~CW2D17VH71LAVHmARqJqBf&&a3f6){;5?|+mjr@BPz=U{ znP3^%0ZxN(Kh_q2c3>bV={J@;;9?or1x|u6-M$=<4|;%+U?P|c%E2CR8if0!2ik(} zU=SD&W`f0F2RH`8bc}L9JJ1V^22;R7uzoE690KP->Rl`_0NueLFbT{B8^Iyq8OU9N zmY@&}1af-lOt2Vi1xJAAZuCG?&;j%TqrgNk2P^|Sz)9c_-ox*pl5Q|l#;)h`05}V3 z-Aj1T6$}Iu!5mNyc7f9%JcxM#kPmu+kzf*-3)X@?;4FwAj2_4bJ-|>f3Csm+!5(ma zu;)@w;t+lw&<^wgqrenU3O0g6AcmetDrgA`LGgW)3!a|(ofDq#7lHtE!mA~ho0pHyA1-i8$qRg+p^Bd1 zbGnW1`)iq>h})xn-pl5WgSzs;V|cOu5@ssobJ@-u*r)%_#Mn~)ZASdNbs!w9*zPi5 zz=-}MN9a)<*4E0Yh#t{*bfkk<9o1~L?XWj}>VBq7W*&+OGOP3Ili@^le6hc(H(UL= zn9m0bh0OWDAD>2(Q8CpvxM!VI>>1Y5lE0mlhs%dRFh^{0>7 zva^Y({fS^LzuI?uYz_VOAO@EB6VfC%-0>8T8lc~<5_BBnmhf$8qP~1}iN9u2Yoczz z?UhWC{IVziVl}-@G~@K;DKuM6;pSVS{XS}EquSE%t12q4`zpTsKl+~JWhYxrE@HyF zYni|G9r6Q952?8)Pv^l_69xWWvxWY*IXYXW*(vc9_AeSS@}^-z$k5tI;+{zu(RXy@ zM+o4~QQjW{>8jxYZ`eCZbvr;wssEur-kYN?`_P|~MuS$7?fr+27$qhp+vVryTp(1? zeAX88KJ;I9m%UGulj2LFDdvbC{r9kBRP?U}DIWGxG{rX+{inZEZs7HRASo^;oP=@o zB-Il9tR4W6lL)+LRl)k06g6pxziv%?YV4np$EZ~w`4a*yiSO8SpZew_|K)f6yXFDQ zPTN9T=zlro%=~kDG?^oY4(va?fA9Xohs%e6I+=1DXDQ(%jH4&X4B@UrGWnLe&tS$c zj~%2a&t2+|SHW+&TFX@$?|Buu`_O#@Vb|-X>ZoxaQ6Y_HzJ=y-V}}RW~4kJl8(2KJ#ovA+6%c1*&DeA*%!&| zs)xLOEQYcv`WEtT{29uVJf{=N257X9Ly-KcB@f6h77uXoA|5~r{(H_sE zZ4Dg!-yZoWvOjV>@;}JOk)x0kkWV7Xw8!|C%F_e)A4oDwA6+~Rc`14D60!qw22ysr zn2GG=qv*WMMKK<;kbF|_c@_B(@-^h+$TyJBA-VgK^~iZhzU}jrBKfk;vjF)!@?B&w zMi=>#6yze@Imq{sa_HY;$wcNX}jM ztVGJ8eyfnbBG;%@EB(#XnU(&W*dCrF4?h)u$(~!(<>melEW1wga;}&6wU~t4HW8`{ z{AOfzv>p>OSBUDeh*6#_8diCjXaLL1^F|QzJ=!ma*VhsCMC#IxW^%REJ`LKe??A4oQ=4bTTW{isHP)wERy-5;~8R$tevXJ6#fMmu&FO#T&yb3q- z3Hq>irVn%`F|8kaFws|r(S*Dewy{li_zry zG_VkC1c$(RkT{e_7<2%|U^JKp7J~IdCl_32FS_`|pBR|S)>w-kW|yl^{B?X>ly&)p zD%4qJG5S+f=ArUFD(X|e^BL7#Q+@rZKP$i)m*!$9-+DK7-FhgFy)>6V-FE@?o=~Mw zWl-N-K-K;X>K&+$pxS@tHu$tq3!s)ly?+69MyPk8mO-U&aEI!<0cs)Ca;Rr6pf(G& z2x=|Vmc=30eYN@ApH=-msNI~EOkvXfv)pKtWni#E8D?b1KFI@&;-SBpNU!TkX5^O$>kqrZLhTLa9U z!(6K+P?6EmB)LAT_t4%Sq3tp$st)h8`72bnO?2p1sA0Cyo7(9UhgPUXw%0bK)Cbt9X#XtojpyAa)MAK6Ar_X=02$+piTTNG@kBYb4DKd&;$$y>;rGLl@g#ILT| z;?A5$h58UG1M2MysGo%T2Vp&o#G{{re4p;kbZK&5=)4%PDusFhF(O15mPyyewGl|#J&b@U5=rcW-a zZueKWj#B$bQQ}+xISy#!SN==%87u}r?wIWaTSc(`HE2AJfw4Q>238BT7HTHc(F>@?JE7J=9fi7er#sYisJKs{ zeyNP|&YkWk%`XZ3DH`Vp+~iAl;Ne28hYCK*HgXqG`-J)o>RPD4SME^Pe+9+4wq_yJ zh_C#0GP%%MCf(YnBD|1-nq;Bl@5;)ceTa-ace{A*KF3UPG&F0#nS|}M%kO-Eh|)tS z#c_77`EXQ;H4|-i`JInX(fCQsY(is$W9FckX|UUErsr7OOp!Ny11FAJtV2?Z0if>|Ss6KoA;lNJ#-tZ&#_??e1$(N;j$d@mn z20Ui}IBHcL^5vO5?tIDHi~X-qnn3uQ_PWDQhYIh4n&gCUR+sSi?sbO`?IZkdlok-a z#XfiVhoHh=Lw(?ce^tVF+UE}clZ5{UrR{`I*zXSCb3fttKz;3mkJOXjb-z3O29#9B z93#ee76ZRtV4%$b4D7?e-;RNCVxYKYG+mSqqSW58)VY3Dj>|e)@jWCzN{w$(`WB@dY)hRgYoz}Q^&Qk8JG_gE z`wr?5)Ced3uHX5aR|b7r_`~p%ou~)raub~nxo^TagwppYO>>O=i_$})^aDyuPOHty8Ycq@zX>#S>jXyvghsv|VyQs}V{S4L24waXHYug7&&m%oiWMBF!DRR`9$<~B8@T9>pOR0pNdj|A!#%A3HEM3 z=Dw3^#|i%jR0AjctBvV%-G1DCCr_gkIEPYm!jlt8YU6SDoftpE{|~+^e1o6emE#bh z&O_Y_r7obp7V1x^N1%Ks+*Qu?CrH&_P|rB2TGfOaBjtoURZCF{{EgBY!hd%`_`H*Z zr;BH9aKblhO8Ea>5PmvJ0WV5l5Pr=`cdE@(PzKbGP)$y`so_Gge}dWiN!o~0?o@vZ z6^?PhFfXhy8p9Q3-{(HnmuJYyned%{2bi{JUGo;v9hp-iZop-x;twfPm(0jQT9 z)2o`XB6aMq?hIKVN}S_v&T*9f{J%2)KVw>u;!%S*T?5d zzwsO4ITYSBp5nLu%^iNYP+=$wYQ_cBw@_h@kT)YwMYATe1?iu0#-09K&JaEhrF6oN zJ>$-r4N!4ap>Boya3C|4-y~ z&l0{GN+Sv1<*YmWbf~xlsM5;Ful&OudE6faPDJB<0$=)vJMg1W;p$KyJCS=^RjsAk zo^wB-XC!?z=2lhBe<0Okr`P=^4Q5uj4uth|G_y{%<_W6eHC<0o8?TuaR~M!DsFG*Ii|0&NM|wUA z;d&_4a;y|xhLxiiSV=apQXi$d6;{;OUbFQj_JFhVrrgGPQ*O&!0DrvpR{Z4>`bH;; zZ4$-jhC89>B#JzgZmW!9so_rPJw8&}0F5HYOhFsWyzO(F`5L9ThA7=vX=b|5ZRYwI z%rrt{hGS-tn0Y3~ZDuJ-ag9-WtW(?e#|sMW4>c1^K#7G>vx-(j#6AxlvY)m z>FIZy37ME_hDOXY(I0WLnCWD?%{+usTyvDFM3v-q$aI_eNzAlBBf&A_ZHt)(0k@f+ z0nD^SDYMc{a=>k70~+C0XmobW3==a|f^IWyf|$7krS6qx&Rt+;J{sXm(dgxvIVfh1 zUSKBK!c1$F?x{5Mb z0lFNGMbG%v3n8;Fo1FvP0jmFka>nVz)LHIva7RwgH8 zxN)UwRz+)dtinpNmFjL=OsHbEm+^uxst{vaVl_B_^`46)Q0_4rVxzGQqT#V-S# z<+597ia%Rl>T#kReaSdciocG&)MG_5Qi(C~t*0*;FG}&(*O!bLrTArNSt~GW7sm$x zn67G@7Vj37-ji%^ zt+LQ{z14Mn(sdmlugz%vrmpL*_Vpd{{95Je5nH^BP-oNP*juMrm7v-hZw4WE$D8#c z9izX8{N7S3$ju1r)t;&y7xv%904=Ag*XC2&!U*fk%T@n~nXP)HV`xf*#qH&4UPQ<9 znJs>dVDZhU#Vjlu+G1uk76X?nL=AO&H8aT{c%DMQ2B_?(S$HoewNI;NCPr4hP+2m< zI^6PVW`oF`FWKHQX(^-RWaGW8Ned^KwXCG+QBEDyiM*FJ!G#HwvdkzUr7T_tx;sH9 zbV33t9Pb2!t)|&k2`qRoS9@*o2O_Q9TRFAYcliAy*nCb;oYv3*nkDK0ofEay!M1CH zE#9y_*Cm=a$s>|n-OQ?fCC|YhrFLpPU54D)f5hDn_5a5Z?xQFMu0k>49fl&So37Ek zpP(Z7P|5E^Z7@OKTSeCU8&y7VH`XA00ZLhff4GLL{ZuQ2x*94M>W2%cyqZwgKsAG6 z=Tv78Q>Ue4n!_Uxlnl#rxq93pYT=S0cFh%vOGedu*CL3F zp=<9s;w{7GI>=UW$w;~8&WlS1$Ezk0M25mIPcl3E82FAZu1hlGEk?Jg&%B=M6=wsn z{LazHNJfJJYqv&Wvf0wdNOaj_$>!aLuO@?_CsMI5!@YVzTFW#PF15Wm2tJKO$e^y~ z77BN3l$%-`N=9xq)vz|y15U8f!pZn7TxXx+f=yj=^^j|obaSsyMpN|)!I%t^Xb+xx zJxTWGtxYr7%Uy;`_g~IJu90Z?WQ24}Q(Ut%%tD_Gik`^89z&q^s>zm_CR@Wu5ZN7P zP$ofSgmY}B+21GQnG)C3ETXapDD{`LvU5wrEX*++X-72$4IkrvP9L# zIHDa@cRt?m$(W%||3p3v^2xX$i_UKI$tWP+$*OveS=A>4fA8jyp8Om$-zQ^zO`4m@ z>Sf_%cn|J2pN!*aOF4D0#L%6+e64F8g2))1=1PTQSWfm3y3Hp;Z`!+MUA!4>v$q!N zQriZAWU-`g_9Al{q+bUqgvX#dwslR z_)2eJR8pTHGGe8(nK!!|g?>XWvV>!I96GTQbbdUp$2_oYbI(coIz{yZWmnH;}feBr3 z*NQh|5wbxh8x}R80Lq}lRZS^?3^CXRaC}n=po}Hx$75Mjg2?azk4Jx>3>N4Jx;Dd` z@c}!?=w<|wfdC!LV&UZ7e`RwD=YeL#!t1^i&Rid_^mdSu%?Tp!?m9?mbAs@?E-1=lP9a!xa(*QT=sn%*hCQEPBO7se` zmJX;@(oQ!Z2z^fNR=pu^(z$HWkRZ~Pw1R9CYw0~=O^!7r2z^EE*0d3B(kblJh#=DO zvx4Md?WV71m9%J;al;;^ZZ|S2IqBr-v#r;dfb{HCtW zKhr_VG{KsVm=2QIgdlXR)XXO2DV-;sL7z7vgXk#fAm$SUp+_V^dO7L%=mX3ZYkD|3 zNbVB^p*JH%iY=%xgg3=E9TV-_+Z5mQK(y}-P4P`{Lm%LZxY4c9X^Lz{n&?94aH-93 zqpzUSnsFL*33QOtVolp$7mbI_C>pf$rI?pc{hD(#(V*9dn$?^`(Pq!t)ZF;k?vzG# zT0BXl)ts|F-gr0MNh3l%k;p?v8VUOPCK5aC0v*HYL}HKz0MqEJIOTC~m7;nbj2Jgh zcNL6M`F(1co}K4>(Wg*KqPQB1PAgyBAldX?#ws2xf| zQb=AsSgG`fn+DdYxf zhmue_%0#*7EP9BdnC8_8bw;DmbhHhfM0b$Ml%(3I9ZE&%XamYaH`4eM@(zhWiD(>} zi}KKUWHRHZJW50lr(LE}&++J-(yH;_4lcu;H92aQ8>QQ9{C zoJ2QJ$V@z;rl=1Zh329S=p?#=LS~U|s441(Mxp6w1Ij~J&_fiH!AYTRC>2ddD^MOf zk8HE4KW6iFv8EWhp;2f$+JN%Vd2|Pvb4V0win^gxl#a5{PV_mtfg=W3GNDP~9yLQc==pO0ci)hM3cU1j%@U{28-t(J@+O3jPU$W+hdhHY- zClja~6eyp&e}3pWb!H-K#LoFv_nu^d-8tn+x2)K?uB6Jh*^_&_wiN)9Ff>z1BGBBlIYO-F)=dvQo z#tT08>2Mb&x!bt(#Dr<8%G<2tn$Fpt`OBf6dE4E}w{~%wT7rxDE-q*P()pm0Gx#pV zu(t!t#;2+1$%JN-q46!DTTOPi4TR1RmzlWyh|8W}7xxrdIflzGxYV8E?i2_!6&EuD zmplF=4w=nZbpICuJ9kY}_Nj!Pjh_dEt~NF3h+}XunU!id9{AGxi-g|O$LZftgw2*D zG;_8M_XBohpB5B);50(d!zI!mdc>T9<OZjTcyb!wWsh^Ly*O@<%j5}j9fr@0dX zdD-k8VxLbO`v}ng9d>WRz(ZEgCU?UNs>?_Q34m<57H-+xe#f$r5)v9=+0>bC*;oan zpk*^c+iaO=l(eR}Utoh{wn%J!Cn8eiO=nA{>p=&S171+Kr@Jc^YWz?iUj}q2v9=2~ z^pS6_k5FPZfcA+KI=66}|Sp6RzMlvGQ z3iB~xJdJ~_4a?d-gH^c^w){EHQXns=W;0|%tsv_#%i7w~Vw&1DgM3uvV^^C~RqHM* z+-Go5ep#8BpZn1>SqH16={$>F z$(RLhyot@y(vCPaeHI7cSKw+%CSKHgW?a;JW?a+@XJ-v`gxD|2!r54`MHcd()>d-8 z)Gck!_BqQ1lM8>*x?qx37`qg5B>27*Aj$GCm+Xe4R7h59zUgds#HC8eNt^BNZg$Yq!4oW2A5~-?ZnnTnVh0Nob zg<7Ljl#aHcljsgI=kxeLiD(p>j&`Ec$fkI7pxUUNvX!(Az~DuhXd60-uAs05TM~BL z=Rf8sV>Dz@z`@0;;$v)F3a!u7g*&?PKzL@LyNb~W=X;CQuXkLfRn|Z@<-NzO*G&Vd z56Wfg0wbfFa(We2o$smVZw++UbS)_@H&;VdVGyOSF;N`KWF5~ScU%O9Krstdx3Adw zRz?r@5xH}PZc>>uAyoHbiVv7_BiSc$R+i!OGQ1LBciSBJxtT3F?UiI8v|N?bzNq~J zxRvZSD`Ap2*|6PT4^&d`4rY;mC3X89S7EpR7O$iZ40gA-H&hX++)7PI^SLbbUO`7Y zUk%+*O~S$T1P zCs!<|+z2-x!#c-#TLY9SBUy~8Pu|Yn88TH}%^K;R>!_TqzkN0Q6?ce})aAVXiu-H3 zn*)h~qtrx}?p#EGaqvJL_oHdy`q>uZ*@BFaF|#98Zg5Qjo_yIXsMf zpL97q7Od1btnq_J==YXe1&uZu{WKNgCOqd@z0Q6)Oq1 zuY{LT7y7buRst1S`18_+{vo`IYcM6yEFYrMeh80qih&(Jo8?^kA$+u5<;@8xu7>{< z-o)SF&iyGo%EihOqaz;A{S;oxgCS5{<>}c{zZZPWGA2Lw7+K?u2(hF!)tgjSZD5UF4k&RWMjFO4UySY_0A2kAzWm>R2h09BHlWH^STaYRti^ z!wo*HHk^n;tE!HJWSi_8)FYu)^Dm4%-rDF3Bh6Nf^1`-&Wt3XP`W93h{lZqdIc?;t z*t+@JMke%^3@v2YS}$x1TSn`vkD0&lJR>%FAzQ?3wD|E9){^gKT)yA$0?BwnB<{mV9%G@MJo@BkOWS?9xDXMK$vzr{Q2P-(m+TS;9 zqh7rkUd^+FWs+ho7eiYAB(8I4D@wxMn_Rc!JfKe04Nr?4=c(p*u=ye-EC-GA>$WN?l+ch*l zo-gp@8p*M$*9%dPZc`pHSP?cM!NkkvaCLri)>cD)3lC=#Im^8Ex9}Q)Vsqg)j`A@_ z>E}Pnn_o#veh*4*_uo0nD;(twj*|9!xWCIeSRE6WQMl~E<@evit9US2$M?6e+NuNc zN%<%5g!{kPHCTA+zT(FhTRR1_V_L3`pJ3ER&|z!Bm^?^I|932M<*6tC;H7@$Vca2?{s=GQ@%jS#TZB(3&;4*I zaoz8e&@n_kpdkspPp)CG66&ve{)y?;_oPE($~?CgL3&+w|gZM+Ao zh`%`XH#pogG@h+8z3*%0^rdeyDh4jYc>K7=;b%hQ5ViiVpv!PqT;9ZG1}?D=!mEU0 zV46X~h|nVHxsTa!)f_?dCU>9RzXk7Lb>IPE-XctsCL!wQ2jTv0oCd2p4{=GuWdSa| z9|ql>YsJNj%O|*e_An?+^xxDU<8e7fLt4^rYt^#vs8`j9Oja^@KQi;rA_JeU3HWUL zM2On+cTnu^e{h+I%WJsQ{U^MJQw-}PO?t$!&c_2~dAs;a$KO<(zx^jD6%`)gG6|Py zxO93HltT+~Dfl)nYiQ3~>FYmC-TuB{DV3B*PvgcTDmTBAzk|?Ts{2@bd*!LY{N%R^ zhZ&gvjxmeb+s{ijOY-+kvy!J2t#pY{ikv(++e;j9fC)K57XBfNN6*0_mg--fnkwPm6P2`hw z+3aMPsQMXZLZCFgk6&{tG1hOc6Q|-X{Cj9=u&UtVsMGNCOmmLvGM@;PvkY;02bUyV z_PEUal3@?SWjZd|xKs->^Xsx##pPXG4&t&j%&g(T5Xcu&YFnr3q;vE4oXm!l2}I>Lqv3G1rRAOk5VkQ|5wQq94O$7B0?&5Y_52vql64>zGzO zrVh+uZT;y2j;et(J4OgIgAkp49@XuOGV_g#@Ag~y)-yE^vxMzAu{&S{_N$9!w*-Pj*OtVT!48FW^dgfN8i&IUn_P#IC zOO1clG^0GlTKRqHi_LS+G}}^{wTU3Yc|_Q>RfrlE5p)@LiOYOkUcu%2h@ga4DS(T@ zWi2kx6bK5lL|hi&atW7@3Yb-#V%YQ-Ri0VUtQojO2?g=D5Pz=LG~Wv1PYjm7&B6YD z5PysCR|4mPkwIzb9*N6hTx#Qz7D)_Z;0A9WILP1PB@-_n<5I~J6nKaSmnFD7#6@|` z3LXqrF8XWm4(ekMw`B))4X>WwZSr$Z9vEz4Sjdz|L2@A?dXI>wF{a?Af9eP?Z9wdppu=1blkrPWtVO)qRl zdQJqTMQ+=Ue7V~!7TwXF-#8tEwG>;aLfG;ynkjP9o)e#8#R^WZLzDG!cGke^D#>1a zosR-EjWT0A4W7);1Zn9JU?STv#-}j+;Egg(Pe-2ziCji0JE|p73|Vwk`=ZQZrGk@? z`eG`F$#2|o22o}$kF#C=5u{H-?i8_#;g}+1|LYU1R57B+CWBFk` zFEfZetQa$$^_1noY6*T^%kVS&DGGNn(ug6DMkyDa^bk%b6~{=9y83f?gz8Y-EarLL z=g(i&c9M+cdKNcpQ;7BzC*I}6yMlOsDo(r@0`W>AV%xuHB3yGLyrAk7ZFoS;eXjcidi08YYBuP2xtZI}n zE4dS&)<@=(B)_t;-}H$QVfy-yE5Y?o@wv+Nm$rUqwQn?C+Q?*A7?JNP!O@!1v{#Mr ztZtPs>v47!N^*89IJ-|1c{Y>`sw@`bVy?s`qJuBbD41dO)SMFz+lA^==`aDrFdHN0RqXwo28h^?Js^6N)vbu zf!`)@r_$6W7y?Ob z{8wXQ$*{E?=qaB+m3^gPjEYv)-#Ln?7I@&_O4OJEN6U1!#(v`b@3;A zJ>S=)2N9!xD6e*T2F-qQ<}5E`)-P|3Kb&iA_H#0x?RRa%k?QU#Yx9E=liEvUE`*MMy}XxajMQYvMXE{v$9)v z&Fr=)m9c>6I(IQ+oOH$1ur6i?C;ct8UkuWzD%h2D&^HpNXf>;=S!byIQw-AJ9rhegEZVnf@pI<;PHDcj?@gkmkvg+CXKXb`d*er1pW%JT zTiv3x+vch+ry~mI^yy=!+ugb)Xtxd48UFBjGsR8I&pNFcIuYYuAQ80P)Xf*n1UC&d z%P~UdcVb`8S(;{p`*JeU61&;J#Z)D+rqPx2sIO!N?WmlB$z}z+n|6~Ge6YUyonPeY zON(jgiv*|Dlk?z3$sTFiJbH;l>z0h2QB$ixbWS0Cy1`;+yg8vR??g_gnB$z%_~_J+ zypguXDKSXXqSMP5qycg2Wv;!n5XhTo)w#b}&nXQ84#CvU{-jl&{rmfqlk%t^Hh>J2 zC;R>ZTr?iYIqL_SUpU!CGqgO+(Ci zPHN(uwnNQ79d4>G>(rmnq5F)$8?{u<(h=s65U12W1z$7IxOKf@x7E;v{NZa9a$OzR zW&0Kvw?+Kx=4rRSRqZzRw~~TieKcp0`Ygp@wAnAMY!z-^{ymwXS(|z+Zy}FsWLv~* z8dMv#MtzVMEkJqbJbH+t7V|0ywMMBZ9j!on(N!ed;Z#Sh(E#K{Yfx?`vq!FAc!*+_ zFs6<=qXB3x+JH`@t0?R}o2?9rM?KLfG##x$x#%jAZFb6|rYH%GMhnnpbQax0ky(t( zqt0kRRvJ@}Fswl*(G?Vy&4Exml!T_E73d_og3M(c1SO&rBs&-_Ks(WCbO)Ks$u-mt z4M1L$g?6Iz=njfnL9V3nClRHfbd-tqqR-KN6uFXIL5XNMnu6A#TyzCJL@}%IgSw$q zGz+akN6{q|xtcRZi6{jvK%3De^yGd16kkJXQD-y&%|dI?X>=8pSU1k-n3~?r2n;5l?`A}~n&WjD zUV^@g(@fRrZj>`x;BtJddak?S|FTRoHBTJkakxBIec0Xbf1#q8`db_laQKVE_6Q1* z+yjS}I8=B;P3vKl_Ecb7GdrpEH@y3*U3l@-^jZ4{U;4_I4g60+QuHj*v?7`wZ>Z;< zHA=_z2>5q;1~|z|RElT=_Ii^JK4I{< zdvB<>da`8Tz5hsLlG=h7&+5QIb*C!HN@Q`}G?7gAKULe25-vcKUPec!<(T1Gy6I^NbjL!Auw{(_q{m6;lsmUw!0gh&BbGXw`H3x>3 zQ0XriQN~ZW6=J{B7mS*oLbd)qsbi+v(kmj?J~Mw($4uUQQpZeX zP3ph`o4CPYv8r-6C(Bd@hn2zi?Td~w%ALg96m2#e$Ohng`UP<%vA46&)4Ksr<<#CJ z7V!82G}HkkpRh?XI`}@@`=diWnam2TtDHvR9%^W^!IwCCsE&8+&E>63yj?}TWUR2y zQgxWmV0S4`cZTCOKeUIHN~Z`$xmfx|@h;UPf2N3>!Yt)UF=9PceAfPc!7P=K!h)Dt z>iHC-oV%UhRmCy9sWMZH;-1by5rtS0eJ5WAIh(?2ot{B%p_bd-6hmGtJ=4#qVqTML z^sG*Xx|YBY&hmbS$K$t>CZo)l$*@jDUFt_0HAAjTF>BCBEqITQ8ooZf@5tm7-MN&T zHbcd|%#x_1xT(aKS;>^4lCc2eU*cJCtJ`wzBGx^E;v#wiSzkZN>~BPR#`48_f3*^Bxn-n~luUv* z!f%+vW}D>mB2|pMk;zcE`;(M+gF;IA;~WPV4LybWf={fLy*gs!LJ`oxWtJZ*Id; zG0EHp`y9Rd{P}3A@T9t^zN?;3^A&DdiVc#a^}g`IQ7nw_IXxuQ{Ewl>3+-SkFD2VCQWOG7!AUnj+DzR zu?`{DTg1AZSce*Ao!k2}cW61&=@W;t9B{rGag5Q$;g~(&_~Y@N{(Sur(yXCm^>;yT z6m8plbzrDbu13NDokYoMxdKeBv0j8=w7oPWWoYt{e%9!WT;uu7ui$=}uj&kAb?AKc z)G&P+77ZhXw@KmF0qWo|qiX0@iBx6uHHxSvOGEstu{oC~hvV}%d=?t0h7LFUTMpo| zRa}0@<->vMo8er_4+rXm`QHdFP@WO2D6~*qbr@mP@YQ()o-l&IcL@CKV6|?9(K^4} z-V>L*xTFkLrAJb3QwHZ>61h7U>X~{A)d-oew@^MqEZCxPW~5Opnr3VuOJrkU$to#a z3zhv9O65XTN~7^B6y4a={P-o$7OH`-u==p4&suI@sYw>f*Xt{JJ_zzHHOWHtwOD^2 zl**t*UNPEtyt5j>!S?v<{#?4bRGv00Z~k1u`mOv~xmb-D%}XNcgb-!E zPD%EA@DFG#R@RfFskk-v#V3KK)?BR4tToz8?yP#9b7XT(Qbyi}FE611dCQo|4& zORM^poMa}NEgdnFTHF8M-uy|LcaI@zW_239Mp#i7Rez2#idErPew;DHi3Sp<-`;;l z@2NBQ!b_^2-2N)2hcnE2ulSxCGL}`ehXZlw(bf0<;|l#cmP0RPgyk%UF7}2|!Gpm% zs=xkRsy`{RRDV)rY2a&OA!^MVTnWE-|5d_+e7WVUxP9x3%72xXs=IIK%xpQ1!!lvj z*gw*t29Go1JQxCp3lMgAa7pRyE!-3VW{j66Vis zQu7v*bgqshw@1Il=hCv&R4j^Q1yvF3b1hTw*lDlME0pPzcvAyjA;47~;7^I+tXPcO zV3^kah8!}Dnj}kgNTXuSQfCU%EE|_bF6NH%7Xv+!AWP@)25~#;bCbl$vm#54c*xV^ zd>S`cxmR^Kag%mImik*CA=+ylsJ@rmAo4ZsNvc?xxsjz3?y{@&6faG;aijAOEY(1k z+Tx{V`p{=B@yfK0EOkvs7&@MMla$Nni^?QMgjiELh;Y1hxaT#t?BGc?Ydq_|{}_{> zKI$Ff**>1=zZk2nrTj%()@KIOWHTplO4r}WPZ2ktq?V7OUxI&Ge>?&uy zKU$#brZq7D%k|SeQ!0(sSPDTk>8~ zzCvX$<9d3h8jY+9dn&1Lkct@-9qRk3MqCLDRw|_azf+A-mFl#eIDr`xRn@UZj4Hh{ z!cg(k$eWc?f6xG&Mwwfw`b{&+IR~UuTF26wvr@HT8VMMduH*Ax{FQ3UBDP?-A#Qgk z`;VnB%*y|`3p&0->YSu5bc#d0{tkJB!AhOnQ_|vDrCU6!bc<(|?!vCh@4~LqU0B?u zf|OnsMp>7zO3J^U*oE;qy27i}8SU_|^1n)X-sNf9z;|3Z3wg+Lh`c@ z>cULj;;T4|3mQsFR?c#$PP4e67y=hm{I1c<7uHx$O8vfOjXE~VNXWmz3uO?AK_uT1 z$rBky6*mSQi5_bDd=_1fKz;Bb-c1+YYi4L)YJ5B1b%o5P8unYs3I9JHedBDR3nRKg z{^$<0W81CYXB!^3->UTgmW~(Z5YSD)E&hOiw__+^^&Ex*{8s-T>F7F_TzHJ=e#vmC zH|82O+!+3QE;#1lJsj^*vsr>P=RL*IEu5%;^ZbvUL>Ork*pJ7^E)qp;ba!T>CznEWoY&^ zr(Z22#J>X;;YTXM7sOMcxl|-7IQ(^-%t)MC&-I1h_q1$x_Dyj37ZwnnThC}i_{j^5 z8XgQ*rud&{|Lgpf{K8UpArTZJf~7>zejx=EgU(foh}1ait-1OtjLKD|zD#o{cOiFh zBl$V~W&Wg0#qP#JS{-YH4lT98dSx%c_X?#3Sg&eO33@L0e8>$XxBPmQyoe^odiAEb z#?8}57FX#{t(Tg!mS_F^{4Ux$@z_Y}61Sua#ae8ODQOAS9 zcU^Tsn4u1Q8s0cRvH~jzv7E>fbY#4KTtUUI=Y){wGjNY6MT}j25!qD1js;7ouU1f_ z`tAJp{eMQ@WF^%}X#x-N1y&0?GVA1>m4+w6ZzZ*{O~uVNVx^R*DYF<|lgXF)NhrFC zB*qd;{CnIhtAg9F6U3CZ;mKTx-0>6Qh`_oos=6=JAI3=cL0-!o6Yk5g5gdf@cLioj0xQaOlI zHJo0;>D>Ea;O9wX<k7;L zg+li#wy8HabHTaO%HVCZl+P#E67bAf!kEVY8t_}HtUW^)h(o`HYwV(oF&~` zcxqwzSBkc)j4c%Vuxu*9om-5^i0wh+6eCraZ2BTMuveqSN7z<|lL<12OIdlVQ8oV> zKDU)4)!|6dD;;X$R=U<00tHg4>K(dky+c>fJAx|c9Ws_$Ox6B?+i-_!`~kbH?FdT6 zkby(T5I!)dxo6~_4rcWZ9F7$^z$oAn`K~0ApF zvkVEScx{$GkxJ5L85mGr%&OaJZp;PS$yH2+RnB%JqEt@MX(x~DmrRPRp>?@WbNI>` zPoOTV@>49GqZ}2zgKk8QYOK*qV+@G?S9GbPtf-{TlcN}BkuYa=kdZm+7meE=y9-+@ z(R1Vj;>9G+9Ii!hEU82Lrwn{qe?3ixH*(a794n>_jV&5yau|otQFjBsimMtsje=M; z+sRw2;22*T_UcfE!mKIcMRkmL!ROSSl>LTl_1Vghf(!!Xs9ig)s4r;PcUgX;cNwu& ze)9R1t1m-@!AD6Rt&bqD&~sEWq5hRQFZ!Hi;4nvJ{HL>A2dNa|EawBe7&x7@UMEZr zR@SoqTPKCM3tJyh6XjM+UbsCA4j=qrrdcHeTcW>qf_K)S1Lm8bUsqp=6Wzs_xs$~Zt7X}8&kP)iO5zsUNP zux3-je(ejQZg*!d4r^|3{6QWGetXFZ$)>&P`Gb_hy%J+FmAA$4{6~zR9war*i1C9D z$eV+t216ikV+jCwKl) zV!#kM2dVWB$W_!|OFAGUdrZEOr6v!HFt@oWBg%GckI@Y2;tMC&Rced_YRL*$Fz_VX$xC_09#FTB@mOlUD?hpNv_BxT4A_?BIL+x-eQpw=jIte2vb%@X$z=m?S8EbI za~C&~EF`;eoFdGxK*}Wr2d#JXrLNLKUclScKd=h+!cV*;oFEy$`a;U{Lh7o6dWd)S z38RS|?~@Z8uMNkWzT2VxIAJvNUHC0;ifvWP5vVY7I_K+&2(HQ(I0B?elc`ygwpC95QSUgV;sf>@g zXPIBg0Co6F)`+?clV}U|G{kIX3W5lELggMf&q}E;c`9Jmxcpzs&a<_3%ob8ehU$ zLJb}q>Q=K(8K!gJenyE78F4C?U!DWLqf2>_Yni7moYLKms;5a{TM{_-fG>duB!R;Y zkiaRY3F^1^uiZSXkF@`^Q7iwxzeg;tcEs|{0iHf*crk(DUw6(C)!~d$GWtl+b&}Vl z{^ET^jXy(PA5ja>1V1spIYa86BHrN#eW^?6MMX~bc|3kAf6jfRbM7OR@D%g78Xc7< z+Nacz3w%N4P*NH{qA$*&KGGHCjZZnpb3QMUJyO+vq%tCy|54^M+URo}bz2<82p zrf8#MR9vSAg_`!G*0cuI^BAXa`g2a3mb4#L8DCJV zG!?gjJ~w|ZA631+VAsdr53||Qab9I)e!*B?=n)-(c#;!5st$jl%SNFuIg|FB$?_xg z`@S^doML!zoJx1tW>>g+`%8vuu(D20f)m6m7^twQ{b1Wt50<7w#d4vfI8> z$p@LNUgnOGX?NUtHs`~;hT(MUsZn+Y4aev5ZQo1xjh&8*eR3B4X}soege0p%4~=E+ zQZMQ#=BVuF*jV87Lu0OE^NTqz|7|pII(qk?_nvFMV|)Lc26oqMyMt*m#~rSY4kp2r zaJr5-J{*{H+39-G?ta#qoMN~6=DR0_x?&tDgLB>rbv1FwOpo0z*LAm^w_&$U)al6$ zbM180ADT1P?doB7>j@8b+Zh$-=w=C1O!6|S4J4Lt- zJ9!14Q>=iiNT`#yra83=yS}zNssjyOg>!}%bD4H0FUE4xio5nXoV9NlvF&S2Md)UTDlL z<6;9^3_q7~z3JrLg4nPlbDWD0+gpS4c3WGOU4_BQOL4BAPDcH;k8Wl0p@;A7wo1wq zO~-gMtz$Q1^w!0!su4=xVO7HUuu1L2Y47b~!Q_0VU6rNwvHO0yBcFsE$U2Pn0JxXl1)zJ$KZd7)$ zn+!w1o2n3Vw<^Re z)m;bdZbloeQ+irwL}E=>Pv4lL-BwQ@I=3c=wnh+Zx$3+1FrnR6QadKq!cj&9H;JPj z=JPwwuZz3-GUxkt6hC>eq4REKdJ2G?@lsN;Id?q*QTN=1@h9dYS#SBjg_ zFw1Vfwo9suogV#?H8)lfyi}KBCIeYB>$$Ss3_e)_3hM<2iS=ET-HbX}cEwbk;vuY# zsn0m7HQZF6!p5kP%m0_Kk4LL2wZgTcCbg|Qq44!=7$hFHUV;f5wb1N`xkkh}3%VRjD)AmL@*Frj6 zH{)INtj^Em1lL`sbX?L}a$$8>!*2URUszU*&2`hMu+r61XUpDJt`w*ACN{;eoVsai zN~!KZ*li2+6`J0f#7TeQTx)Iv8u_Ys8`nIyZmQeaZ)$uUZYuLhS8co1jBe4^HPvb+ zV~AE)+Pa22X$I>BC&Swjzi#5%Z4dPNkKA_LExOTZw++>)ig}8QrJIp<8y^vubvl_( z$-S(bUv}HyzOve$t@LP0<$TuO)z9gqWs&nlC)W_WlSjB(-&KLwMMC$G!Z|U|xH9cljlZWGSt}KGt?sT~X`8KTo=NaBxr2Y5dFte? zXR!migNkopi2+JPDQG%cfpXDVbPI*O&%z4S6m>(X$cq-Bo#-^WfkHMi-wnm1K4{cN zmXXZDum+t(SCD)$xj1Tyx}i~MI@*kmqFX3zGZCS9l!C^gOtcN1L|2e}X}LIRggT?) zXbQ?gJJDHmYfBoDZME6Tpm@|14M$VZ29$@cpoggZ2P6t5q0uM{?L_C%9Tc<8W~+yi z&}fu}cA`t@J}Sd7U?bEAjY131<~07CMpscJBXpHfB1%D1P!>9hE+H9xDUKSU&S*HA zf;OY0=mrX5l%Y0ihlZmmXeT<29-^pSjKQKlXf#Tj#h-2HB)Wk@7y@X7IwLPyfR3U| z=st?v!vRn`Gyr)~CfbHBq5CLuFDHT$Q3^^&nP@Ni96dx)`#8=%u776?qtJA;2IZnl z=st@1kSs;rP%4^*)}XWK7OK3T%Z5gw=_nVSMP@FS3w1-OXaU-cE}{FV@&Ur3Q3sfM zIUU0Wl!vaMhbZPC2S(jcDw=|_(C6p|Do+okDH?^QqZMc`x`o2>I5X544M1MBAa6@T zQTzNIe9YclWJbBRh1!h%r&w{m$Sma)gSAcSVl&dc?364aqbaT5%vWD*wq$nxu*GH- z*LDKcIL$)3#b%rbgXK@!%OUumrI(M+Qpw96i)D2HdjtvUWU_!1H;oaQEKi-Krt(XL zO<@u4woKOj&pYEgBvCo6sJ_lLTRFCcs?tl$vaTH*_U+F?RNEzHoEw8atWI9~64O6{ z0q+OJdk)?&;Qi+%W*rZPKq{rJ%xVGI0WFCZGBf|Jm9ElS#!PzkUXB=Lrz7b&X2_mK z#jHsx{Nm@w@3G!KLtO)%s+89|NNvM zjrA1PEq8v#QB}VhCh5DElJuP<{qi@~BK;aFGK9?lmV3c%5TDDf| zB{{Qo>I+#$QeQH(uw|@Mi2boH5v6^$?C8e4rY}OmFh^vY<(%`+hp5R@TyZMCEQ23C zvpMj}OZve6F5YbQYBrmHq+ik2(ifK#ovq%_X36~ZpYnZ6VVJFcAzshlLDq8OvsK(O ztXp2q_bnG?HofrBVtmj~jO@@=$ulv?hrGGhK2+{9HX*RQ#70-A@7xrpydbY~&3uuC z`y-2u_Tuw#eipfwe^}FU?y{WAX~oC<#CBnv`hd`S)#Tog&V&CexsehV|DM;d{_et0 zt?R6WU(T(7A#jnT{IYJr%XS8mKXVx74J|zX8%LNmn*kRJlp4N*8|?{Ss1oYTRNCyB zE6n1~)c8JpfoI-CAYAtJm zG5q&zd3hb)58}NN-e;~e{qq4h$VG8Fgi{7iuJvZKI1D-_E>J!0&~)?#=br1cw`M>^ zsWI!#7FI^ACxSd8Saq8XP1chX4F5eTgEo*Shw*;Y=S%hanbr1Tt-|~t6C+WV@#H#! zr^kO|o%Z|0iQ&J;Is1LQe}wmLc;AEfDi{LiaEbb4dX&x9opTuEvzOX{pSDISdZSs+ z-bgju$c@!V_0o8CquIu{u!Ynd+(`6CiN4(LRMH#G8g2~#JvD8Q~kEE3B_`sH8;+yl=IZid{R~~w2~Z`SUx6}-gn9ItvqAJuxW9Kp1 z#}7>Z$E0xjM4Zmx)C8wLJ|MF(Sf}Hgm2zX7>7SK?_p#gX{wdzC;C=Zvykq$9-Yag$ z`)7Ec@dpdxx8ohdfA{{Wc>f&ljqX#;Z8w8X;mI91eSy<#oQCZPcG`_om;Z}x5ucMoBTm7$BwfPq0J?=+wAGXh|5Qo9a0C}9Hm!nsJigMHKeCV^+%|2NooqxAEJ|vk}h~`_L zFLmZOCQP2{6@34U6;D6l>7n0~=lB2N={NE8Bc7uF_MLE-|LJMaemwnzrv`pc8UNGM zW$|;2P5+lu$<@aX z;Pf+2TXE`rfCdN#E7$y0ludQ{I5gI7QzH(V3Hev*o&>x>z?$s!9ea>~82(=Z?mkGs zUkJF4fZrbsPE5r^IQ=S#!Ku@sV5iyQbQ7oDIPLkD(?8;L3#WrPRmuwvH7L(48+99} z35vI!D;Z};Mg~c(;b{H zVHX25y9|G3{);mP$Eo_0F;;LlOh zKdG1ml|6>j1Dt9*`7rgd;Ha13WIn`cjnfx(@_iauoq7j8OfBJ$6aH^Jl?fsIaWlb# zAy7c1Be6jDKY0F&QTiW6ETh%`kQ;S@?tc`sj8^}nxMj3n6&|}l}46xd~5|Jq0Ii#W{F*8X*209X6=D%#h#Gg0D9~bF2z6Oaw)@i zDgL}qO(bpII{xCVdmt@+Umh;gfCTU_RXXOre~*Y@9&gpwe_~dNzENL0ViCApk{_&9 z{fRb*amp;ph27G2lV}&Jgj2NL7OH-y%-B*3?f>fB4jGLP2`HUA z7O|e<5-n8wG!A?~*RttpQ+HN8SrSc z<24qq`zwT%jU=il{D?btyfjaE!(BujKVueUjj9w!HC#T>ut?cIrTfjYRk7NvtrE0V zvWB&*dE_9=bGEj!wj`D=6ROiI{}+y5~Mx}<@ZS`Tq#*e0js7qXQR zV=+0gUz)KFdp*_SteNZ^C9&I{)jQYkJ!{T&G8B^Y%-81j5GR8QIpG)0{h@pd;KcW4 zCwqNW@``zr27CAq<`Y=9{lQe8CX|3DZAF;zS;Q7&i{O>R%^%FQPU-b7{*hgW=y~SU z{YmzolFnp{-#LIAlQ5#21y#~>ZgtsBHcw<_n2U(88%r*xDozcDxQ ztNTHAo6m33P5er?$MO+!i}cZ%$*FaVjiQ{=0kQ0d-^O107mII`GU-TQo#3X65PaOs z--wIeKu)FKO}6}}MQ^!wP-o8Y7Aod0TUgP6mrYMbIHi$p?S2w-&+O@@U2b`;t#?0} zb&nmXq(T1eJ@brHn%WrX^Z#M)bV^Iw`jvH`U(!(S{U;ktNwfIepKKXLBUn}Y3xl+D z-w=bfA$4jTWQo^fwnyHwx{x#yW2EA9lQwHeie8gz57S=S{QE ziZw=`_vwE)Z(4Xcv5!n%1kzfY*EgcRlLi@#p0_z7#!0(t-YM*8T8W)1W5<#vR89+f zL>;@Ec9IogF?HtMFcvmCBCa~6fnZq=jP-$&y&)Vy8ZXwbJMv4~E7q^-q5P62iuEgnUykE8^};k(UM~raDCv}@hvoFS zc$C(L^~*H)B@GPgS8IN`byLD_YpHW$oDq@elvcwDBcg3oHSVq$o7?u7^}afjTf2u{ zHUHTxq2gT;Q=HOHIN^%OcG4UJORVt zdFX~W;A1e10l#n<1x;8DM#83$2fH^B7J>s{;WP}RFhs$3U~!lUqu~Zv0v?4W;pZ?0 z{tU~&hcFJxWX`g%I4lQiK|Vy|jfa(CXIKUHfmPuvuqI50X|*uS#ZVh&!8$Mp)`v%7 z19%oTgjZlA_y9JACe1K5tn$Xd=CCqk!!K_O$TnME+3tm%vb+Nz8)JEAz$f8*ur1sa zLH@VHupf)3;0gFNJO|supI{>V19pHeM%>vi)>{^Kg$-d3*cm!x9B;wtlcKd>OWa{oz130FHqJ;WRi1 zE`r>y-c^vcp?3!y0uREW@KZPpUWUWr-)R^|VJOO5gI8fi_!>-vufslYG#moQz&GJo zI2E#wn0Fx@2Uo&3;db~IJPf65U4j$gpD-P|X=zS^wcy(@tp$e37&^l#FbPhDsc;$` z2j78H;B>eEz6;mD8SoIC4ZntS;5EqTvbP{FJm$ezI3L!A3dX|)FcH$GP4o7_un3C* za4{SWGvO4t1TKKta0^@p55VQ{C%6Ls0awB>dPA#Vakv_mhihOxxE994b+9vB50l^q zJNN$^7&c=u7jA(o;8u7XegMCL+u+Y|JA43lKo@7N`0^AQr z!CW{E9)MZ!pj@LJ7!JXcFb`gahv9vA1Qwu2_Yo`)kHRMK80-v>!GruEA&Fb@&qe6^?>8VLH48XTdu# z8{UOm;61nx{sljQ58y@k5MGBi2bT=mVR&(V!eWq?ySH+2?td4CMp%Tyr=SUY!ALj= z@&?p978Zf;z@l&qECvt2lJHX)124le@OKyoozZNk3!`8~SRPh|^mtYt83hWNkA=C4`bK!F^3-*SaVIQ~`J`az=7vR^hFT4g{f`7pj z_!teF0k9}!XQ?!AMGS+mcpNhA&f6Ta?UJ_>WCtW~UpN8|ha;gEz6Phm*I_0c4cEXi za2p&84?}h;@qPi*;E&J?@4DaSM$6ExhgK=;@Yy?>#;(ZEk zhP_}K%LBaqFl=|&Ca#7|?e^}3yWvr|2Yw6p!&@*H+G44}pa~Dca_|VO3qOLb;8EBO z9)n5nI2;a7z;W;td^eW+|1^drSe$`t;ioVcehJUOui$s^9Q+NQhmJB-Ft9Yd2;bR97vT?Z47>)X!Rv4l{28t)lSbnb!#*r-!B60AcoF^vuR}IN^V;KRL_!a| z598pU@NxJTYz`m5j_@IT4%(d5ACQewyknsQz6045#H(NkT%Cr2_tM@EAR8=r4?%WD z@O}>2^1youvR{Gs7G!e*??cFYes7_&G$LVT$bxxqbI1yKZ#T$#cJCm_N_4LmvXtCA zAF}-0y8*J++j|hQfZCh(83vY1d%uS)arWMXWnd`d{H*i!mV{+t9mu*{Z(CR%J`XFv zS0Jldy;C7eSG`Li>r}nlA*)TjCty{09_Ca^tZ6_2+!WOa%+6~@DHkkusKIj|*M2bqZP-2<8L?mYpS+w46L6X6Zm0Xi#C z;lUEHtCRb`8ir@Ecmh5PlVMLd683@<;B#;Wd;ujU1dqUEcmeiRZ(#vA5yrxF zSPM>p@o*~a4Bv&xkZ%TiM?k(1?41He}N16{SRCO3sk0tf)(IW zSRZD=HZU9ZfXm>Ea5)?aSHQR68aNlOh3nutme-eXH zl_nD`3O|9B;3?P;o`$X98TcIh0uF{>!Z+Yoa56j#--GAjHh2LZhZo@`_$|B#FF~`K z&GsEEn}*>shDPvv*b!cVDewn47XAol!JptNcopu2*Wjn{I=l*hhX24DFseGeWmpyd z3gh8T*aO~zsqi*Tn}Fdr3=81za3j0}^Wa_h4ZH_$!9So;gBlRVz(3*R@Gsa7K7cR4 zhj0}98%~4&z%2L(?tr!s8oSUQ!u@{%g9D3SpcDQHLttc0y4SEGbi=0bG1vhzy5W5u zns6YDgkvG2;ofPm5S$MS!(}iE?t;bPaTpE1fh9t?|9`|#5{utpEOgeQ284xS9E^o! zVFOqZwuP18v#>IJ308q)VGTG7)`Y8IEw~rfhM&SZ@O$_;{2kU!!|(`0Ll{|`?lmj} zo5DJ<8BBl)uq$i{UxcmTP}mwyg6-gZ_!L|PpN9KjNB9Zs1TVs8;7!;KK7wgIF+|p( zrh{eR^RNMY0Vcw}@I{yeN5f<|6}|`;!k6Gm*dOkI1K<&u3crFw;7@QU{09z$MINX3 z3#&iQ{XYsrGb~<(9pGy)1-=g7fTQ7TI1Vm{Z^94Ycz6s>fZxK2@GeY;d;rom3C6*< zVM90>wu4h(PdF8()aCwv7sIPq%z%^NY&ajzfvcc`IdB2|2rh&d;Uah!E{0}3YDicL zX2BXT8@7fkVRy*qM!fytYB&zAfpgL@ti`Ynz7O}njqn8A1iylt;jeHTd<3_L*wV|^ zrv`*=;C}48!(4ukhKKn*6CQ(E@HqB|;3@bc{2cpx@C$yYMK_=ihed685hlQIaY%tz z;AD6Wdj+radpEqv?=z6mc<*I+2m8>5)CaIKWK7uG2tML>Zx|BFvjOr7#XAwY;T#wd z%Kg6rLjf$d!9wsbEDXPZ#o&*yIJ^gApsNuZW5Z%F4pxR`VIx=$c7l~)608h|!|HH6 ztN}A%O}GX=9-2nQfT1oH$6!PF4QvFj!=~^7YzD&{)AfSIU<+6iwt_8SYuE|4gGuly zI2?9><6%db0lUIw@EN!jc1y!>3`0-&4eSN4!{?yA3AZ6E1pC6WFbOt>De!674?YK9 zhA+eZ@J%=v&VZ@#JvaoegG1o~I1+ve(_X=F8N(>}D|{7(K0(6+7KLMBMfetM3MIjb z&PgSFBye2Ae1+z&g!T-X;LfP>*d_&PiUC&N5A2Ofr5@JOgFeLrLpU3yGB4Hno4 zGJ7k%8~g?igx|tR@CxBF;14iu35Fjrtc5?pUGOSA46ng2AhTY)-$AChcz=b=Sef*E z0__Gk65fY1;6HF33^8nzj=;y@FEG+zAOf-g)*I21+Z>jFg$?fiN*JQBs0)k0R!uc=;E`z1uCRiHofwAxeECauSaqtQ(3va`62KWEp7|LVe zZbgpnXn#wAJ&KaU<3FuYzV)Gjo>ZV zG!4T;49%dkH5Ckuf-PW47!NDL1lS0+gipg(um@}nUxaPo5cnh<1KYxM*zW&O_9oy_ z71`f^-@Z4!q|=Zlfe=E-hHSC~MMMQm1Q9fBipoyH8X!PeR8*AUxS%2s#T*qB7|}rm zgc&ucsNmoTiUMwc0~iow89+c(RFL;`?!BEf^FF`d|NZBAzB$!Zr%s(ZwcM(@b*rHB zpgo`qp*KQbhTa7IJ9K6Nj`wi%gl>ZNf_@3@4c!av13d!m3;h{-Gt_fEJs30r+7Frn zy%m}by$#wLdOP$gXn$x|=m2PM=s@To=pg9m>uLXkaZJHu2=qSaQ0Sx3VbBH8Lg*4` z5%e|aaA+lT1oT7bNa$zKQP7>x(a`UqW1uIX#n9iOW1&VjdPZoN9E3fO0i#>xO>M)s z8-H7MS=caI%j=hiFP9%K4|lkvBcWG=PC(t)f~&v{;Bt@)?x?(>UHDgD<+y9Y^W*Ba z#b*%60^>jzaGBK358oui^TPvY&gDU(fAxAewA4%Iu#xr*c7wAZ@gtsAperZ=4}v$q z7H|NZ1DXG#0)dfW23Q8xfn&h>n92tVzznbeYy`VM#?*mLLbO(iCI(P=G2HU`4 z5cm>hKpvRcpMTT99Iza$2fM);koXm*1KmL(C6)4k(cC)~j|+Rb@_7-UA)jO7rIYx~4UB2lk; z?w+L2xJx$vs#IrZbPwW0KjP*|>Va8i=9#IHmL|_|JX%5PLR-t8KJh7a7Tt)OzW^vB z?Ik)f6yJ2fCs^HupaE(xh8+E{Z(0I!b$Hy zLq8O2MUD-){vjP6O~PWRQ&8c7N)bP{(D@0``O!u zqZFF|;=K}5^o#c|h9L)k@iv8ofA!vCm{Rnsx2LxvK}EMTHp`x0y*ZVpH{rb57&*n1 zJx_kmW`>qp)pQ&2S*prN{ImJ}jbxqmE;iz2!&wrFms4lGDSVF;{0+~WdbL z|M0fgIDJkNXB~08A6_H(7kfL$TtC$AoVUJFB|Xo1+n80?cw}oMZ*M!DbKYkDIh6nE z&K|q`G1}s8p}Ljb&wFz%dk@Fe4BU0&RMdoNWU!Bv8)omBbX;Wv`FY~UKg$L~Y4T+w zpfv5W@lcv@*#s!fwd@`!8rgN$AT^ zO?)}@G{0YQ>Dw-S7kUPN&HK-?(liGJoif*J{B%E7{%?ea2|W)@g8m83fL?&MfvWVj zP{UwV$^G39YVtb|YRM?e)H;$CXQt%`@KtFEP?Z*jsJ%pC8kYh>;?Z-dk}cx$v=s7BMR7#i&|>ESce%nzxIy5C1u`%KHI;wU@w z7O!`8XBir{IQP9jA8+Oc&4ig&B60Ye4Ng*jtX<>>;&6b1&IQj8;BX1w~ z{?y(wIl;{F_l0ZZ0z(!in3tI9;1SYRW*i9Am&8FBB;l&K?ot>wb0Z~eN^m+LXS3}n zSsLbWp=Rs-TtfA;KUsE$&FV|-n$|5K+fMs%RGY#^D zLtd$EHsu$0Pvk_tixEz*iExe)<@m!yGcocu+bNk4|^*sp~5bC8B9RG~F+T zyq;)A?@;e6KWoUXgdBa=kcYshmoN@||R=-KZ%trol98q-v7CWjFFZ|bO$ zQ6uP%bO>VMgEDo@j7V&hINN&`lB&IxTN{s^K#FXsgMQH{8m88>!;&h7$5|CgW;^co zy&?%q+=eAyd(MzyNoMqE-&bBCB;j^KDqT&vEUs34IhkZOamN#VB|RCQ{_y-W%2WN7 zST#>MJpKXjY$b(vlVehdt4qj0LjFxio4PR}cWcNXLJkq~V%?aMJ3>gpU_yS1rkGX5 zqpnRoGdhClD?{qRGX$OsQJx`HwK%Iimgj4D{6pahEi~jpJu^Lmqq+u!FjcXv8OHJX z#nLkcBX@8^n_x&S=wg|bLM1Jh^gno5uTL>8Z?Q){9~oCKPD`v<_N7p0_NU#+Ep4=X_Deoo^p5rk9~L>mTMo^uLAU{Z97A>S^aGM2)<}ecQPWs7lk^ zB(y4NJsxXcmyzDJHvJ_1Z9Tkxc3HAvQ7gdGz-$v~y0}I;&FNU#(7W;Vo_IBa98Vo1_`+kZo`md}R+#yHsyznmQu z#v+rZ6_pUKeA1I>!J1@$sDsAvtZ$L^Hge~dV2$7pzky;vRQ$*^0h9w&I zc}#L@3go^J&TuZPSOG(w8<*ACN}u`TJo0CPZtd+HmrI{eHv@|d$0FY>GvwL~^M-0$ zJwZsq2trP|5@gN3T1m1s!;F}C$!m%189$d{Ugkcd=wC9CHIf){FVVkb#-#)hP4k;-U7(%IFfcH>%l+W3yFm^NMxkADn2&58YPR*c-ZY(k0&xq^^3*)bt^ zYsgcKU-JoxnZM{WIXZvoPICHu{xRF^X}&tgsJu4E9N@DbtP7i)lTCdb)^1@QF?r}! z{?Wo@ILXtca%wB{c_ZjNL<|ld?0Y+7?UrrK!>0DD_C?pZxn@I?zEpo*VbWnb-b>V5 zyT%XHTYEyAJFzX^+WWO>i#MH}<6WlSbZfF$z3H+lceFJhHBH)o<%lcH^Hz}hjm`8P zW&0qi8CRR_Oe%EcKdv_WdQC0SN&jMwmDve@EwT&$Dvzb5h8?B7|oy&13qc6`gMnLPpSKus2Wa!=!bOrrE zDVPJ6fsJ4{I13W@vP1z2z%(!itOlFFF<^biz!KzvkzmGmp7EX~IM#wHa26z1!34U3 z!C*R=4_1Rs;0#FEheDt$CcaSzdXMlhnFNL{oPaZ_aPIF z(>`a!#9;2)R6YeNog1I*`zHa*{PNh``0U6szf-NF{YwXVZ*IJPo4yN@+975jP>N)2 z;o7@&knp_tt8^Zg*nrO=2G2w4Mx-_l$er`z8$}v3A28t4?y?T_Dly*l>zyv~mT{G2 zsk_Q?^9V?hbMxW@Va6xbgN_N(H-|&&o6V0;kWCHwSS@dUe6lqAoNI0h)wMh)7?xS{ z9H#?glW-+OS) zv3+uhbWII%&DoQfhm}HKyF_{5NsQi(X^@&nV?aDt+varpsde)6lkqvee`z5lN~5RZ zTZEUz^2^E$OfxbA!84wUPpEZGjNPWTmAM(gda{B5S$<qt7<2fcxMr+xCmg7|m5)R}=#$FK4>4phch#D8dc$5>)|~G%Tq1+9-KFccp$tyE?Pkgg@A@0a#=+q{Ocpl;ll8!4kIato!Xl{(VPmH@X#y#J0KR=8S(WdwO zVc9$^oJ7id)Z@T={zNHlMG@A2A6MhTaAN9+n6^HCLW$jhXw4oWJqyDr7X?qf>vB6- zd!!L^AHfJ-b5kJ6KDlXxtSqF6M+i46b2nlkqsb9+u#hslv8<-dblGEseUWbZIRFsjk1;o%(rjZ~vf z4>L|_Wc9#r)Cl};!f)u~T){pf9Gzx%lU;-)6cF;_<4!8F@;pn@86(5d30*hoIg;2t z;n_p%yGDjD@$PwC8hk*_T{|)y9cz*>Yze(!>o><0mGvj0(pJWZ8Z`=0PtyP1#UL+c z45&R{wErz6H`@EX9%pj3{HSn&_w>D$*NqN0FuWhls2n;b{Ho!7WM*aj*zgq7B$Jgh zOTru{YGG65K*x zTm{a8^+u zZ0?XVJlS?%*fI_|!;_Pa+n%B3jqqFELmt_i#Jr@CAJRXI=j)vH!GPUo>SN)M}?FE!<1 z=N#t4(&}$?1&76`K;6UkoI0I75uO>uy9>TEZamdm)jO;+VdXp};S`&5HJsX8{w3Sd zKvU2;@nKn75x&7#D@Q7@_d0ZaBU|c7xOLzEDwwNUwiDfQBA>Y&s*h@ZBzD%lR>nRaiZ$Xd7GU?OqiPYs2qQmk~=DK&k-}y zq$Z}e+@oS_U{u}bxo~o1aZH%bxsP6Kh_|1kc;3elA2gBu&xNytAGrJtWM2!aQp}ur ztqfQQ^9L|jHIWAvhFe6cqRgm_Y|k-gL1NoNEOgAV(8+~Z=unIjn#E%hUPK`^Y+9qY z8t$0ntM}m;Z!J>1YgSL!%G>bx)}uwBne1Q0C@;{g#{RH-j>jyE9JiN6jN>xkc_cT9 z;naF_T$X<0O(XQwpM3wkEt6C2);}M%(vQcK)P$mGBZ}eGx~9c)TuW5rusouKr4eS- zFVMz6jghX!aNKGCg&KCi4b#HaVmL0dSo(+@iHV|h4RJ4oZ=u=5Ehdv2$m9dfrS)Pm z`2aii)pXHjb0Q{_C!DpP!*mO>dU3dZWJwIO=JSMesQSspltpDsm|FLQz2+0AjpT&A z8 zsq`sfNoTEGv6Os%NIsXhkfBSdQp;o5;r9IKRHM~P5p~U_HF~H%KT6Sy^g}DCdx<>% zTjO=B%c7cSmHLr`5-9lRV!YKLKgvqh4~-wC=U>B3y;e)9_e{9JU7ueon~CE4CrY(x zDX0G$ZV}gpx9Hq~`wVMi+C@bYc=ywlu?53;PlX+JUc*XW4A&2@*54#yYanf(!$0pD zD%Oe@!wJE&(Lm|@EZssG-GZ!t33H#6ePji~iXQ#{G6uo7w~|%QvcQ)2TsYBLBP&qv zUs}mt^)7pk5r%V!+FDt;42?IUadvC@W?8s}ncdoyj63xRwU?+5kG8(paHnj;$zaXP zi*8udVy7hX7LTC$8g?WmOwD%6G21CeS)`zB`W&_uWYSr;gQ0tyn#^lsLDd0nckR>0enfhPIL}QNMv2@<#5EClq;(il3nr<;r@S-)Zn(JJf0rFK+7@e;IpOIX^?5p>@iZ*TU`HWs9{E zTtSg;CT87sZjsIkCZ@?PD=5;s?WEC*;RcbOMPn!SEOORWRM;<4z9QVITEy3g@O^@a z7u(67E5co?hj2YsBKuPURz+o>4^my`)eNWC%6stmw!rgtJNaQH_J7;uRdbM*=U2I8 zRrspv#73=xpU+HuTiVIoRpGAfox_E6{HdewtKGwe3NkbDhBp@+L`vi-d$MH0dRC+-yK0)ljQx^!@a!6lPYVi4!6=JD_)zG)cg(~Qc_Z-?1163VK4=bi9SulJ4Y$_DR+|1`YEb1EBr5I*7c z@+go05J^={DhGZTe#`I%npM`>sF5CMUOD%p@I=GAyhY`o{|eXhdfT+DthYHl&g;!? zUHQPL>PX71Jn>oh1w-4!+^ykvyg#?Cym6a)PzjE1M=s@e^%vp$y_Cy4UxeESonkON zA?JwsgfE#&U~cEA^{!ur+j%kSJzv7eQ{P4QYDP%re!%0^ulGebT&*xuE}) z**swp951bQr{DP}dF^`pDKip@dTED-U=IGj`;?jQW^JKtIK`V8-g)|tA@e_{%*)*~ z^>{b?`K|Hwq~mEb!T&T_&slTPtX=hqHtq)zt12x#Z9W=w($fn&CZEui=by|1Q)SQl z$y{oxkVzMqjTf9T8@A}CD=z$Hg6`zD5KIS4z*?{c902Ezt;wHgP?-{*P6#FY2cu2- zTX9b}4K1}A@uR1ULTScFPv2+%e^&p?sU0CbzKuQWPk$ClN#%3{+Yoqoih%Z) zTDLxW`g|xOvep%-zB(ZINQw+j=gu=iiIJaU!hF%N=%$Ar@{$qC@ee_{M=IIAXM`?^ z;IOre+WuemQP7g<4O!eqG+9qobB=8nHyqlY}$?wg%ra$J@_6cOa?Fxj*ImFBu4*F9Q{9W^#4TlPcuG|;}GvBoDVhJY@~GPa5Ee4 zi*$T8NJ1k?Xu=0^^3NcK!cme2UUb|d;! zIJ}Wt2H!JURA=R2JSprag@@K(v^_Ppf9#5NXst3R6iS`>u)Di#HdLR4k3yS5S%@ra z4%O{=mqPWhmt5#vXnQyOYM16g%kjSf`Xsa$lpRZD1E3Yqkx)JCWeim1jfFnP?|b-= z!9MKeNtfXnmoA3B0K>~rHb|7Mf-Z%=2j$gn*)Hgd(4V0%%M}TsNi&@W&Q&K`Kl!^H z=+1imI{<4U^dMB%;}1hMPsgCwLiLQ11<+H_h0xQ`B~U$M^luVVeW6@I!${t1gOp=aJrk!P7pvhi7U}2k*eJBa*zMfP9o`N=jQWEx|Bs`To z>HNm9_TeP#E3gkISpm()e-*Sb^i8N9RXscWt zn8z;O-=J;z{ku!arTv@Sc`nC41Z^jMYlU_Mojz5sO)8oZOq$t=(0KBn2i2Y+AF6Ln zxw~=KnCL2fX5){$51`esU22|tS2UT<354{Xp2E7V83z`T03$!ovA!vW79&<7dIvY9*`Y2SJ+GEf+ zp^rn?LFYjK34H?k33MKG8$e2rN2Yu>z&FIGwH+E}cVzV3zpselJfaK_9k=~=3I8{_Zap+b?Ysl3cHRk9 zJMV(3oxg=59(oJ(0CXVqAapqN5OgZ^F!Vv_ z5$MyZ^c0kWu@6}ZqWn+%ZVx>J?PLt1>&4L(k6)m? zILcfMKf@)8m39X0xY`ME$ z=t@(c!uIDJY-O@!TfI>IfzgRZAGnjLd+k60Cfk8#oNC6Qlwg|ADzK8ugXj})p653R=&)xG9O@;())U|u4L|m?GM<_ z61sR_^?c)ZQ|{bnX8Sq5!RNj2zk|Ld=n77B@NxJlJr{qs6i?DVR$rA>;lW`HJddDm zxQ@9(gmcB*es=UFImZDPKFL*>&EDlT$Bg}EGQQln(x_pxilu!Z-<`x-n>4rJXu=?neBYQe(>ahMr3cM~V3%lA$=c1*^|{W0JTGZ{dk{rD%*BsI6`A}a8w=BZVD1?8 z($vC;OV$BtipPtDwSs?l#B6SAb;iLBnn&@b zhE`sA)O^!0DS7$vKW1}plbLejD4$WZJ7%6Sv3cdC$4ySeRsF`FFh`l1?2pUYESNik zJE+f`Ff(tSl1+O2bqCFUq@99(pcs^a1z-hO4|alcAo(Qi9u$BQ@E}+Q)`721mghgG zudRKIaC~bz>xW50<-z))WFH-oZ)<0Hp?;{fxs}h4^qVAi{?kP+Ne$)ru7{&lzVu2B zHS$6yriQ9$?rpXhbM*g$XU?WSSN4u6oiLRaXjK&ul%evQ9(m9;1$x1BfhDGEk5aQ6~R$mQ4#IgDf_&&GUR0M zP<`3fLpPK6;k%Q;b-dAK>icBWDOSU1*}kIFTn%~3pKhvy``tDeyJYfdHWTfVa)+#O zh;B`<=o)9qvC}M@y?WY7GP=gFOCme;_Trxi`!ps@)!8MTe)8u854+y=xSf|5tTTRM zO9~q@-=z27{S#TDo%>Gw#O>Ta`LiN8F3M7>Z12siJ5|46NsXA108M^A*opk#i8N^s z8xiN6@pmw0%139&+bpF0aE6;X&-j~X;jpFYVafVkzOrt zbbdWkdj3j`2i0uExa(Jct1yoLHO6_3@enauob^i6v;MY09Ci%%YM0#&=t^ds^|x@F z@=RHImM9Msh5hcbL!;pM-=hrqjVO;0WiC-3`OP2Qu0B(~){xnR%p>GNY)H@F33-%| z`Gnl{yFa=gX{Kz@kd<_^LWp*=Zi~|95$$HRzq|E&`}$@n`@?UUG>OVb{_x-Jd&?JC zWNGEDTpS-LH-b*ZGCXIU`%4QF0t-y4N9FekfrExg5y_{u0*?kA(;J?S&Zh0s+JSaK z$GFvg>($ROpTYNV_U7)yMEo54RQna;=bd}jxi@%qVj$5w&;7BRAExH_$Hc%Dre?4A z2DR7Z3ZYD-!2VJJ>M z3s`g)h1+w80?({gEiWUhGhA)NRv3})zSzb%Zze6ZW_-=ZH z%nY*X%C_%}gb2T?C2LoZYA@gN)$y#f09{~}kw8CH^aCTuJlv5&mtDI`?LktdZQX<$ zj9T(i72-J-%=cHsZ>=(-3#7FqypND1LS7-{%6-OFa8FjhWc=R5Z{a?2h~pwXxFb+= z$Oe`-S&1thW?3@5Q6O2Ctnk(3spo#g)J2Rn+myTZQ$RTW|BGq$J!0x1raxlR3K^`G zeotQcRV_;kJIz)}W@lpGa|ew?)^x)^7#XroJv#hgBvc$Q5`q)mSoLIkW+15|D-e)e z{3Ca`{%Scb!Za!W!MF)qJbQrDQ%HTpqo(}x0JgwUov@ZkLuZXN@t|Rel@nm+D5K_lmi`bhf472vs}v}97zNP7mMcS5dU35f4_J<;%JHU9s~S^Z$bV~$ESxk}GN z*fQ`v8Ya2H|5xVr{6OYXQOSJV6#pS3J%Xb;b6SIDNYSlcwmBWbcG0i~GPxa#^MglP z?fn&c`nso=6LB&Z8_<weUu_QamD?TUt53M~Tqu z7wLSPw}B+IvJ%W*zj$Qv$DwqYzmbW5M|PJRT)OgGC?!t2j$A2fWu@U08OEo}&a>bV z+0e?$Nq7uN*;EHDN;&l_^I@~K6$wYZ>{6C}qj?IPY+|viWHjB)Nv>1o`|nvBeKo>f zX-zI4N7yaDdF0F1R`lD)N2G2WLgovvsQx#HvU&JYPBA+V$yYF{A#~ zQ+ds;)|*CG31)yLU@h1J4gkGcqdsT{3P1^X5G(`hKovL(nxR@Am=5NH z)w1vA_{%HK7@7VTc%9vXm(xwp7?+spVCb{Yn519RWI*~l#Qy4{0SQiWK2*`yI+L^^ zE06uPg}%(1B&QsoHQI!A#S=NdIC2~^`4xm`HShnsA^)z!%0j`f)V)bE;8!EeG{Kn|u+#8Ov8dT2? zV%K?^bnMJ9F7G#^y)zoED|3D`lKs56^ZoTLjz{>75f2W#{zrS|QtA5(qqUPrHA-ds z-}tgD`FA5R&gPT+6g@0qgTJHkg538zPt+yIs$Yq$-;sr*T9%G@Cfmmp*k4*rt~sT^ zn5>_rr$PGuNg4O~1O0ouF;#!OEOdS1D_P>cmb>b6qAP9XR3au$Y}Y3(GHDYx`4(N zjF{ed`=V_v+7CoK#dVYbUBR1a-VK(ib?Q6I`%%!T2Zm>bWPQz-#_Qv}hfRzuulc-3 zf=;##Pi?)CDp}U}y@yOqVPU}AQ_pj=|8n`iiSFkBI0x#}OXq?DFcQoF^pBp^U=yhN zy*z)fJwe-scCFu~m(mHEI{vo_+8`dG+leqt`36~85ggTJqN^8o>F6?5YAy8ojJss% zAS=WFuEQcTe_`9y?m>(M?vkEEtS-hjX*HOq3ong)dyyA2iP<{K@#Y3(7 zk?&(tRx{i!3N?_Dvpm0@vHCVSHH=igA(b_x!i4IQ2#)Ghv}d_j`W7;Dg8WPu zQdMLIaF-V{RJoTgyzG$32rDI>^Bz6jsoExX{MePD=2T7Z6{CnX%g%eBN6xvUBP__jF~)XV~chL(~+U=jmgt}rZ%W~qpUrqwuDKet>z~6 zy>j7bi^~tSqHY~SnAV}!i>>WJr*sYGw7S`#a?x0;#4y$Bq4Cz!CZ?-=alFOU%TZAe ztg`1rEhktry!Wk_iS^?fh)#!wuX4MO{^)X+ZXw|hrZ=D?=m$!`gWwsk8f*ep;2cOk zM;8OSgOOkcSO8Xl^VxCAt^n4SZk?6TN zJ(wo9H4N5?@XOXs>#?eMx$H|1rWlt?dBb2DWTitkH)Nyf<#L2ysh7t*@pQ#cqv{jv za!Ds@I5v2SYY4VJy8wCRf8(%VlNpadU zw3Akif+?x(Vif4h*i9ACw%bl-!6~JUg4RVmeOx8=QQA({D9;jjki0J=7~N&QQVupk zyGpccd7jxsMzC!VhohaeZJ}!f8Nr0qD`FDw<0h^Tfh#oel#7C+x@jM9g{FIPa8xa| z-4z$Bl9h=nYf)tps@#+r%!=T!Rna~Le)4f&CI!?^o`vY?>D7afdxrJ8zAGHjo~a!R zR{v$RE)-jh(TuGB3ciJbmIgcaYD+Nb^vH@a)uUPH_cr>C_|qf*$O>K(#NnDMtCf`$ z?o#B4&}!dajBHY9AEV{>>P>~dMN+OKt;D(?&!?P~7~)9k9x z8BIAuFEp8fo+tl(K)GWBvR2yEv zF|%13O7f>IJ3yst2-<<}pb$(4^TBek9()Ck0X>$mK4=NLg8rZsEC4IOSKt^(X4gx0gI&@3}xH-jYsS9gG;SmpLtiuSRE01+D1G--B%h zp<`MFFA3wYYkqgRNIq$zzH==v`%K1m!qfV08dsMB&e8M!+;tRo4Ij}c8BXU~< z<)`pLOES{kPED!?@F8A8sg>-{;NaHm;T%6(%F35ICM8)%BzLkEPq|z(nW1|o9K8t` zKiP_&o|hqOCNoyaBBYp*e^0ie57!JyonqzG%_d|LXBMdCJX1$a8`fh&(HJob&FIU= z44DO=KL@_qNO)~ZjD#a9fwRbc^I|3R8#R4e>_ad^`c7qm>=O8vyL__r91CPIXGCSl z26+5U;Q5eL><{3(Pb1e&@u|W`KY<Ak=SLtnMR2h*$prsg{B4lCc(Ob)w)@fCTJ z$JIxb-l{(6D1WFAO31Z$;?R`zgi3!IxhIjzFYmM-G6r_+q_*ISfG!Tzm99bzG!4uF zE5Jsu8=L`LpzUc4I)Z+n1Uv|qfpy?3a111RW#0xPV@;nnM#aC_jIfoLl&9NClYd!_ z%+q}8GbzLSUPZ`TU-H6cqO|ws& zn$KzPzENP1!!A1A-^I1tY-p?Yk5$R}0Aaz`p#CHyHBcv*{ z@Pe)K9&vnMpu&I-^24WAlgNM$7rzquLyedcyxP@>pJR2a(H1K@LfR@zw~+3er2DKJ zSNiU%)j*DJv6{J~)UA^G89Z;n^JbK1pTBlP8TlFdJKy$fm2&0z5?$`U%F#hK?9#)~ zKC>c`sF(JU+Q`qz_Se`;an3o?Mwi>pIcK!!>KeYf>{L1;6tEZU&q-uEOHcDZXFd9y zlYz~jTOr4NxdgUaiIGR$G&Q68gm?J{Y_<8;oMz&F|5mF`e)FrNRmG_i4CJeeXqr6+ zVVulNs3AJtj+|v39ey1HX*Y3BhUk*X;jPTMK8Oj^PWPO1UP}FKR%Ya?&Nb=iIPqNU z2d-P?iEWhISJ>*7&hpka%Iy}HUk#-E=bcIIc{%lfFT*(Rybvi}!nU0Ax|ZtfI4Rza z7SWi|QQCRA?>RJFq+uIfsZs3_$DyB%Myi!rucTdic3)egsAhtv^y%$ZcAfP68hD$e;s7vKky5y8;xq|7vzZxw|w)v$|tZ!=67{i?FS>Qf7%V&c{u(l8^#7Q zj6a=>t=I2a{5w7tGY zA)J)~aqbYURLk!C48^fzkzi_@>2OVml)% z{AqDbY$p~^i)-pIsI!^vw2uQ?pB)IqHMf7WjGZE7UsFpj$gE`?r?d!nT^^p*HLR#) z+Js3XM|n66eKV^!%a{2RygZG+{n~1f9?Lg%+TA6ikg4USwc!Hay!(^l)sQ-JCrayY ztVSBO*Ed$Zfw58T;VTP-%Bv6Y*s!~b?k=4)cH%UGZPBV%YB7;>2&U!)k;%*1YUb@})aowGLSge2pA;YjtNh?q0a# zGSw~H`?5wp>=!U;7r)f61TX z(^^l|p*yX5SI4Ss7YSj?u8Rh-VRlJe=7j0$J@HrVv|7}8vqw#>OLF{=?xcBizOlx? zzT@9$m(?gz;QDJCI{&^P#&T*%;Vvtn#W-#k74zs#HQCe=F||l}R`0SJ*0FjzVY+QI z%aOZxm({w?qcQ&3ZhGHZy=aaTzNI_fLB0RYW#QBzZVq_;TPu28(N@_5k8dYDS-r&f zZyHUsFYobh0xIe6vwO*ue_PQ{t$E-Okg$swxxE~PWN8qo7yfNUOuVG_uN=_ccej<~ zy{4DU{mzOmDr}XvcO&v!Vvg)3`*-uS9O+8XrHQjtqdcn2Sh7&wQrz*y*!bm6**piA$QpkXeg^ z?=j9^vay!@74>$r(KEhwnpEzMG0s7Fe7i}pxVO~$&T3&6_jdDl_jlxPYVV8lx9>aH z_rSiWx5QV)nC#Xn0`?Mcu(#Y_WwnSLbkmIXi-xl&!=5x4QZz8$`EtyVSp(xa`e7d( ziXo}{tV<(9`_$ABeHs~3e!$|GiGAdHvKyw2LHj{N9^J<}?N-^okGy_I`e$4YDIcX* zNUZk9N&WrAjQXoS+FWjzqSZW{Z}N5WEe_7F=bc~soL`^qw{jwF`#NfA z(%L`WF2?s(N-EFK>Yi^3C9A>Od~avVu`RL3_g1Ise)@^;QL_p)A91D0XK8s`Tp$=t*pv-lV-(Zfr1S%ul=^=`;gl3jomRr>44Q;K z3J~@KGt7kTR=m9P1J6QJw*O$|q_V1AZESrd87)lieAr>7*{24w5lfx=STtp+I<>bW z;T=}}hL~wJ9n0@jtJ=5J6sMLK%!e@5YqvVy+68G>Xv&^lR%7|?kQIvL-c}P<+YU?r z*6NMPMjggv`!U&)+hp!xYl{DS-0$C}hkALlq}dU69q2FJBpq(YEfX)0y7oqHtOD<%-cQ$xo8mp#`^^X9ZZo`R`pCCN+%G|=y%?-E*^B7M zym2Ll_nn(72U>BTc)b+Gs)lhlN~u52^1gpt<(>Yxzk5x!weuCs?Hp^}J)VOYKh&o* zf3x#!;;Di(^D@~3{lGLZ2P^~Yz)o-yBvTn%g6^OY%mK^5HgFj5&dSpmA$1dG5r@D(@<5`6|&bQxTJg&;5+tNg2%eM!DDu%C(QuU7_|`)+`}#dXr8L!d>Z#dUPa$kukLePmtf`voI= zi0*4D`-+i$U0K?JF>zgI9K7>uYUYm}0ued)H8-HlZ)!QSp}LZFmBZzbB8SX^M9Qys z646nHCRSJ0Toq^Pg!@JVBgS zh213F5uJLV)1}>|eaAqPxJyyc5aU}8q**eAuNYc>>#Z%58hgW1_;-%kVFxWkd?~{% zU3+p3MW3)YfNx)B%rd_xFLvx#q?>wD23K?nq(mmFJWZE;sBS4Tq!U)3>3VC{Rjm|x zqEmpEBQf6O6z>h40==7r@qqkrZJ?I-haNI<4`pG0GSE$WL!(Qg%%FRLR()VcY%; z9^4JDBdnDh7A+s%YFYQKyLz`=_TKE3AB$q16Q4gJZHtm~?G#|^7U1wM(mn}>;^qNNy|Pp zF}1!sF(tPfw(jGGX%w}m9VJ6by3u@h#l+KEhz9Y>WUVpKv9vR&v%P_azo&MZ?6h8kb>^i==t3Pxrp2VzYleMAKWTOy9b&?KDgD1 ztBp-{OP9V==Lzp&bM1GOR!S=IoBB+Pg;}VleJB{; ztpjB4E^oGMDnQh&18VH5qF7;EX15T*G+y#oS%~Sy)=loZ*!`*&32QqeMpEIns0M7 zA!91fiON2KNSy5@eYJj!e8NhU>GUd6_JkGP)Y46^>Pu`2&v!T)`~07^n##Pss2TN& zs+l8g=UOS=99B*q^VgHYx%&MDEhjQ{>^-A2A5mN8$SfF*9C>ywyLNKqZHMfdYo(>; z#LOk{bmM3>&f#!;_V&aE>v9egAWt@C(pH}%`SYwCoOM`s3+jCu6Gn$fn4aA49_ZIi_T7RBs13ePhqxtGK9wc$%-{V@r1e{- zkHQ?#4;D(=w=c@_#D!Wp>@KUm9)we+l?NmGvgvWP2}%02+BtIVv(+mR$hj3BwDEOv zd7e)HZhoVx z2lq$nvHxA_=Ke@6MCvvCv+XzQ4pwqvUaxhN`~mP3!80$)v*8Yserf1_i@ z`V*J^f5=d$fruTB*fGeqlipy|PL{HPe9AVaNLKw$7rMH3LTmR84^@T;{t-mDr--fU zV)d>bI}{B<)JQ^>M@5z2S-YuRS{_pi4#MN7!T7!*_Pl4Rce2x#2NQcVArZ8(71`${ z_CJR9!PN))TbDR}&2;rVd5M=};#H&y3h!cbz5 zBV=bZc3+DW{y7vYN4?a_9{w&m+o_wh8ivsEL^VdRH(-&~mJNc~pI>%%qGi*>`AVdT z{jsa;9mXi8qstO4q9zyD-=2lk-x36$9wB!Y23j{i?ea%Er=~Ie3f8gLfYpLc<+DN_ zq)jD%OMFU2Q6T!74qc1L<^)7Gp)71;XWdQ5x%hcjtILYeI_e+IE0>wpoMY8Z4ieut zk@!7ENv+|5t0O&JIZ^)qvdz-rq&EqEeIsC}x8`n^?`Hnn8z+Z{lU~$6`YdTKOaIM& z@9uMTiHU)M(cBqf6yT1$>I#YWxy|+ZtR(wI3v43-Il*^b4xWf}89}f3h9_d_Zbk`f zRUjjcMA@mXMZ3L;h_)Zt>vwxQ(BIuUlB|`Y>Z7CO{*er;9;H&M%Kt;wf}_aVWcb&+ zeA4P3>f6kZ6QWDh-Q-bt{8QlBFxsP62Xb1#s6av%zii36c)Y0%yI^wJ)28J|A!>^C zoWd2&lv!Zj4RL{r zF&J-hRJdDOhf)hE{AN;#x-e(wC-rAp_0L4TTx5y+GfCQTuZXO#{%Kz`LLqrtO4fMRGFnRh_`sz~3Vk^;e|#YN zS>|1`VLZkE1WSQiHaIuAx=VrG)E3zCG*WcYhSeA{s~1}3PbEKnO9DT6TU=M!Z9?FF z(|gwqmH#RYG%>uFcCS1!IdG%l?b4(2>Zt)%3BTDSD>MnIo_Xl1=@R`=~dZ&df+kB>$|1$!+Qf0ji58UXB~@^w5_Ddg8KsJ493cp zH_i;O4tVQ;%E!uJ^D+?peOBNdld+rpv6OYdZ4dBawT{NFz0#K|Wq%3e1)UL?!B|oc zn3CQ2c@Gb&Z1iB@bHn@T5IONspncF8Lf99yDpTIWfjpBTgIq9JPF(bGprOg&KrXyQ z5??(WC@^{G%Y~Qu)$x(Q43o#U^Xn`9#pBlbRWds;!+TAk9Gx9l<(*e3&pjIWLLXfd z9}D#I-cuy+KNcA1U2ap3+jyKL_1W|KtB9TdIH#=hym5Yg#V>EcaQXA`z;z~1565@# z9DF|%mHtJE#MenBZH?g=on&Qv=GO1umr3HyTKVypEEjg!C){AEC=hsF<|kzZaYu_ zW`G4?BiIcRY9So-0ma}Muo~Giq}mBi z0$ph807iltU^UnT&Vl4Qgn>R_23P<#fhyohA~T>X7!2lsWnewnc?JK@fCSFG$piht zbTA*R2Ae!_z2nP03HE>`QwE2!{Xf8T8o3Jx zhteZBZ0_hVWwf5Uqo1$_Eh$*&ZQ{QBAa1=O#63jZdmgvs+99FdHDW6?=rBQlA?O2w z+@aS2IrVWUMOqFGCHRjJyhCFSB~=`Ds`>=b$x^XQ7|Ia?+!tDwprl+6snnGzoci8M zXF$cy(UtmUsMtBWvhgs^G&SZpqN0P0V##_iq!)!24YSFt(Kaz6ytY^|EEFJwqn|SD z@4brk)S@&wqjLT;*O8;+51qXiOWndy)5xFmYP|hU($^rVurSmj;GCe2X;w{R`nbH1 zTplHtf17W~yM-M2io?!jRJE~ksxXujSsCL^ed07fV;WPtjzytdFTy4kVa)#^=Kyk~ zh~q?YR9j2i_c+;*!oz8tam?411nKU5y?yvWQe55fs>Xxz8b4 zc?^`rjo)K|JGPrC(<9IXply-H;J=ul4cw_R_|fm)-)@YvH3oE{D` zvR5E{HhcP*Pzp)y8yC7kOY#0OX!;|XUiY*me;Y$7;;=QXY01X1(DgO#w?#2AP7-4Y zF=)T3Qc@gh7~z*4O*PO|C&;tKp{r`5z5f>1_?#@JZl5CVR^pmtNexG}U34vDqO(vMszin&_NCyTo}|lJs=B}7nK{gi!^|k7prRrmqLQLgQdydi zVxppwqLQLwqEez_qGBMRprT?@>DJ1Uk~=L)xr@+}lG4hrlFHJOlDjCaypxKOl6-&b ztTiz9|3A<5zVBQterN5qzdzRAXP^C{CO&K*-daVTCDE@CjeH8t=V4S4JlvFni&WFY zo;i5e0=W1ME`qNX zwMf^io$8Z^e0yez{Z6VNC(_`@?-VNh_%#jpF44nBtDX49y98%4FJY%kxW+C~HK{nE z*~d6EX0|^cxWkkQeTg#>KZ6*>qex! z)d4n&W}{>V*W36=;Pa4fxrB}4KcvdB-`WQ56Bm2t;8TkciED_&8_#*EcNg35j^O1$ z)K$`0`*ykWU=J4R&@Yxj|K9{V{dRe&0qOQ&KN5hsDf9nXT>nZ(V1L3@23&mvS1vrX zq?p?7QeNb-l#jXoARoD|XDQ67G?sFfF2%t3 ztucBjVsafZX?np+J+jmus?o!+4EvbY2LE5O(+oS_yS-GW4A`NEo9#TF0Xu)gPFIND z%&_0x+CKg!(G7?~A?m#hbr%mU*+;$iGX3-&{j1V4UW-DLn9HbB!XNc}Qg{f*}{ z{H&W_^)UBYuG^t1WcJmaMo?`UNVRF1N?ML?yT61Ex|K|iHu!U`y%Wh&1fbI=P`pg_)f1Vvf|vNc#s z9W@6ZZ+DS}s~+hmRk=)6t+4lQZ!2vrNE+%aGpg>hogI}U6K+C1gf#eBrouAqQ>b09 z&P4ti%m$0szr57TnW&z4xT!)fr@AA3({idn+&3+!N)%!qO}16hOz6-F7!J{5Mto;k zi7=0fKkk~foKK4@2_GoHa5#X zNY9!q#L$EoCclKN$+Cyp@W5H4jI)s?UJLB~TPu36Y*^P|y$;sLXG68&;ijBi`47E( zf?RmP#k!ZFQ?u>CVR#T1n#-#v`fpGsV&*odyabE=xZ^PUZzOKRs{>G^ z&#!{F_)2DR?ekJ6SD{Gp(2}$C^)-u|47HOi6_A525hgT7CeQImW90VwV-1;h&>wNU zJGYN4r8gBn-ISV&xugEr%pL{gvVTy&_;Ou59~m`vl-Z$wmxa?6)~*OGd5)D2@TUPN zwiL6Q8h~q=M3&SIl}eT}=3&ehQs&MY9@=E7NHRX>VN9woOEuh0RU;4OJ8XZe6Y8_G z)XqEvuwRTRGieN#rB3Hz^mpsOTQiB;RhF`?w)YLUzQ)F6o7z>Dv2{qbV9~re$xD;< z9-o>O(zP0KdP$tn>j-Hmqz_|Kbzn7*$p5n%0uIb}xPB=PH#>uQ;oClz9b@voxO*{8(|GT$U&%*53xG)v30n(!ENLYHBXhVgO`9g zr2ZD#ebu#f$mKj`ThHd`67HhZFt-v*3ObID%j4wYB8*$%1S-Z_-!+=lsV+kiZYnMIWiFsui z#2F2-D&i7$Xs8920KWq62YwB#0A2(h0@eZF z1bzdo24Z?9_Y|F-jJXp1gn3Mg=qKOfbwBqTSiq}iF4Akji(M{_4*MLPa8TmJ#B-4r0#DAh5+vXQe7Jiyc2j2a3nAa zI2ITU90!a6J_NiEh>t>sSm1i#XtNUFq5ZE7>VjhN4!NXh_j0VmF zP6h4()&O4uegb?2_$P2U@CNYTKsqn%Rps1`!`o@(yMH&1JU9q*stt!!&2D=KeY8vF z-QN;(+_8e=^Sk5Jm*|#_%UyS?uP$p{Ivmwycj)Hb;5Q9=$CTo(f*J^DH28^b0aXb| zn)NJ@I^xfO7_J*W2L=Mq0Wo$kd;z2iegR0?{S~kncoFy%@ISy^zXMY&HfbRe?rkejqjCNkD4E3BW$UDL|^|i9l++ z(|{v@(}7gsX8~seX9MQ~=KynoDZtIZxxgoZ^MKod^MOtp zx)n$X-43LL?f_Ckp9Ye)dIm@dd=?l7+y$HrECHqfp9kVopy37J8el1qs@A`N&jDWq zmI3zwslnC)-=(VbH6BJHV)ejDz)QdffR};OfmeW}oqh&p0ULnZfQ`W2z(0U50j~jH z0X6{-0RIBM4!jPm2L27C8gc{pA+V>FYQ}J!f{%xeXkER5oq%D$U|?S$?vgQt18)Zo z0B!-|Ugq3wzzCoMMykOt+25460VB-l9Lx9-khVcOM*^uy-UsXf#8Eu@{XV$#NWcGN zH1Ix{j{#DC;^9Dfsz7ry&m7 zsyC>wx^16*utx7Ii}s-|WkE`@Sq1a~<^sC`R|ES4*8n4d`9Ml@0dO2}EpQfa9gxz# z9!T#w6w60}8^Keo2-k^uA#gKzm*GJSDyM>Cm9@-1IEUYEjD}96An|(^wA89U8lHv& z8nr(IbOLt*>9yxs-6P!X0t^6O0t^Sf0K5&j2S^cp88`{J510(32tEkJu57�CRGe ziGUPsIRtBk-w4FstK27mZvdYMz6pF0SOuikj_U(-#rqEMeeg$tp8?+k)&eQOuYo7P ze<%DU;D_KZ>zHH6y($9wNPGr@KY}2-+^O+e*h-|n}Cyne*)(M{{p51uLCoH&A^qw9Gs?*i%W+LCLlFeFCgyr zF<`Mr?p~l3SPrxSanp^#4(zC5#}qIG*dEv)*cpi3i+aSz0=t2K0N5Rv0}KS_0lNT; zfg!+WHH06EhXXL^1w07s1AHGC2E@ihLw_K4^ywaB;~aKh-~ukei@-?m-vVz3{sept zDYJU9eR>7H8|MDNp}@hwVZafqc@D1Q7V6Yj3EnqlsG!O$g z!x-Q&;5Z=0SB43|Il%jYS-?rad|(1_EpRIE3E%_37l6}&xbx636L>NQ56O7I(8Dkf z_&aa`uo<`*7>v$l39u*d5#TMr4B!CZav(Zd!wMieRKqGD`Ylo_xm$p%f#_!p`M?U` zTHq%@s#|A)8^GtFzc3Wx!3S-A3$O?9abREI4&V^rQ$Q$I!!tm%eZ#XrZ1Xof4@8qQ z>;`@WB#+MnUj&bqVAun^415WQ3ToH~L_IQ;0XqO+X@mBUieuOhgPy;BoM{X-Vh3fTzII@xLUu0zYii z4&z!pd<=mv@RQ1zf7{oXY&@rc57PPzR@nCt!#l$dKp&mi`#>xp*9Y@Rkp4o`0eFrEM|l0p{R$R30xtvofu!}i0Goi_ zfTZQR1F;0a5Cp`>a6=DZ2rvW~0qhAJ4(tUS3+$spU$;MM<9Q2ORYB)l=M03DGV4|# zb!)c)I|By+djTVXgMhaKqk(q-DVc+T6M$4W_XCH5r%b&Em;xLI%m79MsZ+QYxD_}Y zxC3}Ma3>U*0oz+D?c+6??|7^d{p=VBs2hs|wg-*}QvOpw9f9|Qr~ID;i~vprQooxB z90HsMq(SQh;9THr;8NfmAoaH?z%{^mK1FY0 z;054LU_J0T;E%w^fepatRnZ~)JbiNJxheR>>GOuYk4BR*cfVmTH$I`RykVb~^Wi|) z#P2N{K;SnD^=b|(-wMzc&~DIS&>7GrP&bUy2Z82*vOrIQ_JKYCT?AbR`F4UG&{)tc z&qlH&;?MN&PGE}XDpJ5!oyTh7U)UPKG0Fn1<-FGAAjsF1Vw?Sf>waGfcAlo zf-Zutfqc7QJ0mCxG!?WIvhEBphE08Q_TA^T!HtOxA@9RXbgT?6@a zgGJB?&~#81=t` zQu#Z4)P#5KUTQnBo9Nny1@B_2ICG7-zyzg+GVJL2)rBl<5(_k^i=Gu0s@}CHVUDir zQOwb4h}Z{faIM)4@<-n8 z1DQ-J=@?vFVCNIKUUv*12k<~|+L&#|9t%X0h7Q#De`+xga)HHhRMCOn?)Cd7<@X*u z!f?W3&ezni_w4So#<7u{ByAvR56R2#c|`CsNo;XeM-vurTLRU< z!#K=-&MEB8#kd-`XTe%ns#xnt*^S=`k7eLEq{Yw!=2WLnsOUy(pc?DI?Ls^C8_~w9 zY=;RKrX%F?4{-3=LpDEk*kN+Gz_o--E#V}ecH={b6X3#N+U<8>w9`v{@S(+51$}{4 z)tBh$h!39Hd}MK`IZjhI*E`}%7l{Ba7j~LLv|0r9(MKrVHdQ#Z_kz>p!(br zZ#$Fwfc>#5gCsaQ!g2zV=h~U>lVxXP)fJM&Lvj+5{R^m0AvG>=EjfYr3d1RVakc(U z<&-jpdj}d%={s-rPXMQQ$0Mx4-f16G@AjuXoKqQ`GN@H)w$VsgybIys$OTLIY5n%E zBz4YZ^0nf)0?Qbf&%aYR3w4;z=0jU?knBzS3BCn*MA|u zl56-LC24e2``nFg7F<&WY}dh*qM?peF7IHfHfkvI%DeqcsU{oeHTnj=t^Pq#)6iDHh~U+J^)<>wZUs`PtXw1B+vrT7SJBh zkzl>$6;F5>$NS^TpK-W1J_+fMIcHK&kB2IV8fSNC#LfK7(v9{4x^OCT{A1YAc!qbc z;;qJThRTwUraA}vt{FItjq;r;GsXLiY8;1E1BbOT+`QnymCfLtt6yBnEdv=%YeiT`ZzCq`ZIlqA%JZu zAj`M#_C})W)z;iyyMgl)a2~)LXi4S}qnB!U1FQI=+L;}$2)r$O#>`74wZnp)HlJe6 zeSSN$uPaR~xHH5{mEbZ>737N(`@5xBa9>_KGaYoes5>_A`uLcAE%gZay9d-QKIZJYfv4-wdhuma?kqK{Iv?EocMj%s-;XgHQYm(ZV9sYQi(Q6W{8|YLN z$}x(UMFn>-ce+WucoA+VgqU5El@?_ig+jZE+Ynvvh>V=j`;hKLFE1>R(9~pKWWo2yg8CV1m9M#%3HZ`Q zuK+cyz1fEE%eca#a~(4JqOZBLYtBp#$6fYTW%Dx!+S0`s3-;=8aA@JHINyZME+YTe z`oaH8@c)Zh>J>lp66<9=UzEn^rLJ}ytKAVheofy! zQ2AjeGnUkknqGO2zxf>_Vp@sw&tAg52zcGiJkE4&R^{K_%&!~oT^NXj;&*T)BMt7O z&?qK>7J#;Z_JEFpE`Y9qeDI3d2NVUG6CxVsN7gVS@$Gqo3La_CM#X+^q`l0N1zX$Q zwjN_!LFQi|z7b@881Qhg4xcj&?_r(?!=0s(Gxk3KFHV8J1>smqLub$+&{)uX zP%daY=m6-0o-){&Xxz5I>Z?Au-^XFW*9yxIX{y)nS}zlD-0#|x2m_b5`KfEaYrd9b z$bU;y?f=l+`*&ukgg>+p3qEgHObgYjKQ#AA0khOG5Dk;Rt6nm~|4%b5>qY6SVIwp|-YyNJx}iApxq=o?yN^Mh zrK0b_G06CGW7)C@C$8Spa%lN1wHFc#zU5fnS)~4M((atbO9&}nsXF$TC4^(CrQt{K z#_k`!{8;K2$!V+;lIew3AJcb6L+uRvWY;aHM3_}g5;AGROq`GPx+?w)N5*aW6zl1a z48y;lrdx47(w|yKh-&`CRm87TLU0RR6wX$DT~EzSK5yusQJX`p9Y1=lcmGlmwP$f$ z2`L1_q*M$LIcgISt%0ylcHMG{8tI%$zICpWV%F6N?oTaHzelN31xF)GEA>cpx;YZJ zO8%Tu#nHA7R(u4r3{1ztv(dIY2LA6kIgk_(el&03{^66EWn{Yg>bf?l)6K5j{%=>+ zhs+(U3t(|7{C_k_yF(Ux{xdr;wWa^)^M(6|PjQx1IQ#j8={6ZGxt;w2J3T=^q?!2= zU!T7c)w-V>ld36cOl7&;-z8 z(0b4w&=Jt5pr1g7Ua$um2pR>N1Ihwz0qp@D27L;;3To3E<2}$I&{)tM&bq)V zm+}e2jN9(PD-^z7T5QX3aPmEPg`$Vn#WcG*+iu68+zY!2^{p)z?!j34DcJ7~YgDwd z+H{9S-8#(F!-@}}mdOxJ8|Eq6Mk0I@wXA~Z?VCjXr+al&K2auzWhdm@mZ{Aj+dHZ| zVc^=fj2n|%sXdO1lUf!6A;4`>@D*QJEmM}m*C^8+t#SFAM9)E#15xj2Q>Y6MddqZs zc1R^fn*v==coy<`hMPmY1lrSN(EO5NwsFg)Cp5r>VfW47h+h&-f7AI9olM<*lTO>+nR?eMT_ zjxlxe_jE8>Vt_n>gYc366t86eNM|2bN&gftzm>%_?mVoD{)ag8Ry{T}_j*`W{ZqU` z!lni>luoeI_lNcyWs1_MAubwaiqrIFH_8;Ip-HJ9N0|<3)MOy?S4Uz^ zgKXS5jD}bEZPRBoy=|h-zC9Xls9p#5#I8n65qYULV@#cGT#b!}<*Y=9j4>_NPz%-m zG4Psd&%vnzbQtt0=n}{f23-gm2pR>N1zG{x0@?>U3c3jL_^JO^8{3ypc-pval_SU+ zh8eSXT#wm%l_ON6hw-Z%MRYDsuA{4&1|K+%hjvZq%co(C^}H(TK^zK(GjsAVKNY~6 zycXv;9Ip4}no)O4fGiIcH$au5Ht_)7{jL!}*VuODd(MM$9rWIY@nc67o$Kge zy#>+Qy-8Ekavh;AJm?LDMhw);cBj|{(z!Vd`kN8e&F-p!P4uXBR}qMzt4mSqivzV! zEb63Kbyt~rh}8y>x?|OyR)W&255hEz#rOoZ({Rnh5;d^ysxHsb6<##wIeNRgZf;E& zwXg0faZyN=D$#H)?~WjWLL~8C_U|A~+)U-9-?j%JUtpG=h{XAK7tS zY`7B~q@weY4+FNe<`N|lwu9PsRa^2MKCV?BGO7}~r=1WkJj6Eae1uylR>)T>q9E0j zj~qhORylbekGF0bQGl?f;_Ek6Ns1&Dn;zB}WLP<*)^MbMOR;|Wvwr}VKVV}p)>pt9 z40UJvm=^s1uZy6urDHAP`;$i$Xj1T|+n~`{*C8VP5s`?;_1mER)P!|#1+FCqG<5y{ zd?j?43Rn-Hk6;q*7<|5Oy(7SdhZaxaCr&G(Iw8YFYMyR|Hwd*CEwu8Z^^U??nL+<`lxI7lNlD5le7 zcGi=QKKBmkMS=6R_Sc{>d~dQP8)b>!8kkp?yH3`pSFjU)#1p zuh2wN8%z}S-Uhuw597BvDsawe^doo`2~rNaU2#~2=BE}Yhp!b=3zp8Xv`(Rs;6cw2 zsvZ=hkJOGD%izxZ0^m78H44Hu=hQv7+q$Tp+Z}^6@?zR{N8wE~Q?n4cT+nvV0e2+7 z*>-}a@3I`YZWo2|=SlV9ci1#LBnzed=Sl9Dsh)B8R3I{6fK^y61wuU#TgJdr?{k82 zBZ2-|{7&F)5aYD{-08r(fDZ!iR#&ndf$g6ejc5F*seFKVU3ACm-EEV+gRF0%)R#=d zex*s?0UAB%^Z5zh4(0*?+{n4hcPvm1hr#|cW>7QF{bh*Rg<8S z1KZqZLKM18MHJpa6iy~#q5f3wVKSPf*pcX6h^|2N>P@1}pPMjzPV~l>A;_IGI4*|N zQ7PDvGu1ny)swl2@Z=aQh0nl;@kDR;K1%ri1&Q8+XgoyP1K!~-JhWsRC4Vw+L#Fq~ z$+QhQ&^VcPAQO}@R5R!sT{`L3jMH>^Fhev$-N)!!X$=M3vq=eH>nP0Kotoy|+4Zvo zOxaH5HCaU`dv`@JuIb2B-g`@*K_-af7*5xJG; zWK}jDWwFb{1*!JQ>PiXjv%gNhed6JS`nAc*KgoN5D|J?DzEJ(0tP+#F?{?XfTjNE; zNMsjg8ueY?ADmmob_a7o9R7`D&E|gDE;?Q`okYY#hB?G?!-e& z>3gdhBX+jyn~8DeH=R39am2abcr-dm+DS#t@^;|x?}+y3mS^EveQI>zjH{NXT`Wgc z;Jr~(6skj4XkXp+1Uip$3bn6J?e-yat|Lh}wBPV5;&Zpfflac>-afE^D$pq)2-(mX z7T!iA66UmKJ2ky2R2@QG%RG#!CQQ+5!Z~>2dRj#8nlOcG0uG>^?cL24oWj0Q)1>M! z1-CN7w?kq~HIiz=6qQcK7d(uqCU77JXCn~v+}7-)+8}{ko$Vb(`F-ny-aQ;2Aiw*~ zV|y5M<0zj;9`ts(+(r~XO3_q(GpcK%)p*=d!OD&({9qhzIOX=b(b9>g0HDW2-K z$6R=J5}qAN#Txy&p1SUFh#c4qV);B(awqrza;Nt+Q*W83q7H(F1$W6b*ix*I@$O(f z4deg9yT0?hV<_QE<{=F1Cb5_w^5W}~uFXTofqf;G5SY++z;;*h#cV!4ieTK?`#cvT8&?b2hznKErb&&+{!x^c^7IL8eiqR zOT5!H8&?LSVZ5rd;>A0DnfD?a7apDPqaWIRVVO5>zN8`0*wXD0c`^92Au+Z3u=SSB0-=i&{WW3(0b4=(82!35W_h< zTm|_Iz^fl<6lfM`1!xQCwE;2@|EO`>GTbe84u$hnK5c4t25Wez9J9pm--zE*4@ved(q;VYb>E$1nnW`32*LPyvAI79hXDVlwb0$S#VHP5QU00U$wKy9k%NgdvLrVl; z)i8_lEl{(af56+R zqKN&8*vE*SMXX~M*kR8&oGO>te#Fjv#$i*>9s) zIelHPdU!$wH(NF2Iqz^?b~}XM)ML*6N7k%bjjXwdtidt=YRnoOj&Wo)q6ALQABqxO z86Kq7W$vLnazsu)Rx@7GrP@4$!7@!fL>7b>cO`tuXBcKbQ-#|XM zqQd}<08Ixi1$q4R`M%-_WAO1d$ckMYmQC1~+k1gE)QJZ!aw;p;{2kVYEn8r1>vEgB zmE}COb%8a`-+e$pYyQ&_cB(h*P9T9J-5n)z@yt1B4o_gTXueceLutT z(m!OO)uHKJpeatxdJwC+rsrFOJWdolv(Wk!-gfm5F1d@WzE*rdvb+ZO^ua|Y%oeM& zi>x^G5|TzpZY;98@2y;{hAxI=4J5xqVqa@@FRNUv%1DCU36}Q9v0d0x5|9o_0VKYV z+?Q?*cHyBVhbT)!Y5u}JU$s$dOt%KO@SrTaLdgREqnwK-3WiYPU7wP5u^+cH$}8S;Ycz*{2q_3->?^}n5A&L z32tNIcF|IgJT9h_kNPaKIjltxPk{KjjaF3prBs0az>wU(>YVQhojGZx-b@2G>>mIRn zX5uzg>?E{wWs1>=j-z@lqHiUR!?;3A|e@YY^;#hJYr4=7VxU+d&6FAAl}`u7i9dF%1eD0h$V0 z9EqWNJ|3O{9R__0`U&K9JKh0613{y1m!bMh1sQ#nuI?kK33&y^YlsY5IAUH&UuPn;yu>=(P-^sIjw{Gdga%R1O1O;FivkoUB75u zEl2|ygmB6`!997~?X*8uz{1nh-flfS zQ`M7XHY5iiY4@SGdtLcV75^b54?^-bB#(MZsz@>ik`E#I-cu6x5hN*))Iu`xBX4(4 zFjEynVwnrcPhY52G1^@ns36>JXgl&3g;Hrf3>_=`?`u5uHjC5xC{K*NIi70Mi2TDh%>{r zft5y+;|A77y*@%4CntP{Sr5VbWZ24y(FPk2szWjG;tiO+ebuPGiP78zeNcss)IuC@ zLNcg<Y5t)vAPzaJLNBOEtCeQWr*P4%t=h!s57xz8{-;vK341P z8gPxhp{7j*w+1(s!1#a|)7XqMW{rv+tqpJ;7Guf{>S5NX!qM7ouDhEgE-2=4s=LQ%p&C8R{NCuVvc_oc4HySi1=)KW_AW#G^%%|FNDr#uv5*{r zB>gX=8Z*|Tyo(`mR73L0UmUusuE#~*!&}ekKB$awaQzPK9EIz?aayPg4=n`}jHni< zvWSi`H{uCA`RlO#%Uq#vD8|Rlv}?R@ZB8xhw%c{Fb)gW3Y2ra9;@*2 zIu{EF@CKthy^uwahhva~ZC;21}~CfUYO&q()58 zd|hQmR>;(#X%f2tHnnr+nD4q0ExC&JD1U&sAc);7X9K8 zrz}uOIdP-!Sy=MM+&+hi!=AN zZM8|CJ_-~rlomwf?qUV)rhU-h}CrA*ouZ z3YetXjqCXK>_mR%Td^l;{p5m*gQ|QId_os#8RDzHn55m}8sf{LQmJ4<6{jMV&ol+9 z4;I=SuK6hoQemWjf1^gYUd1P%#;jNA48;kk0P9r+b7vD!n)AgwDkLhb^~yC_>jX<- zlaVdaejJ!vIpPQ=GH&DFnp-rBvR>sKg=RW1S@UsS_mI(-`1PuWoJ_zWG49GhbrZ%@ zF%J?n1x2<|WRxVzFdjSb(|cY z2yBfWRowN;JQX!;OK_`yRB@41sx=d)A`0a_T4nUzO;2bi)vc{*Aaqy-oLi2e5I*Xm zzM87_cYWkx9kvaHDj*TLR;bFKHFZ*ZMq=6I)I`mF&B#Gjl!!X>9z19khbrLvwn6&M zG%|iUsB8})5Nv|7{M|#{`hYf}MNkNV1DlX6H{6cPzHiId+O*g)PJ^A}u+uGs6QUZv zZyV@&ugyV~4LcTWQL+pUQU98zjcsw<1VM+B5KI=whWjQ=T#~$0)!jhvxiHD(zIFbf z%9sv6up7v-Bt$(sU31?;d{A8`0XFwoz6wz*le9ZqJdaO;;6n)h`wzh(2&^ALa3ci6 zoPJopc|8dw0j@<6Qq~SogKsgp*Et`=7df~(16RqRCN*p_W z*h~F)X3O&OgDPScGW!z<2KSQ8j`-o9-A)PYSU!cFdwZ!9v$X!&y}c0M3><0qcc3<~ zrFq9C!`fL`d##sRmaO$KzeZlFvRDia=z>J!M(UOD%_v!Gqt2lVSKBRiAHR(rea(X8 z*(nQm;tms!Mx8t#0vsY^d7-b`FyEtE*O1^V zxOlCv`g6Y4%k`T0ewUkh$AX2XZzi>OOM_d z@TV{39)+Buw}*Bey<*jwhcqt@uL+f(KcpEu>I45TbG1Sn#`Y*JBhG`5KjZ9BnVYBO z<2H}0Y?z_ya#5{=)@X}0jNvPvSfk~cGz_XMJFV5QItfGC%8Bc>B$Ex}O5L0LRr(8X zacYAWrO{xr-A1ieqp{=98?|T+Lq&DtLHf?UN$aK^{mWSS@Fp$5p`kZd?FL{fVE1;d zoAlRs_f{og@aw{MZK`RAZ{_Vfw7E7DdVy!3*Or)?d#HO}(7LF8FK9j{Xl*dJm~Qk? z551s0VCoh^*hO7@L5ng$Tn=0Op$S&BUbu$g_r8bZZ zYDdqMC7g{H_GpVuul1@Nw^zfKBD8)z0lqII0loWF_Ig=cYc!>VRlc%M!ycrgx2W!~ zXdi2+yXt43HvY=7A6d59&5a-qRg+~|#69EYUL)=WaC(;h1kQx&=6yihWY9Mpd+Ajpz9#tVekwz0<-{>584Ad0=fh;MB&3RXb5NyC=0Y3bQp9AWQc}) z&#W_>)aCdvFt!n!&gkwB(S5$E5q?^69+9O9p#`qDM!4{xd)`Hq?W(jdK-M$ z4<9^c=Y7@AP4FAXL0L{f^8O~w&f|go{@-WkebwM1IEjRlOK{>bI}guDayulZclFu% zfPme2hZ%@>mBGkN7~T|VWX1nBQ}3&iH^ZAd;LY9eX5(h$A|7sX`hT0L$M@vN@a-bW z!wHR?WV+s0r9TGW?}YEA@ZDp&-dCN4#BvV3?vL;4)Ah1^S8u4&>CU2bpu&#XVokB3 zJt9^{1KvFUOTFS2%zsl$)OWuRD#qkITAyyC8!xe$1vAs)w^jEO_U>v+F+QJBQ+ux1 z8g1j2V>Ha;oe0;9t&24@h{{EeTMLXfuG`Ryyw=y}NoyYsbyeN{B(}p+UBm1>wykfq zt~aHt#89sS+i;o$mH2*opmMyi4GH2BG8zW6^;`w( zR0f#GZ?qx1^t6oRjTslWTcfleAzaiMld3~@Si9vo1|oOx+XdfSlZkEwQ<`~OcQS3js37Vw$GA(hw3%S8P%D0 z5`N?{%S=ZoLAq*^^WOIF&_o7)^qI8HNW^ZWd@E>Y+;(f*HaSr zgK{LyxS#QSIpf~$RDW<_U^m7RjEjkH!rT*K-8IHUe48LXC7Ss-KjtHDXFl~V!C!RD zF`O=8gQ8)K>9;V};QKXsRQoDpKqF%+<~zvTxt_7Aj#+`UA zBEInjM!#DbBNs8c4l{0jOz=;} z9@9ePFzEtg%*%{r6B+BP8S8=>&tl4o>{mx{#EJxCquIPD=WTw7KERkQl`X8E`N2mS zjXfC~+X*j~%bCLbS*e^hu^$c{KmqUV#Q~R~cO$+YV9vf<&NGJEB_(2>kRay4Y@XVSdAh%h0*V~L7&5sM8H zfiNsxA&+7(#wBz{vAv{r%!k*ByUC1ox3jsQ=#khYHa{E6=Ewb+-x^4mgX44c2dZ=| z$ds&Y##AT;*!+~3W1k%H5g2X}W-N4=4nz#c8I169nIzeqS{MEwU?CR zG*XITt<-^R(e0W~FYZOgMCk*Z z;-51|%C>PUTZk-W+$y@iSv*Q~SE7emerzLSRU+e|E{x`{8HYx39jcN_8j1lAB{WQO zs^SpyIi;e@Q;OIi{#HiwB1V^}2P^;_6NwNw)4m(1HlhgV1hYNhN8yK+jSUtxR4+`XP)Q+F{JJS3Gj zPS0tSzyE%=U~XXadzrDUnlV69Xlu*-(2k6*uNZe`Gy4C?SRpF>%D2q>O=7GOd07qf z@l=NpzF~(9D2Ar6pgx4rPb!(eC=P#V4G9upvZ&(3TDIR1#5qwSD)_uNo7+SMA7hnk zNRc{HognQ$^$J_e6c0-=cR`iqtW>V^qCoaaku*wK)=p-3d!;$<7{|PS5~EQ%pSu4t zAFi>#F){*5h?MppEGltud$w@wF7ZHAZKU+;es{9@SxmlA1WTpTZI#NF+ExO{6!*c5 zjgo^k(n@U4vU&UvRgzP#*O_t-=+{W0nn=x!SW8I&O zW=T-d!_22kk!B#86w!DYEr;vP6XhQ(wcYgtJJ>6|Sb^w+9n;zT>|w@)0gO!x81vo` zxoA@7X6CnI%8~*+y^#3=abJ&JtYlt~;kVxY!+h96g0%m^(u@Z0W%Ify@j&E}w=rL% zF$TQFn6j8LTr_D>G4tomj604nX76CEhbGng|Ik%zP&<^d`3}ZpiD_dOj&ZeMkzk@= zeKy;Vl?c?n&-`UcNQ(I1B&xbWRQlzYr2Qwn!wyn{8HctN52alfab+>=kY<=5b*4xv z-!aMRhFdwJO;Wq7WXM)5m?9Y6gY6v(MEa>Ljt4OA6pU@de3*$b8MgGYyulGW^ao?G zG_yphD^;T7#xsKtYJeLzqvKJ|Yhl zM6XNo-f-w^=HsQaIzOIy*GR_32q3~Y9G3w|(`zg!7d}SHs^BV{$Ms_@mF8405h#%e zR7eDBMB{}@D@l@8QZ20`OmcE3a!zmmMUvtQZ%$EoEeBK_%>3n030ShWSn5gwX)q+9 zK{}Tznd>PQZ2FVk)%?a7*O@W+6UMR_q@O%6%K*aWZl~fwnY8}~Y5zuvK$v80a{_x* zF6}+I5A#F6VBCR^E98HwV5ImTF8<`*h5RQA#Wxtu8yU~bK%)F2^Zrv9V@1*I4P*YY zG`9#D>D0h4@-N!mTBHcmq;lsy#d71_jP*IMh)2UXrUhokIEhGn70Y8}1d}NvrGTAm zUNl5dnsIYA^CkDNKZm4FB|pdJ$@efuih0gyNkQB`7Nkg}YW8Km?pMaLpBeK669mHq z_e%F%K9}v;{>_*v100tOa0bh`A#$xQ&oS(Mk}XEOz!)CMG2ao*e3N+Wl!(|$*!;Xy zy6R!fH_FsXQyudGlEV7mn2%l0SaLh#d7Vf3XV$ZUpY&eEUSd(2P0Dx7S4cOyQ#{JP zm(8n0Zxp36UsJ&tEtPhtG{eXkHg7CsY@i}R_=e;EVuLDqIn3B5{BFi33Fx#mpJIQ` zp_*`(U#Vn_+r(HT1Dcx4%!gvTs1e~b9bx{mn3oKY_J3>v3kJWz=#pOVEOaJ0tR+na zj62NeFU_q?+W+at*gQ6!vFr}Ul9P#C&x-yvCVl#xq9F)lHDl?VnM}rc2G2n z@rtPCCP`6(sOHFCEKeT6m@=C&SlmU*J71m@SwbI{*IZ%DNf3)MPqV>J@gQ9)^!J%@-a_K&giK;&^=3mG$CW!x*>bi+XA!$scohS-NMix4hZ!^F%_=oVRA|L! z79`AMOtvzb-D5d1ua>&ux02=Q=NYjWLXSZ4Ta3+;;2rBd7d9UMT$S8N_Jo-sI-v0%8^*Vx_;X%%5T zWc**=n=Lfk8I$i5zLYUQMl?;|Fn?YGPX3koG#Tw)u3$b1tGlQ<21pJa`i0H?o@OkN z-ZifS@}DgFNpDx=BM$$==4DcQ!=*0dO=ojsDBBw4N|1{Dvl9{f~6(Q51q!CC`Ax@g!yu5MNM6qPkn|l@@__(Xy^AqMJWQ2d%{ZUU)BnxrFXQ~ZGN4J7=2)B0^71Ce z@U4u8p4SoW-`%^3Vkr58Efh-G7Vly{O~(6MrCBuvvw6y4#^hASlGhl^rJJp3&wRMl zv8^&9+B=WTQU1+y*}|20#+bhu{eu`Qjxjb#=aDV%dKor0KPJsBP4^Jrk_1EVXZdL< z!hmq*%O7HlqfU?7e{CZhM2klS>zS{XEKQJJui3&yd3!*17HcO||Brz|3fXy4^y&zqB%PYs(JV|Q%4#B+d**r2r z{7Yjz{sv>M)VZQf(*I+_rd|oFq%6y%dyF{8<^^Glpq5&q!NpyVVSIiql$ESxfUnfOU zAQKr|H;TJ&8LOo3?C@d!EGxPkL-j~Dh`GoZF`2PZ-f*t;X8yGF4YlI&`2;pMKF3%f zsyAFz_IXj|b#*My7V|WzO9|7-9PMwg=yJ2@^0=$)pj>M4&@$!|;>276ijmshAo?Ic zz8f4m&Gv$&IVXp4)<+0ti>7U+84+s#Wnz#h-ENAs`(_!8)`@OEB)Yv`>O!Pw#8lDo zryDrnP|1E0EcCmRu0b^#9*xSmO z_dH`$6ywe>7$YP>MRS;M5Y3qKhqV9WQd{G9v4yZclKvY5*3{>k@-kzHQCY{ zYDE!cFK2m-cs%2wo{Y7_8N+WdI%S~ZlA=x#6~EOk?LYDgTTI=>cvjkb%{Jx(BmzSv0vR&d z)F1g`1NJpC`B4v!F+n49zm@C5nY}rx;#@Kl61`mWk|seecDQ}iCKPIou zO)^4CRcx>J1;#2-+2PWBi~b}2h{_HVm7RHr%`-)1M{Z<3dODEWf2?@eC_1}bnqldW zY_VA)R&giuWdj+D(-lQfJt2*o*!-B3`OskI2fxR79POU!RI^Fi|6qB)kCkEf z-g9i>%4Wu6$HieKPYl?HqR7QeO`v=rx!{4j}~3+lFFDN z?LAM|(U>6>6`fJd9@TDVOmHw}JkFRXMHP|Gd`TC^p|1-617lhPWA@9)f69u`cNxoq z825_iJNpFl3DSNWq*+!7hDs+DAyYHSqMFNtxF~9Su=~<>jFFufk4ZTGIpq?-8pc#9 zo8u2KfBF(*gLF29-pu>Upp}mGqXg87N9 z1(~A3@}v_9lPq(}7mM>UEU%J?R7s_(6NN*!kyC^YNi(i_p804=Kx!TH=Xp4uV`%Eb z274t%nUd9wQf9|RCD)E+d#O^Umv=B9C(U&yLZyI{<}#Y)JwGOj`8pZjpFW1u`}rWvqRKG0x06cm84KO9ksCVs+9d*dkc& zCkcr7UfO@7WL@O@Y@sZJ(J3)b7sXRGh0S*=#<(SnTQ@WA_>wVr9Akl~@QO>!$H}Lj zU{Pp(%Oz{e#ev^Kw&*vMQ*=yff2>T?#hqk%(+Wm^i9nJ>pzcjJzuca&bRT14SH?JL zC4;4i<0$|2S}VO=t>|=rv1k^HP;9!rVzHNfC-a$7#?@~#UnE(ZEw#SrD>e_4h&M_r zIyRBbbF!m2rP)%et7Jq|yoW7BbYW}~2RkL;(f~Fuv@xbiPF((&`OD(|dP|Lq?#Gz=pzsqIlU`wL9L-oO zZ@safGGCzAEtG$w1XLser5s=jTYqNUE34e9q}MCWXY&TpoC)2TZx)psn#_D@0%Kks z<7Ge22|rP2*^^<8@C`Mm*+O(RW1@J_^bqsS&oCY$2e4l)Q!x#)Kw-!8Y+g8m1E`as zTfB^zfx-DNzV`C!R`M6o~g zFE%f{ha-d&g7t_uonrH}m5c=eNI#{>>B9yUQkzSo*g?9az$R-ufjSz4brY{gP2d2 z*Y6t1nX+6l7nK}+g89PV7+q@_({iMCo)wk5Ra9<;sNC2_galJbd?xeHS6rj#2?Ly7i%H?1c4gQ5?);W7Gi_=s|XaA1R-@DG~PKgJre#z&nE^~V9BB!n5tT*@Z`L^wxb~SJs6d$|(nymkE zGNw~xHf(u;1#`x6nx4YxgJe$YB|Q`1^Z5fgT_LllK+>S}c%#ILb9-6tm{_c~2=*uE zx+JUF{6T!aO72$YJjLfngfPN!Yv^oor6RaqtX{DAXIr*L}vFPs)g`2rd8 zsg!3Y2S1;TOwA*=v&ub;pt&&A&^K8yP_6ny#kuR;|^EgST5p;PjrvfqprkDFw>8fNz@wl(_$8`D3!kluJZBe46w3$Re{( zX3L(boZl*nUHTlIWBhNHutpCCa5_yEo9i;h*8^Pe-W*Qn)^Iwdnp1qD$qvnlN4WeR znSR^Oa{gvnL-Ibu=UplPOnVlbc-xH+hx(& zE&(T}Qh4#Lg8O{Fwt>@`pXIdlfz1CX@y?BtMKFWYdfBtBkO;R~OngCl63pZt*M6Jj zL(=dx>A+QS)?>ex24ztyU&ZGadS(9alldKdfr;5NJ!Zbi=ljIjQs3wEQ^Pnt@GPgL zxRRmSaV5y-cVxOAmH?G1*8x**Fn>nYoCBv|e=2z3ZBDyJaa#Tur<280L0M$plSO88 z6Z7?QMYC-gpO4zW>Dcdcdg9BRZjn1HsnU@gvB2zR2{a)o7!so3BQCgJD%d4Gym^W9 zcMjlmteF0A0-u+P4{eL%^EkOUojHlmvm_+v$!uyqAiqkjlCfMXfux{_3k-Uk)2Nl4 z*2`MZ)y?OpWRY2Qjn6O1Shvb*8ut?Chx$2f{TZjD*z(Q3OA`5NvCz{{+!ik{m56sr zoakOF^9N+?ugkRBDUof8M6?9icoeK-`OQN)ogL5Va~ zC30;+V4$H`Tgd57>FG3VT`0d)dUPS5&yW5Ur}O`h)1dgys%k#pGmz755+Tn?JG0Np z{6Djn1+K{Au}{)LGX2&|1D9lsXMa^1lE}DABH{^&h@)DVKl2q%Pf28~pU3A9B+y0O zhyAHXGv%7BU*_pp`9-8a#&qMCSZ=8}&lc%<&R;k`y^7QMQgK%XpXZ$5v`ZrBZ3%Ge zw{rgMW{F4x{*E(}W%ar$ro1HAcx(Ti`Lz-sju!BFflRBQD7ZO?^HbmCbo~NOSN)jN ztKvHk-sbb>0V#aY`aC<&o~3+VP|j)jL!2J?wWLzPO$n_t#Ww~>M+V6TWa%lEzbXy2 zj^y(baz2|o+Uz?l8V03@t7Xj36|+Jce<%f;INi5{(__-}ki>^Q5{l^q^)#fX7IQjC zhU|pIlM{`czxr89o3Z!%kTbSPfw{BzeCG&GSBWz|kb?822c!Oz`S}uxb5I>M996>U zpcgpp`X81{oy6(feVjgc1S#70U6l~L{Wud_q=5_4^VDfv(d{x$R}^qMP12xv{oz|& z{=Gq*7D&iGe3#F+kLPsSSWZVl0XzQ_rgFv}(X3x$`ZS5@H*Yh4K)n4#HlN4UaGEEf zd+c}leCHibSBuG8Wr(JHf%9)Ba(cU8=Ku8y&bT14d~7G5_kYZ3{W>Wio6xRb@cCG= zNUPlO2+0QJx;XV!iKL_c#PS>Ee!|*PKF`|=`_q^`xXD7Up&Xt&*j>Up3 zm3)r#<37*n&EIhvlx6u;GN0#&-1>!ler!LdgMP|seTz+-efMMt>W46K{Y#vVmDMXs zW=Cxa=g)qT(=&%T&H5UrYk$q@f#IA6#Yg7;h0h0xMJJ2gl*cI_jVBLgfhdX5yFSC` zQ&>Y^GQ_CoS0{6t^>55ym3XjLLUE4p^%6JEoo2b!(>OiwWlj@hRoych^`U*=ojxXN zH*uQ!D^8D!bM3sz=k>CE9(0n=r%9YB9m(hWD4?LeED6C~5=pPios#i$mu2V{;@~+ zJV6xBYEI#X_DD}J4P}8TpXN0ABB$HLnc^1lIX=B;6+a=%cDh8s&F^yl#yy;_&*QYT zhSLi(Ii2#)oHk#2i4O*eBCBM6u4?7{pqT1{%;SQcoPX>`oW?EYbVV1ZJ1=m0>WiFi zmzz`%WGGfkWW3&C`DWkIAF$x{47Nn;ANf4k&S|PR&ArE&-y)`aAa}#|)wA4u`Jo}| zNj}ecjO7O%;PX*Z{}vfqxDqUg@xLdbcjNmkIN;x<0@*HiNeJ$j7+yb>E50P&-Ty#oV*(Y|jL9gq`BTEBqLugHypJTdipQE0t{*e+4% z-aVE-7RTuxxw_30r@L3o`M1TV62xMMF}>~l?~?Vn>pAXOP#!`#C#JhnEed^y(+5wm z+&;OmxFU7w|Hb4=Shf9mVLsYerfQ`AnwuCVO;P;kkfO&;WU`Z zY4R#grxbA7B?`PJ0jXYMeC@B8&k}{U$hBnY2yUldmfr`>a(#Y9mf72K4Y&5sT*37_ zoTf{f{A)hne2vo!mpPp*=`@Tf`O-ZZsuSD!e6FO|4WHlsdrq6{=kmek8JuQGdUztA z2PM5Tmd{Ivb9!{3$V)o+c|IQ{^|gvGrHe1EmeAWT0c$n~tY%+OOf^9E`=Og$(H>dt zPRMjzEvwxD>B${g-KNM^YL~2fvzxg5&41+d&Ig>nC-trppX#@k!uU`73Jc`P?em}n zpkoq>Q^oo2$a(p{ioAGp`Aj|!Ne51B;qxsLpytXD&y@%p5=+z;LJsZwu6~;ftd>P6 z?+~B&hd51^23nut^MWThy(wOteu>Y^Wf97o%;#C@oSs?1Y2KTh=7?{cL!h$r|9U(V zC)RL!{ZUS{pd2|<|G#h=C-eJg9-ptO;dG}cxJnk4EiZ9?sr0z?r+ofiE2q;Ib6TMH z|B@wE_kU3ePUZBT3`tihpPwk>^kyzkqf>A2`Fio@n~(AN?TR^zKA+Q55^DEJ?B6A^|L6~eU(M;ZotzF5MQ(~u>{`J2=`zjd zO9zfN|1}e%BsPbB&gYXQq;8YIlqEgM%4dG;6i$yyxz;6oept#C$aa0>IL@CY5p}g# zFfPRT&8f0ToRFA)MPm9csc5~7dBPv0L8&lVDhx`)2PDSdTgY-b6624G!ly)`D`N2j z+<|6asjNo$T&Eq1R2lONGDc@4b|;95Q)LzezrhU+ke$ylak3RJbN>2^obHi$kSEuU z^FPP=*NZ5HHdjO-C>39j#pGBO3r_hIrw3#)SuvQ;cdq1g>Zx6{@7pXIbx9mJEYEUn`xdkQfLA55ZpU?mo&Q&4RXf$d71T-t8>PWfuW^2>?AxdOj?XVi$i4m_d|v;L zoIcRdEqBxUWmdJy;xk3ofYiUp`kx~e_kW2iIQ0uoYh@>M<+pr(LiqYIe7;B0Qd#fo z+d02~KBox-d1&5yiqA_^IW3^j3(KeK_5V$|ysE@mRCi_?CY=cN*obHoWpiN@)oaF)c0 zGO1a7JF`p{4skV>L`{j~th0Kz*r#U~z#uLmxIKLh9+oM>s>oI(OVSxzB*j*QA z+9I)g-;bCdo66-%zsBeHWct=hfSR_M^GhYWo9m(1__KBx6TPWQ=dSt_CTlqgWEp|_FcHfM5u$tz%gvcP~pbGlu; zd7p&VR#9N~T;^Aah3?$o^HlNj;7LADc$?F5vCz(c;`4hy=JZ?|r(F{8qMCol83}TM zaNs}q{JKn+_e6p6Tb!RPA$5?1(1a75UoNX@|fIFX-)56^+8UT7IQjT z0^PAc&^g9`l|;Jh7g%7MY(nEyf%}|aF1}G9-aM$2^Kb6t^gtD-sY^KBBez=D%Mj0u z=KT7nIXyQLDb4@uuXDye>B$zkVA%W+d+Fvj<~NGw1Egm=-Ge^Cgy_5hu(MC)+M#dq5)JIf;Dr68VCE%?%~b;q>tLIK8)y z(^X&NbbSk_dH=)d2{|vHBlCY%h>2s5a5|epBP=sbB4hel&cC;Y(>$3CXMWD-IqQWN zAJ|sG=dBVEOC=%}$jzs`pD-V6ex47er4JtQTKv$mb+cQdtDdNt9(b|kE0ew)<@@Q- z%#E!JD_aHxW7a)2IBDd7(zceAhel_nTwJ$5v&A>y_?(e39j4yIuX%EKX3UMuKu!lEp{>r$H4Ua{~Jv3&Yuj%WF0bk6qLHVT* znfmtlF;D01c<3wNcqw*N;MI$JqN|5glonNV&uVKJlR2hi#EU~yTOW@3Ui-sWXAY>I zu)Xuu>&fPLdwgDVYs!~iEc?Rl_(30C%q+WJmGp4Q6YZ_}-Q5Wty9PdTJZnH!(U6o5 zpD(s#@cwT^Rc~*bkPz1~=CPIk9%zDx@qg7w=wt@~ck;nieVG6jX&-{LuL9Tvv;(_= zPT)R(uYmcQ^YKp!&;YCf@C8^Oefak>a0Bo?jK+aVpc-fcb^v>UZr~zt4amey$_9#n zMxX`Q1hfOYfllBE5Iw->!v{lrCBTLO@U;#c><113XMxMW4Ip+PzWo8L1KNNcz-izj za1H1M`hW`f=RBYV*aRE_&I3KbE#N*7jeu7I%m5mIHNaM&BL;JQKMoE7DG1Zmz+T`Q zkU1E=0m^`Rz!Kmja2^C8XWk3Zm4_E?p0w;m<113$AQbh4d5;?@^MrS90aZbeL!Xg6a|WaGGHFi z2($p3fOg=1GyVx=!W=*YumRW#bO8H-8^FjcSOX{qrURA0Uf?uv5x55Q0)0Ty6KD*m z0OkShz;2)uI1lsyw}9vouoTcd2LIFm4Zs>;KX3>*4x9yU0Cxf3NX$?m1!w}+0SAH8 zz(t@J=mU~Qq1QkWumorXHUYbVP9XY8SQRJ%s-DF7Z^gk`;0ACP@Qp?zKrS#Hs04NZ z-N0!eW(*nt%76-B9jU zMxX`Q1ndSnf%`!81dM+G|KtNDzy@F|a2&V{+y!DMVmN?GU>(o~>;U!x2Z5M;Gzw$_ z*+2!b1ZV_WfK9+|;1+Nnh%P`!fhu4Fy?T5<4h{jw0U!3cu|Nt?3{(Pbzz$$9a1iJQ zP6L^^eNY6H0gXUA&VP)j8qf=5Pl3Kb8BhVt z1C{`dz!Bgi&;#58?oWYXN}ff7Kow8}tN}IvTY(N>KX3>*4)~_Ra6lzc2Q&fefHq(U zuopN8#FRh@U>?v2v;ghEZlDLa1w@x(gi4#?i#QkqU zZs0U<5y*T24FN?!8BhVV1G|Av;3RM!=mBm4_kqBt(I`*_)Bsz74&V@Q7PtX4-^D+^ z>G&V01P%h-z-izb&WHM%%zhpctqG>VPI-9dHro1+rg3vp^Y80W<;0-Jzaz6c_{K10}!)U_WpiI1BjZqcI=_$OVdl=|DBG4!8(h1Cl<6jsitM8Bp;#-(uf9 z95e!(fOeo0I0BppdVuH!Pym<#Q~?`+t-yZZEN~gP0o(G;k5PwzwIZ;Ghr4d>tbJ6ag*3CZHXNUIGPx;lLOmA1DE; zfEu6ySOZ)J?gAs1LJ^=6s0QeZ_UnK)UR^fm~oZPzlrl-N0!erXKYJ*+3ak0W1MN)rf!213kd- zWoQ7%2TFh%paEC|Yyh?b9l#;r_%id|Z^u8@T(=x%22KMPfnJ~w$ZmiofeK(A&w*u3TOa2fc?NB;4E+%@U28gffQgQkh{|NkgwR3?nTUQ!ubwh zFK`g(1~T7*4nP^O1lSE60nP(GKy)LF3JeGGff8T?uodV4_5*hTy3L*fj0AFlbwC@i z1K11nt|C8v8>0v`yn{-B{Xj|+Mgph?>VPJo4cGzf1r7q;z-izj&u_mw_9=UBLI(upE$Ly7s|Xl{l;h>VS1X z8?Xb|3-kdoYoG&A0n7uI0Goi_Kqqh#=mBm4C2P?vPz5vq`+-BiW#BI0`#hQka)DxC z`sZP+Y8=!7O~5*!4Y&qmV?NT~wUq%Cz!IPZ*aUO}M}Xli@KT@wSOaVYI)MGaA>cT0 z8Mp!51$?bg07wBw0=ccIq!Q5|`(+prm=3f7JAi}0Y2YHz3-kd=e+wf5*+3Cc z22=p^fF(d9&;o1%&I3KbeIR-hj0()yGzJ>spay6F)&LuTtw0Ch+YE~WDVw`W--vp* zGd|O_{KcOe_k?d$0$5)(P-<@P_m3D{>dT#!o10r$lV_IwZ~WLHg_CeWG*sl4K(5+s z`4|7N)M}BNR2ZhuTKZT7UF7pUCZ+45sPvtG@u!7LPY%-;Eq(QW{KL}ip*9c-iJwl^GAoPSs0e-v@%)o{$Zo-p;ogftmp8DQH}5Q+QtPlLJMo_-j8}HHtL~w z55^DK^73H%XzKeT55`}P8a32MU(vf^x(Nj2eW)=|E>^F7xZSY*{$w=A7?(4`lL z>6C#~dZtSk=KFk4Izv)o`aAuj2bV|}7A-bUb@|7d!VZ7jfHrh9!ECNU?Fr21O+e#n z>*B#gAFY9{JsOQauC+f(^qm@ihDT4#4bzR5j(XIemTnKFfr)ux^^@YMhET23{=^C4 z8lnS4Z>e<~m>BL|Hw>F#PSyHHhucTz)gR9%5;4hx_E1IOt=h=t3=#>w?$1cKhbjVZ zRR_3{Ng@eH;}g^Ep^Cs+wU+8E5-B|zpOJ14Rb)}PmcSDvvgI&pv4<>DIN2Esn!b-y zL&H)ZXL>>{MpGNX0t6b3j0n>xJw$vV8}sgQbM9_@VwlEAYUu_z+T*7Gu3H)-`IMBt zX6e}E=u9)^H}Q|A+jCU{L#oE0`}~ia)_bmw&X7_UW|%Es_GhHc;L-&l45|8SFVViY z%zyR9r<&Y5@zJTC6h>C1=AkDuOw`}Hm0(nrK20<#dF2i&>4>NV1FPmJMu%pY6@Tkb zZ1&m+h3NqLF~c{jwsBPh`o;l*^K5`92rUfvxzWnLvoh4MAg>4mqVk+C@)&CM%*$c< zm7!&?H)B4B3o$8$5QS9VGMH`#E>E!E^cvtikwq;kTQY!TE0@+ahGjWVWDz1%nc)LT z8*}cD@oD%_5%UYt39ai0;@1q{^L5MLs`c9CJdt%AH1iRvD(}BB_+C|TF|BHYr9=N6 zpXd$#Lb#Y}LcURs&yl|}B#>-!hXkTi%SE38c#ulX!048n;E+ICn1%;w8wV}jIwX)7 zrk$lL1*2YWO8epyO?N~K@E>*I7Av!YWO^YJRc_9m^d}A|ft|`JkSChVL{~X@jk+HF z!c}gfp7o~%?V;-LI7GHvYLvO%NIFg$@y&40ub6EvPz}7^Z#JlR&sTdCZal} z8_?fMb1o76^=OpVzGR~>l{Pk+KoXSpWNN}PTdmB@dFWV4gbX}N>*=#H^OFL@!c{m< zRD*t3n$1ZV6m20NKBQxI+S12BH+!_>Hu>mdrSH?Vjn6G@42Ht^*WQXQk==apt{vfBm6?TX;Lm8J`H z(CY%+PD}45n#0AX5eH}k<*CM;sOBtCHCVeVP3lm$MQ3p;!{S_Nfo$mU!m`_=Q@Z;`uCJRBjLld>jy-fSw;PSVZE_=PSY3W;DZ${^(B(@~Mc0!bV<)Iby4QZdGIB@?~B( zIA7%9*II2hCe6#{60{6=0xqp|yQSkka%uREH>8*}FPqYju-Wzch#;s_?l>mR%Vxz# z*pGTNoJZ*xKhgVKIuHJ>bd#m8M$nE+=Le{C>JJ>%^59Nd`m&{iKXBU4g9j;1zqP+? z)<@9r9^Ks0Pwy|Aqd&k#TQ$#f9Ok^GA4Ieb-%zu}BvWbHnwpa1{^-F{MPbb%Gw?Tl zTs!8&3Mx#YZ=Q*w3zm5@!wO&prEB2o^GqJ-!AjTS67=tEHPBc)M6>HjQ?SOLVb9~rHYVVLuu`(TvAK#_tEVm z=i4gtCOh4~X5~v88tPWt5|y~csAZUwGO&p{z@{kQL%yM==dYuOneP7hm~>>IkO(@) zsKk0Xl!K%_6n!T;`(%XwT~2(sF@0GdfPT^r#IsnS{qj;CsMTKein z_@&T=Zcj5YGN~s0%a{{hY51jHzD2{fsb=Pvadqj@u#=7x=`@;mPNTW)iIZUVak2#V zTKY_UV3_HM4Y(3f1DVlb8Y83%gMKX0Ugb`_ zNP+sJ&3cC}3^{I0w;e{CqkgQsTDlMuNh_z@4x`O&r}V@^gcGGNqW7cCsDRUUp%YG~ zW0*&q`4Ke2iFS-0tQu{4?!~2<&H%Oto&p$JmD!IKWAwX6V^hrSK)@ds!SL$nS7BE) zny-xQp^QQy#!x*VH->GMQ?VkPH1k%b~!RS{Zx&Kx`E zPYhS(D6)g-PgKQuQWdn)K4HS5s??vLPo7rrJvB?6rGr1g%<^bBmzIu!dpu{>x~1u= zPThkpO`kJeKf!XMr58Hh(_`tIprf8Mp(I@WRKQ5jnXI2W+PK$lN0c6xZVz>g;4iAt z82A*d{8QZ2>-ecZ8Wp!DqvEYL`)EYP@DDB3r=`MHSm?yUC2+#$3`!46w};v;=8@KL z){4wM?`rOBM0UVOpEH{yXlL-rH;S!q1dF9|_sS*->J|HDEm~PyyKL5y<&BWW2=VO# z=6GQ9VO(|jCMZ;FI-VVXyPFCA*i^4x%ukgW39X9Fwgd!5k9OwgSxcWwK;-jim|CZ1 z3#L-BNf_eNPSnlC-mBQm9O72)Ov%fZ-W);0&T4x;E@62Q9ri36A2G#*9+c8n8(!Hi4HgY{!%Q0hK9SE_bT!g{VK2#@CJvqt#49}xzgQV`dE(tVt11pz?>Rzo4)zq#GdlYl*Q3dcQEt5Zt zs@$IJXkGwknj|*gpF;GRWPhP5oloDM*N#O$Ms)hnu+0k>!CO>cdJ3}G%pd9uXaTyT z1A6)iqPGq8PmC%yTi%aHs2D*xSBJXVz`e9Sdi<~0BoA}zbKL8QrGvx5&RMv~DV;lt zN^guP?M!xhi0LRw@yN>+Lf&s!D8A3Kfiq0;-#;9L5cI(g(f*J)Mw=vEy4ZB+EvSzHooNqGUlWV zR8z+}j&Ui*y8HWO15!=roBo(|&Jjttm}=aO0WLPFkA(*{e-b*O%F;u2h*xw6-5!cT zCpj@|zZJ1}(Cwj$Kn1O32L>8r{}?VU#3F@@CcppONAXV$GMAV7vmdGrnZa-PKNUwG z*VP4khMD<>KQW!|Do)@!C)Q#dbtLHC*aR~zfRXTMjHA-+4-=jBgZQ*`d#E*FEOncC zKAJ@Oo*Iy0s&8ZCZO>KC2`>=yrJI~z$ES|Y^G3^NvT)&KXswo~{7I(cqo|?gZ@c0X z@JcFc^TLIWOq0r_m@{4R{;&+Xr}f-YnW5&<@4NNXge^pEW!n|d)Sd9hBus|VYVwQB z{SOAt9!kGL&Q60aG_uX=Z^MGwO2hBef-_*?Y||A%!^L!>T!ewM&CPFP9(ko5zq$+M zvQ7G4_?1V)uhi|%4yR*&MeQuAP2u6Q`kZtDg z^JkQMU2-B=CDv}M;v6g>i&uLpa=x?%CsFesA$fBG)rAcRQ>cZSu-0dr{(T6DUTbg- z)wRdcIsfG9YVE>5H@9FbkZnT$=+rC1-Ii>#<)3hAtd+YzJk($-kd4doWoS^h zRGi1%p#7>=)rN)tld_yAvT!MtJ%al%*}j#vi{AF?ecZ>HA`Ayp;jIDEvGhB*a`1F? z0vG+cL$;~^4nmGc7nt}*1LI1IP>Y&z37l(?uX6dU#+A4q=QZo&eA{Yn5vtWzY0Ayv zE7v(ZXC_U8UDd5SES+}-Kh=3O?5d-(1T$`qsXr5+=FxQFsPuVD?*g5srRl;^=@LxH zIk*wH{PX_gbUv{PPNK_4)u4xjOzV&0lT7-L5L>*8oVmFHQ&(i>M#wl5G#5R!GU1*S zIzgW;?XKiy^K0ppi?{FOaG* z{Y}vv6Ll^=ty$YI!dR=qRhWU?{*v0dhOmV>pY<)mu&exCN508M9lp}xe35tjz711Y z>i^u*I(V%PArn#n{-FA1V;)O^rFGD0sZ)kIDFY|bGN-AGd4N88V^##OP`VD&eU8cb ziAy6!tJB0{2E!qK;*59^d`;<2OK*>$;V)WwWdfBxhsr~qeXU)1eChEA?#^=jq!8{t z=Sx={2bwp;m4Dkam(4d@{ui6;`y^s&f9mQBk5YwpBoe*zr*3Z%Ig~C=BKjQYus^_? zbbRR#s94_>t3uXKd3-sa^_}dvS5vYpzjP69(0e*FCuJO;OBrg*JO!txMw+|=Oh^GZ zoesf4DqyyscX~Y8@v+KbM4vm4-<)*_=w_w%xYyEA7n~kXcD4X*DcS>sX2;n$UzCA2 zsfFmz#@Ir5F2IrJe36HHsr+$Ie)Tw16E+VMQUDI;hW_~+`sZ`RD5NVrrD??geIY(^ znn%M{N}neB6Ze-m&$d)ZmwhUmi*;bW*%BLYs)FH^-b(Z*s^UDU3RYCv`?jiGALBP_ zPbSzdu|>C|t#E zEISqE>aX!^k3Cc+Ft4?mHCT15NV56hHUH3XHO^M+AQq1bd*l7xdAQ3deJQNLG}LOS ztGQ<8rTFowx#AlOF=9GVhIimV3{W|q7fiQ@+5p;DkywnwLW73_ z)9{vjR<97+E8S#idLS^}9;yiJry}$~(n3Se1Dfjpg#o>4YQlO}U^o|=W8cG*4s8)K z2$9;CLskY)`{4*NvWfm?NL7pSakGjZ3iG$v6G={A zGEXv9Gb}Zk>AXqK)TamDlI;U;$sXkQvK#VF<42POdmRxuW9Cxi7)aF_;l? z=IC+%Fyuu2jXyE3fpUDyFvj7rO`jFiRPn4?^?m%+i$^;XnyPrh7kYc?f<+MzesMl~8{Gud zfhvNbSU&Oz1E5e`rVF_(YU}6KEYBBxDkr-8wMjN(Zp6QXLDvhC28}>Tt%HuKChT zYcp;!h#nK@@0!&<^iqg4(-lEG=BU7+r!h@e_!9tK?pV5_CqM$pc1(*-8-h>HaVHN2oVXp!@!+c_l7msejAAi2hZ4(Xo4hGql|# zW$M4^wt)_48+7@aW_EoM8!+u3-LF@=!_rqGXn3m9Nmwk?OzJwfG-j;Q8!X-V-!a2X z?m8?~_ME5fgh|e>pwG%}S?4(XWJE#jXkWl~lpd>_QMo)=I>&K%=6LWYJEpyuK$<;3 zmD99elVMt2`+A2^m61=>aUNGick#3rm5EeU@1N0&hV}UMOzT_d^z>weOia2xm!8rO z(%NokD%EvvJ#O52)i_(9B>bqAX8PAVgSF6EpK{ZP&ihh0tQ1n8HLM_T`TV>u@pId` zix8BwAG9y=^Mm*v4J)f^*-=E>2k|}HG3Y_WXusKa6xTZ*4TI_)>;@Y5o4|;NM!fq0 z7I#ks{;C@QdL546jQSvcbeP6;)wx19x%{T~16)vhr7=&nG(C!k2F5&;V&3}z_x3y) z$Jcu>8~x_W2d<9rb@d~9Wex1}p+na=zCI7W?l;pu#QjUHyasNd`jx>+{igLp+{Z)G zh3(Qon?nzv#oI%+d129F^V@)b>>CC2LzY_iER6r6ug-3hbvfib>u?2=;7lsJ1Ewa~ z*Bw9SJdt&#jt?u|izccK51qZp?HABbSlZ*mUs&}=Zgszh2@72Bzbx&FjAiLMZPB7JiT*@>tFU%=xr|J zHNvD6a^_Jl6*8&D?UFN(Xr=~C(52}QezeCYE!_$_O?zDH%%gnl7NC*&gYl=Dv&I?3 zTFe2RZM#Xz+%{Nuy-MKrYBt(U1Zabmm~Icn4Qk;mDze6kV3U@7UoFvqs3h5KmlDzIM&n8WRkZRl0os`n8~V+Wd+VGp%c1X>lLM^P|@b{A?& zwz~#!+=_M<@Z#-u#%#fF&;w{Q0mns7*sky-t+tV9*!BOm!>&CM)xv*NiuM!%)4v^C zInSHp{$*uCpOuLHw;0v+@!cjDnKqV0Toz2U7THT2ZJH>Aw*kh(V< zssdEyVN{7JpMbzH;JD4X9ifBc1Gx!QAZv#+rx!aRWCzh!hx+C84g`(&oG5jJoiGdEY&Is-&y$j()!Tr z7zWQjnG+qHHHS8>0pF{&i}9qu5=Wl%MINKB?v{dGY{2)*Q_DViSC9!QU?&FOgP+9sNmzw%=i8%T|WoDP4(fc>Uvik#{1_ zZv4G%z(?}an(OM8;tzM6LQF~_xQ#Zl|8Xr;Zq2BZobyE<4y5wC@fW+?NJXd-R#bV; z7x{d=_dpB8W>SF{me$op7T|m-0Pj-yMk|l!^`A!epX@vnF((QkOlb(%G=i#}{7q*j z8F?D#COA%01kr$x{-$^$-6rsc$mW~S*Zql;JFG|zW)n8{_PLU<7;|j23Gf|NstLyd zb16b8_>L;oW9hhWxm|+qDBS_kfSDFS!%ftj)t@4I?YCTWI?-+3Gep}zBkKNEc)$wX zUzDTK)lZo_k0Gdjirpxm{zg#MuXqSFE%>i2UX1DV7NkAPFlW1*@4msHaR8N>Q5$-z zan=e)p7TW>W2J4JA4u}ECWPLu4Y#5}gh?rc5!6ET6#1vj(KJi}d#JiQ{t$zWHo8V4 z_E1GIifTaG3V+I4Xr?`6kwUt;uMLrbs_d4hw61RXJ7p`e@lxfOv&v1Pza-HzbhE$8 zY#a_xtl}ysg)ovz_gMO91nmS2dP1+t+yNc*N;|RP5Ybj4{6JM3`4?2oi9$}m82K<& zIXB%^$O#toH;Pqea|Df*LiMG;qpC8;B4{TrEP)xS%*^k@&h}7xOplgn4fG6Vl^OfE z(>~pY(qW)Km9H}MABP`nkLeba(t9nvIf8~O=>3xb{HMwseH@Qdd!^w9N^h`q=jj1y zCMClko8!sA4|EOo!JDc+ansD^nW&+G#78pWCNR1AdIol6Eg6_fUL{yXw38c1%IwT= zJLxz@ucgm{e#I;8I0fC)t+JQDb3%2i=&~|A)0pF7UFdj9w=IKfnoPP+n(6B0IE;M< zvZ>E>^>Tcp4VPn8W*2DB-4;5&ai8e0Ua)&uFXluqIE)S$y+yf-e!Wgiw}P3^f3*J9S{S!DGrr+4oB>?J9)Gt24SA}6@et* z5J5ZJ*$zwRJ?T~sKhe^G6e_(mf`)@A-D2ro5wznVy_UWdK|2mool2D_jCR|09OSH} z%OhyVK}v9aRb^TuXgG+5@=i;4{}O+Pab`5`a;k^Y8wFHm46e9P#Tb8*i5ug{(0x3; zrQcy?Y(2p-&Y)A&Rhi+q)Ux$F?KMMp@sw`2G^)rnH^<;XB~_&sj-fJ1xcY)E#^TSP zJQ_ZrnzmWmYEeJd)fA4PGBLOolinPNkbyU-OpBFi`3%vV`hOWdgrN+Caftx5@ zl_gbVnvLUK>%v!5=Dd~Zim1Zzm5L`kE#k7>9y`8r(#qK01YH@rr>Bpal#HNyqH

k18CKhv=MA?8cV5o~D{=3|7#ZQ#_|5BCYI#1R4xT^MOunsSJQhCK90hqj z5mwqJ#}Z4%RO4fb!j@*5d{>8VxLmoOY*zAXtcrVa^ODGTqlq_s9gEs(v2%i%$0>Em zV@5jb>l#BDz?A${S0x7nmS5`;SZjRZ^(0y0N=YDG);PrLnIlP$a!9!>!I7RU%1sdcs+fsJYL(>Nc6q@fPC82$n(>9%Xc4fNGz)vt~ArTni<8u zZS70CH#dIrg@5=5E20luqQhFjRIOvl`c_7^=A+$+Y-gOe>$}&}$|||{+EH??s_gar zjf<=)SBVc8W#LvG^m-avDc-U@fzN$RdbKyE&%Vl%Z%7L~T9iTH92y#|)oM0iA{oo9^3BuN} zQ34V{8kh=-zz%Q;b314WO;ZpYOQj31yQNC7!uA!xUUf2Y7r5VnQX0E59)ung<~C%{b*_Ggm)&wG<1y~WAC1WD*< zY+)v79#pv0(NH(3wdiE1YqDPIWT@-W{%ieu`XS>zuFz`nu<<&^zaBQ!)n)xU8~^mC zmo$9DxaRBL5yiFh)GIA_P`%3fiTmjTV0Jlb`Sokbn9mDy&Un`)?2c>8BP4#dix~xMCEQ3OXjD% z-X+9|Z#OC-zC>=tR*8+|JcB2i-+%RbJg@hbqc6~u#q}_vgMaO9C5JQ4TOvt4j94_B zD-Ev|pJ1>_ir7@dK6P=T4b6o;jE2F_ZD%#}&`jqm?Py>>>R|+e-@0fj*_O!nJq)$( z|3putS>TGwtUi|alC**O_-j3lV9;?=LlSjJrNE2~Ctf+pQXsk0!|TNtxDJ~`c2mislCeO%y-jH|S<1#O%ULd!68})(>U6N{DoyaB|e+X{vZz)vV zYKO>>zd`#zYqNXhChFROz&efh{)#_ zb(OY?UzaOAjaqW759xcgr%_vO7W2j&HghA{wD1x=>l;fYcbMvj`V!;Mxour3a02xzS#J|q{?;hHcr=FEc}FJZ$ApcOLDFsFWOm4L*){mLS#8ZWxW2BbWbsydq2x% zE`&;-L+C!(XI@7x>p$=r-g3F7Bsg?q+!`j4{f*|qTf=@ImSv2dSzt`-Pr|h9YedL5 zGmR=Tr$03!did{SyiC^hHMN@UQP>v5U8n*h-<*e##p{qWPnwVj}DP`uhDH42w zR4bIWPnaI}e8T8QBCLAC;2Tv!+GB(jBe}AXPoOV7fv=8}Q@oa&%jUlB9!czGM9aW| zqlTI&WXwTs026h*d3;w_`oQX_T}cVkB3TuDL_Vv+oe>G0O5$+P=mD-rt58!Dfz=n!=u_#Q>=` z;~ISJZ?md~ke{9vvbR2mu%d<kC}F;d*Z&wL zhlWyT{^8QA_=_uA3rzy-fK)IzCBInAex)lHv0pS2Ntew}Cq;#zH+qf?qvGF2&(mWVNgUAQ zTb-!Gm?@SlAfPzfO&Ql%;WiI&RJ6kV|7$C!TuO(d|3B#e&eC5~T5pOl{N>MvLInV;v!DM!w2Sdv)ulS>NuBpju@z zzs?>jHB*fydbZ-1^x=$HzUu6+>0K@TCsX`a%egt6peW1bK-Jb%lG)_L^P19jILW-D zJ(u`@1R*%Z_RtwLtd{Rn&7@08BMa^jwLzIOK8>0-DANj>Y6^&oXN~ppLcD1;UtXwd zxvG~J>X}w^)Rkab&4a4-O{+QbYG7K;mlqmZR!+3(jZCX~;IOe}&EZ9dCZ;u*Y19gT z2+zqSJg@&wcpGUo(x}d(0?kH{puZ;iAaWvb{iidJ%sB<0dP&lrWKC&z~}M|JjVWMg~AM>`a4giTZF zsCxM|lDnTphfAZVP^B)K>gw0XFP0B68Ky@MW-!XwGQm==8c4N`j>qZ&r-d0t?O?U+ zkjJX(u93YNG%EvbXXU5bV_zd*S_<{ilmYUmfZO|c(o{3|*HJjy^lrFi>|IT~mW`(R zyg12Huk_GXpy!RzsGpEyIjanhF`emc>q%e?QJRw*3K2C55!FUil+!t5D5u|3cwWnu z)njP>U$gn0u4t`Ucx2f{pXObw#_RPkf@4iXl^R(#k1-N-LKyIjyfu#a4|vAX-UKZu@vM{J z=)is6b?Rj*=QKvSOdL<0`w_A0&q(ojqi*oJE%p#%s`puM7W=@1tViOaI-d37oj|)0 z`K+a1g;MEXFTwe=?I{x&xAY(yk}*N8&^#;InY5y7)sL^9mG$aJ7DsHQd;(EzJ~fmC zDyr+{mkGur6~n8fEJAme&~=$A!pA%6NJ|>gx4Ru(}E?AmVD$-z@fLEz#3g*HnAT}%v9SDkhE-y)CL)yZ8Y@$Dy0)>Ak21f zM>byT(?bcU;=V!l&SHFWL(!JZbo{Y$VZ-k`#6FYgi+?6uYivHr{e`~xrAf?y94A%o z)$nAaH9Xm94No>&)6Q&7n5VIMf8F{;X;*Bjq)QlSCvmw(bod!N z1a+kCM3Ou?*Qo9Lc%}@UNIuUPW`u>SlvSh0jZ&CPqceHd?_<4DS_LZekmfm7c(3OY z_3}9ugHvxeik@eB+&GUGV$j@B!l=TyQM@%Nbvb!7Dv|R-G&SbINB1b=<2<9`gZD_Z zc{ZPC)THb&6_0e=HUgQn5x;xYu35!*Q}2( zj$LH)>@_)^&j{aIx-XaD6!QI7R6J{o%Em3^`x8@)pdTkm?Z+DEoGFHL%#`5>62@;x zoLC^APhkb)#Q$$kcRqs(568PbFUSYa7_I%D7ydV&hCfT;EuUg&zQ}n8 zn1#dkiOnYcxA8s8Ycq^sxa0JHKL$`P^=A@>%IJ7-vGkfrIeTz%C?8aduthd5VbN-f zTH4?Q;Y?0*99F4R(8~zus=#ki%Nz}ZkJ@r-5UpzP7V*{%tFEiIYKyd@tqM-IIaHFW z&H|OQ=e0$p*xFg^`X>!++FXtGwVoz3t z!5_TYg_V;>)tVV!Zv1a5CeAe)>XE4MQT3UEF5VsyDJ64_V13_JL2xOb__Dgc{c}l_CFNI2h z%ByX1?kR?nH%IYib{jSH*=7xjwpoLsZDtQ)4T`o|gCbkv)I0*xbT0pxP*j$$<{6RI z9$026ck0$QkMw#=uY=CU^J%q9U1U{~w#o4Ml#^{TZN6CpkIyHt)d*~>&`;#9n zG@`;CC+g?_p|#T@jw_ADU=ZET5};+;>wb!mw?2&z$l;yNhi&XX<$#=wfiSOp;v3t{mJJ5sH7 zaaY;(0>in-vs`Mth;SS{3B}UoMNUv96x(UfQbA^K*4aQ7p-ZZ8w}z8DWaEo0hIF%? zor1--sS6hBNBiFsI8RuTBaouY*u6u>mL5|W06>zU~ z5-MO170HR?vZvv<83>gwdnFedEQJMHt;m%F*_0c^HWn0Zjhrn~gU)GMJKrc4%GKIv z^h!e1TxH)HX}yvVOrCF5bw<5rGheZIl_s?g=Jq9hs^x=P6x%21Nc}ExM%rYxI<`*=|0h{xf-0`{ zP4e+|%M!n<+6R!YP}ga)Kxc^%J#`{%LNTAq^vjV!~=HbzkAhS*K||@e0MYB@6|x$)~SSTnkg@*R6@y>uTafPqmm8 z#)H&7bE8N)3iW34louxuT+8V z$1r&6MwG3$iO#;ke!GXtT?(se(&KG`fky=rvvf3n$}Yt?d}$Ss$` z*I;V{+nz0Q=rvcDTw@c2wh(S_kuIBDgjI^r4nowQ6Cnq8Yq;NAyb&yn&wOdF6CxO2~iP0V(9oa_Jp|NVY%yWa2j<(hWc<}kw;3rSPzBO#MCLX=8AlI0K@hB+TLl16iw zv==3f8Yp1mH{dnM7ICkCvf>=bxKe36)E&x)>EN$Oqm z)058SiMa91OP^S2b(e!z;o4);qie)ts~jygxan%bG<%h!+1=pml~Vsfs@rGc$|^@2 z9{3xv$`L6#uJ#j}x*DMt2sO(VYgW_WYL*%(%!mAC|YxcpEvUOw|ep&rBU+;0dwIUo|O4oED3wD2C%Uuz+ zLlK(J>m8Bq>0V>9u8{Gvo$XU>&YHj8(UQU0m+MLL*0@zK$F^Ne-s0Q7+b{=Led^Lx zxz4}CzJ6neo$l848$0alH+INoxsJL+BwS|&A1jDk`m=xRd$a-dSHi8b7}c@ zh*~y14u$XVtAJRWNT9*wrJlO$2*span%Es8BbVgZVR^n%KWnB}P88S*;zF*Yio1A2 zMV!i(c84%G_|4RI*+33xLr^zw5@R+v+PODxs)$gT20KOfEwraQtvwi!xe;&fw4jg1lJzlqFQVY>=zwFhJ^_0v&JH^S3 zR# zY6m4r%fw$BC`>&!v%Mf2KLpElHeUuVVkbKBStJ&1_N(c>+l*)8u*Z?-^~@p>#U-y>){+Tr0)UTODGHHYTg9{2fjx9!W_ zV(Lw^j=Ed0^35saJi3d!Wd~O(?ag!43F;%wiC2je(K&_dQ;n^p=4G#C5h7zVsks<6 z&WPd9f4myL*xW5%*-C+*xy^Q522ExUoZCwE@S#^(O3P5;PcJBLhsXjV*E)zBeHbu5y$hb4GayoF)AC%EWzjk z&41VNDP~&vXT5V8kAYeBMddXrdxGe;t*Y<2w9OF_X|m~xx<*ybh=gTqhm9(6ELOEy zT|7I!V@^?Ho6Wuxj-y)g^PUe*I>u-kn^vlvb}TbDzHA$NPb{rUgcYB5EYLdi^b9;h zgQl^YWXXAUf<3~i@pK-kGiX&V5??Cav zuZ~Nmz3i+iDYjl#IeM%XcfE?UFAnllz2>MIq>@C8@x8xRKd$mVZE{LLQ(U|k*H#d_8>1|DBt*uypMvRDN;CMPn@5w>0 z*@1dZ(Zhj0Q_YtC{i1twLYU*wo16ChvZ^!|xlaX#ZqaqzXOg(Gp?B4o6YgW^BQ>Ug zVcthE^qv~izSfVvrrtAvsa`R>s-uQDX6hl{>04FlB@+H?hGshTH0{w@o>@-4gJ%BM znvPVJX4d}XGMC<2PHL_T#@ZgiSj*fcKSrANe50xyva>*|%K8G+o<3BSw=6$;$|_4w zG8=gNK0LQ~u4hgi|#kVuk>1ukm#`Mmd>iRNss5L_(Uw*f?+jp*^ zH#AedYSrWh_^_n^J8xi~_P z)R-%|5<&2uS!hR!ofK_r625WFlGG$T;}?4JYw9t??jmtEQqR{I_%ErY@6*P8=owgB zui}s+oC)=bb_O(8>g$;rPJ|Ab7&czSvluo-pq$+=TGvh=00Bh z1ZFErR5n}ATkz2vB!dMY8x(_55V95rK|JUSrh~;ZnNu_!3qcMz2FifTgL#nBlmC)H7RUpoK*=K%AQp53gFqU{ z0tMh0P_`liVnIAe1k=HCPykMV>mV{8kAR*a2`m8FU_UsWPx>p{un4pQJwP%@2RUFr zxCufEa0K)P3qUqF4Q_%a+et2v4AMa!C)8{-7&}`V%q4n z0|t3Gt@^vMHS~i6u|!_2`w_C%R;(P_cE_@(5@hHBH{JB&k_jT~c>QtUAJ*vXk16}x>(Ra3q4sm)t4d$FOEqk2qTkD=CijZ=>jnt`awmqWmR+fb;wbR{hpOUZZ zI@3NG-ffB+sLr%ctES41>rCrTs2~&9XWAExIIYhjPS#ml8Tf_Hm+h!f(+GjM-cAn@ zC48B~6Z7VMV}X-*u)c+I*|Evezi5iLJ=EX5jI2 zySyH^j@edfkH>vV(&Lpe$`JtH4Je!_kZ&`DSgJ&`eFMrY+uKzvRlHp@DAfA24%wb= zPo&QhT#UjVmz}Kq9co7ysz0q)H^m;WAH|t=c)v4h?iKrOHQ&H$mKgoCe!u(eL$P+X3aLiYuh$kOyB4(W+U;4hUEW zoSE(?Atx|w2~pTV4UO!QpU|!2AS)Z0<*H?tN1=)EJg0OuxFfEn;p*(8;<1i; z(+Hj!rsb7`%K&!|0+a=|p>XJHF{Pva5=M?oBQr6w>bUs3qyDf4M|9KUz4KYqIJI|BPIcCOi~rNaqg~LLgNEl@(Wi@_#%8H87Y#>=IMqdeOoQ)EJkFFDjAsPcIqV z=P*4V(<{I8nm$qxTtlec^lIA5@9y=&;BLsihwK4A*+^joIDPAV)5IBM96W8|c;tKG z>`pk~d%}^?9f9`|c=3CYk3htW-}};!^TU+&^e{zv5kJ0(1<&g_-i-%TkI&L@WY278J#GC9y6h~aT z<^0ROnLUtQgzQm2*_z_q&byDiO%v*i$b5iIs}nx|?O=lRsTZjQeM&Mj%B(kA40w?m zV!2n+SCnS^UnD|YVx!|jZ0vnfIA79hyLk@UDoe6Hlh$y~bPTIhonO*@$D^l-$uHrJ z#TZ)c6&6R@67>6jynCn7G;vkRe1y#RKAE_k$ozaPpdxw(yo}>Zkg0S^%z0V&U8gZk ze2IqZV>F&Py>vRTOfaLc zVI}^Bhed8-aG2k6^)&I|e-Zl>v7j@y8;CvfKgE_J=2(GPn=|6zfBl>Z?~TSvH0GTV zZF>7@%tRw(6&ghq7UO;qIpnL}e!225DYqKAYZY>M;D5-Cc$LUlgIx4kZ)7CwA~No= z>nCI!pCQxZtf<_F7=`bN(TqL_WFzq5S&=UV;ClpGzlOkC1kRon17AY`zDM990;RZ168d7tdPGvr@hY?K+u}2gy+wMoo`c5PbAjTkR&0W;o^W^Pz%=o6 z0_JkjK5$M9L!;&auM@H|n;uOI0;*C9ww|}Tc+cLgDb&|7xdD@>&x^*d`&E_W(Qs`< zk9pW(s%FuWO!|NP`NZ0`NH;WNlMwjk5vC*kbx zm;5jGN5g~0hZn?@{(h0LS8C*;v4JaM`|G}qGSft}0cdPRW8=@F*8rODjX&GY`s$F| z_9Dw|5x0SdJi5)(Dk|aMrP+MUK2$1d55(+4rT^Dvw+_VYHq3rjD$Wk{^H75~&?t}| zDivMd@YBeU8r#v>Rx0xSHU5$sJJ8r&Dq;rtnHW4sj}F_3#ur|HQOcUX)}>=tku;ZO zIbX|m95F{BVqcevzx~a}4Mw8~jUP(IkimWyuaz3R&^T8rzVX+nF$9g>X#7$t+6~cT zG`R6g^uQPQ(|lX7=rT#EJxD!xQCt|}mr4)5iN;^k$0f z`-AIeCi>;$2NN;-IU;eF#7l{O8R}E1u^)}Cm&D;jYE56b>kh@z186k+#cOHC0lFZ5 zmvB!LOObILL}v9b;^0s}AJrX(;V;mrTjn)f_aJKqbKTA$kvdFwxqa#~AIYxuJiA9u ztIMa=BM-Metsc27U-Rr9c{S_P>XBEsKCjBVOp}K&ei$@dk94>8x+fba+2NWe5|VU# z&2*l~9Zn~8p7?S&qo{e}vQ5EBmSWKex|VH|^bq$7KP%)Sjb(*2hw*CGpvJPIrghDw zWlc?MTf{tpRUAl8qGvr%`0O)k9D9TzHTHyEwxdFNE!byoHS0!3+iuZ!gk==}u>r*X z#*?fD*x%CnAUPzlZ1){moF>eXMD`&fyY>}tWREyVogh1lcT;n!l=%{wOrK1yl=)&L z{Q{qoObZ!cPB_Ybx3!pWj3TkJy=HtZeug;nRbZ&;TdzZYlpf9b!~vu9I<+#?ioPwQ zxuN5*Q5uwknGCUX6yb3tF<#m~iZp8|zYcvFXo#{=%(gK|O{O|Nj6b#VKzSdx_YC>+ zWIfFB70OZNVn?#x)E!lB2UYr6rt^I7P*mQwJ>MRRCfVOI2Z?$1_fq+tV}BRP?_&Gg z%0%USi?We=m?$320B^pK*Wp^}J>S0VQjUqRTfWIB$3*i5H`>+=lH(uilMVD^EOSRL zc%SE!Lrt$%j;)0W79IS)%l*DX##+WLnOMK?ZhqfM_V?tmWa0VZBb&C{bkZg+e2uGa zZz`}NQn6Q3?%GKI$1ZOXnUG21keIQgIc$%M9{CYmlR|DIwuYBXmnT32EBn z7FFRsvJ)KD={#FcGwp%OUA1!5G=?T!v$1Hw9DXnysXZ6ZFzUeeb{d0>9q*&rWFDsN zQG|STEumXrsHb?Io~X*fL7VwV9{A3dTs$9Z=D!{sb()g zwZjj#eE9<8>1SIy3*JZPsHL+^Yjwi&dZzxps?qIjvrwOi&?2Ul>3&}M0Kw)T=y|e#$&aJ58)+$?_)yO??XII-#W<72DoV~`y}w3R zvFTDw#eSqW*A97qq{<&bXKbBfewb~n4wv$d0w?<_Iq@bmLO+$@K_A7 z)ecEDyEAuJE%Ia3?2emMtNUSKm>Bx8{)pMb>ddKJ%^?q@+@Mp!#U~At{NSzDNC8Ar$5CoK~*B{sBtYLY7U(9^jantndlRJ z@CgeAb{9xhYKbG~u(s?I77^(3IG3Ym_i&_MQAfP->T(t)di>;>uv})q4=;GueM(La z*zj|peRcPt6?Et6rkq;Als;XKJ}Y6m52se@j|FTjrFSM@u!~)V3v>~>u0nOUPc=)b zeo-oRNY$@>sv)aUrEzb%8r5??)l{iU!@XoR3nUL(4X#|%d}>{*ov;TDAJr-5;^im-7-(hbvo;cwXfK! z^KwwlyyA(-)n8XNtz1mmK)gqldk$~Vx5TCt7ct`r?ttpMn6d?(L4S}AmV;xU3eP>qCgAK4GaRQU?Io@#h@G*#Y8!1 z3;Kd_U;)Sm`@w0Da)d~a*LN0eF6y;4xX(qsYOT$kz0T8BkpBF{uY-~-)SYTG?=Hj};=o1v zvp2EB=pwFNygS`+Lo~aD#w|3eb``xY-5pZh5T8no+i0}wDh~T=)cA#t%qqe+xNDIA z<^~x8{~!~JIlt)b0@iotIZzL)m1V!^NgD3=DbsJ5RlC|RvNf^a>rA>#3x!J`TxNMt zT0DF|bz0UKS7p)oiXPFlgcvIa2GeVipgHIU27z?29P9_D!Oi2jadXry<@!LC*n4fh zR@F24sy<$oTeEZipcmx&jk&oF;;Y~FaL=UQScdfe$oyTuslMpB^}D`VukSR)Is{JTShcoPhSAH%J8wK>;`h%7IZrfd=itAdm{O0FOck8_`I zptey%@1bf&xX7z!#CxtKs+Cnw>~ghO&Fxl?`|@8`tNH|*R5$wgzO(G_f2td!H1_YN zh8bZZt%f0E*|O|r4NLaEXe>^QFkZ*8uOf_xG-COmNaLI)&uN!SLpSRfFQNHdl<}W{ zyEZM3Hs;HykF9UWH>_;$)vs{9NrQ^-Ec^SP2F55vaU@)%#Ta2cMfg#S@iQE*0t-O) zj~Q`QGyAgFA*{X8f#CnQz44380P#;7D`Zagl*b!%F^J0gos5QRPtm256({d>GG^*c z_h3Z{Cs}9D41z7Va7MqOq?MKb}mm;(lX- z@riV*Z35|<__~!uKlUO$PQPx1IeJrOcDyCJ&SEj8gXf`s#sF8>GAvfk5H`>pbO!yw zB(MNvgJMt$TxW@F5D)r-RIm^ffMcNSY(`vd>)x(4Z1Q?k@jl2hJ;?~uKSSjORCtKF zqq;_1OfsTlvQgvIs8yXSP5UJeA8D_tl;b6Kd@I2)bKY}m1gzkiXk(J-G18DvNBlU_ zXyjOn;aHcbJnHVX$l0RHD1&SK&}iloV@4UZ-OaqV`v#+DM6-tjYKo+{Sz|mSy36m= zqYU|NZDemdlZ!@MJkI&P(yxL-L|=ZQHT5ku)LLl7OY9JfOEzjs!#7!yOG-9E+?~9R z_{ODYL`Jd^T_wTK?I0_X#ggKns)D;p1I6iNBTze|h=_LrYKz2Cfw5Y4fSA%dkh@Gq z8!pFs!Z0FO^cii$m?JnUsbapKIMb5;{o)B~Smk6a+~iP{SJB807S1PlmiQ364b`*a z!FP;mkU9omo|P8>RI9~=q%sNVvDng!Q^g@W3Kh9_z z{DN0rCVVAvW)!cMw5@5l)bk?Y9V0YzykYPuBS%DyH(c)Tz2Y)fWGbJRvBJ#>w%nP? zd?)f<DRo{1O~B+> zj#~OmnwGA628VdMO)$dTL7cYq={YSuzeDudV(SFLzJahe2o+~181>u@yz(+Ih$}z& zpK!|-uS`UKBk~f+}Q>7NTCc#;tvJk3v8 z6LrTCr&$xZ1ES|7!xh|>L!Lgr2TD!fL=*nTuwxVc7#1eZPBOU0M#_pajn#$wu{{bW5hocoe(Da|u_u=?qkV7FP#x$w_em1*>qf5m@VIzhoMk zklb$&zLl{d)8uDPQjd6F`Y4Ed{ zI)!9=&d*3COF4In@d9NeD22dnCUB+UqG^f|6Hpq?(_qKBNIUTzf+oYKmWm@$Ml|#( z!fpp=QGKqt|5L0+voO?iV3*v{=IR=v2bBg>Y4_Ci+Y@ z8f);ni3XPszD*M4OvQqwoRRefMDj(E@D^1|HhD3milQ_{X`5F>x-W~{MWIeJqD_TE zw9-UXabzMTE)Of!i=xXkR{SnZVMWOVVf2W>t>p+Rk>D1-)QKpi5-GMM(PiG?14`a!IU}HO8vR1hotS z6$_|sMaXo7xBCgpe0E7tg6oLRQm=P}*99z+W&hH>wb$C|gdmR)q(z8trc)x*yz;&h z{EIAw(e7XUl%FRmdfmAsZ2&&w6?647&FcAU1ydpzC+QGk4?L3iCJ4| z(IV3fm&T9UZ;_gm8>i@+W;n$Dw~U5jQX1Ypz-eP&pe0`xAEgmbfBPxRxVU_8bcfHx zoo%@D-`b+hOxmyia>`g5myLzY@>i^0LZ)o}uh^Z0DEr&GPb=yr%I+0$awfIN6>)2( zQODfmwID)_kQeSWpJh~c@AIi)smwfAtSg9WwTfU&TvJh+;o!Gk5m^jmvA!ZQW*OCL zT)DUQvKkqg7*|9Q+PL}MEX(QNXBp2@B;(#CI0XbJB1#N-*NAaPL{$Vw2J2VratU#B z21$MBUBkCKD_fZ9nB0!ZiBaO=bmL(SZk%RBxVt0_9@fSC;H$KuoYSs`@9I4;fY zz?@lE{GD$2R;05<$Js`-YbP3EoS>ElMcgS?aOci8d}{~UV!Mt$-+C+_nrlSsW9jxj zRo8yf&wCZQ?4SC^&G9(&s3LaEHM(jqD4xpmj2(tXxAX8qqg_C(E5P0`o>WAW7Q2WH z+05l>v&fjBY9oR@`5zd4G%eyjPsB&Y->UXPh$rG>xv-ygz5Xk+1!? zwx?5$R3M2j*mYwaGA_?4Nv`Ps)$3P!62R%U&m<|?$P2dnX4Q_%kx>*ia|Lreqy`;T7ljm87u@j;208NxyQRJrvfcA|^2vxWF9j*7GE#9LsTHPibykQ#CWs zh|;TJ{dXeBx>wY@Ocp8<^2nCe(RpB@s2!-6|1@+;7S7Ub!&Erzjo0{+v>GmDhHs=iM`#_(rtIsg52=abNKXHdmpn7 z6`$@V1@Fg;X&;NjyQy2#*d^pkJj6NICN~_4s6BMQI2|XKkFB$zJMGp_Rs(dB1$j;G4V)lM~ zStO1eG(xQhWM!@|5^`nnZpOa&ITk;F#pgZ|Rrb>bI>(MDUku3*aPCenv0A%>cUcyT zL7yA3qF_J6vR!@|px>Z3t)eA;vrC-ZPaiDnbECSoz8qw!)jDAKZrckLgAdRgHNoLL zwn#|_MYFRsN9zw5?f{hhU$zJpH4fs-2NAyTsc3i5sHeeg_8U{~&JOGrmk$~>wcTtc z4sq3%+$Y3UPedLtI@}HFqA#$dDV7Z5-1irZRfn;;$`@2cj5vso3*~J?3l1{M$%^4# zyySzFI_tI}`IY$@=khG2sJmY|hYa5)lTh)~AzHm`T$r)yp4npmTB1EJ&R^o`^`+5C z)zUuptT=42fcySZPvaxT4AnefrK?=YvzDR`9W~l&x0iV;e{Dpl+PP0WjgJ|JRV|Mr z@yCtFhz8HY-xw@!5~Ru{#IXXf`tl%tH6{L~vF=6j=dz^OL^#IsRaoJjlLm`0^# z&Amqbz|7ZWq{`k9OMWnX_d%D5(Laz5SJ1feFOBcec=T5^ltJG1;)OxO<=lzfrFEKk za|HsKiM{$V^H<`hOEiDIann9NPp*{A!5ppOe>d( z?|#IxYnUk+BDB*K(h{#(=`}f7#|a|2*Q0kTCrZ-_0)oZ%6WmTF^LDV9dKym$i>0UO z!t!9q8OknCOzNWiG*zdq;7U-GmfpCuRGvU%=otne54~x7l96FSKxpvmqm%FM0tpsH zXQ*C+#Yvm~_3mo0{Sa$&>jbr7`|+&NQSV_ruw5oH&Jqv55vEo{z44H6o_P5BEZtF` zk_;XumC97RPTzBp#O*nX**g@oQA6)}FIr|vU+1zu#$>j9s47bP#C@>kl2Kbu zS9_veWbVx>SQ>C$$ zCfwX${k62o`hP4k0cXXW-;JuyLFh|8ey{u8$j@BKg~8<~0vyc^B~Y_FPq=JZ+0tue z6vbQqo%4o3eviY-)@Q|)n?~(Nxj8@~jV=AwXYCNks-X<^wy3v2{u8gd+|?w_ACnjP zMu$t0WJDMMDyMu#MfX;;+wun1T2g-%`qj~2e9mXJ-A_Cw62|iAnG`8Spf7Rw@FWq}M{QKijvAjO zzNon=j;uCA9TPD3>UnYSHu*Q?bv5R(d!^fWolKO~6@PLz+4naQqZ7SO3iW52+F$kt z-TyBO+IcOAlr2Ah58Gt@KM4yK`7CJtb8yWtt6omRtx_OG(Y7z6JCV+Lnn`zz#*f*V z#}^!*{fGV+`zK@n7e4zZ-?cvq(S<P<;%w!e2=Fy?*7( zxYw{C9{f^bokNc(#8SH)sCUcC9P~FiMAzB@&x^>wfcTUnC_GB1nuRLmF-4jB7fd!w zmD5;{!*yYDdFrF^6L1{N;3c&?+!mJW1aa^PxE(wdehPjcZVxYopN4bcj_`K46MO)E zmR$g8b;)%-P-p?a2*<-O!Mv2f!kUsQi`jqSWVkn+3cm_-tXJs+b6!?n!3n4Xd<7l|Yh>d$VAdYwHpf(ENVqROMM-VU#}E|a;9+o2csM)&PJ&0mBj9Q9 zNO%!E3jP#MhI8T3@P2qad;*>T%Yr-+Rwy2mVA-}$h9luAFt7Y6(^B|&l8?9Gm*D9z z?u)GT<6G4E_v$0A3G24d=kmJBa^WK3+p%13Vnw2+x2w!SmtG@Dg|nycy1ii{NeW zakv2f3EmFhf_K0U`YSu(s_<^O9=r#B9Nr6eg!jR(>cs!&d<;QhKRf|G1kZ)Pgn8~- zIShXWe+3u7#qgIfB`5V1d=&l_{u)*cs!CYSeIJMG!Qa4-z~92{;S%^on6>KEfhl}^ z&&OE!2RIEr0WX42!fW7Da3TC7`~`d({suk+pMlT9W$-!pH~2h!3%&pclT(6~4xkly z8axA9gZ37Lp_}#GJ^6kG)B}%$8sbge>?byuW~4Z*oBh=$;>XV_RfC>2%(u)=h)BeV zN1W!fVw%&eDsnzk1I+-d;Zc>A*2M$Os^9@qLF)-j(`rFx&u^`Y~`r_yb5G5qDx67k(4&@4fsjeh3Den#&A2h1N;=+ z8nEjRyv!C!<-`kurMUgoBm3OpH9L_`D(w(Dqsenhp0FNb(wx zm8WgsKX(lf1+p=vkESXQ+m~<@i@?C}P}IjG9}Q1{n@NjBqY$&EX*Zod@zzt(mC|o{ zrHKto`fb?G#g8b#bmsiMNW*ElsEZ<#HTJe{v&Hk>uw(fZ>Je}Z+yo)NlB+-~&>JL! zbg&%k2d6<`IT;tU2fe{`uo!GA&y9Os&8%Y5t_LcPBS|8ridj40ND|Y%E7fLV(zSpl zBI_mx48B|upo^R;<}e17bwbTX4i$NAgyZbs_?*!Z83 z3|dB;>{tpnU2c96=XOtAgR4{=q^%;{HQAP1<(9LGNQ|UI)wU`II(rTH*3zoj59=!8 z)2etm5C`Ur6o;#tzC(732(D&EyIIqByze!tj2b_zpIF-0c!+mgMxg6(pu2RW_@ElK z-O_*gC{&ywn#7(^Gc2>ZX)vpn(T_K=?2erxx>U!!j`{MDVoY_Cru_fS{DU=!7X$O{ zM+JzQ6HKn-sA0N-`E@s5g2c%%^C5AkrWqnu4dA?d^++>}jXw`Yn$CU3Y?4SH_r3cWy_CGEOteh^)&cYxLHd)*Pmf+ z`CBYQg^Tc-1ip7wv%2Wk|L%maBF5J=qnkM~dzN8^Oh9FHQsVH0{#Kt@9dasT7h_#gg18HxWZ;fG&G3r8)pw)~KAEq-kdp zRp}wDt?0d@&7NBOQJyW)<^2GV^E3l#2aNr>-n$zGWsD71cE6^GA2a~`8kPY^L5>O6|Yl;#DT7e!Q38aDLpa2{L zWkC52J3;Jk)_nR3HOdp!*qjn5NA6io%_(xyzD}%Z?FQQuYu=C}l!9jF1xlSj?Y4PT1Kg}z`MSPV9S{opjX1H!K30}u}efmDzM z^1umj9n}Aw(12u+4zhpGh-$y3u_s3r_g67%1;~&8Q%`kU&Mn^I`%Sm;~BgK)?RJJ2Um$Bwk>VEOy z7;^7HtV+&R#aC5L-@VZL#rxam)-b}XN zBx*Iz3^7N0r6a@{Y4@OUW_9;?ubOYQBw1vPGoK-N-;KkqFL7)A2BD3ohF$OHRse2| zw%rzoGjvLCaJCn>X(R-X3ENV?QD+R~W#fqm(6hK;gD)*2{ zrf-36zi2%PJBqR6`%PltBvSf&KRbf{--A)jUGBBOmmXv6JkoPAdE^hTp07&28qCp;7H_be1+NsRdW%fC& z#c!FM!y^8jZ=0Fg_nSP+-j)@*?R%A>jJ2HE$y|v2&*^5q++ZD&PM+*J+cIKl6!5LFUAu6B8Rm(a zgNCfJljagk`Eh!l+0xo9-1c4cW9MVBRG$8xt?a=Vr*u%MpJ}EA4GX+QD*$3ad(ays zgLJSQ6o6t-3hscg+pM;Owx9<{1oOZuPz*{z$e+l7wxB0S2I(N@Pfy+D>W^whH+{tuayr)x*&Skxh*@sNXmHo%X4Qa=TsQdK5f<~D ziH=z7!ky65WFlWannzv~hx zW5Bp%Yfkm9E!|g}tT`aJ+AAj#erL_W@2-l=q6iuNIx@R)iKDBpiug5VnEpE|XHb#b zsH;eAU##^Y)`*WCYs_96!H)QhJ`SPm^BJWtsgsx`f6weB4$I&3I*Hrz_v%ifO}5!C zz;a^0*3pqlEqA7q=V-S1f!d)rv7Q9dz$#D(N@-RMdg)vV0a@H>PkNmtWp zB-=e{js4iFH}C8g+cE0chZlC%7Z*00F+n?}6(a8Iz&c{yP|ct;{ybG<7vj?Z!Yd;^j1 zF`K&2du63(Z&(XB){%BpORwQquLCV{K=v`ba<6Q)!AGM*FpJ1MnE0)5BqHibZ#(EAGD1zqR&(W_xj>=+7#CE7o*{B z%)R{nUj0Lim=ajCR(~0DOv|b0wQEx0JK2T8m2Hfv-+Hh@S;mp2%wrG*rs1CZP=%iC z?EE2KDWEq;mM9=N2MErMSaGm`(s3i!mXyJfwy@MQo;upv$#K(Okjs+0I#8E){ukQc z_RAFZH}_!M*P7py_nvdLmM6eKeEW6^*-g2jp65xoo0Z+7S%sfuFm4KShv|D^aJT5P z1D_qlXJLC*drA_i$?yI<+Gsr*5_3`8N{3-s&0AjdW`jH-Nw$$BC3|J8d{&$ z`xk{f0*oLz+jdJ{$!_1drrr`$M>3H+Yq$T{SFabqs0LcQ@6=EirgE zCcCw$2uDpzWU3U&*=`^=b#gI*hCYj=|b zZ(B_+h$#yCwOg=3uGQye3w%HNbIg5(x#mxZC7+v3HTdx7W>t6dCo19`W6Ev&NQ$wa zx~PRuPvmZs8FmH@anh*3CNehm6N0G(?Q^e;xO|HnK0NzP-%j4$;wNMr#khI+2~qig z**M_v6W*YWKS0pFd*a@pojHK`5yZJ=(Rt7>wq87l#!)n$Z6&50q<;cmDKJ}$k8c=m z(Q3PSpQyupiwOCGl>bv?Oi=5H7GF?h?rBw#{Icr&Q(T?G_LD^Pv~OF9+uPYdvEU1{ z72!GZ1#Wze8@*bK+h5=Y9COG#7$91+Ib*W=p7()M>iI7T`7tCfxAvx;`%l{DufL>i z_9@9aQr4z-yjA{Urs(d7gjn`(-jUT1M*{GxNZU!_m*=%=9iv3L>R8KWN@AOPeSJq{ z940S+;#HP~PgXT|#9oxm<343^WG88qJ;sp1iTjG+9LJMUPl_R5(GW**rM`>;=`&fC z{KbqF7g5TJ>@T}9u3~-O-NCN?r3h!S8BvQ~+TH3-K7}%1q+Pj4Km27s`+#K}c4PK{ z>C9p?u#dly#Dr1F@?~XTEBHV3hV!%ve^OtrdHCzUku)kPq2HSWlBru{F_r5VcMZ>R6SAhKW)l8N92Vam&Xy1t0UsIb*qx^L1V9#WFH|ok>u&>L09!Yw_q?@XI zAV%b~CpGdIQRe8vsqb&Hw>}lHFL{)j+zLF#MTeG=o zbp^4kt-Wb4^;@%T06jjjb0qWkC%!e=o!UU${?>di%H$M5)RUfGSImQ&Mw(37uXPehSIt1J z{!^YYSIrGtfQ)r(9ya70+xFwHn@v*c|IKg(bOT8s4P=2la14}zkbfBZg7%;{NCR2m z5I7GEA~y=O0zE(?m<|?$P2dM%|U072&RKo zpb(q}H$inKuVO(DkO=01RiF@*fIA>8P*s`)su^)>x7;vq$Q@gM{9)b~$T4sI4z)Go zsD}caW96JfaaAYB=mVS&yEuRT>wQk^+_+Q}<3gPI%qob}HIaySJLg-c!(#)`Di3v@ z#f~5AI>SY2m{U$1Ti=7iE51v^ofp*p%y~Nh(E4+ce_hO-sOG#Ne^{23RCjXz+&0*) zhOJSkA=Np;ImdEX8Yz#kt*nVtNj05v#qGzMPB|+Lg^O{KKBaJR$NMdPm0HU=#238G z+RlMK`AM~%YrNl{R&|_CReGoVJ{;;DJL!#b6UC(bW{C zoR2UAOF&PM1eSvWPzn^2Yz5-MI4}EC&Uk z9B?E~Y2`{Gzw(g=vcNG=1|nI8Y7Y8>aUdJ)0XIQNW%NL2Fb>QEd%y{B2ZY^6tp<96 zG>`=fz%jr90VN8w0Np^clmF7e@(?vQ?osayUZyk5!DX_JbE8E}rn9yN_u1p*iO;)h zydlF?muGn<8I@$VrurfmI>X%D3(LZmeLtA;T+)DH{&P7cV#Gpcw1ewj9e<1#A1rj% zHvjO-))PgAECRM-3$G~8U?*eeivhlQ;t~rtPZ}3xQ>f=Kv{jF}50!6EjoUv+&82S;` z{D?IdCyLCEob}unz49`qgUGB?%o|XNe z0pgV<&Zn^Yqa|2<8mr?ciG54(Vf>_uM36(Kfz~kvYvyC1NJ!;qNZSGyYzB&{^1HA7 z{p!cKH&9HrsqTA0Y}v$FQT7!lPm{*e&1xurp8wbxB6`ZN$Qg`TWn>N%MehaKx1P(z zgn{D0EK+5l=$PeVyvF-u0^=H@*>76EVdtqggnNs#S}hkHr+9jEly>Fu6x%+T?lRbK$UGTc zcZXM5dRYel4Yi`{nv^h-bHj02IMwhIrweD#tZ+Uk;uB|#`An*9 zxwnA2vV&TByKN<+(Q<^(Bm8NqES8)eSj(kco4;Gg{CF2Yh!7D7X;yf}VX_#@yOZ@j&1zr|)&b67l#d1la-U`1)<} z`YLBV4ZgI}>AN4jL>!j_T!-dx%@BXDB2ry5DuRW#ltdA?&RJ6|SVbA>yPE1K(aueY zB4eGEjSsBGhD*|k8RFV%>BI~Xv)Vb*I;$fy)liYK#*#d~21%|ZbsTy}{JqB6*nQ|7 z+bx-ZGXAOZt+Pk+ddFdY*Fg@m6VSR2a+r0asC^yeFsr7uuY=^x7I`R4UI&R;Zuze% zLatcfcQ1s*`T=SU-L8IziC40nz9X+CVo^4J;|fv7&RJqtw$nHFP$GiXqQM=Yj%M$Q zrfZ!sLCxO%-=q3dDae(ZjtTFI!)r;C36|jO&zyBcab?XA^BBE~yw7C+t1?U7J+mpJ zo!8Nb4wogj8e~=d!+jBZd>t14iiLlqi@(>=5dD!}5nVFJv4dRZWvlcji7xB0BgwK# zB(HPEikxN6phzZk!Xj9gBYK~nU6HafU6QN}TPqup5JY5uXOCCJSMZaBnqw92jyd>+ z%R3!^&k-YYoG}{QCfDh^t-C~AmI7B1xNokgnu`E@k3dE)0@o0Tnk({i{UZ1;sqq^c zjpvG(4dlSab1Q-=N1Y?=EmCqAIl^vp<*0FlY+IOu+CUvNLY$G`#rC(QUhbzJveA-} zc_JvxGAgr#h?Uu6gm`r$t>zoXIAthm(G;$+C~$PPvb178xW< z3jFRD1+r!vA+~SAmzC#Lq@bLx9>D{BG(3&{l;x;+glM$c`7%}V)XhZgb)weH5NkHm zewZ1y1u}gRl=mC@+6=Z=kp1i+kCZJ%wEH=)v<#eV=h%lKYq;K9@ZkYJJ(-zC+6O4p zw>Vqi@Lr5Ne#hab=8G#^$huF>uSioFPou=t`E&``hhfuHS?-gjQ$eG2w}L*g+1Xi? zdYmrpGSBHU`!Dc@LX6l#Gh|&vYds-Bi1VmCZ{YC2_iY(bRJn4f*q!He z2U$uit&o_;DtbfS)5 z#sGI2MJBgE9Lcq~5O8KR9*#i>EO<>=a}#@y|IEzQTqTi94th=chgOjUNX z%X}wmLYahP?L05D|5#CL8_m#Is}2m3S%0j3sj{4Y8f*78WnzxCDnRR|;jvczXFYy0 z*1iu{X8WSX)gr&!;|;Jq6JN--_&SD}~@x!mI%M1gT7Rc4OEEjzI2n zUZ2V=BoiLDwv$(;E%Zf+T@diis~oTHyq&yqaZ!bythX#9HEV3T-##(4X>mo^Wv6DW z_-H%*rkP7@WtsbAAsH*a+fLCMD}I;mHTk&0kSq##k{+5^_~J=2w8kqgXLs`&BHxG^Ug*oa>UMz`C$8>r`i>=+h(~u~&!5;+IZO1}N!?UAtHN0s zl=0SPNp-v|85Mnbe(uDp6&MP5vkF2sLh^LE4;t66v5y$9Ww=NJV5o-~3 z{DsATE*0Mt(LwvuYb-)s#Zuu4H$!SnR4clA30UQ`aw1C+SUFK7>>^|n#nj!@6|y9w zGAn@h+$&Dcmxz&%xioufQen>+pB*F!+0zRI|=Y%z$wtHJukJtpgJoD4aoI zDU743`{AG9n=p>2nq-$ta0B=} zmpTSkRgS8_OqHdkYblDt3`=ST3iK>ed0J3mQX`dvbXJV~1T$BWdcpg<6lO${Do@=p zrH~p%%~J*Dh8ZOcmdBF9;s3zZ;I?pexFcKxejbj1r@>M1oD@Fl^KllAfq#PUhvhk> zMzBIzd;n%Ew9*6)g&%}#!%g96SSDQqxEa6ihaZKxw!%_x4*!SWk9vRq2X4Xd*6@S@6oA$6=-r!yL13ff_Ga0GGvb@tS6}OZ= zu&hF5Xl0usf6ILyec{?LnJqO6?gz`Nvp?Jz9tcyYEOU>-(p)Qe5d0)O1nvVT!oeIv z3Ff3rUF8As+#%=V8sqv|hnx{98~~BKrKm6>bi{1-FLZhM$I| z+%xby{O$(NgkOZ;g?q#4@Bnx=JQSuNq>g~!gGa;f!(-*?mP|e-pdc+I&sx9Vh8Lnf z6J7+*_Ugaq)&CG)jQT2g37iXO!Mos3;4k6j@G*D=Oi@)`{06)YCiav9nAlJ_QkXg)mI1aw-!oje2=coqbJ}Ru(YKfd`isx%2_kTp2<*^U$8*_$&6Lz{Vv6b?CoEI zqhVxH8^BlK2jFt}5%?}_z&GI6;oI<=@Ev#*{1-eC{)gJpN?TRq&>RW@ z@DFexEYrw@$mC-C-_zPS#j}*Gg@Ox zrt(o|MBV35mVMD~a46gzmPPUfxGDUi=y=pw$Fyf*RM`=@Vuq%?imt4q`oPk30?bmn z(hrvTpg%0P5Db88!GmF$xU?v#55sT5vi2AXcZF$Ttb&~c|CisR;or$JhQAU|AEQ9q^G~b`SPP6P$24Wyr^H_gQXcqwI1fGvZ-ak? z_rkKE?}N|rn?8*7`v`o2-{;^`_yT+hF8AuwiwDv}f2<<#Uno$^XaM`+!wZZU6sg4shTw2j!@!s3@qQn5dMPn52}b zn5d|jn5d|zn5d|jm%Xk?x)v5kK)I_;7|r029JSM zv2TKJgU3Ot*a~Gm@4kSR_m-bW6;#350%ts`XXG1Ck{S8_2&8=Du^i(KL_92Gbm$r| z0`7PK#jrkj^uy@jxXHg|G2H8*CxTyrE5UEUr$9{HGPZ%=gVe9DfXL>2QzL#*K7Rm@ zgFk{Nz$WlL@MrK7uo=YU+4KvD$+77=NDc8fuo1ioUIkk~YKX1i@8E5fc)>m0jK#_y zF5rCe;#h_|oOSRK5Ldq$X&@$!8Pqg7fmF_&!91`VNOq?ONbTPT{0i&^ehu~kJD~ex zf|=0+3;+Yc{@?&`AV~IS5ST>s`N8Y=j z3=l>Ow_r^fFj}U$AdHYH9xMkJg6QR@1n?Jdk&5`Y`|H-XxA8=QKduqI48HAA9?L;H zhpOdqZV$)WGn|U{V>{1ri#Dle!taNrp0t5Qqk91 zLb1|p^wF&#_0epwH;6S_qmN=~)fj%T0GcrZ?pT1!7!Tr0Q5W6su^MZ+NDWtuFJcP4 z8@|-`KL)AKo&~AT)_~OZKLcr`{T!qz@fRTV-G76#z&daa_%&DnUIJeS>%mg+8?YSw z7JLhA04qT(`DdJ=Rg)j^<5M{N2vVDF0;x@31CdQrGiU*^;F_U>zk%z(3#zHk{c$r^ zlxKZ~Htp=f=YcDE<2;6eosrCNun!mtlI?i_Bnvhg91A`KP6QtYCxPR@r69IWFzVtF za4U3t!y#iA7zOSH@m&P6Ii|_ri!@kANV?a9LN5OYM?7?8nre}j+K%WO* z0pr2n!1R*P#e(-yc3cL|K4$^=}Mw9f9 zK)m*07)`vyk#QM1-o-GCBHp?%8W`THFbbaHS#biS9vw>cuA3$6pd2U9_6`0K&W;FI8eAhw^+2nEwre-z(Q~{_zFmE z?p5q(lJNq59DqX+_!>x^`)lxBupS(XynYW(2Y&!(fj@$?!K)w{t!8io_$!FZb<^)4 zT@_(}lZ@BEKfpuapI|ZA3ewfmZOdG~vNgGK+tI*};Sm5*o54VF$(xT%(z= zFJguth@A&B27rUXVPG)01H2c+G~aX|NE`0luPPhd-!d=CQyaf??-o54&Tcp_ybNh{ zQtYc@j4=~H>fDcjq2NSt92f;sK~4r2gHyoeU^JKxPF0QHVI=#`xRs%qUgqVS8Stf} z%mm34#DcxSSzrK&k53rmW*kU1dkz>5QU`e$oDZFjx&Wm4)bF!Psv^!u1zOSDya_gTO-YKJXRLQBY%{AA&v!#5Wa;iAD)HANmn+5qK1& z>N*B)0^bDD?$b@!7RTu9bQaXvPeLyMN&hGK9`u)l)c47q`o}4_mx3RF4x3yF{S5RE zBwRIE1N|cSDR@)d{{X*$?nYOj7w{uU!>9lb2QPwTYiq%Y;8$QQ_%%qEwv>UT;5X2h z327;bbh5>l!D{e3kd_&)fLMGnHG(bRkKmu+PoSQTj?si4)UkdByMfpc$e3dO0#XON z4u*igfuq3R!AW2XI0O6>Tn4s+w3F3s5Ld4zXE%)2pgVXKq>STw(bNw5U!W(L-q#6} zbNs-YN+uhK*BeY;;KN`Sa5~r>oC#6_bV=+3{V`!2h@FZu;=w*(BKR6Iumz;>PlNs8 zz6%@xz5xydE5RT)*gQNhZW;s!T%eeO!FJ9t86YhYhk*OQVc=`v{a^_=96Sy_0G@ghrq*bAbsoASX*@CEQD_%djM1;u7k8E)V~urqiFL~)v4 z2T^*aVi2WcDgjr5bcP$iH=yIB3_TMphrUVlEpDa`rnlgLvoO64;w(%j%aWShr zPqX`zR=(Y-nO-n96-oDjFO^a+kcJjtuq)^X27tZ6py%8 zKOLwuI0`zIe>fNnMu0T-jRi-7<3XBAhJlN~$>16=8l*9AD!3V(4*ngS0X_{r3htnN z5$QnB!eJI1UIrfnUjySn8b0QN<={;41UO$s|LVTj`qqnl+5M|3$iO=7V))W&B!YAr zNuW2l0;J3CWRSAG8XO0vfRn)|z<4kfq|xt5a3h!oW`Y~REgpbb}s{ z;gBhiWsoh9-H>9)8OUXb2{ZbxkfD%?kR=eB%EYpkk24LLEO6HY#}2d(;+J%TOkJ_??Em?u0!0s@p?nTuAA<@7Oaw4GLuxmO+1*I zN&D`0GC!tXgr>FUy|>z{`kQzr=|GYbEjSoYKmn%q%DV-(_1mkGT5PO5r3DW^w3kPp zTJS7L0v4Jb!JUlYZ61B10P7?`Pu!o!xQFyATHNDso4@-X?tzvY$koy1YQi7xqh0xB z>FX-@4?G%x#XQR!%hj8IxH~q&x~^K_VgDT-$0SYDv}Fl+{P=r4@J{5oKM@%#fR?wH ztEc{S@7?`v2}@6k>_!eRL8x1wUv9kh-c3afb_$jUd9Ew3TZoQ@Lre2=_28{LPqkfF zndI>YJZ>*nuia{ssYden6CMLss1B`dJfd6SaSI-yE7bZ{JVy!cYrXS`-F4MW0kAk} ziC>|*-A1*AE}wK<+(Sc8JjOe%Zvw)=X`d~|tUPkn&X8#s;E z2jdxX&qvLcyrsIk6ADMIc*yLXw?pq?etUV|A$^fkGu%eqXU4wAn(k@6Z4`-S8pNNo zoUQ5ood)9AgTKYAL;E#ELsm~{`bKm7in0gI`fJ)`UvIQt$VA9W$X3WpkmHcEkSh?n zU*8on6fzOA5V8TX8&VAU0CEX(vzvzR@txLo?QrpR9fR}RcigP{?Qroi?>o+W4d=Sh zwjk47^*~Dm{LdXX_77J3U3Htsx#P6Sojk~*!jD<-H0A?%&Tio`OILL=!R)MVB3R&G z60Ea47E;ybZ9Tl4Z0ZenN~VhT7sl6y-1GsiQ;n^y$EY+ny^rfy9C+LbY`F2P3pOfo z(`|NWcaBUg`Ba;i7*Fww-o^AnBi!jl@3Z{dc%vGj5j@ta_p{HGRJut9PSNM8`q)>u zamK_Kp{pqLnv-{rN!{y|YPIT#UY|;xz!;@>(7RoS^o!Ly9X&z3UKdx6@7UWQoDK{kvK{-(ByfMt4KI{de`<0;i_+ z5xwHtO9NJ8tA&qL?hH$JEEtoAvE9OXM6zC&Ncb|-4^AC-b=P~?r{aDhRTy0Q)l%oZ27-Kci~8~!1ZtNU8c zBcX(`D!^Co>6C!?8m|trzNs`ny^lKfAzqE1d(muFBmH0x75X~mu$!`fgg051z)fw% zyU=QjpWey-srWih`?j*rv~*WJA}s^eH9y@Qmdf~mt!Hl({skO!;y5*+w?4=|5j~8O zr2?>ke;Kb9Yp$xf8k_j7+>Sj*{-VO~qE7bK-GcvWYoR0>MQ`h#xO~B?grtP!G{3}C zejg*ZDa&0c;)}R%Ib$iFCx*=QR+}XeU&Tjd|Kv28J}!@SYBTyZ->Ddg9D;H;^W4oxndFBqLAV%Bah#o6fL z%I|)>Ah%?-^H984m^2(2TaLq|$E%H@$WZZclyW-mu2FPK1~9Et)ySatx;6%9ITZ4y zzPV1d!dqLXyh3%y3pEQ=Oem7ZT@6e2d`dbXFdO&k+NN5n-Rbn$NM zohsfmqbXIbp~y^I?-`OAvQnigXvF{YUe9@@u3xI+{-^g7_p&z`u2Plrzr0iLHO`c- zl}lB{|MXrb$M!J1oBo%##HRJ)fBGkV+dk?8)^xkl;(%xaGMVWj@18QlWz z-PFl2eW-K+&2)%25b%6ZKWH8_Pn~!WmkATmwtG#`>7u|{xsB4hTIU*#NW+8nHRxinhW7JmkVas^_-c+d$l5HcDv6S54l z1+o`%6mkY~8A4C+c7+UtjDgICtbuHYyaYK8`3!Om;^v2`ksl0JxyEyvF?uI$y7C*N zr(vYU=jw}GMl!YKMp)T&cGLphsW!*(cr%fly!{MqqM;*5pz4_ zCCEw0dB}B$tv6N|Afq8OAuAzUdm|IclnGzU0MylwF)HAY7GMS^9ny9pX=9tUn}@Vc z7Hs`*xe=o}ysnKD!#4oN>vgTSWgvW%!pPS!L%5m$YD?zFr;1lEHV-5maOSek$o^KRK&qxDWMy{XJqC2~qn4!}#B22*<_ z8WRN1srtQl&OUw`&SfYL796X#O>1-Zr^zD(9^+!wS4TC+XgNRyO~;rs3?8wuF6v3$ z=GgIefXXAE`{A<`J~Z@t^FT^1&|xk5A~Qe6z*^ubgpOF_!`Moqv#Z3q7iwG5$Y)1&^S-L zp>>P*haXwOeqb-KKj;VE15#>1;An6V_z;M@a>gBJT1%w0N32I0Yr4e8MPC78ncH}{ zd$@|4p^q{@JwrV`L+=*-0Gw&a2m=R$Samg?L>moK^l*??T*rWEUx91k{w zk)VdQ_K0ekq2F)KHCi6+yicEO^P2)+ni)icUBRg!mDx0qPHMWUFVlLN(V+J|;L^=6 z7S7Iao&|b>kAYs`Y>>(#PK6!Qx_fNFPj2FxsoXHR;qwuq6Py#k-rypT4zL&;0WJmO zz$7peOa=?VRbUyoMn%lj2V1!XYq-XT$?O=I3SUYU1z{{#qach_kU~ZV+&6(cz%8nL zrryVlCOaol>lU01=MHe*22%9xpa&|Hp4Rk0BcKK{9WoA2@X*Ay0~Z!n+V8w;K&>SY zdOMJ6m`Y=psw+of#m1`Jpe_c)S){iUOY+UGdcQ#qVus`c;J-`f3nyo*r zb>^4+U|sM=z40PsXMWLnG<^lRv$D^nYoo5XHZnd3urdyFvmqb)fQ{V_bXU(+YTfe~#YKf(H{VJDyOp=HLo$heRZ^ zMwdZdC~Lj&axr~r)7WL93-58!MK!aBk+~1Bb-x-p7uP$Mb&@Yt?~SX>WpgpH?V?iW zqRFgXrylHv9m4Q_nR_oM`*w6mJYs0PFnL*GQGQ*F!`9EmXwgNr&c$MuYwF#zq1x}F zLgryHtGmjY2Rn)9DJ=(6)uDNMZ;yi#lCp17&E2pCb#bZ70J#k5t^(r`p(i3-O;uCl zalTjEM4-;=&7+66ieH4yGDa`AxM6A2c-!@2Jl3rau2&o5FmF0OUw6ZW4~4hS*L#^u z*Q*c7ed2t*tG)Y^cdLd@24Ox%W_QfT%zSAZKdNtURWcvdW+c;5U7U}aO_3l}7E}e^ zs%1XP!dq3oiSHJYtGnSEyZ{wFX2acMQHL;&^$3nu0$)onoau%Q^yQ3hK6pC8bP4Gd zAk+qlTZtVZz%dn*xIs>7wIF+<{eLz zxhLwMo2}erG}FVp)%C5%^$q5$sb%Yz;X>EEVME#TD|CG7z$dNjmzB80w(`+5)8o7b zzG0O<^!_R6=*u8mAp0T5AZH<0AkG1}zJ`p1Ooyz5Y=!I(z%0>Q+qDMQ*0gf9uUZAH zflUA>tmnfb~y|Km}y_NS&h0EOZk1*>O;*)V%A!HSNmhg%6Z5&h+98oNyDdtk)|WzI8uci|GEGsH znR>@vX}X&>MOo8e^`@x6H2ogC%lNwisn1VQ32EqhliE0wjh&+Qq`_D{BhFMQ)cdEX z__v(KVe!CwBQo#?GH`ahdT68WxNn7=!NXPtk6$FJ3iidj>K|>?9UFZdRxJo)KZYwm0E1T_USG-*#P6V47Om>pMawk&{TShlct$1z@0a6C$N|`q zY4$4YD%rFF>tMcr!}a9(OjHq=xfyjdyiEu)$dX~( z794AK8$V;FsKS55HOj~>$a;8>>a z+wLIBZoWC#$8TTqI@xWVMeJ z&#kzn5HN*vPMwTubgBy5s`s&;5N9mNZ$?|1f(lk!x1y2N-|>hhk87KB7gf4d@95zk zeYXg#>cA$L+-qC)(I~CpY?KzB#IgiWRkN~TFM_Au4N6UM+TC4Oyr*e**RWR4ziW!7 zsp@Rh;-eCkS}{%5rYYrfmiY8#GJfg@#1Rcp7w;AXTrl3C?uBU8pVr>65a zr>3jQYUhr-e#1Tzd>wsQ`TreBoInzl)6}HD>%Gn3^V?8b`$ssrX)*ly?hm%1IL`bX z8#~0Py1%zEjegrjlH`qv%!rVl>E=9dWHcWCz*`MurD>;I^FCxU!db z=qJo(nB0$d!c=5Dr%yEh0_8c}r0x)@ChY`aF5$VzJUy~(Sf0Mk$vl2i**m-SRZdo} za*ak5Z|6=bdau61%9W$x(-`qnoI93X+^b`EOceKoefl|b)pXVK1$~$qg#>oP*6X`^G#s6bv&XGH<+)#XHusMy>%3oor+xYq42}yS8z8$O#gO+P7a_MGo$%QFaL5$M zO2}5oOOWG`%aB`;zIb71BxD|B9b`A881ez+667Yt6E71DfsBVNfzZoE`v+*ArepYV z7IFn*y9aZCJ=(6rm;;y|AKe!eRYEO`Aa$4;yzM!7w>P6&^uXpP@X; zv2K0wh%r?$7PtBz#o%3y_&=;r4;{ra`wuI)W%X8>M-cs|lUODpBlW1NIfl5`vo*&) zEN4{1Q8YEYQDgaYg=$x--)jb!9@TrOIi*-5;U;lL<(DGVCkQoTr8-rLsr-zUcl#%G zvRK?O#HMqxM&k#<-hg>dl|a-J>G-kOIz}Idn~UY}wVg$BZ%GJM-=|&IU1c!M4j0F$ zGE4cD;k0L|a7KKY-Va(fYX{13n2VAK*(b6Uvs4{??LUh1AUM;MVV3eZrq9LElaAr& zH8}d(Wa)u^ebI?tKc?I54ktQ1;+P(zBI~8LmZ3M_I)>5mRr=Mn{LaGC85LcQvN?z3 zb|tIz<*;45Bw0#>M!DIvX%aTt$H|6;zR>$B+8!Gu~ z*o|Z0o2c^HD&$Q}i4ID7j$)jR-E?t{G8>!rxFw!O`{xTxkgaSLE2 zyxrhE4&Hffye-P_EtJgJ3bejsZBnJGi&M=N`u!e1w+ZfsDW)DS&mx^sX(v!BpP^J- zR;vkb!wQ`|ff9CE%|%JMLo#?L91mPMR$|X6zqb*o7Lhs|kpk?U|9ki<3jaC6_gk%g zejDAdpM-Zb)49t3Br@gbu1O~m9a_PU^h_k4ku|TFTEnt<4aM`#`K#+g7FHTT9bcm7O@HPteRL_(>n2;QM}{_cxe0@84=()gy*!4Hts(bZ)G zPUAkU6?w#@O~b3fc2_JsT>DTTy|^#778nVc4p{@)4mk=r1GxgB?MnJXMnmR7)MQV_Mg!o>LvRNwJBb@9^{Z37ES4T(ECHI#bJmyRf7+J zAA_TaDyUk&&-F6$gl$)H!}si(O%JAgjClg?##(%iII9&+x|bUHv2JrRv{$q!HE$fg z<}rJ|&9}|AvS&Zm@i86VP&VTej6=9#Wf^)z-HtRn7SiXc+E1`JkK3D;6jiXm7An_J zb5+<`7~)lMUwed0K$V2R5T~ELb1gQPzC6^&f=B5s&mK{qpVfOiJ&VkZI-vDXU!TJ% z@Vfh46wD{Zl@W4jC((<>0HlA9)%syUNgyQ(kG-MO7GS9yPmlu{94 zQ>l9BQ@yu!6Rv})TCr4u1eC2029TYLaa%qAQ(RASmqi&-G`uQcdB0TM{cPitHnly`=D6cASG6Lh3%;Li!DV1#n_^F>MT%)~ z@B4;&x)#^;eQ}{|%%sUOBQ%gAbV{ zSx2E(?l4R9kQCauVG+6*%kygB1HG!qFXeqlzzlTxPkV@6()c z0=xy=$wpjTA+ujK;yHz}aJ{+&i{yQOz>td!P5ME9$Z4U&^&niGRy(w76lT*|)$K=p z(I|QaWjCZ4@&V)$#B?u4O~_ElM930I24pYfDC7*}GUVpHXglG%Uem@ja*2 zTP5pQ!f^Z{xLZP1&h zv|li*OH;W|8wh6&pO7L)eAG%d@=a6rXE@wUw=T+8$A$jIUoZ_B{R8Kwv#Q+Xf~U6< zv45rKulhhf_QYQ?d%&(ZmiA33MtUB5!><^Fp&7+NlN;(^8|8WIFOi{*{5v#}#?9ZG^fGW6#x%%|$D2S=zMsrsh4mPUn>-v568gZubp$i|R za0DN)Emrm$sJb_h!Jw;Z#0^{~2VLbv@r>p#NOZ%EI~R4us+0nkA#nOt_0^3#{jga1 z{RR*0w_$N@Rug_}(*SbeVZ#O-mNCtotO^doWai;HnqyrDk0$(%$ZsOdtY$UfcTD|e zNmwc!KV&vT#s7|?&%oE|3>aUR>uY#avP-n%Ghi7?yJ>`>?|k7_WX-QQhlw{)vdc^#jjpz*hXI?;ewlbpAJt;MjR$H!=xTuV(aWewl709--P+h zP#!JD0fSl$EfVl)d#v?~Q&-W00h9)<#^NkEWIm(31=cr1)v?wB&AzM6VX1XwsFD^u zc01+|JQ(=!?{`}cEqP|B#6NH~+@VEk4M(AI!8l46V+Ym@Rr!aJwYophlwSLj15!hv zo8=kG>rWi=&^vdvGQm|J4?Wn#^1_uR7rmiZxz#e=lz;um4z@Cyuxc4W>tq;vG_bp!j3@t zNFGxszf;yB%ICJOtC`d;2A;C|t5~SoCdJ5DRegCIOC0AU zJ!-dDOEhgZz8&ndxy@NFNm!OhhoT_V4>zmmztDU(t7Jy*UuX@RRViz=f1zq`OR5gj zwmHvk>!NMW3$*pKf8ow&OMYZ4H|NE}bzi%?on^o=>txI09&C~vD`@3GW-o81n z1`)nPWGZM%hT16RX*0;kX*QeP4?D?`ALW?t7;IKyn(ZEYS;xCkuy_vV@Tr!LE?7gS z!)ZwLxlVT@(!GJr>NG{1=f%!csnmcsD;JBck39gJ9yqcRvaSkuPKf1`uIgp0ZKBMH zid73dI=u^zpCqzr+>~jn@c6B=_r@p6R@C2FATL%a?nnfaF^ikG!Y3rgn8%vb=q4;Q z-E_BgvQ)uijkj8_+lJrqn5V$X0w@53X{8?&KfcxeXR*ycpqJ;R(I zxl?p;HiX0L@Rr}Z;ok0-xVO9Ch8lx*r{_`?WU1tGm+o4YiVub%yJoXF<2M>5E<4Lz z-17S4La2wwoeQC272|<3IgMmbbXOZaY>pe1#j1)tK7_}q?&@a`o8y*ju?lX7LjDLI zpLFL#tAgPFInWd!j0HQ)SrvIyT`h@r*s^A85MJr{vA-nyhKv0 z;ya+gFcY`@DS=ewy|^R$Y6qLA`OlvJKaNoOBQDlDceHh|9_;o1eVDY4I7|%=Gs{=% zMY|6(z;`>^>{f?UXI0kRjWuIQdSt4)%XZOosv7s(d=w92;Y!>vX~q&fy3? zesYAc``UF^i@#~pGj1S^1-ms^`ueG!UTq3D$;;M9?eAoBcDu(ByW+lfJ=DlGE_XYB z0|HrU5&K?0)vj}!&Kchs9@qfD66&Y6b#Bv4Yslks#F*fx{^)EAuuhQFN2tmUSne3v z#WwX$AIj^3z+WKnJAUd!mo~}UyP|VpFBHq;z4;X|Sw5tRKK>aGw$XDHH0f{unii?f zcC|U1zkR>#^RBi59%Yw@ntNzvLtfI(Y9&)TX>SDB&byg0t^aZmzHR=~Wg6KveCs2+ z7;kZ847P32tTD#aTQjAontNQa<{oTYY5wrLvS)*Bo6MLsmvtU$!*eU`o64pRv&}Kf zR8hmN&*bhFY<@r7HrkAtVY^VtUYNT()$Ct*6cG zZ&mF&x^`19jkWc#@;HoZ8!D!n6b6!`qG}<=H%BEE_`EXV)McYPOKQS!k9k-EFk-eX~s*O`^v&^uNUrt5x zYrLt=;5wh<&7OuZu!Z}kAxxfk*&owvSiWFuM!O_Ncf@%PiLqTV!!UK5VH;*WWtbby zWL3cjVa}G#z*&CMU2P*jm=_~)e5` zg6?x{yUb`^FV3-jWkq8$a@C!4ymzi`e7fg-SjUBohAf0^fb4`Egq(z&hunmC4#gEI zWFllCWCLU;nrhNC*&aH zBIG)x@BLVJfh>X0UbY7z??J9X+=e3~kcp6$kgbsYkYkXukSh@9P^`&7hC`-6)fa7-S)2JLDzE2arn;w+E10$Qa0M$QH<6$a|2B5PY7~UTQxXG^#9KwG+cH~kGx*<^ws8k^8K#nTj^t4>G_{fSZ8xPQA-ne= zMgK$pvA*r563FL88aLrX>)Y}qCiOSRxH%6=Z8@O6Ou``W52KIJMtt-bx|+S*HqogT z{nB_r`n}~gPb>E#myZ)XXOr|(Z|c^&7^rNY%8tY(6JmW z-!ffc!_yjQzO#~T51BmV#UQfgfYy8rx7Ss?9L$_!c>x#)dVviDpz7?F+0fL$SUk0c2r( zVv6me+5eClu+}!qiHgejdg}hQw*Kj3V6A3D)XS zgdBvNfn0{%gm{j^xB?jsnF(15*$#OLavbs*8X?TX? z;gTS2*Ls^-p94fnpOZ~G-MD~p*{yf{GadCxG5ZZHF@nANM9@qWx`-2I~P z`M)wx=Q0Zmn6>XPH7wU7T)HXlUUtas$IM*BY(C7Shx#bNI4mX*>%L-EZ(!!)?8v>b zj=5(dQ#-~Cy3DM@7)9Z-Bwh~g+|n+-rqcH~fE^FQPyp{h)@v3sbB{9PuqZ(OF<3Do zM*hb1IW5G^a&q^3g_$TBDa>TORN~c5XFa(P#PLlY@3TW#3NvRnvtko7tdfQ?vxoN2|v80jT=30T^MX`S*xM+7@(A-~ zwhU+HVo)Ua$b4oA7UW2eI>+4e9W!n(GZ||;W`1j!OHBzUMBiX%TKC@~v^G1JWU?npO zMM=j=Pn05a!F9TE;96#*Hz!;x_Q2;|cCVYq%#{o@e9pR`D~HefH|su8%%}inc^I=o zsvzkHLr*v5NMlL0asqp#ABW(+4rM4*al|YzDlte76sxly z_BDsg-oy0j#qJG8Z$bTsc4iNk9?bmi%n&h5dm349@!*IhU0AnD-B&X)fzNlbAU+W_cOvp8`gVV~3`N%uKQUVZX2*_Y5=T1~Yo6=>KHy zS|YkV^I{!{|B;&Edg>oGD06f9;v_9!z~iZsw+ z%cUq&Bty|s*QsLRvW9ZJ3U6lPT4uF$_n`C<;voqhn9h1A4GzdyLajJ|7 zX)-26!!ddy;!$P?x;k?MOAl*>hSs>pU44o#8xNHV!hE}N~Opu z#Y87a6@^M;4VL*s=_rm@^tBvV4p@b?3d+ch8SLINj#;SV{K-R;2&ZL^=kh!U2p3!J zBlaQiFLqDBT7q$A;+`w5JEWbsi{)(gWxc$T;|0rnAS8tK8^d7#D4{rMl?m>wCrCf_ zlSXItWcMa9)&63t%a?OP2TGZBGGWOT)9fL=C9;P7_ei>hb6Ianmtk^`Sh&2y?BV?u z^MILo<347coMDNW>K17OVI}Ne)XZ!ZOXx2qJ9{U)hl$C~e~qRNVbj<0*r25MlM2bmm zEaQMRGM!F7%6e2iGZd?4bl@cXPsA=-2FqjF|3*18WgxReENhau`;cYD@l82mTC;!P zfTc3?!8db^1XH9f1n*+KQcP{ieAZ(h5x&gS9%L4Zf6Nfpv&5pNRIt9sNBX~qoS`NM zOnrp|9C({q(un&{X;*u#5x=8%QBpLr(r8Qc`5M@b# z=q?=5et{2E{VFp=OmB82>lgf(*sj_ru?ERlotWMT8Dp}4VgGXJjwxZ%|BJA!OLf>F zMIR{^ExI4O`#Vag7wfe>nR{evW|z62pUj$XbY=etXNiBC4;*)kdHPRgX}V02>{r<# zRR)ff6WyD6K$s?s7M}KE|L{)C$d1g44$RbcOdo>?6fZNC5TV^oy|&HPGhLI>D{-ep zl#E67XT517v*H`3pETaYzN{C?FrF-jXxce zPbsPjDVZWU;}Q!;@cuU^P(PJT8@plA}(~vYt1ZBlyd_|Fp~rD238flL7TmP*bp;qP#RbR0lwVRnFb|OfMHhwg_hf41W?8DTM%6#DULZ^nMhZ{Mu$!`w!v#%YwiYulG&8H8VOB^l zbCC&3L%NI!+8PevErurBQ5Da!d+UB?&O6MIRm>aG8=~Y=%lm6~50;5Z<$bKTWHI+h zHx8j;87H0|@611vWrAY=j`b`TW`#t|AH{lIe`fe%X3bHii;bDpiD{QA^P*Oc12qn1 zHp}o`_kp3On_`}j2x5AzlH>B1*uDA`GbM$2dJnU)6W3|;0M-l2m@d*iW5QWak+u-QY6av(ExDKog787)N>JBkyC`GMVA2QkCmV#e=cCQ2i%mNTy8 zGd1Old+rbp7fB_LdkXFc_GW{3-yP@^o@ z74&8IeCZ{bYgmsv$!s|!{a+K?9xOIJN&;#!0r8d@QszF6=qCrL&11bNj@c+CyWvaL zeWo$J1DIAZ)zM!niSKIw8@pDm`fN)pVMgtFus@WLUESR}(~V;9y>i)r;13!1Wn-3uh6 zF;BDJC(F>$8 zriux!{)_!1+2W>~O2)H8#1!TY86>h3Sg$N$Ml~~QJ(xw3v8J7@pMH_)@gB2PETpx8 z^}5N-igae;bt05nF|n2V*`q;vL2xqbks6-SJvr+ng=zZ*w^b)g`a)t~gt`WTtGh8fW^fA_x#8COmOh@a;?k=A)s~>0X zDQ2GLIycz|vEKB!^#3|BwdKp$BXAU#NQo5L0iE58WFq1}g!L9Ny%k~y{C{Nkl-bN+ zF<}0stVf7@eJ<-EPe^0P{hS>xxG*(iaKNb5gY{;)7_C96P|0{KU{*&lYtJ(yPBO!K zF|!Jo1*b&s&dm9US(`qef8@XLvb_MKP{4J7aowR2ou(esm<)l;c~3Z zI59kxQo>1381Ct&az75>a)_Dm0JC1|GFC1wJ!IyRAI<)8axvQE%X*O*tfDcjCq2iE zT+K|Du_1FJ>y<{MM*Sy^WrrfW1e612%Z$ih4xA{1P);p}iyF-Ik^|Jq#3EJNQiu%O z5%)_tG#+X@RoSAuq3WprXGwpIa@cTx4p1A*tRKlN_=}k*y`V+xMEN7^o+Z7<=bx;H z-Op{qyPowHIk3+))^jj3N~auIkFY};9_b=IMT$1%D!Yfspj0T`tiY4qV`Y%awsAba z&g|YGZOD5x>rFSAt+K4QN7_cC`v{xdpL*7mW+nTC&E=u!k9l4gVnbPOZ zsEGZfSCmUhRW`DF@_o$Umzd$Fm?3M3=zoFVu|woirnl5(fsAg=VO*qDHuf)hl-YEf zS#ge;Cau0)Sa6x$V+JuxA7>Uyl{8UzrT*U{!)InV2e3LbOWtC(O4~Rvnln-ZPrtJ zF=K`^%eyn9WmHS*z!^$9h93Ge<02 z(NnA!NH;6`lJ)3`%#glJA8F;K53nA0P5dQ8S#ye|y{WoS(6SGEI zb=+&LCw67Vi>VIsbA)7c*NjSQO8?U0QkTuM+P$X7qlhhb-sqNrsN&n}TG*(b|s#)GcC`i{UAhR(xXz zyO&Di4EvGwi22NV$v{q;=+Zm9#NWG+-Say!bJ3`c{vW!89pWYDd){FEhS-6Yj;x1d zGK-{5WQDLE{xY+4Ei(ltr9u3qO&z$8^+xHwNmZ=Ztda4*>Iyql+{5%1Q|#sF1*6$L z#HcgeOOlKv37g(w|6G}1WCyXH`8YFHreevmHdHMZ*ZU!qKjpM`8?#l05?tZ`zdjpo+gA|`o{R7vPc_OBAd71qFdNgXp^ju)CPjjIXSpo~~0VuP&b<%?nQ z|C}QxxiIriFr#JI#az{hUoK~uc%Jo;SDD#js)NLSq)K;8k4ohL^g179ptX`2BL9ij5;5PEtHMKy zK6)Da?~#7%;m>-C*!C!~?SX%?yHzG4UQ*OPqu9Oa8)kMs^9FTu>i^ARAi^Xgagvc_ zSsRL!YryO!9MQiwvswJ}#Drhy%yh8eaP&Rwye9Wwr zfSK1t7tD|n1c$!)DE;D#F)8B`gAdUR=udL@uiF@sr{vRrJn?N=hRT9#l zStO>|?jl-uLWNHD-5}DLi!}QW|v~;P{JTbiqZ?H$8 z&dijB2bT{-U&}0go*C`Mby+7>R`O4FFRxn%5!wIR%EF||>Tv+g6NHcw1!LpZxPyv~dhdlJi4m2PU3e!9nr14JHY z=HxMhr3B)n(KVc6_eQCb8=tZs+Jjlsoq0fdNuo?xiX>yL_p^We=S0+hkPACRo?xbl zNyW^|sG|ZgrPfzj&pXM~dNC`+w3f&OBS+dmOD+4y6*DWpXXc0nO{j-X{Xa}BQjW}e z3w=3YPz-7naIrU!}K1>Y>-|NdPw?z({>3c zRnhn;>rD+p84C`$vVK8Ey9;6|YyQpdS<{%AvXBw(&w8Y^sjM*8Q^qmtuR6wmX;e{S zI&11UKwd{?NIz!OC}xC(87W1YAO{Q<)=5U|xRIF(B*S*Gq|GmI{4kr$|I@x^hj=le z1!6+u#Dq5X&?$OJc!7noX%b4jox%{JOAJb1J zAojml&z;Fk%4X)sf$C+gs7?%3wX~sfG0kbxTde0f-i7CwDe26@j|`@pyrro8Btq^h z93b!yW{a$ZHcLOQlIwz$kJ-ObsR$Dic@ zagxIzp@$Te_fYmvTEQ&+JF{HQ(0YmWW?6O%z0G=K4bvx+S@Q@p9E)X4GdK!Fw|^R5Fkz894nWyIVb(RR@@-yD&YZ^~XlA9)-jy{j_B1|E)6J zz97S_zXZgEjS;W}0VzU$2y@RD%<3sjm$#Wk(kAkybr*?Ui2Q*4y(TalBwqdlIDbkw zdYB~8jk)JTX5BjG>4%x#(ah2qX4bdN>>kX@Gt8hTnO3P%>&vVsyu(Zpi<{O%`oI5J z_P{H`MuxH^$I*@)$FY0bWabSip++g8Z0Ywt1K2+(o*7xhtZHKB%d=u0(l#Q}rQ3MT z;Q&Q)fcV#0KP?l6WSJeOc(8le)66EZm{n48m12T5xz3M}bgSfy3%=rb;dX9Y>2|ST z`4X{Nia!1X2TYX&yroF&l?-zz{LH^}n)v>OYu)VvzhUvF|Sw`ne_mt?`_;U zp*}8`TCwdpKe=tKFbuA{jRZMco$Lt@G#6;j2*~yNn+N%!QAsWGeH<5raAW9bh~P4JE78cLWWEK zkGsMF3u>4#k^tMU6VnK z|I#{Lq{u>%RVvaHsgl}nSg*Lm%==n+fmvV6EU08!W&TjQi}f05J4wq}cah0x&~^GIKgGn>?8KGMNf2R`$tKg1xbRrVyJw?KjAA5cR|`hq%6tAk6`!4KbSERF9wYf z?H^aWZ?H#vJTpt$LJrrF>9lm8npXBt+s@R6Fhe}J7t~9?&XtV%OXCY#z~ORVXYP?f zt*EPv|B+Ip1${U`ML9D|EMT$>GOg3t{j@a7Bncm%$nHVHxFFV(eV7G~ULx0$;W7x- zo5QEi}hGBG|dUDN5NE5NtQ@ks=Lm5eiAcTEN9pa)^oWr zrknC)exH4rJwoLMW0MRfNgLSxhMZBMTqS3{#O|4L-~>4l?Hs!|Ob~w=bb{sDuXZE5 zYew5Z{U<%l4k_pkMq7|Zbb2D|p+}ibjm+u?m|4BJ)wjxl;=8eX(j{i1TnG4xAxo8v zm1eMid1sLNzg&~lp?>-j`etHM5XSm*UGbDO(CrNbZ2^f z#7tVpj2OdA^^pD_Ar{c*TlR4AW)`kz)>JU7WN^upF`-4m7aU{%pz+K&Nw45D)+3}1 zYn4V7jRk(vqos}HHM75unBG?Drg>5Vb}_ZF zy*XTqTwA)x@mwBb_jIdRv;$(%62+obh(!zA!U2PxW0t@6fB1SAIGd}z@qg_-7q{8l zjLTqL8bS!|x$T*83!x!|a3slG8-*qfA(TZqw_eTDkIumA%{(*8qKz())k1TYL#_PS?L;4QIN=v(@$N)NLET-+9cwmu&cX z=P`FUkGaDw)-`X~^f8yMY%<%*l%rPGe8lblHEs$Py2s_3ZdW9@Z8Xv~Xj2QD@j||p zYuwx~JZ8flHNO;T`PaJ(OqT2XwQtyVsrnkGp+*e5_4abKc5L&V^q7rwyk# z7y50n4PSo2$}z4-U%Cd3JZR&)I?uZBUpBnn?Sh%7ZTPDxuBRWmo=!ex6An37+hl|d zf9v*rb2laR-5R+3yiH%??g_u_vEd!getaJr{xIIkg>LcHaW47gBG-eif3pTPBdu(H z$I6CodtUEohwwwU`ujT9`sJtAZjE!TTU~iSAF=Tsm+$ijZT>ghGiI)nMQhyt{PJ6y zVT>Dz@dIr5H#fK6J6HUEGaH}V)XJY-gA>}>@S(L<{^DG9cju}r{kM%@?-udp<|bUE zjyj(lv&kCN|K7@Uw=1r@x$?QyTPen-f9o0=;kM`U&=fh(x6)_rBIY`K=Ysd2v*8#s zBFz6v_i5CV|F#M3&B1`*3vr94;ZHVxn)8s$JJ@jFHCF!Y_Vtl$Ao`zQrBTW4&p@%ZsZnDxA9Gyxc$H1Rj@V8CRB3o`!n4GM9oDuzJ6sZGo9<*wBClBCs-L#!!EKV zoo#r4bG?<^+8SBI#(!JQ%3dej{_o{lJk8DJ%kNr)FWoMfHp_-&*-jsHY zw-q0E+bZFIZ2I>*t?cxBE0_Pn%KCMz9Qk**|6|--9d&OuK6frN-5HKKZZmxUl9l`W zTlu7GP$yie9`Yv6VNL#v4fma7WiMCmoOm0)e$>kLMNw8c<%T37*@o*lPdII+4UZY< z?A+V2N>ryS9PUoFzd6^PQf%$US8&ojl8twsu+=Raf7HFeDC+fB8<8@_$~WBp?dmFC zvdqR`cZ>As+cuoJ$I9g&TiN6jD}NI!ySlZs!!?w@d}|x*My9@X#eDwnw$Gf8tidKX zSJRxM=~TtWx9Vtn{Gsz)Bi$lv<%a(GPp#c?w<|8E+Hj`V%8{L{JhjbAk4b0#zjbrG z+|9{vFIt1)?jiF__bgaxnvL)4ZX!RgwBZZgtX$(9Qm)&MNB?Z&YdX)FaMgx?S#M?c z_mO)4C%Bf6cl*CrTWiqX75rou8&3J$${ntut%lj~@^C9Rx!Y`e=g>C2Y2(+gvT{vp zD}T$h^6|}X|DUSkwvW53rMt6T?rYX?q+66fKV`!MmRfni_3%`-4R_sQ8@W1(wt}P2 zSi8sFgGj@BZFrjNSn~}w{Ibh`{2rcvbjxbG+voc2)}YBjD|@;4+$U`KefK#1n|XQ6 zcSl>={B!&^{rD?Z?r?8R(i__FcqccxyW;+!jbB*gl;KV`f6^wTyG1e}+J-N<#kc8S zHhlfMi?3|uZ|)4(HSZ&m3=LU^ z4bO4sh2!pKGUrtrKiS=!1~^aYJ7MEzx<%URQ5#;k(aI$c8Cj$*%(M~5AGET`yH<9u zWM!*)RxWqGeWhDW5w3@wezoZycZgl$Tz9V9*6m$`T1~We5pJ6vHQzI0|9NWKgz=A9 zx&EJ4HgT?Vq4VLVM%nl=&Sf|J)`q8@x3ZJl_uo2~yu>{b9ddWkzR`B1zjSNoTfNKl z{vYq|R-gZ13u^CV%0Fy)(*-Mk{?f|Foy>J}TGP$>Wm_aU*)!IixYpA#HUH zh;SaX>%ZOof2A9;qbF^_V~VZZG04ha+^YZC-S0BZ=30s}3{yb>YYsOjm5*-D_yw*ite!)F8|xg_Fq_e%B|9xmu&d^x>i0Jx|z5h_06~Oz1CTI z{T(YOx3$ve?je`Q+i*lBEAdCB<3;tiSf!OK_^Z|~oMq)3o2^{q?hzj6*($kv#PZi{ zdPI(upSxrGLg)K4+u8VDF8?Wa4|v~7zW;mP8gz25^xLOxc+EU3AFpMlZ=aRx-?Q>d zmp(e^vT~-|{|g)25lI+p5jkJ@bCgFKOAS}^)*(``NYZr z)S~ODA7#T|4Ycz4BDc6c*NXvzQ_d3(KV`#fTmz@Mg4er>z8_@Md%1J``_40du2 zod@c>yX7y}to_ObE?-C6prV?$U4&~$eYg6*{kx6-&=vICKW+H(D^|{FV&x$xGcVfk zv<6nzcO&L=&z7IxZ{ydysq7wS!hHVssZE&Uj@@55pS{T~l5Ypw^xr}r(GA@NcXw=9 z&!%^ByQlBBHr&f?zlLtVSGw26@2F^HU*o_S-jOaM<$Iejr=OK|+<{_F3mbmYdBpFX zgL&S0v=rwNS2~aQv)e8EKeG9zxsf~Swr_jqDUWNvK>ezc>v2O@KzrAq@y; zUB<_^+3+DZriok#3c&BecJWqnsqt67Y{ zZonMpDCW3D_RBCE-*BUqJFZ%J%4JM<4O;V)jepX4z)jA6lXEa%xgnqSv9H&Qo~q9KHsSK?Ru0dza#}YlzpriO^3dAw+VIw2tz76lV3W%>yu_8e!*y)aOE$jK zgLXRsYI}c3#XZe6seWY^ZDE-APLU%g+7}3@Ex0>rt3*3Hxik*Z2TPO0Vg{T*xr@1 z+lqA+>U6yd_($ z-OO|=Beq!ii>si$b7W2C*!Whi!tOVmooit8O*UL9^#6a453mtyu2`9#Yvsx)yILED z+wh#0R$gytWrVXk>h}9gx0arFj%<@_$a>eoCX;NwC2p-;p5ylaFHhKnUT!J|IL~(6 zdA9w2oBoFLY{OkaJ6w7bx9Fz1k6wRUXYD_9&wwAgBi&5r=+;cL=_y5zS>;PNlr^W= z@bI^+oay%InwM?3)lDleyYO(AKm92i|8g%Y$2d=T;b9xD?;cq6pNZ2Budkb$^zYBu zh+eMZUe3eiK5FBibRKQyRU3|QuTnP2w||T371u2+Jfd-*it|@?s`uzym*S^)p3=E? zyr(#~##HHZCMy5lo0C0JwHtM+yx^x*&orHpA3Y$tS@`OP^8!t#Rc>7QrSMAi-j9*L zpW!dB_~ho9s0Hb_E?x?6vNo*RX-{TE#px|qsA}Dcv$}7YoF7;e=G|CaT;o!IZ_1js zw=1Mho?Lr+k1kVI`zsw-9N*=VeEelpBTt-s^JUcFqK#gqcEdTi0xFC@j1C!~|DeS( zSO?qT7+ivDkj6Ue0)1dHtcESH2adpL(0^beIYOx%D1eP{63)RDxDlb9N+cCR0Q$o+ zSO?qT4pgk5R1JuSmXHsHuozaudAJI4-0;i!~6{VVi{=4uiU^g6ulW-2MKp=_&VJggnWv~zKKt&&ohcxH{ zg-{H$hw#s0xCPPdoO;j`20;!?gc+~`Ho|VGT~(=JFapNGJh%kc;0{z|=cGXwNjMi( zy=V{W5x5GsAe?8OdXNkqp(hN299RM8;0oM;4EDfOmhuTlVKyv=)vyPS zz-c%S$u*ea99|(5z(kk<3t$CYf!Z~h2?#(t$bfM$73RS**becr^ap0wp%OR(^|)&^ zgJc*46Ja-;gDcRuF6Gu`hUcMNgEa0A`A`UpVKr=lJ#Y)c>oX#d0|l@VcEdrq0sOT; z6$OnU0K;G%T!NPO&_L(|Lm(dtVYYs4u^P6(9ykKg@eDhxfRk_qZh*pBM?rrW2UB4l zEQ57$2U<3wBhUqgKt3FS({LWHLcMz#8AyhrLHv^g1uz3vz(!DwsSIjE2K0wvFaoB+ zJXi+nU^`rcJCN3dUcwM4gko3>TVM}dgf;msLAs0Rfw5jMhZI0z@<99)4L&5KxAE$AIgg?X?KjzPVa z3=wpMo-hbD!frSSH$b&wl%O^=h79Nr!(bdtg?X?HF2Oa3Z_Ow{7wA*OKSQ7p_CWXp zR0);HuOrQc70)s26v!h8!Ci&XbEZ11s20;sMnT}gF%o31uzk2z)83Q zH$b(cF35mkFs~*5EQ5V;2P(FwaOeUtH+VgJW<8;yY3$mnn5xYzyeqS z=b&+CDus5C0sUbZtb;Rf3F04O;lmKfhe9ZZ*{~SS!&SHi9lJ2FFbHyBVwWOD6=eZz zge%avE0sb9^oL=v9rnR7I0Kg;z8kX#Y0w9TKt2>gG0cXma0|j8reYWb1uz2^z=|UN z*$66wsf1xL0>;5SSO)9h7@UDiP@_AQLrWL}`A`VOuozau5jYQ5A-V?@!$epBC*d4i z0nZKj{vT0wi?%;P2jLi;flF`);(JmLq`?pJXbdA@YHyaoK9pl{2ChMkN2wfILK^geA&?KVVKJ zBMyTg2MXXIoP={wyDtrZ0JQ7NGRQ#b55r&_?1N))2IBkC5J-bA& z*aP81=qGf9o-h$+zyjDfgxTDUauCjedXkPp226!zunxAvJ~#%K;0{zAO2yC;xfl zL5t6!S&8Uu|X0PSEH zjDT@@Ma&AycGw4LPcs_O2ZlgC6vAv+469)agy+*3=m|M65oW*w*a*AfAe@97poY^B zs0{&V2N^K0h<}#BI@k`E;2P9;hEahuSPfg?D%^tTXQ>>Lp(hN20yqdKL5-jyXbkNj z1Ny@-*be*P4pbb;*`)^m#6uc%fj%$<@}UrB!(zAv;iIS=>OnK;2t8pCtbmPh5KcnW zb2I`1&<^^;Fc=3@VIFMPKe@0Ep95qiQPm4ivydI0@(A3Peq2gFyf?U>J;md9Vz&!@kL^?_(%u;1XPeJJ4kcjeyy( z7`DJ3I0C1k*()>vIzmra02^U99E2;-e=3#0J~#vM)956mK_3_btEcJSp&WsF(P=mSHb5Qi*sT)?nMz{huK+U3lXbb^p2N}>Gw!=O+Hfw9A%AQ5n_@kBSSu*Qd z)cu}-?7SBBfG0t|K}ekozA6%bJ*v4UNqSt5O7tcr%OoRHWSfz}UEf@fYUO?7(MtM{ zGVW@8BkG#Ro0KZCH~CZNNomr}$aEQNWUj2e8P&m?p1$jwoBUB|Z%UR7zD;#$GV69! zTTi+iz8!VH%)A{{Mef{=O7LV!>tFeMt=Tg6SFCbm;N7SsPqNI?B1QJzrNKe@?k;Jm z68CRvOiq&?MyAVze@6wq$(gdvgtO%0zxkV-f%JubA0l&M8((X0AZy_>T4XO=szuJi zPko8rK<>i3TI5Nh$M*mOlI7uZj0BmhMWTG*@g*@DKWLFGjl903g-3l+lIis|qb;+% zz6WW`r(R#sn~)~nFfG%iO_;B@Hz8AI8JQ(#!+Z&0DS0{K5BD`k$(1%%$&*%5R37rZkN(p?(qAB+7IhN|J3llq}yw_)-~^29bn<(l3$>sWK&!uH>Z2 z&Pa;ONtbU-I8)*(==dz@T|viZ%cKf4G$%)P8ks9U7?~$cE1K2}u1MJlGGB{C`Lv?1 zE%ioLGWE8pq+1%4XDTtU^mUOA)7Qf$K1*)u_&}~Ss!SCrc`~@NDRORQ8ki(|D{Jdy z`JuATog#5nbT}wIs`yTLQ*tFP$`_2d!*Z@8lT-ZF{YK?!JP-&ZWCotr z^nH8lJL8kkuk)hDB>GFdXnbNc>B1?u=C1 zU6n=zbHyL+YvT>(Nsnm4nRzlH+BAK0w3&so(KId6RMr|oF7!egzDo!&+$F}FnJbAkeD~`&CyiX0H6oO1E7PKU_tZD49kbN5?9ytd z8k7A|zFPH-YE6=pl9X!dO39DZrL;`&)|F_VuVS1DhwPF|i&|Vko~hxBi_rP3UPT7# z^zbTW($h=J-(E!))ujCGWz#cD(}zXLXF7dYRGIu)rRf!Y;*TX=zaKB@A4A!|jnfvN z^oaE}h}%*&Jx8fTmtIg+ro{RZ;|i*l$)8)={u@>0L@e#UQ8qoVwEPj#;;-dv&}&3= zY5wGZ{*&Hz1)VeT<3^6ier{CW@TZB_KViUqwyb@EQmvi+xayQ6^`7|M5zPS3gw0$VO%=*|~Lzi=Mgtu06a+OqTqOEzVej*7irBbo(Czn}`M`C3|ZC2xv*fOnV zHHLaMu8w@I)5p~*lg?@ky3x57C)Misf<@Qj%A}WBjT!ZHe7h0DUntBSJu2_H(b*%0 z=Z-3Tp+nYFPqC;<+Gp)d`%=@&%;r9m|9@pK$!F68)wP#P)^7?!%P6{uoUP+a>>b^t zOv6~_p^hyu@x3yKj~bZxRKMI8hEK>XDb%L9!J?I+K_1dn2FLjt3>?z5OqpetzPitJ z*3CkGZuYafeBIUTlCrIh?Pxm7GE{cqeR6`bdl#BAT-{|nP+@aj_5d@%Ju|a%d7LUK z)26vRtf5eujax{Yx@?8UEy}c)MHAWz#VvJwm*;G$rRCXpS00lQay|Mbd0V+Q)muyU z)b&;L_HQLW#Q9>qM_S3(by@mHbh=ymDQuz8Sf6LXx0T5i{I%kY8Zsd|)YO7x=~fS~ zP{7(ODT0L`s`_+LCe`yb>T#O2SCWoxs4M4Lb8XerxrHqLvb);G+peUPS=Sk9@?AaF zbp}hOq&&(FZNKPrX;2?86U~w-NvDobd!pLN(E7ec^`qL9NvEt(dx~|ucq;m9)GKRI z#?Rg|76}#o@#QR7ZlN;t`{%Z@|50Cczfs+`Pfyy_qJeL4C2vlyOuvuYZcd&YxX;{B zf4GmEW`Z$o-Lb=%#n-tbB^GC zAJ44;)1^^s-*kOk-q4z^Cvi?|P2EYH(;m>0bDELaGUWlCo+EpW%$3_l=1DL>7XmUm zV1{Z#fI<`HY=B-Si9dmMC$kh2C@VQdCM3}Q73n-OqWS1+AdQzn=og06V8@uL2aKSJ%TztS0)5? zzC76+q{9LET8jknr<(3}NYzKmEP2MrY*}PvjvO$OGp><&5|_qI1f*M<$vifVE+onZ zEt2HxG{%)vX*!E8C_~c;rOMKDUuSPF>n5Ga$YtTQ(cw%Ps-Gz`Q)R9Wr{>6KZD?&~ zid1fkT_O|EmWmQ&bX(KBRazv;XKnSUCre~IEmNe8kt|UoS)=VJl*gLSj7%4AdmYY{ zL?iPgtG(|FZ%U%H>7Wn2Niv}Wl_bmB4zxc-&T0`9|AUBB>8wSXjD67eFl%n_gOo(G ze|S)LBWqWSj=p{#Z)%E6>g4-3XU$2S^2?ea#4p;q*@n5P&#*EIi|`4Ez)G0j!c(}U1&t6#CAnwNsq3iv91x)y(=r`U{_yD zZ*H#q)Ro$E^Q1*La;3>&Ez)IHH*#^R)*?xM(jq8LA4a6g;D=2$^K~de4r`Gpx3x%; z))~Ge`Q>5CACbWhw|HUEY%`ePV`|^Qsk}{!CkHU z`r@kTZPO#$R60ouo)5E0#Z&4~ip1t1c)rpiRVL+7X&M_%2NUI@7D*DD%UVoLmL5j3 zAdC#kHX~Ez8za*sE>GK~OK+r{sqK%F*?IVb)GXPVN4cpi8Y5XXPwUm0D+7(plSNPa z?w9VldhniRJ`&{S)20C}@=XJV=2KwpJRHojday@Wqx7<9ta>dH zWt$f4uF=?JQTGev&EmdcWKa$un>8K))H8;Nr;k~LstmfSWnTN1}>J34PoT{GE3GXrS=5I z>FPvZK)+pS@UphZmBBC5F%CFOU#6b{Is39{K%8wak?sM&`+s$#}kie4s^w z{G>&qw3vcOlB_Adl(1l4vMjYqihO33pj3XvBylf6k-ruDd@}VF-~Cvp%QhYL@MNNH z*r+UNG?l1bIx1(XvC5J8I_kbDM4h%#dE%YMm@k>an0J|G-7gU|XTvl`BuT!R#z2mH zg@J52ohb?M0%ba#2?S;SbasCrRSp=*U>M19>Qx<|Dg9n$FalXJ-N zY>uuOIdt>bZ2Uzc%`_>w(sT|P6S>#V(FJA6e8O_8K12BB9N)eA0CabbxmUE9YgSU; zT$;u3%{8-majx3YplOJ>>du$;+W05Z;lqK61 zQZ{#)pN!0r#6{H2wB{{hWSQ2t7MVKFYLOtZV(RRzMUqSxB9rBS4yDL#ErOD`7?CQ^ zXpttX7Gr{6*Mg(?67KiI7t_^YOXw=|I(Lbl&m8%5iJtFV@h;UePueUcLqNtZrIZBO zyp+X}C^vOvk|h4#_XyQa`aO}{)qZcPy{kp41eeh(j%Qk=%g$xKN2xY)IcZtaVL4r6 z+($3h)5eS1jl0JV~Rs=`JU< z!Ec-HE_&P4_{G~4mni<#rn@~>V-rl1DXYyI+_su^)O|H$cx^QsJtz&iFX}~hU51-LMbv`i=Z6VB2^;SQ*4@a)`I7b^;F5KUQZfl2p!4oV}q%A z)CLwC@3A*;pi6u@@XZEn1JdAK1b2^j$&x6G-o=(f{kzOkkQ?AeVv}XyMtnDWBunzN;0bgyL%?h4&D5NbE3xls znJ2y9qkw=+d5=;#@V+C(#g2XKpmn_d{ks_tGE2PM2xUu~ZG>`U>^2&nm@9j?@%aS~$p1%L7m&ePB*%wQAV{Yy^Ogfo{xOhrO!vcdV0f;`bawf4lf_+{CRTmBT5fQqkV`3$=XLH ziSm{X(SI$HrNMqgiVW2vC~xgI?Kr!i{%591>;Ww~F&ddEbB)ZBPmRo$$d7e;j&%N* zcJukdbQ9*K%*T`#5br@|j;E4?gc4;x~tw zG0uvyhqcUS;cK(@##ygWgn-B09#$KEPuft-?Saqkzn`U3-uD z4tRLkv1`f+-w!CkU87I>?ndzXV%O*|d`*c-+qLv>ylB+V*xSC;nKI?#mwME*q`_HM zMP|12IIH7xWP%Cv@#$GcgLC`YvrHzRaQ)rPLhrxRwnUkvLrJpp?`HLXM@YUr%VukN z4sXcYi*sfHEY%`SzR)6Fs(q!0mudKlikXHfCd@Q^rQf5S^F=NCnzL&bpD%r_4f15v z*QVwTTJR~c7Kzg6zkIFRr1B;)^yV|17rE_JyE1Qf^$X+Dm(e!eyunOOPn22zrC-%> zq^2DGx#>4rG90nzeV^*%&BgOfLL$em3$!+okMu6+FgJ_~*d=nWH1V18or&kzd6C8@ zX3NlvIz30`Uexxva#)8M)|(fpFPF!ne`uK_y^Z93l973`_8+E`7yn^~H|`Q5QTl0- zB(pA2Mp~+TaLKn;=3VwRWXWy2jD1jkxa_;%S7sEpcxCW6z6SNTc$I2lUvws=mU*Ar zm|>l-y>Qs#x~Y-4ircEuX<n}71^SO52xl61UHC_O$>CXik~KC(=DPU&mglRDnMwl%7)A~hAia>X1yKfPkc z%KNR^n89z2d(P7$Sr&bZNs1iMp`iSvO;V-lcL-kWXu)0RJ4Tfg``+)E5l-yi>2O-w zuDJj9Z3y!Q19JEW%HV|m17&c){}I8_`9~u09XiBq@<)nd2mi<-VF$-v(~|eJ*GLV> zglqbh!!`E9mTSJo-eAJ6FRu9pQg)`azG0Wa;2SIxPB!yzP&p@?12;_0pR`DjMn5B1 z20z!OzTmiroB}h9pU&n-q{rr*4|WSvP4A-&45BaeeV`QBe~9FWxN#rS-q? zNt{zh8<{6N|3x9G^3%V}h%~)L=5!f&i$-K;%Jf^5iKE(UBy0B;YdeiQ&@Vckr&=Sq zG5kWjeyaUN-_R1I!EM?Zkb$=;n~&~wh>z~I;6(H*k;&3Q3m)u$r9$2Z>kuz@e$^wN zxGVOKZ)}u)IXkzaUyu9;TJUCC3*2WV|09h2&`SPp`uhWGEBW~zL5_S;$q-?ooIhLF}boRnqkP~EEer=P6Y2)qA8p^aST1L98Xu8k!x^-uo;)5s zV*QCS?pGd2yTtk%%Q~$U#`?{xjJ2`;`=j_MtD5`B^t5b^^;ef`vHmFivCQ3Ae+zFg zMOxI-GAILU>1tDDx{-VdqZU;J)8#vpj-#)w(|KoRB;WTjGDp_d)^@xxGLi#m9l|Ne zyE@nL=XvzQ^M*J-o}Et!jO5r>SBGxNeaqM6J{~gC!G%x1{#?yv+9$cz(Li7d7iINot(#;HlT1$ z#|=p4WI3w=bCe_p8c=hx{Gz3;&^Nv7yfvTVM`%;q=uF#JJj6iG`*Kn@E}9)W%=MR-@2E6;z2&Um%0K{t+C15qcNHIvQcA-;Be8H zRwc`KTJU9~CJ4T4qy>}PgmO8e?rcIinF0Auhq-&lHKmt)z|xcw5@c*sicOTwP07Qn zb)Cj@!hNRC-R@%s@SmgaBPTDGR~g9*#rr6c*UFL2bbPi1n`t`^=SK39p&32lf&Xwb zGsriaQ78_(Io6qM^yb9!T_`R17@|2Ib(n)z59EcP?*XTA6vR+?vE}>D-zS4>hfEt{lA%8_D8-0B^~hYLOs| zwBSQNEs~@`fGo)}IACg?rA1Ia2v7;0R10cOz$9IUCYYM%Cr}l~eI3bZKamVM5=^u! zVQiw`+)K74nw9WVB1XI;Pa>2kqqInp%}G?uy4C_mlFSUS(MKgyI`5~GiRE6B%;>T0 zV^b)eF9W79X6Z6ohcabVifO^w6urB$#UEtE*+p%FWMzDVq$bGDAX)feB1o1bsg{c1 z1JzV2Ns+NS6qL28xFSwnAy;%#wx()Vl#1(5le?*ulP8p7#HUsJ>E|D3LP zyw5$dqPM@6yxzv26#J2iCqZBQpL5FKo0-Qj=-3Z~AKUm-V~f<(IFqh&__hV7LY4Lx z45HilW2IkPf4kUc)is;0zkO~>SgflU@~FSQ>~HH&k6ooY@)aX}UFEAxx`bi<7nu?U z#_m-cO$uKwMe6F~?*>iUee!lY|AVm`)exP7OaBjQtv1u8_vu6Xsz%J%3Vzf_sEOw{cU5Xs-C)Bt}UR|wA(A4!9UykAC7%brO_^ZwQFWeIRBe%L#zz$ z;7^O)X8!-NHWJM_=J}Z00nbnfa|P@q_&l64S|_5W8Fj=$XDwyY?yF zzN`KH3}Pond5vnv*Sz%AKgw2-p^Mqqi4MH2F4eYaEvZUR(Um`wR{WShUb=Ml2V-AX z^+Icm#i$Kx|4I+%b@um&9j|t~n$ukG&zvChwayg0Ud_|ST<7VO?pLvH6=}8P*@sx0 zTU0cy(bsvtq^Av5JcfZ8nG+BB1F;iSj*jIz4O-o;XYS-6dcWdff4Bs?_!DEdD*YWi zeO+?J%o|8CTl&y}#a;ZZV;86eb*;g9zTTyai5`GK#|(RT1Q)S2`h9DuRhEYI$(1UcNKJ6zRpbV`^ElAjnk!ZO(a3573&$e z)`OARm*MXgdqmxF^IOas&<6X=$Y}qP)Sb?~XeL*ea2~WlMdyIb0`m&5y6*bI!d69Ox{V`9M z(4{9suvTrq$5uU~vCTYe5NRuP+D>)rUYj;9-li4naW^ZtS}#`cpH-nvSN)N?*}HYK zjlrm1{w}dIN;*Ez8K~cdO88nE>`~*~(Digfr<{w8mEOH^;Kk~^n9233M6g5moaGe9KM(cdX z9`%okeP1nh4zH)ncTJBKF1<(WW)<&tbVa^4tMe6WSH?{Aj@_>g5~nZylMp)X$m8#r zwEB|Jmu;|EWjKS7FWI6q8(+7eFB|>$YNDIxWY^Q$+KYv@LAcz~R+CiEcBUHD^FiC^ zL1w-8qkZrEuj$yL=W9hjf9ooFs&o27DG8ktl9YJb`kTbgSC`x%bVO=3UT+SJY4Bs* z8JDTW9c)d_2HBd%>B(i^4vZaDGOr^r(U~ji6;E1oso5X5F+z>AdDSpy5UnTP7%bEV zFROev@zHKiSJeH$sSk{us58OGge%L6(;t|VYfIHJ84v%#hs$eua;zYY#(^n4nF{~5@Q z`BU>7Ai9Jbu8Q-ziax(%F+8t|>6E^<(-B>LZQTKr`Om+j^hM^EPqaZr*ZVDc1=bkE z%Kb!DbPm5usO{P*QE+XUItYLM2i22r1?o%xS35mYee@lHh0;5=P>paSqkqjq*W64m zdowaU9%txgssf#pD>QSrO1A8V$Nd?xud3Q^<0zJ)E@7NoV8-Qjh~1&KhdPJT)YS({ zyuz%(4E{=UoYPh8alId=4?S!lPHltf{R`@<&c>BN`MQe5dU(>Fz~_usQSM%z;e6E$ zownc!*7rVs2TtdrMz=R_=}9x5u*wiT;WRbG9S6r@s0%)+Yc>bU7lv?P`%rBRmEbye zUXQIgO8j#OH|-^Abzf71YUWNWN{{WlCmH;nPja^%tMYAniOb8^?ZY4|cAU~XS6{PT zzt-urf}z~1n+;{vty4#IqqvSagK_3GHI$pxn3A-0E^T*7=36@Rbo28%I`aZ|v&t|N z^Awq9m25Zd9CRH4-7hokd!NG3Zcu&PqSC)&qYXNm(~7kecq9j`lLuYnQ5sprb&d#t1#9`*E?DP{A8snM-v zU$(z#>(ROIkWj-F<5eBY75FF84!IqsyC5}k{7o6zckl+E%Kr1=)un%qzXAQ&$WE!w zSnJDJPQ{Yk?ZuPpuOo+Z{Q77+-iGcH!X@m$J=|}z=sa?NuKzxas>t&?%cxvqr2oXP zJG2|4-(y65e=8rY-=i_Fc~+7N8L!-GKLqQ z?~e6XspeH@upzg(s;a!F<;oa;Q*V5XM342yg~i9Tk(Xb@I%BNgU-jvyoFPjxRSlBm zWBqk1#K$}p?@_g6T7_d3!URaJ$V zPE{WD(1>le@@BNat4@aM`&&sd-siGq;*0)ZyGVX)sBFDobT2K2B}H0k6DGHt2jja)Ac$J6C~uIS9+pO~VHzUcmSxuUy-a?_P= z>TxVMt1lMCNTVi$_#(zaA{)5vfYz-&{#mRra&eaiTx2digCHXy#G-<-$w;niX2aT<7OMtIOmU z{jnV)!}*Qk(A}h}{(t@M(yguKe!o~pm2Yh~Ra>W-G9ruXpvTGnF*vR0m;H4ki-!_% zuZ_qs5f%AK#UdL~Y$ARnBHu>rwif)5W-}Xc%|t9AqOXl;Hc1z{vY)O|*HW|!wY6(# zRW;IS`Yt;IPJE}iDhX6Rfvx?~~gCbm#v zq(!-YM;FoN(52g7HP55oEXl}ooVz^ykGWN({lk^&o?%R?ZvM1ybqsy)H?yBE# zk2#CzQDHBXI))hit8MPm-K|?Lt$8Skd;yh2TIeJcGqBv! ztgVKU80v0}>RcvcUG+L?q0YsW+a?8S6KVWEI&;OS(emSD`u3cvROl&LSJhNnnc|Yv z{iOZX#Z)V|!UF0pX}jD|RVx_*J&Y-8$BQ2I7kB!rrphj&mTKzD?7dK08^%0zc~nQW zW{Rg|15_(F(3RD9q=lxk8h+s~Q#b;7q{1uyhpOEzzWxdu#ogcVZpAX>6@O|}acSYB zcKzWMK1!(2MfIESQFUd1MwRN}j7SXsAJ8AySVhJx^^{Ceb(L9In)SQG9Z35xkBoZ7 zAKS40GP1kG>gBvWFCa;)Aqi9cwLCrL)HLq=gO*8a%J=42*|GqO(EX%3gB7~;A!%Z{ zG;XtZrul=_%im`IgiW$+P4iX{=*&N|bwanE8Y=gN(&9#{3M)!iQ4LkeD>J71oA&6U zo+O?(3+8f9MRc?Q|HJuM~%HMUQ-K+jMZaAynVQ)yM zSN%0*^sD}Q530!X#ORL!^i@lZ$h4YXFC*2UO&&GYMbx6DrD?TL?hiNIPD;K1B)n@7zp$yL4=?~%6H z=4ui1@E`R8?E6lo>Vs)iWY%^@rX=5UBSO`AIBuLJ?N&)z`ObW{qx3PrdC^{a2KJD4Pf5P=Gw^rPLK~2$HhE%} z-xqO{$eN}L%tV!4Wm{B!CaRNG-5An~rY2x|k&c>CQe*jEOeQUKe~tT(CAE$;Dalv9 z7Z2_(+xzmp=tWxTsJUJY&>2F#$S!A5z8BAy7}AUJ1Uz;wCg}K**66=?YcD+)Gs=}$ zelF&b##ovw&iu}2C|`Wc2GT-zzyDl8`$!AjLfu?csSpU9Bf6!me2q=gI8gC@-8{Xz zDuk;_1S-hn*?7okz7FS)8ywR>N0rpAe_u3IH-C|jw4{)N1f6^oU;cNa{kzG-%RFT%R{jm{!4(sNb=-;6}?y=EZ zKGCZyhT<9>LJe(?y5-#ecZdH$+Gq8o_k3;>J9vj3Iw_R55q*J{Ke>c67CIGR|$lcbX{CgY4dm`UdO9O z$c1@KTp?<-=}{v!6+LA4pIH`?mZir$wr$M6;=JmUl9uG;mMwZOFGfQCpsp$`vvcEP z4%d~|^Zj+g)L)EJyTb6N&tN`UH@{|u;e|cw>408O4ffP8J4oeQ|6zT3i((>Uer54I zW!lssW-xC>J}zm~3;AW+RKKCOWM|e@qn<8Ji;ron(@g&()%|7k#E@RILiX@<0x{00 z2l_atA3$I4^k*A+xf|-0Sfr+-hc;LJ{}}t#q-DDK|If6D#@>>*g8!M;ku-N|VHuPk zk#3~j>v~mR$ukT5QLLTejb-QpzkX#ri}VK4X`#PX!*!^h`>bt)|0rhtBVK(hS>%sx z6f>)rS3T$!V1tr3@_PTNn4^8Y>RnUZp zp${6ZZ!%SdMX7)M) z8%xS7S;aJW#Q6SCdDW7Vc9c!aeD?ccUgi5g^Sz*M50eIq7{BBtURFI=8mnIQs)udt!>G>o71aA|>;}{pwy@JPysE&)cA4qrg{~Qev8C#| zQuQpV#~S<{b+A=aX0b$MzwYZ3v%M<8#?D4ImRqq_HI%Z=}puS?;(D!w(DzveO zPVlG9M5D&p zHndo%SDWelEYwBPcQH#~5v$ln{t@*9tBw>eM>Atuj9Sa8f|_L2Pf;6L^(v~H{a;X9 z+1RFwy{e&AA4YXUHV)Md?|9TR)}ZeauNrFG_})^lI%;Fb{oc!IA=6i-x)dz*heuR< z+p8wnq}ix{l?!jt{MCB$^$L#o{Ti?8Xw(0W`ngrNto5qSR{aUJfmNg5@$wL0`nL}C z6RSSA&a2K^wflNK`Ep5F7i z1aG4)()$mr^&NcX`-EKt(Ys2fr2uu2HH_RXd$nQp4@#C^I-iufg+2zgxix%ikF;LF zW9?^qqz5wM;k{ny?+Vf)VO@z^k8$wK@#dW7SO5EUSKu+Q6vZ z3kSr%lH&e#Sl?$&p6pL__Q@+5b+k0C)$+dgiA>UVzdPbpl}uFRFx2P>d21!7xPs%H zBCO?G$K?lYxtXX|a-Ga={*Jocxvr4&*Fo*+UO&O!_iGSCv%*9!ODm!m=3X~U!Rl?Z&Q%>l$ST4o!+LP7O0J7t5$oX#u?R{ ze@ZrM!)Bl9fj6mrQEON=7d6qUf|_9S9QjPztR~OsziMA)^1P3lYSn9~6|CXE{wf=^ zVV~1p^`uSRgc`K!KTsPOHPZ9BSA7>IC*Edc|ND%NzOaU4bEPl6>UKq$yN2kni(b{n zL`Sqo{f9h{MMV51FK0|`9PuQo%@^@fsk#I;(Hi`@RQ(N=Cv38L!!OI;wG3*b%W@VO zk@`=aw0|unb|_W5ma08V)yGQJ!KG?ushVG^K3A%aMcrho@ZNhx{OkO2k-M*YRfI>r zUQ16u{9aGKZh`mE_qK8W_+BPq7V+aP-MGy4H0~zq!&Ytoi&u>_YS@Nfyz=8Zf1QXf zzv?|@EQ?W}vFdlI1=e!#9j`pK9?R)>v>!B<%Te#K>K@bvRy~Uvv}*KkUS4h(+qS5W zT6Gp`C9A%P+QzEKQQxrY(7RrhW7PwtYSVw~Bc&;9aj9Bag{fE@8;@GksNNLCe~o39 z9#hf=8F4RfmwnRkT?Qh6>M^P}Axh@z)aQL+oc-R=sc}`q^vy%7k41;6&!p3L6>8{1 zaFgm`_;FK0H`Hdk$Z?TfYfm6~CAN~8K~g{fDqy0CVb`X8&#hznEKtva5Mn!8)| zK>aYa#FqO+gD_4Zwi)qZD$~ZkggV!%l^TZe*|TXwjZ*a<)ao`iu{5?lYNU;Q2$dHR zoBXvS(3W~+?`D?GPmRLVJW1HhvYB$PwBF2UeRr?)Kt{A~9LA%nPKtOE6{o1xk5D^W z_1~!VtXj88n2IuLgZofFbe`$~C$-RC>{1i)zsJITzeSj8A8A?;c{32kGo#gOB!#I* zDrmh{cpE*urpi}Q@y@#T8K{1%E<#PV>ZhpBST(tA7&mZZ`w1!!0y^6XRA=jLrw3if zMm~aC)s4g8_Mv={-=ikkXm9+3a$*Z(5%~~}v}H9$Z7HX=P;8%WdPsFy-rR1|VJm~z z^I;i`jNHuMgj(*Ep<5Z_M;-}NKg*L_$WDRMJupn=8P&UBpv=`)JoawTR*{c~sczCR z-CJGuQA$M5Az|vGY@z~h>!;+dHu-p%u2V-vT*%Vu8(RH0>VHY!J{&W2M(@{8%cwtM zef8-uRau_@BPKUX)JT=jw0mXlAL(V(GkU2Ri)yIzjOtzWjP%}4!?rtl*viN=nB=&e z?f9@O)tbLB(p2Z2JW}?OEn@qqFy)nm9aOusRNalr%o6MUXq2?xf#G$ceAe(TYHO>u zCUq`q1*`okRwLV^KIV~0 zyZo`L zMvZ*$)i70?cRjkuPhOJ-?^D!~*TPg!YguEqS;l0FOhnE18q0{KbHjKtFlBv?`m=1( z#eTX_&yD8;)W4w~wCe8{g>m>bvA>|cXVrBQrY0HH+jOzq)z$uKaTrHNV;H+6OucN? zH&I>e52#&iY~oVA9<^=c0o1eM^45oVm_LN^Ow{*JG~n3WwCZc9hfU)f_T3#;^4*irH;_UOH=neY zHpc?gtG2tvAB6E(YDzzZTHmS{QR~{d`E6gA`q9Q--5;j<*=!v?4&!OWWUFv6jANlu z??eWDbnb|{M!m3~bhLCE`AlhgF{;hg zZ~RQx>R{aF^FGh`A)FNC}a0M^Fzog)bEyH;QVyYg1TGJzM9b`ARDw(okR9EnR)M8t3 zr`F;6lRrJD<4|4qH=Ee!_4K0MXVaq|&|Qu>NFAJ=P4#0?la1n$esdDQww_0H`qn-5d!YNDFS*28r9SgCpg zwWEzqen?NVF~~;Ev+7aQB&*&jRUhc0C(+pULUjhksQ+JA=K@|uarW^&o83bQkcE62 z1DF_00E;ykY^w-Tf+Zk@M9MW>0&)?81-TTw(Extj6c7R9R8Wxese}?xqaJIJ3aKqO zk(=BF0!SMX6ksJslN7p71X9g6SHQ9tyDys2$wi4~dOinXh%t^PK89acv7@NA~YL-qlt9>0pkE z>Tc>KvbJ&hPkVc;d{pXDi!~M#`pAZo4$(WnCz|M}D<1cp--<@tWwF6V3f(J@i^T0j z?K|FcM(WfGutMXM39`&8&&%M)8hcIjoOd<)lWHUR$rf9J3#3DeOmFCltnF0m?~^^& zX)4$$kpCC3gVE^Q$)a!v1-OJXS4sY~DSRBJac+q2qA6l0j?tq?yF5|6gOF>V@mNU9 zIDR!aM2GA;Rdo1_koOgPyh*6kLEu@D^BIm^rpsYSsc(R-6-M`g&&27d`7=G|zuM!s zv%*sC1>0)1{%nt%R4T+?@UjlEV~*$4xH`n&p7-P`Q5GzFp2vh=;nUzBRVkvE_!5gc z#`)R{vJsU>urS1QFhQ%Wz~j2~br*RoRb@q@4=(1lXNvr2iN`pjLYx8L)HwfTIjl=H znk*P3<8|TItnlQ*Ru(Stbv0JVb{VwNb5>~e3iye}ia%2+jq6r1*eP@?SBZ_gXyKWq zvM*-uCi^n*evMy%td~&T{iPynH;xyP(sgRm8qXP}F!~huB=-+?F`c{c7wy?#t>-M$ zo~yym8qa~uxaEny2is|EUB)|+#%>@BBKz z+NyoM2BJB$tcf99u%Ueo*{`+dol=v*zS*!m9x$Py@onSkSbw7~ps?)h%zI%_y&9_BI8A70@I+MHl3z2t#dTskczOU^*%oW@(U-mMLf5PIg z56GE>Qe$AgK2P+Z%-z&GC`+u)y!fEVI>;q@>yVDS^-!2}&tWa~IV|S`$~*IjmU54T zUT+&|Pbm5AkE*VIkP;30QqB}qF-pN~jfXAPJ0?4ha%cyx(fF0cg~vm+?Fo+$K$Pzi zu&u@&7X7MF?Eo@qmaXz4XimJz;zf%YCqswcU>BWjnZ=Xf2(9Lx3QsW&%+hKZ$P8Sb zZ7axtAS-|3w44tp^{T}tUxn(u7JGwTbhc$@!U*sFOLlV=p&Xp5vGu=0{0kUw94uB? zthBh@;$DkKES|D>7VIRdzNC9qdvc8?tJV)Red=>?qL?7lzYfK}TFgEhs-+4e()AmU zj~!Igq@54bUk16MFB{DLPQKLSxuWTyo2y?5xBtqQ!`X3ODDC;$oa1!=DM;~3@{7Tp z3Zvcc^_`J%BJVh(={xs}<6Ojg>|&DyFs<#V0t+%8tG>O9yF@7BHz8s#VZ!vhA*j)v_7NWZ$SM02!0BK!(=a5dl1ZF9WHt*^?)y&_k z7;X}~$xteP26&fv=OhjKa5u5;B>9Vw7zU*@-bl}dlGt^E2fN=s$xu{^$PkO4UkNfW zg3&6lJi-@k@k#wlJc3%g2P^-E=2}l$fzfVEi|^q(iDs>NV_I^aAFk_eOzT9N`S9H# zt#)&)zCJ}H)^23HF=KI_7E%1CbdFX$*w#bi6W{=iyTMKx|EG`dOi<{~>?4++;oabDAMp{^{|`xQg`%2n zTwf)L@uw2Kh}Qh3eSK$=N{+q&#&OH`3_Wd8KcCNTWG=rF%+PoS{Hw+l{e5S##_R&0 zDS`6s0w!rJ02^r>1Kz4}HdsgGR1*sI1i9;D;_(%7Eb`eO&l z?kDT&K5LSe8~c&5`;EP5Y~o-Ys+F<1#tt*K*x04Ueqih#W6x{rClt!pb@n-$`3{f| zAV9ZYp~yN%mzai>qEiL9NvHN7qEn|2@tt)#HEU=XraQ>EDkBa7pU}7;WTy{mblM}n zlMoSk=h$-f+%VtynP&gp;XXH?7yX!+!ne~DpXc=ND`m!cLd8IyI{7beETQOrWc(_u z^s$!Qjl)G=4U->In8g2}v$5e&#;Q`H!XH4RUJcb~(g=DPcP-D;zf(s0tj>D=L z;J($w$Ibt#)l{hd%2DAX%2VN!R-IwhKY@w5FmHmNXneFNEX-Jte}5)RI~%-3<7;5P z#&4`|4H&Q0E1-#6cZ|<$UPZ_SO(lDPDOw!~nz&QJe9`Oz^|7vdzTmwXIc$T6GktBe>5$COTZ=8lj}=-0Q912Ugu@)gxBDY*pv?VT3f$)U`R7 zA)3*jJS*l~*RfXpgH;z>^%bketh&*vN3D7a)Yalqx}0yhUDaT0ZJ{FEh>}Vht30fg zepZ>Rm8mH0RX^8%|Bb&*+>=_V4)geR#)Xwl1WhCU+^Y8|b&7XvB-{1NUvA(0M?_}kxPNrPt(BfIo4N6q6kV??BUX@k< z4VungZ$enEB+#h8v}$`WQ&)GWRYzHMo>dov=4@|UH3piO{4UVc_Zawd9XDZOScXO* ztM>EM2QscLLF3xXx(-mTs+Pl)?`}DOS=U#s>ni0Mxv104*svM#L0tfUQdofcAln~m zaD_|(ZU;>P@~mqg<*EuW*!n&On(MgA`mPCmqwj(}x!24X?8Z%2?+30oS**Lp`@&Bz z$$6#5CdEjV; z(HihfM6A0`u?`7w4Nv#ZKb15In)p{3E0oD)OUVevLLv{Em&GIE@i1vS}hhs)*t>m`?r)tMH zty%^KTHRpPN-$Ze(L>;aaUv@&NcL|nlif|7pjDYj@HjyZQmS~w&jWSJY>`%_FUV zz5M^+n9Kg$?>ShSJFlnkK+{_U>c(>78a9c{2QnR}w5~qR5}-F#SV)k_P5PL~6F9p# zKH#MHrt4!8dAJwstR+r5+p49N$A=U=gTi)XAN(sE&rtYk3iA+^YD&fDr%ux#|0p5Y zj~pjyg>DpJJ6dx}8jwjIjXCKof-Sh+alWF4R|q(OZ+R$WOLmMyT6t_nE26DykLwiZ zHI8%S%VTTbha7|1PafkK+=E}a&Gq-*v>|8`H5o%qw{UEY)5rUK14)dgPNn%pzR7wFx4vZW~GB8Vgy{WD0E}D3=S?tM8hG$LGj&?;BxBc_;Ed)Nq6z6B6fWZzxe6SGZ-CXsl$SK zk+k<{raRDhp4T~zeTiy+k4^a%-wRSl>=_=kNa{{Una?%ZK+||!x10Vb5=I0SktDHg zMDTRtk33Y~5tlo1c@vR>Jv{XP E0hNPYRsaA1 From 84d8414a2e0c169ade46fab074400ee859ba1626 Mon Sep 17 00:00:00 2001 From: Robert Lefebvre Date: Fri, 23 Mar 2012 09:17:58 -0400 Subject: [PATCH 06/78] Fix Auto_Trim to allow it to actually be called when setup on Ch7 pulldown menu in MP. --- ArduCopter/control_modes.pde | 11 +++++------ 1 file changed, 5 insertions(+), 6 deletions(-) diff --git a/ArduCopter/control_modes.pde b/ArduCopter/control_modes.pde index ebca424d6c..27c4051427 100644 --- a/ArduCopter/control_modes.pde +++ b/ArduCopter/control_modes.pde @@ -72,11 +72,6 @@ static void read_trim_switch() } } - #elif CH7_OPTION == CH7_AUTO_TRIM - if (g.rc_7.radio_in > CH_7_PWM_TRIGGER){ - auto_level_counter = 10; - } - #else // this is the normal operation set by the mission planner @@ -152,6 +147,10 @@ static void read_trim_switch() // 3 = command total } } + }else if (g.ch7_option == CH7_AUTO_TRIM){ + if (g.rc_7.radio_in > CH_7_PWM_TRIGGER){ + auto_level_counter = 10; + } } #endif @@ -212,7 +211,7 @@ static void trim_accel() trim_roll = constrain(trim_roll, -1.5, 1.5); trim_pitch = constrain(trim_pitch, -1.5, 1.5); - if(g.rc_1.control_in > 200){ // Roll RIght + if(g.rc_1.control_in > 200){ // Roll Right imu.ay(imu.ay() - trim_roll); }else if (g.rc_1.control_in < -200){ imu.ay(imu.ay() - trim_roll); From 89576a281a2d715ab079083dcde7437f656b949c Mon Sep 17 00:00:00 2001 From: rmackay9 Date: Fri, 23 Mar 2012 23:12:49 +0900 Subject: [PATCH 07/78] ArduCopter - updated to firmware version to 2.5.2 to avoid confusion with post 2.5.1 versions posted to downloads area --- ArduCopter/ArduCopter.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 602d5fffac..3ef0b5af94 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1,6 +1,6 @@ /// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- -#define THISFIRMWARE "ArduCopter V2.5.1" +#define THISFIRMWARE "ArduCopter V2.5.2" /* ArduCopter Version 2.5 Lead author: Jason Short From 63b96c0153be74ea3e6e36e12a404dd1e8061c8b Mon Sep 17 00:00:00 2001 From: rmackay9 Date: Fri, 23 Mar 2012 23:48:24 +0900 Subject: [PATCH 08/78] ArduCopter - altitude hold - ensure throttle_avg is initialised from g.throttle_cruise parameter --- ArduCopter/ArduCopter.pde | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 3ef0b5af94..529e020f1c 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1580,7 +1580,7 @@ void update_throttle_mode(void) int16_t throttle_out; #if AUTO_THROTTLE_HOLD != 0 - static float throttle_avg = THROTTLE_CRUISE; + static float throttle_avg = 0; // this is initialised to g.throttle_cruise later #endif switch(throttle_mode){ @@ -1598,6 +1598,10 @@ void update_throttle_mode(void) #endif #if AUTO_THROTTLE_HOLD != 0 + // ensure throttle_avg has been initialised + if( throttle_avg == 0 ) { + throttle_avg = g.throttle_cruise; + } // calc average throttle if ((g.rc_3.control_in > MINIMUM_THROTTLE) && abs(climb_rate) < 60){ throttle_avg = throttle_avg * .98 + (float)g.rc_3.control_in * .02; From d371862fd2a8266156ed1262443e98748ea43bed Mon Sep 17 00:00:00 2001 From: rmackay9 Date: Sat, 24 Mar 2012 14:47:21 +0900 Subject: [PATCH 09/78] AP_OpticalFlow - resolved compile error in example sketch (it could not find DCM.h but it's not required anyway) --- .../examples/AP_OpticalFlow_test/AP_OpticalFlow_test.pde | 1 - 1 file changed, 1 deletion(-) diff --git a/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.pde b/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.pde index 110ab55173..5e8324651b 100644 --- a/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.pde +++ b/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.pde @@ -7,7 +7,6 @@ #include #include // ArduPilot Mega Vector/Matrix math Library #include // Arduino SPI library -#include // ArduCopter DCM Library #include "AP_OpticalFlow.h" // ArduCopter OpticalFlow Library //////////////////////////////////////////////////////////////////////////////// From 2d65ec2874a0287676697f574af59123aed9a3e7 Mon Sep 17 00:00:00 2001 From: rmackay9 Date: Sat, 24 Mar 2012 23:21:11 +0900 Subject: [PATCH 10/78] AP_Baro - change data type size of temperature's average filter to int32_t (was int16_t) --- libraries/AP_Baro/AP_Baro_BMP085.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Baro/AP_Baro_BMP085.h b/libraries/AP_Baro/AP_Baro_BMP085.h index a07833e7fb..c60e022cbe 100644 --- a/libraries/AP_Baro/AP_Baro_BMP085.h +++ b/libraries/AP_Baro/AP_Baro_BMP085.h @@ -38,7 +38,7 @@ class AP_Baro_BMP085 : public AP_Baro int16_t ac1, ac2, ac3, b1, b2, mb, mc, md; uint16_t ac4, ac5, ac6; - AverageFilterInt16_Size4 _temp_filter; + AverageFilterInt32_Size4 _temp_filter; uint32_t _retry_time; From 67cf7b9eedb27bd4e4042b83d4d1ed98b1ef22fe Mon Sep 17 00:00:00 2001 From: rmackay9 Date: Sun, 25 Mar 2012 09:13:51 +0900 Subject: [PATCH 11/78] ArduCopter - updated firmware version to 2.5.3 --- ArduCopter/ArduCopter.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 529e020f1c..06562cdc49 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1,6 +1,6 @@ /// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- -#define THISFIRMWARE "ArduCopter V2.5.2" +#define THISFIRMWARE "ArduCopter V2.5.3" /* ArduCopter Version 2.5 Lead author: Jason Short From 7c2f3a0c21c35a1f37b34ee542bee0939ee24b33 Mon Sep 17 00:00:00 2001 From: Michael Oborne Date: Sun, 25 Mar 2012 08:22:09 +0800 Subject: [PATCH 12/78] firmware build --- Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml b/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml index c64b47acfc..0784a82bae 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml +++ b/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml @@ -114,7 +114,7 @@ http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560-2.hex - ArduCopter V2.5 Heli (2560 only) + ArduCopter V2.5.3 Heli (2560 only) #define AUTO_RESET_LOITER 0 #define FRAME_CONFIG HELI_FRAME @@ -178,7 +178,7 @@ http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-1280.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-2560.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-2560-2.hex - ArduCopter V2.5 Heli Hil + ArduCopter V2.5.3 Heli Hil #define HIL_MODE HIL_MODE_ATTITUDE From 7cb2c1de65914e7913e2dd34c934a170f94e36ef Mon Sep 17 00:00:00 2001 From: Michael Oborne Date: Sun, 25 Mar 2012 08:27:31 +0800 Subject: [PATCH 13/78] firmware build --- Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml b/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml index 0784a82bae..a08bdee480 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml +++ b/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml @@ -47,7 +47,7 @@ http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560-2.hex - ArduCopter V2.5 Quad + ArduCopter V2.5.3 Quad #define FRAME_CONFIG QUAD_FRAME @@ -58,7 +58,7 @@ http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560-2.hex - ArduCopter V2.5 Tri + ArduCopter V2.5.3 Tri #define FRAME_CONFIG TRI_FRAME @@ -69,7 +69,7 @@ http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560-2.hex - ArduCopter V2.5 Hexa X + ArduCopter V2.5.3 Hexa X #define FRAME_CONFIG HEXA_FRAME @@ -80,7 +80,7 @@ http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560-2.hex - ArduCopter V2.5 Y6 + ArduCopter V2.5.3 Y6 #define FRAME_CONFIG Y6_FRAME @@ -91,7 +91,7 @@ http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Octav-1280.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Octav-2560.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Octav-2560-2.hex - ArduCopter V2.5 Octa V + ArduCopter V2.5.3 Octa V #define FRAME_CONFIG OCTA_FRAME #define FRAME_ORIENTATION V_FRAME @@ -103,7 +103,7 @@ http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Octa-1280.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Octa-2560.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Octa-2560-2.hex - ArduCopter V2.5 Octa X + ArduCopter V2.5.3 Octa X #define FRAME_CONFIG OCTA_FRAME @@ -162,7 +162,7 @@ http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560-2.hex - ArduCopter V2.5 Quad Hil + ArduCopter V2.5.3 Quad Hil #define FRAME_CONFIG QUAD_FRAME #define FRAME_ORIENTATION PLUS_FRAME From 1f4cfb933352a933fafd1f5a9b95d37216acce90 Mon Sep 17 00:00:00 2001 From: rmackay9 Date: Sun, 25 Mar 2012 15:55:49 +0900 Subject: [PATCH 14/78] ArduCopter - added PID log type. Implemented for Yaw stabilize and rate controllers. --- ArduCopter/Attitude.pde | 74 +++++++++++++++++++++++++++++++---------- ArduCopter/Log.pde | 48 ++++++++++++++++++++++++++ ArduCopter/config.h | 30 +++++++++-------- ArduCopter/defines.h | 2 ++ 4 files changed, 124 insertions(+), 30 deletions(-) diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde index ac7f272dda..8ca346f8bd 100644 --- a/ArduCopter/Attitude.pde +++ b/ArduCopter/Attitude.pde @@ -59,30 +59,47 @@ get_stabilize_pitch(int32_t target_angle) static int16_t get_stabilize_yaw(int32_t target_angle) { - // angle error - target_angle = wrap_180(target_angle - ahrs.yaw_sensor); + static int8_t log_counter = 0; + int32_t target_rate,i_term; + int32_t angle_error; + int32_t output; + + // angle error + angle_error = wrap_180(target_angle - ahrs.yaw_sensor); -#if FRAME_CONFIG == HELI_FRAME // cannot use rate control for helicopters // limit the error we're feeding to the PID - target_angle = constrain(target_angle, -4500, 4500); +#if FRAME_CONFIG == HELI_FRAME + angle_error = constrain(angle_error, -4500, 4500); #else - // limit the error we're feeding to the PID - target_angle = constrain(target_angle, -2000, 2000); + angle_error = constrain(angle_error, -2000, 2000); #endif - // conver to desired Rate: - int32_t target_rate = g.pi_stabilize_yaw.get_p(target_angle); - int16_t iterm = g.pi_stabilize_yaw.get_i(target_angle, G_Dt); + // convert angle error to desired Rate: + target_rate = g.pi_stabilize_yaw.get_p(angle_error); + i_term = g.pi_stabilize_yaw.get_i(angle_error, G_Dt); -#if FRAME_CONFIG == HELI_FRAME // cannot use rate control for helicopters + // do not use rate controllers for helicotpers with external gyros +#if FRAME_CONFIG == HELI_FRAME if(!g.heli_ext_gyro_enabled){ - return get_rate_yaw(target_rate) + iterm; + output = get_rate_yaw(target_rate) + iterm; }else{ - return constrain((target_rate + iterm), -4500, 4500); + output = constrain((target_rate + i_term), -4500, 4500); } #else - return get_rate_yaw(target_rate) + iterm; + output = get_rate_yaw(target_rate) + i_term; #endif + + // log output if PID logging is on and we are tuning the yaw + if( g.log_bitmask & MASK_LOG_PID && (g.radio_tuning == CH6_YAW_KP || g.radio_tuning == CH6_YAW_RATE_KP) ) { + log_counter++; + if( log_counter >= 10 ) { // (update rate / desired output rate) = (100hz / 10hz) = 10 + log_counter = 0; + Log_Write_PID(CH6_YAW_KP, angle_error, target_rate, i_term, 0, output, g.pi_stabilize_yaw.kP()); + } + } + + // ensure output does not go beyond barries of what an int16_t can hold + return constrain(output,-32000,32000); } static int16_t @@ -172,15 +189,38 @@ get_rate_pitch(int32_t target_rate) static int16_t get_rate_yaw(int32_t target_rate) { + static int8_t log_counter = 0; + int32_t p,i,d; + int32_t rate_error; + int32_t output; + // rate control - target_rate = target_rate - (omega.z * DEGX100); - target_rate = g.pid_rate_yaw.get_pid(target_rate, G_Dt); + rate_error = target_rate - (omega.z * DEGX100); + + // separately calculate p, i, d values for logging + p = g.pid_rate_yaw.get_p(rate_error); + i = g.pid_rate_yaw.get_i(rate_error, G_Dt); + d = g.pid_rate_yaw.get_d(rate_error, G_Dt); + + output = p+i+d; // output control: int16_t yaw_limit = 1400 + abs(g.rc_4.control_in); - // smoother Yaw control: - return constrain(target_rate, -yaw_limit, yaw_limit); + // constrain output + output = constrain(output, -yaw_limit, yaw_limit); + + // log output if PID loggins is on and we are tuning the yaw + if( g.log_bitmask & MASK_LOG_PID && (g.radio_tuning == CH6_YAW_KP || g.radio_tuning == CH6_YAW_RATE_KP) ) { + log_counter++; + if( log_counter >= 10 ) { // (update rate / desired output rate) = (100hz / 10hz) = 10 + log_counter = 0; + Log_Write_PID(CH6_YAW_RATE_KP, rate_error, p, i, d, output, g.pid_rate_yaw.kP()); + } + } + + // constrain output + return output; } static int16_t diff --git a/ArduCopter/Log.pde b/ArduCopter/Log.pde index 4727884dc8..a4a3e4a157 100644 --- a/ArduCopter/Log.pde +++ b/ArduCopter/Log.pde @@ -72,6 +72,7 @@ print_log_menu(void) if (g.log_bitmask & MASK_LOG_CUR) Serial.printf_P(PSTR(" CURRENT")); if (g.log_bitmask & MASK_LOG_MOTORS) Serial.printf_P(PSTR(" MOTORS")); if (g.log_bitmask & MASK_LOG_OPTFLOW) Serial.printf_P(PSTR(" OPTFLOW")); + if (g.log_bitmask & MASK_LOG_PID) Serial.printf_P(PSTR(" PID")); } Serial.println(); @@ -193,6 +194,7 @@ select_logs(uint8_t argc, const Menu::arg *argv) TARG(CUR); TARG(MOTORS); TARG(OPTFLOW); + TARG(PID); #undef TARG } @@ -783,6 +785,46 @@ static void Log_Read_Data() Serial.printf_P(PSTR("DATA: %d, %ld\n"), temp1, temp2); } +// Write an PID packet. Total length : 28 bytes +static void Log_Write_PID(int8_t pid_id, int32_t error, int32_t p, int32_t i, int32_t d, int32_t output, float gain) +{ + DataFlash.WriteByte(HEAD_BYTE1); + DataFlash.WriteByte(HEAD_BYTE2); + DataFlash.WriteByte(LOG_PID_MSG); + + DataFlash.WriteByte(pid_id); // 1 + DataFlash.WriteLong(error); // 2 + DataFlash.WriteLong(p); // 3 + DataFlash.WriteLong(i); // 4 + DataFlash.WriteLong(d); // 5 + DataFlash.WriteLong(output); // 6 + DataFlash.WriteLong(gain * 1000); // 7 + + DataFlash.WriteByte(END_BYTE); +} + +// Read a PID packet +static void Log_Read_PID() +{ + int8_t temp1 = DataFlash.ReadByte(); // pid id + int32_t temp2 = DataFlash.ReadLong(); // error + int32_t temp3 = DataFlash.ReadLong(); // p + int32_t temp4 = DataFlash.ReadLong(); // i + int32_t temp5 = DataFlash.ReadLong(); // d + int32_t temp6 = DataFlash.ReadLong(); // output + float temp7 = DataFlash.ReadLong() / 1000.f; // gain + + // 1 2 3 4 5 6 7 + Serial.printf_P(PSTR("PID-%d, %ld, %ld, %ld, %ld, %ld, %4.4f\n"), + (int)temp1, // pid id + (long)temp2, // error + (long)temp3, // p + (long)temp4, // i + (long)temp5, // d + (long)temp6, // output + temp7); // gain +} + // Read the DataFlash log memory static void Log_Read(int start_page, int end_page) { @@ -791,6 +833,7 @@ static void Log_Read(int start_page, int end_page) #ifdef AIRFRAME_NAME Serial.printf_P(PSTR((AIRFRAME_NAME) #endif + Serial.printf_P(PSTR("\n" THISFIRMWARE "\nFree RAM: %u\n"), memcheck_available_memory()); @@ -890,6 +933,10 @@ static int Log_Read_Process(int start_page, int end_page) case LOG_DATA_MSG: Log_Read_Data(); break; + + case LOG_PID_MSG: + Log_Read_PID(); + break; } break; case 3: @@ -925,6 +972,7 @@ static void Log_Write_Nav_Tuning() {} static void Log_Write_Control_Tuning() {} static void Log_Write_Motors() {} static void Log_Write_Performance() {} +static void Log_Write_PID() {} static int8_t process_logs(uint8_t argc, const Menu::arg *argv) { return 0; } #endif // LOGGING_DISABLED diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 398cd1abed..c9c08e178e 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -830,27 +830,31 @@ #ifndef LOG_MOTORS # define LOG_MOTORS DISABLED #endif -// guess! +// optical flow #ifndef LOG_OPTFLOW # define LOG_OPTFLOW DISABLED #endif +#ifndef LOG_PID +# define LOG_PID DISABLED +#endif // calculate the default log_bitmask #define LOGBIT(_s) (LOG_##_s ? MASK_LOG_##_s : 0) #define DEFAULT_LOG_BITMASK \ - LOGBIT(ATTITUDE_FAST) | \ - LOGBIT(ATTITUDE_MED) | \ - LOGBIT(GPS) | \ - LOGBIT(PM) | \ - LOGBIT(CTUN) | \ - LOGBIT(NTUN) | \ - LOGBIT(MODE) | \ - LOGBIT(RAW) | \ - LOGBIT(CMD) | \ - LOGBIT(CUR) | \ - LOGBIT(MOTORS) | \ - LOGBIT(OPTFLOW) + LOGBIT(ATTITUDE_FAST) | \ + LOGBIT(ATTITUDE_MED) | \ + LOGBIT(GPS) | \ + LOGBIT(PM) | \ + LOGBIT(CTUN) | \ + LOGBIT(NTUN) | \ + LOGBIT(MODE) | \ + LOGBIT(RAW) | \ + LOGBIT(CMD) | \ + LOGBIT(CUR) | \ + LOGBIT(MOTORS) | \ + LOGBIT(OPTFLOW) | \ + LOGBIT(PID) // if we are using fast, Disable Medium //#if LOG_ATTITUDE_FAST == ENABLED diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index 2ddca06d3f..7d827948f6 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -265,6 +265,7 @@ enum gcs_severity { #define LOG_MOTORS_MSG 0x0B #define LOG_OPTFLOW_MSG 0x0C #define LOG_DATA_MSG 0x0D +#define LOG_PID_MSG 0x0E #define LOG_INDEX_MSG 0xF0 #define MAX_NUM_LOGS 50 @@ -280,6 +281,7 @@ enum gcs_severity { #define MASK_LOG_CUR (1<<9) #define MASK_LOG_MOTORS (1<<10) #define MASK_LOG_OPTFLOW (1<<11) +#define MASK_LOG_PID (1<<12) // Waypoint Modes // ---------------- From 39fd24ed14feb9fd04ef3558facd5e0be01dcd22 Mon Sep 17 00:00:00 2001 From: rmackay9 Date: Sun, 25 Mar 2012 16:14:07 +0900 Subject: [PATCH 15/78] Filter - remove obsolete warning from comments re alloc/malloc dangers --- libraries/Filter/AverageFilter.h | 3 +-- libraries/Filter/ModeFilter.h | 2 -- 2 files changed, 1 insertion(+), 4 deletions(-) diff --git a/libraries/Filter/AverageFilter.h b/libraries/Filter/AverageFilter.h index 5fa0406819..37bc05a566 100644 --- a/libraries/Filter/AverageFilter.h +++ b/libraries/Filter/AverageFilter.h @@ -8,8 +8,6 @@ /// @file AverageFilter.h /// @brief A class to provide the average of a number of samples -/// -/// DO NOT CREATE AND DESTROY INSTANCES OF THIS CLASS BECAUSE THE ALLOC/MALLOC WILL LEAD TO MEMORY FRAGMENTATION #ifndef AverageFilter_h #define AverageFilter_h @@ -20,6 +18,7 @@ // 1st parameter is the type of data being filtered. // 2nd parameter is a larger data type used during summation to prevent overflows +// 3rd parameter is the number of elements in the filter template class AverageFilter : public FilterWithBuffer { diff --git a/libraries/Filter/ModeFilter.h b/libraries/Filter/ModeFilter.h index bdb56a4246..4335ad8ae7 100644 --- a/libraries/Filter/ModeFilter.h +++ b/libraries/Filter/ModeFilter.h @@ -9,8 +9,6 @@ /// @file ModeFilter.h /// @brief A class to apply a mode filter which is basically picking the median value from the last x samples /// the filter size (i.e buffer size) should always be an odd number -/// -/// DO NOT CREATE AND DESTROY INSTANCES OF THIS CLASS BECAUSE THE ALLOC/MALLOC WILL LEAD TO MEMORY FRAGMENTATION #ifndef ModeFilter_h #define ModeFilter_h From 2b2dbf2a7f055870c216eb8bb0dc1acb606315dd Mon Sep 17 00:00:00 2001 From: rmackay9 Date: Sun, 25 Mar 2012 16:15:25 +0900 Subject: [PATCH 16/78] Filter - added simple LowPassFilter (simple but it's possible to make errors with simple stuff too so might as well have one) --- libraries/Filter/LowPassFilter.h | 89 +++++++++++++++++++ libraries/Filter/examples/Filter/Filter.pde | 33 ++++++- .../examples/LowPassFilter/LowPassFilter.pde | 60 +++++++++++++ .../Filter/examples/LowPassFilter/Makefile | 1 + 4 files changed, 180 insertions(+), 3 deletions(-) create mode 100644 libraries/Filter/LowPassFilter.h create mode 100644 libraries/Filter/examples/LowPassFilter/LowPassFilter.pde create mode 100644 libraries/Filter/examples/LowPassFilter/Makefile diff --git a/libraries/Filter/LowPassFilter.h b/libraries/Filter/LowPassFilter.h new file mode 100644 index 0000000000..e719a08f67 --- /dev/null +++ b/libraries/Filter/LowPassFilter.h @@ -0,0 +1,89 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- +// +// This is free software; you can redistribute it and/or modify it under +// the terms of the GNU Lesser General Public License as published by the +// Free Software Foundation; either version 2.1 of the License, or (at +// your option) any later version. +// + +/// @file LowPassFilter.h +/// @brief A class to implement a low pass filter without losing precision even for int types +/// the downside being that it's a little slower as it internally uses a float +/// and it consumes an extra 4 bytes of memory to hold the constant gain + +#ifndef LowPassFilter_h +#define LowPassFilter_h + +#include +#include + +// 1st parameter is the type of data being filtered. +template +class LowPassFilter : public Filter +{ + public: + // constructor + LowPassFilter(float gain); + + // apply - Add a new raw value to the filter, retrieve the filtered result + virtual T apply(T sample); + + // reset - clear the filter - next sample added will become the new base value + virtual void reset() { _base_value_set = false; }; + + // reset - clear the filter and provide the new base value + virtual void reset( T new_base_value ) { _base_value = new_base_value; _base_value_set = true;}; + + private: + float _gain; // gain value (like 0.02) applied to each new value + bool _base_value_set; // true if the base value has been set + float _base_value; // the number of samples in the filter, maxes out at size of the filter +}; + +// Typedef for convenience (1st argument is the data type, 2nd is a larger datatype to handle overflows, 3rd is buffer size) +typedef LowPassFilter LowPassFilterInt8; +typedef LowPassFilter LowPassFilterUInt8; + +typedef LowPassFilter LowPassFilterInt16; +typedef LowPassFilter LowPassFilterUInt16; + +typedef LowPassFilter LowPassFilterInt32; +typedef LowPassFilter LowPassFilterUInt32; + +typedef LowPassFilter LowPassFilterFloat; + +// Constructor ////////////////////////////////////////////////////////////// + +template +LowPassFilter::LowPassFilter(float gain) : + Filter(), + _gain(gain), + _base_value_set(false) +{ + // bounds checking on _gain + if( _gain > 1.0) { + _gain = 1.0; + }else if( _gain < 0.0 ) { + _gain = 0.0; + } +}; + +// Public Methods ////////////////////////////////////////////////////////////// + +template +T LowPassFilter::apply(T sample) +{ + // initailise _base_value if required + if( ! _base_value_set ) { + _base_value = sample; + _base_value_set = true; + } + + // do the filtering + _base_value = _gain * (float)sample + (1.0 - _gain) * _base_value; + + // return the value. Should be no need to check limits + return (T)_base_value; +} + +#endif \ No newline at end of file diff --git a/libraries/Filter/examples/Filter/Filter.pde b/libraries/Filter/examples/Filter/Filter.pde index 295389f377..3ee1094479 100644 --- a/libraries/Filter/examples/Filter/Filter.pde +++ b/libraries/Filter/examples/Filter/Filter.pde @@ -21,6 +21,8 @@ int16_t rangevalue[] = {31000, 31000, 50, 55, 60, 55, 10, 0, 31000}; ModeFilterInt16_Size5 mfilter(2); // buffer of 5 values, result will be from buffer element 2 (ie. the 3rd element which is the middle) //AverageFilterInt16_Size5 mfilter; // buffer of 5 values. result will be average of these 5 +AverageFilterUInt16_Size4 _temp_filter; + // Function to print contents of a filter // we need to ues FilterWithBuffer class because we want to access the individual elements void printFilter(FilterWithBufferInt16_Size5& filter) @@ -44,13 +46,38 @@ void setup() delay(500); } +// Read Raw Temperature values +void ReadTemp() +{ + static uint8_t next_num = 0; + static int32_t RawTemp = 0; + uint8_t buf[2]; + uint16_t _temp_sensor; + + next_num++; + buf[0] = next_num; //next_num; + buf[1] = 0xFF; + + _temp_sensor = buf[0]; + _temp_sensor = (_temp_sensor << 8) | buf[1]; + + RawTemp = _temp_filter.apply(_temp_sensor); + + Serial.printf("RT: %ld\n",RawTemp); +} + //Main loop where the action takes place void loop() { uint8_t i = 0; int16_t filtered_value; - while( i < 9 ) { + int16_t j; + + for(j=0; j<0xFF; j++ ) { + ReadTemp(); + } + /*while( i < 9 ) { // output to user Serial.printf("applying: %d\n",(int)rangevalue[i]); @@ -68,8 +95,8 @@ void loop() Serial.printf("The filtered value is: %d\n\n",(int)filtered_value); i++; - } - delay(100000); + }*/ + delay(10000); } diff --git a/libraries/Filter/examples/LowPassFilter/LowPassFilter.pde b/libraries/Filter/examples/LowPassFilter/LowPassFilter.pde new file mode 100644 index 0000000000..eff3d7bdee --- /dev/null +++ b/libraries/Filter/examples/LowPassFilter/LowPassFilter.pde @@ -0,0 +1,60 @@ +/* + Example sketch to demonstrate use of LowPassFilter library. + Code by Randy Mackay. DIYDrones.com +*/ + +#include +#include +#include // ArduPilot Mega Vector/Matrix math Library +#include // Filter library +#include // LowPassFilter class (inherits from Filter class) + +//////////////////////////////////////////////////////////////////////////////// +// Serial ports +//////////////////////////////////////////////////////////////////////////////// +FastSerialPort0(Serial); // FTDI/console + +// create a global instance of the class instead of local to avoid memory fragmentation +LowPassFilterInt16 low_pass_filter(0.02); // simple low pass filter which applies 2% of new data to old data + +// setup routine +void setup() +{ + // Open up a serial connection + Serial.begin(115200); + + // introduction + Serial.printf("ArduPilot LowPassFilter test ver 1.0\n\n"); + + // Wait for the serial connection + delay(500); +} + +//Main loop where the action takes place +void loop() +{ + int16_t i; + int16_t new_value; + int16_t filtered_value; + + // reset value to 100. If not reset the filter will start at the first value entered + low_pass_filter.reset(100); + + for( i=0; i<210; i++ ) { + + // new data value + new_value = 105; + + // output to user + Serial.printf("applying: %d",(int)new_value); + + // apply new value and retrieved filtered result + filtered_value = low_pass_filter.apply(new_value); + + // display results + Serial.printf("\toutput: %d\n\n",(int)filtered_value); + } + delay(10000); +} + + diff --git a/libraries/Filter/examples/LowPassFilter/Makefile b/libraries/Filter/examples/LowPassFilter/Makefile new file mode 100644 index 0000000000..d1f40fd90f --- /dev/null +++ b/libraries/Filter/examples/LowPassFilter/Makefile @@ -0,0 +1 @@ +include ../../../AP_Common/Arduino.mk From b5dbdab81e2f144eb7f05a5de6a84592bdf31a7f Mon Sep 17 00:00:00 2001 From: rmackay9 Date: Sun, 25 Mar 2012 21:13:31 +0900 Subject: [PATCH 17/78] APM_RC - moved Force_Out0_Out1, Force_Out2_Out3 and Force_Out6_Out6 to APM_RC parent class because it's already implemented in the APM1 and APM2 child classes anyway --- libraries/APM_RC/APM_RC.h | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/APM_RC/APM_RC.h b/libraries/APM_RC/APM_RC.h index 7bfea34fd8..36a467e302 100644 --- a/libraries/APM_RC/APM_RC.h +++ b/libraries/APM_RC/APM_RC.h @@ -44,6 +44,10 @@ class APM_RC_Class virtual void enable_out(uint8_t) = 0; virtual void disable_out(uint8_t) = 0; + virtual void Force_Out0_Out1(void) = 0; + virtual void Force_Out2_Out3(void) = 0; + virtual void Force_Out6_Out7(void) = 0; + protected: uint16_t _map_speed(uint16_t speed_hz) { return 2000000UL / speed_hz; } From 12e9d1d6fc0b7b4785a2fd683b3bec0db886da13 Mon Sep 17 00:00:00 2001 From: Michael Oborne Date: Mon, 26 Mar 2012 18:21:49 +0800 Subject: [PATCH 18/78] APM Planner 1.1.57 fix antenna tracker issue with saved settings add pretyping to config list add rawlogs modify mavlink log graph interface. 2 x yaxis & roll,pitch,yaw now in degs update dataflash log format - thanks randy update google earth interface refresh to 0.3 sec --- .../Antenna/Tracker.Designer.cs | 10 +- .../Controls/CustomMessageBox.cs | 1 + .../GCSViews/Configuration.Designer.cs | 30 +-- .../GCSViews/Configuration.cs | 32 +++ Tools/ArdupilotMegaPlanner/MAVLink.cs | 10 + Tools/ArdupilotMegaPlanner/MainV2.cs | 11 ++ Tools/ArdupilotMegaPlanner/MavlinkLog.cs | 186 +++++++++++++++--- .../Properties/AssemblyInfo.cs | 2 +- Tools/ArdupilotMegaPlanner/ThemeManager.cs | 5 + .../bin/Release/ArdupilotMegaPlanner.pdb | Bin 1017344 -> 1021440 bytes .../bin/Release/dataflashlog.xml | 184 +++++++++++++++++ .../bin/Release/m3u/networklink.kml | 4 +- Tools/ArdupilotMegaPlanner/dataflashlog.xml | 184 +++++++++++++++++ Tools/ArdupilotMegaPlanner/georefimage.cs | 14 +- .../ArdupilotMegaPlanner/m3u/networklink.kml | 4 +- 15 files changed, 624 insertions(+), 53 deletions(-) diff --git a/Tools/ArdupilotMegaPlanner/Antenna/Tracker.Designer.cs b/Tools/ArdupilotMegaPlanner/Antenna/Tracker.Designer.cs index 0c34115461..f748e44462 100644 --- a/Tools/ArdupilotMegaPlanner/Antenna/Tracker.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/Antenna/Tracker.Designer.cs @@ -110,8 +110,8 @@ // TRK_pantrim // this.TRK_pantrim.Location = new System.Drawing.Point(153, 81); - this.TRK_pantrim.Maximum = 90; - this.TRK_pantrim.Minimum = -90; + this.TRK_pantrim.Maximum = 360; + this.TRK_pantrim.Minimum = -360; this.TRK_pantrim.Name = "TRK_pantrim"; this.TRK_pantrim.Size = new System.Drawing.Size(375, 45); this.TRK_pantrim.TabIndex = 5; @@ -124,7 +124,7 @@ this.TXT_panrange.Name = "TXT_panrange"; this.TXT_panrange.Size = new System.Drawing.Size(64, 20); this.TXT_panrange.TabIndex = 4; - this.TXT_panrange.Text = "180"; + this.TXT_panrange.Text = "360"; this.TXT_panrange.TextChanged += new System.EventHandler(this.TXT_panrange_TextChanged); // // label3 @@ -175,8 +175,8 @@ // TRK_tilttrim // this.TRK_tilttrim.Location = new System.Drawing.Point(153, 157); - this.TRK_tilttrim.Maximum = 45; - this.TRK_tilttrim.Minimum = -45; + this.TRK_tilttrim.Maximum = 180; + this.TRK_tilttrim.Minimum = -180; this.TRK_tilttrim.Name = "TRK_tilttrim"; this.TRK_tilttrim.Size = new System.Drawing.Size(375, 45); this.TRK_tilttrim.TabIndex = 7; diff --git a/Tools/ArdupilotMegaPlanner/Controls/CustomMessageBox.cs b/Tools/ArdupilotMegaPlanner/Controls/CustomMessageBox.cs index fda4573224..71b2f5f0d2 100644 --- a/Tools/ArdupilotMegaPlanner/Controls/CustomMessageBox.cs +++ b/Tools/ArdupilotMegaPlanner/Controls/CustomMessageBox.cs @@ -59,6 +59,7 @@ namespace System.Windows.Forms Width = textSize.Width + 50, Height = textSize.Height + 100, TopMost = true, + TopLevel = true }; Rectangle screenRectangle = msgBoxFrm.RectangleToScreen(msgBoxFrm.ClientRectangle); diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.Designer.cs index 23aab4e460..c95bbbd9a0 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.Designer.cs @@ -141,6 +141,8 @@ this.RLL2SRV_P = new System.Windows.Forms.NumericUpDown(); this.label52 = new System.Windows.Forms.Label(); this.TabAC = new System.Windows.Forms.TabPage(); + this.myLabel4 = new ArdupilotMega.MyLabel(); + this.myLabel3 = new ArdupilotMega.MyLabel(); this.TUNE_LOW = new System.Windows.Forms.NumericUpDown(); this.TUNE_HIGH = new System.Windows.Forms.NumericUpDown(); this.myLabel2 = new ArdupilotMega.MyLabel(); @@ -289,8 +291,6 @@ this.BUT_load = new ArdupilotMega.MyButton(); this.toolTip1 = new System.Windows.Forms.ToolTip(this.components); this.BUT_compare = new ArdupilotMega.MyButton(); - this.myLabel3 = new ArdupilotMega.MyLabel(); - this.myLabel4 = new ArdupilotMega.MyLabel(); ((System.ComponentModel.ISupportInitialize)(this.Params)).BeginInit(); this.ConfigTabs.SuspendLayout(); this.TabAP.SuspendLayout(); @@ -437,6 +437,8 @@ this.Params.RowHeadersDefaultCellStyle = dataGridViewCellStyle2; this.Params.RowHeadersVisible = false; this.Params.CellValueChanged += new System.Windows.Forms.DataGridViewCellEventHandler(this.Params_CellValueChanged); + this.Params.KeyDown += new System.Windows.Forms.KeyEventHandler(this.Params_KeyDown); + this.Params.KeyPress += new System.Windows.Forms.KeyPressEventHandler(this.Params_KeyPress); // // Command // @@ -1118,6 +1120,18 @@ resources.ApplyResources(this.TabAC, "TabAC"); this.TabAC.Name = "TabAC"; // + // myLabel4 + // + resources.ApplyResources(this.myLabel4, "myLabel4"); + this.myLabel4.Name = "myLabel4"; + this.myLabel4.resize = false; + // + // myLabel3 + // + resources.ApplyResources(this.myLabel3, "myLabel3"); + this.myLabel3.Name = "myLabel3"; + this.myLabel3.resize = false; + // // TUNE_LOW // resources.ApplyResources(this.TUNE_LOW, "TUNE_LOW"); @@ -2159,18 +2173,6 @@ this.BUT_compare.UseVisualStyleBackColor = true; this.BUT_compare.Click += new System.EventHandler(this.BUT_compare_Click); // - // myLabel3 - // - resources.ApplyResources(this.myLabel3, "myLabel3"); - this.myLabel3.Name = "myLabel3"; - this.myLabel3.resize = false; - // - // myLabel4 - // - resources.ApplyResources(this.myLabel4, "myLabel4"); - this.myLabel4.Name = "myLabel4"; - this.myLabel4.resize = false; - // // Configuration // resources.ApplyResources(this, "$this"); diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.cs index b7023440b0..853d0d4ca1 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.cs @@ -1190,13 +1190,45 @@ namespace ArdupilotMega.GCSViews BUT_load_Click(BUT_load, null); return true; } + if (Params.Focused) + { + if (keyData >= Keys.A && keyData <= Keys.Z) + { + int row = FindRowIndex(0, keyData.ToString()); + Params.FirstDisplayedScrollingRowIndex = row; + Params.ClearSelection(); + Params[1, row].Selected = true; + } + } return base.ProcessCmdKey(ref msg, keyData); } + int FindRowIndex(int col, string startswith) + { + foreach (DataGridViewRow row in Params.Rows) + { + if (row.Cells[col].Value.ToString().StartsWith(startswith)) + { + return row.Index; + } + } + return 0; + } + private void CMB_ratesensors_SelectedIndexChanged(object sender, EventArgs e) { MainV2.config[((ComboBox)sender).Name] = ((ComboBox)sender).Text; MainV2.cs.ratesensors = byte.Parse(((ComboBox)sender).Text); } + + private void Params_KeyDown(object sender, KeyEventArgs e) + { + + } + + private void Params_KeyPress(object sender, KeyPressEventArgs e) + { + + } } } \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/MAVLink.cs b/Tools/ArdupilotMegaPlanner/MAVLink.cs index 17588fa4fb..5696cf4120 100644 --- a/Tools/ArdupilotMegaPlanner/MAVLink.cs +++ b/Tools/ArdupilotMegaPlanner/MAVLink.cs @@ -101,6 +101,7 @@ namespace ArdupilotMega public DateTime lastlogread = DateTime.MinValue; public BinaryReader logplaybackfile = null; public BinaryWriter logfile = null; + public BinaryWriter rawlogfile = null; int bps1 = 0; int bps2 = 0; @@ -2009,7 +2010,11 @@ namespace ArdupilotMega System.Threading.Thread.Sleep(1); } if (BaseStream.IsOpen) + { temp[count] = (byte)BaseStream.ReadByte(); + if (rawlogfile != null) + rawlogfile.Write(temp[count]); + } } } catch (Exception e) { log.Info("MAVLink readpacket read error: " + e.Message); break; } @@ -2066,6 +2071,11 @@ namespace ArdupilotMega if (BaseStream.IsOpen) { int read = BaseStream.Read(temp, 6, length - 4); + if (rawlogfile != null) + { + rawlogfile.Write(temp, 0, read); + rawlogfile.BaseStream.Flush(); + } } } //Console.WriteLine("data " + read + " " + length + " aval " + this.BytesToRead); diff --git a/Tools/ArdupilotMegaPlanner/MainV2.cs b/Tools/ArdupilotMegaPlanner/MainV2.cs index 511d6d2d36..4d70c588eb 100644 --- a/Tools/ArdupilotMegaPlanner/MainV2.cs +++ b/Tools/ArdupilotMegaPlanner/MainV2.cs @@ -456,6 +456,9 @@ namespace ArdupilotMega if (comPort.logfile != null) comPort.logfile.Close(); + if (comPort.rawlogfile != null) + comPort.rawlogfile.Close(); + comPort.BaseStream.DtrEnable = false; comPort.Close(); } @@ -502,10 +505,15 @@ namespace ArdupilotMega if (comPort.logfile != null) comPort.logfile.Close(); + + if (comPort.rawlogfile != null) + comPort.rawlogfile.Close(); try { Directory.CreateDirectory(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs"); comPort.logfile = new BinaryWriter(File.Open(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs" + Path.DirectorySeparatorChar + DateTime.Now.ToString("yyyy-MM-dd HH-mm-ss") + ".tlog", FileMode.CreateNew, FileAccess.ReadWrite, FileShare.Read)); + + comPort.rawlogfile = new BinaryWriter(File.Open(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs" + Path.DirectorySeparatorChar + DateTime.Now.ToString("yyyy-MM-dd HH-mm-ss") + ".rlog", FileMode.CreateNew, FileAccess.ReadWrite, FileShare.Read)); } catch { CustomMessageBox.Show("Failed to create log - wont log this session"); } // soft fail @@ -1885,6 +1893,9 @@ namespace ArdupilotMega comPort.logreadmode = false; if (comPort.logfile != null) comPort.logfile.Close(); + + if (comPort.rawlogfile != null) + comPort.rawlogfile.Close(); } catch { } diff --git a/Tools/ArdupilotMegaPlanner/MavlinkLog.cs b/Tools/ArdupilotMegaPlanner/MavlinkLog.cs index 36e972eff2..b38d69a432 100644 --- a/Tools/ArdupilotMegaPlanner/MavlinkLog.cs +++ b/Tools/ArdupilotMegaPlanner/MavlinkLog.cs @@ -36,9 +36,15 @@ namespace ArdupilotMega List selection = new List(); + Hashtable data = new Hashtable(); + public MavlinkLog() { InitializeComponent(); + + zg1.GraphPane.YAxis.Title.IsVisible = false; + zg1.GraphPane.Title.IsVisible = true; + zg1.GraphPane.Title.Text = "Mavlink Log Graph"; } private void writeKML(string filename) @@ -549,7 +555,7 @@ namespace ArdupilotMega zg1.GraphPane.CurveList.Clear(); - GetLogFileData(zg1, openFileDialog1.FileName, fields); + //GetLogFileData(zg1, openFileDialog1.FileName, fields); try { @@ -587,19 +593,10 @@ namespace ArdupilotMega Random rand = new Random(); - int step = 0; - - // setup display and arrays + // setup arrays for (int a = 0; a < lookforfields.Count; a++) { lists[a] = new PointPairList(); - - LineItem myCurve; - - int colorvalue = ColourValues[step % ColourValues.Length]; - step++; - - myCurve = zg1.GraphPane.AddCurve(lookforfields[a].Replace("__mavlink_", ""), lists[a], Color.FromArgb(unchecked( colorvalue + (int)0xff000000)), SymbolType.None); } { @@ -694,6 +691,35 @@ namespace ArdupilotMega progressBar1.Value = 100; } + + int step = 0; + + zg1.GraphPane.AddY2Axis("PWM"); + zg1.GraphPane.AddY2Axis("Angle"); + + //zg1.GraphPane.XAxis.Title.Text = "Seconds"; + + // setup display and arrays + for (int a = 0; a < lookforfields.Count; a++) + { + LineItem myCurve; + + int colorvalue = ColourValues[step % ColourValues.Length]; + step++; + + myCurve = zg1.GraphPane.AddCurve(lookforfields[a].Replace("__mavlink_", ""), lists[a], Color.FromArgb(unchecked(colorvalue + (int)0xff000000)), SymbolType.None); + + double xMin, xMax, yMin, yMax; + + myCurve.GetRange(out xMin, out xMax, out yMin, out yMax, true, false, zg1.GraphPane); + + if (yMin > 900 && yMax < 2100) + { + myCurve.IsY2Axis = true; + myCurve.YAxisIndex = 0; + zg1.GraphPane.Y2Axis.IsVisible = true; + } + } } private List GetLogFileValidFields(string logfile) @@ -701,23 +727,36 @@ namespace ArdupilotMega Form selectform = SelectDataToGraphForm(); Hashtable seenIt = new Hashtable(); + + selection = new List(); + + List options = new List(); + + this.data.Clear(); + + colorStep = 0; { - MAVLink mine = new MAVLink(); - mine.logplaybackfile = new BinaryReader(File.Open(logfile, FileMode.Open, FileAccess.Read, FileShare.Read)); - mine.logreadmode = true; + MAVLink MavlinkInterface = new MAVLink(); + MavlinkInterface.logplaybackfile = new BinaryReader(File.Open(logfile, FileMode.Open, FileAccess.Read, FileShare.Read)); + MavlinkInterface.logreadmode = true; - mine.packets.Initialize(); // clear + MavlinkInterface.packets.Initialize(); // clear - while (mine.logplaybackfile.BaseStream.Position < mine.logplaybackfile.BaseStream.Length) + // to get first packet time + MavlinkInterface.readPacket(); + + DateTime startlogtime = MavlinkInterface.lastlogread; + + while (MavlinkInterface.logplaybackfile.BaseStream.Position < MavlinkInterface.logplaybackfile.BaseStream.Length) { - progressBar1.Value = (int)((float)mine.logplaybackfile.BaseStream.Position / (float)mine.logplaybackfile.BaseStream.Length * 100.0f); - this.Refresh(); + progressBar1.Value = (int)((float)MavlinkInterface.logplaybackfile.BaseStream.Position / (float)MavlinkInterface.logplaybackfile.BaseStream.Length * 100.0f); + progressBar1.Refresh(); - byte[] packet = mine.readPacket(); + byte[] packet = MavlinkInterface.readPacket(); - object data = mine.DebugPacket(packet, false); + object data = MavlinkInterface.DebugPacket(packet, false); Type test = data.GetType(); @@ -735,18 +774,59 @@ namespace ArdupilotMega { if (!seenIt.ContainsKey(field.DeclaringType.Name + "." + field.Name)) { - AddDataOption(selectform, field.Name + " " + field.DeclaringType.Name); seenIt[field.DeclaringType.Name + "." + field.Name] = 1; + //AddDataOption(selectform, field.Name + " " + field.DeclaringType.Name); + options.Add(field.DeclaringType.Name + "." + field.Name); + } + + if (!this.data.ContainsKey(field.Name + " " + field.DeclaringType.Name)) + this.data[field.Name + " " + field.DeclaringType.Name] = new PointPairList(); + + PointPairList list = ((PointPairList)this.data[field.Name + " " + field.DeclaringType.Name]); + + object value = fieldValue; + // seconds scale + double time = (MavlinkInterface.lastlogread - startlogtime).TotalMilliseconds / 1000.0; + + if (value.GetType() == typeof(Single)) + { + list.Add(time, (Single)field.GetValue(data)); + } + else if (value.GetType() == typeof(short)) + { + list.Add(time, (short)field.GetValue(data)); + } + else if (value.GetType() == typeof(ushort)) + { + list.Add(time, (ushort)field.GetValue(data)); + } + else if (value.GetType() == typeof(byte)) + { + list.Add(time, (byte)field.GetValue(data)); + } + else if (value.GetType() == typeof(Int32)) + { + list.Add(time, (Int32)field.GetValue(data)); } } } } - mine.logreadmode = false; - mine.logplaybackfile.Close(); - mine.logplaybackfile = null; + MavlinkInterface.logreadmode = false; + MavlinkInterface.logplaybackfile.Close(); + MavlinkInterface.logplaybackfile = null; - selectform.ShowDialog(); + // custom sort based on packet name + //options.Sort(delegate(string c1, string c2) { return String.Compare(c1.Substring(0,c1.IndexOf('.')),c2.Substring(0,c2.IndexOf('.')));}); + + // this needs sorting + foreach (string item in options) + { + var items = item.Split('.'); + AddDataOption(selectform, items[1] + " " + items[0]); + } + + selectform.Show(); progressBar1.Value = 100; @@ -784,16 +864,69 @@ namespace ArdupilotMega } } + int colorStep = 0; + void chk_box_CheckedChanged(object sender, EventArgs e) { if (((CheckBox)sender).Checked) { selection.Add(((CheckBox)sender).Name); + + LineItem myCurve; + + int colorvalue = ColourValues[colorStep % ColourValues.Length]; + colorStep++; + + myCurve = zg1.GraphPane.AddCurve(((CheckBox)sender).Name.Replace("__mavlink_", ""), (PointPairList)data[((CheckBox)sender).Name], Color.FromArgb(unchecked(colorvalue + (int)0xff000000)), SymbolType.None); + + myCurve.Tag = ((CheckBox)sender).Name; + + if (myCurve.Tag.ToString() == "roll __mavlink_attitude_t" || + myCurve.Tag.ToString() == "pitch __mavlink_attitude_t" || + myCurve.Tag.ToString() == "yaw __mavlink_attitude_t") + { + PointPairList ppl = new PointPairList((PointPairList)data[((CheckBox)sender).Name]); + for (int a = 0; a < ppl.Count; a++) + { + ppl[a].Y = ppl[a].Y * (180.0 / Math.PI); + } + + myCurve.Points = ppl; + } + + double xMin, xMax, yMin, yMax; + + myCurve.GetRange(out xMin, out xMax, out yMin, out yMax, true, false, zg1.GraphPane); + + if (yMin > 900 && yMax < 2100 && yMin < 2100) + { + myCurve.IsY2Axis = true; + myCurve.YAxisIndex = 0; + zg1.GraphPane.Y2Axis.IsVisible = true; + } } else { selection.Remove(((CheckBox)sender).Name); + foreach (var item in zg1.GraphPane.CurveList) + { + if (item.Tag == ((CheckBox)sender).Name) + { + zg1.GraphPane.CurveList.Remove(item); + break; + } + } } + + try + { + // fix new line types + ThemeManager.ApplyThemeTo(this); + + zg1.Invalidate(); + zg1.AxisChange(); + } + catch { } } int x = 10; @@ -806,7 +939,8 @@ namespace ArdupilotMega Name = "select", Width = 50, Height = 500, - Text = "Graph This" + Text = "Graph This", + TopLevel = true }; x = 10; diff --git a/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs b/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs index 690be35904..3e8fce088f 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.56")] +[assembly: AssemblyFileVersion("1.1.57")] [assembly: NeutralResourcesLanguageAttribute("")] diff --git a/Tools/ArdupilotMegaPlanner/ThemeManager.cs b/Tools/ArdupilotMegaPlanner/ThemeManager.cs index 47bf8b5c24..75bbc0804c 100644 --- a/Tools/ArdupilotMegaPlanner/ThemeManager.cs +++ b/Tools/ArdupilotMegaPlanner/ThemeManager.cs @@ -123,12 +123,17 @@ namespace ArdupilotMega zg1.GraphPane.XAxis.MinorTic.Color = Color.White; zg1.GraphPane.YAxis.MajorTic.Color = Color.White; zg1.GraphPane.YAxis.MinorTic.Color = Color.White; + zg1.GraphPane.Y2Axis.MajorTic.Color = Color.White; + zg1.GraphPane.Y2Axis.MinorTic.Color = Color.White; zg1.GraphPane.XAxis.MajorGrid.Color = Color.White; zg1.GraphPane.YAxis.MajorGrid.Color = Color.White; + zg1.GraphPane.Y2Axis.MajorGrid.Color = Color.White; zg1.GraphPane.YAxis.Scale.FontSpec.FontColor = Color.White; zg1.GraphPane.YAxis.Title.FontSpec.FontColor = Color.White; + zg1.GraphPane.Y2Axis.Title.FontSpec.FontColor = Color.White; + zg1.GraphPane.Y2Axis.Scale.FontSpec.FontColor = Color.White; zg1.GraphPane.XAxis.Scale.FontSpec.FontColor = Color.White; zg1.GraphPane.XAxis.Title.FontSpec.FontColor = Color.White; diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.pdb b/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.pdb index ed5172ddaceebace73ddca6848e1bc7667b3d865..b28bbbb2ad332e74f6b441ebf93765debfff416d 100644 GIT binary patch delta 235089 zcmZ^s2YeMp_po<1$xSW#*)`+Sz=;1IFwQhs67hRwOHie4VED%G|2U>UJAHj`K%J>- zTetm|pjO-RVUuzy9`18`UQ~3G7k{Yz<7_?qlYrd4U8~ur>Q-WN+xN}QZHJoSMUKT* zoWE<-p;8TB=)a_Ot1<=I8Bsj^!=V#CIeqBAv*V}ulD@vt<%t5>)Tr>BWtVbZk1X{> z#qjvKNyn-Wuw=X1g|&Nn&dG77ylr}n_~?s2*3Go?v#f3L{cS%ys5Y&ux4dhhP8?D^ zaDT|f^GY`y85X+#>yK+Fy@Mltcw|^|-mQ^gBh-ompC;?4Mu&y2xb7<^y;scpb%t&@FDx`S5PLaB z@LRZ696yYkfjfh{gsV$=AHwy*O~7r&y@cC^yM()gJ7yZjapJ#?`-$V5xSw(T0}SH? zVejAua6Aw<2sZ+kjawRE^i70a$Nhsli~k(%Uyk2}@8Jw`t#BqT z02hcmPxuAg`?wEq6$tBq>yCQ_Hw3o?w-om@ZW->w;8BM05z5Q)e1yA*`xtjgjtT!5 zcM122IKn=~l?;OTKf^WWcogmg?lS%>xb_~y$iO{{8;M&$*dp9|9kElbC_3*Hy8K{X zxh?7ox^eM+cL$ZzFF&LXrRbw}meKuu7^muexD;i<^UZPlREVFJTy8a(ulm?bN_9 zsx%~b^$a6~I1`&MPcM^u>0!edO`gu-qBx#{Yunl|o-0j^c*7{2U>Kn>R9G9sND4EI zmAKm+f8EY7(%NGc;WPm5!Qa9(!}t#OeoMos_R#&(_Kgfro0hPJV&q3?mb_tC(RFEp8aCLorL7|8G+h!|*os53!GrS2T=rl?syC zl7{g+?hy7A$LS9c_DosB_!W1AJe0!@YtaMBcnxDJZUx64$~O`>2aC9kJJ=ds8nZOT zsEAc{?ts6hVI)#VdpI78^<79`c=;$*AvX&1EMJxGiyOu9RT`!d zCoe;R=HdpoB6GM$DD_pc-;~UDYfDCPYcSp4a78%TP@Mm-eFZEE7fM5p!MVRJ!HhdJ zu=CSzv{S``dSeNvmZztzYOg|qM^wD?aigN=^xj?G6rI*yg_in5-)oWfPu=DRZ%hvV zZbk8X`~Mj_{aAp0w7sgMkG5Ae;>A*^RwMSyWc6#*$6Gw(YNA6RvinxF?O_P! zswz5SoK_B@e-5RQT;0FoZU>95G@j^+%wJcm!`1CJa>|#YE7l{rB6D=R;I+G&tDIAL z&|p!PE-1><4gC|AuIB2t%YUnq=t@@<-8D(NbtlzW2XEQ6FJ zyf#%=>!MmWf4ctm!De zlhM`H{kL0{*F;xFUC|YpzpjiPuI|XMnjaEf8C67AWR5P~pI?K(Lgm++JiT*OhANvY zLx7t?;(#JIB?TE8Bn6TApG{^zS9jyD=Wg$m=TmlI{!=Wf_r0IkA>L(M>g0C-ue*6`3oOq6Evt=zl&LU)>}s zuKzSdl8|v%bVcT`E90}P+j8@{T+x+rTXaR{uPbA_tGn~%<2tOnii?*C&<)(xyPq{K z$iyfKd|qC^+g&w|msO9e^Ine~x8x+U8WNo<4RyC382rH=6kcW$SFw0}aZ?m!h7rZ( zRdubN7_m%3uFk1NFIt8!lauI(%s6QO0M_|E})tkm@TXVObZ5Ztb-Db!FOfb-%hf z>s!&4=}>esZ!g^+Q`*=^U#bpL{An~q9-!{^UK=E)s3ILdExa$aUo%%_+6S_)tlOv6`PybvU@K-B092?6CIKHpI8>UuI^LW z)w_$XEQCc@Wd6Fc`gC<4x?8oY=*p^8bVcUq+SAJ*RyVG4wZ5B%in6S_L|J713CpU= z)g3-3YNY7Os!Mb?HPbgKlM`Zq)lSR0z``-Q$4~woW&P7*b{<=HT3w7^& zR#J(sED=RlWR9*5?x#}XWs&VB{AsH$XGK{S-=bWulCIWIwa#t%>zRWRzObkr{vGr` zp)9@JG|H~8(@u0{NhWEC%wJd5ny&8VyNybVuB<_=^C9!sm1Q8hy3Hf1QoJl&-H2P~ z9JPA9ENCTSTzx(85!JYyEJR(M$`hVCDv8TNRdhs_wLE>&s{ZOr6|cYQuO_JLy5|6O zCX`E8Pq#XOhC)pbxD^_$9~!7CC&U|}1dIqYJf`6>e&M(+&Q?@LoQ?=KBlVhrs$PWD zuKYr9U2!>i*Io^&t0FP?f?p;lIr>JB{&L>WrRH))dUPeH(4$ z+qiAZRF8%uLn^xL;vs5&Rp2||`!F3|- znu-`kmd25#^kcg5Fx9ZM(-4HXZQO&%N8ixvngo^6TZXALlcw3VA)w5v;VRr|1!WA> zd!G!5)HQ~y9VV47a(zb>x>!Y2#teP?Arulvs0}7{Y$;qGp~B7gkLa5tR7;auv;vbm z1$jafEbC&LF{s0V*@*u+lD8>awO1w?y*ZMAHSKksQR=3LTQ8n}QgqU2)i&mT4OBA! zPfDOp=pGcKH;g9tt<&?q9Ifi8x{DCGznaSMobRhFgEDFj$r(3MDlWikl(y8K=pxtS zUQ#J~# z-SvcCo>-k|A7AhV#_BZtIAv^5tRBp)8 z6ICo3&41GyeV=B|xXDxsiweh9yXy-RRfP!u#3toT8=a*)O;^#n>?9RVDm5pm*cgA6 z>>=YUi}YIO%AABncGuI;y6;@$$7PSrnZ#uP=Mp>ZuJ@vX<~btVm);PhQpsVK*58xp z6Ww)Oj)i762IN>##|#XKNl1)fbT|AnH0d$Bi*VHX5^#*5O7u zWMn2ZKi?avn@(0CoGt%W(S*3;7>SQUeHmmJdHwCim!21CCo)+jM7-?;OQA|z!Fwm$ zg#z~%Dszlg^jJ$vO|i7%raVyeaTBwxs^s4ARpd}TaH>j*h#YFC zB2A8>(L=ACsuJ|p87fpCovKou8K9>ATVf^?GkvH|nx@j6QM;xdGmY^)1wqT9O6Q*T z#>M0mc@lb!pz^~C8!p&V$)Bz|P-VqtP`)~puk&!F z|2pH1i;F7G4KMn~3e*U+#yF|JBKUjh2{R~FFTH#QS?Q(6ob?LwZQokkciZ-z!>1Ex z(q2zGsYw1jRx0Y8H#(-5pYdRumhs2}pqEZTOtS6Hd7A~NSTj#eeQKtv5Xwz@&ow7C zUGr{etd5+eA|l)%$)=p3x6XLglc0L*+taB0@w2G>-a6uOj+fcT44={3S2Hj~hs>c} z);zAF;-bP0V=GpIaT$Y0*yR?ZlwppPW~mC^DQ>XNkjf98PTYBORJiV#tD?ML7fAC( zIwO}Mt+!s1tGXo1d?E8=bEBGNhX+cKD8EBCtiScpIi78wSC6?H8eN_m35fWb2tL$B z)fG!QC0l*;g=q|){e289ee`lE;MFWuZMeOzaZj4+oOG&mJ$`q@Mx0-LPC9F(eNv-M zR!+xp!&_&M&T5sJlWCp(AZKnxJc;A#$=OR0zpqZI6A&9DsrJIu~TsyQk|H+%x?7@a*y#s+KP!Ss+1n95voi!&!P#z;aNoE(Y) zNxA##y$b?ul~&~BV|vPKj!F_Lcu_euM^y-tqV|=p5^eRNzPi|4l@M2tbkm5~9?id; zh|<&y#%NE-MO(~>Qr!)XTvgf|7$kkBubw@ZLGu8Sn-cjXIq5yB&`!j3DSS>ybX+21 zU_(^qp|aRfky?{ktgrrlE;S*&sjuExFEBE$2io-{H)tPlv}M?1oI$10JTklmm1I=P zqH^Bvob+&11_Tv}4x*!TxO|?fu8%%u23qx(M%x@F{FO0wHl_Y#=Ce^sE^a z{Vv8Ss;*dCNouH{ZQD{4{cPKog7?$11`Coh_S1WNd7{0dFU3MhdS8!)EXH=sS0N?) z`PJW~tgNx^a;O76VWEnwI&OSU_PDW=tp0VFJlr7<&ya^rP8P+4CHMWrgcH2(0;->F zyJzWSK4NUfcE5CDxVGD`(00j?zwP$3Z8tfFhn_@kL*(Y;?zi23mhHx`L1ii`@u>82 zR9xHbXXqmbij;{vk4_FcCOQ-Sk`bfsr!!N$(LrLo{cOt=BPH>9s)B8qQi5B=ZcX@^ z35A&u3+|`KWO<`&&O>|ySBIdBekw9P^z*CP?3}DIlXS{pvqiTDN4xWmA-qi#_tyYJ zXfn}0qme#zs0?#mtk$rX@5#hjgOfN-ChF~tSsypL7*teueL^Lr-ao3kL-}={1<7wH zb>aRRavo!nV{jRNgqGGZ_wRu+z}+t^?0_=j`OEw}VDO0l5!w+Yza7hB4dnL` zbbfV;B_oYgh<}3P$B(vbJ{;ZgxVp%ra_m|XeX;reI$}XcLY!2=9#mQqbjwi@BbPC@ zzh0Z+N!RNxnx6mZ{dZ(>%WtO*>u)0(W9Ve3F_!<~&Z{>_{wV6A>WZZ?B+dZccOlE1 z0eW^k7f$1^gapRdK=m-LGvXaiYLX*qjRA(Pbup-vzI8DuP@i9@lEUoEW!EI@=s)fS z#s)VgBN0fo9Z zUc|a)uR@dBSHDU}KB-FP)*}(AlT;|(y&;rg_~y_5$TG-ijGuZT2|Kgg-t`^EpAL_~ zhu|gH3Vs0@Wqd!ww(xh@4w|%Ddl(OCP+uk31*Rz;kay*v9Rb~72J8X*z@CtWw$TeR z1slB~V~Igc_@01FP`+i5@yYihq&xVI!v63S90)JKOeh;l9)(}SA@Bxd0`>i>at&h` z2mcZ<90pSrqhN7321=)*%6(CA9E^qIVR<+KR)rH`GGtNZYYr#F4EPuv2&E>6IR4Ra z8sQo~4mag;FoT0Va29+Gk|*CWI0t?W=fNM~0(cuf0sn#6fUhXMcrlEEPr+EY6xN4N z!!~dk>+xEMYUSHLxJD_jS6!}ahjxDlR(o8gD>1^5}< z3S~RZcIaVTd>O_-`n)d@?uMP&&tXeQ&+zqz*Wf_-B^(aFlC~bt!Pjsm z{01(7-@_&F2bz5ltKnbqb2HO2CT>w0zu_O{_{YHi;?IG1;R5(4d>Y<^&%uA-Mo3rm zZH0kwH_Q#<;4lXscol}gUttlb7%W0z5m+2X!Z26~G7|f0!AMvSinXUfvG%U86ybef zX*dX$fx}=d919cSlo0B_90&6VC=Z{6NpK6S40pmR@Ksn99)UIB8OR9h`w-TGS0Q&3 zeBVQ^>wLdKF136Ndj^XTUr{I-i-F8fzC_6A?@RLzVPVEWCjwf)UXW4A_b6-$N5R(c zG1vy?LIx|}Vkikd2RqCRxGMM>ZgWd9GFH^6ZCO1i%uTW)TdMjg2G$Z39 z$SXnaJNX#mnFS}TP_ZU=M3$mf;!%R#QF{lyz2#7Si16HDgku=Sa2Nr(3ig$T*)Rce zedSAnV<1D9l}&~$gLR{iAi5iVp#r_a0=n8;WS9cwc^onbB*Z) z&~q&wb9m0-`)~$w`hzhGV%C_E;rkKJfxp0c5c9PX#7vDv_-QO-F{JK|Cn0reEP>tN z({K=64zp#zUcmvGFjm3YP(y^q8u%Ps3pYV&pe=Ac{udnoOK_tyW?zNKd}F9tWWMPT znQtN72LA&Wz$0)cd>ih9=j(H@n*+HB-U~0o{ZRHNz5@S*a$?+#v4TR_#M??u8gVLVIVHx-~tN>3yS!=ulQz6&E)~etPrD%`;9PAC> zgG1p3I1zq;-fSqDnF~L{KM#Ham(ahB&p2ReFfQu|t-9yhH+7Wp6*VKj@;IqI`B7Vz z&0T|%$1kDS9J-dxeGSFtzJvZY_dR}poBI*J*xXOh-{$b=`o!pNArPax4aMkwflLCj z8`PH%e}{@pNudJZU-;?2#^10VG)#LDp`a`xOgIDvLhR7Ei=LPQ^Stk6=!FMiQM0n) zdy|7u0#3tXkeakk^f8niQ)(kZU-%DC6xKbb9?xZLb#4)%r^Z96 zwFD@&mI$S%mV;7j72yadg&GNy@UsZ9{9|Ah{8L~xC@on7J|`Dzbva;eHn2(GHkb;T zLam5WYYp+|Iew;0qp@VZt`2!#CFaWfZQo&11$U^rpmUUP`EjqtCx;ziAnXLgU}qQ( zyTY=t8x&LN2`fS=gcPbb{#s6W9fwU|f5Ovc7#YApPXbsX`TE1ba5#JvW<&1B`efW1 z4yQs%cqSZ$e;;Hi$JfFMPlv1V_ke35r8PD{xlWOcl6fosDkvr12w#Bv z;8u7LZiDZ@Y+S$70rOx<$YRu&1P{Rm@J-klN`_m&xA14c z<4_isCm?&Tjnj~e8RIN`6TS=If$zch;Ca(1<-5v(B>1hvU*QKjbB&5ETEY;^l56f{ zt=Fhea*J_4s~A^Y#kdA46m~$NG;SYmIIgx)l53@s=#?~@a6!|^h%@RHT>0Fgp!RJi zRdBbe87H|;xcnHilWK>QudfZszg zXsX&b1m1*hcNT;G1^)|>7VzzXzrlm>zwj;i2V{Y2`~^RPH-FCk$H#)w3iulSi{NLd zxL!1{qhMGGdLfGtgDJ;10Tzd=VHjlAFu3CP{TD_;22O(}_Ay2o(J&dtz_w7Dm+o$G zE#aeA8gaQC&}}TiOqhUw87v1eGAn#LtbqRwSP6dQgj20XW&A(Ds?emF09N5uZN;17c9*Pe+81L?-+at z7GsxOF|M6$dy?Y>TrBp}7`F&lAJ+g^8`qk8HuRfoRQ23PjdEOcmg9mmj*G`~To=Z1 z4Ht)MoRNcjh_KG0Zj?9LaNNl`ZtEA`n&XcDqf>>8_XuMSE)^%)Xv9qbu`#)kTM2Vc zF-n%>5<1D+Eg~JG0GrFQLc{v_IFeu4qRYW!C8cV__#)9(IOezFlA%ST5}EaCiyqZ|&iq0AOzpv(?qVLLb;u7wlfE|?Qw%;6Hq;A+(uMHpo)&CA-XimFvFs>EQ1X3wB%rrhCc zrmrRyN!0URWT(gH1kbFd*S)A}1f$dpSnb}bDmxFUztC5<@@(`PIti{$v%f+Ut((p| zc^l7`6Kd$@+f>(r2rIX7(l3e7vW7mgtza9EWP^WJ7na)O-HPJdRcCW%wY-7bRWBuZ z+f^*Mj6VOe>SM;#(A9RRRIhzfWmM29JLI|N4pr79-J4}l^nJw^m4iD}qFJJ4-lscM zYZbgP$nb=p4%C%*sY(HI&}EleL1_nlWR}!-cd4l0O=y%s5V>1539k*oCnEU_wX!o znIkLZ+z5V3mz!ud3uzY>N^OvbB750|^&+Y5cNC58Sviw+=66M_7UpIwO2IFo^a`gO z)wO7YLeWJLZAJ7QqJQ@)KT&gbVg+wQROC#c9=?x^a$se&jFXuqdij3pciFtaK)oTO zXrNl6_wM61^%8wypQ<3(ubPF}H;Kt>BYSiX<&b;!X+hlL!41Rj z%H8uUmGi`^rIKty5JP~$;eAP$IzV1uCh0%PYl{P_T!0+>+tiHFGY+Uag?V^Y6nCK5 z;%uP);()4KSQTYnL9`Q52BPUjL;b2^4kFJkM30`;|FkpfIs3H4a9rz@@kVUti?2dr zboi?(JU|R)T98svP$i$NzNEg_$uD_}*qg?xdb*)dJ714|qhRY`hTi!G{h0fOo(B0=O*tJrLq{Az z&;vnEzHWTPFUB+x^h7W{UvE01%2%D9Z(EsI1?z1ikY!1AYIlzlF5LvL@r0gmnH^z) zZ>n0(o{S9L=uK52xEG0iNrsyYQw<8vzfmN;k+eQWX}>AjqCgUHlnnGiGKC$4M^!_o zai#eFjVo2KdqY5s-g1VyN8^X~$HWmmFDP$&; z{5&K`cStl-^oDN(!gXTrK;CEFhn;OWu8z?_Vc!QcQopUDIyE3t{7`$FrvJ{s@eJME zG_W2wxpJxU4TQ;jE-RakPCU2Dcj`~xRu4P1ovJIHpynEq{+Xe=^NE5sP1Q?8&QtaBDidPn|MJ*{e6m@rjhu~ zES+?k5&Nd2EES7+8@qJ={(uCvOPBjFNHBYAP^8{*njI-m?P2HEk<%(Z;$Qa!#E~&@ zm;ULraXb7Wcsl1u8WyBme9F`{{)|d;tUOh(MeN~5yJyERec}w=Y{xLCGMw(j zEjz1Qk+Ly@<*hp#?bZ=z8Pj*`6dM_5Rpp2eoXDaSNQB*b5z-j{G{zB}gt)jR&L<*jpUMALq)%O4S42r8*vx>KLIHysMJDJ4U#+F*~DZq(1qs3XR*N z3aeyH*3j%sQYg<^r1tmd+wam9?8z-vH+zrtT9ICtY(4BfRjX!~?7~8#E_Xr;s@F|R zax4|GSLeT{8Wp6a&Xd-|q_rknS36JM);MXE(h=PQ*kX5Hg~sgjOV6!p$=5!;{Jd&s zHtnIicEYT0ooBJunzVj*($EnB#Ugcu3o4?j8zh!ok=hxJlk1|Wk@s6hhF;#zY!+;< zIa2k;3uLbiNj4m*PhVgoGc5kTDizVviRVt+`*r>I*{N;smrK<%-zQ#M;%&3yCF!&8 zt2)lZV0V1@h0_nlF}hhpVr`xN8f}^Uf$C_+56zqPfhw*{Mw_J{s#zw3OYx6XKa-Kf z+IT(hBX(mmdRU%4cmk?s1?ex=1jgyBAF<|Sn7H|o+9kumx{Jg+Yq5-u`j|o3?vcu9 zs4wJF$KyX%5=PRvXM6!}8W$Qh%BzhV%Sqq(+0czpOTyG}g__YO(oy zwtoByerhHDbG6F5&8iid1ui_t68-$=YKA$umG1n7df!ux+Sts1epMxzu=7>bT)nK9 zTva{YA^h%DcBEEEZI@LeR89As%!xXERX|mzYgf~quBi$UHPCszP-onDojy<%>g+|w z!}B)J$szjFYXvV9RMT-^GHmctz2^!ON|(jTeUqV@o-GnyBKBNIBJVgjZ6%p@Cq}sf z-|VziQJr#!4VF<~snX`IA-dLAD%E`5qP6NSYjWy!U#V*5l_C1H2(J&Zo2u;BvWvcD zUaha$kskav^KP3CL3-Rz4CPI~RiOcv&)K(r!mXG--?1+L2i;6`{ocU%TkrgiqW+6y zbq9U%yMh_!Z(Z^_0xaCKxr1(goe_0&2iwqP6k`-Op4a8_iYBP%NzGsi`1Rk79x0YmO&{?gQ z4=frRBm?1UUG5I{oLJrr2@13Pyde=ABp3RtbxK-rY>*5Rt93?NFxx?Y;A(EQ%nZC8 z@`DQH_?jFawvRLKu*P1kFI-oVtA4aJ35nEYe`IvvrdGjdGw#um*2pO(T&>f8WT++4 zLkx1`?P$|}WPD$(Z?7rBhI?X1EOQDV9a&~4Vtvo9&aZ!DM6J@Puy8y>L>6>IRgZYX zFIa|XqTH}j&Afqe{^%!_A$ql5c|&!f?!H0lF{!(YU3BrERJDkUUG7hQjZ_#rUP^`p zsx{Is_D01u@@7f2-tZIUUZbs=SW{RNR!F42_Y-xt#x7UlP0IC~lek;1HFmjr+@xIN znd99?lbS+yL$>GMRC3~#H&ulaPdF+vY|DMnHA*k7A6Q0@pA=YwvPAq$Spq1_CtY>p zpZ)A^8iJ@m1UH-nj7eEJ=~J^O>9m2Wn$wN{*4HFH+dMu0cGX30u}JvW?|hujSgV`e zDwrnz)-!LR??JywhJI1>o3Lb+BFGda`s?)UZ9%d6&Mi)2&r^TvO1Fs=Or&8My7TRV zao}&gTm&Hqre)|u{(`>|1bY!|%wT|cCWub?3w4R_zWQ3P^Y0c(Q0v7+W8)gq%Cg)0 z3$k(5(R8PU^?L6w*x-77?iUsVHCXyfrlnG4{#vhter1ngrW0IVFaHChZg?Q5xbFO` zDig8RPhVCZ>*a#@A*%n4UnxKl@_C}C{`OZ)>4c*x-B7G}gP2l+{%~$Ul-_V1)7W4e z&IU1@lKS~Os(8f5P8`Xrk|G9A&*RgayD`|5XtI1nHtP zxn8~XUsb0dTUGCJns8#=>ZQBgKy*>-+^h^A9TQ1^ea#uYv{YJ%6acIDh@e z#!VcRJ$ASiN4nw*`hp$jrw3DRiBvK!gVGB+?oakh`zMq$sBky1j7%@+j6bcDkNK0O zWd|+`-L{lL;RVfb7OD6A$*}W+e(g_IH|?!EF&M~SbQ3;W<5~KMJ&!uGrA%k;Y&n`F zn9N90vGsQ2Vv<_+7x%3)JLn(&Qp3Ef9a)IxQ8Vkjd(1PNJLJu}C##+b9rKp{t!|p; z#V)VRGPkRMPr3%_g!V;abSu*=8^G9N`)1%X8A6^n&50&ML-7DJHDDNh*U}vvfRrvi zE5K}NZp_F#7GTygy>?eo#(b^TbK+2sdEDEI+{HcEiI-ux;I91y`jNgUxy- zX4@~=tmd`NP#LlI_3H*?UfbG~(bNvRC1JK5DPx{(vIM)@Iz~_$-t-$8VZIvNf^-&bw@c%^ zr?{Cu<0jpdq!(?Mmjlb_r%ISr%x-P-UM*pAD~2aIp1eysDauSTVdp4wWJKO2`|hjT zE8o|rqRdV#kF494HAm5UzTPsA5oecer{Bm3i9ojPxI}UPxI}UPxJN0p^W-Bj)#Ql_lBwnm9MS$ zPxH0){%O9p-apOP8F9R@O4M%yqrL9Xov)Y2nX!cKv~eoVtblK0rJ|9m;tT4`-#X+j zAl1`6-mGR)bk@LS^t^bptk*84GDg@JG>7BOjwaN=o=izXWADI$E}W+so0>)=Qs3C9F{1H{d0zULhfB zwC+^ijMWPVdqZ_jd9ySDOUj!Sys{}TkS9h;?;Ona!1?lKRK(-rC%zb~G}UNbwE}U& zE0`hP-L6bu8_YX+^(vTA#n#e;L$^9{w8|uW1mO`w-7wOTai3FGFe`h?vQtGFx^pH~ z6;jcRiV5c=@>w7q^o;KuvE;U>B_31JjE-UW zE|{<;vO!G5vc4a!*H$zuL`-IDgIh+K@wbxxm`tu{H`m2@9ie9_*l@Vz__DM`KE5y4tyKVg*??U=0k(^(gK(WpMYs_Ash@z)8~Uv!VPc< zJPnt^Yfv83$&Q6(_=`}X&p_Hd*V~ipo9T6-X4&e=IH;3S%sLSnY{`?cMq<-vjU4OkuvIIA z0#%Onc9>o^p9|Lo7Y} zlIC?~I?K}|>zbR)jDvZ_>zO4?4?7b)0iWokR5RX$>zbLh^x!t0()y`XvzM$x<_7Ti zG?f|~iDu=>*r;HolC8fH0lO_c9X`{=8=KW4ISL(?`1832(BV*4QknKGJHG zCq}PpY}RlZEn8n`OakLb;F-_#pN;+UlHLRX`!_tNKGP$c_zCukU;=`wm-VMj%sSqx z?47kvsnvf&_&CK0ZzbKSDd)RrpKoGQzw^D&l-O(s@hrHk-)+jW9{$s`z&NvYMl+VT zlTbK(nH>Qya3#O2nHg#xzASAwj~25Y?>B62Mg_B*#Pcay>)#J}$XTgMMAuGwPz^Ns zuI6UHfXbhky2TDJ3-=Z*S<^qs>)gVuqrB=<$+|MCIuEtdxL}}BK94L~M&C$dQA|S= zNjLj>$2*ECI%6dt;GCOorg-hDRz@59O5uFEndW`Qs(xiOu)}J!bZU={WxPeVsPL>4~1oVV#Ab8LWlxp`iRHfC|uaEWE)TwjHn_K71RtEWO-=03n+5T*A z4)eZerK*e)I-_Gyl%Cnaj5X&~*Uxt_7kHTIJa>EOByOCWaNzMGt@Vb*-qfG~BhYjn z5MJ&`_P3%~yr=)u+Lv@nC-SomLFxm7l_J=VVBiCSKSb~{f^|K0`OXC$>?NJm83EI+ z=Uh*{v@^^0b3N~`*5x|Cv*|wlcuA`+=!nxu3qBFSZUo#H zF}oJ@r9dV~Gg%BN*FTFYZ<_ zOuVFj6Ttxl>mG=a*$u%f2wr|5#wiiJir`>x{Yy70<$Cy4 z&&uw^&Lg&`k3Q0!*q#S0>;D%!#=g1}lW@&RhWfibcu3yN(pP0iYuBnWI@|fa(VKkRbyX17v=1YKQ7vy`A9I)Tu=e!y*{GBH zu_EZRF+lb^bkbLIiiYNG=w}9+d=-ORSbRC7KTC)zh4=CGRXbqzQ0{M?pAZ#cq9n5%D`umLUNnF!2G5qlV3wH#zahch z{DN7N5qw*M&pW}g6ktU}aHWA}^@yV{*@?&_*kCI-bD&vSw;IO9|LTEe1bNsw(Cq83 zY|0K|Bxp_zblj>_2Vqtnd96+ICdo=Bs_JV|-UL;Z$3omT*)WJQ_I6aHjG|gqzcGmG zzfo?m&d=s#_Xe4zBit}4sjOG3>Pmyn4yu`+FxadR)PnQ=rHc(`aNRT5EFJLI)&P6& z&ewxY_r7E^9hYfV2u(wEDtqnZeELdMv1mOc(~O94gWT$_rk4-lk)>_+&GadWnoiVW z+nuN}C5!Q?jz@{=2K^sVr#(tkE=N2g+^Bse>RS@k4f;Q#RvkiDeTb;vY}eg}n6)Cl zagz8y^gj~)R_Ld_tp6FpiX-i1JGcLb{>-6d?P2uiIeI#xRIw<1lux`zxIy$h zHS;`y5=3_>Cr_3~F#RQyfZS9#=Oo}R>#FN(S!Qg+EyRJe=(l_9^!Xy%7&9_Gi+gR7 zLOsMcaG#UHZ;pzTOAM*HD!eA2k~MJ>-!ZWIoOGw^I&+vA9XFJy*KwT*n!mTOM#ZYD z>*XJC$9%^yvtc#2RysSivcsvBYGP~7uMM^G<6d2SxY;AszSrW$YU#wPD3|{H{301` ziB*yfp_b8JD24e{{=%#reSZROV?3*G4>u!2+YzUf8z&-~TlQbQsVb-3AE%CU(q!kp z1Ur)pe(gzM_Wl69`*zWi5zmpUd$fQk5Xilm3uDbPx<$pJ5&GU(GfH0_!9BOKkra@@2@ zIoU%-P0AWO6b-4;1DvTL@g$C`C*d~;uSa-K!sFRX?3POsuBntha>;CJeSx4L@2)|9 z?c}0)K_0l#z=hEKgZlJnF384>Hmg5iif+{YdhclNJHCnbTb6d`EZ5v!YxPCh$;wMq z?vEFkJ?vw&yTIh}Lo;)-9vU}xY}SyRc0=f%Ryq0dyU~%j63^9jFJ^05&x*W_X*Nl+ zmQJ}AlB~~-;kw5;_Kr2{X1ZB%t2;T`&cKI$ouD&WIp}7kd)CD4%+cMlGKUse@I10` zuN0fNh~w%>HpE=mdm_)~#Vl&uPoCutVr{vtY(IpqErVRF^zPIQt@WA7LZ7G^%U)#2xRbEJI})qJyv7 zDl+!T;8j~U8*j#DNGiusk(-6%4;Pw-oVT_r93DsHJZi|OFXkk1?h>aOIz8BW?wXS< zASl29=Iz02im*eRZ(96MMQ<&Q7Qa7iSbw`v(N8%E8J#k-$M&i-sN=XyF>C9D^=O`qxh%qq ze&vyJCELS{sEkL2o^MP%QdndeiIS~{$OT=eo73%?NvvO88`j^h6m&ix<(z1y#_S-u zvoZE}L*_e4Ha2QT)X`Tanl1RyV%#LNa!iU}8%)f~p*rlTD@6~O#4bbm+bjt7tEZzq{;o%{W6PjEZs$?~@DuVTB-FN1u)#iuB9%=kF@;Lfw? zi2N-l-(q)l(5-7*y%f2w&h)WwrJi*-TMp}6hnCf+T8Ea^H?R&Zt8Zu>V)fB_{A4q* z}$b-{oN+!@Z zFrvFC9YN``pHdM^>4Ke$pU6e3|0yzu49OawV;lP|Qn*73!KAS8XyIvOOsK1L`~p=< zca=|K`6nQgz?dva!2aMDG+Qy_x_aYdW`#H@)r`>%a?_kFrzO%63Gy8;tf6>IC3Bjc z<&kD|5K2Vac$kZhJ=4rUJH6;Qc|Eu(GMU7W`XwNik5N6&03y{ASk692(A$OQs9>p3 zEzv<0t;6)kt<%Xlf|9HdvK$@PDv@L2%PAiAi(lDNDL6$RPI;b&KIo@X#Zr+|teS4+ znc5fA3L&{3=r2J3Ge3P9hH00Ff}`X5pwbl;d2y`kiNai0w^YVVx3anj+}9wFW)B}O zlbSSpElV@s*1TflkLhOhIO&YbNLmWC@|{9cO0goO&+uFLxNG2!Qd#_D3~+zl7)f4z zNAH?p_89X2U-(2xz4BXb!}{BuSU)%?bti~!S(CCKw@f}DqAO>*ijz35o{UL`zCD{2 zo^PfZqVLRRrFt~hto6Wp#a#g$)YoRRUg4pUXZlI~=S;IqTxqg057(Dur=KjWPRWyf zk@&#K>pnBBQAt$n4YBqSH}M#GKRl_|%`#g(u=;mL-Wp;Y{7%ro?vHyVo==@q>kDOy zMaEk*VlpSVi@AxaE0zL#^xpYg2&c6S4psH75!n7-WPQyL9IeCau!E+)-kD3698D5O zN#Y5T_`$Dma`O86S}wLyU;m9}q=D8#Tso2!r>ttw>lbhXv#HOFDk;*#I2kZ5*;1pF z&R@VNU1Opd8Y3$PIoBO@#Iz@$c8o_~b9Cwqw|57-Gm+aOmz?^jK`i&jeI8GqlY-IH zS{`=HeAN2Xt6ed~*@BZeuAV#br|Oyqf*yXL$=s9GlWxTChLqp=ar4OY)oFcXHnwnC zGJ}rDzj87lH7=8D1MBvN*?`eG%Ueb@&?$4|+4d5yEBeea%Mvho4zo}Lo&GjE6n4yE zWNV;bAt)}28aY|j`uvNLd#12gd8|}#&tZyhpuKbHu;FMO$8|=s!B3O9k@Kg|WwalR z_$W?ty3bF=YpG0_>zwZ%Dzens$2SV3urg=J^wdD_oNG3FpBFA@V~2;ujz4eKxW z4n6NVi5RWM*{y*@TD&1ubsi`Bu1=CxV?1nt8qH&#@$<|;-EfR2RG=JX zT;ScazDQ_XLshtBwl7}nVO8q6p`NgSPSsG>B9VH-0<54Rd-Sk~qxP|79art+?`>6r zsIYATq1LvNU@MiHPnfZF{7*DAd!kk62c(S{z_)N9HdaXPBv>U)KjSKLlHJaEL7BTqrE0EOclYRLIgy zU{ZU{%d#lhv&al==U?^1CfWT*mOB37L!HH(j~sO56qk|LeZR0QtoroJHU-&fA zHJ@bQ7nQb-iqB6)Y}8L>hNH5^PsO}nWe+OS+$a200xT8#-V7(Yj*3+lE|TR0Vni4W zC%X0?g-`q?xYqwM`plF*c6iok{!Gpso@Mobikzw|@g$C` zXHAPF(AetY)~9b9TUX@TcaWQnjkP)yz-Q*|=UIxR)a!np>OwMSB{D;X(XFVpLTv!Sr5rWsu2Rd5RpD4Ok!v2&zl?qw`sI+<_Dfc(ys`diiP=5b zH8pqDu}rSZ_4*jY6Yu+e&6uq_3Sf@h_^Zi zgz6h|balHYR5h{gDG#S?R;3S zOZgqMVf`JD!s6^m_b)%kHwwGeetb;Z&~5~rD88%=t&a4u-3)pELG2+`)@ zvQT}^Nm-(b6*RL(W1ZL_ASwC&IoX{VljVY$pN!q^FOxh@x+M3QOX-8l&07D*J>RWP zRJmkwe{7HP%(xU_eb6)Zxkh$yh>ZBoZwLy{qp*IFDi^nd6o#TC3Itl6TPj)Fq`7q) zKzIF#%a`VC1q?|58{Y{@PqC+XIg?EB?l(X0IVZ!23x3C0E^qoOz_TGQY zg~_23u_&^x98eT)kCmP_rMdD5I5qil^3a3j3*v zGM4GgcbNP_*P3UG9VVOhgAZkVtjmpLE8^X?X2smD6yYt!XMNytm;@c}O1 zuTVZ+X3~C=fILy*Mu#sJeh%e1hJ@FEU*c~9zlHsr@c!^Re))2f=naD3;~xiqfb1AG zeuVN7u%G$Lob~k&zWCuo$@mri0e^#)u>Id5&sL2;VH)I%Aigf}Z}9=3CgCxToHWEK@|eNfa1Rf ztKEMXG5yp#}^9Zf9>?KDcw5ZKG+&R|Mif3a@+T&6P^#{J7&im z|8dw6|A(+Mya+R3F{Y(rTt#wOeshCag?ocBMm-(5(VQGvlA8p0a7%G@Rg96UpWbMG zn{-pDbzq?$pE+;^0L;?mw`8-;t;~xT7;vWfD=}ueBA-UG` zJ;u(SSik(5;@C%K{Z^w|ouiGg2iyc7fm@&?`63(*x562a4Z^->;0`DQ)IRtIl&r8z z)$*T(uM++(%#%-nUFYB+0slf#R8;0+{Qd)zBvg!WkxMJRiC+e&e3%T6!Bj^s1Jw!q zO&zv%!aKpUgimn%Q{Z{NEaaQX!3PK!<&2Av(aX35O=^LSh1MtKK7(=iufST6PvZFK zde%40=vme`%v!>)2*)IiuOT1Sv%Y0E75;!9OR&CSHXr_ke=WQz1JlbK{0ylM>(gDF z%(#u8lUW}zLuP%%EQltO8jz9iZ{%KwWt{M`@Lj?yJO27m1sK++=7imx@E$M#e=&Ax z>m4tecf1#^XN=0IWbKwKN5a+z73E~*XqKY*%R9{@HXN$2yksVrf4!>zc?pw`LM%(@ z(y#&~KbF~$AD@_09P9)WU_Y1$N5OJ%Dl88d!3uB{tO#F%mEZxG1mA{~%lAI40>6S) z;VstwMl}w^Y^uZJum((kHKEL3wIB;KBN@tkRTqwd_25+42+9WprM&ZC6aD>GbFMl6 zpdP!;EECfiv5Y}oU?tcUN|(*h8@HL2O&)eyYJ5n|QtR)i4RF*3>c3I*+RrVOk!Qcz zownT!Nq-oXBvNV%Srr=XVISBrz*sOIN`@xF-h{7!eF=XVK8jyv{-Ju&cC)T|@HKs8 zI}MRduw46(gtA5)1tsHSpo~FmFZFR(*ZLY*S;+QJt6g(o75s9#n(%S_G8WB%vQnD` zH^bR*8)T~Wy$b+*7~D4X@jXKM;Gyph91MVvLQX!ZAKC0Ks2-Rz_*zn~-7S29OZG}^6<1_qg;1$S&dgCh0cjRQk_!2*v zu=F{(F$F&t-^Mq2`8&)2m1{p8RRvF1rJ3my)-O8HHivi^M@T}TF|Q4j%4r8H5#AnF zhSD#qKv{o^d<3i>Xw3f)tV6taU_<2Z!p86lM6Z_B{%Hh!We51afi3aN_}&Ws?u6fk zZS;g)W^b?k@Kg5u$>$oXvdO`kF?lF#eIcJG2G)lnc?RICMl9|CTivaXF1FjO5ODBF zfIjn;ic!;br`_DD;W6dN-5CE6)QUPMD+aUh7k4P77k_y;#z~Ivqx+iS9}hF(6eyF~ zWAHIJEzp>|63)cG7Use&a5mfy=R)a&^C6>CuCaiFiv&CYzl6M9;`<3c3IBr2VJODD z0>;3Vuo7GaQ=o=2N<9bLL2kuatL@crIQ}(oG+Ya(!F6yc+yFPqcbqqIu#qAHl`&V@TIGF2Q%;r|@0) z8T2J2s^?{6qa=P_DmS8`d}zM}EDvK~ zRmio6uQn9@dXQ@n>jV7!F95!F_<3{5*BvJE#*%L^2jyW7tN^83OT;;_GX7^E7caiG zup)d3R)@P_4R`>G{%f!n{@-9Sya!XDCz!zqMncgm4S7S#S03gz;Ghx*jbKCA1U>}0 zD)RM!5}_~TRVv?Tm2RSVUjiS-FJJg?4S5B`;A+Zu0Jep1!*=jH*dG21`TB(~ zL_WOVnFINve-~I0X29x@51;uOLB4b5YYBV9{*brDtuOfZg_H0<0%iKoCEoizm)VmrL;g zbOpI>QqOuXFk&3)6&a_-Lz(?2=m~jdwAX&Ts*L59R<+4UWidAeE`yK3V*E#n#khU% zUJuP9oJXqf=9y*Erz4j&$V^xYik-;XV>Xnt&4uLMm=9&K_ylYN7eQGHE!I^Jnzg+j zGWkhfJ=TlTl@1`qdaa_ySkM0GOZd5U;yfNz#tEJBVMt`|)2K=Yo`EtCtbi5ZvrsO? zRzkTeso}%$IVc5?T9j4k8vL^8SqtUv$_9ACk)Lt=7vLtszlEFO4M$Fva;*q|Isy0K zizxg*&fWyPrmOoOzxPbZO>QEW7?OxcLP!vasi+|#<`|2rqJo%eNMfidkyMODQL;)= zQ(IIO#VsX*(&}r7sZ}qE(wZxZ(i(oBb@n+or+vTm{GWgN=(>A-)?Ry_*4}6DXP|3A zOBmfVThZ`+vVIrq2GELde+JqSbR%eY(9c0rLAR*3DRV$Mg71R5!Jh}Z0~DWw>ior^ zyWsx79)fKj{MZ1-9?<=U0FMWI>A()@1Bci(_1p@&;+dDX3Cj6<3ba1xY0##iFbe3ijUPd~!Tn#*fuI*aM}S@g zoeO#ubUx^>pi4oo!+Mdu20w0s@hRwS(A}WFfgS@b0zCuzJLo0Q`=HlAIe&Qe@euB( zhMSM5{t0(B=o8RSK%arG2W5HACS1yr{W+)t`ZcJxRt4<}KX6@$K7QidmDF745=d8EkF(?8am#9&8MlwpyTQ(YCsvJoUrP zSo#bf*ZAp672K+)->r>%@ASgJm36xHAQ7}XkjnWe);v1v(lO7jI?14T`TY zb<<-zP;TvtbTiZLvE1?W^z zp4&_Z{hTK|Gx39$4EO*w8}T+kDs__8|tDkuiK>^q(ww0hfM_C1W3zX$2|A`-Kz~D*CN1&w?0r2EyJ>2C$ zKLw2i{T#F|=w{GHpkIJC2i*qR5_BhMYtX%*?LhZ|Vo%0)0CW)Ox1eJ{zXQz%J*=TY z&c=_UV5|f^4!REXBq*kMw$q@P%GrJZ#njFABPeEIw*P`+LS#D+iiwZyCs0g$^b|?x z&9A~81o|szdC+U1b3m_yqPN!N@<4BCnCzgt))|XIZ$n@^yFm|v{s#ITXc6cM(0ich zX81#Q{e$HPpm*VZ2#Vgp_6I0WhPd)MFxTKL4g!4+x3FQ>#rVe8nm5M3$~HguvI6N7 z`(&{XYxiv0Mxr6$7C`+Ea}~X1dV}&Z!~q%z>I2HXf-fkKgMOfuKudt~Y9|1+I%rAI zI-r4|4M9tTCV-X!Z3$Y|3#HH+KZ3yM1R4U$O}ad2FVIlXexMaV2Y^-t<@HS^P+s3~ zBFBS9!9BsC(+vI$&??~10*wY;02&YaA!uz-UjNkbswu2|^}t{=4JKW>RiFXr5x5(I zUIBd>^cPTkzO!E<>E%=8^EJA#W?=JpkpvnA+5+@t(AJ=tpt#H>`(03uCyxj0UJi<@ zT(Unl+@BlxLD2T#A2r;ChMR|lj^O_nv@__hpj|-kV~wgS=JA0U3QFx2P$ww6OM`O2 z)j=_N%*Ix~9zdeO?+n_5u6`}O=~n<1V(ZjyyP`h}Ke-ota2fXo6}@wPlr z&UZ|*vsL8dVo)#84?xS{sv|wQJcg_QgBQx2+z`-J^z@+gy0rNR>iG@g`4M0ZdOil_ zG4K;mA5a!|g5p^&y=AQjZ3OqHpxi)MuBSnVgMJ40RM3r}d7zs?H-K&d-37|}@DkSkYu$Ft;ap@QP_ES?QN;Vd1;hX!A1e+u^a#Xd8v=b;k;mRWW#~4_HDjxt_+?3RZ2C3>~T%!@42Q&tmbtQKS4^| z&|Q;nSkmo%(~{IlR>xg9kdqy6!C;F!@87y34T+M18@ewC%1vaiU-7kiMqjZLPPyge zKiB zWSIv5e5fcGq56<31ZQi;g(3~D4PRx9H2B!5kC#uQAaTJfXAqwV;6)p^56=A(>+Nkc zo*K>T>uy*bk!)3`XA=MWmz<6m84ULp1NHMkDzeLInB_}!+?Gt}- z{{d~TijU@6MaeEdlg070k?XmyaW**cIp226r&sh}e0oLymG`OfgDQG{C3t@I_58~A z{MuAm_2%4uj?=b2ekMhV*u<`)F0Ui(T7}SXa&@ z|7vo1Y8E3`HEyQ(gVJMA%x<7B8R&K^dX>>Hfws}nBqO*#EP2Wu9yD*PCI>q(wCEk> zR+>{y4wIl#XJgRR*$3%3v!P38pD@@bsC0F(Ga}ses>?U*8m!dXBL}WPL6rvW(95?1 zIfHQGH7!=|iOQ|tA$~CyZD$!IpF8MJNJc+*h`PhaiM-KxI^iD=jn!b^m zv6QCPL<*NfPfH)#SW}J(Z|RYjUA)N0M!kN`dv}vh$E*6_3`U$>%eZ=YDYb}$k`JNe z3m+O0C&#$HFod}_pqkk(Qu;$2RRQ5A-!TCM2d}@E&5M@jdM@#OEMfLb zd>0E7{njl0IGkqJlARK~U1%T&)7Dy+#NDoi*0~Z&XBx_Aa|}M`jjJsOI80VBU22HP z^a78{y^P8}4!`V|aqgY32PuKu(!}wcrF5h=qPPm$es|Kt+H#EJcSGy{sOVAWUsQZn z2P#%WMSnl~zK$Fr_xF>j={j7D^V11m^Pb?P)VVIi)31n>Vj4rONf-?_&T5{HQ}c*}NleDa`@k`~<+yej-w^<-DL z$>Q3_7O`>;Oq`MNzZ;_XbohU2P5YM+&|2sV@~5#cSpwR|z&Zd){&WF{w8E48&8i@~ z?n84U%s%3vy_d-^)~=s9<11%~ zRDyaolq>iRDp6b;CAu^U=aUQh2E;X^a2H~>6R!k(&A(Pm#yRMV4P|fp6-sQ3YW1Wc z#*u8pGq+=|(pMNC1~2q2<$)qKLe}U2!UOBabPnW$&vA& zBe0qQB1O14cLXnexcKK`5tds*eBWc@-2VQ*r#Q^j-O&3liQU#1iQR*{MbTV z!kOGcuH*RFkO&hu?ksH~CrD_k7h1?YrJwz%VM{qr4)RBrFb_9}+-fN&%V<9o_O4eD zb!{atl;4Akr_rReM#S~%kMJ6b^LC9|%L5#urn4n_^E-(6uGaDf36swzlY7XV$8QY51*KQo$yKFjm)k#CE-86U!9L3m zdu{qX;TYIn?;uBOx!}qBXjTU~!X@v+1`V>BixtFHgE|lN3bVsRH&6?qi*s=ZvWDox zdwuO40}V|(%B3C9XyhOwP?kn_l)FmuKKFMW|nxmI69@VrK?2)f7Mn*)}c;*YC|#%MT%QeHv*c@uiB zj-XkuczV_$bc6wz&9s{%=%E#8&=qwNb~NqY2$lAvD0m{ID+Wfm^yHgEcM>Iblg%4> zhR~1jMHktBMLXhUy#LXLF-7s%7S^wfUryKfmSnRYIi`UY0pc{(HWc`cR=3SO6tq?SFb?&7agdKnqdu=gf7FZRPqRD>v|6(?diFZ>H+!*sdN0UNfP9}c zTG9*p`@C4*)f@6K{Av@@s9|r&Pk6EXW|p4>`Mfkb%kp_ImhapL@|lp|l13ByApTok zEPtEjVSv_-rcs$UAb<45@-yFn{A9@ANTV$*f8)jSmHR>-bAL@srw)A)e=Yrm<#mAN zb08m)PIp*7;>Gf*DUg2~@=eldZVKd^yjWiC2l*+G@0m`q{ZLDLzF2-8%jZIVtS(=M zuJuDx9s6QW?fb*iRCrpDPGkF9`oA3vOat&qI$iFM-23FkinaFG__xb{Dk2(kVX`x%bzL}5V)^tzkjE~E)-i*Y41)fSFP3)=hWs4JznMV|2SfjxFP8s|<*|FB zP0yh32Sfk#7t6OF0{M3#zdD1)4uSsFFP6W~^4OKp_GD1Wq0qnQ#qu+ULViBv|C>Qu zhC=^;Uo2nwO~_-nNBbj#I=qRF{ErvQ?`HY;AYW<}{lfC4M*UyqW!%EXGXv}V?o*7# z`ur|?m|R}MoM8Ddxr2l;{mw8sM!spHb%q1IH-hprFgY5=4*!wDv4$NnhT|MNS{jbP z5peV~9Lem+G90<=z&NFAE6jqGqhN$wPQoChbM7;Y5k_}Z9|;Er4&5<;9T*jK$5M8n z%hw&J*n$3BcR17FKxeHxlGuTsSa(cf2fA6^v6UU@Lv_b3cA$gQ9hK7IK<}qJda(mt zo9_bg_j8tcqLW}=SX zVJ7OH&P*5sCMs5+F<_#?=*&&bJk!E`bd20Z@=AswsNCj%-g-X{v#^Tq%Zl9PpU?q7 zULD|Rlh}iBkVv#&}zQgGnF=luzK(H{0PpWED(L~rIXJ3HrqueA|LDurGI{fQfL%yCV z&szz&!(@`o*M?+Hk{gE!;|TVrJPnXHZ;;gp-?K8gH3=&dGo#I%93ZvEw`xjZW}C$Douv%M$aYq=_`D6nhYPv zljW1;7ztVM-DFrlm$r3x&z8TlYbDV+tbU#5PC+6Q-p3Np(9{A%pz+kXgYNKZb=Y~LeOD(gB8hIK3$IRDuZN|?~UiiG-o(n zn~u-D;nItt3|%VWH1cT%ZN7!5&!F~R&IZK=Fm?tqrYtnH?M=&P$n{)p4ZoZn9OODZ zJMv~CVe9D94pfec;&%?NouUN%rbqv=J89QxHGujW&^Ec0{>?cT!aB;CiFN?b{LSvB znbfWBGutzB z*enwqUQ;E05h4CT^~8^p0HBA?mA#mkpkTnz;TQ z`JmLimpfy&+|Mp^-Zm{lJ-9nZ?jg19?QT0)o-4^5oc?Uc{dwp?(;B%;&X@h|&d(8( zIGoz%Woaq7?1M= zo}_ezH=q+1!W43=q5J!Va$CFB4PLf=K~Z_KX}`DjG?m~5=*F6AFfGl)2!uAjF;C90 zdu71iz2FENW(FnzShJtbe&8{kCQ;B* z022Z1+)w@ka9L81rAW)p{UV**Cb+d9;m$D3endR?aYQ`#aYTRa1I)bw)8G0yBHsEq zBHsEqBHsFdzh9IP+O!O9>Ilu}--Vvv*ouupkAG_!x~5HEi*QXV421dBV?0dc4Uf^w z@!ZuByG^$naTaH!4(OCRLX23vC2@pOmdmZ|NwjV`Qk9KVIS*08f%f`FZM4=A-Zw){ zK(*ylV=gazgWBjrxsHT7pg(Fj`$N>5S^M0}KSU*$P-x)BNGPMTD`4S6k?2yRS3+v; ze!4RllbsbS(VCF+I&y^(RV`t$S_dS&G^uw>Hu>#L~*tD;b zS8U=|_8Wvs456qkas|1>5L{OIzj~vLS8X%CfO^#G&vp?F*H&RXd5|fX^+hnJ@ zOlKZp=B+)lGjBU8>_k)^`p@3==}Yt?smDO{WqGr9TlPoG0J(9Hg3m6DCbR) zOtaVbFYfjIExo?ZE|q7;j4Q#7#5?ol5*%ZdDl)Gx^Qtqi=6$&RB59`IY4%n_8 zdM2gpKqlQoCVc}V=MH4jH-;o<5=)k#y*p4-N^k}-!Ceqc!UaJ$P}adpAqmlxohSgv z;ASzJw^LR^aa`BaatDq`8J-F;&I>ND5_}_E2*i&-m+O=zhCHH{prmBVLa`mnCF&A^rih8-&(g!t+;Gc44nCfKtliD|YYQTpX5o z@^)zeRo*R!Im+ToCst90iY{SiafXji0Hy7gt0Mu+b|V4zk$@(n=-_V5RhrWjqS#%c+Q#8G-M@@Ir@p9p;Ob9Z2I#`(Q%q7-K5ShVmI z7rF2ix|g*Dh}%L7hTT432MXj@k=vnrF|0m7Zuc5v9A;Uw7yZ~na3+kQ{Jl8LGGR<{ z{&V{N&%-Rn(uXyf)3E}`qR&O1*loka2F$#D*npWh#NA}S9A%es-gFQATK16~qRH89 zmudc|aw+%hgYpx*v@YE}>sw5Fq$Z=>-yf2n*`;1%_(W7&s(4sdqzPl(QHSLVvLinn z;ovXd?N^BPjMrcs`9HAAuHR8XxhIgAA>jPHik6>%w!w7$gdACA7+7UL=9u9xw*Tmn z8Dh`xE}XZ(EC&kwZ*S7;dn=7j$$`${@LkjJO~(_kRl)Zy8xxXYwDJ^8{39UK)09cv z1DRh>$yJQE-#K_Qn_43%jxV2Op|sPo;`n(LM~uI+NV(%E<(_w1-Xu9hZ0)vk)VU63 zU%k#?*sl38-8lm@!iF=LB=^)E{iKHVsLPM?QGXm-(+crnu%5(5bm?VuNiELGHH_IN z3dR$KVTeNEf8Ddr%6WDT2iLSt3Pqj6kl9HQ57*?qE~zyCoIJ!F>;ldsUvZjS3sfoQ zyk}~aPeab5CKdq5!H}j0Jz`|WaO+#a`E&#_+Fr=4Q|aM(m^arMvV61%QNi7E@fYOC zP<&(IX$Av^rHp2X8y7dcx|DtaeNSDQBgi_Czj>IDhzm23F!sPr4foYu@T|}|jb{Gm z0z^6yS-b6Pu~*sYCppc*V>16YT+EZs{e&G$ktjRvz}L3~t6!9RI7H;_wl>sxIaYov zF3Mj@9cog~OY%YI00q;JE28;O`(}K`=(6kzFKeFqE|sHUBT5&>(wBdeOWH& z8fJLp6mU*9rQ4U~upmSU2a9ob+5&Tq=x`O+J%i1C33p;msq)Vl7#h>?pONdSh>*`! z%KKSPFzP{LaLlZD0{IeG=+4h_@Z{SvA4$YXY0yAWKEqfV6f+$Cv~dw=bGR{dX7>iY z4>}SQJ%IjYKY9@T17w^#&t3ukU!dzjpMY)yWqoc?yMj~rpfc$9pbF^EILvJG!jC(K z;GdvQT6{%*Rra}RT&I8`6cO~d-3P{rg{wI6rFBNlZgh;Ie!+>7M#m)Tc+p1!A3!QO|3h+S{2HUqc?f0$|25+IJ0exEaSp1LCoVGx@N-A5UM7 z@pbwQ=!Y*fjIudQiI2U*DEYc*95Ft{t1sVU>>fHP!V9PI2TG7r}X_9jMAodnUdo3i07XC zv^g!Z>tF2}##@qH&SuT!r9a9%__o|kLZSA#Ee~{vva`dSqCbp&@wPlkiYuf(cVHK7 zQ0UIPBY%t|vZtv@k$hRh6%Lv`pQ7%e(%AF$jz69z-IF((Jzm1^s5AIxNAu37p1*tQ z%ne%nI}(90LyN-g$3v6^V;HzWj{5-cVTo2FpN?9A@c;tv0BD!b9Sr^krH+1M^vKcH z_nL3eCHDUt#D?Tkeu`oqY`Q`19{{)u;H`X$>1P3UFi-?waz0(?Yl%wqLjd@;MVph4 zM+_~%Vg_)xjS-9DiU8yANQi5l6DO#5Q$_VTxIGZ_s$iXip(?EFW)rDCPkx z#GHX=0IuZIax2j05deISuieV0j7Oej{|(y406w;L zKY@a_0Fnx5f)&`!0Pe}rx)jhaRv`K*fMfu#6i}C^7FCNFXb&Kzfby+?{TYDn0EQG$ z%rm*TTBbAbDu5{kwB(sZ)p-Vb09af=+H;GK_Rj&l4q#gWjeTzMu>*iV?$6OK6&MwH z6lFd4SoCi!s;oq6y@6jYSkysDGF!%?#bEaV`+C8meZ_3@vn!F#H^BeHP)EnxV&3$P z-BRarAfxq#%(DVoZ^iW`Et`GRTV``_|3rJRO4Yqa>iR6$dsB+#M0ct^dFx8m(E zd+bS+t|^hFCt3Q^0i#Civy5Qc>kA|1E=@5Xhq*xyAgtv<=}sv1QlcC?_lhJ3Q~X4w zlxx6{QJ(n;H|f@t?xlp-Ths9+n60hwQp^KeH|V$*R1s8N-%Ee8s_PzAd-L$hR%36a z1f9F(>q8SX#n;&_%`@rAq|F*4mW_1SGijzb0?4F~ycP2ynj3W8TZ#1A2;Ecm+4a*% zW}Z`f2Qv3_AOZNGlVeD(WMuAp4ol|lWtmNosqi-$FCWF_GFjY;%D{V;7?${KWR`x6 zN#!{+xY9|5~LAKlHO&J!?%@wYo!l+N7p`p@};aELZk{Oo~Eo{GLofFsEW zy8^Aei}_TtuTtJM+u-q32;$H(-WQ3_qD8(+q$?I*@o|dGDNhz1V)myNHZQlc=qa;n z9uU%;5FYokDBg+d{t!o}0!t8%3bQT_iI-woG`|%Vs7swnpsSq)4GBA!jPaTkA1c{^t`6HeOEGRFHkz!`I!-uMzV$KiF+$@^uuT*oL zGT5A|k~;gbKTMbx{Sk-3hl}ID-;g53{z&m@3!A5mSyZD0*k@q9G>eC4kVt6>rIq~# ztz&dEs$29?Az^DiY~%=vpR7cCs;yrD8VfFS(&CO%y#OV`5ogHa{^&fllwZ5Iiua*1 zDJK9WnMo@J*(=DU0L6Ui@&-k_pl>0TMl+A;kK!7$V6*?Yhxk>(KTHLdyObE&8&iRw zT3~i_#ib<3QE+{}07bVSuhsN~tGd zJl2_M%)}TBCXDo@l=2eB-JPZ2ZEHR~gQR>6NFFo z&*$9Y$9eTv+%H1VQBoh{?C5rMp0hMO^T1eIY32~)AD%B3`-788D|i~ZKt$*Y3u1iJ zLkTE@P%x$;sxcDAES));nHZ<^_-`l!ag0s*EPB3>3-tM!Vkus z4rL*RVP*oTV{w6qc6kxSg0hJAHiK7P7=`cNfPwXHS*4P6setCb2ODx+Ib`(Z0wddd z!6jWUpb_PeQy3&fVHB{;Gq^q+hN8JuPO0OF*LzgEZKgYof4|fh;Nl( zcc&^!q2%=q){@yS)7}uH1Zv-cv)o0?W0Y74^yo}`C*$DTH&nTr5~&`7z#r7U8Y=4_ z?%~yx2A-A4uIljr9pILw>HF$RgsUaKD>PdtFJo~zDL+SB_PJT>CA;yyj^{ zDQ~G|L)Typ!55bB+Vi#{!W|7SEg%w$t|Y09h%5)gT`Q~(st?{(h*je3hv-r)n%;kq zwz*}4?Soy+3nS4$}ukTC!T7}4u;YVqM`O>|t1X--W~+dV|5YeKtHag*;sb*^`db~S&$uZ=*PV4Do(l>hh9CP ztcWyE3^*-K$W>d3q@|10>WFl=c!Y@smzG?Xvf`B(HJQc9^%8X7ZH60cn^F;$XOytZ zSHW-B1ngPrSLipTpjt>mQ>t4_sRoi#3y*7i*GH(iNU&?H5h~}PSiOH%3pHc1u08W5 z$lj`j$W5_Cj#G#bYAY|fj#_+kRcK1DACD8FYs0fn` zwwbyF+8mBiw0vD9z_r+daegOI&N`SWJ2AG~f^l*aD7`K+5l=%-!)i03uf+A}$GVu~ z;A2mmJx@HH-kKCY)kxyIoGQ8WFV zhlwKnoNtL@Lc@c3qJAvfW8qJv#weShM9Zu(W8_<&30fize+gr}6;6Q?juIy)kygHh zV$yKyFo(=+ZYGIzn%OT~*xb|;sfN=hOq5=?`iT8;#Qx_BlvN+4_j85f*t4!?9Q(3# zsy=#ETbQAr=66NTCb!nS>F`P|)+;A~rxb^%aRX>O0c~x=XkY`+s_zhe#sI$3)kcQt zqoZN2n6FlEhq%t52JO%c{$qIMg62j(gVNifI?te#Styqk z?G$fmhMk^e;@bFvcG%6BK?m9?kZZpSFJZ$K4&**cq6@Ba{@2 zIM-gVkJ{VWd()z1lqT*1(r)jk{A9&EXw{n@Gtd`+{53_i$0#FzT^u4bVBEyL^X374 zC~6P+6v&5sP5CSz@?!b;4v_B$`PyGo&ki2LKyO+Mpl*KviG~8(kP)L&Gx*Ia*|h>q z1XsY=a*?SfZuac6#9sU?a&<(z39@8 z=vE$DFz#}6EHOx&QsA0kR&F*Uac%g#8fFr4os_E5qJ8e3olsrn+xr#q<;RoGN>zu* zFt)}QmBw~vLKlc4bB1=oR1S&W*ag#t#IN0FyC}8nQg&Upe^&)Bnx8~F$_=Ba?pT!O zhPgX*SNhrQ&1v(iNYm0Z#fQ$ms^D;2cX;WYGh3-B2O z=K#DBPT#+738Qo`0OtV=45uc&EI=j$7XW02)5pD(M#k5GCv7yMzHgbl-ip)zC!o3E zq7SrkaQ0A@D&sW%ahiWG@4k0IUk98&;r3A1sP51K44xr1-9|gpKUu zSva4hWsvdz88QXM!S?B6iM8Jw(0&C1KZILNWhZG216KiD2)CNbPSSY>egW_x+-jyd zNp1RKp71MxCwSaeX8=4S6=5|2o}|ht(03g`aD>$ac#;+|a05Vm zgw@P=lI;Be+yqcR!fIwbNy7m+Zvp5SAu^c~yCX+F?`O%8^N{hs4VmtS3<_d-KTD3Z z?++!g?`y+NC7W5vyZtRnc0kg5;9s5 zWEMowcLO};rjt}U6#y1|+PVm8l4{YK$-wUbHbv0KR^TcF_W^tpLH+|Rm8bJS01p5h zji3ouU^fE~0bGrsU#vj%Ae7=C0B%v|L71kP4R{gw+9U9B7&m{AB~nircnrWNlA;D% zfYiYNutB0lMbca=aD;)s0Mv-2hgP8O5CBgABt=>+)+gyB2A%?F7iqOvBddl2cm|+f zBsCf8nJ}EBsSG>^FeH*TT7d@)VBFNQBdzAyla%r%06T!`ku}Utgq=KXzu_76@WL=l_RWES zra|CrByAsV?N9Ecp*;nRK!<|6Mzl-C{_}@hI+WBAC`ca&Jf%4!ECqQSe9aepM$bp2a;3q)Kg1F%QNuK)LUf`b zuJ0zo+_n|}kYZc1!RHZ?$BPz}lZM$x3tE;2`%c%&A`qTr@Z6*YxxR2Tx1XfYbR-DJ zR7Zf8{_4~p<(m0^8nYkQN`*wu$DBx4IaoAuTq?( zx*3Qx&XH&Xs!*Q{OZF{h024?py9({gP$HuF4s}FcpAnpbnQ$=dgFE4V$HNz?X+`Nv zFlE|vo|Eu()(NJ0nN`s>5=x8J(DBARc zPcADU8CW*2Lb@s$d@dADCU%V+S@hh;bcpFt(y%1-LH1CCiTfyBK%I)EY29b#ySgj zv^tc|q%O^8Qja#zLQxf9w@7^nF>6n*9I)F{d=8Rx+Txw7VS7py=u|;I66Am&R|Qeu z))iD1q=g`x+>RHT}O?ny2kc`3>VCqf+RljEv3fk(z~bX z(K`(>*U9+e=EoZyi1jqE)mp`6$W^sH4u+!0I!#0U>~6uh?&?@g*L_?E$>qh>Hb7@@ zo`&LVRWpBnTaM@TR*0Mk{--N7#P5{9j{P@SqNi?B@FHkI?|;^IQ80*I*&pJ1al5H z`DoKD43YT#&^w5Z&Qdh$b=>as>o;8NS8_o?{*f2f;6t6}shE=#{|>^!D6J)QrJnCt zTKQrIFw$yWy3)RP(8{}X6{N^vMdZv@}_1MrUuew`1%zbg2-%)cf0o4}WGE=(_@yrnQ( z`{*kyyRE!9a9MpR1fmQ9Ov+J+Sjf&@iY+{>TQ4l-YK>*;Ld@7JErV!3Q*`t)h+;je zLn|1{Hle!=Vd1Gm<(C6mZbI0P#1dgSb}>JSq^#u#1xv}J%Mr?cLq70B$e%Uk2YiSq zi$$R)%JW#_DI}U!z;!woS;C<&!tAz^`Yq(-T%nYgLn_(nx1p$~Nh@GBjIKl@R$z}f zv6B1a70Ow={iZu-mGY@w!cr-AjnY%fuHv4xM#1+uSg0)dNVy>eMZ2ectl&7~S(>w! zi+rt;V86}3aY(0{*f>?zA*Gn#i(OPW9Fjg$#%-D6ww+$y3ZzRl=H*QdZ^EN0OBusqq`=CQiQ|-3Rl(GuO z`gxxzmF$ipeQwAnWsm=iYFfAv%?=a3I~$da(%Us@`R7WWbh4(q-X^6xzBqb?<`y8Q zF~sdGz}Bo7emDa9>wJCpDg)$%uBa+(mc6(anbxJN+h-s4=N)@q<-Wsin=KCcbvmF- z;@VXyS*w9VuOH5%sKZKx{NX&jAlTA(3>6$! z*4V?@(2T?W*>-O!+)lG28MqmL;>w^uqSN}Mu$59w_akaA6dOl?wMYq`6@W9<7ABu?3--iyx^jGf!!NGpRpn*e% zrFw=fh#bXW6G2Y}2|9*FlhwoUlyT$PBln{`^h8i+h`_^eL1qf_(J>4}`1WWfo}mA(ljm^}6nqRkMfQqmzv}W4V+6n{zZz? zxp-Xh4nl9?$*OU{IMrMtkz_xCR7X;%APqo5t-{ErA)_%LFtaI=(uL%l6P`Vf8g%3Y z;u43rT+E|~Com_vXo(AgvHcU6wohL;ZbG90^=p_8c!|&_wQ~pWM5~l{) zPXVX}VA%T4hgOAz+3{WQrJGoG4EtU=C$*mMZu^7M zOqNi*bI+n9K-M<-ud-8q{e799??8tbcn;l<$P>G5lXxUE?VM65b7&*K#R-L8=aupp z0>__MKG9a=+ut9?QPc$(aef%*?r=dV#|J6&-IGZ_p~2z4bM41*l=qXT2v*aNKcNUd z0&sR5Nf#|Zi;Dn025@d1jj#fn8TbUi`EhjC3WQz)uol2ijFntOIay9Br`z z4;WYv;PN=CaM|J`BY|gJRc`MAJq>Lw;VZQ zwDn_))wB|F+D6D}GGBK_yZntOfax55@g=JE-E^Ga z-Q7(^g4k1WW{_L`Zi@d!2RaLqF35Zj(Z8nkR(Tl-CBNXvh_HdJrl4PumMw^K<4kJy zt0nb04158gWhSk+0@oS9voc!mOe%TJ;-m950NVfz%%llcUlrnj@VDa7! zbb+CPx6p2SOt!13+bwv{hrp*0N$KT+HV#gZGHoA z06@lM%J@x*3ePaYWV`tc)YDV=R~At)`IekBZl^?}xeFx+p=8!%s&&_6?_5pe0XV+_ zu+q>UqxsEN0*^faq-6ch8a&>hA!K0Eo+`*xxNcIs*W{C!4hU)*6$40Jp#Oy{|Z(g@C7Ki(;gr;fVh`_bu_?aUVr}95S;F85H$|`8P?JBg8oKpJ zF%JZ+ro}*==YS43HLOhYt4OzG)ts)ZrqX{x1D@E>M(Y}qJ-z3A0L}{l7MPyn)8YBz zpGvW3zrW!5C&(-|g75Sfj?J6>?@XZ1i$L9`hP~-XK)WZF1lXTI!zIY%8yXJ(Wl6wz zpw7!c&zTw$Goaz+rxp!Gtl?+K{G3D2o*@f%J+WvQ@)R1b0JXnu)Xu%Eq1rQxhD(sq zu0qE9ZJ}YqQ;UYzo^bPdIs*!ej;Ujxv|^n9E>uXt|B z#3PW=u0!Tk5&WV6)su&d+NhDv8^Fex{!>OH`o4D6{1RvNqP;41>LD`8@IG5Dt^p0~ z@P7;764U>s(YTcThkKUfZ-b0>8!{{3rVDnpIP&olJmZlR?YzZvAZ3ohy*d-6;uz36 z2x`AU@QSV>`2P?Im!az}M7*XL<$#C;(nYyAt+Wg>S`lRYr*K4q|BePJ&~OiE^}lJD zGuF>Zz5cS~=OPGdzeBM06v|gD>2ayha34VDzi9}43+Z`XwWMbz1hoec>|sRYe?{yX zL>@w9>=cU8RP+0+)ij)eKLBJ-p*$<_BLL?k0ISW=i{3(?5aMMCxQ&+@>Hioqn++NC zlRjRm`Ek{1+5rLQpAfiiDoGg!C4X6!M0-QYUy!+5tmKAO$zlj-PayDU3hnc@#9eg& zcnY9IF2y=5Kso^DGXQ;ZjnYdTk6@ek@qEj;nl7>D=a5OwB_AKv{N`vib@qX0%n-HV zrsvJ$aZbb6*OKr9kkRarnV3s=d{pymq1DvD7m1Mo>^D5y2GIpyOVmDtfF?uWyIlI- z*WxqWiC`4~C(K}1PC%S%PqtM3`H;~t&D1XD(oUx(&UQa|#+y7^)u~2;T@z7Vll&|_ zXF6mwFUZuKN=y7Ko-Z+ghkUe`rjn1pB}(1=0pMjHt;JNzvI2(yIDG(Qn!(v8A&W|s zuw+r=5|F_&Kw7RT)A)a6HbX{pLT2_}=LiTe(rUYbuG-YaJ{!=CgGFkv+E={HNE=vFp7{K~nyEc_7l(YatN}^;-0??+3 zEJn%tm$H=Xc?f8wAmBHReU_!rQfdv);L^DiA{7WU&hSntS$^fn8E7e?1CY`15|Z}P zG`dsD5_W??crF8=r|J1p7P{pbR?piYqv6>kEoB;A2()w~@ulIp9Du2&=k&?&oL$-y z@@J6If*>f!Z8p8nAM9JDOoAWQVuK}L&!Oq1z!BFN%7C>Wk20VJEA z?Qg^LO?ZwoCJyLB*qYD~pY!pm;0Yhh#2>E)&A&=eFm5_+3ASi{%$h3$m~3iJXU+c! zwnS@42%?22thDLVX+em^^N#?WRRAn9JzrwapN3dGwt^n1O00xv)dvzii-uNGBV5t5M47Rr1c#k$d)UA!zKPtUTT4`&9RfFpxi~_E zpDX!iMg8Yq{u!?S#64soYJ~n%x0~P`4P?XFgi=ZW**O#fmGz&npM@0p3o}Dxjoca zkluo13bIU)-GZDK%$TC5WKjs~Ws(58*5B*qGt>PMK(_b3MbDP2J+wPUt>((bdxacF_QEE0 z!;7<;TF%uJPZ*jQ8`O2IEG1V{ovu~}#-+wa^*uDCnjY<$)sO@0Ek4Hqrsp1?xFbVx`+1Fb*;mNYo;I{3Fd+7>MN-KK{eFK(hX3{ z!`6%V+B%Ntk~(V0gw(&ACUYRCHH2J)^|Zc*rS)D1;CdNAf~jB>E=VBPMa44s$HH?X z$h2Nh6Jjlc*=`0J1L(M(ez5}4HPI}a0C;shn&k<(x$*5Mn~_b^HMbR*lyQk-jQry` z+_L%}tkU;ussR$r#roBX730(Z`J4$Q!zIBk+$RnmelodhmnM!uCgDrC{5y(?BgR<5_U3Sq83Q4d4ORy{rc6Kncb?4koW5 zLJ{^k{`Nw@A-8%%=z=*;4`m?)q?MCJC~*LV;;bgwpk8wY&r)njY=hFGC)N zv*j}?ZmEMSO1XJloY6%I(v5k!o*MvrDf&_zDY+E&imN5b&7?7UQR8TIqN{yjp zwyq?YIyHv)=LWKYk?q-(-x%Vj3}&4s$ZFW0#D~Rwn?U}t0qp`L*>dP;6UbM{5$cng zLLL?(A)nS1^34tCFdzwbp9@VPKipt;O@RDpQ$9NZ@(T>;93TmXnmY-Qck9d$N=;Nt z$oZ!HyhO;KGvse2LY|E(iIBIyE#fn}8JMt>AkR>e%^+UQK%OuH`-gvXh<7rWxy=!s zSKl_Gzo|Lo#~6?^3G%R6R7isS5`(!AOvg&y++fESr1swE%nOp>>%1XQz6E^2%n;iG zzPzT0NUZ@=_Mc*eQrH6W)u+(WPq8&uqb14=hJYq5A>Y}M-`W!LJxuwFEg_F(yk4A* zT0uXS?j2g8PGF@js^iz-%2<=r8@I6ueYX{=)^+G?jjDx3wy0XUtx>hGqSmY8uGUb4 zRWvI6K&elz(A}vGw4~-5@{`)2!edD+Lf8sS!s0i-E%NnZ8w9W)Yw)%R;5*a9=(g~H z#jNnKp)EXM*$NK>rK(d!2np>FLd~g02*cXJ!%J}KO==BeE#T7AP}mMZWMWB{j3BV0 z6loZc3?H*iA4`)F1Qv`NlM%!TBZ#>6P=ke_@X)J05`D>l7BX}V&`DG0)Tk5Wu~6#J3G!GH>0y2irsJHx!s1?OeuM+pk9Jb4$Pb`H&yqTw;SI~43fxEa z?F@xj>gaxVF;Z_j9qp{vlbcL8s|<^jFp1$Q1A+J5NiTdn;7ZW>EzQDNx(E;7tQVpQB3WH=!UM)-2g5< z@>hUKt!9YG2XsSZFh$pW4eJJE!VJplhRDBd$`^twW4C%=ajHB7A_ zfo^=@y)$pPnt?4{{iVPe!_~m(8IY;=(6~=)z{ut)!}?=ZF1xZZFM5RIdZlraPsi!A zF)F@Tn2N{9&WypWDi;S!xTbWIhKsD(d3OYyE7)0XESw3`AXlG%#f=2eb*zdbhRhqs zJlqkf(fSdpziOyv`1A<16i(n=$LVXT`W9}v4j8Ehf>C)SCP-(g#Yi=h4l{rBNHrkz ztmPEps38MVhoy*Pk~}LsODjiWZgrM+3$N!#sx6Eir|A@(hIP_Rq&ne|NHwL*faPUm znrD$U9UpW+W)@^xnKH{}z{LAEnV@vYyaSmIrp%=oFgW~8WT@-fZP(`hDT0_Q@ezaeAm+N0|mLxvBc&7&~=9dy}qS>klEkHU2A zUC0i7L@}dOa~pa(jR)YwDFQ9s3@CaQBGYb^CE-Qv8D~(magQi?w8is~(eRApC)#Aw z^JlXV%dbYOE@|>3e4?S2aV#+)T=z3kEtNM$t>?+~#$%xOJ$SGFmil@YnD)Wo)4X1mt1SGdHKQzRnOV**_IR>Iu0>OL)g4}DEF6fX&Pks)ap6Dv>~!& zw87?hV`HAZeh06#2^G`zfdQHaVb0MJ_;IbZu=$wCIkJz#!er9Z;t;sjo}-1)d82Z;!k~X~lfiDWxu^jq}wqt_6$5i6&l5BVTNl zJrms#=FCFF-lhgNj;9sKWv@uUbork3n&Rh@zYY=tZMwr64&lbWmC@zVM5p zOM+#8PZtOWp&4)BxLxvlYPsm9h9YyNk3;QxEI1~7x0l(3qG-;0FyKV-2l=IRO9!`( zDBNJ6w!^n1ehb-xg9x@=F4Kp;zO4+aYaN;jM5_;^-E!KvP>pi6!<(~Q)40ZQJLCv&p3VYiozn)*Y+0QtfdNNF4ALgXc1!20O1f~F!`3$ zn>yv8#y13K8^=kn@p;eymnVGIFqu}q;~hqi?qTri1z~=ey4Zb(@U4baYl%Bzu^MHUIZO0q@qi_mT#4k{@$Jvb z|6-y(Z;854qUGYA-n0)?McTI9J@y0jtlfcN5mCGCWhx5ACwXbh)Ht6lYOoSjT9E_zk-kJ}C117DtY7##dK-9QHDL z@*ylv2_9n^z9C$pgQmp{x2ang^P*H-rEXztVn()wQOJxH7RFs>6j&HArFqju!3eFQ zhUBf(18j_+R8joy&A$`G?@a#PSNvYazq7^f-TZrn_>7_?^kW`-3nm1lB@sjjh?LIM{2Y- z7*%c}?gIEojgUb5eC^Yc(zf^py6?8oa8A48Cu)6s8jy1kX{$O#u7$I(ieyYk3qDbC zxitLm4yUu9s1;nh!^Jfk<}4vmSabPcXCkF!<0*0dnjm~#kd2oa`>s_3TvH>27aoIo z_yo3AjdXl%vgy)in1E)sQ*cxMM!dapZmn8QEn<{HH*y}g^zx>1>!9hm;e|V1ZYhbL zju#KOuYhvW$C#6gNzO{9OC=d0Cl%9_9 zTU)O-v=64l_2>eJBG~~^G<3Zh>k5b}P6MQI7tOl$$gXi)ps8@ZXM7(_j!)t9P54|L zMYTTl?57Q;sSFGQuqTQ(eyYYq?=e(zf6XeJ+l%}0(ed$~dv}|YeFG-TVgfOk+HXJ~ zHynCKS5c_r0<|>F-hfU7E>9=IBM{ynWy?8F(vpOgoxjyf5>|Ges3i$2JKIr{_@$2! z{qA_YImK3Xwx1^Piyt9sDg9^oee`@wKZ992iJ$%mQTaeO6mySpYAXuuKFSc7Vtu@J#ps_;+WTf^NLkJg45~Xa!%<5=#ajbbz#B(Z85M=e4(q9Z|Tu8VMWFuyL zeX11~23M#g`=TYzV5;~zj})^Seq=3LwN;IB zj5Oqj&@>jBeyBrPUt*5+1Li1Zz2$iP?P{;V^ceD9 zZ$bWEU4@#SMNidehw2Q0%c#1tt3JN)JcEDV!8c2N=yC?pq#bCR-@2T*(;yy?mfUqZ z6{=qf&ZW6_Z`!p3@tjF6KPO(F+o8r7cNq*Ozn!Qv;}G0FOkp`%v}^&69dzC4+58_& zIgruDL#C)6t>0#JO$Odq=KGn)sWARPby2I$@C*@l@_-!nd1EELt=|a9Gyvln3yba)Sed@5s zk{^o!l$ZjbEGE00nYKYA>G)E=Pz;YS&fMCgI{i$Dvq<@Wl)VX@&E@<5f6kei_xpVq z(;UlK#$XIW2;qZlBZRD3LbkE*dka~PNQhyC3&|ELS+ktTo+KgKJ}MOzAw(r@^nYIO zW#;&NKi}`;|MU4wulKpH>%Q*&zOVbbH@R_wVUOqLE&HB7`Sk?0m=Tw`hrGGmK8;S_ zTr&1kNt?@r{dA(U(3n-M_FpgDl)V=rU_V(%3vA%?=XB zN2KpT8mw~<)d1OWkjP9Upw%wB_!rU{MVU(mNa=To%=7RZBr@-0Pmu>mmJ+5z`0zpD zB`a_5)d2Ayf-nO@VjU@eC@SlpP{K?IRqDvHLvfX2s?>><^xM1V@ zc(yEf{ZXxV@$v#*xS_GvyHSC>u7p_-%zE-sG@VggwNKk zayqT|;g8RRf1k@Ir$qM@ycZV=dQR@f?3(XI)x44K5zZX^eNtbRycZR-a}eU^LbzPt z30Tq>A@IS(YGJ5& zC?78?VF85J>2mm}8dlS}r|eI&u*84BZcnd-(m#N0A#6{k%b*Wnd(vau9L;uK*#x#3 z>5_0PD*O(|AS{BgJY6Op!{!UFJBF&}1#nv#7Q;}dp_Dlu<#Xt92umOgZYT?n(`yfI z=wzZddbE(^$Eox!l*-HayzTms^q2D7D?MH_;$+cBMA~y#NgAd9V*pF}7+K4ZwXKO;!n0qZgol3| zrER?okFgw{Z<@&AkBR9wF0aa014}E%z|u-m)y~pN(m%mwdBJ7!I@ng4wG5xr{IN3k z6K--HAba35Rvy zf5#;j@tkz^_b98l68!#%g37X(!J@2pwtX$jF}G$)3*{yB~6L@2Ah> z?$7pH`V0K7!SBs>(&`KPm7A_#EjKNIwmR|__qXK+RIKW4<=ro|+$LcEy8Z=o=d${h z_$5=EHSKc()$(X7)xV7M9;+N6W4|P`))LTLE}u+(IZsi|tXMhnWn6p=?o$7Cf9q_8 ztl}9I&l9NUUqWd;)Bk|GqohAVJd;}GQa)eq^O03&;%bz_z_8#8qhDZ8YNVmxm>3gu zX3l=!iwn*%)Sijui3g^}<>QPRL1zZ+_idLOvDk6P#~FPBWA2T78)qb#!P-?cC4NpH zw=Iar_&i40pfla_`|?Yb^~^`xiFL1(_<=laZ%$%MM%9-~1p)z;v%L;d?6JXe1p zQY4Wp$^sug5GfxrFdm}Fch75F4*Xm_(mWrRyaf){kXHGPE-^Q1ka5+xK;%$AiBYcl9VrlKbgU16t+(W7~&DmRt$1kE7`kow=`;)bL(1Vw2feWz zZ(`(oIMSrN@n;~IZg(2(Rw47ho8L4gTk|F8nwL@b1W&v+IHrJ-tGSZBCQ1XnG zF16Tm>g+?VBMX#JA42J|vbPp{H$B2_B{YCgcdV4D9pxjVHiUEt1IEhC+D5Us0b^;Z zlG2gew+_`d3WY}MZ({GM8r}6eIq#}GqVgdA8{&U4QF+iPmby5bKPEJQerq#-`e;VB zyK}-bzH&@ecV1IR&Z`iNW=3SJB-Amy*+3oXPzM4gB;(vznOMgt89L`m_jHvWvIUmV zMy1>Ev;vC3OY&j`-(YRy%Ouwct}zA z`ZVx!V@l6rA_wNi0rSqeEBnV5fI;MRL+$2MuuxtcE5v-Ffcpc z@imy-xI>ifa-Zj6b`F#5%=wPzrZV-QR=Z5O(a31&j)C7vH+ zyMXjKl&f*JsrrcDKgYfZDo!iJOkMOav(>JSK&hjlBu!Nc##Y2l+XHRjO zBk4_zWMrM%87!Dm0{w)uB)+E+5Q*Z{(Q}SuHKn5Li;}CO@fEQzJg~UKC9g z-Z^r!siBtlcFl}(@fWn*IykYC^cBo>UukB9LY|Wj?`n&kYbT2hQLO&Wm67AnQY*AV z_){Z#jLPWasN~w5=1OXFmfPn_Iv_`2ks-~wFmbL-Zcd8ka(kb_D+Z*d5vnoI)%j+) zfonrlMQkqb4Ur`aU1!Y_&CI#tf5aAGXUSQLXA#EJ{DiqHic{^WbEWMgWXZcxa#agQ zfL=nm^bsR5bcrXKG`1>SmCm`Eiv?4b;=LxkJb~r=)n(CWskM5p+<1g&{T<~~E!U*C zh4HV@cHiEyH>48w+0qV!0CNMnAHAo`m|_z}5$zabLmpnFHDyd1OLY!;}WCNcFzQ zb0VpgWS%}DUOaI9amj4U$g~t5q-%+n=|pB+5*e zBz;V{E%o%O%jdPQ`SNmGBi-$(k=quzSCLz)uOvK5hL`G_lUJIC1(N?d3nf^z1C^>}2g5VpQ(DlB8+boF zK-P6IyfcI6<)#vThVbzKDb|r({dho5X=zhkB*lSRkI^zS2j44pR4nuuCsFM2(U;(os5TR2c0{SlwU~7+ClPcCk8%nV<#giux*eW?qpOATpYwz z?_l1+QmM1iBD-cy?o4_8ipSK!PKZ+F6)a!xbT&doJSUy}9pci1vRM5G5Ni3sa_4bc zP?10nQUluvDBOXSpS;}LRW&Etf@{y(GlP&x6qQ7HhH z?@o*hbw#y$aj270ji7paNz%JgKucU_FCH&xJXG4AuC(@BNUJss{b5I3O7%lr6FHrQ z0$u*V(N)x9LO$H4@|PLquHyLle=Uogmz~`Rf}Li@5hsWwF7?V|$UohTP&u4(0^s=1 zRQ?7c&~x_!c-dKZc{zLCWqL0v=hNMd5}|6tJrRzL;pMxFMD(JVyB_$@uua@qj9ReE_b%h>G399xlhtQ-n87g&9;Q?YCjs6YJb{W z=t|n3_Kmh_&Zq9uDrJA#Tj@$WpCi~+SH}Jf4KNA@YZEvnM=+^}gO#OXFC$;Dog1+t za$_JBuWK(OQEK*O>E~&_{L5uVFC#f+c~l?CrBTk?fC$t6b2(Qd(h)3|uN?Tpfsu2K zf^ph>Nl0&--m*7+=yFLPN#{MjH(7fBsGJg04Pd#GrR$aUFPEkTuS5TG8M%$Q{F&Y~ zzIjnJ9sifhZ6}1nee8g$_c7A)Od9P7*X}b>MotZ+$hEAvTr#VVkw5g~6FDJkX)c#7 zedu{AKIu4Xpt`obTrN2h8ztvG%$)N$G2c*Uf<~OGwzq{YX>iu{kl)`&pOYU3*9NqdxsfeHuSjmh_|cj(7Q0 zmiDwOqLh&pjxw^sQASqS6^ZL^(Hd89#Xc!n;XFO4dA>sLMOGI!VmkW(kmR_W(%PeX zCxQmpJXNSf(rGX)Zu|!R)04%K(2l5xYfrdB(kJQmCuo5M<7C%hdZhK$=*{*k_tJ4W zIirT1>jsv5{#l=ea8^V1P<={Z0Oz^&mj)*eiA4-MYJcNnM zh^YYo@6%+dPKA-RV3O-+N;sSliXcAfUIYz?N$*RwOaZP zL)-uNzOb zk+&JW=L~0xPR*`a=a{$@qIFebJ3okJ@_$V@$+(~TzJB$6ngppIoJ(PA|ehEpJ&Qv zPa2itK35U{C9G~w!Dzr(VvbCE%BUJDG3Wm^iEW=ogo%i*b7b7pgw<6={Fku&W628( z#wl(Xa_Uv=3y+L7LV+oBr2AMSDfG8X^2+Ho*)x{ruyicrQqQ?g)Rd;VZ_`v6j~hn} zf(YI)S1OG|+4d$fla-JQLP{2I2^iinhV$}=5^_Umoh2ooi6V@A20}c9$yu@_ns5n1 z{yY%2W;wC&wHcBzY*^n>QhBVuMs|qZ#*@Yb*tWTB()M)@hP*PKG;Yh1B9rO3{+EUP z^O8D&!0*9x!aQj{f%=v(FQ+iHOIc@cBlfS842&nTe**p8IyIyejMFBtPUp92p+c@F ztwi6rx4d{;VS6hmm%>KDax1d^#DuQb!*Ww!Eq7REv)!GD+%0S9WC|=F zvc7cLWWqWsWn{7uO7)zy?|BPpz6L&D58&YiZdS;tp1d>m_hbfD#|C>|sy|EI@+0rn z1=9UlCWhd$8AcOXQHI?xtf8P(FPwv!X1((&XyO#3vMT9Q@KykCUMOfkymS;iyPTKny;S4O@->$u)KXh~&Nsx~<4)&@u2+7P8~ZLrlX8S?@I#F44k zOgHHCrGQ+XY9!>1U*yR2TGj@iG(Q+u1fJ5*(Vx$YB5RG>Al;s$zHE@O&)NOtf#-;0 zLE>mEk;~6TwWeCrAQXboW{H+>K^e<{A8fP44b3r;ub)Qtd41n`_3<)OqpA3KKB_5a zJP)BTq82QXna|TvEpVlHlc3phfTM5Og7QpFIPcp40y#xYi83Cgb&t=k>;Vmdjt5fePR`d3AoHa~ti(|8X1bc_}cH_!ULW zrkAAN%qS&uvJz4tTzpB^&5WuEH*;qq#08Sn_^KmLYLTZ$}m!*)A@&9ZVf z)Bj?wvsdRfd&Y#6Oazxi@T_IhB$N5-ESFPrRr|Ru&g^)Lqz7{q_ivG%nMU#8LXSz( z=aa%;Gwr!=^*P8&LspaJ(tS=;X0A~}DF~gH%ZWKr*&mvVWuP>K5z7OzX-7=qltQhT z8}P@y3qBm}#;1|yr|(T+Zkg-{_OfQ}RpL{~h%bYTS6p_<+LWj0!pF^=+-sIaF!#dp zF2Ow5&;PINeBA=YC=2DIU6XXe7qjPEt{5)FtL)eNaj`|yy>gt*@Z@#JkwX@WNw^@FF6$!_ih(IN!FB zhuIY@EEKS5#Bo+D&%(tvw_16mg!9b=o#PVjH?wr<>3lOyXP2e(jULWrDvKFncF3B= zM)3kWqLQ33s&58?v39s+rIx{B7LfP9BCS?3b1u2WNWxF8B`EMaq_YEKfx>r57&68l z`&2dAAs9N8`P35fZHHWSfOnJf#pSl?yq#1~Wxhn#M@tzptbd<@{rcIGbb)4vjC{$K zl;yw{2Tr}j6GuDbX7;Z_QgNwq4^DNLvOp9qvG?#NhK)gz7EzKT5f(USETzJ)UF#Hx znt;>{vqN?+wMBpBfd6HixA4nG@p2tsb$C^h+UKG}$#~icL5+1gBm-Y}Wlk@bT-+vS z{U=$oUORLM57zEr`6O3nDze zvyz7XmM+%ji+=Ie8Z|;qH#?Fvv06*smTqgQZEve@XIjH&w1iV@kx&~6CAY|*YmM4*CAT0!&aGo+ zg(gHjdX+-hEq!05*)32SQoXF)?U;dHdzCW$Ad03nYPa)@&zVp8c9pCA-qRt6X*9Dz{axy=K%4fN*&mb6E>}9frCvdRdQM*H?sas^y-qK#ZHTMRvS$_Cfkt<2PxfG> z6OYpg-d@MZsV`cs#y?br)c9H7&H?^`vE}<+NW8>|>g~(etWwVHXE2(L@$wd1Uhf^X8fdZy-c5%?#DO@foDzl!!pfh@xpzIxKY~G{GsZvzP0KHP?GkjZZ-} z9wxq54#=Moqju=Z0VjMflJ7Z@e9w6u^F3YB=T!4s)ZX{(Wqsh?w}|(@4&EK__nf60 zYbTL9?9#jlBSrJCj?zv?`O}hpPde|U?e}^orxdiB*j~~?V_av=9ZepA@3iYdXcy^d zN;>i$lG?kNbLKsilMa=8L`IJ1(z$87jD(;^OOm$1+^qWS!mM2=ieGEm5&3kNy_i(` zZ90_Y*dbaS3PkTl*8Oq(-}f`jP5J9xK@!&a*&2n$H@QOO^4ms{qCqy4QE&aeb3Ee2 zHrW!VjivrT?+%f@pJTHPuzBe48RMfs%Px^6Ul~sZ0_@4jd)8PLoYlke_M)szqE9|~ z)|ekC-ZRqg9HV`JoifY5XNO*?zL6T|jd}h+YCk!8fla6E0x9x?aX3)1f8^UAj9&iW zVS9H*_Ws(Qm(bNe9uS#$iP2E^JM8+A%{r-rW$hIrv3hW1+*PBaKiGSy6Zk1f{ei%* zTr<`OstuDRKN**U&Jwzx>kw?(itEr=18;SMU@MJ?B>ik8#RbNXja0g2eBqBNHZdR{ zE@B&UsXvUe0oL4F{bBTT*UkLCj?UKMlYba&9d=f({JslvAeq;$M*Kz73fvAyCjM>g z4FtwK7peD;kq{f`HY?I9#;oTLV9?KuHMtHgQ!dAv69ZV<`OQ^)ab|;{Z7V0&dCWMC ziRalkvr_=`xXsYsfWbC!!*H*(tws_z8)mhjW7GC?a%#&%vH5nGyu=*99Gzg9tpZq| zyIba{0LEsJw*V|8Vqms^^bDGvVlXPp@FWg-eG)VigO2Uk@9QENj|cND%w0+vhz%g>=aJNYg0nw?yeo!?i@4t0NCLRAA@KC?#9 zvBUX&$u_BHK1i6{HY&-nq`9Pp`JtTQYLWcr#sEgIJNd~OY+S7hm}<(3j4NO^_XlHa zBa+|O)7fi%Hp%Q0bc|4b-$KW&XF=Q?V-tJyotkvEpt(MPy(qJgxhmMiwz~Lz`JBzn zEee}ugPmQsg1T`zzho6QlLI4`%f`ZHzo28K@$=%9y>GvA5wmRI-R07yh}k9hk?XIb zv*Gz<5tC~Qm$UzzeV?yi(?i<-LvSPzz^n1=&x zUy1Z9X67{l%#y~HBHNkYTq|WR3^41MR@(e6zyx7p8OqO5>ixb?o$})fmsN7sjlzL}~IS`JyaU9EH0}IdfsqR+p)~+~!h% zrV?M?tn63iw%&c_OjTdOBJ%xx=7^YF+X6DDAeC}N1w=b~sNeUOvyXg#1sZ~*6Z(C_ zoCp=INXa-lp5OPh(>|A0G-;oXa^&~jc5CDP=KR24k;q5)oBd(}nY$ykA25gc1DE#7 zx@y!4#?n8l5mjfz(+(*80iwFTy4l_zbVeABe|qO&zDUu3ne>Tt+q-I#o2?E-D%CQ7 zjx{#L`Hb1eq)a`tSj_BWoXNXs?Oa%&wsqu~9@1b&;257P)HfTl^>uiCvz)ORKkbgo zvifGpP`l#}n~q~TQm_M8kF(6tQ*8>9onKWNnEILhY({86o0=mt9QW6O(Ay{6 z5D}$A$sGB-f%%Yslcc1ZX~q@;U4K%Vq?;w<)}MsaSvZ@TZh8xXo8$nD@o&NybIK7V zsXJMt$lcHkg*+#3z-6bco_K9D(Qj|e)iZcu9d6lht2ZX-D$-o%9tCF;?14U<{vI*N z%rB=Knu)MoYG@{>%=P>1*%;iu;Y0e27|zRV8iMKzY;k>vR1?rcW?J4GpXQ`aN7}i5 zsrT;yXIDQ97^HD0Jn>tJx^>!(x_x{wcO#*NAI$ zvYd$Pc9<;t0ti_&j9qZ||LTvEvyI68-NVfM3ma1cS(2x*nHJjpc~0cC&sXVq;rp;@w_v3Y+e@q7-qR)s9NijcT8br$~!p3<$*#4KbEaM+~y z2s26Y3<~77_k5F(CWwALN`@|;Wr=?f+fw&8F=J)X2(33w%>1DWlujL}mpyLTGJ^EQ z58|}jCnL;6o2zgbuBvc7cp)cV@wUvi51YwSVWcB2UglanxO@5;e>KWs&%@NUZInZY zALPQrRPYWzIKDOWwN}oPtnRs!Su)m7`!pu=F)L0JJWor2O48I!3}v|9H0vO#x2ELi zAlKPbJLl;GjBNXOE0+eIrx}57C-66akQ&X*O6A_nW{(NA$56L|zqcu%8y9nuq|$rK z>}KY}NcdDG>_Ect%W|igSvBtXWzGFiK8|lJUBxBpjumGUi=i+^VEoBuEG9>qoB0F$ z_`1276iWWlk+0EI`7cV`BWCeH>W^}5j9EzPJz^#me$k&(_51YgZ_gPtS6-B%kC=~W zm41XO{T4y+N|)W0$l_fXK_(40@0DwZ{aWj5wSZ+OEOA#{mUFxEl+XnLk7GL=#x6Me zT#>I^m~CA1|0b#462jXM&Rmi1Eu#qAm9QJaeOKk{mS&B(`>y`?Ea=+`#yv2$yegTk zOmES9lY9jselLWG`Xot`zMIL#1Fg+aisz(@H`U0Ssr-Ek%LO|Sdym4?t<46S{MJa> zhm>R2Tq&n^=P4}yHfF&%+v&fQ%D^`G*^i%VQGSYw6_d+b5!oc?;4u!s)9EM4)t2;i z`su%?FRLw#2Vordlk9@A+&E<oQYya!Ll4KKcX zu^c_rf&SHV(k4!JaM-SI2l^u3EOWEVF)z-KzI=glK%#L3iIabpTpi6~!O1^6{M^WR zS+_kt8L*^9N7Fk;x=AKU&%HK7+5| zt>_5+55AGz$c%r(*VN^cjDuvxU9!%@W1NO(>@7*?PVSC%dH-APW_5@8bC~zvl3mKY z|NmgF+XLn=U^ai3em!6|e|KX0-y~mxIsQwS2fIwt_MN*HX*WqmPvo6}W%cj8?`V4G z^)|8X!%Q>3g7DGrvGQRZ_VX6X$X?vtB#krh_ci2eTnY&x^_m-m_E1yPe7m}TmC>lfg0$>j2>AvfaeqqrUQylnSP1cFA(Z^n@hvkBp$&fcRdjPx&*$K&|ECn` z9p!moZ#;hsp{wUP`0jstJ_nES9Xwvd;8yk5lX$=mX6zo_Vx?hoOTM(4J)>K{eOQo>~jXK%}{Xu@qJ z{0QOVZ7DM#%E!O~W?KF$5U#t?qDfZk(Xv@988HWa#Mvc*;sTp-6}I1R%bjTd=>s8L zgW$U(g9b(k-k^k^AXs<0(7Y0QYRmH&&eugmqj&vLxrC)4-5dRB=UtO`X=SZGX3x`D2>xx70`ztK{{*jJD zqH5I|CESGY^*?fAi0N&>+a#$&5&9d1jy~tn3CVgNT`B5b;!Uy=9`hDFC%7KQSt-b3(b|Bs|QF4|(odoAlN|Y6>@y>*=;yuWG^>BRda1kNitCM?Ok@llaZ(oBFBd_3lh2NK%Nn{ zyWrInwq@{FwVW-$W9#tMjem?d$Sv>E4;QO%fbMZvR1U zKNREU_Q<1j4XW2>SLeyf^CvuSdpui|=YvtG8=jLEh9-EC76zvfTC*j>8g0f0Pq}{R zjjvN*uY4G51?`m)hj}!**&^vX+AN;3$e*KwGyNROsuiJrTcgRxMY6{Md!lh= zG*%2|)MKbhe-XWVM>@1^KYCRu;424KzGtNua;8<9qn@q$Zz41MSfu0ACO0IsJ09sW z)_gV)z=HAhGuZWFPDL`un>%6y*6B!-$!4Y%bmp0UUpG0mhVrdWPo4|aD`Wm?QOrw5%mRkqu8+ycy^ zTCGRW{7il@b1F86$S_etdcy$opuGzqR+x)#XQHDIxn#77%@;X2*Bs&x9J?m<=D~UG zn!~wt9%7h>*pX}SBKE*>KSc(;s0O`e*B#gO^Kl(~-QmAJAO25W%KQaTZrPMofs7lG zUJK1H`~kG-dW*2Iod6fBg>4bW+JEdHqk@%fz1Hum?3}1Swivrz&tK%)5*Vv3G2aU0 z`c;2?6hI-h9nZXEz7=#7PBjysTY;T=^HQ@<00pzsN_BoapQ9FH;&j}Oshgt$X1f(#j+>+IsaxtxvH4}_ za`ORKty434+cUZI%bw-tW3Kk5ZYyU}o|RW%`$kEVdzy2&Wc3Piaq#aN%~ksQSh zF{f|GI#+gAevJ^&6qXCXg}Pq9Eqm4Vch5EPbzB+cE4_}Zb;p$uR#!&yWv^p_ ze$*avb@9M{Sf#`|lRG-@I8}Q5I%=&mCi{J(oOV#+4RVS>*sk-3^alekKUT#s&Pwa` zdjHr4b9#)9sP?bT`is#r^590ZRv?BR-f^G18FxDFNb(jl!yjXJn{S#eW9T0vAHHd> zteh*eCJml{NzEeTzBAVbj1jD5wLU0iE|}#*t(k^9GjC^xc}y}cn6=!?*c-v<^%`o` zf|=8tEax1%Km%FYJn|bN{H(kAjGY-$=Av0L0Jhrb?;@)&nuDC{LCP7WpnsAf^)8vk z0$}$`W>Vmb4B2?XU&KE~{QLY>tjUSmdvbN!(Mx7Yqck2W_L843nKdm(4TDnkGL$k< z9_%e$E}M;VC~K8+FO>eh<-}c-B0riX&Cf|iW^b}9=OQ7Eadg6nb>@#|!%_G0Bg7f^+h^r)?pq5<4^sR!2ABp8w?(rwa6J-xX>oiN;BHP z^)V+d60I^ZA7^o2$*cYr_4~Ez~M10M(BA%B4(}!b{}0664A)AaH3}RE?Ryv243QHs-gy z`DYussf6|rI*Sx5K=eCHPW08j+)qzKaXEhhE7spn51_H#pnzrZ%@GfFMvz^hA+8@! z$AxcVY;poGJNgol!R2Et9!kApRuPF$vI-dqXk~t%BowofLZkZ*>B}w0_P#1r$_OvX zDjrB!B$t(c7W^TH-{H~y3jOpH7&px(5q309bHk?bqSTZ??81UpHEu1dUXUbqAc;j5 zN%w-5XEJFcuPdP=gfffdqi8}(AuBEZF$h)dh@uYvrx~h^WWi%}f~Vdh*;Ob?YFuF} zO~OU2*g*3|QmJqhWh@k<3tl=dl2wJH3gMCx9*59tk>o8B<)d2>2wfozTO`wpSe^m4 zjeM$vZV<*Tk~>ALVxe(vOtsdjF33|X-?6;ZUs@(pWnOiuy6ZygW`CKSOoi$%DSg@h zv_F~1_V-EVv_KN~>7|yW7G6*0!tke4X$$d1sgM07wJ7zmztnZ0b5Y7@_Y!Gdk}|Sp zvZ}D6sFfIO@{&_|l4P<9xvL7sr4Z%rM0vqWQYnR+w!mffqCCLeS)4*m8{lkCvhRGv zos%xI-*IP$l5+eh1xzPJ+=E)oDu`R?Ici4bV$_W9yvUGfU6+9WDXv*;#Npqi zEC=Z%uFp~@zB+f%%E!gN#jN{73teZg2@jA1#jJZnJ6&h3=DI+|#iCD=$~I%ISV=5y z$NJm^%Xw}>t0EWo7ROubWp1Y6ONZKnbN%MaD--(X1Hg?B(f76$pJ0Mbm^224rj|gER zk6+lQN7pOE&M411g(Wse*kj(HXP`1Izd#yUl|fcDUM2O?qMFZaCG>*ObCv8!v&zTx zT;-QHj>U0jbk23h^ckZqORnomwRJ(i~LVOlFeh?O|l3me+xH1s>Ls-2^DwT=yF;)qgI+CuERx|z8+-nGR@bt8Y zrX>Ea8FHeDp{8Uxn7L?S;=C1Pum5NQB|yE{-D#_ z``LxqHXr*>Dm-9a4A4!ssz$S}T+J#PpljqujX+h`afLe4jszc~(=ZSExLe$~Yhd3k8I8#Fcc82`Wo9F*WN5XSQADI@sP>Kr3mnp)nz@ZHj~F%l0Uv6LlGHm1`qWjPYHpV6i0T2iHI z3_V?A+Ep!StKVmxZ+bu;AZct_2@Iy$;SBZ3#Aa5Klx<``6?@*p}AdVS18UlKy+{ ze713@mSj9^6)YSrE@QOw+?g)3*ODy9^M;45v;b*s-i+FGfL;otu(B?~*^&66M*ZR>@$sL??e3PAbwR6l!dF%d@+=X$-|w%x2kGO#0;Wz@BQkL*VO zzM`X5BGk$iY}aR7+9|vR$9Un%mTn9-iH}*0{EeliOV z3<-5+^Z^FYtyC_4s zHd%9@+{n%ID3!Zgu_@6a`VAbVU8CJMs@6f$yQAW0?dl~%yIZ``LIGgo^7WgTQ`V|= zlZ#y9mNFGz4Pe;~%N&m;4s8OWP*$Yz>ey%L=m3H~HMrsEg&EIoiK3)FoX*H_sbguu&cv^Fgf81=H{qGTc z<(LAny{#htfb~q|Xdi2>zc2@i++M<; z-J3jwzsivr{j6vGlfpc}>BA5o=9M|$9iQ)o+*H{-Tt++$OaR%K!)bxa3wZ${nwtqzlpT|D~CUAe&s>! z{O$v__o)C@04sw30xN+H!TZ6MU}dlqSOx42Rt1NF4}fFAYTzWWCi~38bNHx(!&LnxDiMz2)6;L>fxRsl{Y*D zq&kL4uMb)n+lsHPf08f!Djyh{!h1nXIpL!qmYeVwAclzWHLx>y2kZhCpcy|7rh;9; zDj%nh0J2}%HxT52o^Q}3KHlMDF!&)zEW_V`L%|=x zVIcS0_(u7C&vNgG?+Jc$Zr%4J$Wch&Qy_1RikI3i4tokwUV5;5MB3I$!$8ax+ z`*ARjuYoV<%VnQNsf^nNnC>~3yShvtZauAr;$!}WYyBn6tsIf5#|+7S`*P|C%&XgQ z>59wpk7Annx5}jvR$7_uxK-c^3#v5DxA&Ogqnx4YIzLxa?Q{UBkRq9dW7ev{c)YY9 zWz9rM{$`X_&e(zHS}Bq++VVDlZI_m#(NH50YNyDPqnU%%cBL1iH&=D-f-?sj@f^FJ zFSv8C(ags#I94cqu5z>&G~}<^Mq{K97>$ zX{_4#ordl{#;zX z9?MKGJPvB&hr!BRKXBY*-sg;x;{ma7o8w0lkuDR)4sb> z2`5NZZZznNvhpd+Q#)K|jR~zCXJXd5>#wrx20bg=Vi6uyD=sTBJL)SvSlx_L5*cMH4uV8GGA!9A8 z@TDkSbToOW>Cot0lG$U?`@ZBl5|ysb9O-_WbXO`R-;T3N2EbesD5fY&*LLar z3|zb6YF$d6ea0#u06R{yO3KM+NZ9E~B#}$ik&goVaQ2|MBi}*$I!ahmfBtE#Ho}$^^iflZoGu=Ly+1VqUS0nEor$c>?klxbnQ3 za77Qvv&$uzD;Aa;1Gvoc#FIt-rH_>WG3y7OU`u38(8)c-@ zB+>^Kn{rqBt~%+vDr?{k-osrkcHnYg3K3cw)Q3(efKVBaK**YrR~;+tuT!wpTN5dq z24VWCt4=yPg)zrZ_IyajR77?Cowr17!|U8I^5(cyO^Hs2kf(;%{Ysnf`E+vtsS~Yx zB{37b>UOCl%deG zFa*oVvgfQC()C$PLZi8d#;dy8POjZuJ>Gwop!O5gvU2kCvjhcRo@SLwj^T|$t^#9H zhBD>jA*}2Y^Go{kbZloQV_|-J3W+K15;dV(F@KUR)3Ac9S6crln)WL{$p#h>{6ERL zDah#gJZ6!^sqh_+;?v6WleWI%(gIqZzFdCeCBc-e=c8KRhN(pV0MXC7Pd=MU^uhAe zDScW~q0sNHN3CZn;JRdJs9kAkp}gFd;|bMBUw0xs7g}5=rAf2t)&p{V3Z@+Vk>ZqD z*Z@kuL1oi1M9R+OtLF1e)^CWPkpUnkY33VTb3-t)e5O?(dKGB9d=A-ohY&uf zBr|u$kP*{K><13N-Qb87Rx`vDkXF+z!~e5WB0tN}>9n(tTuv=ZO$he2>2wMvSJrsx z(%ky_?sOHHL8xetMxXno-VCc!sE^C9oxis5U+htTp^oRjID>u(=R4b8CSzu?CVYJc z+5LA;uoW>hpLvM1SP_{*TyL_s$ z-a}Si-VvIWy<)Lln$2c`m|5 zBy)|$S;c~7BX`zXNddaHNYd-ppa7jjg$eRl z`Qr%dCwT18{XOy~4vqphr&kY(exS~X&t;CkPB zKbvTjN3&&LL#uEkb{h*M@$ZmRE68BG=rX=x6My|3*1c|?)s1@ost$R!;waC|T1A2! z9tmq{y)P?wFliZ4Hga%>)!onTUM|5{9~b>14^JS!MM*V-(q@AcD;h}RC_f!R8|(xc zrdDBXQwL@83%R+m|2=Jc2`n=Y&?mq37@Mu5aZ|-iUf!sDPoRujzZ*%ndje_Zmk8!b zWP965amNf4y@_ZpqKOef>BcpCJK>d`*7yK%8MMo~9K@?lEAH$98}T-Ivb4EmzHQAj znEx4vHb|M>=u%*-?!kVtdAHS(S%6o`MdeKjV_bTjEL=uH1 zd##y4Cn((ym%fvYYYp~c4?=9_K5JFXyp60QGz=7uwAgQb;*Wm}p%G3}+J$@LtQPJ; z+MMU)^#g}EaY27`NG1SsoyB$aRbi6(!#}CqXF?F;Xs-`l7KToMR zB)1P*#e-kF!7%~(08M1bJLq-|-a(y8<|LuUL-}=_BG7l}V4COGX>KD~^A5G76Y<@! zO-{Un_5@!0z)F$j-E-%W5{DS#iypIT>Wxp8{f%VyA=o>^zH5iZ`F1Z1D z3TE(Q2ne;{bYOJc56g{~C{T$r*?MxAw0#go*TMF1^zo=h()Tct?LuU)MI`fZ_8hg5 z99P2Q5Q@Jgza3^3r8s8Im6)L<25pTZgrh9FdgwE$zC!97d+yr#7u_2*A~lh%kuJws zlBR-3)}FA~2)%1Zr2Hvsnm>5Wu12~e*51;2>?5l|p!i#ngpX}Y@6Jg1PplLEz*oEE z&rezC&i!_z>Sq?)gh@uiX&S!O}iyed`WKo0b!&==;3s-DlmE_ ztAVOF{L8Pk(f#))JkN}C#ui_@0mIeMU>~?78{*+tUXSig&httYef%*mi%_)6LVvK6 zZ~PgSgz`$3f*m8pMQg}+xU5Wf&|WDpm=;jPT*?i z%IBPd=oRPlUL<(ySnhQ1kR%Js8M2_1*{3|%O3 zY#p}CgAj(Ev+fJLIYIXJ$z3E*uP4UXik_BPJ~?oXrjt*;a$w}hK;hgE*fu83hi}`Jmqp7(|A70f`yLu`9w7%Y-#E#cv-&u(P>gU(rF~6cZf<>g%_soBtTBKV> z>V9u^pEPSb-qNux9|RkMr@%%&-}42jd8`M7)4j%EJAnOFac3?eFZK4gp$1pu( z758<;{YkJVI05VnVw<-4o&)>ydz$+jn=kLa)c1ukF8c;Uz*ejm+J-Un`dDz7{3keq z-+rpT1{4F1;dd^O<`Gt1XsmQTZ@m~ZhwAgwkeI@GC*q#RSH(88TKHcuUaox-EHY`D z?M|vdT^*bb>f-PWP?vXSg1Vsl0;sFE8eS^M`o`o3zkIcXK-DmcFas@ydoneJN) z>f+9;AerrZ9VD-O>wUgyhrw<9J_k~mVP;Hvr)5~jg9zvc-v;x8yTQ`nUi@jn;5WP+ zd=Grn&%Fmn_}GubQ5cfR;E(wIFYsfqIrs^vYb2k7ox#&``v+@q(5b$D-@j}{tK4@` zH9IeWY2Zb$9C#VLAG`uq2d~M7i&k2UR_dPyp>8Q!n)S^Ja{Y#t%WZ??R<`mvh95*JlJ94WZRN44lKG1@&!k^B4xNp9tg*-d`1Iek z1PArMbh^g3XJy&1R`~+z{_R=4j>gfG760wLhVXA^7pVOj0!|6JJym9$^u0-MN#|;u z{7EuzTEzn3#+%kb|7jWd8|gYNSq^M*;M8x{y}`oQonSbBJ}fSu{LcLzQsNc{mD);> zuXJl^(_0v39&;HrJ1BXIe&j8y1A}7yJ?ut5bBjTd&e`a8Lw>tum5k|jBOuHF2{yaO zish~V{!Zg(Ada{G3AXi*mv?_BvJ>&p;b*z_yH!55!_Q7cblB6iqptkb#LpkDdr1k6 zC4y{2FBPiB+hCd}8W+XSW%3`G8QT1s4m(LWiGQg1pzdL8#&w}XzC zmVeRbPu6U4`NaPNTHT9((dTh)Q?F7~|E{ei=P5C3h2f}WFo@;bkKH7jV! z_`kW})iG#{mkod8c?zCC@H|gY&$raG=k&jN?sgl`Q}KM;^SnnrM;(D4FQ39=JO|I6 zn{wxN_BK*ddyOR8R$;sxfX94|;fzayR8+6)(-*+uC`ycBY|D@rR;wU;2O3gPKoCE6kuoip*d=q>U#LjGw7oUR9@cR-- zR~$xB^GyKrP&aklC=9Z&9WDok`F{g&D%b*i4%EkSrh%hD#*sV};27kmyo~4jg4c9Y|_|i@_G44j`RD9X|$w z%fTnW6+|^WhmVywEC*MC%qQ)UV?Vf>-@1L^HIQT8_K0x{T*vR+28*a*L68w7%<&xG z2CyEu1?&XA2@U|af=`1w!b}Hsgjo*m(5!lc4;^A6;9KAcP=}Z=z&+qKkfA1g2iynd zHGRJQU~%vOct7|q_#k)~d=z{S>;)bHp9J3rr+|z|;TORZAQ%4mCVj}q4n9tThrv_e z7oZMVKY%)9-2!#Uim{v_s|ffxzsrDMfDOPe!8YI-un+hZI1>CCoD6;g&IZqdtHJNV zw=DAiJRe7JxB#93e*iCm7r{S39pw^(tRa9Uz-wSN@Fy@GybiVne+9dNH^GtMZ{TF` z7PtWX9b5(e0lo>|2KNTZ|2uqqio-wPd5|tK{0GR0A2xFNd;u^CG{BOe3DyG9jKa;p zAlMDe1r7ok9K++ld%$U6BDe&kiw&;>^MZT9eBcL@_&}uye+d=>e*g=EvANNAz(Qa$ zSQab_)(2C-7GN>3D_9a74WeU)r+}qE0Z~!HuYhI1t>C@jKCmqK8CU_F^erE{iRBNl z5*UnkHnF6D>?aAA2Qe&%YlGFnCSVP)C-^UL1XvTC3f2O%z}nzSupYPrtPk!18-O2y z>EL%@L*4xHD<2Qx5SIsy8B78jgZF|>z?$I0U^B2O*ad6`4hD5|%Xsh+a5mTiTn4rT zH-W9d{a|bG6sVhCz6INYzkrYG=9gHs1l{yf0BjGI0Xu;I0y~1bIqNa7GuR0n1a=0W z0lR>+z{kN=U{`Ph$jW&5EwDRy6zlS-|x=#bS>h8^8+1zj(i&*yx7+9&e`%NfkljpwFFt9-#Sq30NRRV~qxoj#Y_@DBXWIkzN9{Uolq zTqzjL&$qu2tFl*^p%zZ^|4%z1V+7tp`Gdtn=Ui#3>@a5GoSr{e*L03$=H?h%FwI~P zGs;Zm7+bJps0>557rKfmDCZEv=_Mw^@dbj3a-=X{Wef11i~4n}Z|->XT7Meb+W$Yw z?gBiDBYyb!?IpQn_Y%kfK_U7y>(HzO3$W8xq=yyor?=u3)_HU@txG-4%`AbRX@f$_@UR4 zcbuBbqcm4uPb}Hel9n9ix^gRV=RCh=_8q4C5>D!5_cl0is(RU(MJ8r3V4ND9ot-t{ z|9ciibFf`9GmGQnd{o$QomV)r9bNQ&*e*=Obb;(;d(A88m?zc4%Gu4 zKbi4We0yhB)hk@SF~m^&y>V(mdnezA4%aKQ#&beRZWfkxalASl${Jtf+RD3kWsSqE zCw))9Qs$qm4sG9@L zO%)r=Q{pzGb?@uVooagoTY0xUC7k%5XC9I7qVv`rzYjmtJ*o5&gIej>(-&5*_v4G z=i5Z-E$qj~rR<2(hikgE;pLsE*2@y|=@ad76H>0^labbnXf~RR$a@%i<=030NV?63 zjJ^f*aQoZ zub9&Qbmr2EsidhURjj@XR$o8)gve8QiAFKy`o@YURn+B@pqPB)(|QXEL8+b2>5`#o zwbMC^Nx#%i=fq--;;WwW$_q0ZuRcf@HeZY38E(E7!xJ`Ni{S~Iuf_0$&DUah!tz=S zdokMQ456_(F7UV?S=PRy9J|HTPZn=2B8r&NgF8%I}v375a^5I;bji_^2J z8y)mO#y@0Y^`^6Ks7$eXPS@`nt)E2Y4DWBwy-KW}jd(3%^{^c2=hL5G2ITmq#3l_% z8o%4Eiq!)PX4srI2g%^+r|H7ovCLUAdc3@_o|eq9y6=DH8{cQB87G4oC#a*IEh7Ca zdc}1a$QUz9uoNyN?WC6_^O_C1rgWlooX^g5ZBr{ck%L{^tO?}=B{S$_ee{qI^aW~W zIGf7SSr7gY&zsZxsQHZ?Rjej;^VF!$9NP<+?F44qnb}TAH(NPz_cfdM`#H>DTI>G4 z(lVUNh28Y*sv&#awcj(HEJjYneO2!`*8D`e*~#@&njQC$+Y$?^E_u6}z&7`l*&(N#-oiQY1aH*8SAiUG>jM&t=9s z7LlGTJJh?bTykXDk(M6rYk5tIw4+z6VtCHlhOJRB)DuBwCHsZPGG+-&&}Jsfvw`}n z`Q12d`m62TNEvTip*nDKcAf8%jOTaC{!&qqx{;ol$ySwJ(4TkUQkStpceZ%PbPJL# z(_h+3QYEdfZ)p;~yt^Ldm&6rAlsYt8FXO41A*F%0oRY>zb2g-e_Rwi=$We7OUO#4^ zz^{vabl$hb_FvOie`L?HBPF??42ViencH6JMV`o!gnV`Q&&QtP%&Y`h(SC&wX$Z5tz${-!t>b zJt}lKc{`GN{*nxtxg6!gtrsfDH|4b9=4ls_hLbIZt7jwGEyI;-6s2DY4n6AV*nF6{ ztY;qHRT)lmNbbujdIn2UBts8ZF(b&(XVs_?B;pc@D8E;&7@_C!E5BE^jd|_6`!3ab zx&`x9o{`%$?+XRbs){3-*X~n~MscyecHf5t%f))g3oa!)bI!?0ip+5ss{ZFS`&l(-G&ABUo#XMo z^!0Nj`*^dUT(ZyKsWK$!qwVC7sR{Z`d%ayM-p%!RlU*ru-8wIh;s`vK$OsOR4P*3+ zy0sUj?YsF}v3XzWyjF~@YmC#A?OXSzEEy-4`c}#`TNUdfyvPK7q@9GspYRP$IXXda zV|T3QnkD$Pik`$xeei4Ez_US{!P&ajL7*~ z#ZUfluex5Xml2y7QRub0l72+U6mE7?zt(;2Wnc5@&vf$|#+YcHtvV{cwl2?X{bS?1 z#z{8uak)95vy)eHu!$P+umJiKXx^r6QO( zs8sqBf_nCqR@8IZyGBEZ;8G z!y?M2+k!3I_vLfnaptA1Y=^QcaVC$rtXs47>bsdNc{fWw`A$8V$!+pU?~<7_(K*bD z&hi|iLH+2LCCc6?r4Ehc(Uy6ray$j7WjB3->TLNzWZ&1Vmhb13#WU>3~LciY)jt>$v~bn;!wySaKE9|u3rIEKGh(F-U6 zhrc&Vz#3}G0)375qPy-wiot!vTK8UcS;*;m9X~I~UbarpcWO}WebYiV+p-$eKTVa; zQ3*Yj&^-wSFY<;;d3KpT7&EKARk6=DAZ}p$+P!1Ds+a`dg8!E} zJ~rp*pOfh}kf!qcwU0b+;$xN@Qk_|oSL=Zxxfs1Y{cM}W4IOBnJklb6v0Bd)7)iu) zo`@>;Z|W+^3+2-y9VU{0ZX!KkVP>1fT5I$yyzh@6c02f)Z5A`hXzylh!e(Tf?O&s} zva@MI*YfC%HE*|;Q~#{?YLfJCXs^ym|MvFkmGqx$uPUw6tNNIWIAO2taC2}tI;31& z$91_;p`z?In{7z`c+#v>eq0Hye_2sltwwLr+wRtP0-wSo_z$( z8fR4PZOrlc35o&i4`D8BM=%o|c%$txVgSPU<#jJn+#YRQ_yw%UnsC`W8I8Q=Olu`G$b5(u9 zGYg3?33?@0)!FnQ2Hj*#b+cfL+{g zyzrz%R!z=fo_H;Hnenuqe7|Y*E!GqwU%b8gS)0|3;k`H`N98FuLc?@)ws_@^WzA@ia7|~fa8PANQ z{#c!gX{nR*DofbI+DxhB8LTcG;Bw^69!{y1_v!(z*_G4c%Vp0S)p9R4e;fsSS&xgX z$NMVk)LwGQ`zlsU^Xx**x7K=?)wti9dr>V~z%w<5^TbXaw8Fgbj&rpY=DVC>=ChHv z^12q@V3Xn#pw67|3Y|4E=E^1G65}eYXCtvgE&CGSphaAmkLVNe=9H$aa^UK?r1FXwC^}_+K zoYF@cFmPC}IOZwGnH)FolVgWSx%Q}qsVGn;+_^FoU!g0jJb%?T2%n2W9H z_E~*D(U&9rbg{&hgHs;Zv5-R)W$#qML*_y@57aW7FT{DLVyz*G7K<$o9pZkaQ4MQj zN=oG^(mVAxg9~=^43>FI)=j_6UZhi^OFn+5svI^~tnK0du|~3yh+xJHGGiuLG1ni~ z3%l}umbT9`n`0jyCN=BR4bE;3jyS?S{T|O?S*qNIy`u@A#?PWhC?eje?njuiW$m=} z2s5K3N|a4U^l;aJ&#iG%5a%|>{d7bx?s}1Ka2{)6NA(6|hu%kdzH^Bqu3H@{G!D}~ z{ZP#P#25!vmK@XSD93jnp8RuC_>K`qGr7<8P;uQ7SWx@y63y_g-(9q00@V%@Y&&(yZ}R%6?AAsbKU>0#J!PCqx80haV#JS(Xi`s&KE;nTP3l?6_7+LB)BDh} z#HM216gQI7Y%0;shh2kDlZyjV$;Ek3>yeqxdM1_wNY;y!!nxu6+TV+Op6Rw{q#Wx~ z{xEXVX}u;ZeBm^SxIrR1)mN`hlZa0B(-I+ve>3?)YA&rAkKwdz(EAJ-u$gM{uE zXV$p0XE;n3d1fHXl3S`~N;}IfU$b-tOn>&NjF#NkOvNyoS=Bz9u0;I$Ec@XnlJ$>g zZp!tVYliR7a?Ri!B%4Xfcph-cSNpjBU<;`d=eViT(l(Kuo=HW0bB0`s;H;9%tXO6n z)WBLvKCzM88KSNa*9^7loF3@E&KjZm$l%m-dUn@MPgF^-oQGM=9v?ZQR5{Or5v=Y3#ock4!f3Cgv(Da zvVCL^+Evg6GgeWHdKMR!7}+8wvOzXcV7%gx8SP2GchA_>;tP6IrqIULYDv)|ztY$> zb(7*qy}Y11Gc8OvGNUyz=TW^rn}(z>M7Y?ZAR zJ?^V|WgjjT)q(!pYu~uaFX(y8s#jO_vi9H0rj)#<_xG_ME}ydEN1c!EzORyU^QO)l z>m#bCe3- zN|Owa^#1lH^-{(> z;`dD-GOp^A%o3mfrr*%5Orr51!hCS~_^~{=EZ8um)f4@c-OfH4eZu~^>idjGg+-gB z41T6>vHQqYH|q@q-{roy)^k15KCyC2kLUUnUR$2>@4tFRU#)hE{~O9eZeNP~7(?ti zZ7MaZktJoXk5MvEtF8XXXbkWUR6~P}-O{}Bb{H{gxs2&{d+jW$gpa{ZduHQj=5Z^x z5uzSsF?x8z-9pmB4?>LlT1kF=F#ffd>UTfGsn$jKM4LZ9s)GSWaE;C}#N*GrY_Wn;h1t=;GpVg+_xR3V^chk+zH^*B zFPBBsW%ebQPNp&AsSEXeLe+uhzCr3meGb-yW{x29$!KA@RL-VS`}z7tjAg1KOeG2H z=S>(Th%B_Qy5nbXyYeAz!SBcikHd_B91lDREHCjqe*;P2cPb*8*H<`&a@^i`oS_iiP)yHIT;)KEerB@`@=wC0&(CA8NZE1??_G9P`t zk)F zTrFt0@&#REtaXHI$ul=YyX7=pUeq6nO=@iX@!*;rJoa|Z8yq+ z%&)j^cDgydK1#e;Jizcyco2)4ZAT>Q6lC#rS!A@WkgW(~N%Ro5prY&Fj8I*crT@BLnA6c&(DsL+R!CaTDCAc`6lqwv3oPyf?s0YCy?Le z+&|!ce253|Z#;qyu4|5BRy=|E@g#nP`~v5$h5Rnh6yGRO%jvS8)=B|)HfOd!Oy6BH>F#vmGAdbc$oQho0yBA_6+=yB6AZEi< zq&c1Y4)V1c_cM${dsg1~h?y`SMqxCT!a|r(n?PX#?Xd_B!lF1Ci{WA{jwx6I&teST z#gh0OOQA1!aHTOAKgQfx4r8z)R>eyA1y;pQSj|o)_W=YxW58Ifg)^}(F2{Pf9UI{> z`~t6FGyD~sGmghNJC)q$5$M8z_1G2nVK+R9 zyrt279ed*=?1!(hKRR&;hcRNhPcpQfbI3B;jNeKj&6PS#9 za0*_)uklx$iZAdR3<%|ffmv`S=EGT72IpW+oQutH0d_@RC+Qx7OK~Fd`abt;T!kAj zVKsrH1lHhnT#HX}9XfdWupYya57WDgBJZViSHw+N8@FLA+>SkP7mmQ)I2rfjJUoEw z@Cfe1qj)xq{C|SLO$MCACwLa$<2lSoZMln>55LFqcnKTfW$cPqa1>s}8OXDA_iFqB z58!o7#UJrD-oVFr8{dYL|L+h8;+~P;W869MJ{H4A_$l(DO?LzQ13MtC6y1ICIVK{l z(A-J*5|`jB+=B1$2)@Vf(Z|Q;zK6c}90Slu;2J_F5QzqsMJLw9Kyt6Xzn&%G_(P7Vbcv)wqu%PdVIIu@OGNFYpC6Lp?X;0_MQhSP0wTC)fe& zU@W%AI3MzVF9KZ{FcN#<*Vq&1V;|greQ`ey#7j5`AK_rM@xW~eX2qdc1czZ&9F8q; z1jge?OhDSPy1&8Ev@LXhOMqsW?sfPj?!^gs7OB(j{t2hx6Z{(AVG?HKiScyIg~?a~ z6;{S?u@TP0SX_ktaWRg;j6@SE`cmpTmZCrqNa2x)Nr|>S`&X>T21c84T@Cyb;lm9Uf{)!*t1FVfS z>vXroM;M1sa4`OX@dUobAMhPML_3#ouM!CO5HRv{{>Lz+J+r$o z(%{Ek0cm>Uu8TYbbGJp>mbiN(jUU`!Vm6$E*>NM%&eZ)KhT@ONi+SD8FdY30&`1s= zFefGyBan+gC5*(+F)y~peAp9du<9O(g>VWM!}(Yo*JCN%kEQV(evG%U9R7j4y2{N} zvaJ#ZV^z$J)qKhSF$6wiKvk@TUmz`F-QBPrj>h^p6C2uZ~sj9chmiCZxR zQ}8UxtKC-o>7H4@V%4q}@~SAh_^QUU>+A4M%{_&4%_V7FG1M+KM({V@+Zu@nYkH4H|1B*M>f?#>v3gD@+OL*9q& zPR1}?fw?dRBk?%q#e{1F@)3A|1@R>oLcJ9E97C}<7Q#|k9!p~#q#e0C7R%uf`~)Xr zd7O9FBkD2(*_aJ7WfPV=hcgAW)pZIIN80u^~>vSe%Ug@EaV1 z({MV@#HBb3x8fW;igWQ2F2F~)5N#jXY>O}}F2*9b1gm1gQUWaqEW_@&9Eafw9EWQ# z8Q0wGNN{{&(gz$XdZL+})S zji+%bp21ys7SH23`~}bBYfQz!a$FZ+I9|j8cm>PhRjiFaVk^9XJ@7V;C`bOkLtruk ze!+QoAJ^d{+=sv6S^NWU;!}Kr&+$F}jTt{7|6?S+!V>rnYvOxsgFGa2_eTvUq8%3` z5bz4E%#ug zT9$h}^8Hh{!n~NUl0X3h`>-H>kA?6d7RL8j1VbwDTmTDWF|2~cu{lze-Q5jia443< zu~-&o;YYX}%i|8LfXA@1gZzJ$Koti3iZ$>B*2I8{lna;x>tI1_fS+JP{2ZHLYix== zu_cbgRyYOQ;Sy|*JFx?v!&tnB9UbKVR|GmSAh;3_1~3}qumX0$de{})VmIuLy>K}8 z#!1)@zs3Hz76;>A9D-+X1pb7);@$l_y73(*CJ@N*Dfu6B;dm^Lldv*Q#)kL}#^N;W zhcj^k&cgYaj9XFRNt}(ha1Q>BbJ1Cu>jTV<^ROf)%qLKlzyhp~ORzmI#Xh(a-M9*; z;W}K5>v1z~#>2P;FX9foiz)aQ?m^!wTo+&#Jc#-55SFPT=YIk<8E_1n;VJBer*RCP z!P$5gHz2P7aUaF=cpX#mDPBNFRq{WE6z`S@1Kf&AB5bt0Y{252$U7U{ha25W7`|&Z8{9=wZD_y^`i$7d8+m<4Cip+6CKViNMoLiZ}%hr4h; zp2Wj=9gpB6JdUsN1Ul{)8@!Hh@jkx8w`dPwZ5xomFemzBAq>E>sAE+$ zurWHZ69(dN48kO&qK$ig16vncCIYJ&kQsMl7CeR7@kh*ozhMNv!JHV_kV^#2j*(a# z^J00-ho2#@HFCGW{Mbzu9AZR8lq9&5L8b60md49i27giAhZuDdY7qRk5xEN2;pey) z>);8ji?@)MB)OkrBeZ?NWjzLBGmOCISQJ}hC2WKBu`Tw%b~qT@4! z2E^eh?1ERYEB=l>@g4TU42?OhV>~3FXD9k31{E~oQZ$oEPRK_Xf!2*V+hX1NSuR(aW0m{Z?P)Q!+JO$ zTi^ohgbOjD4}nDlhT~!!hf6RCm*PBJhAVM7Zow6}A6Mc@T!oi#HQvHC_z2hHKe!IH zW?YwGAa1~HxRDoWx$_X%#DHSB8Oz}otd3i;0dB)qxE;IT4(x|1I1+gymwN*4!s)mh z7vLUTjeBt$?!yDPA5Y5aMuq&R$0eB8aN>{(RdR}V!|x~6$#wNT6hN=q}o zoYefvNiBtx0i%t^_LOsOqk!G7BSX5U{58h-)-R|K;VN|U&Z|NxUrscd2c-Nt&2ZT5 zXAY@X(~U~{m>A~C-=dT%GmJi3siV9(?FLHx=nN^=pNJghG@3% z5N&gnBrUlEFI*2yHnKSG_}U!xCaUOUBc~nP9W`pEdmUA9A1yFtSu(Y;s8(aPX$_xk zWO4n>L@g)!+B8W@gT8U`=^KjPQT=8cQ4Su%IbtWOxwDO&u2@f8sc9&a#K{|?X_K8q z4V1bMeY`D7?x>JCOnHwfA5K)2<`@kaBV^4J1L_S3Ct`2SWkx$82xlHnBFJmKRVRJFSeCJk$1xBE&xn~+#3%fZ@ z%LPU?=01M`bLZKrW6M-^YyoN9l5XxgF?(2*ol7rg!}f9WJ%P%5oxZBYa<=$4(%V6L zhe~hHg@#Mbme6EES`U?b2I<+kob)_CPy2TB8oGkXnk+K1y9$1jwxwltd#F*1*l2e=gJmno4xonSBBQXY#k928a{TmA zzb`UZG-fd?`iK=>GEKEw%#pUl6H{hDM82b7HU`?1;3)RtxV<0~{l-Mcrm0tp+4jfM zO(e7LDO-onC|&RkP%l<;;B;7R_^J*|_{>&MrS-5|F9Ygn9c(?7YX^0E0|WWxB*^@7 zsBLLd+7Tf~S5HOt->8BGrl+liY?PiFb(TDTyrh`wN>&~2o+@Igk&Q*&Sz&y}-W;`* z^gbrNo2RQ4OWB*7Ju^zny4pHF?>7eSsDjIg&jWQw#u<`fLshS3Mz|~EjI^c8LVKw> z%ZzdXRt2&K0p09?#)-{*0YK3dE(1T%I4rL3DQbofcZ@fRegt% zl@!U^4^WLb_SEz3Mt0>UR}&>^gSFu{Fi(C)a>OoF?=~1Y{bCo&-it}$xUBq=Q}etO z3a=I$jX-UnHIr>A-kA(E%K){Bk@`lNj3tGtn4KKn!8?t>h;=!59uvyLWJVNQl(uS8 z3Jg@*CNrDY-b4cU{mRj8vFg9ch_+*;%|=~Mh5b9~cZt9cTaICiRo2Z!!2d)@+Drs~ z@p4RBtafisw|(Er2z~-{%v`LZx3GO@@>8TFQnnX`mTi#va!0=mX0RXo*e|0Q{c@HAT6z2958G^_s&H2o=65MZJQZ0!oqB_(Qq3(a*#^g&P#%NZR5oF z8NaZa`+!ABwrAV{E(j`5;^T;mBtm;n1aGl6NbTE35{IUn&S_5f_cqQ-Gt&*Gm}hnc zw;RpLs)^g#uKc9v7_d~W*>2>qgDSE*%bF}Z_ZE*U&a{y3(43I+P(pW_4tz;c|Hg$&}2LR|Wm2^vt)5 zm9zQT91T~g`nxE&8m_Wt;f+7+zwu8>e2w`3tWtmOGV&Ds=Rdj3f(sI)X6|u*#a?=R&6zLbtOh(Awuo^3kP=_R#$s8)Bs~>kNMEH=C zMwmItFT@=BR%Vvf3`XoFn9U3(-S^GLD@UIlWUtBx!f1q52BO z+H6eQu#%5QsQIL*dj+=pIC^6?Tcc$*a&eM=vAz0q?HoHW);#k|R!%>TW*0Wu&)&ri zWqz%QbICJ5*-Vnp*-UcPI(wF1i9+6E;}g$o9r_j|0)L$?%>O1fUjXwi(A!YuQXz90^3LcFf4(em z#}?J@fDsxokeMzbj*Q>onX#;h?2l2_J8DNsKDNHsEHk0^0A=YYvp7gT$YCj8rJ{`dEwnKI`;kuHZPw)Sii?_Y z@txut_URr!&^k7*v50LC-O)->LD-ZCaZX(6<%PDq#bSmx?YQUa}@3h^MKU8ejKw2?&;;n8uRg#2z z9pS3mEej5V`4*gnX;5^;@C|aOPq_Ier-uJcj<=;r_2O1Kq2k?xO(f~Wm$=P#$YYIVo+lW!?|Ei(NH&7!kFSF`dZx|h!w1l75qA@v#PyDs4J(r+ znjcj1H1(2ncpEa7U}Qb>iHBwjG(T;ab2tUJlffe}$QH>{p|nr8x8#Y&D*rHwBDa)J zZZk@b4^ieZ%zA#J*(RDV3T`ykjAE8cZn=z_!1H7|sJ>>nEc_dkqf=V3)W#X~cfeWL z50h~u&PJxS%~7+C86WvPoan3CKk><-&u4f5!xyM$$BfKAe|m=JT;dtN6oWXxyle4> za$X+495+G}Rx(aD&l=2*YcUtDLvo&(CMlLT(f=uK!3MYu+u{yn8uQ~1gl)U&KZJYn zG|D<%#sl=~Ry!%Zszn-3ISe*X+SPDyehL^@N^q2AUe}rY}uZZRF zbNmFGVtH(Vm9QOtihZ%NX3Of{MS%Tnek-Lao~OTB%EOafMC;b$GtE}fY&jhB8KdQt z^*IJ%9h55~PHX0|+Ym$PZ;WNJiTe7qkzcnSpJ}%CD)(If%n7X+%T_kOd%&{H?;bc& z);8GFFU3$h;^o8+7>TjS3EIZNXXcE~NKs=>R|ebAUje(IW-$B5VKT$NLWPu5=6K2_bNshB zm*J~$9&W}3co-MsSzLl-S=%!F0hi-XxB`F1m3W`!+g1~h6Vh7L$d~IeBg&S@fm`X% zjoXm}(UyYj65CGfio0+a?nbtPZ4XXInVv-14${BS(@)}Thv_E~wqux5oxpJdhmgX- zeHu^VB|L>cqRfc4ZniV@-}Lm~#`E<5ftOU=IpYuAdb+6D@|rE$b6jJr9HZAU2g+RX z;0^WFc_S>rdaS5PV>k0p4y?zX@O>tc)5HUe!iSj88t*QQPv|d&EZkigr5#*7{1aQ^ zbL@zea_*k^3J2h8e+!D-v`1Y3%4dd87W_viA8=CFl*h;n%>Se02R=1vkYPNRPx9BL$$L3-+sx!3| z3pG&kPEF)DWwTLRTdb`fUNEBUJQ>Y!(Fo05kI{0aUmr7L1C%V;2<2*}v8sL1$fa9P zK{aj&VxQ=l6IwG?%BVIdQ@2OC6N^PT4y2`970GbGu#IY#PUO0uB zJ9`33KAVKya5DDCZ*UZHYI9Q>*`_0mT{!mV9J21LBfrA7};$bY0 zN0F9Jwqw`|k7GNOhHahj6vpEjr2UZXtg3N|3~fFA)p&E2ya^(KW^QAav;D3RD+RCN zPLyVAd+;ax4ke>=4P&-iOZD_$zjQ*^^E5d!}gf|*Z2np+2(U&Bdw*w zF#_|c^OudHcAhrByUc0hA0h=1`Ckk{wu3tlzCtM?UZWHdZ?HUSK3poG9p!Z4gK}>2 z#W?gsDIy#=24yA2qO^P)=joq-2K_;{mP%bQYS?*{ee;SDS}-dEB{A7h5|bSzF*#5! zA;a)vj8M6+8d19WK-;GA73QR+_RI;=AWAaKT$EBz8bpQRe3Vjg0hYi;NQF$>60D9( zu_ms>j<_1TptO&2qqL8jiqbx6CQAFL*(mL!=AyKVT0~J|HjG-!fb9&}f;&)ltTc=| zfV)w4>>j0GGx(0o92I|!U2ufKlI~+D>6YeDlJ1iz={}7yD9xfIL!ZYQn2J*RNb@Mk z;Jo2!Y*&tIG4 zg*;O?Z%Q(uZ09UE3$vq?JE17Ye;D4x2)u>4ktZE9?R1&=krg|-_FG*a)vS+IpxIa^mF1d z+cr_g+qiNyKWthDDW%OePMz)5tj0_;8PJ#!3$O{U!e&S-U9&CHPHayZW@LNxLKntkQRD*Iyu9p>EZjB_<@gzlt#K&I zS!+1P<4Ba_hQ|aqjE{8dR}zhr+MPu{naho1tmM)0D0y@O=0ScgH}mKul+({-`~<(o zS~ykxe#0oNTfd=bJQj*w!XODLDbmr?TW57-KS z#CG@-F2?e4XPj0yIi`7FYpw?m=gjpejaivZS&YJuP|BWiC?!}WtcjJe zE>=Ow!!@u6eulCyYU4!w9FwsQ&O>Q7vk0Zx%n~_SHz2Tz0S$30HbzlKTVnL1)5cEVy9hZV33evVzS1+Kyi8mqX5fMk*l$aSKv8gf}^ z+k$=^vs=}yTgF29xhej(5t?%+gJs7{BNBO{5M(QBzQRK`62CY}99o({Lc6WRA-yhp)69 z2}Nl;k_)e4Uc8P&QQDBm4!DU)cv~7WNvZ!c0~X;gC>#7&l)_U^cv5Ie|7nyqC0Fow zyob`ZL<&V|TSDHoJww^>GM(<}=YHMx7sIolv^B}&8DGF0pTMC+;0+^WkI00T(B`m8 zGwDyHUlK3{eHeZKeUV!hv(3o~^rv60o&u0N5VOt6Wt8c!Vg`nD?_u^|$6)$zpi5Q! z*+|g`EVT-sPgKlPBXdF{#>&3>0wp6iLCMHXu>dwl*|*YeLo#q{td4C^GC~LJh#j#D zc1AbG;Z*E`a#HAuvr(F7$ZqI?i{!z2PXcoC?TvEsjYrA(eeodn$CEe^FXLeR6^Ec~ z|Dnip5Zf>;g~O4@4_u8uylad|uzm#7Y*9W;!=GG^_(~%jsbG)yvK8x*Po4v(U_I3ksrA?Gi&ST#=`U$!lGCfrMCVwEP=@wgIwkFuKGj2 z7<=rgE7j=xMrfnz3=UwuYNBM)&oB?xLdo1xXTKauoqf3iqRzg#A?u-B0o6w-JsV&G zHdGJqb0)KX>(gv2tj9M}vtO3d3}q?JQI^sIqp=khN2%d2WwzAtuY!_6s$mEEW%o%< zf4Sc3h$B&|_J56C&^%;uIsM%*$X1V{El(de($@ELw#0j3^U*S~xUA9i#8?>OS zt-g6+lu0P!&w|Zg8#VKnN8;HOT_nTh?^`Bv;yesOX$l}09?}#*%2sI#Aa|sTu_!LZ zQb<#P4;!#1{n7$J62AfE0%Rk0l#|(J0$mtDQvh>6?!Ynhn@s_5H~mrw$l6IEAWZ=l zd-|8+VfvSOlrll$NxnJC@a=dEy=CM>nLUL_gEKiU`xD--S8In#oIUiY!EP_w51U|zu_#8h%X{JyIUtm*wiJeiJEA&EXroer??L8)3 zAYcpNA{!m}5Cf5WJ2U0}7)*Z%X2MS}GgiP1SQoQlOU!{iF%$=2IF7*xoQ`=g8D)#i z#=KIAdyW-we~Sf)un-F&cWAa%r0_7x1ZS`~!!KbBawB3kPI!-{>6b^*WiUT}jCJu7 z9E26{23EueSP8kPvYvz%=>PDR-=({MEXoGEOHNE18TSmcahwm7(t(t?1J-)uo(khQ1L-x3q1 z6X-`E853|ePC}XSO#GI9^1j&;U>Po;pDb%u{3nZ<75~rS5{8o_%!>cy0JGvh2bfvm zzbvJkRN!Z`oAvbBx@P_SCIOtww=-fK19spPl#2N*#H^UV0VN^3aUa9?c=`|ELHg;; z@rRMlO&xi&e*Jkou6qA&eCwZ^_qpZcV}JfnjA71#w#wAHu18lVCE`x-YNWGq&5G#q`0g3~ zS$gi@cpH)=Xh&CmyTpf4Ur>cg2A_70RA8GpPc z7eqP%xlK0kAqL@7%z!VE&xxCNHkmMxA|?xlU{;L6Y$(rSvtu<3MJe0DRm3x6gl_$U zE-&HKj+rJjZ zU|p0mYdx%h4Nxvrt78{zh6Aw$${DpKeu=GdGV;}R^Fp;9P9y#1f~GSfmH{iUBd)>D zC?}yVxC`6ke(bIq{bh93t)J61+h1z2o2S6>jFr{si?SL6F$WGtxi}e$lI-F58IHsT zI2vP-n;-KOItEA6KNb^l9F9fV9OH2!{jy!ZLP_mpyeO+Ng}`M7e2sGB_zlXbF$sUc z8TcEH$7h(V#yvN>+WG1I$#bKsz2^>9@^52_i$mDGltOI)a*N29Z-4ol=5yytFbRMA zDJL*qkEc-hs?p*X+A+$m##D2NV=JH>*$Ws-KKj%7o3B5bhYR@(2b;< zNwKlH*~?F#G|WD*M@E=-88y&bVuoK)4ia}5~kUTgtgUdl?k+<8%j5gZWG-J zy4!Rw=(2EYo zbZ}C1`10DK7e-DWUpFsf&SGz^me8k#Sf3ORQFmTYJ+X+}NA63_%8;^4LR5~I)ZYkE zn=kXBgoZDv!4u-C1^JSydJob?_c5cVs|6_$UV9?sr1k`-Rpz(vrO}o;8DXysUPIt( zb9|JjK7VCY_EepJuaaI#r8`EHOH{jG8Qu?izgI6A;j%NLe4>>`TjO4FaVqv#XTc8> zw|&jTKE$b-sK&ph#$HuVT&Wx)R~WbHqyT9BVR)omwDR?pD#d*&dRkz-S0Qhhk1z8X zn5Zhf`B2UEy-Ji3evC*=RBPU(OWi{m;b6qZM3w1nx)F`uGQyt`dlS|0w?-a)uV>Mr z*1PX_zBRmG?|ZMFN#p<`-%C`X@2Gxx&l6d;pQN*p`8^fS2PtKzdTXByWUu+UQUqHl6BI)t+P4G-tTIYT~R7&MrO!8TM%@ zJ~CB8a|Y{)<^nao-ux_tYN2g3X91s$#3+83H&HLrn2hzF zlyU7tH=BcR9opt7Wq2^ z?etU%bVjH@D$vlUSD-VadLKr!lNXFDcdjp(-LG+m!C#M|f>e&OIFco=__v=1? z;FCq&?q&~Ao90n9*zA28PjBjn-rH~ZBF8D!Qg`Ne#du~D>Pf*V#m8==Ty@h8mh1CV z>N|;DkKdjoow88Ley7x1-PwTGcGokUQ5hCdIcf7rD~7Ftig8juImvKlb9o2KWK8wn zkMz`5n$sEO;4AIb~NHXL7`q z2y_Oz==+d7N%d*9xj7$8mXw}WT1DC(omS=-PdFto#QYY^z(;&n?OLESJX3{qQ_D)8 z=6m0>{61&x8U?Yq1}ttKi!(nLbuGx5#lIm#b~8lYx*S0(Z(BF6NwQMvFz`b z*&~moeByHUuQ<Ln+ zW3GvOl`4>}v-?y^s}N@|yGHk%E-*Kz3Aze&9q5MAP0Ot%RXLfwL0ScdIr>CT*WpxN_T_qMeYx$ z%+TaWXQbl}Gm3Anq9dI-ed2kO{vXBk-Ac>tjM9AMLlCsH%k2zyEo%PX6Q+-9o7)*i zlwrA@x%_WfW7Ye-&a7&EKBvEmjCKa7@Y;?d>S=DLeB-UpSDaCU^RV@QW`Rvxs6u(1 z#e$l$8s41kP@ALq5JqHC-vD0YFHI+ud#A%!ZHspD0`MtzUv)5#Gr+}j%(Oy`70;=( z{N(t@%$muxC{pFCBBGp8cEv*Svy0nAIm2C_a-%LwlD#E+(pP;I<&-vI7l`V(OPW$z zs#j6$krYo%*&{kJ{Zvd|_K2TqWFbuf%+F!@sU&O2W{V3J&+UOK&AK*elQt_UuN*4&l5Z|mD~u16 z-i~%=cYW`P;60ihidSyu%5>W^Shl9DmP6yiwCrW`b2N9ECC>X~?rO?2j5fcG}6a|w;yrrap(iv^U zq$GSng9Zv3DJd;2D4CIYw4kKXf|B}w@4eO$>bZW;_2=^AI`{kQTKnGjejA5Mq{vEm z7;xFZ;P902KCXD{Ar~K4_91KS3-8^>m0<>4PB6GWC5FDK%;j$jt~7{cZz^L9*eNkg zcuH)0Qwiz|d0&RCLdcA##CN|7nRNmok0T`LDY5E=GRhqE6n#9=YK-!Q?>cp)IC4T! z&3ida&IH-b`NDIP-nx`rDU6Sp#`?!2ueUj#?$LzQv}8FG2bdi&w;V9P2Vk77;j#=l zbxw-x-B2%xM>J7JqLxJ4BT$Ev@_}FL*G*T7;3b${78LbPl6Z27$+~o2DUQkjTwF2S zND{wRD18CuNCZ5A0MiCBC(<;^Y}(M*P-zV+>9+n#QTR4q+`l)+#zvGz;#=R9qT($) z{Z=WO-%`dxpgPX`mudmOt5Vofv>ump40W8bE-DcVENcA{=q@e>=;VpAHC(n{D*QWC z@H?{Lk;*%=oYC@1A_A00(R2j#Z@T4CG$aA#EZZn{J=(A7jWPh&j|@p0#aAa4>&KW^ ziYZYz*5iVbVcSMq@tjGuei418D3T$##AJ98A-{#`XS&d5D&+LDD&{!U#NjDh?UJN$ zcn6|1VHs7IT> zT5eikOxj54hf?~vF-X5{qu3UM^e=7{U&NReXATQR&GCl`s5=4ux(IFnJKT}y0fNAC zuo>(Hhd?#B2yOtKx1t*X{6IK}2b)1YI0S0I70>}}#zUupA6N+RR}mVc?4N<7>ppbm zv}c6(3>;mjJ!2~#uNxF9N_QD&VR>ky=eG{D%)qh^7uF0Bh#^OUSDgEV?@SEqeuQj& zMy!}=vJUG$Q6vKd0uDVR&Le=;eV;*0ebzW!IQW^=fw)9xs78)2F4jAV+3+#Lg?^`_ zgREwus9mhLKDmsv%YMMeNO48akdZ3R``w#f`$VrFihCIWhf{^OKMov+Q-7b+DG}#y z8f`w^&s!FBN)-5;oRw4Jus;;|LuYwzu}|Fe$IQb8L&KwKwqj*~p|8CWvrrB$AsSNB z#Iv*dRiIJ^lpr7{O?)-WG)fP7W{jDx~3; zG^(m@>C>r})CA2SB}3`wLM@M?KGtxnVLKyg??Y3DJloeo*_1P)OL`AyZ|jloj4b+L zWuMqE8#Vk3$~*L|*cO0g$BEe{)p*F7i%2oy;l3;IbJ^POG;HH$8V#xPTSc#IMS}@1 z1MmniS)X#=C!zz8H7=wYj{iw!?d@~?PknVmLU|YOy*1IF;I)zI{?iN!mdmEIqTqi8r_a!;CinWz zigSMq-ppm&Yr&oWE0|Nut8iz9`~82YS~^-L+buidtcXCcegB4S5uO32Dg2FUsg+g} z7lrszGrtbSNy^3hO+f>s77qCY&&E%l3(Eq{+c+2N45?^yO%wIi&xmj4n$GB;or2zrU(CSC}HP)fP)jrC6-x zy|IT=gZHb%n!NRpi(^fD6gPTiQ!ZHD=5Aft8Y;&*TC+wLZe0MTAW8{??};p)!=O@io57S5QO=0P545X^Ekbn zO;Ru2h2?P=F?W&vII7jdq1I}-%Lmk)Mh`IOL#5=!H>qLkcK6j?s*<~CdmKk|chUPe zP7!zY3zeGWF8t%MpW!WX?CVbKLM5XOSK0bI0 z9}5!rAi<`5vD9Mnw%^n*fhx*AvY955)?ynbXrsYS8BI?gw_pg&(+VhOYa>UCiq$w# z81}IZ9#~v$8fKo&5v=VTErM60`LFg%CtEgJm_Nd!(R)|pB(bw!m>hmBPkcF7zTE_Q z+KHCcD7m{|#&UQ@i=Nf!o6(~7jENqp9HjaBK7rysz@s^`17tO&+0cr67+qC?Py_CI zH2k(lEJiYSTsN0*WYU!()^D6jcAKo^aN7JGE<7*Ujusux_y*x{p^U(%qdFXos>^Vt z&wN_AFgfFf3-d6oOKW00~Lz=fRC!ji$P@U2j#qnX7l}i$k zsFV{~S9{LdYERr6i7#BKPWbq5gA0C5aKe8#P!CXVph*O>^{m$6Zx}5>21!jWn+m zTpw&c0PAx1DbrT{ru?ccNm!=nf7?^_^3$eeioW#4svnYZ_GP5f6uf>#+b!L?$u!}C zx!x!if3raY48?VD7mUE|sMEnh5D&J3ec&Xx0B!*J?9_-!IOB0q_NQW%BsVkubXj<( z!i+#JPBp!wd?cDbk=p@jrdc@qnST!32T5r#IXEXa?6@pmNHdKw?%*vL46GZv>``CKct)clSW)(GMt!o;(;kh& zd$Vbb*#mEKmNQUOLCBB#KNuN;h}NE#2NH@bFRLnXIFY!p*%ah>a1jFVC+GSB6m((| zPA1#%jw*X$zXhi2EJmwsx$xeCzHeJ@Bi_7YcY6PGrWMw6zU1f7>S{!KAV%zZ&SZVp z$63+z945s%1VqJ%AD_ddh>DT7t5H>@e3Yh}x&tP6$ySqf|NX4U+lrLukuozzytUOd z(VWRCrLrR-o&~GTHaYIkFxe?l!k7Wu7$tl%Oq0w{ub?7iM5zW*A|V56da9qd)SM_$ zoB>1E!`@PRr5;AnM@Y{Kmu;xPyQsjNm14m*ll8I)YK8!{1_7}vsUYF&f!7}VbDPQf zHkq@c2XV}`h_jXB=n@wuY!=Bw2@8pA z5_rJ?-elq}KUF8cVcoC`LvtY;8!fA1`#M&R9m?JTs~9cJ+tJ$R`-RGGj~0as2jWc^ z+hJr5^$U}IkCfkH?&WVsi!N}O)euID^6eOxA#r_$NkbhiIzy4&U76hi4wFgb!6{m} zJa3w2zS7TI&g5tj^StSP^AygIx7R%MC1NTWP_gMeXyb`fL4SNDIzYS94I- z`~AYC9p$Re%|X?_=P+3hxgv}faXF~^gva{|9ISb3RX--PTghQEiCiT{i^d#Oy``VG zgXV3_HLX-INpdks>M$4HiWhrwO;gQp#Z%@o1KEUS{oc{EOwIz@_**7t!bn?Lt7Y2z zCq#{WThlVRUkbzh0*v@Fp}m1Z7KaZB%XhiR356KhNGPvyBWwB7QTv&K*G_0JAc6}a zwb{6OaSWYx7cG1U<2}ZLdWq)UI6Da6VRAt3m=(_M9;m?xM0ppf>SPp1t778A$2-vb z?ftyvK=V#)m+s{-skw57EE9n{k==wR`bv?L17BH| z-VgWlmXm`^Ikgj|q;i<-Q#nJplv_JZK^OwxJPbiShTxSoVnrS-(JO2EDkW$7V{!=i z4Prar#ucb%R`(gW$3#;e=0q*0k!_a?w#Vf6hq3AT!$3b25wQzJypJNjStFj^1&jVo zzanJx3SiBpVOj_GlPnk&!ZDYk~ z?@3Z(MD1>9Z;WW&eQ)FHtnkc-?P)+J)7DX9(d7x_HvVgUpK&Wh977}GJh)Dr$?s#LG5CL)4#FjCfSbX=sVn9n%5M|&$5hZn<4P7wmF2K$Lo;xtS1Rr_9Xvi(hxb;pr zAi82hYMo8h_)h&J$_RQTflO*Wn#H3{I4ZsIqG_%10qy9Z;I8Plb(lQKj@TZXz8A}O z9C+sK#Ra0wn5w_-HJ#V%Va`9=hjo0`pH1QVSUCQSE2vvnipBdNVTuvBR)2nF)vO}Z zt^xYD;;Y^}VA?dmNQ18E9uaLWHp4{ZLDSPl8YM*+OkV6P>lX1ob=7K1Y3i81T&;V`#9d3wp1AZVDq=JLsB)9@@0S7!vFaZRCweLC!R+K#G<9Z(#+3XFv?b?RdqMX^h^uy=u{0rg@68 zLK;`Red28#mRE?wZ{ujQLfD^%&bGX*t&+4o;t40QUib{@qqd6$C*>ypcA9NtpdPZ} zD@9uk&WCcUOb(*u6ej)cJjJ@yye!&JVgi1S z;$K1hn(gBKN)%Va@uk8`&4|OLEL;PPBh82tf$zX#{F@_5m6c{IPNckp%Q2V5X@shH z^2OlwJnKl?*uf+AqpoJFkIY!wt5w3Y3SEHbR!LZ@Oyl9oBiGR?(^%t!oCy|)=g@OE zs&HZx&3;pnjWmg?g#9Vg<0yK=DHQz$ioRwo+H)KN!8LYyFbAHy|i^m7WQH^*}a0Y!lzF(*` zp~zKwKg8bBq|0{4i$d8ac4u+qe57BP?AmzYbrwg?Gu>xi&fc;+$3OTZMf<7U5-7)1>_U z4E7MEv5=j;MjDH;${Jx?3!8BOZ;cf*YE47o5eg58gj&;hape`f{Omxj$qgQrwf)NN zt;Hb;cbXff;x#MsRs+7sAnlv=P$Lboal4K9elhmk^54U$C@j~Ye_+oICTPV!a5aET ziuS!@oUZP#Llm#)#kM-^mtA{a%&A9IT~5`mdeaO=e=eu${QIUwiXI)mxB(qMuE8`x zk3NNCfswjN(G}2%@397CHR^?`iH*3VXha>chEn7v!$6!B-}=zxmpN#P>=D{?I|w6v z5?lZszy^;fO$H$#9&84s;1sw5Zh>LGhyy}EEZ7Y8f@7c#Tm#);*bKx2A)w!1VMN^i z3pgG$qYHn*M%x7p^)FgA`&L0~X^FJ=5nL?ad;zn}8o^sAuVR*!UN9{f{rk5y{eU9m z`6|U!bPsFit1b;XdQj}2kn&!P3y|}r6jPc^;~lLxGRo;5i+XOJfiv0S{ju`CijT0+ zz;zu%eZ7r%y3^z&=6+;S2WYOpDG?(6Ap>qgS*?2Xd;Rjok4!J)Bv*U!a@NNvEQYhLv zQG#kGs+(bZcZ>SwdqzG<7(YRx93)EpK+O2$-a;)&q$9vT7Xd$Ey{HZ5QoQmC6_i&( zvtW{LfSGVx!>uYiQSNvI^C@hSaQPGk;O2V6#0Ih8Q&`uDSUSr5q#=U9!37&d&bHDk zr~hR_bec@M14*B55Wjxfztb)uU?&2eZ4grvRV>sl!DK%Bhm3RO`q^1~A+ebKu#LSa zNK}2nMWS-sAv%1C92k|tVtr_G6HrX;6j7ga~ZoC7aDAYDZ>u;{&Ww-TR)#v zt?TI|p?n6rup4o|L7Z>T+4T)Z0zwS=2pQBU_I!qe=OCWC4qqiRTL$Vj>eZw-R7ev|TI9$FU-}H(Xaej`qMMA&W@|gL8==vP% zkt7jt1r^sRdTk7LTl;1E{~EbJlLP7n84I zX^dIE<*I3u9+UdJtGK8z>V4t*g=wM@^HYoKN){;o3v5SF8{T@QSh$lwr{Z=n)S7*MPJ@1R$Vh4*Z;wnFNpJ~t0G%J!#b7#E2;#wJ zun!yqb)W^@0(Sn$6ZrWnZn`M^NCG+FAUFXUz%_r^D9`=>f(^wzD~7i|6W;&Ani_KB z-;^`L=HI62p6~U$WlJ`qx!(o4b(^4YqEOx>y8hod^==mF|2B%_SEC>j^BL34qz~_Guuo?m3SH#l) zxo2}?MIizPK7oLhS8yBS_ojfMav-c4asU;6>$57u4cuZo01XhM9c^4h%}t!op|W4y z#09j`@cn*0X6m?aa3n{C7Jp+}Fd)$Cdknq01mToItGHk zaAc(gp7+(L5$`@UeZqn*gPjdQ^Zw@e7A zX4n~2p>wj@rgX`XyNL|}5n$zW_sxMH|cG0!gFjCZfVJm-M{jX_!)wn}S zi&8cHka7{%IHQcO-l5d4BC;DD;dUFlVxxZ~KY1o1Pi?o0u-m3-#!2iwMr6yV`)->i znBQPOS!HxSqMF|}K7h)a@1W1lqOyjc#GE@=&KZ8^kctCQHTKbJObQ%C}-h21uLTmRw>qPrb?mwgv5AXkYQ$z znD`TFF_YuU#fT^Bn$o~ro0_8&^VX}w zZKZL{5nbJ|uQ|fLM=N$pkLC)4aPOb(mUZcyo<@9`hunEaTPS7;iPJqW&pD!%Ts?4^ zpYB(zoH9A0qQ~egLVm`+f!lA?o3e)-w6MgVaW4KXp39P&FH4aP*Gh5L_IPtd?ax}( zT7QO(e||vUjlsjTh)%zt$iLxsFKc@2%OQQ3^!{%@Z+Vd+M`Zk>o2nnwP<`!~`JsPb`UjLu!;--?%&St~V4^DcY{ z8d-A}C-OO>{w|iO^rGiVVc(0{Ca?_p)q&E8iV5~EBD(k9^D3|th-0Y1Y#U-0$9qjv zjYFV5GXFWEumc+$lixRb3HM)3CalRk-#1PdG59SSI&c@N`jla?*!HVwGOs^zN8Yc< ztQML5-7LQN6$`|_b7pd28 zZbQxhRoN*jItDmHL=04|UvsDw1p`%FazoN2P9h4X4))l;a-cUaP%4Gd4!L8sW7yy! zX4t9LFXL2-JOrrq2-s*%>ppF;+wamUMnriZQFdFSSf&jgE#{B9_W_DZk%2e{yvfXP z#6$emsD|GwxCa5l@OX)#o)haHTJq>7+$JW>W9)GtZM(NMUn$ZCArm}kVrcUa_-Ksv zfssmaQwHGS3qypb*kZbOMpP*xO$hiW0^@=WVCo)8mLC zh=%vX8ODwi&kj+?n8%KzEag;|c7B(Ld=G$kjHC6tbYf3~ovWBV3>}qZS)GuC zDAMT4g9_d(;ed0(T_Vsyl_}yJ)Ugn_JHxtBT`8L2XZRH56?ust9aQUMJ(VKVjDSlB z*zYAanlZKad+{)cuAK(F2>y8+J5gg+?Ob;EJ7_(G{Y|)xl`>!n^1H{}x&MEl%@>JE}v?x#R!O zax)xJE>3X_Gbd0yq0Gc0@gI(=+0*J}J! z_ifA=hO%(BV))ToR^ZIRBgMLZ_0yv}h-1L1ilKLc80FM&AT~H5@l^!a_;5wf%^d6| z=BC>AS&DYVF?@kICLb|)ct1_H3`f8L9EXPbh+V_`&E;kp@Fh}=^$|Z0SG~<+Irlke z0$PB*KwoDy?%upCaz^|X#DB#{oOkY5f_VhguNWnSOr*!AcrR0)9^jw$s-}g=Po65^ z%sNb59HH9it3R&#Y=o*GuE&D^i>c}^V||BQM<_Zx3w;6)I%G{#bFlTOEy@*LnrNOh z5Ig?9YO?D8p=f>@-rL)vkdLykF72Q%iP$Y+Ewi=|z`fzZ7 z`jsBb!S4dp1p~196Tgi%xQOsMs+)dhPt}ui)KRMbR|hfJaiFU>^q}g-$6=f?iNk3bCnMDrMzXpJ zZer7_axGE~G9J;4={>)>OHsXg53y~jx_U!kn@{UnoQ1q9)tB$Ww@vO;AOv_mH6a9}9 z#CHxxeAgllIb*JBju7dv@gc`n>A*zPLQYBtCZE>39nygbH)xf*Uyq6O+A8%cBj$}( ztC3XWgO96oGq+EbQxN;hP^O(Y?JNbSKnu7H)Y*8F1~Q5$yXmE>`UwY8)oEu2x@?Th>pgK8B%kv$4AWZnasYKcSAbbwogh z=>6Cfz{?C=H;2DE4*uI@hA91iZC0B_@pwUamLXYiumEE3nEofDC=SorqsS)0XG=|2hn zm7?qulcW1JthrC%MCujPu9EW`#Ye~I<-ynQAADDC ziF=z5{vpf%Yd731>Sgk2NdEb|{ddF7V#<>Un2vxS-WAK9R7VZ?;obkoZn#-ABJMz6 z#C53o-EKH?c?!AAK*+=zxf?#p-4FNB)PMl==){^oHvWI_jGIN5%wi_8c%nwQCZW%s z_(QV)YiHa>98AJ`E4N>ge%s?_Of>YWA2M$emMbRzdlNnZ{sZw|9D`#mZH_zB!$nfX ztjEfDG-0wZU&VyGy+I8(KA=r+1t*2_oirkLqZ&RS1L~+fOkB4St0dAMm<75K<(Bk& znNxX)vL5{~;r=wv)JPE&d>vD}!9MS}+|f1nWT-I0#OH25=3i55Q!D5D*KJ!A?*LPJxTy2CxZ1 zw*o&94&uS)5M`V$A3qL(I?w`c12t69d4SnqNhtP7%l297j-6l2GuA`I^XLOd^6 zHYtPOB558?+b~}4Bsbt(Rfc!IK(eBnr2hhvCG8}YStJAIkZk>dWaMikeQ`wr`OMTM z29ZbbM3QCeNv516nSF<3C^m6q!NxrC))v(})9E*Ihdn~F;ta{w|B#Fhq6+)t-D@(P zEv^nrneYL*+wI8RIEma{*tn44?(dMi{3FTSP?G0%ku2%ZWTq|*cVEi{$|(wP;fh3K zQ%w4Y?kCxKm}D6q6OsORmXmu!F3EOW@|OPfPmyfm{955F{d;keAY~d>3sN>}<)T&c z8^Y3~fD0@hPws5YL+Kxl3p`T#b3ql;DBNcQ$ztxYc5X-$-o+#1=k6g{|2oNbUy`;@ zlPsu)lzV4Q?2(Ht51BAyuUNfR^)|X=&PsQ=DBP+#yN2PYB%NO8Np3hm(*7lJW~(}C zOz%;0SJaR^?LjgETQD+R+n>eHTh)0pBK}V9nDC?T%7gAbAiJvpnS(!zx6yCg;qzm_NiHY34 z50P~5BpJxwF5BGK2yG z+Q{wo7)d8ASY<;C@KmIfiHi8wHg%R~c{qhR-hZB8CGC^hG+ zBzs^dq`QmT6*z{nE$JeEODW05dE(_vbyQ}Ch1`KdNG9@py2GZVb1nIs*^~rx|KD_@ ze9PFBRI({a>!$eU_K|cyM6x%SWZb_fp>z2!M`W8~A)BJ}4u~d+e`>&8S zF^x^l1~xSrY+9OjQo7dXNXE<(FK4M!acbF^rH*&4Wed?(Nx_YwBr|r2LD}e!${upx z{2NIZ)~h_LLUaG-v0m{S7)s@vNCs` zBmeRPB%2FK7II&=enD<01Ict&=EHv`cg#qtm-#rki@38aKH?0@8RNvt?#0Sp&dT07 znBpHDE`~m@dJpZnPVVd|mJf&(&#R;Gv`6~$>V27Utiu-8!AREO1lHlk5H6l|HidOI zGM4<)Sy#ipBX^jIsvU^aFWIe!c}$Kj;`rSB-fNnBqONTgMLb-m%-hH=J~7BMsz#;}r=xssK+d=wQ_$;#Z!%ABx+(g${v>}6$c z=YvTu8ZH}RJA%TaKjiX0AsNFu-C9QO%T&P?y2c>#*uWDjx`^BXti)X>$?eJOg-TZH zY)|sU8c!}IsZApgK zk__`8d6@P4P6oNldBSa&O>SSdL-nrI%tDrNBnRkxT!rgSb!uiK8;061DPj8?B=4{x z==3DF7aw)}oyqNTmt-6dT;e5icLq~|UOe7$+#j{LO-7D?Bko0)vVaC`lFq^-=g-p2 zhrv8Pd=*<)!tPby>{JcRYp;X*&dW*-Z*w+2W_|Nt=tsByVYrf{7;Z~!uMj! zZY(z{$BLIBho0k#-r))s&JZ6W*#e(ditqaf$rNvr{yZ|ay!@!-36RGsUEoC3usDf{ z`Kq_8Jy!m*p(U(=SFM)FNj#aaj#}i;rcYT$`J35t6;B|y7n{VxY!dBR5q+`4B=c2R z+Kv~WC6w13~(jc`!Y#eZbv(t#LDC39~eaC1&hc6 zC~gm1x~nA=oWK(=W+AzoYDosrs!Er4lH9gGkZk)4NgrNp*>ZRZH@Ef}gvqzmesFk&#{y*Y}JvfVsW3w0Y4y8NF z+7rfR&z8+zE%#DN2gN(>Pco6sVFn+*6+!;NYzCWHiQ@R=#o|JPS2jh9H&GY*C?#+r zJE-$7Aooo+dogVG?uf=0)zOQJ*y=T&p=gOb>C@Tjonxz4&gU#m)fBIUtz9$Dz2!hu z?iCaF!rBzG*|V_O3uLqB$;#rTQuo!(*n$6o`Hg7&-C_);WH(O`%!(I$jXB7F{dQbz-v2nS|+T;5t3b+3U$r83Q z0pF9mZ4$}eXGx~BRV!q3>&q1_=KOQHBjVz<_+xeF22sJiH05*(o1=C%N46&MVWB!| zf&Vfppodpnjch)8R+4|kcO< zQI2F@1<7n&ACvA{7jma@zL(j~7wW}JFR9*xvV$mIqpf)FCCq?IJVPYY#W}M7NJ?*h zm1Ggy6EC(W?ySmJ`K-vZl;YiCJ5fH9-AhT@j-z~S*OS}#ZIWSRB4+9$*hZ9?Il&7g zbJ<3uu#IqM8<7|+-uN>*y5uK{clEy{=ds1)OqFv zH*(v4K(a?9?t@*ec#@pPDw5_ON&2$Jb+H|+&m;ecpGn?i%izwIp#X2ako{}^n!<~n zNya=zGC+{DWsA{BCUBCjiA_z{REltpErfeMxsUScvim=UYY~oby&K4X!&#DPyr4Q< zAf7BzN4ci6>fYp)NEw@gk{88mMe4jvY*uR(4SknnVlv4)d}icTNbYk9Br}$f%>9zx zkCLpcC29X>lKzKCMmCakcPELrJ!|FVQhqaap`78({S=VLGv9X_^j8C^CHpIK7qVrLcdN;fzdVSfZwSe>0aTAfK8HzRi;>O?4llMC zWxTLy;+av2r+C!SF1CCiKV3=L-Qh!8r|3DLj?Zkj9&sF~lqvtBXz9aA9`zyV5=XL` zmosIksjO}DP)c{zmE1)ylRV0H#G)s68_iSQX)dpj?1f2Z;f==XE9938#bPAHW8tc^$d$yhSpd3{0lZ zi49CMCv4262-!U(>x)PRu%U@&L({a9{8N4+>25U~=qg#k5?-LivB9a}m2{&gh5J`a z3G3pUNFGyo#5y^nGDq>&%jzuGV#JXdo_n8U<1~^H-a`M1I&V=no1*4-$UpQ)k_ww5 zFDG*6=8-Jq)tBcia<~1JdS0`Hn8bwWDPCmA+2CjcJ&6Ovm}wsWeXIF z+RFM`R*-+Kp4@G0k=i~KgAS_R_cyUc3gD4D%ob?_uW@i+x0X*RTc#AYNIgSz;+cc$ z6ibf{Md&$CvYt&*=U#G0jHQD8?a5unb3Kn26&bbUU#XG|W7C5-)Cyjb-c5U;)M<;+3rK~ zW-Lj?TM_?!RdvrSW2J6lrEZ=>5z1I+D?cK4mm^7E>#~+*1nXoIt5gQNeekfdoDu#! z^O`=S^cAf8{xrigb!BV>;^tC>l+Q^9urWBw#=v(T`P({E#))hM5=M|acnpP?@C+zn zhat+4Vp1(VzVY4+z9#jPQC?NSbBqY%To ze6^JPQ`ji?)Gw zcSv3irXH{jC3oO1lI_ovyvYrVVdXF8$$OL6A+?WDyb?jOfR*3p0rnrE$w|5myzZF7 z+Mj_Alw(}T>yL6Cnz+qkX&KfZMXc>@tnF>A?M{2dOJ$hUQwC50p{(Uz4&=7qE50aG zAIyy715Cu%@asfQ>;BuSseR57LhxK z$D@5BxtrIMEUT0ftugb|iDn)4;R9bZ7Zky|T;NX$z1}2QF@dBHZ>42SCb#F4B!gMk zTknuNjCEYuMeahmRzvx^JUjAm|C!`zR&E#W+D6`HNN}d`0#^E~tn|@`$iIh=__cS* zUCBD%^Ax#_XGoTFzH!j~RdOuNu@vC)I>~zOs-n&0PCrPpiLFuYY;tEzCuw10QNhNd z>~r#OEfB7M!!^rZJ-I7*X;8^0Es<rr)7K-<@xj+YHxF0rT^tla`)UM*~;}hDpHO@-z&KIqg;F* z&-Sv{D7u+fA!%*oPG_@|%X7qH-SEUX$+4>EJ}hSQb2FUt8A&qoWs(8+Yf^lFRP`Oy z`y6?uKPV=?fwPKEo?!KJ$v^HPl5IS*FP|oN*$*Ur|3b2ujgos9xr0}d49sHrJjoc` zz$hzQFqqsKFOqB}PqHGFWQ4z1`ghEoV6IQu|B!zmuecH$$er;l$<}O=!KcKTzvH587u$CG`>8#? zJjPdf+b8ftir@JslD)5x%w9~gofS2Vcem|%tsilL!kf}b-lU_bZpt2VM^|f7Jbp}d z(YucmTaKyT`kQ0LYsat)n^;4UyaL1*aA!INQRV#aBY&TxBum)LC35D8+?YmIG$nxI z*^eR_Jc#8pBu{_B@(9VJyvOClo$L~&`RjEhqOe?jEHmHWb<*7mWN4(u~pb` zncT%ZS?c4-9Y>QxXRIK%?Jbf{yb298le-|7WG(Licv1aLx+d1->`7wFaa_ecEsBq; zk3{D2DSjer+)Z9WrSk#L(?IEB zb+S1!vnHhPqX=z0NP&yUeV8@3jJKui=a7FTYi=b^s&>{~dw&Yg{f%TgYj7fKaGIvU zD(<*q6^=k7WUTL7{->N+S>V6v|wu@ajFCk3E5W0%z+~rGHyBC=X=+Oa0zbPV$A_mmy#Oo*3DVb@k_5SD>1$|@x zCdnzR^%<=7KCJakto0Q$D4vmb-eb7mgQt@Jzay`$KCU$#rJbV#Ut9b&?jKp8aZA*8?=z>|HD|siip6x-w za}@6m*EDUu=FZebPN#sQt4OBts8zCtm$Qa zL7*@DZxnBwlK1dU6d#^a=M7Ea3Y}(MKWZynPvdf0D<26hBPd-Xo8~gkuZL%plEV42 z5scuuUcy?I!CKb5iQ;9m+85iAwa&gy{zv~qGV-h@#RsQV&&;E&c&(8XXgN-@hYPD< z#p~ti?!}6i;Y{%=w~^ey3RcL9mClD-cedbh!zrHEV3NisH7OoHqZ(a$z9P@a*Gakz zqMA2}>@#?{uThjqk&V}SsiPO9@DcJVpYfNhq(sVHk}(`^W`*lyg-id4!rQlqiDz-I zLF+1VXRtoCu|C=Jk+OpIB(0U=b@C~#lmC!Ipx1xi!UXjuZJ<=*!Aiz{=O< zM)4b2`TSY=EZpkD|D^Er5SpS9ERB3DZRO>lJ1uoa>hic-is~q#@(js#y;$+CI!g%^ zh3~4PXSA{&9%el(VLhy8J#1$^tYke*cwT(*t~zSYVb;55KE|h*Df?*FyK^el^Bk*K z9xq#6{KT9Zb!}#7IK@whBU!=270LB!=jx~P(k+7HHT^>Ii&)!Q2T(avco#d6waxuG zir2>d6UobHU&?2a&WQ`Mf1D!L^La?ZMRG@Ha0cIrIkmWh>8h~Qs?HNLSlcYDZOsFz z{9@KNg|*E+Q@n;`E2CN4rm(ho@e!?!k6^j1ZS|Q{T!16V)*U2!*qSu6G4~H9e|INE zjC~I)7@uD`Avds)t!>39^6%yGZ{zVdve`*_jKb}+NVfAtb?1SI_<;P&(?}L4ldR`* z0>^4@@$q}AF|&0y1-9{Qj^Wz&a;N&|Q}|6*POrJtYwq8$KOb`g8p-X#%9-{pxzo9~ zyZFpCo0Zj`X2bnDPo54jtR}siDIqGat&W2E*mj328ul0RPk2$h^bd8hz9>-q>mN8f zJ=ClyO6ZyW1{B~ayN2?Q}`f$lUHl_+O<}n(>%P5 zY;6u7BLBiLlAUx=d06Me<`W+n))H>ugKZw$k)y}RzvnE;whJV?Sa0fwkh}R?@pBy> zIQL>b#Pjv_>gb8)H56R?CP{lfjArn`Ad;LbJ4-dCrt2xMa*zw54G>P-2V zWX4vKZB8V!*$UO)A$OrY$uypy3fH$Oko?ar6mvdMM}>tg;Catiipt6*qtk2&WeOYbt89eMWl{8u1tc$XafxhX%6JwkY*cdp zP4O!E;FG|%C53f9fo)4W*_KRQV;v=M;)A$5_xDvEhZ0^ZRX9_;q6m^L5p17o*$%b-%=I6jRb!^kg%^Lmyn3iTPZ4rC z!%!ZnDKC;gzSpwoLv`NL9zLJXRms1c?T*hZYM&1;27OpRo4FxP_fdQc+n*-3){3k6 zvgBa&3~%%2Nlhsc#2+3yda-D zVa5073D?VtAI%f7@dCv!XT^`^{I9az&gOwmVZ|@v!}(QSPSmsFD;<=N@0TQvWEe!% z1#DyWvX&Ptq`=7aB=gvM*z(#SW+M4Ju{wr@kh_(&zwj8j{drP{@wV4t*8Y-h6kfpj zv{NUEN19Y~W}%!R<}6T-*b%=uYye~x4f z*Xzy-j>m`Rqk8I`FjDJGT@$Y}@a`F{7aMs2Q^Y4hO}EKEQjiQ|fBOe0qno|tU(fTe z=>>8Ze?`)tD_s5!xr;bFaDsG;^B=22GusYOSQG0&8_)UNspMbGHlgeYxdZG-R`3lS zg={n9cqEHCpD?al4BLvM?v$>bXGSP>hNI4tt$T40HL7!rSbY(Ts6rmaz$xMloGWCu zv2kc;<6ys?GE8}oq(3(@o%JDNEr;{sBJCEr%h_lId`|8==n6T7I|q@wi=6?b+VzyA=&A)S`F;qwzn}LL8@^8%` zS;U#N=94>+&4h)=uXi>1pDQP6VM`Fo<85!E{Ikg>&eX-RQTJl)$$O0w*0ai2B$K;` z(h3D-~6c?;TE>+NS#hQ|L;ya?9%K-T(l)~-0#`qQioVSeJ}Pcct!^1QkHKa}2V zRVvp03|=L~c~Cj+T%SZ9Z?C^nx=22#dBu>sjoY(ycCrSUx@<2>u;C4o z^*n54Bgq}e%f3!F3u$Z?a`|Xqz*eD=ZD%f5#D$L@8Egd_7f=J*>L_0q&Gw3SE~#Vm z=3?>1C3Vz_1lHaz)?S6DS|~TZgtgO&mpIX{P+pynk(|QeS6O>cv-SpT5-TpFv%SVr zyco9sF1yI>?n|x0#pZ#jMQHtju92DLh~<$)l{ifw#!r#>(4EX9{C= zX*m?onn%*To8&nj%_fs@{Y+iuXyGMK9Cxl*P=ZjdiG#t_EOJSBH_%VfyKy=Q^Ay>#{&TH~hPjK9bU?%TMpKMV*sy?)!}V!I=t>mcN^#i=yVG~6gW5_Q>QzEA149c-k`&W!*#d7 zWE&I)LO?z^01kl@059Xv;Z@SQOTf(*A4CMp!9H*doC0;A1>69)!3Yeo{1|Hv*bDIe zSKW1RD--|S1$G0`N)QXygM5HDed+M>ZQV7{0lI+=w9x^CgXLf=*a=F(F>nghff3NU zcyJP22Oc<7%?2SL7OV#+fVmp~bpsm{x(+NC8@^PX6I<|eoQg_=g&+!S21me2a2?zN zcfn+P;UNnkU`5#|=W+HQ&P zZBZRF4>+Lb!3j_eY|O|2goEXv6x;x}fjShG21y_X>;)IVU0~;k4hECKY!CvLfLL$> zTmv1T8`um(g@M~J+<3JHKlXuAa15LRb>KG8IiXN60!#-v;0U-o0tLCCAdn9ZfJ2}G zbbtx2XaHCa_JLAx11yBSKM1aaTfoB&!!X$m8G#TH*@|}-g~P5c2Wv!1t2){~Y82WD zE`aNzq*Wasa0!P$8xM37NCrE>K2Qpdf!koZC&m^m1W_O!)ClD()iKy(45kN21z8{; zG=NLs8n79Q-T`jF4}^o|U>_(2$3)~;>iCEw<1kaeT`E-2X=ye;25|e>c3LQX5Jl--k5-FKo&RzszC#|1g?PzKByH)23x^Sun&}iW8f6f zO~jCaC=d_!f`g!A5{jRU)&Vy#0jvSZVC!Veg;V%Z2QGpZa094QkQo>U=7NPF3dDmW z;3T*O?53h0fCrciLO?#~028L6(jXk{1p7cKI0jCE7NDCBTP0tWGY(7#3&BBf1x)ru zuYmO+3*>`C-~?y@mp}*T1~xO$Ixqoj1v|kpa1peC5i?N+SP0_5X0R6=lmSe)1vATmjd? zE#MK3Lcweh0+xXFARin6hd=|k20DOE1cnj#fglhLc7lDN4qOB+;5JYfV;+IIi!uID z_>lxQgB)-L+yavyLE#_-#DXl44-SAspc*uQOQ0LrEI|dp1mFjPKsZ!F$3ekTyPK^0VlyN za2MFEL}4HmWPyBe02~6>KsT_7MWJ8<@B>?8b&GVR_;Cu*y+ zhyw9oGq?h-1CI@;3J3v9KrBezfWgVak87X<_-#aAfN-!JB!jJBC)fu{!7)$=E`sS# zqd>3_M1gp)8RUSy;5xVk?2^$qumr?{RFDM@B+o|+@uM0vfJ>ko*rcGfU^!R=lEF?; z2QGpZa2x1^@f*C9J4twcgB4KCCJY6*09IOGy zz$s7%E`kwh=vOcoM1gp464ZbT;0o|~7DN54Zm4cHe(d`bG65ICbkX#U>TEf(8EHTb zxB#wz>%cA@X~ASL8-#!?a0r|L4WJv?Y{7H|6M!EG2g|`4kPPZX#J5kGaj z{Y9q>UR|HurP{dMi{sxHCqysfL?Vv6_S2fptiC8Gv?#S*>d3M8a=1^vOPMO+Hb9oX zE+O^taQTgaD$hg8*Z3aLnEkg^$HGU9@)f03<8G@r6sLQsXZNMX*JS3}JG~6bEtfM|{vB>y~Q7 z_fP-xqdG}hBZmH@PE!)Zf}hlx%3AU4Pq^uO=5%o!QXJ?;>{~ynll3!ah*90@d}XFs z)veyIqF+aGi%*He-Rfx9Q$w-gMg8SF6J0ungSR@1ue#MSu3Me^h4<^v=_7?}kLv0= zePq9Ibf`C{zcf-T?!leBm->gJ%dGi#xQjhK>KOM9_kQX7^;!2Q_>02b_Kxn_Piqy? zZPqN3N6RR+yX{B2Yd@_~R`>O+hldvB5qrnM+E1Psv!4(ven#)D5xaiIi_a6p`#+;g z*NPv0#_RSIri-b+s1NEBe8scBs8h`eGx|Es2JWUuNNdaq#^DQj?$ zErNAXiAkxlKp#z~$xqV+e~YEBBsWa)aB&nRW!}pQ!)48?S_bPLNP7C2gnL<$A7}MM zUzpgJALDOr+esO$yH~zeJo#}}m<-nO8iCOc z6UrS-e(k3CUeq6&M}AuKX3gxE3wl#V=|-s(e}>n z+D~qQU%%;iNQ>gDw;zcIZKxDKOh;=eYX-?0J!*M2;ZbyO*v7RuC9rlHg>f28ORG%} zG09Sk_4ecYD%J0ZVyDXBt9tv<9MwZy_(Uwgea0cX>T-+fXDxL|7iWdS34-}DWT~Sm(6m&(wgGEIJMMM`} za9uxCL_n8CS@rwBs;-`z(Q$tK=-2gs@71eUugrZgRV&cCis%4TC0VMn(h#~TQqH0U z6w!Y?h!h*vLYJT86;Y2EU0Ulr>jWH(LEE&Y5v3~cGXh=-=~^4sI?bhM7br&Mq5;<~ zS~M>-tjKh$CkR=U0M9yeMC zynCNFo@(l$)!VkAlT&_q15Km|e^*WS3*th-^_wvKW*CgnRWLtCETUfk7uw3TX!XYe z<{_`>+PShI3+;kP%qj@NN2xr?GBmTkZV)0y!OPGE7ty9L7!jl9Z)r^#{-nOQy={F4R;72`5kXzzJdbAgd-7^J8c`6X{)GRTC|Reu%23)d$UGVni#IX_kG6 zN0rV01n=+5BhxMZ01a#8?d8bCpRMy|II`%OMtChfK;Lj;6}4=Pf&|m4pfPSU=(@(< zTxU)??P?5OKYi8Mn+M5`UT-%?4vq5S6kU+kc#&8}$GzTuEZN+I3(Bd8FBx>F2|X3` z0^e2AIlfd;$0pt^XCRHHG=WIKM;pX7ojz|OGBsnpy<;^GvG)d&qpg{kG*EiTU#9i& zDX5i!bayQJCL7kKs3#eYaG*>R4)K>EAe6H?rvV~Zk_K2g1<`gDd`!Tp8@%x$Seq+n zBc}nBALor9Y)fl~tY@RrPbl@XG+&)YRJw*&T>Sc6{bTq$DN_QdNsK z2kGo#mih6B`ILBcYAW9{tvBZ*A_J&zytftA#Cj7v|5GxdVwY*%_Y8~;f;}-=kSbR+ z7iH=Z!SV?-hBDN8?Dd!!4IpoV4r>+6_1{OeF%mZRhQQRdH12ubeN}gYJzn{z)8(8!BWb3N~hqu`Yb&m42CC_@-&QWeP~@X zEpI=@MFpP}@JC@V9IId+;QCNpb6pxvRed>+WqqiyIikll4NgtBW^a7nr4QZF+}kTz zke28CaICVPkH7SxqsSmxkctJZM`gk%VPHcd=B$ELEZRhWEwdPl=gujgS6wx8y4_#P zblHlyfA47-=EoS+hg#2ewx?LPSwC6aE4^q=s$O>sz5|JvQ43PBl!ppXg8``z9hu`y zq{c10jg!T_4hFO*`wzpuGW=Y!`&3e6ZKE~_IGA*|x$ za68ujS(3L`i6E5;T8B{Fo>doOO+PMu>L|JVR->}SEVYPjWloC@tafrs>>~_bcHVY^h2iUrLfzH1HJ1*udbhE?Nw1D#GEN=-&DB1nrR3q?|f z?T459P%s%aEl9!;oU_+N|r#m ze^1vo-fJ3QMs;T=Osul$wN7HPbgmPoK0)f(8J9Ae(iu~ya@yS4n-_~hsRFtYQCW1M zGsb`{OJSJ?FBY(`iw{$WN2i(w>&Zf;>kbgP7*F{Xke(fSAVp(0qM69~2H{BUb zqs?70%?tYIb8$_lmfgfeY#3ksbYnM6{xazqzGTrC-5?sEmfeA6)3ENi%c0x&E=aq& zgQbkV!X2&a;cY}IJ@BF63L4M@HdInIU#jTg9++d6rO`og_0h#1csfv)PVIUE&Y+^6 z-d;TYQ?o91$~ZYFkCRTx;th6HR~rTVVoz^-$2gjw<&Dpofr-{Qv4J=6+Bu7^U4S67 z+o{Av^krpfL%=bXp)S2JwA+~=-c_sV?-Vu+LU0OF*@1XhcAOF{D|=xKwKX7T1ut{4 z2EffarQ6nsM5RlcDx{&zf*F6@F3sD-Rv6GC{X~doLKu(MsnvN{&yqB6+o8&)0K#0g zgbp!)g`>)*!$-DRGF>_;fS6Za;O*FP^mUr%qyQ>P^&5OvcN``Aylrdk+_dh~zzjy_ zhJlU;JS|6wSvex&m4$qaSIS_ZL@%bgTbXY0qX{Sz`e2>|e)^lwn;h~QTC-Bf6CnhX z4;uuwjamn~7!#p!l$ws2?l?Ny!i>*pfw_;gplU&IZso$MX<4=v60@w(f@v?y(B04y z$^^lrY$(NYe;n;g*KI%`DfmYLe-{QLkQBTEQz>{kLzhPAs5P%)peoe^T9~P&WDU;@n+1NGymEk?68X`FkLc>ZI#-1%qNrK zL%+8z#a4L}a>m4|EDH0-6$jzPP!*JL{HFJX1l{58um&7cCw7}?-z&TFH)T)$^)+l>V3i$p^-Civq7B>_2 zhDmDy(V{uS7s8}b5z61Y1)Q3twc>0oAjTxB;w+q39TX2Z;63b;igc?eT7;bEbhWSUgWQ)b0` zS@0Imn^_&&K9*?~ujaW)7$7DagVD(5Eadt@UnUE zJ`lx1qH-l>$-u!%hM#RrrWdnOxyr$r=%Upqf~)Ymvau;ftwD zj<;I~hH@p%&)17-ZjLSug{b$+s`+yAD0PJRoyaHCg&YxmZ&~>a$J_tlHQ1P8-}lxg+~OuGYp2W zR6T8kr_1Ox4nKsXk+*^y!_#Hr;6t(?RsJwtu`CuWeC~m!^}+s%Z3Nt;c)k=oIQWp5 zEJ&qB8xV_8X=St%M;JmH(C?{Y>=p3oFgO^3Q{bdBio*$pkaSrH-hrwt zX;jwN`!VKux&1KtjqtZ$`r9uJ&8S38spO z5tbFISh=nPhE|m4ZEr$rrc_Q^V^}XZQs42Wcy*2}>e^pSt|#`#3L=Nr^cOSu*Z8i2 ze&tIg<>q4r5ujW1#mxH2dy!m#0z80B=@YIf|_>Ec#L50IVGPNkja6&PKJ8 zMTo|JbpHTv+lDrrNiPh*ygbuKUx_Prb_XJp3@YG@pRVIeCOtk7=3rI8cla}XgK#OM z0fVqAD5o3wQbD^ov68+RgvCJ>H6M&MM^zdP8;nihDj(e@uIcpBU@&LUMZWl{YXM{` zXd+)K>7D|J2Iv*OWYa~ylu^g4alv7Zt3@WO_%4eM@+Ck&^Cg>l4#6dd%J_nfYQB`w z+e08wPR^l1E|)J^v|uQ(06jhwrOBo*_^yna55uLLh7A*rzmqSO^cr8P=+|LbGG(Pv z?r`vAQZ-+)Xfs~|bbPp|73T=S+HV9{vEI3H1h0F1^!NyP0PCGkN1$+iYFLO%fN~4L zoK4piLNtdq7eY~xju(2bh9PZ=u*F_ZQ;LMiYxu5`ju(NYiW-iDwu&_BHxjv2_~^!w z@M{IO>_=i5g{G=^XT#*sJ4}W^W@beQ=KgA!F=rmn0M#HP)5IW?nW+t@>(LaMmlq9+ zSEgCKTC+9KfebTdRxF;npt5}40%%82Dj^9rXj?Iwpt3bf8%g<1#9{PV zF?t;v*5)7^1?(+BuVcd*)UyQc%Ahj7_-PGaGU;u;WYMoBaC(5cjzUdj(?q`H&^@Do z1?d&Ol+i^_ET?v(ajBqDqmfuick-o*UK))mz|o;|;_9PzV^9T^=`?W+>MMg*je(4x zUgJw9T^!@hptr`N=SUmt?SfnQ}#y**as`YSH<$vANJ8RzYRjAxA#b-$S} zmGmiJs;KFB)H&Kxk+}Nkp7GvvDlPRkrbFYQ8?9+PwE3xHDK42bkuO=aoG$@-trYg4 zHSr~f+D*VENTYC}E)$XOeG^2!FHI2nUc`mo;&lH+q*qbdM6b`~OG~3QlJL>n6TO*8 zNhjwu5JCTb4FVed1Ya^~*EJ&VuW+HlNzl__5-bc-(Iljo(QSMwrxzx{iVFIQFO}4M zGA>nAFd6N}mqrUFqd)TbX!B&a+m}wq8P1@XDY*D4i!Yf}#g{Bv!HaVn4N?s?i!iIor32+?5Vo||29IGF&ZP^GE>v)a-r6uG z=JI3j!kN|c78C{->&;qVqJ{c1v~jdPrd_bNLbEqRYl8fWEeyi$7;UV;P;6xzC@T+@ ziHlrH`&dP(EOJ&*o5}K+R7w{BJ4$KO9PI0y;uNu6k$>%?d38d zxKf%>sb`{1qV@{-{xDdZKXpJqR7wW`!-n~DVFRCDkTwjRTUi)BCzqIIgSK|$$FHT- zrAoH}9kZ(28E`}?O%8*#$l%wiOKBzGTH8(VqN;j6Z6^&Xn1@A(-L=Ye%NRtG;(tQ$ zqq3)l^UHLLAC6Tshgigp)Q>X@)4i#ox|Jo>E2c&ZB^O~Z5hKHuv5nc=UiKfOhV3diTA}rcERG1T@thG(n4$nrjzh5 z<;{d$DKmAuv@MIv%td`?>UL?f^l8{KLV(Uh`?pJl2vc=_NWh!IU@gLyVn+$yhVoFU z5Me4l&oeAaH85B+b!dg&JxI(d6{1YZOv0`cmulWD_Vz5jRERCbb%?oW?kv4jh$;p9 zF)2pV2W;ELkD(O2kzr-mz_nJP%efymckKJ)6BfTeGWNi?7AZMSW*$ zc9m=YD43rmmeLZyt!(95_jH6|)YbQM;FBYBbf0LwRCWR@`EHKx6D@}L zYXGH`I#;hNEr$4`0J5$y#)w86Y8eu~Il~v`YM!e=3@LcOfV))dFv3N_X^AWy41*CT3f?H-b$~HE#4X0Nzt|Qma5PK+ zp`iro1l(Yr5Lm(j=S50BQf%`pw2GgW#QJWK0vA}|h)CHPCZN@Ie>|HlrLV(a)V1oU zcL+GO2J1i-3Vgay!JTnnALR{$QORoQyHUWKYP`Kd(x_www{C4oC(ti7T76WYQWeiy z!Q-2+t3YikI00`22m=zR_=>wRt(%X1B->JL#91L256ssJ!sCD{NPWCPP)d#kI*fW% zaGikj!(h~_g88KbG?*|L?O(zC!U1LlVK6FL!Dj^QSg7ZXrml)OErq4?7iu1;M2#!> zq=1ok0zJA=b0U9+Nb!`WvWlZ&Di8w-J|Lim>4 zg5cuMTA;^8itY4D)W6!9>))Q?(~Gb@sOqE=^{?QU1?;;Hrr+%FG+J{lo>Yr8Yj!6O z!OC}TvO8F+66ls|ah}T7r%gR}2p*wtUlQbS!wSJ8N--Hcb{AZQ zm{7w~{m#(CUETHE)m^W3byWxr#kGjJXy5g^t=cHSU;98;cfIIbj@F@s#a%e1%VMo_ zsY3m$-e|vogMi_Z{3Q@b!?}b~S{EjO`d0!Q1$|}w)-B_T(4SEh}?Mh&=fb#(( zht%63a7Luu5GH`?RQs`|-C5tx8?eJ{MMQwl4lDSufWHfa(X18RzlSLAjo$Xk%Yigh zrh@s)BN&9J+l}7jWO*Y-oj@9@RGHklC+paBqcC~??J#+*NcjXQA)8QlN^AXIED(2- zZZaxO!HWgF(d$V-_1NxX%dgSQCG7d*e;s#-U=Mc`Keta0nOU-kVSi zd1Dm=b*q?;FcUd$)~!NEui!!O8fG|QFe+NXdj))|3Cvh=vu*}jyW;5%&$1ae-3&A2 zjb#P`KrwA(Cc1!p5CEI*fHxE1>r(1*i*6VKKy{wW1iT~8(?WNbNVVL>$AlI4{{;88 zTSEO+fKLRg+-uMbF&H8*+mZaVL&0A%j1qi%3rZkwWC?swtFquPwV;!{RnJ0e-G>Fd zDGWxE>OcA;63}Db8tOj+KCQEVS-@Rtby(}?vq5889|mjv{B8lCZ01R!PijNmUcjgI z@oC^k9MtLNBMwyQo)B<;7>qbjJx&TVVIZsv&2$4kgn)wYV_3|JlABcqsUYfG6m1I^sdW{d=?Y$}kx5px_+>ek%+{ zJSaG&4@*04)ACM7Bq*4_T2o3nVK5>=!A4((=ZC?F1O?X!cv~2Z+E?%?0iOpoL@J0b22!pj=Kej(h{}cuz2$Xc4fPG7K z)3o|NFW{MBuvXvG@>%(&Fj%i|0e_;yymO`U?mvK~Ju*<=3N{8o8okHg?m+J$Z)CLdo3zS;8fGHjonkaOeH#7WiNTyA z-ntW{)vM{R$PFoAmQ8ntR`UV<^|+Lg3?B`HQQ2y-zf8c6yL4$(wt~+K*cS$)vQ?Aj zPtl;eyGv{F8Cr|yFVn~tUlv?wy&b7qyu>UYAOe)5(n?q*zp85rQkA%pF5M-z-PZav_1UJJg??YE>OQQ)Z&+@~`-gNXn z%-(DmO;{;E;t|sK;%OmMDtlC{^5c*g=71klS~I0Mw7PA9EwMazrW#FJ^F-u?Q)ydl_i%A=Ym zF^MQ%?rj{(6Ber_LoD`|@+kW$Pg}1FBbjty1=`Ae0)25gnzwBXf>9Yf2HQt@bYVG) zYr`n6s*nH0F`W7U>cfHqdl^K&-FwdJSH81K%0!xz^{v`}X9jG=j3EL5Qbl_V&jTfX9l>zuzu^8BM$P;h7 zQr#*njO?Pp(aMtv*i?Y4R)sw24``lTCg2?}c@pg+izJns*2exPSd$*qsw{wTRi!579bNBjO*2M=T6wb3<0^QOfRUTsM*Z1{4+Zo0 zGV{o>Mu)Z7=zbN$`D@Un+GZjwl&jYY_}VpEZDng=QNJTgr@f(tg-Ei(B3lcKn+5CF zYjl@tVbLE;{5-mfL|Y85MO)kHS@O}Y*2N>Os z?_m@*4Qui|>atE3(8koQ0ukf2vejeOB;& z5~fD0>Pc9mqwjlI&qb?hHNyoZtEMQ^ucK`Qgm z@>MbF5b|iYkLVeozSFI9b%Wp#1nMK+3_BchP~R$p4sb{w-Tw%dfhvx3wEEsE;Ex{B z3#ZjLzY38@-u2$LDM~sBi&Y!yj)LalCFR*u=ggy$eV%xly58%xGvcq9DAtY4N+mxv zZl5ejtDr&Df0jBShy@t>`}N*HNP{*UOv4H*kD5KInHogdRcGEEOQ<|5d{k?&{IFK_ zEBxJ0bQX_>##4U~g;V3bAFCX6P5jD*Afm}hfLpyc_&T`ZNwc;3~dyX*W-MbLk&0KE=akXkYgEDZNl8MoHlF% zRzV+Zf|g1$H{-5~25iRh0vz4AZZjX@@X;=Dk7?^>aAi=tEn?a_aSQG;Y0Vaq<#A37 zkhv9!c=ci{?t*mNR%Dq&yS73tz7NESI56}VT*_(OUw~E6oqShGukc+Jo%;*UX=LE! zM#sm!J*eJay;LM=6A4h&TneSMFZP<>)Abr7iWz_X) zcmW5co)!i?{4}&w(g#m_hr@t2&tPGI107Z3>Z50#kq0_He+FDwC_IacpNgJ^hD^Hc zS*XQvvS;D409|@k7?8dLEIBlbFG1S819p_r7dwEJQ=6S4%ZWQ7UP;S$f~ATM?nD{! zVJ7D;905v%*;MRe1)I<5cVkGvPsj$!p$P>+|eop1A?6HD9z=*t5Bi>Pbdd|hOf%Wug4ZrY)QQodT}2*-2VGCOZmaQ z(z7<68TXgeYs+qLZ0E&~?N!wrN?@K%`?Of%$M&l7Ynm~9dY@ML{McUQzz>oUYOi=( zQ06OI<@1_R<*=f;#S@Cwa>Rz3N7PRg2E5{JJ6QRv93i0^60fHUjnQ)|D{JgXm1#0k z%e5KH(iW`hXn(xNC`c>9$`K=~JeLJa{;PU<5F@JL%}HVnx4f#g%W`e4a!kNGU)7z3 z$WSG%!^#YeJ`6@=D7ZUTWrgJ1uS+8`lxZgfJb%A#8iGPekH9Lcke=41`Judm_Y3&D zFj(s{{8)q)QjY^#-W6IDJR#sC*PszkzS6i6tvH~CRD~7~t+5h=6$kJ(sj96Ct*_ue zB2Z`y8J$i$4|rRp%3E1c{N;94R5w;+%$6b8lI5+%hR{%KisnLiPy8wa_zxTu(u!&I z5@_4&c$Q#$M2m?Ng6HV#y5kWOD*E~F9u!jC8<_jq(ufIFtMxlDoK{v3FQ%pNJIs7< zg>{7%9Cd>4?l-ht^e6k51)Nf@)QEdaO{EqkHCJ(V4c^q%Xi;)Tz_AsGk{jOjHcA%v zN)3WU6>3sPR&)28TA?ZtB&v}e7Vv>LaX3$vr4qrR#;0s7135VSQ;YFRd*~G*nJ%M* zAO0(T{(}x8m?HRPy2X#MQP%CpLb1>oIC8|)Lb~Q4J}6X3CH1i;>y9O0A>Dsaw;G|M z#MTP<%`h0DqF^^xh!_(#|j#p`rq|0}R42 z@iw+#ZRJ|8vR=S=!6h``szOw#3UOm*8KlYY;DzC!v^>CDoJu*vqr`b%e4lMm=&O)2 zT?APcKcG|NYikGdhks>JrdhmN!#yH+N7qyaXXh`xp_;C|GAF^axx;7#0f_^|hRha+px zZSQ%%cVPOx;0UJQm9+T?77|tT`4PCIPe4kDWj$)dhK~EmVI>S$& z9|bf1MDhn%ie%Bm54^o;=!cj`ZT!IN;}sJUuwXGi#3e|>_)7tDs9C ziUmv8W4Kh&lw(*u;H{Q5$M7%(AMX8B+^191k06Ry^ZDYZdvKu%{gKa+kC0CmIgdkS zfCe1L%L8wo^ERQn{*lw==7b=vc+SS_PoJPX z8T7>`!gp;x6=favDH5~jM!v%)!lx*CHhuajSaPWOKj0j^8SxLWl+mqxhc_es0hS8- zhVLq=-AQnwx=vy}iTAx87FQn~7gto*XJE#gTAzt5Z{s_>&h?o$kG6g8ZM5cdR2rUs zeGW96s`-*bPx1x(2Ye}`cK?L)wGo4xTwecPNacHE zpn6c0$;dQD&zN_8s4y~36efem6~)^E?#?9Nzr69anNn2-k1Go1ZGlKtGR;y2-z#2z zc_Wfnrdho3yK08~LE=nf?n3r?!GgJXi(vu1{x5H{B-;qh;d_~xF8m7~v0-ieIfeSj zq%L3Ta7D*eClxv<&Q% z@x@Q){tx>?=ts{$UlvuL@%C!2IiKq++Zb6>S#3~Wvf0c`)11=XK|d#(ZIZjg>)Fz1 zKmRok71{Tpp=49s*JwvJ46mqSuXQo(_#R&t7NpXkd1gEE&n6#Oh6+-#AQ)AZ^QY9Z z4UD|VST!}7CaT=er@T~-ievPnK2JtB`W$&06VbC|4y?n|`!G5%<4qiF=Z_hJD$18=SJ@FCu9j(5Q7}_bs$Rwp zQ?`s5K}ur+WkG8BEowiLhJ7n4^v-X^xUlP61V}c0#g`mvc~*=Iqxe!r_nZYMhVir5 zyQ?7cJM8OK(v~8ES(WkH~olkvtbdX^5k*~nnwv84TH7j!5`x-;m>y`(pfh~C_db#G@ln3 zzT2JXD4_#REYwQTm`W)4AI%g#&!z-;ceF%)s!EVnVbT%(sz2B;d4CBW!=r#pa3dVYcU9E$znJZzb{2@Mk6!pMx**j4#s6}x`>5k( zj)HU=cbR8%KVdev;xb+W_0ubtp*xc0>7u<;elN${xV3gAk*@rsC=C$B&+-mCqJZ~c3k|IfRsQ9spa zN5D_@`Rm3Nqvl;7vHvSE(frc*v_iVI7Mg+QEcMLv+8J|~mZb_f7 zYuJERG%y?2+KeceDsO98E;Ai4o%2)GBh#&X(d(*ES&I>(fai8YD)F7~0hPf;AsLBT zGTLl%5r&Nd9Pew@&`fd^P<|sb-m?|sL;)2xG}{ig&C;eZ+34I0jPVO*YHL-QW~oOX zq>6BYd1+@ueACueRTi?CU&$+=(+$m5A-FuW#gK-@hVWDZ&Dq*8^bvHCu4)vWl8Vn$ zf`39I9Bi|5L%*a#EDg0*Kr0)W?L)9Oaoj54cN=N8^0ta9O8=%T{Yw~(Xj0BUDc~NB zwW9DF7D}4mJ}aPLV_i8yMp@1uR)T4bHOu+s3Z;BwbB5o7a@5gjFY2gqqOc|`J1rEp z3)ts1TiI2pPijxLfHX(S_+nTn8@)`ERmd}3m3J|=$YB~(*TGdj8 zAW$r8u}v;CBvPztx0nDegwKB;x zt4xRl7u@>QZ*`$2kHKkE>*wj2o^yRZRZuRKQqpZT0B# z1v6_xo|EYozgB15QwNNJ;>-CMZpqcuj7zeOK+P$|%b1aRG(||+uvTm51w6Sa+Mo@i zf|NA>8S((F43pL>=dyqg0B&eY&4mWWxwA1;?V6$BMr+G*rR- z)fVOLA*hV8#`O#Embi~k9IA#Z(?t+u@n>9AliR`kgg-r$xTdw~o?xrg+C~f1&{#~! zcowGA$uvtHVoF(89K*cfe~U<@QGO<7M*O)ap(?++LNbL^O3YG;@KP%Io7`g~W=%59 z;?-i!kI4aefA=?uWO`Z#|4pySvhDAO6V9l8p@MR z?%MHIMDTe!g=eFJ$BS2T#@P;&X;LYlsZ+e`1ur_>sUcpOX7OrG#Xw|?H;U#hn2SHk zBma<1Z5%4akbotCo=OD+e-CIpyJOb1)Ah}JnQrlG!=)RsHQp#dzn{N&=ED5y>2tIV ze}P#tK~;cS{9!u*44hYUL#Qrgn#GK^q6`{?Xd7=7;)}2|YvySDGTq`Y5ApMN?Z+FV z=7~oSTKLIy@DDr)?3jalj*YW&SeT-X7s@g<@Q!IQWU$U%8 z!u&w7@bNyy0xOLi@+G4a&$0UWbkwne`SC@LF{pA8zPCDHUQm30Ni`&i3B&y9T3z1< zojJy$8)_=2iobuQ_+`4quT6x~Q1Be1g5F6slag#BP`9d^+KXc3&@aiDRoF19QQ63U z(Pj`X2TVsLauN8Udu>wF2(aPKUMdsUOeM!7v!%qpEtbfW==6 z6r@#keAq=5_q<@?O_D-EDi*D|b3_d08BD~7Hf6dDdOr7|Z02pC!Iaq^HV?McRlp(Y zx#?K}&ux$Dv0*qwh5S}@T!ZQ9_NZJNhC`I}e&jlsPKQZr4&m-%Fr{|T^M*rIX-m=E z22tH9BhpGU2$c)Rb0478N3wF)COa>rE*TixZr}B!7{CT zmY5||5t8Zb6*6?C1NsHq2($^M^e{6}kE?VqXuaPetXc1;>h$?~`Avsv?dI(b1 zLZDpJz?FBk(T6v}2Tbo*Hg&3)vdZOz#Dvv>3Um#&TF4Ane>Drns@{+Jhs!)Nv$Squ zu>%_z!z1SJNDMKtNwJmFG374Iqzrwbj?Q`s;YzseyNMHx=Xov@8z!`c+1j$vaIRzjh|%QWGvOnyN_ zl_v$=49e39-GZ%3>lRK5cxM=_wSqy2(GTq7-j#T;f$3QkbVn*4&AuWH=+uXC2G4gf6a>U9iP~oRhU9d7Jr`z~~hsj+q z+*Q&yU9dpFk>;*uIzO%-C9XcYvny5}_&d8Vbj1<|kDR+g2D|Isu&BVv=5At%acehV zS@dK#C<@?f{=l-SO?O~9RK%Ac-P#@6%kVXSu$0p`xKM+hW+Up}!|Z{~C-xATFYkdh zP=Ma+f%OcYK{xDaW;x4!G@vKnr{k|gntaCjATIPtFG#oOW#(XsGpd)#C#%=+B|x9@ z1^K7Jj2xPnCi1_BFJ<&n8uBTpbGXo3KF;4~`jGz=pU8ie4;f;Y`fVRF#4dGAItq_n z>a29wg+E=DE=s+N@9@<{zRRMX8N%jjzGTxg8OS_`F7gHIG{2ZhRQpBYH~W!TPG9-W zUULv*s=m=Sj3H5ahapyL=7&?NzFVWg4~gg;WSWc(ep01$*D)`54v9&&Dy`X`5imN2 zwl^jSZUz1EXtVu%o4G&E7PPg>1cfF6w`g^Lx#}MEVElE zH*E;2fg^^{{aNTk?3}dbb&BDLK18NjIiZEAVxK`LF@!E;X~j<0TG&=}5<@68pu=cT zs@RRu=!Z~A0DXvU2zpbc{4m3R(1*x$%NX>m%0;|dv-qJyjubLY^77l~iuXu3FMS(8 zAEJ!V-$VDKlNdtYY_qLxqyDkP%M1%=h4&#c-O3k%pz^Jc$=i^KK18Njyod@_exB%Y z{E0t(YZ&xYw&`tX*%+w6t1a2w##iQ-t;sc8J2p~st~uUqJe-k28;kH|=?8MnjOMQy ze1eI8eGr29XY9ZDP#pCi1%~f)&7tl?tvaPpY#*~Zjp}U{xlgQqAdV)DG?VE-Z*#bN zSpmf{I{E9#siB|FiUK4yt~FS8aGLvNG5W@bWn3?=;AI7=)ujT0>- zcU!u?uUY7xb^%sEaa;PozUBn?WeaUi6Z@IN+%;@tO`h43Uh8KTxOdpM9rJK|nKK4D z&E2212)=W95Nlysi?Z~`?Z!vg75&Zr2}@IiEyhM{$f6yg3_#$67L+p4^iW*BInceg zCA6L$1B ziz)Eo`2k?vzYh6;N~GBX;p<{9hw$}#1I+>MI=13SDXiFdwdtm`LFOQL&3UlwD2DR2 zgYZ!BGAr*t1S~%eLSEa7bk8-qG-Vc)Li+ceG{@jAmjE##B2XdWl5cG;ZX z8;e#@%I1r@^pAr@XRu?wffrprMjs%qE- z7`?(S!;=%tiSBGxfZRj_Eq0$_F~NM#L=T;ZZL zuS`YIuHc?UR8ZP9@J-`h0eu=e@M-2)cbe^(U#FR)+~W3!07U z_jsx21&5LBq9bKyOL$-l#*g`bX@C!BmZPhwUv6fhv&zQM(3FmrBd?4ok0Xc@D$I_M{VRslx9PwscRY=$Fx!B0JNnRgWX?aqxfGm` z?n{nJGl>pXnEX`v26^`@?ywW_d^5wq;~epW40WqCJAtVY&1aG7O2HIt&L7bTF+Bn% z%^-}Q=^|y%u^Hw=F^(-gh(gI zHX=191?2V#bZ(Z}+;jK<`%-B77-V;ft1%OuuGh${L7Yr~jfE~CDdrB4BXNSQ213Vv zFpLc%*}33Hx|KPLE*S>i)Md_g|1}JsQ*w^}37(dm5C25xnA82UVXP2Io`*o@Nb+5f z10`eZ6`C^NZ0SstS5KQOhS8XU^HJEYHtEc=(7s4Y5~y>WB{?8E5SISLw$!4TVG~{ zjTQUnz!!V`u@0lgO7R-qHEg`G71-ZxY@CJ}#_TwU(TvqMtL<#m;RY{7iJyu6YV~t~ z-T-U@!kmAmF+mde-+|2jo8T};S}7*}+LZc1!YF9wF!($c|H9>Z7|WYGjC=_hW^I_@ zIOBbQwZNef3T=ytx$5V@UxR)mOi;&$8=Gk-TinffF^maI zW9!EewqMt7k2P#@p7C**TpuL{EZg`zOm3)#bu<2>%hg6G{a=`1xYGD`y8E#CVEr6; zD$^2JsBW-`w6UuVUzpt03WA~CjN0rlLA~_7jgeu3I0RuU%`?V@$?3u1Gv4xSR zi^Amk=;5Ai+#4oXsPYq*t_l-W!@jJFZDDe{G1RvBIcVkePoNj2IF&tQJNKkj1&nOEM)RpEKGs7|r?YIZRIP>avX2!{l_2_Aovba+d#_ptDdvu8PwDLsfz0kM-j& z{uf|a=!;*Iun{TKXwbod?Hh&ZUduIF0aKm7oge4#z!R4)09)9CdQ}9Bd|*%79d>vf zetVU}xWUHs@%UP!qLW?--7`5x9k7p)pD4d=jWA}QF}}0Iz?4q>nxNxXKkn$0x;Tsj zc81}`eA?B4cc$boe1HfT--ThrmC9PtwvBEMT$P~iwt7hw zJsieP+oigtxyFT_m=)Se^#~qlB=vF_Gi^+dnO??iz)EaPA8Pv=9|GGWi*M96QQHn+ z<{s)EObtR+5w7%JU_Jj(X>a32U?H#dwzyblw$Xo#-YUX+(pqB_z_~8T-^8vl*{{Dk z-eKHlXQ&&KZ458vIj54-y*AjmJ`B?bpy9?AV3-?No{*(i<~js4bVIAjow$Zk^>YepDG6Wg2D}o(0to z<1IQ`YbMtAUf?j^v~?JDicw^_&|y?KWlF39a0OOZajnC6+DZdfr(lPXWW-$;n%Tx0 z)e3@Knb8Z_qL5CytJd^-wk(Fp6ofs__ZL%}C1z5)x_={0wGNb8%fK+a=oVYx3&Upf zc6C=VZDkS8mtph;){XfRQ)hrwRT5|5DV_D>a;^i`#!|NjbXN-tS7#Wffu##|p78!nP$l&r?W z#m2&`U;<(25juL;wOkt-gu`_-G&+W1;iX7lOFfsGNv^tnf@tX+W?jcw*D~u`Ew7#% zp{x}h7}6-7>TWmPF{>YOU{z1mw_~p(XCvkcqI@w`Aphx*$%8kuh$!|nkO_ixF51jF zw{+H7*ZZvNTI;%1UOhV?(o9Of39=0Z?}Y#U1rmQ1Gus&-!v#uwoTl7~{exbQbMOj| zi8k5y4v=cjqL!UpFD&^yFgQ&7BC$ijPSehRx#KabFpOD!IlT-+*<;?RFT~QR*@j?JkhpC7JO&8^Eb; z5?*i^O_&qEM0pYab5i>~)MgnkmOc2)Fc?erI*bt# zeH5gRPTvj2_dwQ4vhYPVRiusq`M4y12Dx04%U*IAYbBZTH?H22zc!F1>HRVnOo%=Q z^0FkK+J{-YAf0FT(dT!=2*)d&N8EkLxjx7?lI$2t?GZ{H9wKLgGzG8o`d7%j51ML2 zN%vbxtC7@JYTOO7l_cK>*-XlQX)&HfQoKZe3z1D<#rBL$od~j%B$t3BNw(N;ThVd9 zw4!GysgIR3$WHQ%0_l*lqwQ2@&|;j4q?QuB9b|J!t^?UxlFx(0h9f)cG)PO+7a%Pc zehpH(#q-}#>aQR(q?ix0)Vn4563AYX{2JuLlDz#jhjG6oV_#RwV%mUg)QEcCXEt|s zd5@;tkIlFDu!H3gNuImkS043j0Eu33mD#+W@iOQST2m2jJj>5=8{qU9<4w>rY11kc zqvtt?ajnI^1$0BFV2^qFJa&QHl0NezRLXQu%zqvDnuJtS3VNATbLujBRx3IACw85* zAOrNGX3~Pcnob-iy-?m*M(D4xP9x3|X%go&)>|S^fqu}GBK=aFMo)`p4rqr(&(-K^ z(0K493U;qXKcUfYf^Kc`oCZC|q6<@xh*a>uj#o4|C)5626uTplqj5Sx$hE-@P$2vOkGQ5B@@P5SWmeeKC z^(^`qjdphlr8m;(rl6I{?LjZLWFG;&&7uc&b#k{a+%pw4dhUlr_jpTJI`^RH9zXBq z#D}{%8Qo(NzB3-9Zrb9ey%HGEou)h_1j>=zhE}e@*7*{Uj!raXHA3vR(N69sk?biS z>%_-0OCAHcd4kh;N-%p0CpwLeGIik;CpN(a?|oBI;gX^4H0BjzZ)5s4QKojNbQ-@% zGPTNSOq1jiklQ8MW4hB=CzTzX;pA=>HaI_=L2cH+*^ke18aG+uvz^B6lH3aNRUzXn zpG(V`(O>N}9+K!GkhPM$dY%(=1fj8K4gJcDH{amIMx8LT&8;dwPdAW*C1cI4R83$! zfTVHKu*5p2@s-s03&`t*xO34R^f@z5zR!utmT*VHawoo%&G~tXLE;-cOgjYTqb1IQUtSN+flQSZw9$512}sMZ zQ6Nu9)~=hJ_zUpDPs=ttv9b~QmTYliI0$+%yQ^7^XFuOQ=`?PXP~}s0sk66p?F-pO zPdknNl3_Q*omciy(PIepdiM zjd0t}w>a{A8V8 zn?M$W%oe0`+52=WGo~GJ8Vy8JOb*Cc55BpJ?r`WwJa|E#rv4fte*=j*IrGL`Ql!&+iC%de z8oOPhPjU71zs%5q$H8@Vh%5?`V?*Sm5Lq4~XNAc5A#!nutOfbB$imtECo-QfTgDvt z#c6mP^!ej((!pOjK-dE3d%sHK&i+cbg3WWefeXe3x52pIKwd4$f`%?U^yO6Na}DVn zGZtdsr;kMM202TTKY+xOXl5+;(v)pre8B5MM=3Nu4zjHz-vo*22IuoHkXe#UGF`kl z~j8MujBb36Z_A67MLD=bic#49NlM5Tr9VnU*tpV;dLdP%9a2j{}GpUYMMe>M}l{ z{BP+b9bD+>g@%zJJ4>GHuX1s3&FmL&R-~gO6Fa+%yCk`xi_7>yk}JEpj0=*y zt%u7PD#>?xx_Car8Y+6ZFinwW_+0p2ok(2@a=9d%rn_()LZl{#$j%_+WoqwGY5~X? znK}YwGeO1#K|buDSDr!CT*+|ZsDtkr)a|`~>iG=Z^#i`Nf~zNx>B4e_Ax{-Z^qWi` z0@+`Z^|M?&$>!7!AR7y^O&Z93qAN4-bU5_mj_y0WYx*qW_O;$Fqi>9`Am+Dx1dUVD z$%91IGgz@ZCPIXp~ zr+z!(ys@P;5!aYKIGymQlcwy1kH<`M8ULZlJ0UT23hT)S88aPZBgsKEyG*wO+j_ge zvSOOcc#h`h#>7)GlAQx9sLd{DUQ&VYdBc=>RW9R@WDQJr;V_7hdKBaWay$nGO=h~V z-kA?F<|dFa=nkKQ6-#Ej@M?J6NGJYA`g7Pp`g^s@_(Eba+vdBB)egZI({G`u4ZWKM|e z4HC^UvLZuIYN>IvW;YZ9^?$C zWKQ1X!Xky4YfC}?h*OdL3q1sq0XX6bm+`EGeurHFc1sj&@isJ)D46$27rsO&f5=Zg zo3o~O0HZ1WcetRXLdx}j%Ef=^P5dGYu@u;fC|JUFG=h(*LQ1LGk+xfA}cuhh&#>WW^W8n!*aeogA>}Fu(mNm+4SNKbIyV(5ckEB(zKJwOJ&t=y02yj|1X_G9Bn z{iA>-)6Rpaym^1ZM!@cgQnb{J=sw8=_HY!r_krPTulT{N@XGtx?>2BURe_Sg|D1F& z(`_8FQXSjVV#Edf9IKz-gq?zQC+9{4N6f z0b8u=ROM%Z7XYd?O{CI)15-~lBeBbWlHpIl+UOZtH0PI?<2Gs^vP_Ls`c$sl9+4xl z=Dpp<@+eBT0*jX6YrwqWa&N&)Nj;{sa# zk1XK=fQ3<%z6uNny~Qt5?pR**2LBDP-xZMaXI9d$zaBf)F2EFLep^|WSqky!pPw>@Y^VmAYu zW=+(>F!uk+QEuaGlu{hR0NEo7_8(xcN5S^uOF-?TVE+K7=0?rJtbxE~fX(UtLs&K8 zWh*R21(_8hr-1A)Q#XL@CCPU|R!K5roEs}+AyyS4*MV#!Q}={YzX6#lQk{*)(>;f< zn61VuyJ?bf14u8EE!>Jq^y~#$B=MM1n;ZkOoKCaZdqB33) zv2qmT7?9lr8B+`LZw~7D4i<*F*SPUaMsQ35nIg%XL*#m!A?6j3Ke~ln%&uu}<7=1H z@koUmYi`yN^9{&+sXC@xmD_Mz+4P$3#y+RWrXWO44v~vM;s^!nSOxO>mQr%~?+#m8U5H!>@_xY( z)8OEAnhL5ZJx4Ehjm?+4vC}S8js`hZkg2;s;!uJ3MM`X5;l`5(mPkDa^4lnEJ6BkGiq7CQA1R$f1Jl`z1)6ko&{Z1s}tp7Dd~POV$_t{xgc= zg{mpc;(1n-FR(FWLo@$8|R7yc?sk_f=sR3<~BaCdcVl>kJ{zNMm$TT zz5uc)O8)NMZUZm;aa?TyxnGjy&%?2j9QOi7WvOR2$OE1~c3yXU@hp)pd;mQILFP*G z7LX1}-U_m{Bp(KuBFUFPPM2irK1|{0bWiMfrF@7TuXV530?&hdL~<3s>c-Q1&d0g> zRXXMhZaLAH|QMUZ&IkPV96@5WOyL3Ra+7Xy(>#mBLGJ4+_Ni{t`H#vkDF z3g*rrvFG<8RP+Lg=Er0JB$^GAi$V-Hft)T=zW@o(Gef~^+~*4NI*?vT-VU-U?K}pC z)gVhL^&^nqz0L!KNOirzJ*^;Hg~$w$rcBKTxm1e1`6fHQv0b4&956UthG#KQt6JBL!!L#h2iE|d(< zfpkjpd60O=mc{-LWP3?Ae1{v0NPP%ol_Y-#Iarc;hq*2ULkUP6(_sx|AiD{&_I{8D zWy~8RtSeu*J&k_XZNJYLiET%>JKo}t#9T++h6jgu_!o)QKY#wm|BlTDm@8oWE7p< zzKbwam7hyr2yj*u!9Bp#;vq7_!{;KDS~^(gIbhLrmVS?QTr{`c2v9ALA~PI%K6-|; zfkn&kquX+NN2lllEF z!)d^tjDj`%F*>&Uk1)=k3pV9HZu@PiNMrT_Q#(G9*o8mAx?YMdR}O3x@)hNeRQf!? zXm0!JPq4)QMwc7%$CzBl-2m|FC@$UqCs@797>c6E%?1|DYg>WIcXd$y$kKlRP;C=N zV&{M*MhQgE&!Oc}q+Gjb82djj8VGFCpI|otyE=+7`>#Yd^yB}9HkxW9Ej2rz4^_B)TBh>q17r=o+#nLokK{|R>aPcY+G-B1z#vbgNY`eC5u23#161vbD+ ziuBqjU|pkNHv@|{R{U5Ca6uHos^6jue*P!eIKvY)!}lUEyZl_j0*A-=B}zaIbVXPC zH(+z3$aV5~?0vmRuMPHi+8E9PS^P-w>fs(t=8m4mbR`HfSCWr_#6*=-w}5<4kTLT| zc#KLHojZ+V<;O>Q43|UDo==KBIDaCz&xXj~K=zTTy-Pfp2nmKNkQVO^ATcrKOzJ?U z(#|iilHLUJDz{X8aID9;Lvjos=ix;xGmi(^Q<8UpOpxR{kgX)S8>E%y z+N$D6V=|_~=8#~R+z?9>|uG_Y6oJ{D895 zm}ws4Im@16J4b2ji$Qkyrmv9aF_04kncAbwW0;miNrXi2at|JV2#M(+J4tdmNWAaJ zdbWUUMEjV02BcS#e-otl4EC7>tH3`Cv7P~0PqKawvKQrl4Fzo~JUB5Y$ag^Ymt><# z58eR~sjWcb)gb0=7b3fa$TW~QN`@yvwv*)H5P1${woL6<E(l$`r~S*n-edgtzf?ZJO7WcA}$r&EVy6rF9GiR_B**EbK?cH66_^7R&bHvCa_7^ z34au|GQfQ|`CS>;Lw6-Hb6&ipu7X8^GX>WPZWlZ*_-TNRzM(BKF)L|)tbo!yu!Vce zj;!_89ZFhW9cjx*YhOp&4$@*zz1EI-l(dtQFMf^;K6;lgs5|H%NZTVB9fhAtPc5vw z5pzk4-8iXTnX-kYe*Br#+KG3`_<9`$?pVYd)P3O9&bQ|mzUoj%+WE!4N^miQ8NS(C zlU~pN7?~#rYIsw9Vm&NoC5d=3CT9Bo5cQI%{}lBKm>kCX5@d5F8@5K&$db6)9CW^| zM9l{yW?Pfg#^yu~SJQef_qkFWgc$(xxP*;3LDXrYE*JG#QMZb^Q`Gms^f1^*;E51_ zwIW`pO<>bd-37XWPk}|D+KAzE_0IzNp)*^v9MHw>2=)xsnc_PS%nH>Fpo_Z=ba8Kr z@3)|fTO(>@rTs_^O6vf+I&=cth3Y6#i$z^4>PFB-cuUj+AWw1FR{UMmPer{Ws#+EI zZ2`JEv=OzxsDnXQ+AL8Qi0>v*e!N50=mL}C~6nbHEo!v zqeNXO>M~Kch`J5ru_@a*7e&1ay3&%@#Osg_y3!sLwX3MZMI9~bB2kxvEbO+WZ3o=} zwGZqbs$YojP0$@Aw?TJ6>9Y6%RSdcTnhHAKS)hyiORzAETPeODitkzRy(GTv*T&=K zfi7-7=;9WDuD;8~w@iFDitiTjJuAK+i|=Jot3lVlk!Ry|XaKsg=p<^ssAEN)1hx)a zyjIkWqV5$n3cAwH#nh}M$bC9|1G)w$uCre^gJH`9U8i>gUFY-yo$nCwT`az(;=4|K zE5!Gt_*RMU8PE;hK8Y>M#&=^_?%iOT~A!_`U$T!K@PBzs7wd z=fUBg*;B(8!1fzr=afhX@K(!EZuy4&${+O4BcSV_KA@{xp{PZojskhM(7qeigXtBX z&h!mbzv6jlJJcYcz0mZ4vUd6ETE$#a@4e}(Co3-N%*e3azB=Po+|wC;&Ra~utT?7O z)Z3jD$HmX<;hB8}Y3x!F{MAmovsWf@wbQcp*=g-bTgxXwc8az*8_W-JCpa*~>)@CW z2kf_Be*@pq;KUFQf;k~x05694?%VcE-6)Z`QSg>&kVFf2ze7(XnDiu_5jlLoR}Xms z`!}LKtHrI0-|`^yz0f=5kgv`;kBf)x3^xc;?})FS3*|`pQBGFQW!HQ5)Exvl0rK3g zjdum)VIPZMg2f>g9*e6*;IdHtNYt~S4%N$|R)aiPW1Dgh?4M{>&=kM#DSN~QWfXy# zW`eIXOQ(UcRST19jocd2+M1pXU;7%x)|z9ucs-6=H^piq9a*9#b6Iw(n#Pt-Gq@Wt(|n$+*PFr= zoo<$<=+>rJijJ69Q*^F5lcJNncF}Vwy0MqgqM5mts+T6b!viR3Iyd!sZcglC$?1R0 zi)p%R`KjAuqiyTy>{jN5COXx;`6GSYth`SrnHjyjbaSDXS7aLUZ*+D?-7|4hT2j`= zeshXE8aSlj>1U?2{9ECg4?4d#Vb;r|qS;;aC-<2plj#@C@uwLegWZkntFZZ5-k7z@8-kH1jT@ zN)62zj5Lp)E5NoP)z%P-OxJ{ZB(Lv?|F;OzR5Z>;kBOT z!^t`~V^{;Ft`c`6y?!*2u>4=P#H3BpTN1Le&CV%$aN9Yr(m^G34xzhKb_(^mO^=Q6 z*sU1e!3Y*MG#OKM$Mn$)C^muW6nH98u?MvtP+s+Qc0xpzzx>rLQ#DOrDxdy!cKN0A zRna-q_0_EMn>VskS5bqNyh@`>R_WOZtnLZbo(EiqUS4lz0d1U UyguOdXI@pjPDlHe=_B6%0cWV{>Hq)$ delta 231905 zcma%^37k&VAMo$F&oj@=!;G0}Fvb{T41=-nOO~-O*~wO9Ft+T55Y0mpvSvA`7)vGD zmqukRi9(1{NffR2RNC}@e|MRAc;El$^FANP_n!0noqfIMo_i;-v0-3N!v$p{-VZg5 zACnC0_g;>AG4f-z-Mnk=_|qGzcKjC-;w>^|)UXZ;`K(q?#%=AfwCM|f4Nm`l+>rV^ zish?NAgbosKT@Vg*ZXqx%WGbY8Xw(sTjTZW#R9F?wkjGHwQNPqkc2t?t~Bp+wE50E zC)Vf6N|{lrLz&ud)~G*k(BzeG%^958S!CPGw(>@m-T1_}Z*461*7Bky(gwc&>@`bJ zsa44+qrDolb;jjl1Ghi%M^g6_-&=yttsYw2YM>d}q-PcHyK4@fOTQgx*4=+EXY`%W z`D$UuqT7eIDiGygGA`e~<_S}}>)3;3!Yg04d`@arFe-olcJsIPt5ZI+bc5n=S8rZW z1SCH4$%zH>w=LQrZf(Q#>xYYs&N;O&tTLfZda+LH9j#ydFJeclHM^^CAJEF&(JFg4 z0n|e-cIYG-mRSOP^O(dh3M9Dmj-YL=INEpaZ-MW?=Nl;fQqSy1U>&qa1srhe|Z$dUT)bCECW zWiuj+En4?|ls+;eGF+d-rti*(T$i);`N(jk&&-VcaZ%<^QTpVp$OU@9?8vQ)4*eXJ zQ}%_(9!gK26Zy}gQr8yf@OhC%7M;14riabL`d>rncXGB1vbbMCRAKN~wEDG*jh$-5QYa2D(Udl~U=WR1#9& zFs32i8f_RQA2N(@xvo^*Ff?XbeX0qQudQK>YP+y;(X7tR3}YC{JC2#x)G%&h-otHK z5m?+XiX<9FcpN@j7)DB@VJyKs$#tJrhVc$&bQINrdGKd8q8Ko38`F3&!M{VbNo5_& zMTfLd(T^^!WEj6<=A@B4%!9wKg$-j9Mt&V1p_0Q5V{?RICT#e#`YC(lwYYe27UdO>HE#sAU+hW8B~FB*Q3G(zYG0ftG%urAqX* zC}$Y2meX5Xs?=H?8ydzNm?I>h9*KVN_ZFEOSeN#SDMr=Lqj}sYucKP2RNnzAC?$=E z3p`U0DdsJ*7+DsV5nU5#1ceOacZ@;Q{V_Xnd$AaGh4IqV24O1E-i!JTV*+Lo*FG{h z6!Q<2{$vxwsMZ`^ve5^#lItU_u~Q}kF{u>N2pZU_#D$HEM~tGlKfyF%9C=MId{QN6 z6{H0YE=%XbJjwM%YN9TYFQ)bUi}{iWYBXh-A&nPFeti;qjMiC+nk-C2BQYH-7{&%n z@NWTS`V*#eWy9EkaewPV8Cj@N=co6!RuLhuQ1wR_Hmy{H8scX?muBk7yQANGgDtcC`mQ|LoVIExq0f zxrP4z5jC**r;IhO&MTG9#fgrLKcd4JG_!MZXuxZ&Oz@j@Zdl_5iPMdl{r^>%7j8)=2Ea;a5chKaJY zPEi(FaKO@vUEL;Yk7tRlv~JO@(Ns@ruZsHr>sC^313s0}^rjGBR67+x$szPz;2Ck11z4KicAJRR<$A$`eS_hh=3_q?;_P6)a zMMs7u(Rsa=_I0F+Ws-1pW`EPGw&=*@Avz)p&X^3Yu5OK!i#Ld_47#E#vS8gv6kT0! z!GuPlDDLCF8BDU7&aYQ?z9q7HyFQ$1X#*t9x|TYYjzLhH}vr zS+K55K(6kfX$6Ohu1rv(D>6qn8LPd#aFw^#O1B0ZS$2r>JFWDZE~;LeN|o{gT=(am zz7n9!xS}Jn;K*fJ(!QgC&?yZ+4gq9c=q==@Ytr*tJw znN(bzUausz6djptL`P)7amq5s)%|40;O3$$%OBCLP)9#Qc*RrF@^tQeRY-}B%*>*b zlBTymN{^FeiyO{@f8KmdbYwXrIwA{>Qxs9UYaR7vO*P|tM&Ew-Ds0-yEATGP0LeU^3L?%L~#yomSUQ2(SuTy<$xR5-wC%u zMMstiqVsPZJw|k7s&{pYt*X{qbYux2Iy)-skI>1I#iFb8WwQ>)L`N2pq9d~4Ov=L6 z)vbH3Ot$FCf>(4!7OX34C0BRt-MU3YSJqHgxX{tn<$E%H$wJ9h?mTq-x1uZyDNz=g zqm0d3W#;N;mU+VJ0B=I`4R`&t16IG5#hvJi%n4V2MIv;aUaC%3pO&+% zqMVuE*7^Yk$1dw$H^ig)CY6$u%6eEr6j`uta_KzXx(UxeFS@b@7G04A>&lXzaGP4A z<+%3GTEmL0{Y6=X!OF6>braEe(8$>mu&jAS_h4Q9WiJ|1+GDE1!nT8#KCZrHI{fZ& zHCk2DkM>p{hjY8hirQ-^v~}-$;jy}DA5|tX!3f8pzt`}YEaPu;-3ntXDkDKhN0>4C zf9g(Io|>Vy??j#6S0(!z;9hLIp50f~$rT(GK|=(|+x6|f zs$_KX_7E!xg^d!?L}Wa!7q0i!4K3eQl98x0($Q~({?zSyUb?EE8_+2cq#>BOU02HX z{YK+}qO zTZW1y=%X2`ap;*CyBwnjlHfKZc+y+C-au8Sh*MLzxb@r>℘yD;tLt)$0bTG?Tj9 z{FIXpxrvcr@>NwNXTb<{ThVnIy{`)CWusI_@$$jS9Q{(ANR$x8E0MJ8pm~-<33fz>%R7Nr%7A~9QVwSc%AKBk4OK2 zeZ6fs*B6~@+?S5AgB0fy&UK$Kg14_#^?b4V@i8hap_7r zt(NJxw9?1YGCS#sXx$gysF6cPWRA7NllIz4Z?nTYj)(ig>yK0lJJQnncP!nelTOIA z(7;CTOe-nF2ZY5XmWXD6HG&f~_9?roa5p5;WLgPIKkAPUk)f1QkxOQ5E?3JXa}<{c zkNRVD{c$Qx3hZ9~#DqgMmH?UhHiSKZ$LvNRJut=&WSmNjp5Zu4Ar-Nlw~ez>b{yQF zsr2DiQN~+ZYP_YDF#dt8j~p|^DoQp4NKre)_m!d4?l43WU6Q3T)eh(tG)eZZ@hY+0 zy`ZEP6s4dRGK>n4EEKXl|NCI{ZvDhs;)NekAZbsjg3;Me*twT@OIWgur&Q(W$bPo7 zw4(Bs^Vc8yll76ORCx5lAXx=VmT=79L8a=N6Bwl`(7(>~(|snWl;|^#rc^nKMrXZb z0(IS4@0!5iW=|5S`d{%@5pQOHoib6SIRksD9zKyFzY+pZf2Ffd`xD|a^Bczb2sZaT zhJm9s5J=!*`qC(s7$VKIi@r6HIJ)TQNetG_Myp~fT&Iu5DMC*jt>XQXB}q&dy>OB$ zA3e^>Z%t`CKX-v@H2kFLEH9)oMv$mbfZnf^B`)-yrl;YdT8RN2jRdaCY2%Yn;$@MPEd`j(J8!N4ri^ zEfT?_OVaZt>YEc)F+J)T<<(J>xLUxKdQ^{|s$zAZx;Knx8LC8qf>DOCo@7vjM$#a? zZ<0#UVOc8NtUXBI7R$`1Rg`X71V#$isdpDUL7@PwPB;BO-Bo-=# z>P}2I#D6=X71gUJs~F$FAsNF4jMev^QdO$lD@^?xZnA1Q$+}q>M}8xvp*X*4B&+if z{bfKEjk`&}d(aVi=OKBuAEi6dMD@+*NJq3DE!R;qR9Fb=Mt9wb`H7Xr!e^M8IzDZB zRY6@@~LTMGM`bk|eIds)jo ztGo$i85XzV^C-E^3i2r(sk?6ctcq>07?q8vJcr75M@4F$A?N;_jTAxT)X&ybKkH&^bckN-VQ^*|-uaiWwJu=}ftPU(?$l)6)BM3JTGp($1DC9j)g zcU&@L$-wV58`l4|@Si?X7nq|;M&Bj;V?}Lwx`e4m&tR%4skhCbDCU$3i_)X6gn5hC zLFWjjJt3@d;+AYkwtG3*I50=0R<-XZ++$pQp$2P1NE`(&f)P}MFn2}k;VB`2;qPEZxxaNsQN4VI5ldjE2> zx^oBXCh<1nVHkVWuZ-$?b(k5WM?LEC>W%YMcvhmv2uQk1z!X@9g`I?54pxIK09oiY zG5khNOhLyKGa`&+uJc(pFl8Ay>{|h4ydxtAzm1q;GNACQL>Q8Db_N2{PYE}`RApSh zaW5+%gKiBR5@9Wv1na^*@L~8KWf{(#- z@Nsw<_J&vC6Yy8q7ybv+VJJnB0SmxESzO2nFc=nuLts1{3QNK#VL3=02CBf}upt}? zWfUI``#_2^(BH8SgJW^mkg+GQ29AeY;RN_LoCx28S(CZA%*8WM=9B>cZo#SW9-IdA zGx|)21>p=B4`;%fa29L{XTy$g4(tx+LV5l_4^Ds!;8eH>&W4NOA~_eZl#BH^EQ4F% za`--c2_A#5z%y_a{0gptavoqE^m*A=gmLh7SOUHQ+rc+sFGxcSq{B^c1l$a#!7Xs9 zm-64r#ReR^T^I}Z!{YD&tOXCjM({9f3y;7q z@F*MvKY~xgkKz0*E{=1N15dzX@Fe^co`OHX)9@eoDU>DQSy%*q4l6=>MxY7&0(OUA z!9MUj90b3Hqu>QN1%3l(!0%wzTrMtCtxqtqUBh88l*Tj^(!~N#I`-l47WPbd8_s}t z;Cx6I3@n3p;cEB~To3QTE$~0M2QrNWE<(C$;8*BXMiy&99v|b74>IcoVxS+EhWTM7 z7y)ZQY3*rH64((&;obv21fPHf;Xqgjj(|nsco+|-!(#9SSOTttNs9iziHnjryakit zK9~YOhGpOxSQcJ{46A{kAU9Qk-yk;|0fs??#c&`$l!V1WRuX{{kjX5N1{v%F?O|Ss!w91><9Am~wcIhh6f%?B#3#0S;vRY&C3kS&$ROb9 zuPw6DkrWx$wZ>us4K%z}E0D zNIx_FhCSdvus^&9sX*g4l*(785um;d52VD65J(Bj!Y=R;WJO@DA|#&A74;!0{1!oe zz3F8&KO&4v`(9cZ$MwPu-k7Xdyhs@pfl@|sP|Bz%lrmxsVUg}f&EFx zJ{+>f2#klNpj1=}Tn5X+H(^D%4OWJGAZw7ohqB8i0UpJn8V<~8mi-v4p|8E7s(Yf1 zmO62zO3G?Q8?^7eRqlOyGxX}?F282@m&@kR3tPfS$ab`~Mr;F%VQ&jd!uGHfWbtEV zP|{Hrdl&3gV0V}XdqCpJGJ0|G6b|CyX@}F{6WCvXePK3ChwCA$sK8E`0dwGBxE~IM zN1#L~L(T~7UMglJjD(|M5jYl>g5zLC88V*Yf}0Y{qqH8eH-~ilKnFMl_Jz;FEI1ub zgU`X)P$Hb~*q1?u32QAn8*als2cCiRAPvV@0BLcSKVKFXFXBM^Fc!n=j-U=)iv1C| z43b;R!yvc<`y}`>#E<2UuCWsP8!#Kb57)w@P!f6;N1a%Wuy^9ZI0W{3VGTYbTN zY2Sxrl6(7JUFF`_C*Wx??(*A9xGX#594m7mXI5bhJOs4}L)>y0A7htk z>lmB}Prv{?31>?iJI%!+9L~U(p?F;9*rgYp!+jV0621>F!XM$cFr37F2W1)(e-A?m zrv;>Rt=p2HpxlxS7@kp718@LyOGat{$G2mgaUbj88mJ5WY_eJa*lkl_chVZ_2@C?#A9atjl9 z7$#Wq3goU1HfdiE=Prq4G_ZCJ48_sJ)t6LE&r%*^Mpc|E;7wXcMc5ctfh}QG*cn!X zy$~nAVTuHP2$Dy&F}rP}-I6wPaH^8ye`F-+FwyQq_D#_4JKAuloww zp=7;sqpD=W6B|`W=gGmBy7VTV9I%S;l`gH@Z&JlgIAW8!!vnvO8`xNs1)ZW55 zua|5g(r@rEtF+#?CHGmZB!hoe`)Wm0uO;gOTUC3~oYQBk>ZT-Zn`1(Y>XX}453_G+ zow{As^4pOr&d65X&X&&P?W&kbxYtXd82E|p^4;5233E*H&QC~KE$lqWhY zqH%~iA-Zv&sMcGE#v^(H(Gzc}glI0TaxCs_E^XFT$A!o1^>3+g{}xA9ST8(DR)$S5 ztA))f7*0`;fP6V@XFWwwryVV$OGf56o&HnbJjrKBLMI~e z9SG6?<*3?uqK3N>O+r)-(V*Qb!7O(`56xhcY{6`=S7*1&?^Pe`ZM%6?^07X(n@!at z89Wg>|F)_YW^YlEyn1h|k~NsaB43ma0Th?jZyI#f&#O}(AI-7*YPHb)sSq_KSSOIVza+M}X8(n3ZS z_r~dto$`n4Rydh0_v;az@|Vz)_NaUwX$zJ-dygvSk?P;SN4@Q#@^oT>{H1mFUgh2LO_o>tZ$-mfzJtNP!x^Y__eF#AZ1gX1qy+c7hCW@dVf~vdq znnS8&Qq|pFtIr|(`43)kKcR3+yzSzBHA1D@w~BBW)z zz53ySs&;PVt3}co$v;R|{hGf~t|a;}v9sOctMIn2cUaYNs#EeFT%D5tEw6dv^t!`T z=M`*;aTM6e!;Bx~^!i~n(348omd>aTIpJaFLK%Z}r*EmPmp@c9{iMsPg#mUgq#aRd zeo|z)RdLP=9Z@wr72fvhzaLi&;AkjAS3IhI^|6)XE89b-e58td%JvA+kEEDYb@o+H zlrGWR8?F}|pk-x$q~4=;B5#B;7=Nq^wtEOq-FrBFEa(IWcg)5ej7*WPT*^BeH*RBO zd(U{z@h5{1R^xU3#mB0-Q`*tG^f5{Tb^Bwv6&kJQil88ZWAw6}s6G1^O z5kVY+?|SNeCzzz*g%hf9^e;W_awzQN=W+e^C(3=u8m(J@qLSMc#a~D-r@T6*j~km| zk4dyoL-yKAQVyJ$G|RsNQ&zS$w_TbyAh_*Ky;}Npn0g`tC_pEw@6do}!T#BZ4P- zG4fqxh8lHBr8q4;TEBwWmw@<6FMarwDp~G|8|Pjp74l~_)HFDT)7@hpNiZ16mN$V{|84bh8LcE=$>c-eXFYI782(?!f(R%ggq_8AGj_#vB`kaGi zu)sN0*#ETSuc$utG1ZWEPSwh7kyFm$DH%`STAot$v2&`L^Tf#=6mAoDUkpQTVW3=$j~3X zihxgER+G&yo9Ome)M+1&*L~-^>y+qOkF808kk(!7FLDzzD-|M`_tTWV*k#2vC#$qC!d)>1oLUGI>sH-h4of3I)(i|SDmy%oqx^lxP40$F*exvuwHP@9~Hpx`$MN;kLj zW{l0qY&>DeSe@2KrRKKjOXB|`YIU0He800?sN<-+1GLr+e$Smk&gm(?qkjqg%;x$v z(a&`B-A27kPu;?a**m`zi9Ls%)208w6NfT=tD5Wff8>r4=k!7me1~9rbNx=R;9mrx zml1r~oV(#=A#~WgDm(<6oR)Z++vrbx`J?sAPlrb88*h6e66#RFavJX&iYTsyonv=~ zT&}m>rTHz_$M154JEOHNl?+O!TCPL>WWHbFI7>dH^)1&G-{I79`#)9D=+A<@cr97_ z1hXlnzxPkle}!cJ*IIx7Ck^R8N7G$wt&oP4s8(1VU$48an&=gOsRCwH8(r-N+Xv^g z`kNrWCy427bn4%^$0X0`(IVhMt8YOYz2a|`;$P6l$(BBNlZJNwZ4TqoW0wBI z0?aM!ivQs6NBr$;qq`x9-skv}G?94YWqoNx{>Hg2;H>EXg#PI^`rbd};q(LgugF*u zt2_Q1)NH2y%hdlfo~}8{dUau@{`ddosG#fQ7XOd>%D*gt-Sm~aM|{8FwcI1R^F5X7 zFZYO3A^OzsJbX+`K#lxmY^zZk`&?d)&WJpH1RdTF9R$u(w8>Uw2cK@-0 z;Q?0Oq9}cWH4;f>uhLWgqbaP)J+|-FTmNG}X2PHJ)Tc&{d2+~zL6)*~wN?6*t$gjl zAe$hS_9J7?swD|#Y(j8^nNJKEfxrq!#+_A5I+?_|WVo3aJ)K)V8K|Xjq{pw)3{^2p zwwfe;$=hb*(An1B3hhFf$@;+e`MsVGJJ|E5v!an{%$+5N5rRC`mwRr`C(0R`1#xz;&Y)H$Q=P|FFW@NLRXME-c<#~wCme?YH zoNg9o7V|K0*tW^oOvZ;5VdfZA%nT%_ioT&2!%Ko0Uwz-4T@W zoV5?D!^6!({^?d*QAW5v^%JSN8jeRAcfJU-y-8#36=A0O?Z&5!c>6vzJHo8tw;Pn~ zom%g?+!Qyv(I{iObB|lVOfxqX0k5@NzPhbyrjvwu!3fIbk174mZXJAv)QZDA7KvItD_(F3L1|x?Gu)J^{Es2 z+_s&ldlxd3L-`VeuiC5k)mb7=Zk@)b>A|Qzg+{n)_16`4Xg{1iI%}>fcM4c`y0YOrpY)5d5@K_enB~NB^`k zudXC%@9Iv!P)YCFL+-_AO?R?O)W3<}lKAbkN-Dc#bf;B$eq~_aW4|D@$9_R*kNtws z9=)0ugw!5=(1!JP&>pSiwV*vZ$wsGS-YCM~Rd1|y(p6HjM=wmKkoM?JHjXBn$=Fs` z&mXh2RBnj{w+-3Sqi`CQGE+@5&U%;a@=|6oznw{C47P7u_LMT)nq(qhX>+qQj(19% z1AQ-YCa-t4PDwFKny^iZIfwd8jQ1DT*HX+F-y-C5v$d}b^*J|Nh75bXC`lcnrydJw z?3`zmfTRxH^Ng}9A-|4t1Lyn}qm!MjHc zCt_K<57n=vn#s|7f_%v=H&mYz=Z9a*3oO!d4k>T8R4?jwISt zSbAh{t9X@BMIVgwGHaGMOZn~Qpo|!OE1o%|LbdC7JdTJ4e$WaI-190G3#hvT{sJOIg%&OydH%wV4n!*!T_8HpLgVQ z-~#L`;fwH9$P>-LMmeG<0c^v8Llf4~JPkj>&Ow2|DYzVd0aw6FQ1ritJPHlmg*@r9 zj_j?1a%3+X7J#c^VJQ0Xa4q(V@Ksm?z6KwbBYLlM(G-XE@DV5;I>HUu`@xNH2;2lm z!Oid~D0-9OHth4@4!8vJd_V9C6bh9AOIcm!61oTLcUgOXrY64u#3 zHomQ+fmv*%SZ4#Da1;i>lXw^pPs1tjQ#jp`&w^*MzXU&rYv4Kf2K)kUgI~h8;a8AH z3D#M`qfip?G5iMi8}JgHD)2WK-{Qcwt#JjGhTlW^`cYe02a3lI@JGF=ig`4oBafFm z=FG2Zc2XYcCi8EF#^wA|&Ghn#uKG*+a*rEcgL#L=oNv}vol?Ur?wPe!$>X>N`r?}* zVLIEFKSUqj=n2(PBYEMa{@Q%u`alh9;woRwhHmgN1;|zxDn@(tqv0e^X`cjBjjmdjAU<@-aqu!<< zW$`pdU#e|3FLKs;FGvc*ozYt%q+lA>VZ}zy=G9^PAtMdzGGCGIp>@qQ=CW-$1?rg( znLfU;;t51sXhjG3g#=%5?d^tjuI19iEE_*+FOxB66fZfLg3 z4REyxh7jQBPxVI)bBlkVj&6h?8z0Yos_Qi}-8Yv9>M0@^ijSO6^=plC7a{}o6%jm% z;Keh#K$@8v{UYZhr1a`JY5G(ro$y!D6VuH6dRe?l+ZydFpjW1u6`X1ts86L4#xTP8 z;*9<)EhssS8zUHwAnL3h+BitCO$3}m@r^pGzidoJkK&9=aI9zSSlcx*^Q$vjjrPUq zF-?M^e6W;`xk+_iu9Zy`ZTXZhAhG zI-E|;Sx@2XG&2i^jz%j9tySkdO`Qd)cy!x~oP40_H#akTc}AQzb)%hr7Uj)Zna(_& z)4sV`P5E1WD(P27Ip@Jt3$unvp+!IiKBU+iY{B|)ZqqiP?gO}zGwK7|olt6*j zW)qK<&E27KdRS{BPx>rpO>1+6$L!W1=b?7oDEW4HX-FM(N_&>9tvYyhhoWY0y}mv7 z2}?V;&k)^a$ZmG5KHuJ~>mC%A z+oX5svmK~6W&z*(9jqswPH9Wp+|p(qGDv5ej`T`m`>P{&fbUzO$`jd6okI%hDcp&g zAEoLQoy-}&HTb>yh)(HD2Zil-s)o)e_oBZRCttjDN9!5i`Of5Ft;Eze_-X4JU9}5| zT8AL@0l^XxFo*d%KOp#11g{}@v8^uIHMgIw(HUJ4ypG^tTRpEUYx9F`?=Rc=`e0Yn zeU`CCt4GmakA9hUI`z?@fQF0U4FtW~>7~JfFGRqRdf(i3+U%Cwr`G7!-4MKq;LUdW zLbsrxc8P#hobSQ|f~4*Un3{e6wbR9W1o@aNg3So}wb!$I%syQ#08$85_(`hM&ZobP4U@TA(ds=C=@ z+^2N5Doq(_c5j~i7`N&#I&PKiO^9QUu?ayXUwDk>S%!Bar1w|1Wqltvqx`+@cbkKo zNtLa9oJocn`Uv_jI66tXQ-S<(F-@%VIi*PDe~zHP9bo<5c&0Ae_cl{KFShsUMs<0f zuozd*D%W-Zo8K;6Wwf^wezi9Vx63Qnt$rUyhZf~>#`G~aD_B|}+Zn;N} zEws}Yr{xdN$?j`j(IuHnS~P0x5Rm& z<1DKR)j~FuT(Z0fJs7X9)Bo@~ zaWGyR;I-TuC)S?g^?mW`I{go?<%W>ChIoB#jqW_etQ7s46U6_}KP&o;&{u2qy&)_> z)LJ{r|Diu+C`n60zqzBQc`{p29~f#zMY~S-d#&OW2!3QFsOP-w_oHlT@+&Rv%K0@$ z=j>YD{zoy{?~GP>)LHlPQCl_-@q-@&)M)PI2xyz8C(>rSZn$7hTgE3bqW z)l;$Rjl<0Fgi@%k$FxU%v8ztrfCU>oddq+L3nlbmH(?J-qJX0{@JJQO zhDJGEwHh0p<#Z<-xx-YUIrtjIhC_Zb^RDYlPt7o6Doz+a?5Q!lI6Z~{q)xo34a0QA z-tJAO+K51kp`3nYq#2(ep{+xOsxXcPsYq`xClw!SsZ1xC-{b9TM@5n;*(#^~qX=a^ zA+$whCMpr^2}lIef~7Xg$tG<)Iq7Xc0&wX+mM;oV_M_FSCZ5|c(*MbtivPpLvZFbDMzn&jtz_tz3%`8M0> zGKP+vI5u-g|0l<0j2M7|lx!w3-NlF>S5MqG;&un~DDD*<|874@)pdt*2Xf?sSxt|4 zPWf_^@3zu)PC^>GsetctC$xBr&Nr4N;Fd9F`3Ksk>$RA^HHMu<-lFrJwzS)4xP8EF z!f6HVVA;gT{k0;SQCppCjvF-~Ju{=}$Pptl`e(N8PlvU#S|WzlfnV|G>Pq!X3n_0s z@bTBfDq)t_ReuVrq9Zc7<#DcCXPVX1-K4lB?tYj--rID4tx3vC zfZVp+j3mg%8pMyQC&`c&Q^A_zt?v_5kR9WA{Ug0q&mX`yNy0{&MRdn;-1Su$DWe@% ze9(}s;EPt>2M!WPOBf3?4 zqV33ZX~kA-@)d&`_!B>_p8MRjqE_2O?9aJKH?F9+J!K{)RET9)3eyOuwNA+51FNkP zSEfd8W<*)OIZzDY6*n^|OGm3{4=$oog%r@yjj6lx%1ByQMSWi{@9gyQ198asRkvaN z&#s?u@h*L0f>|qW7{Sd!N92p0AnO?wqbuu#iDn}{@YZ{xSw+7%sp2|Pc!IOQF-liZ048@ zzQJT|fJu+7qLU`mQApZk%R}$U4|o_%$3-vq`E3=xp<~8Z4GweMm|<269L4ayhnH}8 ziO;z3R$e!fIk1Y}cEBTFy_ie`+Ktjalzs_Pk}ZDD(N3{aQE`eHTQfL{^#1)bMrGO! zeJdfzhpIyfLFeQ}BSQc?LxgaDjv48PXNXt(TUw-K3Tqv1^^L6_KIe}Kq0e(U+7`}zhDQ>?`Eb8% zMNdI%FXH>s8vJD|=^0h{z>*b9M3xzAR#AGyfUv^4eije5sp8G~Vyt6N7tXGE;vN6o52)np1#b zLyF}P-X)HLd-CE)wp1vV*pO1z<W;uNYIj_b^G$#QdP^t)M-J> z8+Yv+E~Uj!MgaH6UAFIoefs(|v+JP$_wwe9<7=Vo1+xF(`_qZkofkT1j2$w`YV)4x zDEwq&#E+{dBa#Hcwx2xKt(x~(_klHuJIhbdNz+-Au4#7T1izd>g6`$6c!FYtPX! zE0pGW2f;i~FnoYxfQfbdJn$}Hmv_UQ9Os8 zK#WJN6=B=-e%7b+tnvCL5e>kf_;K~z`MHmac;9}nZE zaVFzj4gDKV31@~N{J z`%55}Hx;GK4hE_CEtPGvocQ*jBFmkF@8`uQ(-iML&oUeIzrP~fJHC_j@W)Cc1+?wlHMZ#sIl5%r?kK!xskY4!$HCLa}uoyZbPdk*?l4UZg zX`kP``2quPO?zn`HOIQ1Dw}du?CaHX-O;{2DA%Lx>!jtp7;*JEwyo@Y6MION22@jT zn?n<*DNB$TeQ^$zUQ?&j0G7_RF0Hmu!oDsy*Va597NfUr@q}B)LPD)Th9j!Ro3&QS zN!A7o8Do`jCV4tg(fW#v@t%_>8P26a)Kq$3Ctu-&9?17#mg9EZ(UI;cEuyBpq+oYX z391Oivx08BDeQBnUqCNO}!cwlC&3?lwQM&Jr$-6oeDSdE`xw=H-ReK2hB2!l&puE->qte{ht$SQQ0+H*8q{ z^M`#5IE8xt0?g(dPZ{E2+N zE2me4DySDnd{YU_*KPuJG!fQOIs?(=!MzQuuemCqJOEi%LE79-)|gjS2tGJ?`CiK(sf zI^Xyq8Bfs&tXGO;@~W*nEn`M;YQy@!2c`Y8<6TcpjVPEPiD^Z^#n2W_S1M&}=vyyPu-Qp$S=@QSET&5=VXL;_ z9In#js>U2PG@@qtQXd$u-N|IPlY&w~Ddl=h_)-S>J%rkpn@o|7gbj*H6?!P1vQzm{qp97db+VTV+$R@YcsrNpt{Kkxv)OC zh;Cc#3I(Z!&r=-|ql_u`8QDFn%mIG;xsBpY4(n~#`q}18zx_Z)8IRfT zS6$3DNBQk1E#fyRJCs>$wYl4GKTXNiOIw4U{lr8W&FnaitsxHkQHU}Y=+$pB#I;>( z9*dJ1(tetua-VwiA^n-U>N>N0Ry!`=S4N;KJOo7~Cy)9Ssl zz9{iAoQM4wTn0sN1w4WMC5LZ1?wcU@nSs5IeIMi-D_McFTzrP$vLpB&eu4d8DBmjz zr~632vLyWmyL_hfJ6PXwZwRkoZ{*k;!|$Kg2GU~N5qGGjJvQZ{2M+B|ABm~#7Yp~DzUyxbjl&0Td>^ua)ZHsUVu-G z7$!6sE4{D`q|F6dLCH`X7{=FR0-R_u^1%hL0OWb55e1pCjfdcGups;w7J~Vx(IT)Y zlz}rH$X}&unks&Igroe1op$4@F=VWKY@HMCvd~dcO>g^ zaSsQH&|nU0h&?}S1S6ohN5ZDqqa6D~uo?D}umvmyTkF=Zn>F=}*Ud4Zah$}A;yZ&&QLl*7buOrD|`k@Is&i<_BpU8 zlt$hM?t*>c8Q2g01_!`WG%fL$0taC)qxi0lIF!R-uzv0hvx|oZYSt&>;zpq0es`w? za{H;7GM?0`mcx?Cl+UM>qp}C&%7JcGqX&AO#}<^o1{APj~G7;au!P;XHkGgW2C)ut8UP z(=3{`2iFT!0mgFh;vfMPA_v5$vGu*)ZeXQ7dsq0ksY`A$|1x=4SbVctG)Z~vPo;^! zB&x!Ly`)nm(nP(w=Vmj}%(q!jLOm-SvE1lK!DRRll$KHu)`x|lOi%Kqpo5WCgvH?pFcF@HCE#~33Erfm8zs4rrjiV0dMO1HVQE+aroaZU zEbI--L%srNeXD2!tcpDgN`9xq>N;bK`K*8O7JK$@Xr1hfYk`&wI4xmm$oOw{%+@+# zt69c>`hM*$jyC0MX+P>{cheI^+kTv=j2!#L={>xB)wlsFDFmDbWjWRa_JGa!w9+Uj z$r}SZ;JyfU!d<52UfAD)kL!?aW_9z!t-9VeswEv~xoPhQWm(rBO8PUP3^;=z4@Hc@ zQ1)$xLaF6pkWC>gx{7cNb{Tjwp{%aP!?kcCd;?B`@50IO0(=JkA>aO*%7t{)XQ7Oo zGoVz*EZ7yk0H1*KpzInlZw6Mv7opru^ATL@lfp~jN7$FaPaubl0tVgT6)2PaN*D)M z!wzsQd`vp*IxaGCkb)ZzU&sEGW1k2&U|$F~!ex+0?N&$RS!`f8_MPwmWMe3iL3js#0Hxo32vf7TVCE0hg52B&C`KzG6r*tpyU0&Ma%H)%fS+Q2 z8J>kasxi(%0=MMv!!NP3-D25~z!BK-V|)!GxOtRszeN~Hm_$Q&++p6#vL9`#+()BQ z@$?z%7wNSd2rn805^#z28q-@sDX!Kq0rxhLb&1t)S(gL`I`Y9V*=szv9H!#$Ls$j* z30Mt&4GE``)goAK2fni%0#{%?>@wtYyvh1VwM2Lqdn0{qr`g?aKe?0xdGdXPa?Q~4 zA?09#^-1hDun2Y@d=TVVhw9ZjqeL;ew^4^@a{-K?AHLtO%sbiG3~P zbh7moZi)CU$NeB==^5bTf<`uEezp8DFB*HXGo2axp+OHg0Q13vka@;d?11j$ztC6*fwwR1o&Kv!MntPa*#!RpfVKw8d+Qv z#6iBoT^P28d>TB^1r~vQVNsX~Ig1jIo-Q7z!9?sY!X)?#yX!k0-IqexD$&0 z+b{+DZ?G)<2bP0bzEB1zE@Gf47J-$p^9rU>8S+N1Q5DvK)ggcF&8PvpLecLD`F43= z7_0;N(wzLw^T13;J{LB?E?@a>2-ia1Qwr>aX(9Cg54dQI!w;|t{0}yRVa&}fpnTQ4 zB`gJ7!}72VtP6R`JkSJofR97og0#Nk%?nV0vDo>VS3u_YN8$6Z8(awaR7zkatPs+Y zIhqT;^%B?#AA|ehi&NIuyd|e6v8Q7{?eH2D_uH_4PSU&PD%1bLK6^=2!+J?C zdJyWRXjy}yED?t2YkT>)i2dAD84GQ#;YeluHv%qzBX!k%W~_&&pgL>1C$8~W++|@h z4i<(_L0OPYgcADGP}Y-EpsXjeU`sd^%KB)Ues!N&+5g>sJ8eGerDe5I-`dBf`%n9I zf&Hw8o<~_CnGI!Ze*q@LIZ$r5=E9nAK5Pyb!0Av*Ko+NqvCC>_349wagNGgY$Bz9J zT!H)d@FjTFk>8fpka+mZarg)F%5dNw%!ZN9&?+0~Yq1xE>!92|z6v|Q*I+mJI?R9@ zLX2nULP_9!xCQqGkaySuOC0y*a3}VcR6MWpaj_AH9QeMYAY=U7y72+?CG+q>ec^yv zvK&Lgb5h#xqXt+@MCE?>b1Ulh6G~-V)eB!zFq0xvH~g&bzu2K!!U|$C`^MRV0$glr@aFvx{L&g>w5a z9qxzxMTx*^I1_TOZ_I|*;T-q}!cGp?LTUzKmVgCQO=v7_aRvYm_zEi@>$85_}!jgl|CB;>Me>Dcl5G!0oUV zWOB7$E`A60ku}X;E(Reu0LQ`iU;rM1bKqgP8Xkqb24#E)I5bK zZKx?SC>6vUB9fv-QChN46h%=rbZ{kx(w3SVimIu!=C(+uPg~XhyUsr6=IHPHJb!)C zeb0K=T6>=NUK{RUxYgli!Nu4|pRa_#<@pN7CLeAXz9$*(D+YZgT$qJmE8ZTFaCs>& z7Vg_{>%ryeOnuLWVr?%T1YW60fXhn(iExj>Z3Oo!+$Z5)huegHIwX-@?5o=FXybz8 za@DCxK)LHkh8qJH&jafgs9VFGg70VGz7Cgz%UuJ1uYil8TG2Y=dy9b|fZGoAS@|5?XW^#9od_4BOMRx;A1;dzfXfLv5bkGi z+2{RmGw{t(tR)(33~Aw z`u#L71Q#2dmyTjcln0!97Z`TdyJpy9F6x7C3~}|9-F&#i@I4i7A>3lP9H{AVc^z&B z+*5F0h5J2R42g@b!JQ2k>FV(sTuxRDk&9ILI}ffW-1%^;!&s0W8}1Sofxy#Sj$JTZ zq6NpK7o@evVFwlATnbo&p10t7!CeN|8!odu;4a5E*PplHCc|9`m%A|L>ub2&MXtv8 z47eDg>+6i`;BLbAyKr~GWqo_#ZooJ9VEnxg)fMJ2XC0Ti%R{hVIq+9GFnlu@I3Rez z2MON5Jv{0Nn!f7^L*?3KjPvJx=^Ff{blp?J_G9O-r32pE>wpFSHYK`(&PvyD<$vM! zbJ75qoN>YEO|T@*3ZRu2qyX3ai!hlZeN~nGFXPMqTj`-}n@vxAFX1+X2l;=G^Zbjy zmj<{$99JzLc(!T)ZpwXoRT>GW`!(J9L^utv>tAnQmnH*)Q;iaCNIB;3O_twvZ|d~d zZ%Q9Z^?C_U({D+~^$!kK@@*-~hU*Rke}FL#`1gY}K{(ZD_>ayV&9wiz-e&-kT*W zHe4LTjK7$DoOcY2k1cX!fw7^-djzu*%cA52 z_;xHxj&|IFZ=(kpG01J|8&1K|vQrv8h`x)EJJZBy93`7(;MFN568c|!!n;wRc*T{I zhWF$#?eX9$!HNFFR$C{H2RBFhxRPqgRb)=I)H?EPX;**OxjM20TVMm}Qe6<>%dl8^ zk~FH3>w2u5Bst#1{{0;+^m2%4TT@(D>rh{II!zL%ClHTm6j_EVpVRP!p#tNTI52|W z;(2ZHJCC2ERCG>$T^s8iER=`GwN-9j@Dp!nqci58{Is@ys|G)rYS*b1xf+hAG?3$r za|9nCnr2M7pS$Bp-!+hLO9vacj>pSAacv(#zdn}y66FwjCPA)i7=iei@)D4#SR>Hx z8|Zc`dX3SKfqIW)*|vsvKU)%(8#-v-oG1s`KlBg{Oww{6-IXn#_M#SxTfxT(W@!pIShqd21)%Y9L{^=tT-8>8M} zsai{t=}&ORCds0h@VOrDTzcS-2RAuxy2zbJtYa*p8BGvFEaYp&GHq@m$Hf-A`SH{z zbnr$SPeT{D=|WFGHuq(kBv?Z2nnDkj%(Xi*jc6*zIqw+!Tq;o9JT6h*L$7cf96Y+N zXZa<5$F@evQ?kFasv-h!R=P_R`4phzs2%>hqKw?fl+C=6ZLD=01g>h!=R5 z&gi0ivYxVgl(XCLGwIs^exdtLwM4p_wIqKQ%*j#0H1< zxuJ}`yjFDBp&{ zc#VE9!&$Qmh`0mq2>J~Xjus@D>OQjBuB|BG?`j$fjOFQFZ-C*YL`&j(_mW# zw!<1tdRjK0UBFfK!r?FpR{pf?&{hM!qS1Fx%cjATB~&{Za_;~@3zeEIo0iv>&|CnH zH2}gqMX0HwIj*99nJhbFO%j(xUdyV9I$HzD9&fOkDg3Vz)U5^lS__rEJZXFji(elz zunxdfPr8JYQ?XOsig4!_%9Ak&;VCq^>DD5u9|VKJ&%BmU^DfjJ_oSsQE&9JZ7bQdpsxbPDB>Q-`8kkd=VoTK>>mLDGAk4I_1b?N)9 zWYbXk5=v|hX>4<8tG%diYdOrh+K}ez!DaY6et0^V%2UwIeMh!7D4*X^q;OK&pk05^ z8vVvjx1XXyd`Ee0P)LQH$R*T21-`roUo<zckTR>?zkHeX zj2ztrTXotngAdkZM`R%moD%c>FfM&U+_Ew8|IavvI~P3Om;g6+krX zA!}LQ6x2>OpJ(7!+3aGtustcm&O=8SkeJ?14zY{YmyOTphtYPmlV{pROKS7T6^6YB zwU<{)cVw5;LEdPS&^B%EC>Khfs}$c!E|bs-+=gpM{nZzq>WdR>dppacI;Q0f=!!V z-QnT@}Jd3cJ zcW1AMZc-aP+6%qpSgjbepnWvEmmK9Av=7fOA(8bV1zm}US!n$*>eYDf0J_%;Ig4L4 zsoznrIEc6EEmyNcosn?D_ug{46tvHExVQYAq_u@%%&UVbCLLWW-1g~mSIFt6i`J*3 zBW(x#hr#q|x*Q+-!(d?tl1uYtgn=iV5peGtbhDNJfD*q}Q#{2n&bE}%2gRm6^n_*7 z>^|-`v@IQDpaXzfne@9AXxDWT%$TV0R3Qh2;IeNq608;xchja-UHzY)=f2^EGis`KHMkk zzvZ3rQczpGc@>G?)_)Lu!78g(CySy6!IwJ!RmvDCw5273;7d>Nx5=VU2gy;+Hjn3T zk^%l_!9OsI24q10z{m5SW`3;lYLm0*VFvV1emsBPVDMu#SfeajIvD!t@%+wA@MGal z`!I`=GQt1hmKH&Gvrs~6S^yB$!=YSuJ-&(6|O3gv|TRonCKlAqk{|ni4hxuQ4 zJb(5O@b?G*glw8O1pE^o&#%4+ek{UkZ)Q{cizuaUKAwLA^A8077M;I3-Fy*Mb<5+0 zx($WUAP61Frtw29&0i@482~P4(|1FWdY2!ssP{1NW2-=WkWGcd!2jU!{1wcf3I3Wn z6!a2eS2O3axw+^i@MnR)aSrWy38~lk@%&AOgFhSmJ#uKkaPaqdJpXCt&jJ7N9C|n$ z;UE5Z{=8i94*~zo99o(S{WBlW?;HVsY?Wwhawus8^sjk5|NG286#RR0=*$S{-}`v} zZX>~uEg0=W4vilP{TCk3e~bBF0{{ISsxk`t??0Y@)+q1~2Y^e$~zc ze=hhFhEQrA8uEn4^Y3PUY#nJ`htPHA@A_Z)4Z~(UFtCp5t`5eVAUvwWF|iN{LxL5f z`km2ooLmbXwT?C(1GHWy?U{%n(Qy9gV0^6Mk4)p^0)I?3J_5$#<1OQ(D}T6* zkLmn@eoEI?J{_+T?j0-Fl+X$3lwTP}52Jt7ABPWg9QsEVf1p>;KbG+antc7^6n~&S z*FPNN@qxx#|7gn}Xo>ZY0{%cVtABjNA814Mk01F14W#~2YXUyd`spA2_ybLw{;`lh z&~E7;NBIMdlK!Dg#0Od&{Uez_(46QWWBCKk1RiS%qD>QJe+f+kkfsu{3d~j8le*hO#%_cy^x70#yYW_i72CYn255c z6I)LP5d~|&WDrqcbmCSf_H64qK3VQ5dDg+|PZ}(^TV8*GrT9V&-Rc5)?cd0LMzBAl zt^YR?I~7PAkZ=Eu%w+_7IaN*N4lFg^>!l`!=fCc~-tfRsrIn2Ib zov1}Yw6CsOm39<@=6KQub zE{7(H3*Z<8V^?-uZXx)cDXjxf8TQbp$z7#y*OK>i zd9)ORX<0K@-;Tc%{tlr7>+$-{7 zoAwjlSh&!g=FP&APRdNVs(b-&Fu)3MJ6bkV?qOSLS)X1>zO&>s%q(EeHde!d2kkFi zu&MJeoE$PIH0=H#DHt!GEyoxm#h+AaIa`j>?m|OQ58-w3Y`JP|5Dp%(IL}R{BlU5D z+anF%ac;U;`B+7}XUjEgt8|+obaOT)^}Q@CoNucrW1rkXf>)`p!K-`ls=)ASPX}L5 zTKpR3A_ayJ&%=19XEnbD6s%&U13&Q?P@t#qZ?*7mH96GDGF zYC3UV#fw67u)49DX3UWrIzKX0b2;K-v6_mH;pKtySMdVJg*gcDA&cL<7QC94pMehl zxw02@1kQzy`Z#|jl0#g1Ud`5eS{P4~B4#V*%2A#bh*|G6Jkb^4h@_iyWk(f!xy7K^ z;}s9uGh41sb^RR<+V!*Su)RXvsyUih=EnGWNFp3q(Wa%*ig|KV=QKkFCk!u1zoREi z$?J&UJ9Om}6qN|^Tfbx8TKwkZpg{(Gr(9LP1G!lWSLcQDJV|En^fx$uEkV&#NQvrWU+xOV4Vidp7f&ByM#Tcj35fNpN02GO!*=$g0@J;?pyQaBx2ftIy9fX}wm&nqy>`3$EY%%aNf-;~iyt4ht@mL2L%#%SAq z*diYEHrnk|x~=VSTJkoO^njAdE}EC&ekv)P)Rh3z0KDv?_?4ChJ&%E&0QS0QsTH^g z!1GxEU$|6i*v98+V*@0dI<0~Tw#T(IE^3)+iNZDpuwSlSbkVt0?)B1e3S12U8|d0E zF7nH=Rj2gTh{P{A&Ss;Ea<6LC8ARJbzKR=8UCX_&O8yES$|_$iD>R%xVG7NQ?%@+m zu(c2l2d1Lf(cjTHDBjUHNcuY((DNgL3M*V#hjJF>reYX|#XTn^(K z%Sz!@#2VR))|cb4*2ZgO|4?jW=o?c=c8}57Sv|5xh|0m+5(g<`joiT&P8-%BRxcn{ z?RHaAj;)zd46TKuBluAS^r~U>Ldk38#u74Le+_WXS`?Viw!2oWMd_B1X`seQ$fI-X zu+oPt(YeOH3$8Elfa{AG{;Yf#)d(rCBUc$gY7ZC+#D6`IUtF%F_40L_y&X;ia*Yfy zYUDqUMHe>74vj|bBD|_g#?C~D#R{4agVaHv&`4z=%mpdBq%CS_h z`H0s|T&7|VHtP3aTr0P8^|}qFvx6vRha4uK9R!n+e|wddl*)T;cJXego%?_~_DjYN zWDuo9VWoP`W;Txh2|un~hAf{Lh2=U&sNI`7m!ai)U~X5Ub>g_SPwF)yuiCT-q@ zQB&v4$}n$iOnj)t9;AzwCBn;! zc<#%Ijr$rOa(<#GQpP7p zq@R#T^K%FXjANYh4NmScnbSf0K0&AE-~?g^<{Q|F6b_n&8faOZWk{gmdr^QIqhOGK zHC#ZSzgJd5aVp4NrE^APK-a z<)?yzRUR+-@^e8L_k1dQRr9q3dCcfUJ-BG~cfyj{)*?w!IS+kl_oo;;+(ZebtDj=e z&zCZ4*{hP*XPgD>H<&m#Ioo`x_GfZMdwy&>xvDLSY?hSltS?)5IF^1~U!(1}O_g+Fk6abT6vw!SJ$}^S01CTp zxQH$*=gNtoGP$!s=CE*1`H9mR>klBI`&%#`>iW_C1M>4o%g`^-i{3+8*3LDKudMk3 z?NtRRZE|VP7dXDsCbu$mIkW!n@fBmr!)nYi*IqE9ebpP_;bPNe{y}WIw9Rm}JS4~1 zq|TYHoWruWWEZu_hV8-y+b{~6b5wp{lSU79%|4E?jpX@~>&%z(Lz}FJ4~L&9;-sud zZE{^PC*@1BU5SK8_@}sh&&X9Vy~lGN%a_@7>ku^kETWPF%Fbo9;w;o<)2*{|be*9f z-F=(;2K=+U=Y0>KKY~~jF7QX*YS(vGlF!Kjj$x4YTq&gKL@IVF>cGUYG5Q!vtIlDC z|0VD=GI>&tf#=3KxsLHHI(u)X6L-KIUOvP^qt45UedjV(ZG&yAjNk25UGvY&TP3>) zt<9q*r6pmE)$bDeXwQ{&=Mrk|rc2l^Yovb+mWrBC&u``9erwP@*1#=dJ&MV6B?ZP$ z+Fh0#7-LFnUpX8>sBzjg`?6eO({RKR@0C!@cjzC7$dYkKy?97y(4iGWa)B1Cd*0AxP}c%5fdA1 zXzM$1^{>n6Mu=@NDv-7b^OTj>mvLYfak$R3`jl3Q|XqbT48r8`X?fL}gOcW%i+Q?JS5$S1o2p!1Q%YH)Aj zyFT1oaNEGeh^nYRTnry{V+iOW^-KEbWAv-UI9XJ*68JB0H^TiD?#FOhp9}6E`2HO3 zUvSUBeE|1+T=nw!2S4r@jDNyaXvuB)dHLaaVGN;)UEu)wdGL8q?tZt|afSVW(_UIC z+M#I&DdtBxN}hI5qVCsiO5B?Sz-0Uy<3y&lEVG8|)<0F)}OA8M?VyPXY zUle^P2jU1VxF^?m1kNyEE)GZVyz0N;F$T;%@DZv2Y&$~s3OV=@CBtFoiOUox^$}`O zp>q}2!Wq9&6`0*aFPp~OvqjbP#groyIZ6|Tjvd0=3OU;3dRQTwuLPx1;?Ictvxxir z<8&#&5k&=9uc$H~HWD~G>?NH4xuRh_%*c6e)@+{dBmaYbk)M%}!2^DgbL=7?Z652z zrTELg$OY1bLp0!5tdbTTa+UlluahJMpyhw$@3b3epgX!K<~|BgN0;6YBvQeBd9&H} zwf+O;=O(ziyQuFU?(%bkmi&RZ+yan`InPMNeE;eO+5ZFplMmWh7ag|(`2YfN$47g^ zWwe$$i#h2_yVXiXNY2+XSzY%{sMrzC)yqt#l2_&N*TBV;DC!R zZ7jVc;Hs3oiOS&jQ&0MweCr;4dSLWb1`Z>nBDlW(mGQ`QXw1 z1W)xHcs4^Z&s8Dh4B%p~R&NKbumYVP0#J}?Pwt@658YG#8}u;)7(8n2chDs(5cv;) zngIIjpw9nTB<3=Jd-~d{9Tb*lNrXQbfZ+`7;EqL6N{sX14w1-Qt+-TW(22|L$AWJx zTBSs5Fe0N3EM0WiqQ%z+dRx$QOR1^N0^~E$4#2olT5SccG0+~sv{LfZED~uNfDQm& zE2T+RU^fFD0W2w{>sBDv6F?^bOG~Mzr$yBw208;+UrKwdfXxfQvjDc1Qk<71AM+T1 zu^R1gDPFs^sJh5NZvdA|NwZrdy4eAw19(tMRBxrNF+M^SVc-P-31#%D74Y>@q8vSRRPuvenB zE2E7*O4};JIxkmP5IxxL+Q&BEe{3K7``*I|_-dp$lmP7wU=zzI%z+Xx(NG>_lz>T; z=%)zl&D`8fqCAHZO-EnGP$Fy0SRQrgLkVs=C($;CVm_mCgMI^}h70E!9%BvjRbm?0 zc8a7hRkyda&{;#rK$FnL{aZVaH=!7iY`nLK`v z;AW4wH!PsUDzM6oz*d2O{q|MnFVCq9XhAoefn8Qb32?q)!MKMkpnWXT_R~u5d8$@G ze^h}#Z(7JaRV$#3s!DL+C?p%F+G-@dYW_N!#^g5)GN%W(mjyH{K&j^p-d`Dz zDmwX(04!o&4nP>TSg@)lhOi%~6yeci0X3+Ggb4qllFWlk#I%~y!FGc-FuECKZj`~{ z(PsF_5tKMXiFLOmzSU7ta4S-q@C7xku0+`!q^JmjuB z`-F3)x?*0wxIwWsP)inI;#7W6JTYsGkj>VGFCEmvABF}iYAA7XcMJ`_?Seti)f!4` zITv4B*5RvlO~qdxYhuG|Dy^kAupC-bc}7C#9Ur0ukt0y?m(XE{1u9J?^v^nR6cf=W zgNT*-KqW*%KU@|FvAnLcBU1wK{tn> z#!2YabmCYhq9@bCzbORl=)LwZ2RbXAxb-|Xzq~>fhlE~Amq`eP40@*2P_UsRngrK= z85TnLzYr0`y`f0L2c<~fy*RjV@4k;h_d=CgGCCXG5E>LkY zy@#OgWuA8UdV4f-<;O6kv0XI&Hjh~%w#ng$En4r{;YzB6*7jVuGTV+OQV+^p@w7Wk z=6x~fnpc~o`%E$h+B0-6lKL+yUCR=x7NBeWCov1{s2f*P+-4anm{am?;N^|#&Wmh98 z_yTbM06No1iE{SGMSgA!xN7n|H%Yum&FxZ>xTaFXhGRj-)f8bwHi^*mV(IQl^b<+6 zU=p?n)<20ha+9Ho+emHDN1YzOE{V^rybi00aAnC(N>d{_576l*P;>~2u2-XnO_WB?>xLpu zFOFm~r8Gq{CsPI-@_JHv0-H#(lV&2;w5h4$094u(Eo3sC28XjwbrGE?BRa|CY>t7# zvbWUw2zT$N;N4+(msy<(pHkwSnFc$1#|?iA+SVU;MOsh=pNVgM*hj%{=Oko@Zs@)R z1vZ0UEvQK|r5+r-LsJ7zelxU!a}8CTket>n=zS)a806|kfLhR%W(em}gUsRNc*2+F z%2Up37A0IpT2LPZ-}$SBo4YNYyAF-YS2$Kzz@lNEsU_7Q?<6JOnN;J^Lf5jg(6ywB zSfAj~y6DcX;;$E!ncN&ge0sFxause*HI!7xg)0=Z3rR|d^G$ z$CtZ+a_|~Z^JMp!=>SbhM&yq{>h&O6myD6)>p_)~=Ok<;BG1XzO4PWIo>FR3LJJh2 zn$7UPj`$VW$}$KXJ#vD3(AJ7_TcFFg!Wq!S3BVC)MXOpMe?oC*)vQEZTUya+kUe_} zGL3A8Bi4@T*dJ^ifTx;`Z0p?;AwQ0g{~1b!Es<@1hE|50wYBDu*Pv4^k%BeCDt!P1 zEF~3#ilgu1cukupc$jg3TC{>fSj5mW!YHSedwOty-Ur}`JG$B{VWP)0RyaQgFZyNo zH9c+z#R}&icEuNMA0lP*z_m!+a4G(SS2t`78?r8x-f(CK(@``GY^<5q$ys~3>!V1 z0dwzr(-Z~3{xl^zRw@(zvR>{GX4pLRT8Ez=gYm~L5f|GTW zw5TUC8%BM!cgko_Pxp*2o&I0|R(`b7GKzW@T~Mh-1vGfP!uI0LWBpL{Ecjs!NIL;V z%zxtX{E5B5-yi(9%BXKI_XA%BO8|WMxEGX!MKd-SW2Kc z#K0xNEZe-&#HC?NB1RYq&nb1KE~T!%&!M==@02Oxn#hCamAZD3RJ?w#A3tfG4pt<~ zuyl;>5Z%q`7)Jc3%ylkZX=IZQGoIPXV}r`fiy=mXkUNBBy~QMNs@8i%2d5Sl883 zBB;a)oMzx_0O=9*aFBaxp`21O0GtIdFoK3E6H9))IDg#0H5k5nTo^j0?@Z2L>uTahBgm&m-uq(oeA-aVE7<{ z3NtMs*~h>o0HqOh+X^(u!c_TN0Of{CN*s)pvXNQt>2x_Q2an%n@O)kA?SL#xsC~1c z{R$ZFL|B*7%4r+}-vRh7!n%}JP8S*Y9stgRSr&H6sZ$O{l~(~&#pAL{i^}*H4#V@Z zM{^X1b`5A;q;-j~oN5n&zUu%IBdtq><+O-_8vr^+T9+Zq$@U_En*h2;T9+ZqDHnj_ z7J!^ck;tf%NRcfsT2ka9c>HdIC)eOXMyz0c;#K3sKe;?Q&Yn0QP0H!BN%~Z6wtw0Dl3*$Vu| zz~2BU%DQ}8P8oRs9s*bqMYAi{b<61(1OEW{7{RSvsxGG%qmjwzf3;mvMsfT1Qgu1K z4<5}1p0A?l%xFshL&u;9NdV3n!YGHAMq83^E*LcI8EO?#w0(>vPyb*^Y#eI$D<$`g zu{0&wW08fPU+WAVj^i>QU9?xqr zO|gGGs3#7I=)-5U&-w7=33xK14jsrx*9-SfzEa(pU&r)JD8(ACTWNc0FbT7-MHUuL zuJ&wF0B0aA>eo(!dW?Xzgt~Nm65^16!yslHE{7ow;RrtnPaAa37{)tL#miWt8CBqg zV`!5xfoWwhn0NZ*Fj=Whu8D2m}tB9oolP%>}EkLHhVw$EG?0Rq$8zFRk(Q0n2MNUf~R@WwnD5B9Gr>-^QtGf%`)0aSWW0ewqmeE6oDniU@=GM zolJ$rMF?dO6uw%IHWn!{>Z{E8Uji8DeD7a6+<}@>3>}!dX?JxULA19RUfz9dsA|3p zma6q1jix(P`7c9b2sA!lpH{z&ao_U>Cr6QI0i73Rc!%3MTULZRFIuHjuofgvbah^I zMG)9p2~YSs3u`63f($`kg)g6mjfcS$%gOX$8YWkrDRPxoRX^Z`pVQG^bfy;5(F`m# z{O3Z;LvZMtj?s2%0}%lx^E?(pJ+*MN#{C9K6?0T%R_F{%N zZAm=+KEqO6o4f)b0>JHf8t@9H9Jk{ua~#J>Ji3VOiN^X*7;_1?brD+=O?66zpg3RE zfy7spXz9mzI$n%v{fJj_Zty{|;!X4L3u0>p(|+Mx6OKAlm#i(EcEZVq6WYbP4q%+v zVRT;B&-%c#V@tgUxu|(K~mI$O&AgA&5NHoTb z%FfP$3eMD6U6u1ST}Ol0bdBAFlPid`gp=a!sH!ID+`C`XgLfKi&f5uS^nt}kvq|7CrVGxLqG0xEQc32037s5VG8bDG z-#4p-&?y4a*FWpeMa?_iTwokW?zg&7r@81B&$X!(spHm0D_LDc$4acO8w-4p2+KA2 zoY=Jzj@RJ@d0H@e&4X{#@HChi_C^BhE}0f-%4z64OusOA)mHVys`f8Ft=tXxH$XHD zJ+#$5NqQaaz-mL2+0=FASz|EmjrUe;UG+ssm1nkH*&s(C9s{n4+OZdZaUhzqW*Z3E z*HJ4^>u31O>9^P67X}Slc~1(P55LMSesQPQO?3Ti_=C2-qJ+@=`RI1L34=*n#c#0^ zjYFh?-7FPjaIV=(F_c z0#y8=&x(}f_;bNYB`2?g^RZAHj-2psJ{XGMSdbMbn0ttCEXwL9m~pcI4aF-o)e=0s z={9-{lyPC;Ag0oSH&C?J8Ge~#q*U7fh7#VuWssSh)B4|1Y9aF?P%3w8HR%3K zuVi$Vc?*$x7%^#Qo};A;Ey?-~0~pe1gP$j95!NW+#xKH9XzcTq-as8z>=sxH>XJnm zg=2K0%`^CD-zd!2&M#7&(!A&C4y#!Ccolt0;B_oils!)`mnc!bWd^@qqN!qm5?)e- zL0iBZXq@NY$1c;o62w0NOKhAqoah{|9^^~dP{drGPtbvN-3W6XU#vW5lanHBba$8< z1b>U7VZ8@aJl#ea7Cw$I#js}hQYcCXldfpjQYgX-2cT353mRc>A$hTWp|fVa1=fWo z>ql>a^(_Os%+LoWl&}mC79n)0e#-!1;X!z?iJ`9}XwNcufRzNl7xaTn&k^*RZ-bsI=xyHy zeY&78Wcq7@zL)8%1>Juo=oaNFcxkj9^2diws{%TG0D*<2jKz%q4`cSiV?sRL`AFF;VPv@CW2Hp89q($o zU3m^0-aTpF0n`9=kYxw3%_}-B4gg=iqd{LNS@QGGqVDig?&U9#ghQWoc^||!zx~W} z+@{z(=7_U{J&q^^+z=i=q7-s#mU14VKo4_B)T3wv09W;|-PAXCI zpqVmtf5vAV?LDciv4!!nG%gSn*}NpQE3=e{d`+UA4Tz~VK){pdY z(6TdjFa5qI`vKq-a`-+2UZ+twaVhS!5*&(Aw%(3{#UnRkVm`avwsMaYPHA8PXD%E% zI0~W*Axii8*VfZY03h4~t)br=fd_*5Z#cLaM|%ch10&%K`e1OKSF5TV^>FHT27|(I z%07cmE}Uk-ac;Flf(Lrx^szuspTWLIT|BA5G2qmKl`ao!h_i-{*F($Wz;KHETIph| zOSxa8XNf~1{WF(JzDCdT&)mvH^2A{z9~@Iu-*3God0VPjJpX>)s!!OUKS49Q6>6RrBcgvlvIMnpYVPc<1q(usZo0Q8cEsjE31wL&S_*&)C;al!;VGAsG7w94Ek$l^5_FAP{F`L0N>_O&^?PppL+mc`d|A!&wAIp z5LW~MlmJjh)9rgolmyqWLa8oy9<9>A*{DrNe^Z(YGn9oir2^ap?$1Zlx(fF$TcJjU z$x8K-pRvof80eAFMq$D(TZMa3w~%`O4DlskxH_5&f3_6deGK3M0_`t^!U{C_1;ASX zI**~}ez8a_0pN!x3bZsl{Gu1!F*yEj@k{*`lFPx+XAH&vYLU!iU93%>)N*s)aQKNjIW|AFut010D70#Gpv z*ZYq}_z-xswcu$smVW+^r8p$s2e1x6tFhGgz6Dsqz`FnjkEKuVThc)N1HgI!L&sA5 z9~K~wfeirWkENwn;35MX0nk{|{{b>n*>7U5t zP2kyY@L-o_(w~;##{PvwcpnTmO(huxQ1a4W79~r- z^tVOHAuu>T1jF;Dl5MQS=b=SO^M_D^2dlIJl}i4!D%k)A$H!nOFqK3W;#%5E|5%hn z{)4>P4xVY_7PW-6h#wy+=3#+CS_07F0=Ujpu&U5Ef_}8CF=o5CsG1tB?EuUBEZ@~l zUZ6%hN;lh!go2|swKC}W03EvlRvT|*Wl9kgJS|%kRIq|Q;0YN|4;4gymt@f}RECC6 zfF_w5_OXU~ibcZ}@MwF%lVWJtBwIA}QJ`TT&@59!O7Xvvk4}R}`xHDc=^ES#NNFmB zKLaq!6h6ViD^*Jp9s`f|Ie6w9-ur8oH0-27!+xNfO$`|@BLY62mI&+vk9Gh&9~&Cx zXqE^x_k@NofPQ6axbiZLw|{-#Qh+`Nk9H6|=f=||&&m=&iCz#s1fV(|;L}3hV1~9^+vxgQsfi(pE7nVpnbR7Xp>qm55wp*gR96Z`l@N_WLJc0&#L&Gtk z*^g+LJKfho{cM&rT?9t$I2eadpgrD}_&9x_;Y$FsAJGsx1Mzvm#}c1eVARUNxWEX= z|7Ec`z;XgCTP9GPLp5)96;dt(Cjo4qKqXe-8vu^409-JAub6=bA=uaAaVK9j+V2#2 zZW}ykn!J5g^IBFRm4d;6M{%^MiAI)WyaFYES(U{4LCG2L#2P$Ma@(q82^h4m!H_tS zKJ~MNU3~(;SpXd;Qv4GZAP<1!8vtZ_oAN5WZ8N}q8M2VBu<$wXte8mN{;GM2u8`9F zA$%UdI#YPtt2n{oT0Jtye9bgGk?*IT-0Tkv_p%pj;z;O-0cGElCY$VYW z)htQW0`0WpI(T-QJT3kY&o*w$Z-8fiKAo#(@ws+&05<`Al~1YFEx-~0j#~hHCK;(z z!CJqqZt>Z-26%3Rr;5qb;I)7A6oW_m0X#vIXk!hF2fs1!BY?_sqWcfinIm#jgdfocPH|B@DnK-~p8)C^R{9N(Jc2(skRe(-4bz%yzR z-3he#-8=}w6#(8eg|Ey((>&8E{4sd6pTV29!UTJ|oa*br#=4d^XXgKZw#^&dhkiM|Rv+V9}Gr^mh~4GU2d+_4V~ z1^OSLev|2$P)nlCVBkK0YLjWR6{uj~4*>C#DJaY$(LW5pp8%34(<@fs5CeY!cyTiQ z9A+us&BGD=2LMLmAx6DlSnxV(mQT1P_#42Z{SBT8lj&r*MK~}5!Vdw=FokXNA^d|? zcoulHf55YCGJOzX5&naPF|X8in8JB1d?do+^Uz2L+rYDTGQAOL5&i~%LjrKz6u!d3 z??qaKJ4Hbl&v0pfPNvaO7U5C=4h4X%z=(6&0tmkrWf6{zhA^HB(d-4(Guk4&1b_qY zj%pF6@IDrPDcT}zuLWUG@MIQHqgoc>d;ktF0K-h-#5W+^rItnb77N?KGrEAP)V2us zsSROo07a(oDi*F++ai1jJem)9HWkp%R^jF`5XM_$+J~mF^Gyi*#8`wkfJehSWZKRG zIvHc}Ij|0d{Qw*?g^OAE2dnTb@Mw6nOtVd)59(Ni{{Z0U55Q}RNNsdsWpyn5;Ly5| z#KCCIe+s=(SH)`26nfatC&)K5Q7lw(u`H!4b=4ZSQu?E=8XkzdO8U|R0R3dOxmH$6 ziLp9Yr&u){%tM7UD^~4bE2I;#YP4q+c$877S~qVCDJ2d;s0w6oAq|UDqnv{aMOb~{SU-rPM8T^do z6_8r`PuL?1R%`1&vHXE{NB@Z>kYJU!wV~Hs2C1umVi`oNitv7a8LyS#+(CVu12cY) zvizQJ`MuThyWH~op5?cH16@yO10-GZgqgT+zCoT2$ z764~;0QshZF<6@<=XJ%>qc?_d4e%7Nph=A_J=AUn@Km8Ta|KmKEnEBdEXU(WPVr9gBtDE!0aAmIL*WDJ>B) zvHEB82oyIU5?ZQtB`o+|>Z1nHSTIOfo~h&4FAXOY6!S?jlkE-bL=zAOZTbZ(6BWiKOG zJ@ZR}FIX%SzVu2_LnJJV>A{|p0)8xotw>S(%7ei&FwP!C)t*tGkg(jf`5A<@^)qT~ z2}@k@JzxfPIU`us0@7F7V<@TB21@qpN`k0I8?fIrkWGx-9ZP%KfZZ1lXmKt#Zi}SG zYLd8DJg6=B8yV0pKvMH@bi6J2pErnY+kqczK7xN#JMb46&{06rv~hH)9r)K7#9r;e z|Gvpz)E@jt4Cn$N>Et-N(;ocybYd`NcTk^@|6}sc?*RU4<3&(^>;QgVE$IOMB!f7% zBZyc4L7E{aJAysSKprrHg$=(>V4r0Wr*}ed=8rdmzqJ$iHye9;73pMxr6qD=#T zL6dN=8;VxcL~5CeqJ^2WC|c7~QM52k){EkjfFFv=8I!&o7{^f;8K!Hezr6xI`7V45i6kku0s`%Q^uJ>dmrft!263!h2Ci-c#P z2D3XM(C=A98uK_k?G`c=2}r*)zxP=rYbyf^=>=8oCsBMaWW!K{xQ2)Fi#N41fq<&fe_f+2PueI0E$hV6j4Cl zeGvr=>~+?nzF@^*Ua)TJ3*Dpfr8kjRfk{OLBJln%ATSt|>r%sC0P1FQ5p+qWd_2R}BL(6X%f-Z;783M-}%DmK57rsu+Xu3!HH{kGXO?ZqJ{k#IZU_ zH&(*Ksm=JhIEH&_tQtVc|KLLUuVYnzaH`{Uf!e}pHxA># zvov%Z235G^=AKB58Jd+nJVP9RC6hvp8UZTT4a z4!P;JqBxyw`539q0q@!hipy8c9pveh55R!~8`>t*qu9j=O_zL2%qv(JhbgoVD=27^ zMHnkQ(T>*vl$pZsFGeVLPEwsxSp}|RsMVdP4TuNX$On&a=(kCD6iYlvH=SBchHjj7 z(1!d>Ig`~Wb;!@i0Xi{Gtww$O;pW3R{j9xi1MM6arEpO6v-Uh<$C0n`eC~a$8lu~B z1B7pu;YUH)Km3FV9Qu5$>ZJVzYOsAF>jw}ch9u%k{RlYZ9Ja6IY#W@dJF;WT& zorp6Uqi}qh=M2yOD&&}lkDs1n6AjT-vJ5iU0BonTsP`x-h_+5q9qJhdssA__r9V3b zlZx*RW=;z})Nzh%g_wu9ey>!`W%V4jDCCKRh0Mo0&WXE1)2Xx&qw57ovj@LRRPS3f z&kqVQEy0%_v&xhXoT{4km8MhwsYvNJAZ5ExuS|81;-}Lg0G@9Gu-})2q0b&gYJj#7 zlsflm#U@y5ol^w;b?yuO992%i^Oh?~=f#zz^P;lP=UYnWX&c{CIIa^=@2p#WAqO(hW8SQV*U031D>T@`PS3x5> zBFXPfLtFTA1^G=^n@Y0`;-Kju&ac2541>IK<`#M6h?FlwUE+1YAMSx--X zU^)xgSLeR#nb*|OUedu%uI+DP{-8C)Ih>#8Q%s2(CjX2>GrH|;QhTBmewNf&&jjEx z3*<$2?V+@iREHF^fHo7V)U(KY&H$bb!|{l6zYQGk*(8(;YeTBN7`dGY4Zkd))Wui? z`Na_8+~di2G!-vKLmEx1;LyRZm4K37ngicg1lhJkMJa5PNOT z@Nsa`-Q==yFS7h619u1A^9#vscVD)`jp7@cA!rO zV+pk(%>bf33B*xCo0qCFPDe@Q!7HwwwQx2IfvaU$&VEZ(@VgkxG{ny+NVRNqJje$_ zjJHr|{VcK^@LDwGE#3b^Z^8e@@FgAoPyJcyPd%2Y0iI1j8P6fwgmYALmZ1{k3zay< z52hi`<=d(dzcWoQR!79Rs2Ubh8k2K5LS2R_@1@21VJpLQ181^Xh6lla&gdsX@yy7| zupjnNvfb31_XucuK_FhI<98u3-K(f2F!m*2Bw|dq=HO z6={5lYy2wpoXvh|F(;DE<7ujh#ud3y@2Cmh_j&yZ|2}_;Hol{d_Z*DC`~!QRdgMB; zLGs{B&rdED+^V(Em&T}Q4brrQI0Lj&{MOTVulT)+)B3Xby$`=j*6QrMJVp`XH?NOT zYw?>G$Y_xG%`0S7B!2S}8Lbq*d5w(rir>1~{tIiduGE4L3e}(o;qo0@9G}5z)y-0zx(s= z*5daR{yj+iUe3RZ#P8kwd!_h&k$>+MzyIdnm&NbUc&J}5)Z-^bh~NGBcWd!`3jZD? zelL$ly((C*C(exZs0J-)t#I}W=bCWT4LVj^IPHX!Eu0y`Su33V!nr0Kb)%3IPCMab z3ugu#s!MoidefH}knP&2hoWMm8bKF3;dU&{@oZH4qy6gso*JuVqO^^yNrmsJQ4-wL zk8CYnm)}z-+HC!(_$Xpjcb41;$5a)`u=%m~eRMlnklI$0&b_aOIk(jmMkTm(azD{h zEZp))6DDcq;b5t5`3Dwk=Ha1-L7P>7XMSL%9SZI=fo;YL*A5FARFGi=qz2#D#m^JW zam~WPjSM)t!e~m(El~Q4fpLS&wWOuH!S$kkTd=?w6C`|P25#lprVhrXFuTK#w(s47 zbi(fmQlQV1daKR7ydaRaRZX&GQp#2|AK8ez5=z6is_{-Gv@#;#_Gm>LwqgL=iuP}H zcj}pB-v+T9h*2mt+UDL1%cL0$3<2IYU=;Ice^|iKDw%lVA6ZK$maO9a- z5lia4T$;j9dWg|k3P0-+tRGcQ5liY-bq4*FgJmCL0Xv1?_y|_{ur(C(LOOoo=dBM> zOjF4Ik?zEPgyPg}3j#KNXx8ZLObqXgoJgUJk1&?{G@>%RtRaP#K#~qZ#5W^T^jn-M zFaz=tGOj1(ZRP?x9hW+`R&gj4@iBC7s9l*QTpUxV#mCTH8dIs8i)IRq`xv7-51g|# zyGp)-hmcH^+90cc`xsgCDSC?dx)iqEJ)F*@-0c`n4@FvcH$*98Id*2YYM+SYA;_fD;L(P`uh;9+LzfzFf8F4P zwX&@k7boBHs!h2&R3Dt+O}yomKpS>okJl^}7k9vi{qW(S=|le&9Ews)NPCyUhnL{P zrMgsD>fYncq(cl02M`uZKbNX;_Anf==ah<~E8F08vobZw?Nfdkm~+9L8B43n)EIlF z!5l+ZJ`~J;^m7?@V9l__?!*?=VTA29gA*%T&RryV&kZAml_uti!<*ce`V+5nz(`==;5&t8cli-MP}fR z{DoZ@)TU=>4hpH_@G9AjhJGpKW@=qf64G`<=P2m>ERH7aR^yzX89F(1+z7Sfha>Rn z>~1t5?dbGwwVwTZ(_6~hf%u2)QJX*3z2Te!nQQ;npnU3HjJcrJl3_N0uE0g{J zzvpQ1U$3uFtIL=|B!8khV)5mUQ#0JpJd3}>&|=a}ZLd<^CuodbrHtmVAb&5&q44jS z7^3X@1RZDHDtIO@7w>&J$4>2r&Rwf6&<0^p~Hl)B%N zAWHx|Q3${X69rC9k0B%J#75sxbc8TS@Z)~8SSDn)h8?(>4!3n6XCziuPnM}w$m?6Q zvK{c`1@f~4O*w!DtqAi5QL;sM2NaK{xwG+)1IWgy@c3VPPR2@hAb-|nN<4_Lh>?rwj(5m+|%AnTEM_G0G~CYvO|^> zw;cvB9f0yA#T~Y!_&5e;0I2;WtvHM}vo>ZadP32@NvP_{BQSw_m-0Tu?|Uz6rU~Lq zYJLQQuR!qECu#5zi&q;Mcoo23jp?Kn2s{d4CV-qK^vqEV2XZhmF_RAI;h_(qD%-6? z;CIXd|Az)2omk5!0*;>D4Zx+Q!b?h7 z2USnkbT2)j;W`fCIp7I@iY6Ub<3huqGExGEwHL-=W3L`;n;@7kFkL)ccJ??1N|W4t zB47WezmH=(Ka<*h35|21@$IK*#Fv&tFJ)jJfHP0gcVAk<8CwqEbpVcL)U(_ov7CYV z0NOO81Las3ZPQFyw8bls94Bx9)2whQC&0A;T*I2tuoK`KW^iq_a$RGtH^4Qe8Tp;G z_}=>@fHwiW*^CNLs&TeADdTet89qO0snmZn(?T#MG^d!aEYi7O0ayfJU~?+@3eEMv z<|6&f2DTF&`wHc~6Ws!*bB}?Vv+GV2dP?P?M8+xPRSEReOfvE+;|naneRxWBI!zK+ zHXeV#M#P^e1ouv%2Z9+1o~!wv)_?EABUAdLQwid`^3katf}jt_wmQ7oPzBzb3Z!|b zRX=CE;itJ4(3!6&)d=its~lMJ?Ig3Z!}f*w*dsXcS8DhqLc&Z z){@VtAb;;5OknonoEj~iYe7i|(F4snhMR?R z&Z!9~O1lAQZ$Xo1OS*mznmk(yUs)5EAJ{fH4;5W0MK~F7=;l`{G@Qr(LQY{QZRR)6 zfner9Fydj)V2Gu?i8VUU3+M*g8k)JVb2reH8eBlPv&BN@-0W(}?t%+QyDuyu;=y`X z%X^<)sq}&#I;g^k{1(0Hacjq)qcg7k2rg>K|m1 z_}Y<5M59KHBG?NmSYp?M8Vd@Fg{20&CPuNBV;3xmF~*X_mlT5m|#!uOAS`T7+@5J-4ef5ufgv+_`TDf z5^(z8amVz_6~+|+qXazJCs3E4U@8|@6t1Cw66l5iuj^i6j+GrsqvM)LphnlRy0qrk zN!L+K>k&o1$wwL6d@6G>dD7YIUUm<-)2lmSc3E8I8bEc5AXk0@;rk*eCsxW0%!41S zd9u`Cu~lrgf4*^TDDrAtg%tx|E6QMbcO_R#Rhf<#s6seNl5HtnS6F=ZRyxX9+(wsC z8tY;WE7|r_u{YM{Q_Cm=<)NXjqB2TZRgW>2A`)&vb_sz;dj+M2E*4V!C}O=m5Ka>- zD0q6i292tqB*>F$&~ZjAfXd=oEBUP99z=`%l!p5EW?-hrYku&E<;rtErKOCO2r!Zc zR#d`uv7V4@nUo%ZSl3ll;`EA!h+Y!w-xcAxX0$8FAGWsSQ_-&I00k;PNa{(Il)LiH z+OGD2iY&QF+E(%a)k9jvsQVZJ&Yq*T_0m@C=xg%Q`kgOoHGV(h43Wx5Qh^&umK z)KQg{Xc;o;s>;d^86s%=5Tq26W_Ad&$TDRJ=nx^jLs5=GER<}^sLMgEf~!xcGF#Gx zG$+|ch{F9lOc|&Pflabyi^!*jBk~pX>0!9iQa@nGToN9cGs?DO1ab*cYIp>);Mu^F z9)+veH)hwW4P4J7IPbqSaFu1t82VpOymBRv5S5%*1(gg*XH6A6ak00N>(44&9uQ2P zS4C=t93o)>ZPa>VH6%>P8CfDi*N)WExC z!zn8S!**g#rJ;=J9AV>3MNOm+Q~2?kC^pQ}qoPq8)fTQcvC5ya-pCkWSS@RK?b85E zY4NT#4U|!yGDeQFO_a}c(d#9cOg5VC-%ZeTMQ@gDr|=LE8dh9W<&rMCp#&wmQRKCo zA@LVGQ2S=eVDF)Pq7eTIUUePDZx0ogc9b(?B&yz34)Nd*yh!~DUHYqxMhjag&8)rN zZ@bEVYBTVD0~R+Mq)n;bt4fseGAJHnsrRdj^%hA}TF!*#AOw%4-1yco_64kr%bY#&QyTPoH)h^ExNB?$2#e1#)W zEtN>eS7rp3G}f1PgGIk)#Y^iKVl;uJyZV*p`?30q%i0>=+T!<_G1TleJe*;!#oxnYEbOJQ(=V?nIIL#<3U8(O>J5wtBwH=IOi+6#wo+m}lECrmT6Cqn zR!UD@WKqKIrEwt3w>3HrvXj&rz5A=NuFTfl_O2l*TdNv-d9TppA`gXP>fyP^*=-d+ z10lO z*Qj*|R8|pk@o`5Q)j_G|@iFEHZrZF{j+4l*ld?(5GR!l1v5=5u7*a2b0}nQwleC>c zL;JiV9nV7NubiOxIezF^x@*dfFpCX#2P1^bg?d0pI0O+Kw6;wI>A4#xPnKDflc3 z8Y*W6nhneu+N92L^@=F$uZ$%FSM z;ME|!zHG9vckX4`RNO@gbG+u}lNHX$Y**za$Jwr>^}xz!1XyZAsff0BMZ5V4C4Q$X zec2VA{Eo@b#SHcrHGxIckyn*ulsk2gv z3P#8pe;J#o#s`J-cIskE@6V%mH{_UKgyI0KhO(F+_zrWtWIA&xGkG!PbVDgGrtJbg z?xu8>iYTx<(sL8(fdQwM-4&RmezP<^Ea~U)c6_ z-Fnf0kpqo~f{hwByf}KH)Rt1cUPi?2dKopbvX=tu$w=wYej@X9eJ8GaAFp6N_j!6CQvtE}6dWjoKZTEW)<-_?MI8EhUP2BHL8? zEfj30w-iesj|u}#c?j=5{b}o4igin`h<;@P4sj_#{VB8$N;Rl|X@zl5&804VkjGp~ z7my=hw}8uilz_low<1a#Db~_V_6D&j7^{ z1gFyAaZhJ9{)Qp=azp8P3i84`Dbl;-C~vP|Y@@tOBL^zA98*fX32nl=FBboUfhZcn ziZpvD`43X6d1W&{r3_Ha^BinfQOYx99${HA&#-j^y?s_2;&DMKAgl-#t)<6gVE#04-?tqHqN(?RvX8rj7Qm43rUM_AFVb{ zP8qk4Rtsq>+;BBcN=6u;hQt*qKKWUVKLf}JG#_b~n#^>Lv8Lq`|D*<{l zM2^}5Q^W;5mg)>uD#)vbQS?BRYoDR8pS&8D<{7{leLPgIrb5B; zoq(qT(sPvn~0h1dP*Dhasf5M_4s0R7tCaMbLbvO*d&=kUYsF z_lF@|e>)64>#7@#XZqFjOvDg4+=!^ra0nS6ri#FMq~z^oM9i zSWH3?!UgSw3H3&y^45q+HW?clj%RKu=HY4$Y+a&)7K7&V?by=Xcu?UWmWkNUkES~p z3^$!M^xY_9?yNH!`NKIv*b1N?qunOJl}vaF!k7tkax^kNW`YR18iGIwwzcFKYp*V? z<#%wc;|WDHG7aATgg0#><)$g24sD|F*32xgbw-1?Hxj4ic7?Y8c$l_mB;chR6?jX z)?R@+zUHA(M-UuKOakYED`!2Hrlz7yWz!V-f29h<7Y_N5tEP7%ap|f6yve{v7ETYvxKryNGKbH zgtAerNbxHJXGnNZ*eF({aN!jxFPQMjZFytqDPVjG7qs}aNt533Xv*LQ2g}! zW=evn-dL1<#|d~D_vv)%Jr;SM+Fuc-{aBFPNI4TQ>@1z}V(vGRG#lN*csR=UD=0{B zPe3`?W(qE=`)(w!iAK_@PQ*Yl-lSSm5yGg9HkdXMV@u3Cr6tHR5TbRLDy~jcq8dF% z32rj^Yy(D*8a!+WRu@oP$6`@e&t`K$(y{2A0&XFjSV9kzHn~lBn<#yfQe7TAheF38 zx5&Dk3MQf1&7EVWf#S!ZOm0tt)~AT7PDZQx2T{K@ml7sJpm}RHl96wogSkGQtU;M_*1wIN|e3v+`f!?K=(p9^fA`kLFBM>N|$G@&A9wdY9=4 z#}nafoJW(VBi@Z};ry3)r5PwHSeRDMnS6A4Khy;sW+)E%+&oH}0TKAM`Lt>hs_*O! zRA1f<%r)=N7n$J>%87fAj?FN{XfG$CR}kDU^C`v&F5Vq0ZPQHZ9=@-CayCW;+5&`Y$j4uV=n%K6^b|A%~Z;ke7h>3*_e<6 z%zxkJ7*bWmB?!1O0&bs6EtV+VO2)F4AlO4d*qUn=MxCRuKXZGDV%c;5fN zHp{T?{M_WUCjOmb5Hyy%J1PAr#E_kIXc@x%&W)4jiJf$3nGt5AtMq~&g9 zyO{|QAgo(K7nZx#h9ej2`$!O6D`eVv)FUvYQUb(c{K3G14UWbNpA(Otwq1n9W3U7` zU2>+mh%O@xdlbUBYqC?$F`vr0DQamcwj)GS1uXWJGQB)lda0xic7vi+1toALeNAqf zu&OISs0KotmADY&mgF2JR0m zC?kd)=BWvul@?F&ap(zuS&5cqIR(+~WoUj8tFT7jVY2zt^<`*n-Bw`%`;Fy>65}?z zo2IQojj5}wMkD5^-9kfDunHn)IX4TV*ufn(rb}(MVLf$wqZf@J+{e zA#_|LxJ;inrCUn8&N_#3o#c_`sp zi1XsRG&2utyNmCZmN1XMd&Q!5uNZX!C8O?Mf+jM6VppSQ?xm)y(KFj}CPxk%#b-^7 zL~yz6rF781f)^wL%C5j|u}j@?Km?R3c`(t>Qtb@S`sTrgBJx^;6xHVH%cGbzNYRSC z(iGKzuYIDkIM-k@*e68Tb>f@T=7psbSa=CS*Mu`Kx^veW+`JB5gLS-HI|N~!UZ7&)8b7=pZs_eT4Now#`>G+$tH|I^*5QdiwNNfhr}Wd zL!~uwf~P43t>7=;?jDv=&LY~s8DYdAjQmaX{bsc2e77*ThwOJ7{`ZR(ZM-9cvoze> z_#GKKn1`{5_pPYOYIL%(<42X)UFWt3Z|_07VaXT2zK1C5BFY(?DHQJ;`^?x}nrxX; z)^HBHL(HD|J_0*#60Hr51Li#YK6>_n|9B+1h@>qDJr5W#(RAhsr)&~4Oshtf<2#_U9%vUVu-O0si?xtfA2EuS9l zP+G`9aCIzU$k+*nW?<;Down{ohv>3h#A=n)5xTL{ttHmng+hKA`~yusT7L?fgb}+? z$d;2;)knoE07pd^Fbtd@6D-Ap@Vknk);yh}I`d&Oi!IhOutUkmiD^qz4MHsA3 z;?*2Jp=PIF@+IrmK@nZqja)QGs`~Aq=ev=Memh>w#W8BS2MfkYZqD4zj?u_HP?Lz0 zCFt4UQC>kXpYEXV_bAa`pE5tC?8c}bRXSo^sbp`@jzvJ7sB7o3O!l3bW33n)ZDQ$WQ6w*d%yB`KI)aV{rf zA96C)h55LEa$Few3ychu8DQM7V{L?RpqnnGyyNlS($eH6RY3YdHwAL1gQ)vBWcSK` zdi$W#(s5;fX=!rl7aH#o7M7d}kqSvagp?MFQfqNY@ixE947Rb>nX41*$Iy62ER}Uy zdXELVmU2_z57Rzog9;e3xY>Y_zb|6)9_=UZE>SNjrnE*Qz6`R`3h8Zdg#J8+F}cAJk!~xIXN*Li5kr*oIHbxm1St`1R(u<~^JnPH zaV5-aI{T%*C>Dsgc=Ja)feQ6GDgq3moFk~vJh<>u@C7=fw4zawGabI9yAWikIC+5i1}C>{$KJC*w(64c9+y%@q?sywyNuH zp%PSC$7wJOHbcpH(u_|q%0EgC8Cz)y|0siXu_q?kdWhq`m;T}7zG5p%vfZS@2(^MM zO;YWW+-kCGx~v|T#a_gp?Sw|oGL7% z#_2+BF5ykx^qN>}UMr*al%XOw7`oZPAoSaktvYpShAi%~s||Ib%a&}>w7Z>Wg#$jE z04Su(mQ@pE=%16ys$*oRn}M*MUlt)k#ccdYE~obNfLfVGS5^Y)i*l;3sVbIiy|J;c zSIG5M=gHj{xH5g!HnJ`>sgkXpIBa~syxNf!r8_Dh+-?;RF7%=JF-8{}Ov!d$G=k=S z>M~s@BqiG{BayEAew<1u82_w@)ZJL@8s)E^l=M!90!_mG5hMQ{E2%woDCLZn*ib}U zPzlkpCN5BIY%1I&Td<%d2Z9Fu+76}(wV6fB4FU-ov4kLXhYa1<^B|NCR9y+dYP1}? z+%-8^Z7=EV4TY0rOBP3@uT@qD>Ou)6;qZ)cY&tmvZbI3_hwF`&b}dBBm!U7p4plek zS%$Vnvf=4EK0n_vOs%1>Gu;CCz_B0YgsH)@YX$8HQwQrpJ0s!NuE8H0uGWz4E2($5 z+FK7?De_)N98|s(u2z#&TgTvW6;ncbN8;R z=ITOlmTc81BN!dV9;?PmEZ?@Mr)IJQ3k;&4>ZxfSkXC6?2%2VEeS|FpP|5a}I00Tz zAKgJnf|6~NNKxems2fA9LyMUxdTCw*6}?nQNRsWD*(4jO%jA~3U7s~l2Ybj@_Pd%j zRYys3>_OVv4DAB*=%3AyR59uCFcjYuNzH#*?I!7BlHv5nr|1=2m0wXYGGhEb+yce9 z{Fp1|RrQId0+Xo9hXquvl^W{tVS%SGO4C~Pbx4JLWM53h0PM&`v{pOeDC_9fYE1<; zPnCs*w5GKh=~!rT@@&Sl#(Z%PWj^0I3zO!vO#p^^ZB&LX0@B;40r)jv{Q3ak_~m42 zj6A2zr>kw$*Q87ed0oZrL&SLFG_`phG2S>WI5|dx&qQKqfxa9B>()SJnP#U+91k|$y^Zpj%FaHcS2!17zBFlE5fCBnwjbH=N09B(Fl z+ExvQzdL}COvz@XhAE>{2d0f4D^v(9KV(uwJ7gcRwNs!AIB)+42K!h*j#KR&xCMX=xg{9U!6(YLvtCGvRDWhzn?Z z2Nkxft_WwA;yJ$yXnO~>uA|-6Qf_V<3+Mp{(#Or2^S^*1I>LFqn={L9h%!wMFqU4( zTSr7wIwNYiwL5ljiG-|FoGq5tor@`q2XMOw}=f-I_$Xz<2 zR*mp*@WU}bL!$p1#u*^)~a^23D~nNNFj$V?;C2| zS&gZAuY}#h(GB@phrc7Js_5@ZbIzfsh?5HII;$Ma6%Hl`!6-k_^Ui90hw_79x5Tv+ zcU=m)K_d8pS!3=;_o`v>gM!H&^9-fyJur%!omStdRaZRL~uAlV@ z=iLH}V?Q{Q<=|L-jlS=yCYpN%nbhbF5OP7Nc%72oa3kzz0)a5_I(`3!+SoDh`v0*^ z26Y4f3h>XlPTAd5Yuh}Nz5~I&5`@QQ02F@?E0YG@RYy(BiT6tzqS|NU?+VH$tVqPg zWyRIihemc6h0z^>twLa4Kbkqce9kA3q#kO3!*co`l{TygyuJ&s)!n>SCasLOwWpFv z*TJLYfhXrj@_rMU&M|raN0>Qpf`2vm_x?zS!5^`=gdZnRFsLl_v)Q18w|#87!@S44 zI9FGtr&>vBOt17*gQ-%Uj)PV`RbM!a@2R#nl^z&Ydm_OwV5!Xf$;|8ePq4qD^+Ip4 zoc>3;hV_EiweY&h@_PLf>~QStrCO#FQ7_E14m@RVn8Bx3;-2zc;+D zhu2s)ufg==nUWV*GD&(1JR88X%Hmmn9{Q-)-ok)wIa$@4O@rRTNQU84P4J}NvKmYRN}~FW z5<4)NRLne^!PCUziT@Nlx4!l$Ev-R)5&3)I8Fq`Z`>NJ`FU)oz*xv_XrR90|rzl3h zB-PggPGV2`ev)eKNoUfeB>30@AFtgulT^$;3fKpn{)>;Q{Sf&F@bTa_CG=BcJRba4 zw##6%Zv`9OF#}G&@bCF(os6Kifv5NmjY?LnQ}P&QK=926A^NWHY-{^QecFA&$Ioro zF_Y?~fNeY229&Zj_)oU=U{iL0E$=R!OL2>)Vt){Jg7EMzwdn6gm=A*QE)c@*xyOGI zZRTQsw`Ti{`F4XZv6K%9_z%AH0Vs?;;L9-iDCH6g_C+3o_qhT z_;Ut=Z6Da4-lN0J_VmB9y)p=F`@t4>p9T*CTipHs7TO)K*$;qi(|xm+x?Fx?Yd4cp z1|uXFSiZYYnS)j9mR=@KkEl`VK@iG3@T7|^ab~j8kdiIoOlmy@{tkg${Q->vp=R|5 zA_^W~XGhs==kdq8O92lpcWZogyKRWRI~3s@MmQ}VQuI)_v3wE;_9Gy?Wd=a=KZ6u` z@kjUG#Ga3WXW~N&8s_GC*f4lL2Eua7v;O(Nd%g}H#+1p8Y z%POYORCvq!f935^D!iS7H~k3}rMe}f>PQeyb26S#!bmql4inCR5cq@+yAz%<;X@E2 zo=~+>Za#*MQltDn0-@#;krQ;$hW$FVOQ5vn*eMam$so;uO*sp;dQa%NyZ`vnAbbo$ z(!esnxvNam-ZMR>cjrVRGr1c8nR%gK@zV zx|!xyJ$2GS_!NZwPpC(_n|!ey1p5UL@bacH>ce1#PnFy;Zq2#Q82G&imbE`qk1=j7 zX)_Zpfe`QuT^OTUXZNt67>htJgRtlqGtiu`AS=0<493C*JnCoQQGfNMPsXa&#eMi5 z2j8EAGUHd%cf`M-&|QSb-N-pkwR;)vunvz!Zs&oL58ZCBR-#Lw;8qzV*jg22s%jw%cjjz@xdsb+){Y&@84gcOYHp{g%cdK*lS z-^L;VsWd~>e7RwmZx=s zgmeZN_Uw$1tzDc<(kG&Pzd-p;{oO3z^nYOhU`e*5@n$g374ZCG@$6=vPbNZau$;I9 zb9R^TI?uT6=SkWm)$Z{AqqICg2Lm1mub^AoDBz!@MoCL(&?Gf1WQkNNcw=cg5_{i< z@Xc$oCA5AL%6bVM1JLONRP*CWYHf(xA(PR1zC`+xpL(*%RQJopnQ|sm2kpdU zwT=THM%(5Ta~OT)_q-6q8fY zpv~_~Zr_jHzI~^a^2EA*C%S#7iSKFC(1w@NY5~Utd?#T2MJ>LPP*HH1TAJ;@k(dt) zTs@|%FoCeJ(A9f}I#ZUR>G(ba8o=gfT-h_#1D zr^@%fagAE6!o~#FbQhMR#~#grGOvcQhLUV9O1Yv{IIslzD_yLsBwIi10%LXBaj7~_ z7YnHpx5sdkv2;q3bCbPZq0n!lMp3D^8paNYEi;D5Xd{AF(l z%CdJsiM_#;4f3iRuKs!I*OCmuxWyW1;?!HzVl5K$(;8@Yn;1XF=)(;8RIfZ#V-$T=_o_K9$>L&0Bfsd7;4jotTI`yMpqEQ*y& z#2)IV_fU$P?sJ+GWQbSO--p5!(v;z&vM3t+78FhO2d>^*Sm_TLXw?VM*$Re!{m$(WRlCOvf*N~O-v6muIk62f=m2c}$u za+-f&n#GR|@*)F+$i5ej>aT)h7k+qPW^}#0Pi-p8Q-2rEix0pVBepBprKU(8#&CI1 z?c{+W(RJ~lx<1xhgMkD7xA=9})V*Qa$apa;*A#?nUPwsgZcK33tJJ(33}M z6HSO(pwxd1iUi8IH>vkywN)wQJ*LQ@tb3C#yg&&mRwLCfk&BPs^m5 zwXB@j!qw~-wYCRqsq>|ZuBpGPlO?%UH`?_~^&|UJwKpgi|58DD3O%~{Blj=$4{4U` z>0j!8Nt*B4`AmJ?gFRjPi#XJNi!Lf!O?5W1x2uKC z$R2`R8&{^HtF5XX^xW_1^S89$*XOa6ljwKAu7zvR>)^odEQw}p^QuVA{WQA=|5_C0 zv6&wGY3Iy@)1``P5fsBc?;S|6a{9LpfBGCd|Q zjlK=g8Y30u9;p?nMkUQpO+e6pAxJkh*O%^otq?F_~EF{$+%HI6lo*|G8zW(EUcxC(v(wO~M&fDZz->iBgz zP>XU@g9ed%iX{~d;FHTZd>N$qI&6zdv&On%SbQwKK-G!f2||(+k>r|-Xh)D{tus5( zuT1CyLcJUc4Mtw-<&;Lk0S)96QxIN)HBV_E-%1Ohg~6JJZ`}U~p!{IXuD3G%;CycY zy71K5p1vUsA-DM=0N50>Z8GVsWa7LIy=Do^s3*+7RYeNq5*wPk3pzgvy7zdFdMtLN5^7ETK8!nx%^E zL|2&58-%V)=y|vn>gZ~wl-mxAii4IQM-2OpgT-;D z0^yF+ZD_9V;hflDN?D{;q?5r~d9qj0>~O#hSe&)Sx8sOgVz_;Rc^XVAw!-zwJZvcO zTCaJoNH4E2xIGT0j4E1P$0*a;>iL7Iu!>gQkz+dZa*dnmVCpiRuiIv5xW7}?Nb>b} zvP}S@R38+SV-=OJrddjn zPSm{`2z^0lv5KZw)2ey3ScQNnJ_4CeU8KQa$vf!9L+CR2XiEf2Vch6(DSQr$6V2Um z2sx^wZFFOQrZeY!h&T+?r#ifBbfa-ThY+%bby{^~aR@!bx3PbPH+rh0c?_XXt7C{8 zLJz8I)phAzGhFHti8Anv=2n0F@ zjnKG#n$HY5CWAj1c+GKvY5~hgeG}(pr#h> z(IiizZJ*&fnVZRCj1tjcO9orVJW7go>w_PFU{3*|XP(Fq_5Bg*$4Akcwbt!KA+_MS zKX?Y_QJY$Bo^zNm0EDzWI_ysHstv+G5T@eHer-1&lR!`xu>6E%y4f7$xz&;>+9LO# z&!UI5wFJ3%ma9b_t+yic4B0>%BmcF4$~M&Q%0&xZe>T)`DyZfn*O-^IHIgodehKH^ zx&-1(MD3>9Z5d-?LNnAuY%{I0jByY@8q3~GgyTAP#Q1ic9Wk64oW3u^5hGa4%W%Yi zWjH$75rfnkcI>*u_2tW2riVOoxvT%H+H+6cVYDN|Bpe@@nc7NgD7RSU+S5wwD(fLe zx$+Sa<1|h9>smt{b%aLAMh6YIG`PvA7$dHN*AZ9GJo^51#DxMk9An$U5rv%47LF)W z!*Lxu&da0YZMF7NOPAhG3y{&Rlp6AJ5pov>7ZHXvky_H4hX9dVZE%<+Z`}AzpRR|co5;8>X*pD z$KMJ%pclPF^^AKL;yb+w))db>Xi6X?YGc0)?6#5kqtayfuH{xHS9N~F;CoRgy$|fh(MiC#dE%nbK+5OQ;v-|vJ zmH`trCcchi-n|k~QYTST9m>(n1eAJ*a-yXC$gi7_VS7rS#57H)NBNLL6JKw8EOw`u`wfubk7yqg+$E46@Xe?sRsm z)|!dvm~+rEXZnhc86egUhma(zWA1}*omMAmM`Sdl-d(gE^2@5ryQ_B6Q$`*y^gxH@ z)xr?`pduyLTT@J%%`cDrNz}IwrnLrc z&fM6NXn7w@QLRj8E+201Np!gnCXV55+&pn4kyl@>v(%Eh_eD*$LQp&v;N zyu~{k2&bRn(xo5Tc|RK24^`Wbo{g2zi~2!Q2^??sbmWf90)D4R0U?}!T=*?%KLgy( zyC9Z+D6WBSKDhw;QO#r&SDOi?0kS~aPfVy&lQD<&ccZZo(2rIoYaODw32+;Vu|*pZ zCi8L?|DZB2`PUje`zKJ@6wN=dHt0;-ZwALB3-+gRVva`^!_G^xF|ZhVY@DOxYhJ9! zPBw0!8G1t2WhaYE0fEM+QP6C~C0SewU<*6o=fcLBROaQYU5WiQ%`o?aP?^N$e(;&3 z1smpml10gf8?GpM@gR7FV0s&4eYYs$8FOcw4sT&Kx&6(Kk-xjC~alT7*`NYvlB1;}dLWE<_6WcR1UL7II= zIQ+xPfz4;Kh?Rq6`yk0~*-sfW2Kf^QW-5ap#@TGaCO@Z=2W@x$0b}r}B>ow@ipWAG z_z8la2c{pEhPgq)54|Sof#f?_^E5UDl36~6oy@^nTuJL~VYc2cIH&j*;nsTFp!Lq4 zMr;1%(f&X9+j0@$Uuyxze_sdx=9%O_L~CV^vsNFmV!_pwAzB4{TQJ_8DT;)y--KjV z{WGuXv0`kt{4}=u6_+ahO%P!Gw;ckgGK-!M(Skw>kdoTqVS1HWrM1h9Db#4F_DZbK zOjrS1iTT0|ILZi8{0A1>m3L>+hM`(3({8lo%j)J$%E98Sr@zN>s6ANJGhbP=*q$Jq zWc=}@aB%~StWF)Kb(Cw3bDbNe1xdOXRapaG@2fHu4vf$iN`bgVYz_)i$>0%>AS$^w zr)o2$8S@{20aK(i5secfjuYqLY?zvzUjQ{APF>k_rlan>fn9+=*lf-u;KN7Ho#TLK z@EcFq+bV!Q2j~Y}1gr?e5gMC65C=7Efj}Hkumu6Je{ZWSsWvAz3ZYy*HcC4|vqx)* zGiFcYVuqn>xbwem`1>1)&Z$cr?*&*$W!qzbS$uqqIuj;$K7C9pcM6R-xb zC$J`P05BRj3Rnv`30NCA0~m{w=*~s>Xb6Y*fQ^6$fQ^CYfG+{R1U3QQ1i~_|lWV0J z5T#^m0SpJip05*u+2Vkh_-ru0>x4GOhMIIH12JzqQ-Pp4(X4D}v`zxHlV;eQ@8bh) z#d#bEDc^Yx2<@2jYajw~J_L3FJ_kaL;jD-b3ay1R0@w{$57-mf76@H|6Nmq8y@9YK zX2TNOIT45zq;nn+iE-ivstxNIC$2@=`p>|}DSQk7UIY#V{s0^VyayZ%gh?6OaLG0k z);4S-@f-KfZKHs=Q)n9v#HANo8ZZHv4(tsa0~`m04Pd7eh>6OH7hBo%taBZ35|Aw& z&zOvl)A*PIyab#Iyasdve+Om&RW!<(z+fPX&siNf8;IvOZ0`VH1I_{V24({Bu#pX_ zK&KN3)txg32;G`<127x77YKct^R%a}nQbvXaK6))1H>^T8&oAu>{!~C0yQ+sWxxu+ z<-j0dE-)Opg65CWKET_Li#kGomM~V!)i)!N{J++QVm<2s}$~`L62piYh#N2!-Tt!7Ilf2D` zDQ8cF-gP%z2rg^?<y7o|~DUd_=fiT{m-kzd``iwV255=^m z(&cyv#*g2DTB2YI)DpkMd*BxG9Q?e-Klky^*bz7|d^--7T5ey#!&k|8kdrFK0e=Rywk%|f`> zpc|2YvQbc$M<}IE@{E=Dc+m9zp0IK`O|vWek&pcWlr#;Z|9;pg;Zll3=m6Ud%9$*M zh49$C50VeGLbk^yi$7SH^@g|wc7y6Hg8X{}PxT_jHw+zF$S(Ms3V%H7t$`U6=I4ZS z3U9Dxi#dyDXaNT2E^xBYR|ob>n3H2*G4}?opRTK@w=g;Eo3wrgimli!01OEnz;uXYT(CDeVNs3=u$f{d zhLe5MU5mDdhB=WW7m`Flw8V+EBbof%5_pEWCDf(2Sc_O8Hv_BSTS9*ro&o)LC=9O{ zg+kY-L6y~KIu=vV^)VBx`6w0Nfw$b`u(2pgE*DP9Ey~K!!o2)pV+H3hkZz&#x`coo zq3j4As|;_^gA7#9E%KTPDe;IKm6uIO-2&(h5@%|Dj&`ujV)y*?QW%H5A~V_{zKr;4568`v}mtP=BMi@H|mz5`BLR9NaT-ap)hi+ zm`Tb&-Yd=4D*1e9xgpOorO!kr*G<9FzvpZ${g=Q%jFnVRCR*o6_Ryi(i1sj|-4jYh zv$4IiCloIS{|Hg1RE2rhP+>}Usnd=@lyL)iEMt#o!SINx3x*$PF&Uu2gi36V=Ib*ac4v&*2B%IL6LFU|8SV}Y zJSF+yBEL%+P*6ISy0LRpLQr$GH_#8f<|1=Pkh$976f;+=CIffO(jtXs_MXVrJ=zR5 zulC_w+@H>3)lLA$oX2y~I#SrtOft9idxrMaxWawUP`*;!JgAWFiM02ehcq5_^TM6- zUdfo`NsH$p%yT9Kw>Vw}AxyUKUcj`AZl1ZlA>cV$bxK?Y1?wJaG#}YHitKcaprrX) zv<&oq2dYD(Y3!Ph0B*pDj+J1>`)IIQK*fCYdSA>(Joo)$viMUM?m6~MXd_y|#16A_ znz&By({@(fZ+Qnzu4g7x=R4dOxJ%uCv9W)giIg2f%C1JzlT7sPt0uqI*dK_I#*VqL z6_&}6zHD(Y$>W~X2b|O>M{m=alfpy$1B#f50XlyH8vX{0MwjOz=?Bpxqz7~zIiwmW zK1!R5Vc~HW<__P5C=3a*xRonza2$gaMjb)Z*I6`5pNF9GI^zJ|eBW8-2BiQ2D>W$d1op=( zFGl7R7$jmJRwX_bJ3I-CHHGrCv>G&ZF&ey&$;B1M+>dGXVl7H;S%ZdWp>4iUvK4a> zPa)!2TZ3BUU}9QpdgfVx8+@^$KFP%_FBJ>DY`FL?)uH{7jf~ySLB@*dX%4#oA8yIy zIw+=^OVE(KVJgW=J-6v%p&Mup{fZ|PEA>DNHd#37+`Wro?g#pc;ui-kqgQYR6;mO| zi1z9d3|PhV>k_R4x@G)QWa=a`l@v|GmqIv5f;}XTnKQ-sMC_y)4}CX5!P5Dqn)T54 z9@3Y=`zd%o5l!`%Y4yEMuy?wQtVuysoWpemXLCb-4_#q?$m>d{TJ(Hb$-c!NYPTHQ zBxgYA3EM~)W*`JJ&7Vt4ufxLPjl;sbo_X2_g{QgT8idE#nDua}Cb2sHLuLi+Cn^({X}Y zmb_hMS7^sI86xI|by`c0asD3SN^aUmn8{+-qfd?ZcePlr;n2nY0N3FST9Pa$1-gPZ zYtJQ_f?PrGYY$}^6R!7GgqIoO>b+GvAjx||UFGxHQ|)k9_I3>y9J@xip6}57W%+8P z%YU~vTt*jn&D_f$$Evv=?#Et@jINOF(hkdOYq;7UWCv95-9rc$_0;UJHeE*fA3m%# z)QEb@I5D zB;j18O?hd(m;0%TFiI&veN+Ku{(1_HtM9GEnrp)_P?X(st0}}@8gK5`ktq0Z{>KUvzuzFYC zdY>Af(dx^N;my+%SY*U~1Wgb^&i+W-;K4zRZYu}6I-b?O zknHsl>SNqvF{-loAy?%&&EaJ@(QbZlJ@p*MuM;%w90rmTv=Try>cR^2-@S01k0;m@ z^yxV*z=8Fi(HG%jOTnK%Wz_YmK-wn|Km%~^g=66U$^+a9O8EqXMcgMCl)Jgnc<3@{ zuc(>E3>QY5KS9wnKq_x;p$nftFal1Gz!iwKsbzd9{5)pR{0Nliy4oHZ431>*(cnJk zwOGuaS?A#uM^BWWx6*<080~(>Eg4P*w;z^g3aQ?BdoXFAqHS3;YX&LAIt|ANuPu~4 zp#o#x_)nq3JR2q3DfLqvb11|ceJGMbS}h=BKA&Rbpx%KV%gQb1sE~@^fY_9{7^h4w zAjh7#Z)4F}?kaS@@DxUaE+E;BknHODlzpLOi5foaK;Vhvf2SsKKL`u$VdJR`UafjxdUsYxxv?cL_7YDZ+W* z0OL3|H}p_ygxDt*>2Q zU}w@Cap=Yu*ctp9;r_Jyg=2v3V^J%_^Z0#N?iUKf`4`%zs-NYf~VCOF`d}n7&@9& z3%tp24aHywKl562u4rC3m7{w6v|~B(!eco~$1j>#faaO^6FO%(+WiwYtjp0A!S$=j z+@OrO7r+7>g1BMuWbDMrkhB}b&J@Eh`yIF1J2ERi~%&~6ayP){m7pycExM8(AzXn($mCJrYWp?D9Yv|ErF z#$pfjmeyN(LRW7gus`6Z@_3SOqjy#wUz#*lZuyE^5Ph7`LCrhq;X}uMf~jT>-Ip?M zBhkLJ{x(EFU-5=L-m_Qf@olUCg@Zi>ifOYf4VRZe7p2WCBvbi;lSf7(s);Er&bMP73CAkxr=gmiaa?d znB|c21m*DgT}X766PG-gZ4SCVs*Lr>Gs^ZJisJx!jcbA-pP8EnbD17-4N5&K2X#9Q(ePV~ zsn-K-sYfCj(W5aQf#s*c-N#nXQ1xPi#@1sTJ^WS=n(>a|4!t*!w*lt@vAna*1M<%8 zd>|W#%mju3Ilc&BHqy}mm;?7$flGk#z~#VJK;~-$B>Zj<%mtZ+bEx=UZHe~5T z;9mT`4upE!`7>}okbBwzpaewaI{ko0fK`FV;BOZ241Pn=ZbKMO=)ddRKEg)<9MB5p z1fzg2;aozw%0dE0o0`CCp z0`CDE0Uyxz$6Az!YXYioIArbE9(YzcgMNJs`S@Uj%fDFDWT}=b>}RbmPH4M2|Ds*? zP?OLLjve!&>VIev9{j;a+>K3o?t|xy3D7Xicg`3a>F>`q+|&94r+?0o&r>Yyv1Q}{ zr}1xKTFRJ|kz&QmtLKSd8eM}41S2sua70FGO@y@@g@SzMkY#}|;YnzUAH)8nU_ zx7iuNQX-9x!w;m*RpC!1 zfpTWNMW-$;A^)}g2PrW;GUXd^a6^pDmZGw7?Qq>A+IKbS!$BRwnb(r^E0ksd4V z%CuJXZdXq8#H|SY{R@6J!SQ$1yNfhw`58S*nF9XB_m)4@qiZh4P8*j5&yc+3)CYe} z@Vg=Q@7dkb^M6Hn45+SSwCT)=Ve(g$A?Z<$1rMxHL>dieTsf0;&2hw}aY)=KK&yh; zRg?8tX%aP+^{9$dk)E)JA_&{alwqS%M~_aU_#~;ODd*ad z_1`XoQJ1Nnx@9C_5^eW{Hz&ODGjUutG>yIe&fehkzr6MJg0~EKYhrmj#@^g+Lr%n8*=&TB*{7;I*AIwqi#kwk4GZhPIYqkv6g#n zk=!z08&=@Rsp_7(=pd4<$d#q)KS(oDQFCK3&Y320U>o2&z`npaz>z>qFEgAO_~7{^ z8;GIa$tPU0fLno>SDeRz*iLs|0Alg&gzXPwo_Pf1dFCG=&nIQjzIlF$1g-$q2lD*V z2FTOO8^Cvg1AuFRqk-#?ROftrtcL@PkQfsRmN&MI_>CLx#>9e~&&EV@9ryv7x*E5w*h_x>;XIr91i>#I01MLI2U*U zxD+_!B0jd_;}Y;NkY}ZHU9EHP8;3eQK;CH~=zz4wlKu;Z$AkYu^5Lg5F z2-pbt7}y&43$P3DSKuJvZ@}@u-+}Xie*klVPl4|Np8@yiDF5g9_!tiV0Ivek#hnj; z5D1)q0%f4Lw>a724^;8H4iJKq^A#YUZ0Q2@1||W^07n5K89FBeeSz6P46DvH!1BO7 zzzV<cB5xMTqNgv%0OC*Ve40&pL&Gw=*B5%?vr z3-A`OD<75l10Qd|L5KLz4HyLM4y*<20c;L@6W9sZ6PN_-1so0R4RiwE0_Fny0M`St zTkgyUCIOEF`vE@&CIk6cR|@bOV1G}1T&Ejl^#`z+?_;Y?UzO9hdDX^e9oJl6y`l^; z#I>fpzC_Y7|D$P2wm*cSyN-VPGI{YmSCOB7Q>5~zsNcwVnd3T+NWlD!eZXH)4y zsBRrgQOG9@gfbvpol1?v^k(2qXD8@Ilp9lNRhSMNfd7^ZyrO}!q0_;-Uv9XrNqE?L zm~3go73vfY|32{Fa2mZGj{0Z_Db1=6&c^@6f1L;vMp^iuH_d~BXX2n|S_CdR;8#f~ zUi4jMy)OM7rTfyBvDl)nR7Lm0lA%r&Js>wyx9e+6W+)lPqOjvabWcjFg8#&V>ey^j zxtO@J11P78-T_%(8HuEqL)1&B)5%CZQU-n>qK62(9K35KRicVf$b6qry%Hr3m#dlU z0EH$+=~4B3;kOzjMb55md|K-0l!1mI%?9xDF*N&tV9|}{`M)y~r8hSN`nOE@I$kpg z|B?Rhsv!NylG4CQN>x47(E#G7RrHLLcv)lGwn(h1+r111>Xd=|5zY)WBWG1T#@zi? zXn$1%=YpV^>U7tNaNo4##EA%$`)9ei`Xs*dX=^jZwY8ewLy~Vzamh8%L3PoJCEJ^{ zejC)(3v23^WHiI1Xgyj+tILemTgqr^7oznsx@anrts5Da?EBQxd&={sxenCQCrkQL zNbfw5!5)QSQK61LPp&q@^<^C(e7cG&GFE>s zDKjxAPsgs&6FG@y*Vp}&S#ZdMiOu?Yj3cj*C-TyTU~RXBU~Njz!$4A7T>D$hYs1>K zTR0g{gBlh!KsKC~ueUR=ab}&x1AMZ1d$a<48pqW!W%4JEt4nrzR^L0!cy+NhUlI^U z)iKgD10Pj4%x9S2hWQNh+c2MDejDa9%x}YdhWTxn&oIB)e1=@xM$@O^f;w=GiN}FR z?XgCt-n|oRV$87qz3BsBK{z1P|i)%6r0yITu9R$J5 z-BS#u%){v2yeUSW7)n3kC5+p^xhcll7;*&LOM@(IiXi7A$fm#1-KJP1HidZSUcGhQ zs<&>5t#@kD+!N>Oc9cB%HJd(YhLGkVq~U+iXU%l$?&EB#_%aCdLD>BVwRl;#ZuHKk z`5@RcK?sKE$Z?WkTXgiT6026TNpB9G1>o6c@r3;4Q^U<%(QL{Bi?R?bKRu-b&Gl&g zCzI8mBAVia(cjH=%Z35hgVizHBEso~HY&GEYNspY{`t+ZW<0UShI-TWoUF;H)5rcAQECTum^2kFU@H;o*m?^RY}EAjuK?7qXJsQw4u@9ZX<%xnS)JqaN| zAP{}q=|!nR=p`fpA_N4oK}1BVB8M&@z4y>NNG}3P2~AKyQHrP#iue7Q*(LFN zfA^1@=Q(*zpEI*_&YYP!XXYl4FnjA!cH|M}Pg=Z+>BE5)uUc7{4MReScf6YB8NsK2 z%=RAf>YO!XkR+i(<}|^5&6&+a#r82*D{IK0zT{?od1bO1xromW?7PSZGUL@khK9sv ztIv=yBcyB z14vLCsl@9YmCqd2>NT$;8abXj{dETD@=gM?k=MilWR0`=-P*5FO9zmA+pn=^loOXM zVBni?`vqubcYc*8UJuf}(}k)*hk1s#{0psyHcO3)=Qy6j;!d-;coug$+v22{mS8si zH@^gukge^1g0u?{Q{(&cKFiKY{A)RojqqKYwGmRLNKgX@>XCX*&)`C8LtoOy>VbN} z;6k2Z-lAQCx;#*SPZc}D1I)?^Y$H{pog>z&<_VlIM|c;&HgeT!OEmKb^L}TddK~TI z8!`!cK(u!o?#c*Op|~6;%b|%GS=@JV?*uH<{u>|MmZ=Mj&b5n=S34ymfO~dgx%CR)`!} z*N5sy?5EeHFCC`yQYL97 z=LsGpquFlxUBzT|ZWOyLSv5=5>v6xj>}blSCt2R~jWmNPqu$olj}fmHVB^=y;K5A>0&Ew@@Qz~#eqo>fjuWx=OeaO@_v zBb7rSmKyXDH%W$4dL3$27al6LD|zd2n(m_wwZ8OT!%b@Z+B115^@Uk@U$ym5oo+gM!O%w&Eto zk8IH}wIWUTRzQ{K8^L7h2w5Txq=89t9uLm$5qX-EaQ8Yk-0_n9?P$u znQa-8lK=m0Q2yYctyu@4?C%uoaB2T3hf99XIN7=X*^>RA5{vW1;>lL^>!-xxiDyc0 zPVFi7R~V-U`I_VY?-KuUHESHl_f(Q_rS$(KVM%k|BrHY#I~!Dv&-BrDlGWtT^y~KN z8&$%1%JXwJrq3R)^L8o@*3+Leg5zlI1pRy6`k|#=z4`94xnJnKyNn%gOwwoAGqN96PEcB zokw4inXh7ka+%8bO83?sSg9I(#r|2%h$@*X;j1@Szbn-m8L@^Dv6?86{XT(}Y zG|N=Are|B!a7IL}V?^6bt59bf9GB3im*g0ZU^j<+0e-a*_E6hQm6<^L-%du4gF&y-VpG*L_I#=NrV0X@WK|O|o~I>D$pYx4&6nL;+&+9&5`|Ia?D$1jn!PqaDzGrG-SYqYgHVi?VOn#{?z zCqAD;^tKYc5wFz7IeJu)5!}0$j7^p*(W{(oXVi;hxO%MQ_u`!rA=$^Zk#U}gR#q`{ z*$?+-vt!!M)r0b8pRhyMB)&x6%NDAF<$dH6=W^G~yR#0@B{n>+aNc~S{+P>^_Rar^ zO^hl#k8R9;unqD=R(_!vwSS~0hcQR9RfaN;==^5!#XPEcdC)wLhZx17&DTS%?w{xB zH9fC*lf1*5i4|jsl7FmQ%3ZX!^SMV^j=pd5`-JBVv_+d09AuIz46I#@_o1z35<9uX zp80wyM>Fq?KHqSHwQ>T@7GmAAsPK*6-a)#y7QL7$9Hd~Y@2pI3rBBT^R>hs8NWMUi zx084h7U(nddgk$?QBpH+ViaCT{>QO3f1$p^&X3q}5f@!IU!}iZq!)EKx3f9ZUaP33 zWQEgSn^|E4-an+T^cLWoE+aqO!BhudtKQ2v+aBbRh5Y_2P3Ra zb)Cii%$Lh4cJR75bNzBG$xq5!syb?#-{QzETjTw4x-m|+Xk88(-;@mJ{@#KWdL8@0 z*Xcj4&}-S9vp7LfQ739O7n9h0wVp5d{4nbotM}M$p z@d-)4vs$mAIsf7fd1-A_)LM3AS{o{_tvZqS{QmM)q3iXcd7m-nG>;Nx_uGc_O77ZZU|b&+ z^Qlkt|Hl#^m`n6~&U|-?(>sUWe2MulwdOj<%?3RnZzf~^$iCFJy;73R(}<^rFRO38 zK`$Ecf(iZFdMZH1IdbGSUqhcY(E%p%d&xva+Va}NC-yF?@kR>suNYFBA<{B3myGuA z#kOn(yKK)!y`!By6S|3ecx?EGn42jrB&26ew4XX4^NEo**!z~7EpEa zbKO>EyZ%)B%X-uHU-G8yFx7cS)}`z69US?~I7+IPRR?zHQPEZT2CVFQIZI#S&@0U0 zFPFvY&2TG6Y+-$J@tA72licb!aX3;|jowMtek9wJvZTM&hMi=&f2;kkT@mWuPReJ$ zWt)U4m?Yb4@s6n`yIAB27CE?_8oY~04d$b=R-~+z^Tg52mSx_71gRe({wdRD)N)z|aPtI~XPgsNZn=p{XM zGmfc{y-c%~X}V^crl9J%m!h*(Z}S+R!6PoGh)c-|YR6vA2PG?H#YHY{pG#aKwC85+ z8}qj5bL-t9a@&-VUAUQ?w94@Jm76QiRq$tgEOqKWiW<+YSRdP`yXcN79#Bd7@8{yA zl4k|7b&~ygrt7fZoK73WXQf8(*K^s=S5UKe>7i=%ey#|cSF&Oyr*zpHCXnOIhZ{E5OsIXSI-(J*C3gy!y&F5IV=vbRaEkDzWt6m zeuxC~_B+;;-jmIXY$ux+YJUu;mlxKi?UVD*3+s&Yg3pD9si%8+y0ZQ-=am;~_hFLR z3u$DVm$nOfj^L}F1$)mTFO+^nujzN*tR{O*H9JB?&JvOKHPz4~M5KMqtcXMs<(Fne zeC721QgH?g^DS<6asmr8za;%q_HvkS2^lKU@hxeNZzXS>*>}j{?;CCQb0V}p<)pn- zX@eOzS3c{sP4+z>EFGBGvzJ+Dk{$cf`ZVlIb@@9=ChZR~$&lpX@x2%&Kb`#OFIDhS zii$5)*`t)pU#ezDxerKj;7yKTmaMp)DEl+WoFUDca-lWfZmaJaeIeQBi(^{ZRdTD3 zl^kPlzEsi2%$00N)^eNg&v~ihtRZO@3oZ5^<8YW*%i4buQ%RRE)n5#b{?;>CmMxDr zvad6qc*^8*Tl6I#<}o*{%klr&B6Alpg-pq_bf%nUO}XZ{UOKpIovb4*w>kFyabiOQ z_&1qm0dsKp39j=0_6(L~$>rBer48jL>2`wr;HBz!f;p$x&DxGIbCNWfWc>;55w5Lg zjgu_5h&k@s2`aZ$s-HEusI{__dJB&BfhQ^8oZ}$-w!TA^7_QZRldWB2jPrZOoT#sy zr`|j#Ap1YXh;`(NC+n-hr`|j#AX8>Uz0W<&o@Puq&ATDtQO+_XE|m^zFEAL7rwIEfF}+2DI@#j zEZafjd8ezP6$|ydUyd-9epdHZJv*j;W*T+#loL(ditKgSk^H~jAw z-a1G8ek6Vk8!F@bY&)&p_l&s2h$#)#=D%-x6GAb`PI8QPi z{~gyab4TzrzS?=V%)gNpWjTB#mw&Auk7m+%#^nn0jPvF<6ig?a*Bi3M=gt#}%S2*+ zBb9lcNX++4Dv^+5zpZ?$H9~943m3R_X{!caAoaDiE@axOc~;+JYuu>|9HUpWtxGPz z+bZoM*F+Sz-sA&=`9UQrk`&vj7)Gc|h|z9CJlILL50nfz5(DXXOJg2-k;N^0xz2rm$hhSac-@VKYTpvhK=tCELiH*2qF9_2wL9y{@pMGT2e? zHdB+Y=!5;P(cQNh?<-lY6;UOx>H!Yv%l4}33^nO0^K2k3PH$;Gx%V_kltQ()2!Dr_ zP_SlOHQQ`8=m1Y@3TE(VzG~TY>h$N(?38?8U(*-qRxwqxmA9^McU{-p>sC2ameg!@tY$;*8+siFWkj_%g-h&=8$5yUT3%(|(5u=@R!FaSQy=WGzp9+R z^tR4-fZu*6{rWFDuf=a)GriC~eS*{eZGE-!551$~1UaDjcKgB)xspCfUt%Gi=r?_+ z7qoK6aIO*eJtj#{e5lvgt(;D?^;fNaD}U;L>sC_HY?Z8AmJgoFEz6!w(mVdGAGbT+Wta1n(l^Kk=`B4~4ubB}P`B|*y|CS0JH7u)eIl<)Pygp%J*SWT^E|3fIU`Sc zK_4TRAJ>@WUB)nbxJ{ic#K2uHqhbJ`>wK8s7~&nMQVJM5?4{ePn~_Y>IK=qUE(@vP z;@QZfFykkdaUR#Q5G(NH5rI5wEgSg!HbW5z<#f|>n zEtwHz^!83aGRlx!6)YledW{l>p-FTe*my|=jKDDr{Q9`Xx)uKFW2pL(y8s)jpGRmy}8xH(!RRd_og>z8G8G+;~PF@Dj9jSQYyBRQCfJ{ z8L6gLGD^i*ck*QWB@gkwH}0lq%jLSl`}Zk1&+UEQ_w=VnR5pT(2To<|{@$|X8b6SE zgR5l+qp3RC!H9BIH*dMsV3Gi}u%i)HdaaMmU6|f=_%^P`Kw3%#+M2w1+f-wQH)01% zIt;l~*Sljib0+3sToa2P#$VVV_|%PRq;=3ichgS{)H*{H%`WXa4|l^9rzs2BBwt0EqsBG@g=@O zo1LoP+-=dY5c*>IR6010+_llbmgvH6m=gzK5T;=s{1SQDoO=<5;3nklknV$62rpm+ z-oZ%x3yYz=bhIRfVKl~IDNJodM`=2`U>O{OW$|+?hu>g%+=3PG2*%(KSP_51s`w|; zgv;%qto;t=!5UZ$>tGd(#Rk{_-^Ye_Dlqq^<6Q;}!}strY=JYeB`(LdxE}VjcVhTj5xYL*Do29)_ReB%B}6{aSi6=I&m$A;YKWjo3I9^V>8@_U2qpB;BFj^`*8{$z;EyfuE+0iUl{5C z1RduXa1w9fS^NjjVPHX8QeY&W$Le?iTi`|Pg+JiO_#;k3?rXXi;bq*2S8xwr$1`{X zZ{TfwRFL$4hYlOX`+FFSG%Ir#L7Hc|D?0_$^BL;94@*##}S1gM?uom{j=GfOk`tM3dKL#Y? zKy+gQPDPr_yO-h++=a>bJ${7ua45b;+KjpLaBCz5OW|;=gET;Nw?b;hyW@~5+oQ;)mKGw%?uq}Rz zy>Kypgv;>@OkF|8LONDrIyV_@h+agfA9?Y7bjo90(b$V@gi2o%lIx{!H#$x zlkf(P!<#r4Z{bG#36J7!yk0z&^iRiA2KmsAEse`R9FDlUP`r%1qSgHn3!<$g4WKXx3t?(OI*QU!79+7HmcZs% z5TEZ6*u5pxF6ra@398{gmv&wj73K@$sF@wLm$$AF*@F5z}xs9 zw#25`8=K)sY>r=I3tWyZaSyh_3)mWe#WrXwMZSRfupO4c_pvU1fbFq8CSV62(*IaG zcuTE&Hg>}G*cp!?%`M#-_#ys|UGWw6z#OH?NU#w0#q!t>Ya`7w-7PTzyI~^6;}A^2 zWE_tlrP48-j-fub8P2kt_vz1%ld%MTiPi8cY>d;fEzZPlI17_-HjczOKDO~W%8}0L zkH95Z9#>!kq*2LhH}Ai12^C!+=#sK*0u=)Fdf5j z8G%R`;6!YST(Y~n<1|dcFL5${g^O`I?!d3{EY84N zsPHk)#8)^MbG*fM0T#lASRNN)ZA@KCM@u@EVK-cbgK#ybA+KX{e~BA#5pKav$QLBt z2a#sp?#s9nAL1_btw#FCFx-PNDDS0fg!`}y?#Ch3NdE`u7|VczI2{k+0z8Tv@EGpL zQ}{jdvU>MV_&xrK=h0D}@;~OmOIQpuunJzo26zkK$Dgn_{({4*lm740@fibt!E7JPQnQM77OEc zq{Y2E^$Z9~oJ_y~*PODu_jHMlOoa4d`EupHLHir4}xVOM+$laMC-Za3DzX;>2% zVk~aNx_AH^I!XWM>1f1&+xQ+n#ir;}lk+@=Vk@kGyc59P5Zhp9Y>R`j9gfHMaXx;4 zo3T9}#twK9JK`<;5T9UIC+Xi_i}N`Ha$`@7#J*S=`(b??i0v=|d*NUlibHT54nu`0 zxD0tofqNT{!lRgmmvIc<$8q>CewIo{-rC$4z|#0R#^MD00KdS2I1xX=NjM89<4T-@ zJ8&u^@8XSphaUyQS zdAJGJU^?!>ZFm}Y;T_zKnYagoVoCoPh5N7u?#I@#lK$!F%YcJ88V})gJd7*x2=2r0 z@CQ7K5AYb;>vFw-1@Hux!;@GaPhm$qjY)V0$KhF=i|24--BdCXI*u~nJYL5O_!KXq zQICQL7RDd3Dqg~-cp1Cn6->daI2ki=F zHE=Q3WcYVjm;US65FcVAzeLg@9W>yu)?_vn8JWHNLvT@Zk&b}@N2w@ zGw=Z_rmy=R#R>Y`;5_Vs^Kk?&!g2U5eu;~j{vNKN|2a}m&#gD5bb*DNlIW-b;*Mbe z6(!uUxEWjH7VM7OaR~0fPjC-T!M!*K_u*>XkGt>yp2s721HZ%H@F>2-V;Ink+yWz& zZ<>+2!Ff8{G3WyJLf%~K9*UQ79A3dMk=MAmSKtlYfj99u-ohVLmo%eO>T^05HRskp zuEiI)17G3^e1%u>H9oWy zJ++0cw=EYP%NURkH(`F16PBs|Q6g|QeG!wOg&YhV;M!xGp< z%^PDxhL@*v8-ps~8RYFX?weQzAE|3&jQ3I-)A@BPQWGx0X1Eob;}L9uKVeJ!16!eQ zYf=;D!}l=?Kft=k3vt}du>pW!{P0w;|v4R@CO`& zx9}5uf@9IqmfL=q2ghM?{0yt&cx;59V|$!{J@55LmDjn-^ z8t%X^@i2acXK^}a;MaH;XW$c5_zHQ)klVi<){q`j$5$`KgJz64tL@-+=X*- zH!jCLxC!_AQ>NTQ$36xe!~J*x58zEah`-?>{2LFW_5oQJ2Ha2Y9IN9A zY=9@RC7!}gcp7`-nN&Ik(Qy_>;W-?S-{V(!9_Ql)T!9yHGyZ`4@JBp>m+(itj6dNO z{2j02Gt5Ar_7rq5Ctk-;Oua!zaXM~d4Bo;T_!Bn5+t?cK;D`7#_QPK=8Si2$-opua zA7|jNxDbEC)%XC@@pn9kf8go%r2mI>TxP%{yn~PNAwIzu_$N9$P%^?`{0j@>-&g|w z!AkfHYvFTjf|=MBUtm{!i39Kz4#n3viiZ#!MKR-zV_Ld>g3;3MTb;-C)ze!{G)mjk z$4oY6`leT$ZZ!2*xuzQh(nrrVoOZ|UeYEq~LJOM(^NnJ<+=i0B@#&}L8;M$2MsCga zln{_dvlSyWCUhgD8T=`p}v+8+_iK5 zlB)J(ACY${Be;#{e4A^krL601w-qm`facG-da8j-sW;tIZHVVRBt4}nT$r!R98qMS zLx${^A%W(Qa}}u>6}8OBq4)GGCRFV|&D(G?)*AjZP8$A99=FU0ljW>6F<(rydYL(f zmlj8uZSi}mvOD-b^^;{ruHfdMSn-j{d_Lw%@-8<@1jmid8ti8de%yn~SKXEyrTjiO z-?N^frY&dNxHaiCK2}UoJNa1P6JCv3&VG_)z;T7tPOC7!|Y( zHE;!s;I5{#(Wh$03ZrOnBhTcrd*s;TgXr7Y3%ynBRbKSeTj?v=S-n+UG1{WlSZM?V zzvr1j;%_%+=&;hL$D-%0WYKq6^wLk&k(EZ2?^2mkrLniwqsCMcTD{cBsS+piO87d* zT|Vlh^iGl9ZqoZedIzjBf>ppWy1t-`FOL_QMJ)PwDk4g=>^|!9Dt0vAI-lsUny~dz z`)B#)H$UFxOMLpMva5|Sb!nMF%h*Zd85VreGfcKx_BP)pUu~2Q zZu(i)k08eiUp`-LZd=S6w(V!OZN_J+;~I{t8J;O+0ZeGCYqh0V|Ebga8u1KuPG`R$2;4P*PS&ja>NH~zzRt+c z3U6&R8u1&BT1S-c66GbItEKCVsNf}@1!bjFZKJQZ9ZiOcUeEORnBFl#(r2hT6_UfH zhOIY(b;ktnZr4__VT;!r<@~MMPZ>UHPduMNd$isNaB?TzS#g50Z{UEbD6^>GRV=4P zPc2aG>u%@k@~b!+Qj3yFxwkrfRA=d(B4Zaw??~xg*ORvpxDPn|bN0`+oqZCM)tOaP zp3B%^1Zn-%?;ALh`>Vi>Cg$F*vyr{sUp-#V&g;C<2=JX`#-QeE`bpsdYAOSR*L{(- zGv#3Euhwj&wrciunXl+=Qs3OKx;cqwhemH=2mQ)6u9>7-Z!+q?$-w5x2%Z`^S4>t% zHW@{ISMbzEQ?cYC%6~J7-m|Y%_03GkV+Ci-6xDsRQPhqT*0YOzHXGh%v>EE6OvOV7 zXa6bc^=7h${!^?-hpG)5*!@j+unz{xF_vG|-$<1}^K)kd)wCVv@qKIyv-7ON88cNq z*vyXv{!;FEb<$l4ODqcTCAW7%fPlbkF;P1|ZN?c!FJ#uE=`scGu< zR-;sKscF{IB(+GMl<4^cfV}-F(X5xOlB{mYjg|RUs6@3;y4PF7B~Mo7tD$&>NKwAe z_{bWr^x{t8&{p8mI8M?Em^fmdJ!Ww{c#Yu1;?!SznR~S*>iH><3=5+mjmWG(c_V z6QL?^F{YEUF79A1p7J=`%}}p*$T@IE)?AVl2W86)2B~H{`Jw7;H5#k+YYpE5A>0oM zrQFJDzV*x}705~VTaAziNAPMU2x0;!6BJd}f+d5Nv_D8`yUfJhWEWB30h6=yOd8J_ zQFg4g+i3dcQ2Sjb_=^b!&Q$q!GXef*f@!;%;BO`vJyY%2oo(m6k`ezfV*E@MwTFCT zJkJ=t`$SHqgRR%@UUM4xy?yhT zv&zq{D)7^*_S;CRefJs#gQs~`D?3M4KUnItTRG`qwP7zOj=}2GUJ~zMEh|GDGJHtC zo=hw=$qpN=w0-83;TC2s_?G*~Dh8{xoxH9kejmBQJ3Kv=Rmfa&&@t{51%tDnQD=F9 zOwh(NfgBcwIl=CIoap1T%_qfW>2)uM0hs%jU>lN>*tzeR+A(PBN35ZJYrb10<1} zjqH*o@p3{UPgYHL^6Mn+G^kZ8CpRV|3T7mEGt5CF()ZO|BBCbA5pQO?1rHIs1M{-B zQeu~^_MfM*V$(xLW!Wi*h+QVJJ2YRdJVXw2Xnxk@OwDUxo^Q&Q>Wd#{`WH-J{~Oi( zuu;m6r}rC${+rbvlc`=Z)vw>ECx?xq(Z7DdL;|XYYq)RN@qT^bJ_zRt4Kv3OEJqMa|xIzp25CNDZyP21~vLNYfi}<%{jwD zHZz(>ShieCvv!V@qf*pG798TkzWbEkyUVQ6-jtc5f{$~=Ng7O1Wse(SA$6FtBfS%r zXDvw5BAa#Gc(0UP2+5E3wx?x!wP?oi*VDrM&x3fU{|fcPaidVwNEYYAG&0_Qg*WPs z;B5@&MF_S!PAM5K$-gSAuXg;?T6Z6+x_O|EmU)B}xS+1>5 zujGck5_IMIA^w+CfC%Kfg(awFxN|kxi z2n}Dr5=NHh?hZ@Yk!>mT+CEk>r%3iGM=7%o?v*@P5|`P&oOz_GOC$ONR%QK2lC^!T zMxCMv_c0%JGGZ(I-+S?987Aa!pZVYVrxB+Pt5lBDMrhv6EPFN6$oLMP<%g;wCn)L! zgwqykq>4LDxp<@+ewtN{RI^SSVc{dStaC=sxa3|j%q+*49K<8dubFv1Chy%T-jB%_ zD9051{b^zTw-cL?)vDGRa`ZdI;Hv$?vsmHUHMr ztBq3I&lq93NBvKHI384slN5Mgp5d1rr2@|y)mwUt+}088ZEzr!Z{$zXz4z}74GsdR z$zvXP<$9RkYnI=lAhAD6kZA+fWV4{Oh5n04ntvyC_3f7jh zFP@3?g`SBPskrk-?o{iBg(h{G%s=k<+8#*)pI%1&E>1#l%s;3_1^nDMNR>*%kI z8?Xg#!Y;T4nbv&e{Z`yg|9;$wCy?z-bzh`o4+AoAFWyEba^J@TC`ZU4EQyD??Hr4z z=x>H+umzsS4#=|H-SG!Zz#s8ryoBTMGET%RI1R7!tC^qIxygW|4EPCYBw_mnb&~&G zERMfoHT(l>;X`bKkB}PwlGfbR@HbyYPsMy&CjC^%x4poj_!`F{8{?jccASQeR61tT z;fGZ7Hh1aID6g9T#nVr1Z}V024=|A7dH8v9VmMOnbeF`!xCu(R|XOV@2tdp&ASU_GlM++d9e%A6~eAq7`vgIcjHi!L=P;FGG7(!M1KwJg_1=2 z;D^``18q^ZKwAM@5nE~X*(IZTs(A~GL*x-hp!`YN+9t8$FPRy19EuVlSwSuwL4OGx zjg`@jR2Q+0!3HSPNuDy6{+38GaJR$p*cm^^UN}MC&_9rl$qbOpW-5M!U*a(Q3dsn~ z1*UrXKgF*Z{yEOTNuKdvdB#h*Y!<_p;~XS|u+75*xByAVwuN{Bzm+%ilR#~Y8E_4k z;7_;|NsqSWNIJ8vM2$Vf<*A!wU`8keH_~4OH)DC+iu^pbbY!>Nw&8Hxj-TNUWaG^F z=i^=`HoyHOyNpz9#^G=QiGTCQFq@V{)>%i;;K_i=#9S zD~-QnCHw>HAZv0r!^hYG|HSV24-UZRI0Q5CW0W>u^83BUi)gd6HJ~9sL#mC7C--v( z_~9!gUv%eZa||qwE+kiwkMf!OJrHB)&xvng5H`l#*b?*L2bd2fvo3(~7>ZVOJf9ttZIVYI8QYVzTKg9gl4dpkF!!VRqU*Xsr<;U%V6|pZ$ zw!t~Y-5ldlQtv?Qgo7~=rLor-l*V4;k#mlFp8R;j=vd5vkMSUm!tYQTb3H*aJu@+- zp+Ea<3f;7G{TY1sw#&(Q;+SHhhy^`^y8g-LY%N^B(TSjQV zb9UR9CG0q9)0K|WmTMbc!JU|ahfz}V5xhzNSx^5tyiNaY{23)zV;kI$JmViD+v0v9 z{p#^8qn>Wwr{#DWuYzm(=1%>Ku~NeO8}p(x>?(@SQ8I%}l+54-zJoRg#Q@Mya(_F@ z>BoV+&<7G!AqQ5$!H+AgkL{!g+}LPphPAgN@Vh* zM5X}Bxsad1T@4GW4!4a+JNJr5-zGzw!C*O4OFJOR*ydmu&c%{A4=bRw2dae&u|6)s zhPV{FqqGa^jnW**jnW)wGD>qGO3Y?+pqVJmfo7vL16n{q#%u?)iUFG$uo1VQ{DjgD zXfJL@`3ZNZ*gHm#RO{xnCZ7{B|0JDC5|FjJvb|lDJC?pj~(m z_u#L12!BIL$+ka`QnBqJN=aK<1j%9eC*H@ukV385GDr@?O#1)97Y?=PXJd4#bx&QB z7KP?tH2s@bTA zjLU4JBLz9ix9;s2hreQXq^+i{hZ=R)SZC)ULAiTIXsdn<&dH7#fWbHr%VHvy$3a*R zhoBryA7LjPhFx$tCg8^?N6~0C>z?tJZa!ilFKMD~Ep_CsK9;ePd_P4=zT>bc@}$p9 zzMrFy@RsrwRk#4GqAayP@h5U=4nypCJ&25!fjxD$WE{dfmY%8fdnBf8Hsfaine5&kR6 z5&k=}(PrBiC-S7o?ZQ7X1%FV*e>DcAS`SDxDdm`d#rc1f(elT=9CO>ai(+nDCCtb0 zDj11XQF5$mC>dT&Y>3jRq$$=xN#*siKQ=`9eWVS^c%%(Us(S_*qCl8DJu>OV|U~N&eqenHopoT zy%_K=_Qv)oO)bvh3X~MH1}Qk2&0_w=4fOl6$2O`{zZu`iBc6l@MyQ_7U^y7Jsc8?4 z-11;Y21o4n43>r#fjqzpw8h$_5K@dVdZv%M@tc20E@@m5XnV^XK~d1gGalo2P8(+# zt}~%DrjTN@G^UWmaRKG-(ZwB^040ljh;o2QBMjNeGNbP44?<~-kq4!bMN!ZAlAiGu z@CCzV-^+Zp@L&2R7nA-pln6}J+HmrAa(-ff0}r4N$|34RDMI<-88q-B$^w4GK>9Cv z`mbP4`ZF*{ee{QsZs$o)xrgjvX~7^rnzUe$6x;?S1xw3?k|-?}}}TTH2wkMXIyQTBJIA6m~#4M|MQXi=}#dEJ|Wv(`{Ypm$i1o zei(-%u_sQ#UT7YrxP<;b7-(xoUR8onTK)N_QQgiHyK+xCls;ypL}nBQVJa5HG%SZ> zunK;HvdLqyIev=Wa2(2}e}=-e&!keIZmQK*w(`qY->+wqP}}-R7vIV z@I1iN%!heQCwGqJ@G}2qGn0$1IVc&YRE(F>g;b1}3{)z{OPO{7mc>O_2^XVx&o!i9 zD#T0V*PxU#)?#-#o~2@ZZwB!8GV=$Nit%IUPe(}*+ffp{Y@H0j(o z(!We63Fjcgx8Py)=E(c$mkRPnJ=2|H{kGE#$Y8)(eC8REiBetOU*nX3W${O>hL=%t z+V8O`Ud0ZWfqhXT&>y85eY{7xV1r{uo{K|BHcG%t4VHqfp1Hm<#J+9&C#RuszEBa#0*ge!nTYE zj76qTHSZ@EX9O2^X6^f}7)}3vEQJ@bG~UN@$n}9)C0}j}SEPSFR>GB788=`R+=bQf zB)*Neum)03z*Y+>mf31c6=nw=br}$Z^|3HEM9OJq#eT|Jw)g0#xMWt~AA;}GKLR`A zeC&)1u?te_F)QlRu+*%de-67doc5Y#eSDft+WOPaiPaV_RhT2_NWhAigq%vvUD+Cw z>F3O58-|l`1ac}dE8x?D&8%m?9mg`924S{w80JU02P>h}pO3}KNLFbsmrT#BF8?8> ze#wa5bnqbGJp^YU8H-szp2jj}{rInO7Q+|fY$VB<_2N0O%xdm7a%5 zq@+L1H0tn$@fB7c-&4iz)pAEmEpVnYYkkX^S!#Jl;$a}ESQuVqON)_vYC{?Qm<8$1K znfM(_mFiRY63?SlslFryn1AVz3t1k#nHSX#d_=DgK1V0YC5S%;pn*K7u>~N{VQhgI zgE_Ds2BG9nxzw~*6kvG7o#Qpz8OmVUJq1zDI^kFV3t<#SU}Y?fu~-CU`y#O=N+NHK zCFqyk$TybF0!=i2M1N`g3d`WvSQcktahxajhbyQRuZ>n71$& zR!7z9kBgz@1Gj7LrxCgtc!~Yt6>>;baF6RnO?a5Gyes7fM_s0;7M=44q zphPzb8{uGVfyo$$LooqUa5Rp?2$vJS7BB$Sz5! zL+D0GAxtDJChQ_yAUq=YbK|%&p=o|@1jo}cmav?#k8p|bh~Qs9vlS-PAhadK6UGu2 z6Lt|U5gri<FDws6%K^h$oCCEFf$nTp&Ck_=mDQLJdM&LK0zoD39&t(y^Ivf$)G3 z5XJ%tH3)49Nrdr)<%E5N48l`FP(ikqP@mA5Ah)Du64n!r5;6*E(_(wgaJmXRxoPG+ z%vUa)u0oE(!}u<6sJ)X~M4y(+`k-+xb<6205&Ziw2L)QrvYt8#xm1WB)tqvv4Oe}` zR7*cTCYH-n_s`G8XWUY7x1XyEl_kRbUC{wAh}ARC z6zW_=jy$TTzsvhp|4cQ_-$gYvrpZiEJN#YV4-IFk=Zpw`#fX=lnQd+2d-YOrf4QPP z^@=l97oC}3GmT@o8mGI8MmvUEah0kZGl?uWFsWigUiD^p;b3|x+{adN)bzA9$W(a^ zmh&&msWM#EGF;wzvY9GPM%a98&bq_ZN+VnB?#l>`5lO>UE?2e@tz3+-Gh)KHYg_t8!uoosWtydSsW1^F_WgUOZ*SD^u}LcvQsF_fJsG3;!9h@pV>@dNo~y%j~0 z`RNW1OJ5Y=8ll;rrKmzVT%{bDDGs%+3au`Jy4anne-4-7V7IBn#@uT|s(XbETTCoO&EaZOG0!T_qh!Oi^Ca^@5zt$5!mg=^AZcGCaLj zkZZoyX=+i49rqjwPdWbl!#Usy^$DE`DTJwn#e`ji3xo#*|3XYhs77c>h$oCC%q46l zoGhemilHIUj2XU#{Ti~pdv@DZi5b4(_C34R+E@NN_?Aa&j;S_zUD3`)jDNEG>p%2D zYC&FCK;RSJp(jUlA$Fc!#qM!NsI##SAJub@vw(8H?c<}KFQ?VK!JZzfJRm!hQxSY!ys!{n|k$#O?Z=bz()ncY^UbQP9$3A^;)-1>V zQS0^CN6l|gsP&8Z0Q6DoqXlQJZu3h4OvscS@{<@-JPVM-DC<6|`0i$8@K@OeQ;=rx zVVQdR{;btWT0E*=<#)Bv8meXmT#-4rq;fvv^?|Y+KFl5yLKWRwMRPcnD&PtZ_KuOA zBoqASQy&eL7QzupoegLFK~*Zm<*mHmP<t3<9( z4rXna#QqrH8=m9)E*sV=jFmKHCAV3L`JtIhVXi#RW(?5|srjq5qQP8uNx4|w@@3Nw zu^<(j!zZu0GMsEoKEbW}=HuhM8I!cCp32`%)vSUnl`BtY{-buacb2`9C!xuK=S^tc zhzG}Bj&N6R`;*=2L&IGMG<%=D>2F84`rCDDZ)#N4mAYDLUl9@ud+vG>S5=3bsG6^! zu27Uj#@^ubq4S&YKPK0M!Ir2?D>zXgeX@+r-E;@YW^gR z-63r}BLqcgwhDyCgl>cs!UDoJLI&X}pa$v@2BADaq0Nf=8RO`^|KOr{oK(5!xy1Xr4ON$A@k{YY}FCL+h0M zjMm3RE-|;B=ZrNspK*QU$UP(4RWNw4XHY)R(S1stdz-hc`=@ASw03;-mm{k^kyv*| zA`un5&NI2JU*d6Eor|X3+G+WaY6<=5o8@o#grll*DOc49>mwfRvi)p#n9te{G8XF# z;&V&6&e~Z=LTT58oIXX!hzQjPZHs7Iw7}=ujB=blc^#f}MN1V`j??D~-pc*3s=h;M z+!b219Ie3D#BNr06$sApepVD@ zLLa49aYf_`^9=UxSRYMIPSpx2^CK76)u&Zh506isV?R)9tGEXH-KKld2fU2`lB1rd z9;l4=<~sFRG)Es%(QJ2B+(rM~>2s^PDrokptR%cU&tq zyDYkftGRvA2kEbCxb|r8RBS-}_>)q1Jjc0IOqxm9MYuqCMDQ<40hCaK(3TKSm|B!p zvbr{-J;{OF-p;;#R8)JCL*G8W^5M*yo))rS>Q#AS?_>A0ip^;6%Hx;BukNfP- zzgXgww)VWL8bgBVGk+raMP>7*sQqp2)jbXEnD_l>enp+h%(k_!+SBn(p)66o>d5N2 zU+=u$S4DN=$G+b8zf0Prx^yD>KFKy%e&S7PQYTk_ZIfEk$yL+ubv`KyB&z$JIC*f_ z-#M|Luj*9WnYF#mIS(_^ApJ;hR}L-J zXh=LIs)XfaIJ*cJ2=@r`vi&@SGK4yW_JkzDc)|k0Ho^tM1A^2SE6+*`DFJXvH_vbil?K>LH_u>y*=!HR^9=ac?tXI3v1l)xv}6Fmn@cS!=C|`G_y6 zE#ImI=*K+c@~LTODcr`V*elxke#q3*eEz7wd#*fH-eE}(JQLa4^h*9HNe){_a1aTS zdN(!)yWKlpRv;ygbt>*X3Igk_l8jlHT&EUVgZ6`Zc1{aW58iVHF%8Z5Yswcr3ZG<^ zEt^tMBA0VM?56rRbyc(T?GtmvHb(f>WJHlT&OGVbTh`|0Q$@%CowXQIKTf^fjQqBK zT-Me~u0YeBf_#~0y_&Y24V*fGOT-1uxbd-GZP-S0*7fS#HZ2lvy~md`o0}uNQ8M>J z`{wM0+N|J}XTi3%{kVd(_JZ7huR!MVCH>yJhTMbCuco(kHMXTIJqe=ckO8ts@ry}KISj`@#v zS6AA(nx{^#N7VV_K(r;3(54es6HXHD5PV8-eMG21XiMlza1*8zRuc{pG6>HIK_w{~ z5o!=x68aLx66O-t6OIyY5}pwPq-GeuUV{#rm3j2%2P?vjoiw+K>hFrOWApy5$=pzx z7Vir4mBK3@{-rf3L(*uvsOn7NCP9b_9!L`KFD%9RVtkw^X#nTlf81F`PB}(GRNO#L ztRZU201Cf7)2y*_5|=|OM8*8b4ZLa%{K}}p@#b|#L>Q&1*mx2{QKEDqO?8Z?^mD;8 zqa2e`G7gofMQF61w~%O=ZwU$Ii<0IDGjd0Z5V;xyU3v6($9UqUZWZBG8Sw*M0n9yo zpexe8V+^+(_!cHD%M99TPb5S5e+WAlfU2tO|KEEB!0!&OyN=n^QQqpLnjWlB7qokmuq(Gsd5eEz!DJ?ZHosmZB|J`S; z1GoPF-~VTQSZ6=aeyz3l+2?Wbn40<`>4fL|%PV!zRdgg{#Jh^#WL$|nXca0aW>?|A z7F!#hB7ZH`4R{F8uIqX6?po6ra~H>y#n<7TPy8Crkq>Mq@~YEQ_^d;MaY%6QW)Zax z^}QGO3S}?J1ab-IMmp#wO4ne(a~GC^q)(vI@EJLh^8q=sGS#TTD3(yG}7qmeiAL$ zj{HgytBO;}TFVj+rA^?W!t){q-%t^`9w!_sI!5C6;)d$`FT&yxS1v*1kQyp1Zs_16 z>(MN3FNoK!+N1hz_>u1W2g`=^6qXGrfj3GJ|AKhe4TCLW1NP(MU+8ae8`1p(K6jIw zXt0MV*Sq7V9i4=`JAQ@ENmOq@v%nJHG}!OkRypFt zI(PLwI^MOB>ZVyRKj=wb?um10rr8EVQ{IU|&zQb87-`7pb@$WH2;I#zWf|_>d}8B9 zT-+F{ww!n^+k_wTihtq6&F655Wu&v|b$_OP(X3q4g!?yn$@AitFc=4=p9hwJG_W1) z2dBXW&;=avsOSU`0+xZaiJ19a^t(6V+Dh(Me0WZHZ-RY*d}x#DxV}y_w&R-G<9X8z z82P!MVA5XmJZuRrFYV5q6I-4)jj^2L{TbOkvMhC?_yfBDUJhDsf-FGbhvy7p?ksHe zj@xYVGa!qln@zh1Z%0uMgEOF27D=z)y#+;DhQ^Mm6y95)U@>@7PSY2iNc|GsCl!pZ zR!1YI*4lE}NwM|#){uNtLDX$A%^Nx_OcoEf8o@1`NtuMzRmbi)e96ST71roDdaU_j z;k^~@-~6zR_m!BnMcBVc;q#(tl4V6Cok~WOW+74}z6k9+Y~?L=CQ=l?2zz#&y=7lX^@|ko z)dT*dKQ3IhqYCe%EK{Sz{OzWBY`0KI8SnuDBBI1m>wq2vSnxQ4T?(G?m6g;bElA7| z)!R+JeTfqbk+>3Zc0`Gn3j4NikBb%rC?6u=C?^(q_c)9Y9xuUAX~;FnO} zC=pL0k3=bnY7+8`B(}rV*!q{%*q$VUNyL-LBT-7C`eoBtW7H$ufI`0%hIi2}EcK#< zWd~~aj26Ug8-<@o9*A!@?0~J@V-+SF7^UpSK-<0pHK^h+&B#TGvK?sr0gL;)N?PD3 zas5GLcUNXNgTrJJInhK3mmU0x7I$!#fmzdlM- z7oq68tzt;)%tcpT!MWbI3X=wtiyrt2ivBMSljV>Xi%}x>6%^g=(f$)UsNQPP56kQx z<}jH=UO+~P+E-BY1}kqz)!X>0>2VCT#8)vWK0@EW{g`;^Rnt`S+mBJ^GJ`?Fa~lj! zL^)ovenj^8NcD%Y9}(#Fkx*2G;;Sq>F||J;_aR}SaV*AdGdYRezN38{{xVVz!Koh+ z!8k-@HFbm;-!XYa>eF!d!)Tkks1WYm=!W5qORZ6*M5g>e*c-hdOm4;sPKCGiU&Iu7t=Yz2c-$H2hckrl z!5OM?hD(o&r}toPxMXz(xmJuOLl{j{ZnXMEk==Lo+P>0p;Z=+rK1L3sW5q+o$YFGB ze;H*CkJ1I(qx5MXWtYi8oGZpv{G+0+*vhtgzJ`20K|W)bi-oUQ*|Q=Ua0UUhmy7qU z1N5&Wpaubv%f-akO%I?tsqh;3DZExMx1rlScV5Tk%4hJ|0w4K{h=aR^V&lLWk21O9 zF{R};C&vG5cvwGzOuS60O-gYnJ0_QRN=z$_GgW(!1{NKwFhEjVaG^Kt4XkD`f86&5 z?(A%cIPvxyrVkAUSmSeVVRe^VYFcD~1wL1b+ny;=;-R-7VN?;g(r`5D#Eid~whb`6 z{n&|*-!`ouV5E-K!3#K0eZGFdt9|A=yFFb7e(tuVPRc4xD zK%+pqij*>3QlTMUg69CW_VPzU9p5$C7`7}wG3;H_yMuFHnuIFh-zNFE3jXZ?OE2c&Y7HS zrF)5J{1j<#9oB1W#s<;(F-FywNF0+X96m8kx5Q|Pp`u8G_s1eXF=?N3YY-)$ApTc~ ze=Jjc`Ux%*j&Xdc(sKMS72TfrI^a?o|68kJ{Tfhy5pf3k{|}BV=LK1!r6TnVZk#lT zQ)iHE6S8&LD84;|yE-l#`_)R?qsN734XXdR2!;?DA0yi}H6}N)S03%GF*zaVPz}t_ zY)&YRm9!a;i#DXNgt7NjcuU*&xG;ZedID!o{uF0!#+jQoirt^W=rmcK84>YJ0a|Ue zewpb06xMc`Y=3Qu)F2{1L+Y=Q`qoCV@iU~pWtCbQ#aQ{V#F3)vS$i9Otmya%$L(}1 zzhAZ6h);Jop2bcH!sNHDJdA^E#N@N+?^xk~7R#qW&r&;REfyz}jN( z=cwv(ao}^)J;o0?OK*`^gVJ_=j_y5JgO5LEpEa4(OUmW4)|g(uKt2A+v1P-^Ixd%0 zAMPHA2~&OpF#=vcSk*~Z6=nPaL*ZvDZ&_8Ol-|R#`deD|+;Y+Vg=wZ`5qrzFl+zh1 zXWcN_b!eCiXqXjQVqrZjQ&k-bx56qfq`|Xmc>1S*)Ogk-Q412KsfoNTY5)KDH8TE1 z#Lv$XH|n8u`5a%izRW*Pc%3r^^THit`W)i_6Y+;+i{0n&gwK#{s++8Yj32MJnmlpW zU<~}FKE{g=xg-AxUcbO9a42 zK@+$OobXDJA6NuZz*evioCHna8nE}(>pVapSPW9YRN0p(`&d~Rlf_I+lF}y_YUn|IW2yD*r46# zTqT;@Ok-_vtIzH$QJSg*@YUKX5p)Uuc>de2Nf_5F!F~Q^@V9#w{#~cV*O&10SQiR3 z_wU#j`lj8a-Dg}SBELbj=MZgBrP%llu7U^Q%1^eZG$9apU%PvQGE|)Y2GiB7NId=0 z@J-*tXRCy<9cRx$@`<7-&Fbu#(mxmeWkR2>40X?iHM#=i>lkIYgp_B{^b~VRJ5+|Y zkXH$p4wNVlN!vdZ^E+Tw+c~~gqCC0FGhCg#^VBVFR&lhEOu7k4y*?7ZcJ$peMI(KS z;yjOl$zsYgxHXacEe6PBT+Ue6bd%NRayN;*XB5pgtrER5{br=cmu;W1YW&21;e`3{ z-}I4q>0fBQO@GMqiirGGTJ#J>TP?2=`pd8hTaakqM>gWe8vFjvNJNO;3kaz~c9$`6 zR{bG6)Hf54d*+FK&jRGRqDowPU*A6tOAs)y5sFw|^*f6u$Gm3I z;*b+YJX%+;8?HVHFD8GFwJ^r?#_vt*4PTuWH@?SB!=}^1^@?et5kpgr>q;gk?h1C9 z234NeeZ}OeH%?T$Uyq`x#;Wcrj8)l(V&M|yaK!t3 z)4&3-45WeWU_Uqwnm`w@_k(2wv%n&d05ZT1KfRmo2oBDIc5nwM{#cxYK!4aF&)r=x zl`+`s>p3sHyRdYITwA7pU)Xe;rui5f=+P=|);n)?=Y7?B(tD{D=S6Hc)>P+3CWO0n ztmI65sT?u1MaFqiPBH7dF-@Kq-Q+Ug#G-2*pH0SEuk)Xca719XP{HQ?$01>Gre9X)xaHv5Re_s^}hGD@K25dk>qC7?J)n1~1UN*4i4jEz7#N3uw;J)7VXrA*i0lhZHTIxwd(NM*`!}9|9e@g`pI#GH|G||T z3VZ24xEZz*zCW$Tt(kFmFlVDc58W}%AFx^TJq+IguWGI?8RxA=;o4(bId?I}z#6a_ z>;=a_6SxNKXJ9~qK(H93fURI3I0@=zVC)3%KCJf`cm##*Jgb)%&q1Q=+W~l##uuMp z-24lsrgDT0s1Gwg1IT)ZD38p8-12@L$t& z@{9Nn_u@(1_Ygz*PCVCZnyo)7PW2+uF?gkaFTU;V>%ybL=T`*an<#cad@rJYHBI&T z;d^Oj=yquerkDtfvm|)j>hq^-u;)bi2hiv<78^%V_p8anxbF%j93xUK_(ZDxZ>Dh; z<5ev)TKhdGN}sd;6UvkS8%}#1r@eJmy!#uJ3i8}9rimg#eo#3_r0&I1Fo&Mc-9cXE zs@JY~MGYWFsp=?Cwi_<6Lbut~swl>|ANic3davzJac~{1wWA&v+($)_UKu;^1kQTT z4K$g2R5(koC>FTXD$5yEY8BpF-Gp1vx%6;lRlBVXj$8D~cuOb8l=>$dDOXtRl<~%u zKT!tWqV!i>RV=ns##z?0pIr9JsUTMr*eUl~y4iaeyyYbYa`?b_Kgwnqs9^sbWee{T zvj-~P#_%r6)OA-kCY`K-iuR29QBfh|;(HNxZ+3}G0~PJ5_@lzp9s%zoVEj$7&|cAY zu#e(legxnRLA!*Tc$nWRKyO6AX#{M%DJB{fZ_CD;{f*&?0&WuVMzr!KwJ~hRsy?OU zgNIB<+Ip!z9qf~4JJNQ%>f<>`87(fLdBvhZXyZ**b}=bAU5A^WcCuOs6I<;R+?m>t zqMAStI>R7k?2vc4D4J#5q!af&tqfD|)NT^pgD`b(5@wTHx+x~r6$asMeXfnGGS{y| zmNE}qwxK$C6tjfHDU&i5xwMh12QJHTtJBKifU4{99n26#ak8wq)89IdYFLt@OtMV> zh5HI;k;^>wEW_1(*G-~YQH$25U;ur7mmg zB{qp{vzk}28F@`J@Ke3WYlIrwNTJtBcy7Y&dJhLQ{*!o)K@L~h2=cwTO(Mua8R=r( zPVsB$0Z;ip+$NFgfc(edlNVa5QL1-QxILb3bx>^3Vl@s}pBAV;32{`I2PzVJ;kj&{$t8h@)3*CfeP$tY3>^F^cugD4+{OBF>HjEQ_vL9S*CI(QV`)|G7` z`%TJxVHu(fMUWPXJ7>ZsD<}g`o>^>kYXef&I52yYl@@_@G2wq}0RQ)h>z9<@sOy6^+ z7&4)}Igu}Fkx-Fu9&7!Jhpm6pS2&ux^hFUC_4Cd7!qy2x@Bw^pM0SXs|Y6) zXq8KUn7qY+Gy4y~cgZttroo_9Ah{i0maxlr5tp2lsYCLuq9e9$i%xvFZNM-w!4bWD z`sM&dzeR*Q<8pvDj*p5$XN;;U$r>j%iUcgB-?+ z^Zzo8=jF>$Q6S^sK;lmkXM(GEV}zo;xN%fml>wh2V5h6t=%Q$^ zRvi_QE(pL2+;;o_5O4|s1Mvkiy9!sVf9e43F92U6xx==Rh6cG?;qg`hm6|t^J z^*K@vcf%d$cHD8^=ZaKt{VvrDBK0HNk@^=ze1LJd=yHXA<9I7}VP}4sFnEniRaGPPU{;A;qHirw+!r_au-j#D`PBAxlaU4^GI0%}m=D8&(pf<{5_w~E+N(EF_- zZT?9qZ}3S9?14fWINJBZ1X_2 zkpFwO)!n#Q8|JADG1htf&v|EiB5!;Zz;2_bc-vE%YTW3lMecA{hV~Uzny_tx@*JZK zv3#LLW8=3?xO?DwSu1k(7^p%MvJDzT*@=!|82?pQtW@DP;@CAKPRJNBYOGZ=CXYqp zuMzN|mN2$I{D4{9vA3 z(c^#hQ$!2USaNkg_=rACGLQT%~$Z8%sn?wM1?5J4ZIrEA8c;(7+}_&@<#7b{B)HwT@V5v{B=8epm4Sgx!e0DCLexgn#;PbiLtV=m&p zCzOeX3K#Lz6UtKKm#P`n<4GU2DD6)u^Nc_J-Y+l?#e*(97pE*W!1`T`L-spWV})yW zO1CT?abV}(h)0|X*Au_QE7+bO+oZ>vevvMy=d=~d6$7k{Yl1Sv_?>FE^g5&PJqqKr zCIPjCJ=rG1U^dh?UQf;0ntA=WSTlboDV6+WdqwF?d zAicFlxn#t+QA;(FO1w8&3CuY=1tSLkR%6zvz-cD7CO`yO4dnMxcY?#94qOKI zvv9=;W`PK>8pyAf>;=a_6SxMH0PJ3X5U>nnfF0l@Xb8X?*SBz>%*Kb1i$N~f1I~a}U>}HrfDo_@q=D^VKR698fG(f}p&(!Zhyz(*XHX7Gi-S7Q z1?=xbW?&YG0~ug1I0jn5Eihs(HhI7jkOKCABcK)B0v_{_9xMSVU_00k8o(7GKM~#c zujs+Q?Y=S4X{dZoM*F8=v+diX+6HrqqS(TPYjNLd+*aD*YIG7=DatEyPdQcbu`|o9 z!K2pO$%@EKg$Z#$z`gH@U)%b&FBH)s14bjj?>#YSeV>I=@Q@z@@Iey0i1)=Cm{4UEXxV3O?NB&Jb^QVm0zbWV)+5R7}Q$+p- zoNOHO{KtFZ-3`ig%Re}8SD18p3S4R#3FKz79IU0*EYP>tqA?I$oL*) z{QL>)t!_mmB48k13AU>}L0jGYkf_u?Z8nWVPTw9C7oWv^(Ia&b|IMa-ReqVv>hxKcH;HYtk?=r;MKTyYr=Zuq`E@E+#Ldc5EG1x-&e>q$zFBe0iMj{PgMWL#2pF|#U;$VL(!h4GADjWL;0|z{4=W4; z!D^5T_JNb24qOIzfz$n%5kLrt0~ufkI0#OIru+5dbXRbo3(@O5z$_2}R)Z|C6C4h~ zu4n1)EsBTTA$0WAsd#KvnaBNHYqf7HAD2Psb6b>$2A)B}%OQA7Wr}|HR>eN29Ul=3 z#CAt{7+&HeCf>|t`3zfZF5J9cAklKJ@K zQ)E)c<2J68iJy_X)1KV5lgOR-6v@WpB=d2VFXNkECF%YP$(~x0;kc`g@El#~Xv)Zi z3lhDVA|zsxlNsm*N%y~!+{FdRPAB&%tO#VhWbBei*@-2Jl<~M!k~04k$zVMDC*6%4 z-wRJuDivcNR z9yY_Itl_Te^d)yZEROUKt%Q`D9=1>k>9H$Btlx&^ekKO0bQ?wKHf4BJ59S@|?7>HV zq%6HoGI$_Gi^r~*>VJ`B!8;_gt4Ut>B-t~b;^VFIAulTTP4D~{`G9Ckh?dC_()M$V)+NtTYK>{IQ@UF^x_xJmAkQj*TtLX)TUXU&Pm(m}c_F*c-hf0AS( z9@&xZpur@Q-Y0pROihliWEFW-u&ueywx)*@B)&}HVQh2qcab~z0LhLGB+GvxS;{K! z&$g$9ZBM{oI3C*`Th;cU_cNWShDL7KBF;FSZIPaBQEU-q(Dp3J3V(6*B?S-riH?_) z@i~!fN{YEbD%g~?y+Y9oxjtSy$*qUYl?@Zl<-Y1qZl6OWUC7kvu6t1N+IXNAvxNy@ z3)Ato8b3$Z!X_r1O-#%@O6W6{GMvJurG_m;I-8cTr4(M^O0tg4C;)!w)v}6{ZW}-S4<0?^}?m!HMA6iHZUHxn1krYg_*FYHrh{#uz(K%k>qh@6KjPPlHD1$!4T< zy&7+_E}sWbG@qbxHDyp*LDKSXl7+!~@#Cv_C9niL2eO2v!m<-B?#Tlr_yonf%36~8 zD!DypknBE4GP{Mxs%S6 z=RpCsyvAuBME*T&qe8uep;+ zL%K^@cU`!GkzB#+zTzlOGrP8p;?=XQs~k`6M7DJn9w43E5LbCZu5=QvuPNTHNj!h_ zu*#Ki0~I-mrLQTY7Iu6?`IWJ4G;+fp@*#hhSd#wpNSZH_EaZV4%d&QY`1mztYGir` zg*(4SvN)Keg$MA}MeJsq=2=4SO75o$o_`AGQF~n%k*`C+Z@)p&^xAa9rmw!5{C8n* zPBv%3F>;sQBvD@3;jseJCQ8^S(W0a*A<@}FE*3DY$hWe zDN^&xByD$-tldvCpUq=f8vC=A37Adpm|G-k-Xa;!eUwaQQCI&s`Fr9iGgNM@uC{|b zlGrSUvX;d1;AzAa-d<(upk}s?N#Bc`dvV3rokZ!3Y>nK_JlL&U^4l&SGyYz{-&9EP(wtY>rB ze4Wx2ae7}KK8d`vhSxAI5GJDrVOG#j~qIpUW$ z&>fK;)EWV7Vh*v1sr(bA^W|nXbNXPmF+prwIwn!P-ls`6vu(T1*4USeb(^oV^Y>7^ z*f>>+H{Vo@IlJ1}Gn!-(8<=i3FvVs@TlDnC&%{qO^eU&xK zi%zPOKW>cX(&wllu_+Uni?DM_0mAOq&}OM1O%IR=z|sbT`RDHWRgH$Q`^vykDw}iVC_z zZu3r(1#BKFX?dqhVjJeQkiy-0IJh4tciC-{zHAjLb_mzEl>02jJV$ypP$#h7Hga>qK647F#)pzW|px@ImwD%%aSo+9+JIj!Lnl}{35 z-o|BuKlgMIn~X9x$B}F@>P>Va-yo7+3rMC9pnQ|KW4s@Jky`5ph%HC*M*7hx0Ufrr|`8=tRtQC6r1{_c@({I2>BQA`lDhm z`FG4Gsps@XZ;-p0x59!f;;p|b_vK`=|5ff(m!BzK$v%=XMv}4UGTCYV!%1dyC*<=~ zR$-xd&V2q}wkmCGP0Glc=<3;+fp{fpjn#1%30z zXNyvKzg~Rsjxr_ZkS#@M`-n5#L(-RLb_@5iKNqOto1W&UPgURhG35VnZEUK<-E$lCiu( zsPv$do${ja&N(DgdFXfY$|1%^jVHeOn_@AQuuW;hZvKD&rg%;7xkRbz*?8o!(J0}u zk;q1)o0}^0KD_3v%ox+#PU(W!SY-N;JAWBTpSj|-!&p>#a`+)u{JcdJew7VC@jP<7 zcahBdo}^iu=0}qII@dmNKDmvw_}0k>Wo2u14<(t&%ZV_OIl4p6)J#4+?YFQypOvME z2YvnLl))*sB+hJc+HR76%RZ9ze92P7CrV~Z63UjOn%%)_x8`7rP`kuDMi~UK=?LWl zWwPa%@-l@tvgL5!Pwuh}BxAp2$pwy0Aa^yJrpEt}J98&V_qQNp(KNAaQX1K$OyL5R zO{9p0Y*M_6$X&pj1J|#U`!=7bh^0B3{EJh>=kH==cl9Z9*PkSL=-(v06q03ZUOJyA zcit}~ZD*3a`d5;jPm?U*e42-oyMoP2cMZ8+(n%&yRVA*!*sip&`r_L|>X-=4qloD` z@z&pQ(e2Cjr0_KRvmGh@QGEM%WyX-k0pwqFKc)8#5z~(-59FNUu@=q~Z8P^+GMkn1 zDoPi$hhzXZTp>@yF8?I|&UZ-eV)Ido&XHrct(~L~523_Njvqpr``Z!4XJY7O@(f>0 z(wDCyeAICUBgy6ipATMGj>_KFws?#@{@HAJ28wM6A5ycO@=2dgvU;TWxLld>cqJPI zPriET^rrAcHVC`eAQbW{qW4z{Z{rJ(8m>$v8-m!m6mFiR7Y`oAOHuA3@2E0*VkjGe zJQoTteTZc3Jd)wOA}F3OE*@1zxyWa)Wn*0-D+kvj#el_Hmh+okKO`q(Xz9g z0jqBkw}cmOK4u=EaDQGMbf%HJ-j8Gjsj+U?8gkdZ4~fd_%nsyX;gRI>7joBdi{$5t zg%!%EiM`3>AAOo+FfS8&_(H3O)!cu$*i-?{C}uT}|B&L>uOn$2B0jHB9`eK!F>2Q& zRgp|)wYFuojueg9R>(Q!LBTcL9{IePQq0CAIa)fx@AX&}xdp=3=&2hyd4!)^4PV62>F=7Krrv8KEE-vBKBjoPgF2hYoycR=Z`177cnbGt)vssOk69qLolr&vV_FrABmXFSx3cJc@=l@k{#Zs8@vlyAu$#Fj!IOzs+P;9|BEwY*da*h}HH z^GQxwNwQg?YC6wT-Qwkwip!wrd;MsmvER4H;!DaI#zcao>qCX&(TNM7ec zHNHdcV3xhT@`;V) zZhMYp9!bk1B*RXLh3~^ip3-`TuLwK1ql5SoyX8xYUztl154x-Q=RHKSlQp-ER|H{v z5h*_!FU!%{MDe`15wEh5obrmkW4>J(uapa2kr`dpm-a~yu`#0umc-f zP2qX7#FKF6r1JgXMz+@VGbudGon*`xBzrSRhVm6kEjPsV$H+fFfTYW4k_Gi7J2#R% z#SL-lAi14uR5?gjv6wvCgyppISWept4v!+4_ji&3KanhDn;MGdkqs2Po&0O!NXBxy zP?m?v$v>0VjH$dRC}j%~P7SH6rY(T!IsMoWZpi!%_m6b%Y?`d3U?NkO6B2+ zojmZ8-XibN`>A}*JiB??kvqUuY^zj887l+HZ4~8|%Aaz=V=0;cU6O70QE;>^$=-WN z)_+amWt&M>ICA{KB=c$V)Ro(jd)Gip*T{>5pdp-Y3(0^Ps?5>ly-6OnH%T_WPO^}t z3oBp%t;lq>ew1-GH;X%uyCU9xh#yAbr9&y7=&dBfJxSVfflDH!81;;a*^KyR(g}lpBzc|3yU!AG$FLa*A5HEsHY4t~dhy=JiofYPn~V6- zdhzqe*x9foP|P;8lWeAHHW+3$7|m=jir7$;Pp5cB3ss?l=iK0_kI?A0_M3MHCNwtd@bOvLglP7!^_RnLr*K;$t zur=4posspwh6~)%O$mIs z70cqt9n0z*&FWmp>YT*tT*T_EXY+qxp7`aAGBvF5NlHKEU6M7djmfOdwye!lxFJec zQ@mbQrg&DSa*IQch! zPtu<|J@z?rmwA)S@olFZyo(#4fzHLG~gf61LrDvmoio5-V?^)bko+_vjT-hP2(PX)0J}@TnFG?>!`@e}+A(Lqn;ciLADVxFYqew!1PYe!(r0;jBC^z2u(4 zYMaMuo4%3!O9xQCc~#^t=AC}uPI4cj{uJjwQ+$?&@)$I;20JgJNJciGW#|go8Er3; zfA(;a72Ju=D>*)EY8z{6TcKEbR`GTz|AxXN|3cDb5as71iqGP`MK5tmiZamxv9O-4 zYYT54RIsKNv8KlJ1bv7#HI+3r;2)HE5Nm4Y17dcqGHQM*Yo-rtWEgM41#hAFW>&ED zHgd=JkPPP@DGCs8)haV4w#AWu+22Tdv4U1|digfI+DI=5!{@j)Qo{n! zi|e`jlUa>ZS&f6TC|z~jml z+-gCh;0xuR>Cvo*J* z-y;V$9#K@UjNbi? zG9o8PTfMOIxo@W=r+6Z$>VU~xNa`vsJ-+X$lrgRPTbpo^-!m#YkavK zz*AnuXo?tgj$|QEnPz`-r#?o~%(~FcgDr`5C$WLT+p8kL6(-GSm}BQBTqtfEDJV&a#IcZ@AB z>@sgqeD@HNc@-o}W|55L{IfqNw->8$8K>{y1>h;3u)Re2m&)+5nY|RfW(moHI+C`m zpp_5k#E)Mp?t{XIQ}-v&5w2h14fH%#AB%|m3R}x%36!qn2&eBN*`h7O9w2x4i{iDf z@RVmBYi;&X@(-fLtuDEc+%;_FYwsiX0Uq5I`^a7R2}uinBLb7B=O`*&d_8$z=gWx9 zWO7g8Z-g21Sk(|CaSZr!iyyrVFC;v8H9%u8#w1uyVE7&gAKTq*)bM>y$ znA8=xiXWPksje+gPG1v$EC9-g+WY?UknR#3v^NRo~3lC0p_ zKEHt6+4D&@a{)RW$sM|bWaD~v+mWnDCF%T|lu)uH)@J?p6mWGkNj+PQ8nzlOn#twm zQTcF+=kpNB-YX={+@kJ0VO!X0qWM1bKdr(t* z3H?8m&vKmEptzv;a@mv4JrTw|5jKLdJH`4D#?wnY8=iDFJiFNNl(0c*Y@~Fz(IztA zAT~USY-o}+LleyQIGPPiBP)LOhmrfkH}WnM=}>7vFio8!*4tiy*Mq)ZNR57%fq97O(>WRjk@Nha~_%@QNIJGkesa!+^uh5dQ;SHx3a zFsY=N+o}XS8TK1Rs%Q18`HtM~9waNyv77Z=&lhY3-;)1rUWiw-euuJtce0_%E*2MC zal^R$ubj_Wl0K{^^$z4NWc{n*9*p^c{Oei&lD_2htbfkjqW)a2m<<$O!unXjD|8E; zCr1~_OY+1Lis;1!?dE$+^|#1BQjknqM>3w*&{tWHJlR0hZ=vwwOC*apzcMcPE)EZx zAj8F|OUjU(FmBZPSW45uo4NT@$?eZN-R;KVpOdV3hGZ=FU@@m}?2+lE-~xIA90m$5A{b4ANjC|xwWZ)@wh z56FMlE2vpw9{oD`7qMQKb9g7~b!{Dm*JqOKc%NkEK6aB@ z<>)HMkw*nj(k|P`?e0r5i1pn62)Pq~BALv39`*paZMCbSW8@A9BpG~^i>S-W@}aS0p>*k7bKmKD@yTWRoFZ#-F>7)mYjP!P za&I$bSj?JS7D7$v!d+LumZpctLJXVxcvk4fffWA$ZHVhiSfLB^)qF?lI-}_X1@Dop z*-X-NpV-uiozknU;nl3!sjS&Pd_`o-n(gxfr7QU-$zClVwipL^6;Q&OK7}>i$l={i zlrEH8GSuBL_Hl<{C&quLIO{z-JU!bteQYy)KtbV46ZdU(wJ{qe9MWaHIn+^SUv2aY zo-bm*S5ok`)pOq~VL7(@Cb+Ku%rRpJOtSh9-KkpxGC&o$3oy~^&?q`6srpH!G{{`A z9h?PsfQ-a1-~gR&0l=>k>UIo(7VgEtF;E9C0DBvp z40wRmAPwY#?O+es4~~F40N<9;`GG936YK+r!5Pp1T7k|EKNkbm0Q?BGZZoI@7r^Bl z{OJOBK?ue{1V{t9;0QPk&VnY;4z7U-_Bbh60un$L*a`N5!{8PO#6oN@kl%~B3!E_9 zd4O3U1Z)R;Ku$aUTmyb4WCl_|7T5}Qf_E%5pV+&fS-eIs%{YumVg9s7_@>b;1*B@<4Z^&4y*wgBJ>AkY|b)A z^bAM?+rfTt1e^wEK@+fn^2`H^z!Gp6+yc5Gs0)||)_}d>Ah-)WpdXXLED!;ffz==l zKo&R&&H&xWxoD7)7_;Cmuy;d=K?sNd%fNQ92Q+~@zy?--9#{mHhyy<= zqs@UZ;2EF_To8>vD&vFBjz&xm!~j`fC)fuLgOfn#iE4mAumCIuao`xZEPSsiLxYx$ zL6d3=Dp+4Bj5t)66MHsN`x1x1-64d z;529g?O>ia+6ZKUouF0pT*DZ-Fdof20euQqgY94s*bk0?)4yh$zT?U0DHh$a1Go6j`yJTz!H!EQa~2i2~OSvyLJW#t>6mKO~XmR zW>5z%fV;rS7bgOygIfzg z2G|UCfW6=tr~-B10=Nuj&BoXV`@vbz1g?QQz-A6A2Nr=8kOj7alb~S^dQ2CH;Q^+B zH6Q~V16AMxxD2|$U0@%Ch6AfXF4zwCfU}?pw1aEF=02PhxPb}456lCLz&>yo+yY7t z%*qHb4om}qU;$VRc7TJR4qOIZztma=3^#Wj6XZTUQh?_0{i=M65s(QgIOR1><34{X>bSFgrJtd4fuh1U8bB+! z0&W3aC@KZwz#5PNHix4B>u_)ZTn2Z6{R22T@BouR2-pMmgCpP$u=x{C3jDw#ummK4 zonRlh0&W4_0<F0c>7$-!h00ak-Fum@ZNjtkMW zAOWO+tzakE2Mz<>gXmWK2G|UCfP99#xn!2V&J9C&~b5CN8fG>{9n zgFRqBI0CK#n+OyJxPb{^E7%G4fmUz@+yc5t)EkTd<3J$T9GQdC;9xJf47$KwU>}8o z01uD`j)2pk3A6*7M{q(g0r-J=U=c_FC&3vYe-CK{7zd_-K(GMBfgNBkIGBS!$G~OK z1?~d-Xq+6hK8liqz{gNhume zAOYlT#h;yEA2=$wr5sjxQeoW<4ax_k`Nu-1@=!N2}lFEU_00Y z&VnXz2RQy2MFv~JPS5~afxO;Rz&H>H7JxWV1?qr(GKvBwgAfn_mL;Q8R^#9-Xaa6) z(H6iD%mYh60!RT_U@O=O4ug|m#5$Z1Oap;n0f+-@KnAD+b>K4S0+UlPDnJBS23Ds) z@zZdy9qa-7!CBA*+QEcW6b8%#OTbpJ6YK*g!5MG`+yc7wXaO)nxZF`j=49Y-GuQ$4 zg1f+J0~!H@fHbfj><33c6KDt5fK3`28Y}?`AO&QBGoS%n0lIXY4lD+7U=7FsRp3H8 z8ul^{<~@Ts=x(s8FYcknP@n$45Wem;0QPi znm{|a18g>;@Ea$gH*t^vc7lE2FgOX$fCkVCu7F!2vIndEz0X3Ez%g(cbb-6TBMY4d zLclVR26Dk!&;;7S9pIOZ`hq1O1!RG(;4nA|&VW{M1>6F<=g@#44jg+94OWGNI&cAW zfxEyST00rc0(-!I&)U=~ON+rb`i8Z?1+VDmf*1ttJLFb^yN2_OYzfd+5| zOxui+02YA7IrtL?)_^Kd2QGliU{*ewA4Gs;s3vEuhTxpb4~tYv2yB*^WX1H;@9d zz}D^WdH(xr{qA3tW%_v{_E&reztzTUbPSN26PT)7KKRCo7b13{>uy23x5jD6P!DIVUPwy|D+W@52tx8OLVv+pW2K6^e#IJg@ zvoRM1*S%`1%RS*{z;BlHpZnha)N&IKrC(?s>aHGg>HYlrqg+#?SROf!5yEw#+10gugjG1&Kr8)b7xBh9KZh(eMq`=T<99J;_2)6!P3BR3!|Y_1 zN8En10>n~#G+eycW^bN@_WRTxt+_(nv^UQ-BqWHbM)L!PghcVQ(LB|XfI+FXnAC_B zqS70`$8vg#gS}-YnoA4oQp2tr&7)mb@OfsUwY1=67|$!jl<^K$!DuWkxK0g@9b_II z+Lsz_rKw^d#`6kY*xIBtSvMb5J;{%BZzkGJi|dH7w?b48G7s%92pUb(+%z@#`XFd- z-00%_hm*z28~t@e++J|TCzQ&Xr?&a zVzxK?B6lq;MO3%I#-*U{-h)1ueR+BU+9z8Q3WPy|`-AF@ChDn;kf+hp4-tH}%C={k8a3vz8pHk>aYwJTfMdgQr;; zT4}{2b&sUQuTSf10`j9KkbA&dKQG3RmT}jm^f#C4CoIn9p#dk=V7bT$T@#&TMSj`{l-6mH9DyVIvx@J}$_>R>q}%Yj_98#d>dF4Bc0j8Z ziE3o!(pM@BQf*9J!&qM=ZV$zn=nJ+Qq$7+nc#4yCYAb7*s|LqAK_~lCV?1irxS|FZ zA$5)xoQUzLwc2KA0IHFgHa|TrZQa_wej7AwzRY3Qv=aI`%35K>K9rtJwc5~ED+=RUVJvA`w#qajX_$3^ zFnqM&tri(v`nzBZA8idNZ-_1uEyK)X`wL_>Vwz;IE+uKjpJh|8RexYjGYAyM1;Q}W zy3*cRW+_$3T|K1nKQjT1sEvQABTLok3LgbmbC@|Dji}`yuWgp%w~C_@*Cr&cm;N-F zkUz&qt7`ERpdw4vGdie;+8G1Havuku0W*E$#h4N1nR;KbbcFd{M+^xqr7Xx2Q8EI9 zb_u8Q#h}%Ko1k1vL_LC6YQfToYSjpYJ}vo!8j~NF5d&7s>aH61|E?4HbNuOIp$nG9 z)A7@RxSqIIyz7G1v7h)sdae+zuI7n`fR*9_S2(AMr(LmFp0!dObwylX@trHKF{TUe zkyuI35K$w|_v>eh-6P>SOME@je4k7?%nhv&ARdxpn%Lr|F2RpW*OTIg6f1E3P!y4Xt>O2i)vO>-6RZvxmtf8+9^I&QM3Wlqc^E71zF-tY3!a5D1&iR( zSP%3CTNPxl4E{qw$d3vVkAi3#s>6r~7R94s1pBhG8i{Mv;QG-RPkq5w`fZOv5G;Cs zm)c5|<&{CO@b!Qy_ocQ{<#shV3Bmeck%!vYMxb4SMX85%X{@vtKNe5H!`;sqq z*GE3e5-d_ZvA*%}gvskWZ$f_@`G`xf2=cT(3k<*3BzLteteV8i@UOYQ98yvwm&$&KX@F@F-NrhE*Ooct*;u?V3)C2U-e~y7kF`EG+Dr>>RfC&<7mPO3g5|6?M_9&LrIvdynoXAz+#C@;4&y{Cnjds> zIxpU?VH%qw^2eF)aaRwyY2+Pzt@J6F#pZ}coWNZ@)S^IXw3A#>qgcFfQKBAdQJ^@Q zO_LAsAQvok+|@%Z3iM^Fwugb)X^vQyY8WdVhd9`~-;!=E9u!CG$}~(jQw^k91HLW6nu85~wle8f%aXl^_ z)~{HTl(-f*3$$sI!nq=70BxLXA0zW`8*jcRQa#j)V5R!tMQ#RPDa@^!93bsJ=7{?l}nczr4hMAs)wA5yt3BD zOqaJTT(sJO>NX-~0j+QpMuqc-ZfJ$uJ6@hS$Oji<>YE!b{b3~rA!*F-? zP)i8i(8_!n<)0(MCZa*rLoEt)Lo34qoCmo~#JW;F)S_V6YSmf{t(+s*mKf_RlUDV$ z6!~+ttj6$Z8DCtVh%u}lYFT0oYZ|#3g`6WiC&7xShguYjVXa`fDC8UwKM6gp9%@lA z47GyYQlqFF5bB{81;bFwWew^9>rjkb)I%)_#*3EAG87$Aul>84Mvo|=$?T&z@Iae z3mh#tLk;$wX&sD?(1Ne2!Knxy)R)>{yfqW&4-n^Os*A5*XR3>@8MD;I*V4ty= z@zyLX?E(_TB~`8zt^w-eYoQdrVq?Jn;p;l!t0=bj-WuAyAwW8Tgd$Z)Z$cpSPH3T* zn?~p%fHbAqK%WQ}4mJct9wH!M0TB=^hz&szmB0OAR|NF=P?7il&dkp4?0v@k__5!f z@64GqGiPRJXJ_|f!k13F_>e(g z8Y~Dz+6J}o{=n85?a)DdtM0qZ$99$%1e*4>d_ruiz~xQCvZ6{RqmC@Mq};3|)SjvZ zUVR---xlbVgrQaCHV)I4;gr-R&=fmQWNLlPG%#(Ex#3dBmpm;;$(d;|<|q$&hp|k9 zOC>5ujj>X0>SF*^F7Pg7=+pCE0!db_@oJ?q$g>|bWEaemEgunCs)P$L`x#CtT`@*m zv=&)$nEgn1Dyl;>%I8ePl8|yqa;8gKWbNlPvr0q-fqWjr#3|i-koaf>e&fF%^?J4lFD#3Zahe zCYPMdF&kGdRRu>l4c*yItAcDTg2rJ=hWd5TTEJWu^pCnj*$5Zq&_fNCLsip5Gs~yw zlQhYh4rwvesS)Qmy1Q2C*@z+KFK^R^zuk3zwQyMwE&O$)*1{z&hUtrr)Cd<j*11`^xyttplxhAO04dndF5rSyhWzBe+)!-PDgna`KC?6D;b(n zCJK|2j>0S5R2K}}D}S7EkX5VJ1MmsF=Gf^_UPSy^S1oS8-&nfaN< zSbDA(8p>>-lJdj$ zK{TT`E^8JI%PRG7WITv&xWm(!Ug?c1mC~s|4^<|%_*iGsB~L89IRvv*ac*W+fv&1- z-QYL%qN$)yAjYfRWjbWm&YkPoR5!RJ-a4T;zfDc^?c!1CDIW%s1G+{UwH+j;!(#?v&Yw-|28lWM zi+mQMt9&S-{K1&>XVQ|vVmiEiFcOr~*}<3&mz0seD3Bdh0;knvp6j+V4J^W3zq52C zGYhV&NS}*%>`ZqS1)A1TbapB|TZGAUt>(dcbfGBF!kvi~*dfR!m3r|ZjjrcII&B>S zhcJ`pvm9zL6o*{uHWV}YJX*wu5bb4Q34JjX6Z%q$8HW3W@-pf-42!kp<+MT^E9k(m zKo0dChC016EO0F{XgeIqLNtaCC3O36q|T(ne8{3pe8{D1M&N+`7$ZbJck@{W9pghL z{mzFh>QIbBHkIH&zm0(Pjm7vNaxT4IEL?Pt6iM^>kU`ZWMbfP!QKl^Vg3od(W)u#2 z)Nhn%fLr-cLNDS#eMiAwt{#cRw^<$AVn>LSyp&U9hHqaZsG#Q6AaXcCr zC%j(AXC-uI98^lF&UjcWEu(_*$fdNL7L7**mtu{5e4t}}?Rv=3fL~F;&a9<zyf{E4TrL(GG z9r39WNzzQD_34K=5j{Quz0vX&{aJOgT$H6ReLMm42a6VN%bj8y1s#}(34%qJQ-_JD zu2d@FLmI8)Lpr_AhYY$p5tWXQ6HP)(WYHKtWYg`Fz~#_k9BA|;4$w(~mS}}$AhR0Xkh7Xa`XRxu-w{WBe3EGDZqMq|@FhBHOR{fP4O_@G5>P zyc#uCbjTGDpoGs(Mb07miVr0eGYyAQ>NO1=Cbf*Jrv*B=Q_E@dG?Xy4g3d6VO8)6M zq)|2>(y4+E8MKZMnRIMAT*;!Ve8{Hk8E_?ss%IdtT-wTqJUYvV5Cv!AfbDQN(1$bN z*s_^{*6y@2+CCGxrC~*5CUQ@!px`W6PNjlbFp1L5Lb7z)&Sw}0naiXGRS;%TFFs_` zqAGA$(cnWaeOCpQJW802Zi#-UuGENCBacSUMyThRgEUW66TaTsYwY7O`k!HLkyAwmBv6QWb*BSWJi5M6oPmb`GvnislPZFkfVLpOuWJ|6cn6Isl*-|> zpx1(4YB_+RT(vsyj*|}bnuR+FYdDp1vo;V!N`ITs=NYC`U&>8=w3nJV)JGIa``CFf zFOXujS}q25rL>ZjX!mzsEcMR|)az+Eig;5O6$3F<9CmLcWoD*YoFyZWis{t6K;mG_ z6yi)($x5chEV(!|eID<_u*)qu)1($y7et!LH0%06G!|3Uf z43aZTrHxJFundGSp;-&KdKc)W(mMZf)}k2;^ipZ_gG@|tNX0! zv#RZfM3OW8(jtl1lGv{<3%Rxz>V9bfwScv#^FrM(Eq2ZcdNyclP|DK=rJ^X!uQ|iZ z7iis3a?-C50!vM}>o?#WKU|1gOVxlO1eT(g2|8+#P9ugCeL>KD9W;VR(UTgo@#UZs zE#n9t)xIa0MxFe$2z7FDQNZgerouURn3LOx)BU(etA>ykHX8+eI>x1dv&;3iPT1@BT(bZcyfN3}R; zG{3s<-6-fyO9CD3)M$Q1H^v5ek-8E6xkPKW5;V8c;jcRsQ`%D91cnDiH%hWh6uEr$ z=>DZx4YEAdt~YCh;?bpgLD2lFAhnvX9oI6QM)NCrnV<_DG@4)0mj%7tL8JKj$u@o_&bVjAHiBk>} zhyg{P7PK%?-;YYnTcK5AsTK`I&Dc(8h3=^q4g3KN48{%`(V!OE_&XTI^!W-b`KcBv zMKmb-prF%kMnP_f@YP*+6V~j6%$)O;A}Ums<+d=ru0-XVt$ zqC%CtbxX_6XSGrC+BfSZM|>#7EkY5->_{#}d?-5k8q3a|H|vdnAW=FG37w-36IzhO zwX#ek-J%ysiRPQ~hsVcTcznD?yL^=)YLwPo)}lkVU;`3{ z{TncRekLRrZ_x&!GHskFYQqWI+={JO7)3e35g`ddVpTtX#zGBh{2`HIx?d&;-G~Gm zh2)eY0oq?BsMn4Y)V@vRaEcQw5RyVj>>SX*D#15`Ug)6FwrZ`Fzfw|6dv3!LvI-A= zaaqxC3i?L}jTTjO*K0+2R|cBfwT#A8G=IeeS1xL|GLV!cPvoVF*UgoKtvj%dO)GW( z(VB|pFP-3muG2g*Raw;P$aK^y&41nxtmp-T-q_H`Uw^UY@Iq>Km~xB&N}E59QcU$5 z`C@6~sz5!fOuQLb>5N0>T&6o#p-l2bmZ=;=fKociO60m-_X@49=pOJ8(;^3rAwbdl z1^rnx+*otF?grvO>9mL2?8f5T;f6dh-M|2#ls2*wU3BDw&`@+E6swr7y+ijBp`nI` zm4ex%krQ3XV*7nS96CMkD`VPiQb zI4LBfA+b7s1)5VO=z1L|SSu4;S3iFb1}S+W0z4;8Z)jGcw0kuN`874=Ab*3Wn8ZtP0?ICulZM7tOD}zT zvC5`!8 z_hqIJT=`yV`;RsuJhXulI>1^k(ZYpk>j}by#rCrq%1j zmi~9vi7ovNNIbYc*4p``Po%ydj|CZ--etgf z6_0)Vtbv+MZp=t&XssQG#k72y{h;k&P6_&&GQg!TpiK|ridkT$&ej5vH(3>kcP8n= zgLre+(t($%0{3IRtRQT;PRc|iWM=FBV!5e+s&-={Q1noso}DK=RyPFov8Yr)xqEy~ ztyk=XNV%ttQvCJB0($Nt^fb#e#HwnX;aEf}po=uo%RE={bis_Vx(KsfZ!*@@r zpU!Q-bm(E-I0iB0<~c!s{BR(Vo_;t`-!_4&Q98W5Qb5pYXVY43d?e_U4SMCHZIplK z8gc6J8+89rPpaw0MKk>{QoGQC5AhXHNIu-4dyJ7$Mcc9%P7w7-ATiOZjxyU>Uh60@ zI^nkZd#LF5vuWsnX{kr@`bT3GPcISc69En1c4YGKh8H}D12@-aOlZ5Z1v z=bF*#u(Tgg=4?^!lhZ!vh#^H7xqvAHqoN@RkhEXqWnhU7! zHqEU(w6(G~SJ1a0ffZDFXlr##RS6ey*?2Y3E=fS;5!zdMz6?QzKK!_z0ops=+#}Zm znIUQ)4`kRGpuJTFEs$9O-T64~_*78mY3;p5(Cw;X0V|;BCv;cQ{%T}zkK3&R8u*0Pd-=hLy14RZK{0YXVP9M``N4>~`16-QF;4M& z5&}y1a!O0+DXKmaq$f*oQP&eR>4G?vna9e9kNQAQ_rU{gUx zIsGoqE2!;GOf9i5WM`lw{k8+o{~y|kZ62xg;!d%P;p$E?-LB&&p=3{_rS5Zy@52$t^4hTRt~M$i(Ip5?_OBOw|yX_ zzI&n7`YCLq%A?|^K!@nor=VOyhxx3O&Oa5%@}y()#x+j|t_3Kk;->?702Ori(@;#M z*PlkF*pu{(aG}>T!i8J;3|mI{EQ{RFVp5+?y`IHc4&BO!Tsp>wJo4{@Cf?WJLkTU} z2b-nz>^{uxv5n)`eJC}yais6(V+GCJk2I;YYd^H`GB6*~smXIVWKi*Q;4*35b1;-e z?>vVrLlkoW!fYx&fE$Ps+HgSJTztW2x%gdf)C0CiJue)1;CWanp?97S^oIjY4&r74 zJ31=Fv7B}tlsh^;IS4J>TpYq7jRqZpg>+hR2xhUJ>=0@!lYTuU97sP5m28^IhaB2` z7=Gl^7l*;+QIi)$mSbK(@)BD80#r)r*b68lKC9$Df_*^g<&=Mf&nxKqBk(qr4j%~& zMwY>&@DDq4_>e(c`H)GMjzT4i@?R9yyyQik<mFm1Aavk#uik42dzanxy^GcvMjednA z=NJM%iv}IT4i$_Js#AG!W6@vUR`r)%FN^m9sJ?xJi|OZ%p>JC>h9O1sUW)$oql4Cl zp5uZ}c@>v^D>a54H9{WoacT^~9s61|h8;CByo?)`{=7A$FW$Oez;d~jTgt^0B`X)> zkQ%NV)n#)ZzKY>mnd9q_8i)Av@%?FcQA8YFdmJnHmJS9ZHLR}0eUH#dq#NGAY)G7& z)xwYbEzfa7(;vTyim}}?gNuctyW)nXKYi|?aj{VJK|!~9O;4>|nL0&s>e&t&R|8d! zgM$9^wLm;=eLWDQ&tAi9+VTR|C#5*OKHGs}JDbM!NnO798F+sxd>xlBD>X)2m73q6 z=uf9!m)SJ1br2m&r>cReqve3;Q04qa(Dg?~B-3+mAOyRpo-N$?mewyrh!Itk(}LdfmR4E(U|-S8aJz<1@1PMGif)fv zwf>ZLLQjpzP_BI-=-DT9*ANsc^#I&@^{1VV)Y{DDh@gLT(AtoZi956YbnV-E-dYrF z6ZFXtI`R102&px1YatcV;-N8a&)~(|nDtn#rHvJ9m^S(hOQ$_=2NF}{sca~Iwy%on z#cdj^VV648lH{qWhG9dgEnqbYoz!Zi1fikm9|ZldgVv&9J#OR>{bdocbm3&6o~u6{ zeHGK&9w{u2KBXJQD4`K3^qQ_6+si~@j5-kiq5IUz$ zX?4xd_SLkHe-xoVMZJS*pOqS6pxU`s3#L;mBNC}=2aJ{C+>B&ix>9<}gx;!m^jx%f zxGd=8DawpES7x-psA|dC)qYnuqXot{g04RmfwA!a0(FzbxiW*eP=y+I4Vzi@u3jj_ zg}R`>;Os^3~D$Pg2 zLN$gLv&xAy{zJUe|}a#rn>VBubg7 ztM%ZMLU&kId1zYUoP{&#j}HS;@kP=Je3jN7A#>d@N|P>N*zI%{Rcz^K1N#o46FQ4x zS~OZfl_S~1CdBsW-Dd;dI;KueS@yoeX9F*}Tp9aTd=&V}g?WGVCzzI((B@BYJ5frX ze1a)F-YRSGDQ;KsR$0NPd|pA-pJL9RO4~oh-9{RH@+p+lDd98RkYv!9&v1sDCO+V% z2?rYe87_fwpX0_chx&aEc`n`hIh6D0*yqSDM8AG6Zd=-ZfkP=x_yV^pc&laI7kCVl zRZeHcc?C827n0(|dOoDl?R-e5V|>UU_c_?hq;BVg`_<>*Z%GAh;L}t(!G|=udJg8( zDg8@0pFvZP_!2kFF!Lq24Emjgcn9Mv+iBr6QvYFEO9ekzo z0d4vU)z3ff)KJlgG(``fkC`5T3AsgU*RUfL|20O0BRZ{3Wy)yC*O(#jk3LzcG4`nT z{eb0iZ9+gZlymX=)7PQ`zW7>HS(9%>S^IqhVFoSYGb|%~gOX>_*>9kdO)=l1a&lfD@enjn~YV}^)i9$c(9kEVk(MnV4 z*VsVY!gLHIsun8ITSwRM^|R4tx^#>tN}oS@Hd@x2fTl_r-nu%E(qnPqJUqtY!g;Zz zviCf`shf)tSa)kYT|AF=8*irNuMn&2#SWMsPi=m})yAT=t0R99bUcm!DbTdsqBZBH zV~iQkLl1B5pTka@udWNZ7*29B5TPnJ-mE{~7=SmYrp%n&ZPo(Rg_TBdG~`}P)-L!s z*WZwrxyogd; zw04R43^krfZ7%7w*74V)N;4_spi!l&#(SVjGi8hlXvSGdHXXPW*ow{=`WY{nm6&3T zl`DQm=;C#spG8kP|1&}tulxKW`tP7$ME||@7pP!C>=*RkoHDv3j(9cg-&i2a!GhSo z5%pLQ<3k#q|2GzZFlPP=dl@wISFBGi91w`SHpduTRX)>>F>b~j=|(2LD`CY%dsKT4 zZE7D(OcGG3poUcF{sTQBhob(2j$&ERf^I!7UOD9Y6Q4yCP+8DwX$Nx8p){!U6;P>! z?B?fBp5++0&|(Z(JAj~a?kWBeI+%FuutovJL)0yZ)Idt() zJYy74Ia6+{@CQJ0Xo|xErUt6f`HP@A^zh|CY)_Rx?*~zld=C96C+ySGQYMSSn?sbT zgIG+;k?|v-bS9@HhZ2566yUpwzlnyu^*3=X*!!Ef7JS8rY)bfDTnmQsA(w9d9h$ge z|Bf|4ys-8MR`E(`!XMyDY26=4kVmic0q+U(p@h<}AXr}e0~dnnSMV|$KF_o63YI*v zuj1Gh`6kVgHk3bz+s zg#|2D@>wdK;j<9A|BFKjb@;EaH{rjqgBM;`{}*=g!s`KX#4$%?0RGRs@An{Y9ck+dat%yyfzP1_Tu?^QSs0?6C-kItPDXcQAiyTT88Vj0=Ls zXSOvOokF=b3SDb3g*>`zT0h`r(ZTWy*8-}-p)aUuO;_~1!E!5(fJz1H>>g2P&AdUL zPmJ-RTJhC-FKQ4E0=%eJR3x93QU_nK8#h$7IF{41zFhH2p5g+IhP^ln(R0QzTy;?Nn9G;Cck{UVu zI9Lq`Jofga!dQGizNe%!%g{!OZiFD{88%!?nH(?5FnB551%II{Wu`7hF;xwX5gt7a zTpx?7XHCYZ=I0D8r>1dewohY&@$r@?7}(U^BEM1HlcM5+9Vt08*eI(pJeQtzn~XA` z$a0b+rWF-Wf+cY}4ik~flo}Hi@ z*E)IE2Aq16gGTVEI{iq{rxJpReXYC^FUmN-(bdx^n^jmkcM3iMX|6c8VPO9yYNjyX;3O&EI|tut+)ssMX$tiZBO1hIkIT@thu4-dT}LZdWKL^ zLH=g4mBuQrl$pASE7evjo0+-;XVJ7ItxH#Emyq_&*~f>If=vgi_~2dAR(vqcK8C%a zd{W5GJhgD+U$X6KRF{Y7D0ez}YN{dZlxsJ%=3MidU{)!hsyuCu)d|asJ!y86VC+%> zm5Ls1SPvA=^(voPTJHQH(ni6FoU?c}MpZhm0tyGq@a2i3Q0cUCdv#TEW*Wq$*+Kor zIjs5hBy3l0nk1m~B`XzUm#V179ax2zX!;5$RdPz%mZmbe)zpyD8pC`xoob39!=lk@s*vji9Y{tuv}iPvGR_~&$fm;NU_+bM#svPH zQ#Q>=#(-m`)*6Nf_iTFDVH~AY6|qv#r?k|Wdi`Gzv?~QefN4B46;-WLkMhB|F)}n| zF7Da1?l0vsko0Q5EcA!rd+9^F>-|T{P5rQXO_6Ot52gfTFsay^f@wq!eV2lnLM|mV z3*w96*h1V4(}_G<*9`NI5S?iz<~?E39w{9G_0aek<>>T4z?Zfc9F_<4%=A_ItS8nSTq2h;y{SK3m(H{IP zjgP;aHH?3HDY2(=o69QWW0!nS!#!<%O1}F;;4Ax)E2Kg8vC5(1rGxk5~%Y zeP|1;D&&d_5G7w5^wu$Ta!PWk!?hUUvZ&(Ppjehw{&F!x@+S-ye2AYg$U;=8+GDP} zy#91Ii^@-ZRZZ}RY`c@I1DesI(HT_g(@cl$QIIlOsru93HK^3?6zYH(rDaN+9P?-5 zy3_p~aHX?obOu#xYXtqCBQ-jM^3y<_cc(x{w3w9|rBu(RrVF~TW3ZJ?m)SHg{dK41 zpj|k02sZRh$4x|cI@(e91|zldCO4AlKRX7SE>+p-Pj!da2aU;g_gOP$gl3jm@h0W6 zYV@bN?W2^w{9>(&PboL`5r8WD)(u#{+lb*4@k3y#nDALnAPkk#dRC&hQnmWlpX%0X z$h0p_rxAuKW)=vVzgbO1X^2EC2Ly+joLmq(d`~=3Kr?>$C2wVh!>fl;J#S{%7bc}# zmW-cbDyMlBr3Zb;UiC1|@l#CIjz0)GDjn@;(Wn;{1zRv;_Mjo@hysg7ji}T|kZTXR z#gSU;n0zVeL9e9id80;DX-A>o_Mm02)@?Kjg;GrsRm+}_^dl*Cir{Gd<7916& zT)!EQqk7Q88GI*_f%>-m$F)W2w8m|#(9w#gT@~LH^r?(sVwRN}JxHaVi<{FPMz?uW zrk8b}9-1=;g|JE?I7-PtXiK@xU)+PfV3EjD~CQqJT-edSs%V{Y$^-&KhhWJ~e{lvrI zZVTs@&!LR0V0654B1fx{r&*CgSs2_by2Kvbc+st2*m8`N$vpXO29;-h)JZ=&nuP(u zGKKL%jg!lmHinjm%IrFqGHFU)zguD$FpOjjMpBpExAmpm)JLCCUF;)Ezk4M zA3>N2v|iE!aV|6Hxd2NacnoD{A~`b+x{k`ki{S4k*IWinnW;Ts7jjb{eW`&#=d*(T z@zZU6%O5E-b+ySOe=^LpZRtvxsf%u<>UlcrQelo(&-|vdax)dZP8LmgX_=F9(;Pxe zwM$oAOZ$aQL!`{qMOZ1@TZC?hQt{J{hCy$P57Z7yp-|2#OQTdc z2j0~wnC&jXmuJO!1vTp&%(Weiq+nPLQ&Y_LY!d- zJD+9HJA8(Z<8{LUuZDI*&iKA5A8_Z@4du$B2HjyjmwI)FFpqBU{=d_m-rD%n+Z=yV zF@&jxZ;Uaeci8wNWwPN@MMsq#a+%Qm-|eXMRxw8oz(d`b+1y7Gj7 zflCdhqc8~d=0PYnNkG$C{a3h-2$iEfa2u~I@Z)r~GWidTQ@!y4>|i^a)-G#R7<+nC zT2FKtE49}9K4Us;Xp%BnvUKgD_6}O} z{O`~tIWvvcFW(et#B#7>Xp(YMAEQ2orU^YUH1X|3@37@#DKmAoOTfv$(3LV%7a^sZ zJriS3Z`#vKuV*caE;B9a**P>xxoHkjq$0EyW}v;ph9)U9brC~qXyVx_N3&ySl0u=J zQl1A38bC>Xf+M{vFW%XLHjcxruE9vL4@qN9C-{k@|`-7VPSm=}#5!VG?1 z97i^^^4WU?*NPtP7aZdKVCD@isOu!yjqD%HYIF|q%zxvi7`#wnRGQjNX@39UK<|1p z+otq&|KMnEEzVYWF=jxppLhK;FkLk;m_RQM2=?-}o(V6+=`{m!x}Htpbdq=F3`LwD zh-Aw;m#DG~!s$x(Xyc$@*G6lwoXdaSc0mEJhk>pCphhTa<%9Om86dBA8>>OVZ#%QF;2v>U6~{I?OeXTm|Qvd_v;h;5<*%7azjS{!C4E71IJmLuxo%=V6@juohx z*4&s2Do~BJxRs$dh;E;Z`d!KXZk&ve?_)WWPzh&7S#`OnGC0P&(y9}5ydv*9(#NHX^)HJa!u@>TH1x?@Tw9Z-qri=)qaC(!o;aQB%@xkfKsUcU9erh` z=pi%ELu#=~S0;|n0I@)X^-K_>xb9@!%tS=)=dyB7S~m-7m$?WSv|?%Etl$W5rKNjf zR&c2In+qD-hz3`oBjs8F4wZ&=MTB!dMSKQaZNx6&qSHt>(7CSJ$ zVh!6AL;Yr{-Z`2tz)J3-=cW2WhZyR=NcCqR$8#a^=Z5d?<_PO`V{|dp%jO7YLXhKC zRZIOrss6r04E57eePAqKhHdq_bA|OEAx`HWgg;T#9&?5DZg}|ELW&`G(PF87GsJeL zu>Q1E|J@;X(f3ll3Xdo4B0;^yJYoHqL++xn^F%Z8HyG^-Lo?kg)kitxE_y?%-|G-V z-Ftm-0$TNDOfZX0-@WjC&h=>3`7L^6^R5H==QZZH*mwN;;6^`QKsmJ_80)JynSa4d zz}|pOBrFG9LQzYg@UJ6=QCCRw&jaFNocKdXSbrRm2}cbBGb`~I&Mi4gOO^x^+z%b4 z2XOR#f5|X5&~jM!ulm_AK6259CBYb9`M(Y0v=rz4Y8Yv5DV};6EhxmkJ%CdsO#IC- z)=2mSV4j5M0I^yK%kEac(}|_Xw1YhQvVJ#=dUR?jid1Mp_dt^!4pF>d-80ODb4_Y7 zsGBAA-`{E1G8CZu6~m~Kww?lfl~R@mYa#L<0qpCdUC?yZrq7oL6W!1I=_<5Ru8VLP_08JF z!jkpJ4bVT*1)p3iP`>8@UzKo0eU}j};8FrqQHEtF>(6Cm8P9+lZT9dW&efmGNHv0u zT*hEi5Hva|3gb|FV>~$CqQ!qf<5~&uzYF-WXcvCqR{jNz)TJ8P!T1W~jW(%qsYYpx z%Xr`7RKT&(4n}^g%Q$CcsB`U&Ch;y~w#DI*u=(dg_}`VV)MZSwN~n99Vf>!tG7#|M zFNl>%^~bhCO$#g`Fg821+9)k3wK5)eSl9dGHO3J~Ix87hk@2b{os;`SPiMx0(BOn${!PLw zdP3W#$k5ZQ#`ZE2z}a2LPRRK!O#z9kxcCc;NTc)LB<%4w8IJv%bS2JocKO+xg@2Q9 znKPm3vg`u%H|aL~O}b~AVJxnxY7YKQ!gv2B!?S;r?qYa4Remo0Wso&BMWf~}1B(aZ zFT9zO!Knc;oJ$9%E(qaVS8z+?YA`wqFx(Nqz3LgaQn>SYw4DX(r+5dZSmJeH-l3%C@rDTKMAg;S{sQeNKL(B z3b+|!3WoBB8$DC(GX7D6GbJN=uKCxFuKpYD0Jyln3Sgely)(+5yoEdSHMk6e3hoNV z_!CCEj03eLK3&4KBC)%aYfoUG2e=;XS&bW-$O@NnkEya5_+KumehYSOyk)8no#HZP zN%f=CUB)A(%A}bt;}tV$%ULc=wPn%}@KzH?RPoGF$lWcgDE}_pTHIgF)gxp}UjfFQ zu=o>CE=|m}@PFV`fQ56OIjAaAH=IlS8!iK!>Uv0Lc5E2p3@3n0tHJ19;M5d2Jj0#f z+SZWneQ@bDaJA>s%r(JyztL{4%Xk+b|3&i|SAqB8R|P!yMBdt<*Z<6Xm+`ibt}=P^ zjV>caV&7vcT)gE~r1=gQ-{};%#Z4|_zKI_MZf@ekz|kgt7q|%>U5oa=2zVfZ4&NP& zaX)bf9bSu@yFc!58DC5Ki+{L`-fltr+uViOyu`k=wHRxKitiF&JqfScu+H6tQ11l8gdy zpPId@q0!cAJQgKAggmTt2G;B3pUWs3mJ6Kj7@nSFw?vnY$R4vm7itT|MUpDf>3J`vC)q1 zMnvdWOzT-Hlsd zN?8|-9lZ*$zRATI{0o=zk5k?cPE}2u!N0;|b032XnCEfET#ZYP`VQPKS_|{O^|+`G zU>Lo$eEK<@q?u{r4MVGo(DdlN_C-D3u20ce_kvTi(s;`w4z_l~9|X76vgwTZ!lzuu zYQ#l^=S^B4&|R|PS-9Ee z00&Y+=Tzv}4L;n_qYJ>Po|J&W-FByk(GwhgrI$miZPWsstP;Kz_+8JtjE+`yP0_mg z-0rF193Xzh8;WxQinD+1W6FPAZD_Deyl9Y}O{mkvUbiwbE%%J2+=2e+FEVsDY(k;~hS+vbCC01j|njPF=FN z`jd=$32v)rg~vy0aH?$1_$V#C7o555`*90ar_uw)w2muW({MTSb*Q`_)g(iK_McF9TOIj`dAVVu%olZa%B} zBSe*5<<3FzV{rI}?%P;-XQ{KIEGdE@_9EZ)lMh`x*6sxx4iiq1iCG`J{HfP$#0!0K|EXgH@ZUx0hu%B+QBdUFRZH;KZlrO8oSaiYe6 zq_8XJ%iuz0RoD&1O_iG3vZdR4cnD6lD7doFBycLqoZR&C3UJL$$C7Z>)DjxTDv&7@ z+8m5do;`0nPLyXjYKn71$6L~On}Z3XUmM^yJ~usV5*9Gq2f2+dW_yHl-wt&fPncdb zF=lBqyyU2Rhq;YwXwRc!o^W8K8;{UFe+)tLE_Th`L#H+eV?0q6qiNTp!Gxtz6Wqoa z%Z{_Drh)s@;#7Tzfz7C#=r$%VtJo174uC;(Zc?@@t6BfFSuVgko z7P)aR%J%%vFL4{+`f1meV668RH|}sn#gDzsjUNpV5}p&%qg(Ne5}!QiErpW- zP1Q#MTS@8bfNiC%Usk#KAt%>W+3jv4UBYz&x*mfqTlhPmOY(mJj*)Q09UL7;cf!Ep zJKaW_l>3P7Lqzkk0e#%@a{SvTJ8XI_z+vq2y1eht|8-P&~ zegv2(;eTvtEqpY{lr{%^S1SApm?vS!`>ax=0wzcw`mIC!Nrmlz>m=+-W`rZy0S`#& zo$KA0eMW6V;Xc3&3BLnuCSkq%t$2tByjDtk0j5Ye8PKe<^?+ve-VgYJRG9sM z+n6AIeEUJS@tTmj*FQw7pFq^4Z*d!oq~Z=hv$RVe<3<;u^88k}(N!w^0r;MTC;#a- zx=Bk7w$TX;9KO_TZeu-(76*D&>fQCY+c+!Xl+^q1U5 zBdNXYB?>+X?d1@aNcLZVO$7A2UUnNXUOK!BeLnU$uJ%&nCcs8?kxda`u7qy`ZWGWw z|1~-ftNvxLVHV)S2gi|q%?X~;h(w10>r-eqyghM(ChW#;hCfcwA{>2BzRi8$Mo|9W z0Lxr-em7Q}#-E}SOqZV$5d+#+0T@ZA7|yfd%{IKphMNJ$N!_b}Eojdk|21@5_-;X3vhCG${CvZ6cp>8WzpwPp zr{vLh;G)~uDNOq(UveAwd1=ry2!<=a(voLUC$7sp<>Q=vwE?9Q{#JnX>PpQF51nVt ze2)k1aq(GbE(e?;p#MDJ11<{gLv*h6dAL`x#>;?HCG6n$;8G!^8vxr&_&Q*$gr5U8 zmC%Urzy+b(1Q74pv$5fT?Ic_Zh%W-M^aNmS3Ev0AFGI03s+I>mR=~}GWfJ;pTW~61 zwUmBj!$EaCxDgh~$^fG!TnLDz+vm|NREJhShgz5%%q&UBDWU+R}1JK*p3cA zkMJ5LkG|4&9*o1HsMnjK-FS`W5aMI8b>23RSeyF&-s za1a$x-N9pYlBu$3(A~Ww1rI@SB1H9ssM$2YL*`UR-S4X@PwP~V@gAc0 zAfoqAyy1eR{`~9EKyD%PkLv6(`bP-td$b2vtH|&TK$nDX0tO{K3y86vJqq^ZP!(_i z;5`!7?d3r~719QPrfx65zC!B0s~4R(4DUDew$h~a@$khQRpT$~>oLCaNN4&Du2Ug?9Pn#{PP~AktrnDc-;)t*7wnydQ6X9zmEb!4A&?>I@6+gX3v6t8Aa>F^&t7uX>UP zJJOi#`~jf42UU+xRIT?2AqdRnfpD&0sRyqWrgU*P#4~&BxU29OU(}#lJ;h_-k%IUO zHxn_98}YBXmNU4#f6a9V_o=)wp^*dX25PhYX4TxruA`{7RKPkC=G(9bU_DA=g`&9} z;6k?;aE*jt0XCq|S>dt`>&&yHjRDJ~g=O@n+!mk1Em2mM59xS~Gg?9iWB>WJto`hcl4wf+UMvpOE!j*t^DUI#kvxIwruyD;% z_F70Ymhl)Uq|*VTC0q_Tj6$y<+3DpTqcNR&rB*}Q{W3!K!c89DqWLnYjGH}Jy0fVx zx3cF=50b(k?;iI zSP9!~wiLDkno`%J9=!W2Ec66iBcT61z?MFdhyV9&9-}RuAtOI`i|w@fRn%L{?Obo1 z%D)D1gh#sbk(D)5-t%SF~;K9dZh4f#5ewprDz+36#X0#&VD!|63#$zWu#*0#8^4mNE5z1A7O{DT_z*==>3D=$Fi4top_57d5_`@8@ ztaVSEbDzBm&g{F|9$Lx$7hIK@ptG5t53D~c&TDitW#QZ&aKp@H8*t8t@7^RYHX_Ks z@Pq`eaShy4;GU_0t8C&mj+qOF;Wj(8#`0-O4G9Og_FB(=!xNT*Q;W&r+`_-%?gE#m z=ck_VaJ3!(n}nZ$QxBoSGrR<@J?(i5t=XiF*V---uGR}&l9_iG^T-Fzy7X_--2v`) zQ$O5hbX$j8&em)LQau3)PxunJTAVZf!nrrvd97!R;oMj4y~atI?0?cddo5a1P0zv; zetE6edMqE#T?D6=!K>b;SD&I%#5-rGryTyWtsb2Uk-e zJ_M(p&4;J^0i2lca6aMWk08~2C7i39>NW1Ip(!3o^BU7k$HUXrN%vaMkWEgOpKYxN zSyP73f>RI3!;QWKuCRs-y%{xk)|TMjR-;L{(O*DD)KJ1dGHWhjMV8kXSc5Z9fr}2e z$>nF+@$8z1hfl!ORKlh?USnAe89o9|ZI=iy;2Cfnh@$?($$GgpC+rTcRSg+V1y@tB z-3ab4#y`17?;em3*I+a?ujc5U2=2KW(#7R_4J^%yzwiP++R1AS5)8^8PF@7LuLh&r zI(w~+VBzWB1(#Vvx`+a=fm=uM=Sau(pH=9!o}4&Ha8=+Yna|h5xs!dp#t+iw{}ke2 zKd-g5DLmb`;M4=Ef#Kwi{$4{pjtS@92A5PrhChIdA=lfO%D4yMk|JSS8x94;$^t9g z4cJk_qkt6>wi@WgG)pLqvEiM7O{DY*TlxuLij@8ruvEg5L0%(O!n*+j5B+X?8O1Ngj)uAaeMxWiB{ zR=DfssS{^Aws{98wQjc+~D#$98*xJzLh{!ai4rD=cD@m|AgX48Cv z7gI-(O}-6>*sv0?iL`Mm;QRz>`p*Sk{20oR_feKU3%M);js_en;nRTS62>n=u_QbV zm@MHhfQKa9v)F6wm9X>%%h+5S-U5hi3&_pi;6|@e-%T^$M;$f8Wf%Kl*oi{GdbIpQ zz=43ZBpd;_Qo@e`YfJc*4Sxc}yM1S2IDZ)~@Lt;RAq>~K#fueAVXZgdL;?L<0WaY7 zJJwitn-`N|*6<$y{N5Blwh9+*nb31PN2kz82VCrt33uM60Q*Xf4*+kJZum#6!*$2h9=D!rRA|qz z;S#_)GT}%NuZgkVbku;x)EP_#NQw(#YJ6xR%$F{?&Ti zi}e8E_H@8OX5Adv?lm5f2}eKS#WJ|?DSihECSkpuxU$J~DS$_@#?Qt5VlRhi;s2p& ze*?^yFykqHYg0%w0UJwL1eh#g72sq6Q{D$$U|uqNnF9|WSTy(cjkAR&eY`fo5NCTWKrRxF9B)kHcDq;KQc*qhK@&Fr9=yL>Vf51^LTJkw6 z^w9%6#BwU{I#}58%yay2S@YLwtdBcLNquA;Wh8(GUzz1EL`qUI0W* zFsyTk+hjb$wuilVS}CME0W&203=oyg3N2p{mCdj{AS#>TWI$9l!xez2Y=#>F(bf!) z0HU%P{sxH3W>|WJhiL)#0HU&4dJOOwrThz(@{gllyvRuf|3amF`LY*FK0@3HuXXz( zgxFvBCT3!hQf2l3dHJ~tr~Do;(M;+8lt*e7`&t9;lkii(i4qokX2FL67f5OJ=R7!z zWMzP+g~-VeB4!tUQ#@JAccw_ZHd78Wi7=1JK0I}4WD z@F75KsN&qt1DY8({oaB_He7DQy?}TW#>sxOVb>qHKM3g-Kr`cy0kP|eb?g4f@hM;{ zz*t$i1?Mpxk=u zsGP$S$H*Q&!-E+Ku&+T+A8$%!?Upvo1?(iHa{=2)_=v5r7cfFfp94&xsITGNS-_T< z8L{F2_VpRJNR6BO`7m1$d8`5KAmL%aMiRaQm?+_ofM(8Z`umKVh19R=x_ zsw^L1QwseA=l`%_LXi&>KOwyV@Iwhl4B?zv>c0u_TRb%U32sgw#@2-La=>e8`~_Is z1sE^ktAG&_p0K4~+tTy4G-5b6h_H|X*hD~o7r>`nG~oiWyEKAJy7nU0a010X{Hm4w z8|>KMnPgOe3!0bE!C_lE=Z^GQZyXJFZ0QV5*$7VE=M6T>%S`j)()%hnbMGU+Gfxj* z#HOQ z2}Kbmg1gn?oJIH&oZ8QdeOZnYd^yf%JSsBif=TXppS7GZ#LzSFM7;-2?Q{#T+l~`_ z7~W6~*o{3Kc(&z;bNAX8;3l(Ptgr7xALg}bzaX540jf>cLv8O+tTTN>tY%sp>Iiki znC3|5e0^adxH(oj+o%g$@P7d3F}ui6qqKoqzCwoI9s6mL4^Oe!uauOK&$=~s`i1Y7 zf_qM?{Rw!tl~s53JW^P@tHg&HoUry7U;|6dY6GYl#y)UStQO}5YAh0rJ_o1*Z?MmPr9P{?!@^p-1vpG#e-ZK84kv28e3&sqbKDcv+rc?|QmKQR zVYf}<>NAX=lv>QvsJdmkx4OAAeOo!W9-2q(hIe;x z&M2Aa;H+9hNd|UX?BHnoFTr|a&-5jSRL?2Nc*?;!b9&ps={e0S`<^*bXG^+Gzg zg*JC^&I;(_;B>dz4Ik^^oNmo`aK=*0s>`UJb&rEA(`xlh-zOcMo?(*l1~_%O7#4O3 z`pl6|uZQYcSIV2}rFRY;aTThPe3>>Zvf*?auC(D68y>OYM>f1{!$y;>EK+Saz=oB8 zc-8J#3}3ebc9ifLz}6Ce42YNPSmED*M++V~S;LJ0P|aacf*^A^jMz4i)|f3SUq2VcVa8^=IIx7HI8dNE-mUBy4C)qit!7Ese9K@wPP4lDZqu zpw*Xgv(X$P+}FUqJJ%F-u|>m8(O665uLAVrYe1JVUAca?j~_9zb4vj+g=e_VmOf%j zpS7hg*wQn$^ix~^H%$?I3fIdxmvpX21N0aJqH*|oBqI<3WVP*<8t(yBlU*N z;hC;*X*8f|a57+LA*HT=;>&nzE(ha$Pe2$aRbK)$3vw3FwAp5^w3#|r*>vZcqAn0M zC)aPmIF~7z0!b_B%NkQew&<`adPSrY9)Dwseu46c$`n&nWsB}HMGruP{RSMGhfUEdw&+_^bO9pMd~mUJB6_jaTRQ-n z(U#f zk5g^MYCzM+Wq_uSJ50r=Y{lno#n%AMHger4E!MhGW$mvII0V}>c)$!T;US#I3Lns~ zO{H|y2EH#8l~KJxre6q=tPJ;ZQ?$|&`PKlYiv+$G0fTh$3dY@&fcTWdRltt`0}_4< zSSjIqVbni; z#>Wz#2Xxawwr~OPSK0*V|7sfwhmQ}`kBssEyxnJHx&-#M+Tr7kWUM_3@LQ=}xYK96 zXKKVe$v64JNDsi3QtW?oH%5O`<=h^=9ttDB0XCV3-6tqT|_r3tn)1u#ZP{W*Z$v8o@1x?l7xx1`8pC15NC8X)IK0F&qx!-Iek621hu zU&6)vEa?is0x3OWOJ4=VE_$|b#+H5z7$c(en_my0CJy(ST|`ILVq9 z%KPj?;HnYRjUr=~c6`CUdn*ak%LAwG`og*1f0J&=-=v!ePTlpvrg+#bvgMnscR;#L zC&Dv44NmRu4Cnku(AG7iYXeU0dP5J4 zZaFyh)e^x`C^|CHy#wE=jE-D(T_2+_eu1FBF#xytgYW@{q5Pvt__XFoV-!}C#u(%9 zW8o8xNk+&hF-pGi!|51-oJ*CsZy zp^Li4MJ}L&agnWSpKoRuPt-Lq$@wuZG9#i%f?+(3H(rij9!rDTyCV0kijNF5qyMHx zMo@XD$T2i4KC1tHI>PioyW?ovTR-dWvK&B%77PYS~{*Oww?c>5POjsTN6pW@Ry* zhNWOcPt{8sbXrFB5J7Loh(Xvx5m*sHPxY8IdX&NlgQ9+4(!=Gq`|W<``*+6Jw{y>B z3_O!dWg^?559(ju4Y+&&j*@hp1Z(N?)Vk;yTR!%Zx4IGiV0oA>R!Pu{SPt`6(ffgx zmYJq{oCb?7z8WN4Eo+hqqs@|AK_Q=P#TH=0Za7srznN(-zmIg4S5N-@eT^;LLA#6d z_lz5bp{1hh<4%g9Efqp=$S=|a&vC(F_?iFZb>YcJ-mih(#JB}MuU0MgJV3qRhc^BQUsA-n)peY;D_cgW(=kNP@Rbgx zOk;a9)MvMm8L7fl40bRiZp$a?xDzfZ&}~fE%NhOS?g>MUt;dVqh>Ex*3}fWvGJznc~SER?9TNG|_azI?lJjNFlightMode Thr Cruise + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/m3u/networklink.kml b/Tools/ArdupilotMegaPlanner/bin/Release/m3u/networklink.kml index 0f28d211d2..7504af4016 100644 --- a/Tools/ArdupilotMegaPlanner/bin/Release/m3u/networklink.kml +++ b/Tools/ArdupilotMegaPlanner/bin/Release/m3u/networklink.kml @@ -11,8 +11,8 @@ http://127.0.0.1:56781/network.kml onInterval - 1 - 1 + 0.3 + 0.3 diff --git a/Tools/ArdupilotMegaPlanner/dataflashlog.xml b/Tools/ArdupilotMegaPlanner/dataflashlog.xml index 3964602e0a..973da2116f 100644 --- a/Tools/ArdupilotMegaPlanner/dataflashlog.xml +++ b/Tools/ArdupilotMegaPlanner/dataflashlog.xml @@ -93,6 +93,190 @@ FlightMode Thr Cruise + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + + + Err + P + I + D + Output + Gain + diff --git a/Tools/ArdupilotMegaPlanner/georefimage.cs b/Tools/ArdupilotMegaPlanner/georefimage.cs index a6dc599094..39f0039bdf 100644 --- a/Tools/ArdupilotMegaPlanner/georefimage.cs +++ b/Tools/ArdupilotMegaPlanner/georefimage.cs @@ -26,7 +26,7 @@ namespace ArdupilotMega private TextBox TXT_outputlog; private MyButton BUT_estoffset; - int latpos = 5, lngpos = 4, altpos = 7; + int latpos = 4, lngpos = 5, altpos = 7; internal Georefimage() { InitializeComponent(); @@ -247,17 +247,25 @@ namespace ArdupilotMega matchs++; + SharpKml.Dom.Timestamp tstamp = new SharpKml.Dom.Timestamp(); + + tstamp.When = dt; + kml.AddFeature( new Placemark() { + Time = tstamp , Name = Path.GetFileNameWithoutExtension(file), Geometry = new SharpKml.Dom.Point() { Coordinate = new Vector(double.Parse(arr[lngpos]), double.Parse(arr[latpos]), double.Parse(arr[altpos])) } + } ); + + sw2.WriteLine(Path.GetFileNameWithoutExtension(file) + " " + arr[lngpos] + " " + arr[latpos] + " " + arr[altpos]); sw.WriteLine(Path.GetFileNameWithoutExtension(file) + "\t" + crap.ToString("yyyy:MM:dd HH:mm:ss") + "\t" + arr[lngpos] + "\t" + arr[latpos] + "\t" + arr[altpos]); sw.Flush(); @@ -345,7 +353,7 @@ namespace ArdupilotMega this.TXT_offsetseconds.Name = "TXT_offsetseconds"; this.TXT_offsetseconds.Size = new System.Drawing.Size(100, 20); this.TXT_offsetseconds.TabIndex = 4; - this.TXT_offsetseconds.Text = "0"; + this.TXT_offsetseconds.Text = "-86158"; // // BUT_doit // @@ -389,7 +397,7 @@ namespace ArdupilotMega this.BUT_estoffset.UseVisualStyleBackColor = true; this.BUT_estoffset.Click += new System.EventHandler(this.BUT_estoffset_Click); // - // georefimage + // Georefimage // this.ClientSize = new System.Drawing.Size(453, 299); this.Controls.Add(this.BUT_estoffset); diff --git a/Tools/ArdupilotMegaPlanner/m3u/networklink.kml b/Tools/ArdupilotMegaPlanner/m3u/networklink.kml index 0f28d211d2..7504af4016 100644 --- a/Tools/ArdupilotMegaPlanner/m3u/networklink.kml +++ b/Tools/ArdupilotMegaPlanner/m3u/networklink.kml @@ -11,8 +11,8 @@ http://127.0.0.1:56781/network.kml onInterval - 1 - 1 + 0.3 + 0.3 From a72d4b46b3d9ca3ef583cdeee7f71c2a9146f67b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 27 Mar 2012 15:16:00 +1100 Subject: [PATCH 19/78] Compass: implement Bills new offset nulling algorithm this seems to work much better than the old algorithm, converging faster and more accurately. Even better, it has no linkage to DCM, so no possibility of nasty feedback effects --- libraries/AP_Compass/Compass.cpp | 66 ++++++++++++++++++++++---------- libraries/AP_Compass/Compass.h | 9 ++--- 2 files changed, 48 insertions(+), 27 deletions(-) diff --git a/libraries/AP_Compass/Compass.cpp b/libraries/AP_Compass/Compass.cpp index ad84d9d03a..eb6fa7441b 100644 --- a/libraries/AP_Compass/Compass.cpp +++ b/libraries/AP_Compass/Compass.cpp @@ -182,38 +182,62 @@ Compass::calculate(const Matrix3f &dcm_matrix) #endif } + +/* + this offset nulling algorithm is based on a paper from + Bill Premerlani + + http://gentlenav.googlecode.com/files/MagnetometerOffsetNullingRevisited.pdf + */ void -Compass::null_offsets(const Matrix3f &dcm_matrix) +Compass::null_offsets(void) { if (_null_enable == false || _learn == 0) { // auto-calibration is disabled return; } - // Update our estimate of the offsets in the magnetometer - Vector3f calc; - Matrix3f dcm_new_from_last; - float weight; - Vector3f mag_body_new = Vector3f(mag_x,mag_y,mag_z); - - if(_null_init_done) { - dcm_new_from_last = dcm_matrix.transposed() * _last_dcm_matrix; // Note 11/20/2010: transpose() is not working, transposed() is. - weight = 3.0 - fabs(dcm_new_from_last.a.x) - fabs(dcm_new_from_last.b.y) - fabs(dcm_new_from_last.c.z); - if (weight > .001) { - calc = mag_body_new + _mag_body_last; // Eq 11 from Bill P's paper - calc -= dcm_new_from_last * _mag_body_last; - calc -= dcm_new_from_last.transposed() * mag_body_new; - if(weight > 0.5) weight = 0.5; - calc = calc * (weight); - _offset.set(_offset.get() - calc); - } - } else { + // this gain is set so we converge on the offsets in about 5 + // minutes with a 10Hz compass + const float gain = 0.5; + const float max_change = 2.0; + + if (!_null_init_done) { + // first time through _null_init_done = true; + _mag_body_last = mag_body_new; + return; } - _mag_body_last = mag_body_new - calc; - _last_dcm_matrix = dcm_matrix; + + Vector3f delta, diff; + float diff_length, delta_length; + + diff = mag_body_new - _mag_body_last; + diff_length = diff.length(); + if (diff_length == 0.0) { + // the mag vector hasn't changed - we don't get any + // information from this + return; + } + + // equation 6 of Bills paper + delta = diff * (mag_body_new.length() - _mag_body_last.length()) / diff_length; + + // limit the change from any one reading. This is to prevent + // single crazy readings from throwing off the offsets for a long + // time + delta_length = delta.length(); + if (delta_length > max_change) { + delta *= max_change / delta_length; + } + + // set the new offsets + _offset.set(_offset.get() - (delta * gain)); + + // remember the last mag vector + _mag_body_last = mag_body_new; } diff --git a/libraries/AP_Compass/Compass.h b/libraries/AP_Compass/Compass.h index 770a520d60..9ebc4ffeba 100644 --- a/libraries/AP_Compass/Compass.h +++ b/libraries/AP_Compass/Compass.h @@ -97,11 +97,9 @@ public: /// void set_offsets(int x, int y, int z) { set_offsets(Vector3f(x, y, z)); } - /// Perform automatic offset updates using the results of the DCM matrix. + /// Perform automatic offset updates /// - /// @param dcm_matrix The DCM result matrix. - /// - void null_offsets(const Matrix3f &dcm_matrix); + void null_offsets(void); /// Enable/Start automatic offset updates @@ -134,7 +132,6 @@ protected: bool _null_enable; ///< enabled flag for offset nulling bool _null_init_done; ///< first-time-around flag used by offset nulling - Matrix3f _last_dcm_matrix; ///< previous DCM matrix used by offset nulling - Vector3f _mag_body_last; ///< ?? used by offset nulling + Vector3f _mag_body_last; ///< used by offset correction }; #endif From e956e21e7ddac094826f402fa81f8c1d56790fb5 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 27 Mar 2012 15:16:27 +1100 Subject: [PATCH 20/78] ACM: enable the new compass offset nulling in ACM --- ArduCopter/ArduCopter.pde | 2 +- ArduCopter/test.pde | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 06562cdc49..936823a67d 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -982,7 +982,7 @@ static void medium_loop() // Calculate heading Matrix3f m = ahrs.get_dcm_matrix(); compass.calculate(m); - compass.null_offsets(m); + compass.null_offsets(); } } #endif diff --git a/ArduCopter/test.pde b/ArduCopter/test.pde index 2ea0a9318c..714d102839 100644 --- a/ArduCopter/test.pde +++ b/ArduCopter/test.pde @@ -332,7 +332,7 @@ test_radio(uint8_t argc, const Menu::arg *argv) Matrix3f m = dcm.get_dcm_matrix(); compass.read(); // Read magnetometer compass.calculate(m); - compass.null_offsets(m); + compass.null_offsets(); medium_loopCounter = 0; } } @@ -551,7 +551,7 @@ test_imu(uint8_t argc, const Menu::arg *argv) compass.read(); // Read magnetometer Matrix3f m = dcm.get_dcm_matrix(); compass.calculate(m); - compass.null_offsets(m); + compass.null_offsets(); } } fast_loopTimer = millis(); From 989304fb47bc833c49e9eb81e5899b5d2f74f95f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 27 Mar 2012 15:16:41 +1100 Subject: [PATCH 21/78] APM: enable the new offset nulling in APM --- ArduPlane/ArduPlane.pde | 2 +- ArduPlane/test.pde | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde index 676a8720bc..3fa4751119 100644 --- a/ArduPlane/ArduPlane.pde +++ b/ArduPlane/ArduPlane.pde @@ -784,7 +784,7 @@ static void medium_loop() // Calculate heading Matrix3f m = ahrs.get_dcm_matrix(); compass.calculate(m); - compass.null_offsets(m); + compass.null_offsets(); } else { ahrs.set_compass(NULL); } diff --git a/ArduPlane/test.pde b/ArduPlane/test.pde index ec988bbdd3..b0e1c27462 100644 --- a/ArduPlane/test.pde +++ b/ArduPlane/test.pde @@ -603,7 +603,7 @@ test_mag(uint8_t argc, const Menu::arg *argv) // Calculate heading Matrix3f m = ahrs.get_dcm_matrix(); compass.calculate(m); - compass.null_offsets(m); + compass.null_offsets(); } medium_loopCounter = 0; } From 9b95d2060a8690253857ad2c3d5aabe3625ff645 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 27 Mar 2012 15:17:28 +1100 Subject: [PATCH 22/78] ADC: minor fix to the ADC Ch6() code we don't need to add count any more, as floating point maths doesn't need to round up --- libraries/AP_ADC/AP_ADC_ADS7844.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_ADC/AP_ADC_ADS7844.cpp b/libraries/AP_ADC/AP_ADC_ADS7844.cpp index 29a694ae08..7a925e6351 100644 --- a/libraries/AP_ADC/AP_ADC_ADS7844.cpp +++ b/libraries/AP_ADC/AP_ADC_ADS7844.cpp @@ -228,7 +228,7 @@ uint32_t AP_ADC_ADS7844::Ch6(const uint8_t *channel_numbers, float *result) // division. That costs us 36 bytes of stack, but I think its // worth it. for (i = 0; i < 6; i++) { - result[i] = (sum[i] + count[i]) / (float)count[i]; + result[i] = sum[i] / (float)count[i]; } // return number of microseconds since last call From 47f9dfd1256e27f1d6f12e2bbcaf3ec55984b94f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 27 Mar 2012 15:33:21 +1100 Subject: [PATCH 23/78] ACM: fixed the build on the 1280 --- ArduCopter/Attitude.pde | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde index 8ca346f8bd..9e97226647 100644 --- a/ArduCopter/Attitude.pde +++ b/ArduCopter/Attitude.pde @@ -89,6 +89,7 @@ get_stabilize_yaw(int32_t target_angle) output = get_rate_yaw(target_rate) + i_term; #endif +#if LOGGING_ENABLED == ENABLED // log output if PID logging is on and we are tuning the yaw if( g.log_bitmask & MASK_LOG_PID && (g.radio_tuning == CH6_YAW_KP || g.radio_tuning == CH6_YAW_RATE_KP) ) { log_counter++; @@ -97,6 +98,7 @@ get_stabilize_yaw(int32_t target_angle) Log_Write_PID(CH6_YAW_KP, angle_error, target_rate, i_term, 0, output, g.pi_stabilize_yaw.kP()); } } +#endif // ensure output does not go beyond barries of what an int16_t can hold return constrain(output,-32000,32000); @@ -210,6 +212,7 @@ get_rate_yaw(int32_t target_rate) // constrain output output = constrain(output, -yaw_limit, yaw_limit); +#if LOGGING_ENABLED == ENABLED // log output if PID loggins is on and we are tuning the yaw if( g.log_bitmask & MASK_LOG_PID && (g.radio_tuning == CH6_YAW_KP || g.radio_tuning == CH6_YAW_RATE_KP) ) { log_counter++; @@ -218,6 +221,7 @@ get_rate_yaw(int32_t target_rate) Log_Write_PID(CH6_YAW_RATE_KP, rate_error, p, i, d, output, g.pid_rate_yaw.kP()); } } +#endif // constrain output return output; From e0c9ab5a291ca6d7f645cdca05984123a14d0097 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 27 Mar 2012 15:36:58 +1100 Subject: [PATCH 24/78] ACM: fixed heli build --- ArduCopter/Attitude.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde index 9e97226647..7ab489e91e 100644 --- a/ArduCopter/Attitude.pde +++ b/ArduCopter/Attitude.pde @@ -81,7 +81,7 @@ get_stabilize_yaw(int32_t target_angle) // do not use rate controllers for helicotpers with external gyros #if FRAME_CONFIG == HELI_FRAME if(!g.heli_ext_gyro_enabled){ - output = get_rate_yaw(target_rate) + iterm; + output = get_rate_yaw(target_rate) + i_term; }else{ output = constrain((target_rate + i_term), -4500, 4500); } From 34506b170f4d2dee9f530afb8019949c3c88d411 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 27 Mar 2012 15:37:14 +1100 Subject: [PATCH 25/78] Mavlink: fixed warnings about limits on int32 values --- ArduCopter/GCS_Mavlink.pde | 2 +- ArduPlane/GCS_Mavlink.pde | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index d97f89adc1..8cb0957367 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -1471,7 +1471,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) #endif if (packet.param_value < 0) rounding_addition = -rounding_addition; float v = packet.param_value+rounding_addition; - v = constrain(v, -2147483648, 2147483647); + v = constrain(v, -2147483648.0, 2147483647.0); ((AP_Int32 *)vp)->set_and_save(v); } else if (var_type == AP_PARAM_INT16) { #if LOGGING_ENABLED == ENABLED diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index dd80bae476..60056b6fcc 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -1792,7 +1792,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) } else if (var_type == AP_PARAM_INT32) { if (packet.param_value < 0) rounding_addition = -rounding_addition; float v = packet.param_value+rounding_addition; - v = constrain(v, -2147483648, 2147483647); + v = constrain(v, -2147483648.0, 2147483647.0); ((AP_Int32 *)vp)->set_and_save(v); } else if (var_type == AP_PARAM_INT16) { if (packet.param_value < 0) rounding_addition = -rounding_addition; From 1c934dc7efc9240346e63ba261bff0ea8fc11aa6 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 27 Mar 2012 16:00:00 +1100 Subject: [PATCH 26/78] APM: increase ArduPlane version to 2.31 --- ArduPlane/ArduPlane.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde index 3fa4751119..77ce236731 100644 --- a/ArduPlane/ArduPlane.pde +++ b/ArduPlane/ArduPlane.pde @@ -1,6 +1,6 @@ /// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- -#define THISFIRMWARE "ArduPlane V2.30" +#define THISFIRMWARE "ArduPlane V2.31" /* Authors: Doug Weibel, Jose Julio, Jordi Munoz, Jason Short, Andrew Tridgell, Randy Mackay, Pat Hickey, John Arne Birkeland, Olivier Adler Thanks to: Chris Anderson, Michael Oborne, Paul Mather, Bill Premerlani, James Cohen, JB from rotorFX, Automatik, Fefenin, Peter Meister, Remzibi, Yury Smirnov, Sandro Benigno, Max Levine, Roberto Navoni, Lorenz Meier From 8a645ffb566b75c0b44bc9f8a7d2711b4e265573 Mon Sep 17 00:00:00 2001 From: Michael Oborne Date: Tue, 27 Mar 2012 13:16:48 +0800 Subject: [PATCH 27/78] firmware build --- Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml b/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml index a08bdee480..3ba0affdfc 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml +++ b/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml @@ -4,7 +4,7 @@ http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-1280.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-2560.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-2560-2.hex - ArduPlane V2.30 + ArduPlane V2.31 12 @@ -12,7 +12,7 @@ http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/APHIL-1280.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/APHIL-2560.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/APHIL-2560-2.hex - ArduPlane V2.30 HIL + ArduPlane V2.31 HIL #define FLIGHT_MODE_CHANNEL 8 #define FLIGHT_MODE_1 AUTO From b2d6db94797e8da2517c6ae3252e257e719fdb9f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 28 Mar 2012 20:46:11 +1100 Subject: [PATCH 28/78] Compass: implement noise resistant varient of offset learning This adds a large amount of noise robustness to the compass offset learning algorithm, at a cost of 120 bytes of memory. The changes are based on a long discussion with Bill Premerlani. --- libraries/AP_Compass/Compass.cpp | 78 +++++++++++++++++++++++--------- libraries/AP_Compass/Compass.h | 6 ++- 2 files changed, 61 insertions(+), 23 deletions(-) diff --git a/libraries/AP_Compass/Compass.cpp b/libraries/AP_Compass/Compass.cpp index eb6fa7441b..4f485b2705 100644 --- a/libraries/AP_Compass/Compass.cpp +++ b/libraries/AP_Compass/Compass.cpp @@ -184,10 +184,24 @@ Compass::calculate(const Matrix3f &dcm_matrix) /* - this offset nulling algorithm is based on a paper from - Bill Premerlani + this offset nulling algorithm is inspired by this paper from Bill Premerlani http://gentlenav.googlecode.com/files/MagnetometerOffsetNullingRevisited.pdf + + The base algorithm works well, but is quite sensitive to + noise. After long discussions with Bill, the following changes were + made: + + 1) we keep a history buffer that effectively divides the mag + vectors into a set of N streams. The algorithm is run on the + streams separately + + 2) within each stream we only calculate a change when the mag + vector has changed by a significant amount. + + This gives us the property that we learn quickly if there is no + noise, but still learn correctly (and slowly) in the face of lots of + noise. */ void Compass::null_offsets(void) @@ -197,47 +211,67 @@ Compass::null_offsets(void) return; } - Vector3f mag_body_new = Vector3f(mag_x,mag_y,mag_z); - // this gain is set so we converge on the offsets in about 5 // minutes with a 10Hz compass - const float gain = 0.5; - const float max_change = 2.0; + const float gain = 0.01; + const float max_change = 10.0; + const float min_diff = 50.0; + Vector3f ofs; + + ofs = _offset.get(); if (!_null_init_done) { // first time through _null_init_done = true; - _mag_body_last = mag_body_new; + for (uint8_t i=0; i<_mag_history_size; i++) { + // fill the history buffer with the current mag vector, + // with the offset removed + _mag_history[i] = Vector3i((mag_x+0.5) - ofs.x, (mag_y+0.5) - ofs.y, (mag_z+0.5) - ofs.z); + } + _mag_history_index = 0; return; } - Vector3f delta, diff; - float diff_length, delta_length; + Vector3f b1, b2, diff; + float length; - diff = mag_body_new - _mag_body_last; - diff_length = diff.length(); - if (diff_length == 0.0) { - // the mag vector hasn't changed - we don't get any - // information from this + // get a past element + b1 = Vector3f(_mag_history[_mag_history_index].x, + _mag_history[_mag_history_index].y, + _mag_history[_mag_history_index].z); + // the history buffer doesn't have the offsets + b1 += ofs; + + // get the current vector + b2 = Vector3f(mag_x, mag_y, mag_z); + + // calculate the delta for this sample + diff = b2 - b1; + length = diff.length(); + if (length < min_diff) { + // the mag vector hasn't changed enough - we don't get + // enough information from this vector to use it + _mag_history_index = (_mag_history_index + 1) % _mag_history_size; return; } + // put the vector in the history + _mag_history[_mag_history_index] = Vector3i((mag_x+0.5) - ofs.x, (mag_y+0.5) - ofs.y, (mag_z+0.5) - ofs.z); + _mag_history_index = (_mag_history_index + 1) % _mag_history_size; + // equation 6 of Bills paper - delta = diff * (mag_body_new.length() - _mag_body_last.length()) / diff_length; + diff = diff * (gain * (b2.length() - b1.length()) / length); // limit the change from any one reading. This is to prevent // single crazy readings from throwing off the offsets for a long // time - delta_length = delta.length(); - if (delta_length > max_change) { - delta *= max_change / delta_length; + length = diff.length(); + if (length > max_change) { + diff *= max_change / length; } // set the new offsets - _offset.set(_offset.get() - (delta * gain)); - - // remember the last mag vector - _mag_body_last = mag_body_new; + _offset.set(_offset.get() - diff); } diff --git a/libraries/AP_Compass/Compass.h b/libraries/AP_Compass/Compass.h index 9ebc4ffeba..6fc9a937e9 100644 --- a/libraries/AP_Compass/Compass.h +++ b/libraries/AP_Compass/Compass.h @@ -132,6 +132,10 @@ protected: bool _null_enable; ///< enabled flag for offset nulling bool _null_init_done; ///< first-time-around flag used by offset nulling - Vector3f _mag_body_last; ///< used by offset correction + + ///< used by offset correction + static const uint8_t _mag_history_size = 20; + uint8_t _mag_history_index; + Vector3i _mag_history[_mag_history_size]; }; #endif From f4c1b6a3c607336d208b412abb3e7774e71d6876 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 28 Mar 2012 20:46:49 +1100 Subject: [PATCH 29/78] SITL: ensure we don't run the sitl timer twice this caused problems with random() --- libraries/Desktop/support/sitl.cpp | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/libraries/Desktop/support/sitl.cpp b/libraries/Desktop/support/sitl.cpp index 205522898d..9ee53f4440 100644 --- a/libraries/Desktop/support/sitl.cpp +++ b/libraries/Desktop/support/sitl.cpp @@ -223,7 +223,12 @@ static void sitl_simulator_output(void) static void timer_handler(int signum) { static uint32_t last_update_count; + static bool running; + if (running) { + return; + } + running = true; cli(); #ifndef __CYGWIN__ @@ -261,11 +266,13 @@ static void timer_handler(int signum) if (update_count == 0) { sitl_update_gps(0, 0, 0, 0, 0, false); sei(); + running = false; return; } if (update_count == last_update_count) { sei(); + running = false; return; } last_update_count = update_count; @@ -280,6 +287,7 @@ static void timer_handler(int signum) sitl_update_barometer(sim_state.altitude); sitl_update_compass(sim_state.rollDeg, sim_state.pitchDeg, sim_state.heading); sei(); + running = false; } From 10c35e3769db8a32752cc0a2bea62bb60df5d9c7 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 28 Mar 2012 20:47:33 +1100 Subject: [PATCH 30/78] SITL: add magnetic field noise to the simulated compass --- libraries/Desktop/support/sitl_adc.h | 8 +------- libraries/Desktop/support/sitl_compass.cpp | 4 +++- libraries/Desktop/support/util.cpp | 13 +++++++++++++ libraries/Desktop/support/util.h | 7 +++++++ 4 files changed, 24 insertions(+), 8 deletions(-) diff --git a/libraries/Desktop/support/sitl_adc.h b/libraries/Desktop/support/sitl_adc.h index 6a21d6f0f9..348d433ff9 100644 --- a/libraries/Desktop/support/sitl_adc.h +++ b/libraries/Desktop/support/sitl_adc.h @@ -8,6 +8,7 @@ #include #include +#include "util.h" static const float vibration_level = 0.2; static const float drift_speed = 0.2; // degrees/second/minute @@ -18,13 +19,6 @@ static const float noise_offset[8]= { 0, 0, 0, 0, 0, 0, 0 static const float drift_rate[8] = { 1.0, 1.0, 1.0, 0, 0, 0, 0, 0 }; static const float base_noise = 2; -// generate a random float between -1 and 1 -static double rand_float(void) -{ - float ret = ((unsigned)random()) % 2000000; - return (ret - 1.0e6) / 1.0e6; -} - static inline float gyro_drift(uint8_t chan) { if (drift_rate[chan] * drift_speed == 0.0) { diff --git a/libraries/Desktop/support/sitl_compass.cpp b/libraries/Desktop/support/sitl_compass.cpp index 8d1d319a37..39912e8959 100644 --- a/libraries/Desktop/support/sitl_compass.cpp +++ b/libraries/Desktop/support/sitl_compass.cpp @@ -30,6 +30,8 @@ // using an APM1 with 5883L compass #define MAG_FIELD_STRENGTH 818 +#define MAG_NOISE 5 + /* given a magnetic heading, and roll, pitch, yaw values, calculate consistent magnetometer components @@ -53,7 +55,7 @@ static Vector3f heading_to_mag(float roll, float pitch, float yaw) // convert the earth frame magnetic vector to body frame, and // apply the offsets m = R.transposed() * Bearth - Vector3f(MAG_OFS_X, MAG_OFS_Y, MAG_OFS_Z); - return m; + return m + (rand_vec3f() * MAG_NOISE); } diff --git a/libraries/Desktop/support/util.cpp b/libraries/Desktop/support/util.cpp index 7656d36bf1..6a956533e3 100644 --- a/libraries/Desktop/support/util.cpp +++ b/libraries/Desktop/support/util.cpp @@ -13,6 +13,7 @@ #include #include #include +#include #include "desktop.h" #include "util.h" @@ -58,3 +59,15 @@ void convert_body_frame(double rollDeg, double pitchDeg, *q = cos(phi)*thetaDot + sin(phi)*psiDot*cos(theta); *r = cos(phi)*psiDot*cos(theta) - sin(phi)*thetaDot; } + +// generate a random Vector3f of size 1 +Vector3f rand_vec3f(void) +{ + Vector3f v = Vector3f(rand_float(), + rand_float(), + rand_float()); + if (v.length() != 0.0) { + v.normalize(); + } + return v; +} diff --git a/libraries/Desktop/support/util.h b/libraries/Desktop/support/util.h index 7d55f827c6..7778adda14 100644 --- a/libraries/Desktop/support/util.h +++ b/libraries/Desktop/support/util.h @@ -12,3 +12,10 @@ void runInterrupt(uint8_t inum); void convert_body_frame(double rollDeg, double pitchDeg, double rollRate, double pitchRate, double yawRate, double *p, double *q, double *r); + +// generate a random float between -1 and 1 +#define rand_float() (((((unsigned)random()) % 2000000) - 1.0e6) / 1.0e6) + +#ifdef VECTOR3_H +Vector3f rand_vec3f(void); +#endif From 40fcfa294f4305783e7b0ed323986cebdbf0c11c Mon Sep 17 00:00:00 2001 From: Michael Oborne Date: Wed, 28 Mar 2012 20:45:16 +0800 Subject: [PATCH 31/78] APM Planner 1.1.58 add read delay on write for serial add tlog to gpx creation fix issue 583 - georef image with a tlog --- .../CommsSerialInterface.cs | 2 +- Tools/ArdupilotMegaPlanner/CommsTCPSerial.cs | 2 + Tools/ArdupilotMegaPlanner/CommsUdpSerial.cs | 2 + Tools/ArdupilotMegaPlanner/Log.cs | 2 +- Tools/ArdupilotMegaPlanner/MAVLink.cs | 12 + Tools/ArdupilotMegaPlanner/MavlinkLog.cs | 47 +- Tools/ArdupilotMegaPlanner/MavlinkLog.resx | 14 +- .../Properties/AssemblyInfo.cs | 2 +- .../Setup/Setup.Designer.cs | 18 +- Tools/ArdupilotMegaPlanner/Setup/Setup.resx | 2875 ++++------------- .../bin/Release/ArdupilotMegaPlanner.pdb | Bin 1021440 -> 1025536 bytes Tools/ArdupilotMegaPlanner/georefimage.cs | 15 +- 12 files changed, 767 insertions(+), 2224 deletions(-) diff --git a/Tools/ArdupilotMegaPlanner/CommsSerialInterface.cs b/Tools/ArdupilotMegaPlanner/CommsSerialInterface.cs index 1bf03f955b..cd85b92445 100644 --- a/Tools/ArdupilotMegaPlanner/CommsSerialInterface.cs +++ b/Tools/ArdupilotMegaPlanner/CommsSerialInterface.cs @@ -34,7 +34,7 @@ namespace ArdupilotMega int BaudRate { get; set; } //bool BreakState { get; set; } int BytesToRead { get; } - //int BytesToWrite { get; } + int BytesToWrite { get; } //bool CDHolding { get; } //bool CtsHolding { get; } int DataBits { get; set; } diff --git a/Tools/ArdupilotMegaPlanner/CommsTCPSerial.cs b/Tools/ArdupilotMegaPlanner/CommsTCPSerial.cs index 0331169c87..76492e1e8b 100644 --- a/Tools/ArdupilotMegaPlanner/CommsTCPSerial.cs +++ b/Tools/ArdupilotMegaPlanner/CommsTCPSerial.cs @@ -66,6 +66,8 @@ namespace System.IO.Ports get { return client.Available + rbuffer.Length - rbufferread; } } + public int BytesToWrite { get { return 0; } } + public bool IsOpen { get { try { return client.Client.Connected; } catch { return false; } } } public bool DtrEnable diff --git a/Tools/ArdupilotMegaPlanner/CommsUdpSerial.cs b/Tools/ArdupilotMegaPlanner/CommsUdpSerial.cs index 3556c12f67..f5b5feb3e2 100644 --- a/Tools/ArdupilotMegaPlanner/CommsUdpSerial.cs +++ b/Tools/ArdupilotMegaPlanner/CommsUdpSerial.cs @@ -60,6 +60,8 @@ namespace System.IO.Ports get { return client.Available + rbuffer.Length - rbufferread; } } + public int BytesToWrite { get {return 0;} } + public bool IsOpen { get { if (client.Client == null) return false; return client.Client.Connected; } } public bool DtrEnable diff --git a/Tools/ArdupilotMegaPlanner/Log.cs b/Tools/ArdupilotMegaPlanner/Log.cs index e8c7d2b14e..c5b6b1f1a5 100644 --- a/Tools/ArdupilotMegaPlanner/Log.cs +++ b/Tools/ArdupilotMegaPlanner/Log.cs @@ -454,7 +454,7 @@ namespace ArdupilotMega foreach (Data mod in flightdata) { xw.WriteStartElement("trkpt"); - xw.WriteAttributeString("lat",mod.model.Location.latitude.ToString(new System.Globalization.CultureInfo("en-US"))); + xw.WriteAttributeString("lat", mod.model.Location.latitude.ToString(new System.Globalization.CultureInfo("en-US"))); xw.WriteAttributeString("lon", mod.model.Location.longitude.ToString(new System.Globalization.CultureInfo("en-US"))); xw.WriteElementString("ele", mod.model.Location.altitude.ToString(new System.Globalization.CultureInfo("en-US"))); diff --git a/Tools/ArdupilotMegaPlanner/MAVLink.cs b/Tools/ArdupilotMegaPlanner/MAVLink.cs index 5696cf4120..15570796cc 100644 --- a/Tools/ArdupilotMegaPlanner/MAVLink.cs +++ b/Tools/ArdupilotMegaPlanner/MAVLink.cs @@ -1954,6 +1954,18 @@ namespace ArdupilotMega DateTime start = DateTime.Now; + try + { + // test fabs idea - http://diydrones.com/profiles/blogs/flying-with-joystick?commentId=705844%3AComment%3A818712&xg_source=msg_com_blogpost + if (BaseStream.IsOpen && BaseStream.BytesToWrite > 0) + { + // slow down execution. + Thread.Sleep(1); + return new byte[0]; + } + } + catch (Exception ex) { log.Info(ex.ToString()); } + lock (readlock) { diff --git a/Tools/ArdupilotMegaPlanner/MavlinkLog.cs b/Tools/ArdupilotMegaPlanner/MavlinkLog.cs index b38d69a432..14543ae9fd 100644 --- a/Tools/ArdupilotMegaPlanner/MavlinkLog.cs +++ b/Tools/ArdupilotMegaPlanner/MavlinkLog.cs @@ -334,7 +334,6 @@ namespace ArdupilotMega zipStream.IsStreamOwner = true; // Makes the Close also Close the underlying stream zipStream.Close(); - flightdata.Clear(); } static void AddNamespace(Element element, string prefix, string uri) @@ -383,7 +382,7 @@ namespace ArdupilotMega CurrentState cs = new CurrentState(); - float oldlatlngalt = 0; + float oldlatlngsum = 0; int appui = 0; @@ -414,15 +413,15 @@ namespace ArdupilotMega } catch { } // ignore because of this Exception System.PlatformNotSupportedException: No voice installed on the system or none available with the current security setting. - if ((float)(cs.lat + cs.lng) != oldlatlngalt + if ((float)(cs.lat + cs.lng) != oldlatlngsum && cs.lat != 0 && cs.lng != 0) { - Console.WriteLine(cs.lat + " " + cs.lng + " " + cs.alt + " lah " + (float)(cs.lat + cs.lng) + "!=" + oldlatlngalt); + Console.WriteLine(cs.lat + " " + cs.lng + " " + cs.alt + " lah " + (float)(cs.lat + cs.lng) + "!=" + oldlatlngsum); CurrentState cs2 = (CurrentState)cs.Clone(); flightdata.Add(cs2); - oldlatlngalt = (cs.lat + cs.lng); + oldlatlngsum = (cs.lat + cs.lng); } } @@ -432,14 +431,52 @@ namespace ArdupilotMega Application.DoEvents(); + writeGPX(logfile); writeKML(logfile + ".kml"); + flightdata.Clear(); + progressBar1.Value = 100; } } } + private void writeGPX(string filename) + { + System.Xml.XmlTextWriter xw = new System.Xml.XmlTextWriter(Path.GetDirectoryName(filename) + Path.DirectorySeparatorChar + Path.GetFileNameWithoutExtension(filename) + ".gpx", Encoding.ASCII); + + xw.WriteStartElement("gpx"); + + xw.WriteStartElement("trk"); + + xw.WriteStartElement("trkseg"); + + foreach (CurrentState cs in flightdata) + { + xw.WriteStartElement("trkpt"); + xw.WriteAttributeString("lat", cs.lat.ToString(new System.Globalization.CultureInfo("en-US"))); + xw.WriteAttributeString("lon", cs.lng.ToString(new System.Globalization.CultureInfo("en-US"))); + + xw.WriteElementString("ele", cs.alt.ToString(new System.Globalization.CultureInfo("en-US"))); + xw.WriteElementString("time", cs.datetime.ToString("yyyy-MM-ddTHH:mm:sszzzzzz")); + xw.WriteElementString("course", (cs.yaw).ToString(new System.Globalization.CultureInfo("en-US"))); + + xw.WriteElementString("roll", cs.roll.ToString(new System.Globalization.CultureInfo("en-US"))); + xw.WriteElementString("pitch", cs.pitch.ToString(new System.Globalization.CultureInfo("en-US"))); + //xw.WriteElementString("speed", mod.model.Orientation.); + //xw.WriteElementString("fix", cs.altitude); + + xw.WriteEndElement(); + } + + xw.WriteEndElement(); + xw.WriteEndElement(); + xw.WriteEndElement(); + + xw.Close(); + } + public static Color HexStringToColor(string hexColor) { string hc = (hexColor); diff --git a/Tools/ArdupilotMegaPlanner/MavlinkLog.resx b/Tools/ArdupilotMegaPlanner/MavlinkLog.resx index 58503a2863..9406a8df5f 100644 --- a/Tools/ArdupilotMegaPlanner/MavlinkLog.resx +++ b/Tools/ArdupilotMegaPlanner/MavlinkLog.resx @@ -123,7 +123,7 @@ - 45, 12 + 143, 12 116, 23 @@ -133,7 +133,7 @@ 8 - Create KML + Create KML + GPX BUT_redokml @@ -154,7 +154,7 @@ 10, 42 - 432, 26 + 622, 26 9 @@ -178,7 +178,7 @@ NoControl - 167, 12 + 265, 12 116, 23 @@ -208,7 +208,7 @@ NoControl - 289, 12 + 387, 12 116, 23 @@ -238,7 +238,7 @@ 10, 74 - 434, 293 + 624, 293 12 @@ -262,7 +262,7 @@ 6, 13 - 456, 379 + 646, 379 diff --git a/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs b/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs index 3e8fce088f..eb9a933587 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.57")] +[assembly: AssemblyFileVersion("1.1.58")] [assembly: NeutralResourcesLanguageAttribute("")] diff --git a/Tools/ArdupilotMegaPlanner/Setup/Setup.Designer.cs b/Tools/ArdupilotMegaPlanner/Setup/Setup.Designer.cs index 41b6ab6aad..d4389f234d 100644 --- a/Tools/ArdupilotMegaPlanner/Setup/Setup.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/Setup/Setup.Designer.cs @@ -82,6 +82,7 @@ this.CMB_fmode1 = new System.Windows.Forms.ComboBox(); this.BUT_SaveModes = new ArdupilotMega.MyButton(); this.tabHardware = new System.Windows.Forms.TabPage(); + this.BUT_MagCalibration = new ArdupilotMega.MyButton(); this.label27 = new System.Windows.Forms.Label(); this.CMB_sonartype = new System.Windows.Forms.ComboBox(); this.CHK_enableoptflow = new System.Windows.Forms.CheckBox(); @@ -179,7 +180,6 @@ this.tabReset = new System.Windows.Forms.TabPage(); this.BUT_reset = new ArdupilotMega.MyButton(); this.toolTip1 = new System.Windows.Forms.ToolTip(this.components); - this.BUT_MagCalibration = new ArdupilotMega.MyButton(); this.tabControl1.SuspendLayout(); this.tabRadioIn.SuspendLayout(); this.groupBoxElevons.SuspendLayout(); @@ -657,7 +657,7 @@ // // tabHardware // - this.tabHardware.BackColor = System.Drawing.SystemColors.Control; + this.tabHardware.BackColor = System.Drawing.Color.Transparent; this.tabHardware.Controls.Add(this.BUT_MagCalibration); this.tabHardware.Controls.Add(this.label27); this.tabHardware.Controls.Add(this.CMB_sonartype); @@ -675,6 +675,13 @@ resources.ApplyResources(this.tabHardware, "tabHardware"); this.tabHardware.Name = "tabHardware"; // + // BUT_MagCalibration + // + resources.ApplyResources(this.BUT_MagCalibration, "BUT_MagCalibration"); + this.BUT_MagCalibration.Name = "BUT_MagCalibration"; + this.BUT_MagCalibration.UseVisualStyleBackColor = true; + this.BUT_MagCalibration.Click += new System.EventHandler(this.BUT_MagCalibration_Click); + // // label27 // resources.ApplyResources(this.label27, "label27"); @@ -1584,13 +1591,6 @@ this.BUT_reset.UseVisualStyleBackColor = true; this.BUT_reset.Click += new System.EventHandler(this.BUT_reset_Click); // - // BUT_MagCalibration - // - resources.ApplyResources(this.BUT_MagCalibration, "BUT_MagCalibration"); - this.BUT_MagCalibration.Name = "BUT_MagCalibration"; - this.BUT_MagCalibration.UseVisualStyleBackColor = true; - this.BUT_MagCalibration.Click += new System.EventHandler(this.BUT_MagCalibration_Click); - // // Setup // resources.ApplyResources(this, "$this"); diff --git a/Tools/ArdupilotMegaPlanner/Setup/Setup.resx b/Tools/ArdupilotMegaPlanner/Setup/Setup.resx index 16be1cd25e..fb3d0b0e1e 100644 --- a/Tools/ArdupilotMegaPlanner/Setup/Setup.resx +++ b/Tools/ArdupilotMegaPlanner/Setup/Setup.resx @@ -117,1788 +117,15 @@ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - groupBoxElevons - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabRadioIn - - - 0 - - - CHK_revch3 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabRadioIn - - - 1 - - - CHK_revch4 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabRadioIn - - - 2 - - - CHK_revch2 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabRadioIn - - - 3 - - - CHK_revch1 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabRadioIn - - - 4 - - - BUT_Calibrateradio - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - tabRadioIn - - - 5 - - - BAR8 - - - ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - tabRadioIn - - - 6 - - - BAR7 - - - ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - tabRadioIn - - - 7 - - - BAR6 - - - ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - tabRadioIn - - - 8 - - - BAR5 - - - ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - tabRadioIn - - - 9 - - - BARpitch - - - ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - tabRadioIn - - - 10 - - - BARthrottle - - - ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - tabRadioIn - - - 11 - - - BARyaw - - - ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - tabRadioIn - - - 12 - - - BARroll - - - ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - tabRadioIn - - - 13 - - - - 4, 22 - - - - 3, 3, 3, 3 - - - 666, 393 - - - 0 - - - Radio Input - - - tabRadioIn - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabControl1 - - - 0 - - - CB_simple6 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 0 - - - CB_simple5 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 1 - - - CB_simple4 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 2 - - - CB_simple3 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 3 - - - CB_simple2 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 4 - - - CB_simple1 - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 5 - - - label14 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 6 - - - LBL_flightmodepwm - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 7 - - - label13 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 8 - - - lbl_currentmode - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 9 - - - label12 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 10 - - - label11 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 11 - - - label10 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 12 - - - label9 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 13 - - - label8 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 14 - - - label7 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 15 - - - label6 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 16 - - - CMB_fmode6 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 17 - - - label5 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 18 - - - CMB_fmode5 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 19 - - - label4 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 20 - - - CMB_fmode4 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 21 - - - label3 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 22 - - - CMB_fmode3 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 23 - - - label2 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 24 - - - CMB_fmode2 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 25 - - - label1 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 26 - - - CMB_fmode1 - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabModes - - - 27 - - - BUT_SaveModes - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - tabModes - - - 28 - - - 4, 22 - - - 666, 393 - - - 3 - - - Modes - - - tabModes - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabControl1 - - - 1 - - - 405, 25 - - - 75, 23 - - - 33 - - - Calibration - - - BUT_MagCalibration - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - tabHardware - - - 0 - - - NoControl - - - 510, 57 - - - 150, 20 - - - 32 - - - in Degrees eg 2° 3' W is -2.3 - - - label27 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHardware - - - 1 - - - XL-EZ0 - - - LV-EZ0 - - - XL-EZL0 - - - 308, 134 - - - 121, 21 - - - 31 - - - CMB_sonartype - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHardware - - - 2 - - - NoControl - - - 162, 297 - - - 134, 19 - - - 30 - - - Enable Optical Flow - - - CHK_enableoptflow - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHardware - - - 3 - - - Zoom - - - NoControl - - - 78, 271 - - - 75, 75 - - - 29 - - - pictureBox2 - - - System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHardware - - - 4 - - - True - - - NoControl - - - 390, 80 - - - 104, 13 - - - 28 - - - Declination WebSite - - - linkLabelmagdec - - - System.Windows.Forms.LinkLabel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHardware - - - 5 - - - NoControl - - - 305, 57 - - - 72, 16 - - - 23 - - - Declination - - - label100 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHardware - - - 6 - - - 383, 57 - - - 121, 20 - - - 20 - - - Magnetic Declination (-20.0 to 20.0) eg 2° 3' W is -2.3 - - - TXT_declination - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHardware - - - 7 - - - NoControl - - - 162, 214 - - - 103, 17 - - - 24 - - - Enable Airspeed - - - CHK_enableairspeed - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHardware - - - 8 - - - NoControl - - - 159, 136 - - - 90, 17 - - - 25 - - - Enable Sonar - - - CHK_enablesonar - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHardware - - - 9 - - - NoControl - - - 162, 56 - - - 105, 17 - - - 27 - - - Enable Compass - - - CHK_enablecompass - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHardware - - - 10 - - - Zoom - - - NoControl - - - 78, 188 - - - 75, 75 - - - 3 - - - pictureBox4 - - - System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHardware - - - 11 - - - Zoom - - - NoControl - - - 78, 106 - - - 75, 75 - - - 2 - - - pictureBox3 - - - System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHardware - - - 12 - - - Zoom - - - - - - NoControl - - - - - - 78, 25 - - - 75, 75 - - - 0 - - - pictureBox1 - - - System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHardware - - - 13 - - - 4, 22 - - - 3, 3, 3, 3 - - - 666, 393 - - - 1 - - - Hardware - - - tabHardware - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabControl1 - - - 2 - - - groupBox4 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabBattery - - - 0 - - - label47 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabBattery - - - 1 - - - CMB_batmonsensortype - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabBattery - - - 2 - - - textBox3 - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabBattery - - - 3 - - - label29 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabBattery - - - 4 - - - label30 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabBattery - - - 5 - - - TXT_battcapacity - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabBattery - - - 6 - - - CMB_batmontype - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabBattery - - - 7 - - - pictureBox5 - - - System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabBattery - - - 8 - - - 4, 22 - - - 2, 2, 2, 2 - - - 666, 393 - - - 6 - - - Battery - - - tabBattery - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabControl1 - - - 3 - - - label28 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabArducopter - - - 0 - - - label16 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabArducopter - - - 1 - - - label15 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabArducopter - - - 2 - - - pictureBoxQuadX - - - System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabArducopter - - - 3 - - - pictureBoxQuad - - - System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabArducopter - - - 4 - - - BUT_levelac2 - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - tabArducopter - - - 5 - - - 4, 22 - - - 666, 393 - - - 2 - - - ArduCopter2 - - - tabArducopter - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabControl1 - - - 4 - - - groupBox5 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 0 - - - BUT_HS4save - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - tabHeli - - - 1 - - - BUT_swash_manual - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - tabHeli - - - 2 - - - groupBox3 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 3 - - - label44 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 4 - - - label43 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 5 - - - label42 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 6 - - - groupBox2 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 7 - - - groupBox1 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 8 - - - HS4_TRIM - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 9 - - - HS3_TRIM - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 10 - - - HS2_TRIM - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 11 - - - HS1_TRIM - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 12 - - - label39 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 13 - - - label38 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 14 - - - label37 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 15 - - - label36 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 16 - - - label26 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 17 - - - PIT_MAX - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 18 - - - label25 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 19 - - - ROL_MAX - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 20 - - - label23 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 21 - - - label22 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 22 - - - HS4_REV - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 23 - - - label20 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 24 - - - label19 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 25 - - - label18 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 26 - - - SV3_POS - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 27 - - - SV2_POS - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 28 - - - SV1_POS - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 29 - - - HS3_REV - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 30 - - - HS2_REV - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 31 - - - HS1_REV - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 32 - - - label17 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 33 - - - HS4 - - - ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - tabHeli - - - 34 - - - HS3 - - - ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - tabHeli - - - 35 - - - Gservoloc - - - AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - tabHeli - - - 36 - - - 4, 22 - - - 666, 393 - - - 5 - - - AC2 Heli - - - tabHeli - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabControl1 - - - 5 - - - Fill - - - 0, 0 - - - 674, 419 - - - 93 - - - tabControl1 - - - System.Windows.Forms.TabControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 0 - - - CHK_mixmode - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBoxElevons - - - 0 - - - CHK_elevonch2rev - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBoxElevons - - - 1 - - - CHK_elevonrev - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBoxElevons - - - 2 - - - CHK_elevonch1rev - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBoxElevons - - - 3 - - - 21, 349 - - - 409, 42 - - - 111 - - - Elevon Config - - - groupBoxElevons - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabRadioIn - - - 0 - True + NoControl + 13, 19 @@ -2028,6 +255,30 @@ 3 + + 21, 349 + + + 409, 42 + + + 111 + + + Elevon Config + + + groupBoxElevons + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabRadioIn + + + 0 + True @@ -2199,9 +450,6 @@ 6 - - 17, 17 - 446, 185 @@ -2349,6 +597,33 @@ 13 + + 4, 22 + + + 3, 3, 3, 3 + + + 666, 393 + + + 0 + + + Radio Input + + + tabRadioIn + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabControl1 + + + 0 + True @@ -3180,150 +1455,441 @@ 28 - - label31 + + 4, 22 - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 666, 393 - - groupBox4 - - - 0 - - - label32 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox4 - - - 1 - - - label33 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox4 - - - 2 - - - TXT_ampspervolt - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox4 - - + 3 - - label34 + + Modes - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + tabModes - - groupBox4 + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 4 + + tabControl1 - - TXT_divider + + 1 - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 405, 25 - - groupBox4 + + 75, 23 - - 5 + + 33 - - label35 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox4 - - - 6 - - - TXT_voltage - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox4 - - - 7 - - - TXT_inputvoltage - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox4 - - - 8 - - - TXT_measuredvoltage - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox4 - - - 9 - - - 31, 177 - - - 238, 131 - - - 41 - - + Calibration - - groupBox4 + + BUT_MagCalibration - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - tabBattery + + tabHardware - + 0 + + NoControl + + + 510, 57 + + + 150, 20 + + + 32 + + + in Degrees eg 2° 3' W is -2.3 + + + label27 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 1 + + + XL-EZ0 + + + LV-EZ0 + + + XL-EZL0 + + + 308, 134 + + + 121, 21 + + + 31 + + + CMB_sonartype + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 2 + + + NoControl + + + 162, 297 + + + 134, 19 + + + 30 + + + Enable Optical Flow + + + CHK_enableoptflow + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 3 + + + Zoom + + + NoControl + + + 78, 271 + + + 75, 75 + + + 29 + + + pictureBox2 + + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 4 + + + True + + + NoControl + + + 390, 80 + + + 104, 13 + + + 28 + + + Declination WebSite + + + linkLabelmagdec + + + System.Windows.Forms.LinkLabel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 5 + + + NoControl + + + 305, 57 + + + 72, 16 + + + 23 + + + Declination + + + label100 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 6 + + + 383, 57 + + + 121, 20 + + + 20 + + + Magnetic Declination (-20.0 to 20.0) eg 2° 3' W is -2.3 + + + TXT_declination + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 7 + + + NoControl + + + 162, 214 + + + 103, 17 + + + 24 + + + Enable Airspeed + + + CHK_enableairspeed + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 8 + + + NoControl + + + 159, 136 + + + 90, 17 + + + 25 + + + Enable Sonar + + + CHK_enablesonar + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 9 + + + NoControl + + + 162, 56 + + + 105, 17 + + + 27 + + + Enable Compass + + + CHK_enablecompass + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 10 + + + Zoom + + + NoControl + + + 78, 188 + + + 75, 75 + + + 3 + + + pictureBox4 + + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 11 + + + Zoom + + + NoControl + + + 78, 106 + + + 75, 75 + + + 2 + + + pictureBox3 + + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 12 + + + Zoom + + + + + + NoControl + + + + + + 78, 25 + + + 75, 75 + + + 0 + + + pictureBox1 + + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 13 + + + 4, 22 + + + 3, 3, 3, 3 + + + 666, 393 + + + 1 + + + Hardware + + + tabHardware + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabControl1 + + + 2 + True @@ -3609,6 +2175,30 @@ 9 + + 31, 177 + + + 238, 131 + + + 41 + + + Calibration + + + groupBox4 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 0 + NoControl @@ -3840,6 +2430,33 @@ Then subtract 0.3v from that value and enter it in field #1 at left. 8 + + 4, 22 + + + 2, 2, 2, 2 + + + 666, 393 + + + 6 + + + Battery + + + tabBattery + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabControl1 + + + 3 + True @@ -4012,53 +2629,29 @@ will work with hexa's etc 5 - - H1_ENABLE + + 4, 22 - - System.Windows.Forms.RadioButton, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 666, 393 - - groupBox5 + + 2 - - 0 + + ArduCopter2 - - CCPM + + tabArducopter - - System.Windows.Forms.RadioButton, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - groupBox5 + + tabControl1 - - 1 - - - 253, 6 - - - 120, 43 - - - 137 - - - Swash Type - - - groupBox5 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 0 + + 4 True @@ -4117,6 +2710,30 @@ will work with hexa's etc 1 + + 253, 6 + + + 120, 43 + + + 137 + + + Swash Type + + + groupBox5 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 0 + NoControl @@ -4171,78 +2788,6 @@ will work with hexa's etc 2 - - label46 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox3 - - - 0 - - - label45 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox3 - - - 1 - - - GYR_ENABLE - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox3 - - - 2 - - - GYR_GAIN - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox3 - - - 3 - - - 433, 309 - - - 101, 63 - - - 135 - - - Gyro - - - groupBox3 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 3 - True @@ -4354,6 +2899,30 @@ will work with hexa's etc 3 + + 433, 309 + + + 101, 63 + + + 135 + + + Gyro + + + groupBox3 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 3 + True @@ -4444,75 +3013,6 @@ will work with hexa's etc 6 - - label24 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox2 - - - 0 - - - HS4_MIN - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox2 - - - 1 - - - HS4_MAX - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox2 - - - 2 - - - label40 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox2 - - - 3 - - - 433, 181 - - - 169, 78 - - - 130 - - - groupBox2 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 7 - True @@ -4627,98 +3127,26 @@ will work with hexa's etc 3 - - label41 + + 433, 181 - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 169, 78 - - groupBox1 + + 130 - - 0 + + groupBox2 - - label21 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox1 - - - 1 - - - COL_MIN - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox1 - - - 2 - - - COL_MID - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox1 - - - 3 - - - COL_MAX - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBox1 - - - 4 - - - BUT_0collective - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - groupBox1 - - - 5 - - - 293, 90 - - - 80, 209 - - - 129 - - - groupBox1 - - + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + tabHeli - - 8 + + 7 True @@ -4891,6 +3319,27 @@ will work with hexa's etc 5 + + 293, 90 + + + 80, 209 + + + 129 + + + groupBox1 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 8 + 535, 279 @@ -5635,6 +4084,69 @@ will work with hexa's etc 36 + + 4, 22 + + + 666, 393 + + + 5 + + + AC2 Heli + + + tabHeli + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabControl1 + + + 5 + + + Fill + + + 0, 0 + + + 674, 419 + + + 93 + + + tabControl1 + + + System.Windows.Forms.TabControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 0 + + + NoControl + + + 214, 161 + + + 195, 23 + + + 0 + + + Reset APM Hardware to Default + BUT_reset @@ -5665,33 +4177,6 @@ will work with hexa's etc System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - NoControl - - - 214, 161 - - - 195, 23 - - - 0 - - - Reset APM Hardware to Default - - - BUT_reset - - - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - tabReset - - - 0 - True diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.pdb b/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.pdb index b28bbbb2ad332e74f6b441ebf93765debfff416d..9761640ef172e5d1a36ef6edc1329d4389aaf619 100644 GIT binary patch delta 190325 zcma&P2|!iV`uD%r-f-aPK{$dVqB!A@6Go1xVCGPUT2?p)iBp1t;*cYjni?vW@-#SL znW;IaVWx(rX60B`R%%+-wXT_#b-i8l{y%H)bKubL{k`v>`ugm(o@YI4de*%5K6#ru z=N;=@&^YYV5W}cd&#?ba6|3jNKUO=;f19Rp=PhLhs~xVOpz7OQ6Z$A54!!yC{eL}m z;KB9J{_FAC`~PLVRjWd?>Ji79g`Byu^w9E)wLX65iIyGbZBJgWp0CvNwVn;kh{&hk z^t8`P3BLT&E5{#t^W}w_x1({-HW4Mk$KFbMPepWjv2*5~*Rt;`4V2a_;*;9X++X4I ze$P#wHuaegJ(nNy@gjcts(#9dwF{PSYB}fXvoi|4wz7hrl_I7+(6jxY8Fg3Ho4aeu zo>>!5*o>l{&BD`a-dumO%MWee9kgoo%UctqpIBR$_WhI8z18!?dXKvIg&SY>P>;%w zQ^Uu+u=eW`?`vdpEm#NM0P7`wdU&+-ogThkZch)-d~5Cb#+Kygg?nU0UikXrzO%!( zDT#O{JobgY-_4P|&%ikKOnA@YT64mqlqAdz@Bc!<_n8tp4@UKQ;VWKP`$L2r)vmMi z!fVMb{ZI90!`Bv{dN$mn4!!_qK^%T5;88FXi~t2-DR>^d0KNGOeI1b81Hy*XpC%nL#6m zZERDV+D{b)1ywzKYgF;=M^u3s6cqA)z2bsYr9m?j5Qc)#+?_@E8+hxJ<)k{K|7r;0P)sM!aEWWbuljYK{sSfrgh$ zg5|$`%)3LJaJ?iwP1SdegtML=N;kIO5ha?YIjl7>6bkx;E9okU0^c@u` zv1_f+m}APY{j~r1^sys{w>FHb$kC>d+df=XBfbxZtK^XNQBEOxN08cFQX73(I*d^5 zs{3jOAAha(C-BQ9vMM>armP*Il1%Dr%Q~xO;YbzXrfSHXGKNaOFU&}3Hd1XesSnMU zn_8fWoqJ_Wmm9q-k~vBhnH0Y*aBh@}FgG2LYojnX3fT5+^>DDuQ^&TaL}I3RhmMAQ z_CWEgqt*S&j6Pg^?Mc;IxoGsRB?%Ijse0D>I?|3QCyU%zO__m>GHm+ z;%-*~7Jpl1O}1*OwichxR?mf~P#H2sHG<5YqH@gOp>k`AYNpyq!>3d-K}SBNVj^qP zxA_0!mEmfep=8!4?wGLLinQ}E!_We4<-k+wU%{&=^tWZ-RMj$gGLOgP##EJRO_-P^ zy{D;G>PML|P2H`k$@Xb#nB<>DW?(iOcQ+cdvSl*~g zs0&9sOuvjaE?vuy%IT+6w46$|f*6W&2D_qlUx)XNiLPkbRuE)+&sNdF^e}k$o5~}d z439av!O_8?&f_G)x$Vd8Sv=|zdsMbha#fSQyDNmoJ!+KM*_6pns(O;Dqok@XsXAb% zTvkn2Rn1`&MUr46ft(bTroy*_(=0iOSlp~F>iw37dP>W+yCiZG1% z2x$R4OIwmo(qob{o%ZpVES-*JKPFjc+?pJ4Tq_;d4aapHS4Gq+^ z;xSR5xvSN9EFf#+M?1|&7s_K24;$^hK67_!vpYO6GhKa|ITeW@f8PaEWCEF4<%>$1 zyTYPt+jUq%Dpnw_Mg44Dhb~FZqyDZx9Tcik<%X`y?3pTvXD>A+1w2c)JQXEzWaOz@atcOFP-Vk-5v9XW8uO%6R=S(e$wApnRV}6jk!6S^;&*p|h_;x<0FhR$7Z+GyIOCJ1R@IJgeejBB~iiWBlge*CVSe zXS$URl!?!%I?`CDbyJ6+(3oxrH_%EE&hZJ?BXW8vgbyQJV;Lf`h}1%4kxxXY&m+n6 zsn#$VGG8^4q&dEvw<6nn2|a$C6SdAcjU8=kIs`?=v_n%fMAqOn)hD90(cTcrT1cI4 zn}Zn-lm!dP`6-@b1_rdWDG!bwi>RT)U>=0IF^5zPluHB+u44N%nX3lXtQDihm^KC& zKwAu;WwxxEtLnvMl87s{9Dd8}vSQL{9i$B)I#{P^kT!zoVBPr)vb)A$ES<;ggI(3! z+8A{r2HCx%%vqo!WIpw$2Fc2KD*B#50SO1kCbW^YZJ0Ftj!>8pK`I_r9dN3741b&`dRKxR)0V%U6!0*l2wGYQp$ zQ2z-CrMss=lKc$KJ0Fozh}1?TGN&y2+Dg!f;+PUdG7w=^X0-H)=(u%y$~S6*nr5F^VQ?Y zCB7OwjFDs`Lv9t1cJM2M5I*Lf2ZvwWy!1Yh4%95b5`=S*@-fXoG4~ znuu+tjU4xB(HYj-hiI#gmi75GmE{Xnq#7a{@PJ^s)$GxAh_+ts^A|=OlZdhmlwm!_ zwuw%XbSu)S9U}41(cK!b)4<($oemJu1~f#{pTlx=l8O-Nir3~zWp$u!V2G@IPCZuh zaxBmMZFY$LZwJbu?qsQyuj*AfNAPX24!`bXM@4Pfp5%&@)O@UbsLXB<%CPf&Xi)81 z$ZY~CXc_I3)g?fI7()$daW1&3l;o?Xe;eIf`v%0pb&=zbM3??`Bq=8*GjICU91`uR z=lJL9Qt1{ zA0lVWBklNWOZp$~$XUZ->nX_ys5UlcQ+af-#waM2XE2?}i-R)6K8M7}!U&B9(0!Aip8kDV=y!p`e z(3hZdq5Gkmpn5lgmY#R&J|4F4poj5o&~wlo(C?scL2p8LLH`RahI(k9I^xPuUDPqq zca>~ep*qOrm(=rjH8QFgtw3YYg5ofYCdOT*cF~M-t}*LdBA~eSd^u0gV*UZuP2)!> zgQ@Wov_ABoP~8Dsg|>nI4DAHHjzQ>>{1y5b^d>X|`UiA8^cHfnp*q9QK>x(8OY#nM z5$RyOH1Z1YP^Qeh=}vKB7);z{;VY`g=-)Q4 zP%q4KruC|HHK1oxx;ph=S44GT-3!$<*bS-+i&keBR(Gf_tX|MjP@R`2p%365<8x<0 zAH+Qg+6Ss@tRM76XsT(n$Xmt3Ks+`;2SIm2wIWK(7=pXl=Y9wJxct0QJvPf(E+~8H zfUnU9lvw(S?Kpzy$82a2bUZX1IsqC1od{*tW3bTAs|TG5Z2;9#>by+HtsB1fZ|$QU zp|f!(L!UN{S#|?|29Lpb%!Q7GJ_{WUT?oyF=0m4Iwc;7j0^B>GOQHLqFF^GqX*u*1 zRG_+}rmxHU7OKPjv8@qAS28}(lc!;2d>xi%>V=r#Z z)u4CI>*DiIhL+&&4?PGS3q1_glLMVl-9zZ`g;1U2HPDZsB*r)nB{Jg#^aJQ(=vC+^ z(BGi5KIP#K4`-ly4g4ik_vrNgc~zhnpmES|plzX-p&g()!Y&$LNM*LiGeI$TzQXL0jRj0M%V!MX2uj7^d?2K`TMEjj=At8wQPp`Wu$Ev1+(q zhgOGfgVu!Z*1b$E9^S`;O)h&>iG_ZKTbICjsCHk5Hh}&DrL^)4>b4oQA+!ZF1=p{LZ?w_D3P)gI*9}3kOqI3+ZKd;>^9{Tg3>-rHW zN{mOLy3Pkf2S9bg2Kn3>(4qLxfIbc_^!cxbYPqdY4mI+2L6OZn2pt6tGukqQwgSz7 zey#(e4QaJjU3NRGBxM{HZ>QkMSz`&HJJW1vG;}<)9&`d!&vA31NzjQ<-Jwl_rbDMd zbtgI%s)xVn(3wyYtA{&-%-VhEZ0Kg(PeXS>=RglZ=Rw1ama_GAb>A#!1*PoO6g)%s ze0!-s{g;nm1avV}_k^sC^K{Sm0<;%&Idmmdpj)6XS;o`9L096ALdPm-Rj4kp>d+$G z9enF z!FFpSd>j98Y-2aH5%e7>!==q{4ZZeD+dFxTX~qE<+Bn~bJ`6ns9cl~Qv5oWy?sT7f z81w^a@`ifF?X19*v02t!Qjr5rSjMyM$p05eCqd6bdqTg4ra;d@2SCq5GoTls)1co# z7ec><7DB&=>PGwz=$p_VrTu!<(Xtm_yF+?O$$AxJUY%TgWWB0jT6&4}O^I1Uu5M)G zEnR-!$j115Y51mUInW5AD*)|4UoZve^RS)Z7`O_8g4vt`NnkL@1uMW#a28w#q1b6G z=mrLZT-WyGda7`fiVeBQGVXdaQ!fcS$@On7m$ZnlP*dh?QcgziJx+o1db9nJB0^?dp%4SvDgpS>;ZnDxFw@FozDO*&O=R5ctTbQ~dGDNw#+Z zs*&%2=UX|yMb-Dv<+`@{WjeXTV(o1LX|Z_VS*Ibm(zCcz?!pXgzm2yNCrbM76`PbMBnz34O~@=c9wcLWS8Q9#`3#P0Gn@m* zV127?+RBh}{?o^yzn0Jt$W&3V+h8N3eWaZR5s zM98^!RO?dRRrZjwZRkF8LOSo^ob$|yAo*`sn&I?40b;wf*mlHfoRkZDR6=Q%YrIQg z?0|9C$sn0l!&6omv*Ebjf|Gbs?({JeeCK1@Cj2(qfHePfEJ(ijXJ`$H*sCI}o4Cf+ z4yqx2`&INvPwiz=%H#S~tRqwRstT4zyR<;jUd)sl-@jMwv8XMnQ>kJ@DcYxk+|&y# zO&P644Z)yG_NgT601~T{gKJ2w{hS_B{6qJvndaCNa$&z3Xp;F3@2L^)8Yi8Qm7S1# z-$V8;lK-9>XeE-t)mw=%itD>aML@1Brq7{ zg885b>;%Wa6~Gpc5e1roZeTFTuCO%ulfr{4*7XR5XB?8agH)7ph?3aM8D6Wc?g}(3 z&J~-u9z`JJkc@r5)c78e&F@nYkHH8(WLJc*?j8~EAsDGJdLNPwhXO)8r5OWYJbXxA zJ*4V2dH9fHc-r80GHwJhPq>T3&iDE2mWI=qFFBV(t4Yvdj>w(ksYj&!VJu`I%Jz`p zjw6)cLLQMdnllJa?ZXu9Zxy?grR)d^pc8kca3Xv}we#7I&VHcn=pxv8MI_lOo%% zm3@OiRvc9cRtl;7&tSy>byW5C&ZlD5g1z7@xGw!ZRMC}}Rb;pa$G~N9yW-O1g@qqc zcO6}Z>%$Qe_mQe?eK;am9*8sJrRb^^A+bY(JW^1C!54j`4pNojzl1Pwe5|7GOC->( z5&C$WzZS!C$1zdTm5_}G+Xwdks-Lg@i}2Gk2tALA8|j3rElW@7W^js=nd={y)=Wof zc#Kl+L=3Nwl$2wo_1{qzX+~!l-;b2HkEzaXopxRDv?zDQXjd1UzmJsK#{2QBVW_E&oTg zf1%cOA8L<|lDJdcp*ZSOuZqxcx(fIbzfWU~(t z3LQV{z|Eg@0_!1!5uU(xKjr*jn{;x>07y)rs?n2rj~+Y5IW?mh5MZezx%pF7$J^7V zPUqiabG>J<#p|D{2yadRPp>7(%o+87>L^3bknNs2+hb(j85QT9H^xbnf6(48`_6Eh zxArs6GwY#Qm+W@AaYo(e8`nBYr_a#Q3mr`|WyEKyMZG4OWf?E+ON7nF+(dmYa z{ajU*V+faOQJ7T1=HQ13YRpu{Sov62D>F26fsk%$3 z^E`mMQ$97~^@c@C{V$Zarr%2&X9J2O6X*)KmMJM;sNTLAN=I4q1xf0Sj>=i`(HC4w zfmS-Js(Nc>mCxW#x#ujGZ2YZc##zEWNVsS0aB*_%tZMDMKjm-UzY<>>pnI}=zm}5x z9<|l#OV!)FHKKUtm#UI7=`0q1#n?&TQ0Z&NPC5en&di*zxky9fw;kJXSQhQ-n^%Kk zOF;FdwW1d%;%WaWpEoraDVn?Rd|)foJnHprUc8l|5U6ZiC2}!vR#{1yiC8Uj`)i)^=B0oVjbIo9d#CH#I zt{JS5e%(W=3408oYK0!Xm;qf^9-c4h=e<13`ro)t6MKU@XrVWiCv4mkPudqEbjDUl z@(soULLRM18`UyLk&!t!II&$JH`Z6+h6PzuPfGKf>Mps$v)5z<)^fMJNxUlKM-^zf@vb?9XdX7@UXu%bs$aJ8(iO!I{=SSo*veObfh4dEzQH1YKrD za==C96lvRwj%i0VUj*O4+2fP+FJp^j`z`FQNRHo9jof<0q7AC5Y}Y0q@o&1qjy^w~ z7hP9H(tHnVy_A2en%>ENd3bs{RHRq@_v$Lx|8KGoPC|=P<%fS`OGQ3W{|s-9wxv31 zjop&%nFisFHI50b(I!+yUj9>6@^1G9)G5~E{u*s7J#-xAe~2T3I2sO+rvFh%Wd%51 zbC_ef;s?mf|Dk!uv*OYj^Jn{2IsG59{i+=JG$^w0wu&pOmKL`OTbZzr50FRUn9!zw zsTlcXY{h_1>~k#^iP(eza_2S~oZyQ>XHaKlt?og%Px)7%T|NDms^^I!)MB5stf|T@ z<^8{u*TPG-KErDL`d_MbS$dk@A)+b-`DlPVbVoG}{zwOv^ngu3H{sRx76`_wlmJVY)|J zx4fT8)XTHXI^Kq?Vf_`SEqk5r#3Gk(Gs(g7cg*C_V*941wgzR^3*lbAYt&F@SoKZ7 z^myeTJTuY2XoW^))RZ-$%vuVRnQC@Sk)M<~!adQ)3zbVFvHwidj4)@U6wfqGCT9=y zDPC-u*GzNUL&Y;)=0;_`^)PFu?iFiDw@|Z|MVI2ZrsFc{I9?7l$D4EsmE2|2B~W((8pG!JFWwfFtS<1r7p8`?Ia43C`tkG#k%qj6o!URFDbuh1w#p8yo|d0moTJbz7B9(_+kPkM2L*O#F4PvVhDd-O}!5sN_q}eE>5A|MS z$KPK-h%)QD`oc-wA+_t7Ri!A(^mtR*QS&zlZRzhz`UCWp?~C`5pgOWC&+V5MJkSefm~86YGVS-^BFkEh!-iWpt5C>lpj5RxvY7((q7K z^Mae8Hm{CTslBV2jjOC6Biq1Ha1q=B5puegIk~X985`0K^}{whne*M>Umsx9iNrW; zvv6s?rsP*Q6M`F8WddDH@Rn+6Ur*u7 z>(+@L<5T&truiU~ID03#Sv0{ov~p#BE#0HdIB%v;+~1F$kr~mn)ia{nkkL(uRCmTV z9hbjIbOMR*r)UfwMJ;NXg<<_kV=l-C>vdZDD3>nAoXrwf+pK5hkl$b0xHrm%w(gF_ zt?HPCibU!A{cGx0S zIJ=(7J;7(proM@HFZo@E>`lmDH)~6&=lwMxq#oD~I`4EGbl&MW=)BW$Q0#X)4vPIw z$3d~*={P9%I~@nbey8K0^sCQHAcVUbR84M1nNhN$z8N9atC$|y%@eE->znlT%1Yk*dX`EnfVlQooIJe`8m#vbiD|_`v!3}qUO7E zEhw-oGiCO%;ACG3ip*_93349i8n8jOG%{Ow2L#BofH1Q3wM%EJoaMZ?pt}bi+ga5l zc5rB@OgS9tk<`YNNtTRmOqpcKqQ+(;?{c3eZK8Stk|l>5Gcr`%=p;yc>nh5UCQZy} ziD+VmdXoZpdepFa^}Qw0#bC4V7Z zBZA2Eas0OdY`wW`vm1G&Tqm>+}fqh=Q%WU9wDq0zlawD4YF}9i6*c`B-`2J>Qq07?xmfQ%bA-7wb z3ALwVO8TDpCU6v71VLO`s09+LFHPQ2n8p&ulR$grf}ZQscO)*stZjYzj*>n*RVTUl zCR=(%u8P5Oe3KO-5#xB#A@Q{e9w|vMyZW1Z^?L};r6t#Q??~%=uvF-y_n5tXz4BVw za1W*@WVX>B`Q#qcf2y@sYP5mDgvFJxN4mB#iy&ElbBaZOkZ@D=)R7_sW%B zZOr6SeShg-93{KH-6L^r&DP#;bufxo&+PPwG10zfUieCIkecY+GshF(4Q;WSe+3BZ zKojLsTl2o^&ih!p6#V7i6DB3nxgDc9Sz6rA++vc0&h2UBB>2hp=Bp+tsMNvS(y%uL zng*tT0xIVGDEllYCPG(ihd(M>ljo#E7t{X+U#85^ z3@$sk)OlIgrL=F)lGb&^eb&0yH{|Ppe%t9!a;V!a-OPd3?ypVhveV7v z?LJ!SCtnw*+-J5{?&rDJq|LU8@06vxnP5^47wT55DObBQlceY?^e_jy)pU>w~Wp=gfZ0@GB$m~VrW4r->eo2tfNkI?xDGk;!>Dgd_OQq z`qVUs$odr1W8FOn*B7dxoJ%p==mw(C&>Q!mf$Swr&q30)j~N%;b5PkaoxWOG1at@f zkQ4d=Uu$?*KI?-S>?35_Ap1zrSA9BufAy^=9BH|~FHIi(fA(eRk!I^xMrG;uP;ivY z=w~*nI-MLW1Dn86pkL0oNshV~c6P%ikFP){HGMTBb_9{-q6fqYUp4V=IiI zsj|2~GpM1d{_=8K&+~GizuDf`J~xVb1o>^qA4-*`j|3>n(v0me{*@|)fs8LTV+V|; z1H^o^wBc@)UXQ|f3r5cYa^cYcRl78UYb>s5e`C~r48|@PD+WmI)PN9+G~;a;{~aI; zQ%k#_jqJAJjp5+4wy@${;Q1%ZXwEX`FUBj7rYrF7UnjT~pJjU7Zy{-qX)jW)Qg5~PDfo6jB zf#ZsoZiARf{_>b}D4XPT7t;r^W^8F!q2d~ty&66?h}AIFdtngfddSDS+u@}RHY42s zD({z%pGjq{8ccUh-FyUfPaELGQ&;*`s#qhkt9_qF&u>@w7{eTei9-lXEu;)Fn_4Yt zuU*=+-@Oc9E79*N!R2;}RT(Kx!mkb?;Z9+d`XvrElV*8h=s7?;&>LicDWCwX1$)6+ za2m7e|}7vzIY;1IY7ZhVd?K^mA2mVs^HD7Xx6gX*yyH?@i-;$rnU z%K=vsRrKR)5|_qo=*QPAeb?YYx%hNNPjOM28Dy#^dbtrTB~O?^JeO`i%SFdyw%&3* zH907#a2N~Kh_x28ni<2H)ifT)?74}wA4ViiWB|k)!rfFoiuq^HO=Q6^rjD|%%v;Z% zo5()x{at{!o;Wv=8`?Yl4M$qffb_(UP*T&m@+Bki7KWt4w~HEYpuR_j-M zQZ({wOs%Oj9AQ47k|bvY?WrrV=f5c_S!@Mt8(~(r z^53+a`#6_JnEq=!NfI;CtnaxOSvPkJb)0g(9=FPdjWoSpzn4x99OEuoI+`m^PQy!* z4|ULP1YPA1TBCkgv_y^~sNd^<3HsD1g5F2afBSjet_`f2%ziPrj%p@r9D-?cz_8F2q`ffn!b~$FY$$hW zb-cP-4LLoIWnQ~XW=@melEveg`CS~xyV4m*Hk`+GPk+v}0r2jPT~9n3lZKCYPc(XQOS!B`%0u%{1F#Dh;zp^8F-v`c7>s{e839B-sGN^8k!>yL`oP zx&bxR=zI2`oU^SYsXG>#-pIV+m+>}afA_n?r8g3jWGONs4d24_w zG#M?F?7v_p%GkNeg~HL}3HLrLiK_2Pg$XQVwvIRNDy@!7ntKRtf18^^fB_Tm;-0JP z`FG{%30UOw@0OLjE*cKzu{(DMvaRE5De*sswvw=1X8peBUb(z%m?SfD(bNx3z4pqw zT((Gh?Jd)!3!|0Yi`$=EXr(ufoKG&aa*hx6-aspD;?efu94m1BsJFjc>5Zi5V7>fr zr8kqJbvxm4-$Z)#R&stKU2H1}od+m1;;;*_^GGh|8qTVa3EUmMZ z?3zSh`h9@6?%aug80{l%eTAm}Qf@w(tUg3mV@l-F$z(OA#8Krx6p9zMBRJYV#?iJC zFWV=Rj)nnJ_&VM-#5KjN>K*Ch`3*H*>Sl5-kjWN8Hmh2_Wn^*X+HYLCX5#JBB})GF zDJ17%l2i47oS0&E4Xf&t>|iwa-Yqdtu?}u6L!L4l)o88CI)L%RbL}of>uN14pJMja zT6R5Ey7W(yzn((zVeF;X0g0Phx{^(jiBn>l|WZ-UgFj+v00>2`o2)BhG=)bR8SVzb8vZKMf&T*H>!OgL{EZz=fu zPu&S6$o3MeN*&9)m!-!orbheWW(5doGfoii3|mF>85C)P+&2TOs=+;Zzb0+U3Gx&| z<$c1~qLftaS=}bFT72~cJ%ozec z$!Fb>!JHECnBy=P&182iu)xOg(GRT|J40$8>~d+!8kaF#pAzYkXHAO84M$PfEVG)K zpk!=DXjMs^#rYGJvZX?#ZSxcilIgQZruT!gWHLp>d(A96ne?93f@2+@gY0=;pJfI) zI;x2$j~=~WK*)Nw+|PMted(RYhGt;^ufEMA^VNbI*pIXG>R`O;B$ThX)l6!H>p|&->>em&zJ*u{8{D9AuMYim*->YFo&?7 zkIPC#hyB~kZkLunLeDV#W4SQL>{dF&G?~kY&%(zw#-~6|H)g~iGnaXr-%F=Q_pEK4 zX?`FKvWwqMAgs<7+STpJo1gYpz+{J1rnZ+VI;*-FcK+8|gHU_SN8+ zlU{$rZzDPL=yFHnpUjs~%&$K+tQdcfF@{teA^~vibRg@dg5pPo6P!F>zsh#DnsoF`- zd@|5Z7R@&s$(4LES~8y#kq}`t=OR6rpb`rmUzNMY?T3|ME z$NRameUTYiSYWy$EN@y9u95+5<@a*;d=V4Fz32+Qm$&d(AL&T`y}HBuxtvS}$iH#;f9;;AteOIWCVJyJ1z56AMeX`;tUGNASS}fBmF1eJ;Qv zCThkI7zaY(4vJY1e+IAtFX4J}+muLb8g z*T`d?=O&A&5ZfzKwr#aM_9txgu+Uzz9M*zGW}V92PB|r`dqq8;YtJOCpR1~zqQ1O+ zd`xX}ddz6A@0xN^eK95%f4VH7-Yp}$`|0}<7Za{a08h_*;LRt^nTzdIPF##N=X~M> z*Q)ioM|;`67&BBvnJ#_w)Luqw@8C0K zDb#~Vds(x@E|Yx_lZXsxCH7WG3*TNP zOWo%&)yGNHvCpOZ^O))}pDuro)zLOp6(VZ6Sx55rvo7l>s)S1ms3s`)>B8vIiiUMjX5lg`wn(ZeTGZgvCH9Z*N<_X0!apfAd*KQKz!e$UnW_S4irH5wz=9zSPydi@gn;Rck#BOj#KAM(=NVo?Ke8HF4FIE zXdTF!lcD}Iwc)b-C8GS0;q&evWdBQMf^Sn??}PcbDsNF?KfYF6;brqqkjW-dh1F)E zn;jZrQpODDCdJ;>W`^6@gHgtE=RK3eB6Ggm*<4WuA6L?MoG%uc*=}doM2D?g6hgnU z#@y|8c1B9&l3qp5+5J#PHz$r`uM&r|t)YwpS@R}sxc6)3Df9I$#kJR(2ZP+xd6!ft zs;Sg5 zF$c25EuOl?9IH&$u0L(%D5k%?6jfB3{c=^>HZ#fXEKikD>|CZcExXJ%X8!}lKkPEU3UT+ar$I$+-H}LH3GYx5q#I$xyY^9VJ8FHyfD;PZrO6-|P@f2UvXY zsCiJiovue256RLKR%CI}M`kPKcABd)E<2x}y!x@Z$)w@Ee2l9kabFf+IHoUVb^VH$ zU(BDZAPn~Lo4O88a2?AwUtWcEU1U7F>+9ktPMSZ2nAqR_UzlIb%7|tA7ZiX^;1IY1 zjJmvb2@*jDm=4y0z2G9a1!^%nPXMVP8x(-`;2gLKYB57k0R2HGm;+XTW8gC21?pKw zb>{9#AQj|+7r}0D3S0$24Gkj}v;)~-KG+71f-8Vd)JOom!6=XiiokAg4%`G$%!QhP zo*)h6ffvEHMvtS2hpQln`F|{E2l|6dkPp^^qu?UA1tOSRH3Qv1CYS@(13l+D3$BAG z)(Fi&x8m7fn&-K(Q_Nvnv}qQyn|scTDlRy0KB>&*9*MY!E8-jTj%5~yOT>3vl32J7q0@aT4f|@awi~)^&42XCVRKyQ!%^1zE=FE|5kfrw^U5absIMo~zzQRKk>$zqi6=Z`IU?;c?ZiCpCSQh9HGC>j84K9LPpg}9z z8W;uiS1mSyL*P0HjVE%@8)SkxU@h1S&c(BRa+8NBc3+x-zF-u{2W!Dma1jLEO)fwJ z=nb-q>(;XVt3rO_INciN8{y{EwxV4B#Ha2sSykI=;jKHY{0JB7jBwW%SV7XWE{7AF zPKLJeZTtTu_tmlLyRH)a%m^7<$Es~Y7uT_FVF}O1T1`AZ!>T;e(I`0;D@Dr5Sj+46 zd-;b^x7>*3r8l>D>spQ6cl!d=l;nEct$VRgNTQ;9txHtb&}WR6J$0?PU}H3Txn;)p zc>i11@-i3m*0UO!-qA9zzExY24v^x(^(>FKn--+s(5pF3D@gqJdu(e+8J-^-s^7I-?b6?I~xWlDX^Q~66@DF0NYqLQKE6%uPW zuSx0h@sIUAiC-5!-$U=^@>uk`!-_jJuqs=+6Rb%X6k``fxM=TU!K zH^hFlzpWeUJo>-5i?%F2vs={MYU-N=@zt8rg1L-vJFk4(-1@_Hh8)~Zus@>E%Hje8 z8F+h^REoE1N!M0ZW8Z}BPswS8N$iDt)W>~0ko&#n?t}Z4&F$uk^v{6WNF-7;Z;8i- z=EPf#O%&ni$}s78dRkivRioI&Oa%SGbg&HUy=Qy!M&-NZMH5<$)&(AJdC>--DNk0c zEuK28^RpAIfwTtu<=cx1NERVk;E_L(j4r?ebhYT$^Fn#(3%KiH?DbgxKS(Y+b}@JQ{>mjCU()pB1O0=`PXZecREjn&lKEzF5m z*F839T#}qSOkE-Rv&y<+FG;`IoI$mDKR?bK{E{qcYjyH{l6$qBM#l9T>9|ly{%mW-c`x|n{Y~pziEl^K`d0cmge#Jb zN`?H5>s#5-4yA?mSC?1I&+TZs90a>+hC7kV_I50ATD2$XelIo%y3msh#!r1GS?#T8 z$fdbVVVhOqGOTlmxmu35Cw-h6yXJ(;AMLHC?m0e{<-S`WKzgnZkv z^ds-9rC}oBHo$l^LQ)b-Kg_;b7QygrgpnKJD}o#C*@-)uXnAY;y|js)qD5AB^Bp8= zY)(XZ8+ou3%2{)`Hb%&#P65hyX~rfPpGC+87E?7p^F^XH-b7ns1x`-T__M9?A+=g^ zIum3wK^l1F<<0@RzSN8@Fq(VC>_Q*j9P?9hK8c-?Ze1+@E3&KQsV)d^MR257UhQJl ziy5f}i9|=bvm)ICcoMhm? zFLw65)P+d1ZoDqv_g;pJ+er);-pc-{9NYe0a_+_6oR4{|mLbV#-j3$Mm1SNsnxX%1 z&5gUFdE)!V$X5%;DxHt)R?TM6{_gVgLE$D92KNM=4SwKfOt|#|f=GlNClP~kCNACx$1b188h?P;tS#Yj+z)CV{Ru>+y2Aa7M(xJCiXl*1! zmsQ*vy4u_7ZDICOXE}HJ`aftbvl@7PE3Tjv5^kF@@pW(((upZnhTE}Ny}q=6KVWZ) zwMiRcrM`Ns>0`~;c7x+pi`tf!SGZnytS|X>szDj!otJd7`&p@$F5SmRs~U2-A7d0H zTInGxW!4#np)0`PWUV@A1^R+fU_K}Ud%+oS3q&w)OaQ$>2AB?(flc5jxCm~8D9+>( zKyQ!%rh^q=CpZQ!1EW2$R&P(FpeGm%a>0C11a^XB;3BvMJRO+vg2ZC)!&Wc-M#G@~ z)_0IDk5~u7`okFo^1zFN#4p?X2C2f`?l1{UwIW?(dFf+rj>M(X+@Rf4t==Yl=iw~<+x_#z&M;Ee*`kx55)M#!#I}1J24}J__)SE#+PHV=1I%{cK%rT5-DD> zw1Psf_!1yXJ8`L|&LF0&SIW!I9z;K$i^ibwP9C&q6*)Y}isXYyb+ZE0HW`fQL_}i) zM582guob0Z%Zr}YqLUC!EGHT@1kuFuqE8J$bTXo;e$m;T8A#q8LRwSHi^dG4Sf(JF zJ6^gEwQ8%}^8Bo!oa-DL%24(cLIvaH!cZ$t6_gixxa(Vte>F{U3Hzvr?bSut; zo)}{F^o{#tH89^GLt>0JNOI@R0~Si$L{USv(Q} zXgPu4Q3%XOAR$*;jIy}U|2KgRT3`VJeQklNa%GeiW#TBO=E2cOEkr6aS0;@PXpQe^ z#&a-c=gPOE$s@E}$VZ+;fX|A#R_4mgClP>_6S$!T79sFXuGAbu3Zdl$mXE<2PL0JH zKFgK;W5^`5oWwnuNMw&g;zq6v%|rrPPU15pTm?iDHc{?mk_u=!ft)M^mLkw(qP(1i z2530}?^pz$N8rAR(qSwbpydQMBOn)ZNJRQX`Ft!YpyebU9EXZ!sF*QPCXGV{w4A_? zT3|T>FHMxn*=T^46IhUqKp_IVCd!U%G(gJq2&bjX@M6J_<5rI zpaq~>z;|O;ckF@lfw^?0_Ix03yj9DjOJ6nKN-^n@uZ_2wT8I7Igb7wHI@;}%S%7Ei z=PS_4Au^st?gK*9W+tfaZEdCjE}3TM(Q!x}n$-5l!pzg2SotdLi80%r*R>~xTWKnu*r)B8 zHWg1yai;df;%v`T+7s)#radtt+cRkzo*2x~X?S86w&%8KR^wUQmA;KeV|5>;z}Qbr8j3z8UBXMuB{=790ZSz)j%k#0wH238aB3U>Vp14uNyvb|;qL zQJql+x`8w>1uO%bi3h-4;A zpeM)x)4_{i8#oFsg4-afD=I)YkO8KHWndFH3NC_MAmU!K1Cl`Mz4~)*Gp*Q=er$RC z%4@pif0Aq_la+_yG~4+%&SA}Y7*4OhbDGS8(;rUW-#Lpk=Mgv`{GD?Hj_Xl4vAd*Z zp5_0fUoUwi55{9KTJMsXc~)(2>s`(q$3GuCB%AYCW;tu|UUEarry~D6ie{IN0KAGk z8^!<_J9f#u*>qYvb`@`#ZF%_Chx7Aku>4)h6oc=g`(8Wt&CRbq&D@+qV7Bi6DK|OQ zmR6trjMd6b8Q6@rzSl~hv3i?%JEg)LYrOfvPMJB!T4=@Y3YI1Ju`FmXmn{Y-8_Gy? zLiC+W2$H;NE+Y#m{AjLK*gc#2nFCgUZQv+42X2DUZiW#H5X!ueLLs~Vl=jG?kvf6*X$z7=WB;4OAuE4)uu%(wcgH_CQwc@A4(^<%EgyKhZg z)d{%54%o)KVyIL6{;ik)5sDW|7jks!6lyi;w2)%2fr58^G0$FTMaI1A)1oKab4(hl z#plW?^pCZ_{QR7Cx0KA_it?3(+_3oFFD!NQEsiA*Sc%-0cB3wfU0)ap^tG4YKm{U{3ZI*%8%P zWVQ4j_lf9@DE2)N;f9faW1yO>TtuUYCL@15&KIhpJay&DBKC%HVN%XrKZvowko^m- zs&clb$0K`xC1va1;|E_-t9bm|AJt^yV#=fzsv4xps>N0tZ-cb5lF(6a)Zf{OE?mNI zp>32)?@=PL&hu=2Una?U-u^XTUP<%$ziUO>S6rwhLeHiUb;!>+;@w6$@oZ=Jl=J-M z5{jBvmGo`6N(ELWZzo^;y0PlgLBnyr){|6VMR<>=J89EAz2&=6(hIBysM*a06bQc+ z=?Z(I+(!en{rX!dow9-X+KsM`a}t}l)N1T@%u}z=?GxKP{7fuw<5KI08S{AY_~)%B zl%)&0%fC4Gy#9ifYBoqKzJHmu*tB$X_D3CV7Fvz(iMWr(1$u)ipaARy$G|NR(H%bM z4W@tsuwMTJ>PgQ|(te4A{!h{fr~1jD5}?K+%g^&WMUOqpqULMEdk>G0pW|MWCI)-?sr zki&obt;$u{;8QR%4$H5rta_C*4wo6SHfS1B+-j?~dx76yyq~(cJ-wQ3IRB3@zO))8 zQ&CduNcmr~3@(B(4MzPV<$uXCM>D3wNIz2kmn_f22$=z6)RDjal4Y+o1epnE@{#ht zWVu~4X2Fg)_4_09*kv2^e?}YA1>!=g@+KMK$Elt)q zI!{~%E?DHAT9zQ&z@9?qC)fakN#M9SWJyb8*u$BzXB||@OsgobO^x0^j ziRhCjYTs^Y&QF+1;_Fs|Nxj=2*UNvMxnRcO;#IF(+$^BJ@a0u|N^TuHY}AG=mHP%# zqmJkwwyY^dZ_p|!benTob0}zj)3T;StcSDgNO6bt)(^`413w0MpLeg)_&H z`4m87%kcdsQgNSc)^aOm86nn#5^xdR0uAnGCkpg0Ry(aarfVYsTc4M>x2>MOlFJNe z-363fYu|gp8=cE2MQ>a4gEP^vjGG&7^}ihuGGCbPE$M@rFqOhj7k!C=Ci&iDR3biRjt!g}1%-FKLb z-eV8y_UmP*_7LrFMC-|vpY~Yw!aSs1w@*E?yX4Ydx^ix@?X#Sh6kr&Y_?DbiCs+$r zlG*QC^}}L(VRU*-IlYhJId4BB=dpL$dTC)Z<<34vt*eJEPvKt6W46hZ7W-KkG{&JS z$vu0mKI&JQyB9mWNn$FGl`VTY;i){fEHQ543ojkG-#W@ZgwOxwuA)k)fYc+a&=$++GkZn!XCtG z@24Cm_|l@wQMd1K>9n6is}nwNo%dkdo12>TD_;!oc4==eM0Vsg@xA-$DxMivR(~OO zm@oHJt?hCgZyiIZ?d^TfE|>K8D3{+UmsEBa-{asTRZB|DK}zuCdzM#v9<;*c7yUF! zKZTdD;}#)xOQ^gE{eleN*E`7JTV@HR9iiVx;wpLxCl+T9l9~}?)Aic~_SJozu?YR{ zLNs#63GW>qkSJ|F5%O1wRp0zK`>5|b=j0LI4HL=|uJaQi=?Caoew7UeNcbNlyhE;h za)1i$kn2cl>(Y{5`<|rzs*nBX`&^)|Yj4^6K3@BkHl2r1xq8U*giRP9ZzosVAk2fz zV5VSNa`Yfus9yOJ4@i0g29(hEb%Fb$)g`Md$tw-tx9Wtg5Ab%$(j(Yyeq}zRk^R2a zjMT4upVa@0)SsLvN8V>1b#h`^>OH8bY@4G*JRcOKDmxRYR?ah>eYE}2!^+N=4kK)7 z|CbJf>>pUH?7W~_LWT&fUt+Pp$%rJ1(@U6?R@QGxI&Vto{+a-Xt@`-V==d#AGVDF) zOOd~ESJp;J?HfRaSw6 z$OOCSwSiWa=0|7(9|maAHAm{Tcjd`tR#CzBjz2&NuRlWC8V2w!{~mol?t%~$N_k3;64ewpOs$o%6g ztC8;mt2%mr@iNL9I=%XCie!In1-Wxy*Q)isN&V}6#RXqm+f28UT4hw1ejWZl&fYw} zrfdKIKhxgH;Y4$YAtZ>HmC~XpniyKGNJC?+A}wl&A!x55h_U8MMc(GAXlM{hgBlW3 zwO3nuwN*uGPG%QmZre-FM%WhPf<)UxBH`J<8y1v#P+V<>2ewYc$AlGU6Id+7Lpv@?VmD%^PQ>P@H2w@qPH$eV>2x8oP+REC0pX zq1v7s__sGIY&5Z32J*mZ6-yE>A^SS>i)8BA$7iJWb#D#t$7eX~=6iRu{EX|Yvf9ZR zcasv_9k$D7q|eRbRsCdHev=^efDrka9J%SO5sc*ODHT=KN2ng>WApA~b^4-=zl9}W z;7itSEa`gN8!b0Q(>b8F*xHaR6Mpo@mg|YiLQ9p4&;4E=JwbL%E&iT3SuVn*_k!!A z&qTk4#~(R7E`!IP7p>M&Y2M`!^<0&=X)_2+G`eZEh!H2H~0_a@Tkzm!W6ff|yI4WaCLZhKPEQRRil z|7B&c&Z$!wZr6M@3n%j{|IF4Wa<|{lUT&>0($dXb*f`_5=x1-br|>iBcL!tbN1x?q z-|=qtcnCw=|9Gd!vHy5$mMVCT<`CR}E;GIYg^JpEm&Mx~G%;@$NbS3ntTzjcmW%_F z?|Qcv7p&hXSU2HXULbvbD=t_!WchDI^+yQ#1=4Sn&pzMkhWPJ6;6?)dP=S2nBus!1 zaT~&g0;@@VWze|(<3^1$PPw%zyBEKm@9E7q* zme%kw(m!IxMpb%M0td>OqSE#;c{i4>_i-Eo+*^(;{m7vu%#HiAxaS{{=57aJf+BD; zqJH>@Y;Y33Q-lNvA0Lr2xHA+Zlanf?&Q9JR{uSdL8f*{1XxQmYh_17H|?R1!=1>@PB@FN%-?Vd7Ca z;v|HX_QeKXf-uKYDQ9{y4)~z7qsUEzN9X!3{f(otwX{R)FN&}X!jYp=HQ=l5KVm7V zEGZSRAGR*z3pKt4R_)JZNelR5%T9JQrvt~1OHE-hwhZS~7X*B^mGg%D0;kSxhI;2? zQZ>w1+r#szFyBne=6plWgu$=^hKa}Io?_rREQlJs40lgaUPT1Dk2XfLs-Kx6I|BqL zg8<3NAlIK{nS7hd`0Ry+8*;6TFE(T+N+XWDooggi{)b4VT~N3}#%N3>*oRbF@{l8y z3Kh@0@a%YiCnVe#4BAer22>z8Q_bF|qVcMB)oN-mH`TnAJ<@n(Pi-~#RO2>wt%~U~ zPOG9tnXhW+Y_##pepx<%{a)rb?5tJ|m=MeONC(vOI&T zW*1W>vkQAESC#ce1TQ#fs_&aBg-T@6-%I>aGmNS7TUq?M=x{D&IH#2JRf!x;nyF-K zcdA6Hv`vl;4t6-J-g2s}f02>sg>vM39)E%x9SmU)FoXv$TQoJ`Qey;SjF)6WWCY>t z@o`Di)Rd3BQO*}EXO$kRb(<=4BYX{lgD}q7y>3~<`L_tnd_@t2;Wr1ZoJ}L_pO%P3 z7|spLlMq8smpGRa6`f>P*3*2Q+QgM zSMb&F7uwn+E$Ay3*7df(|`0%PXCB7;#&RFC3$$^T#fOk1P{5PE$+FYsVi*x6jwD;o499WG zkq*cRe{K})bUKF=2Yrm;$R#E|361szJajIGOyg)|=ui@)VWa<;$kSinXk^{4C^Lu! z(WKy0N3F{YZ{02JlUvcgnqK+{b9mplDhy-!Wn5j=mtP)wfss{7BpQ9wwLtN_!LPMr z$e`<0eNC;l-0hlc#>< zPJt`nK8Wbb)DUz613@}i1$Kk8;5rC&!-y+q8girfMqUqqbKn*TJP!%PfnH!7SO9Xt zF;E2Vf(RB{9tNGj0FVx{Kpr>=u7LX>sypjLAQ_~B1z;m60Oz{%G0=TpB6<*J&0lk$3od{=pi)nGKr%=LbHF-q0GtK4Kxi*K1WiFNFdAfmTu=bcfjc13n@9p~DC$_- z{a#~VRdZ_F#5dcXujLHfOn6T>^KI6Rucuo34tYFT0ZDq?7a<8x`qY;RZ$Ig) z=YB)ZJn3u6EV*=??@XCNtx=r}Qo&-70}g<*;1&q&!?YJ9f$?B5$O9+AEfD$w!2_*9 zFEAQpfn0D3Tmknb{yE<_I*W(;3&*8)lCP@wh2zHMb4_G?lJ8l9W_&bpF3A_s>?OEH z7`LYp<H5{Vls3J13M4UIeHGnvrDa!I@V6{!d!9X4(z?>@&sB?+ z7~Z@3LOpZc^5-l*c`xXSHE^yR@9K-KSMx;4*@eo!HrHJ;Ph=8nOmS5gI9Gz*@TH}L zUG;uAtJ|kiWN9~==$DDb@e^{WTk&8nMSfF+fe^kvAvK=&)d+s=P=N;5JoPcXeS9Q} zo`-)B{6C{e@&EjP^EXL`e=z)|Kaf7j#WRT%Sq`BYm$~VYADB^e4IMdl&=_@45I4Rt z7C1}CKa+H|>8kHjLxlO}ve`ozU~;V0TVfUIk0= z69-Mrt_@mz5qRcYAKgodhd4_{r+h~xQvdQiH($4~go&CvII`s(`4 z)KbPMW1Tpz7p$bruwHZ$#CUrzTBFDh^3V73wRJa-=!+c>#DQdx3e<(s%fN1M3S0%Q z7pbkFG3fN-&iGw!b(DO5ps%ljvErnTNo~>3_a;U3um0@&E$Zh}h9={^Q-5DK^(A{=P($@QO`OA7Jo)I>0v^Cm!V`DaEIbCpN?nq!{FfUh*jkgS_A+gKWH~_bVNm z{j#C-xtB{coPOD0*)bSxtp^&_+IY`3-wn-CgAC2129;>OKBz=8(4+CSzx9T%mFifs2fz`RX#_(>BtIw9 zS6>CwC}mf(d|Qk40}DV7D3Gr{^~FwIHHfweoCViGU@#(}1LzCVK^DjZ zC&3kPA4I*vC;}vdRInK2fK%WKaAC!)1e$^bFa%_PRbV$b4XzGx$)wZ1VEF+<>F2=$ zun`;pXJ!3qUxTSd!x&D1O2bJLkOYQ+1z;m60O!CR5Wsd{7sP?SU>sNsa=Uv{r=8cy~?azFC1iXYVF58uURSG`yZIq2?eU+qdhC9?#!!7e3^Hq&*L5eY{Qn$aj zb}lhZ_G+MkldFchODQ&Z!r|;OoY@}631?@0>TGReMWWYPUxeNSZ@*e1W6sife`U$2 zzO_6uvF1^*SHHw~vFZzdsIg^B`2pc9!dzpk@fQq&;QCrCr>RKCN|!Gf zO~uNfFAVWnJc1cnW=g2whZ#(JOzP)fFm}3YQB^uUq^ORt4jlTL5zcT!D&|XHXLn;6 z@g-xGM@gPfmr3@QB+sYIO7w@oSyK%?xUGSOgs_?pZQ~{LJY$T&IbXQ!Jx|)y<;`7F zTAuS&iFPuQL_^1oElHx9k_L+;e2vVqbH%o)#`5twg7O$aNn0+zp2NJEw!9=Lgv52% z{9O93q@{+~R?fz<^ee=gB6fX+9Qvx*sK;rR=OHwM@W%?Ne;$2*tSHf^a-o)_oF`#x z$+Yw2SuI&@KKAj5tmTO67pSh;wvrD7)dfv`|LLpSJe~Tx4CH}R;0m}8B1Ype=mZ9Wbg&HMfs>=v zvGG@^@9OHHos*>Y6)cH6C*>zz@l{fjCF9il^zW#dTVQy1l4O5ZoN+nw)ptaDD}>#X z#Phv_(D8c+??8BOl8kf`b}B+Hg#1Zz-bsl57ldsP_Dzzf{^d|LR}r>D*gr{jISIcg z!VU-rCP~$+4vCbj5b_`#oFwy{gpUCuC@q8gi{69e04dItb^5_pf`>u-|nWhMPAl#oMTb+d8AT)aq zLNML((y_knqCQ`xoasJH#TH#PBNQRmA@jVbLu%ulbriuN$>ahf_aWJ7KF*kr+vbC< z7v{+Whos4MgRQIiNHZUq=0okf^D9pRh9_sPWAHM~S~(JVgIMGf*oqm_?uH}Y(-dJZ zgz6cx)k(Of2>T#Bo*`v#IwZQ@gs>k%T!u_^680&=`w)6&$hS^H%#RQbKp2oA&;IC8 zHCGW1Lik$-w{;w>`G@RmlFy7btTCYU(sAQ^(5o z+r<;w9O?cO;zwbaHBF}c+ z-_H)ev^z+C0K>g$(&&yuGEEUqLI|BME1ZOjitr(Xj?+c|#Ub&`FAzS0kT6}w{Nk%! zC1JW5KQ$emL$N#yDpGE6FHWxJ)V`|(RAr^*FjjW2xlO8XULJejx^AIgYX%IQZuB{Zw^A5BK!kFlNqwYNw}y8XCbth zA^JUMSvmAEUv3V#=L-ZrhunXLnV52W65*eJ&k_E8_sHZg;2CW3xcL6@o+G&RekT#W zgki3&Bqbds!+&=uSq@K`bMP!KQPSskhZ6sNlzaulc3a6ArKIzHhmr~KlsOO2o)RUk z?mLuRQ%b&u;UBh=_{l0e{%|Pi{Rc`ez;nJtN##ErN0^h(8J=03qm?`W}8UB|;Nz7m5O%XgbXD)5azVPdRGQP2!yX6oA zmmxlFD_B1zth!wHYxYI)IZMlHvHG{LBr5p?TXbor7902{&Z)L!lc{0Vmll->N|+nT zE3k|;eNJ*~kJ{og7h>Q$h?%y0;Z%a&*`wLZ-#NmZGgki|o@J(jQ*Ny!=o26Y{sr+p zTS0sV3ZC#f6x>z{uEKM0ru^w6@&`N)4MV+XxCZrWTSKAJ(7@-=a2X!`2Y9};Fs*Wn4wQeh}gKd;>y#TlkC;UZ**d@MC!NoA5L- zgxOK8JJRqO9SuK1ea_a9GMxyN4sk@F5FY&&JUuK83v@>WFet_bZbKbsYq&g}1CPGE z>nK2b;L(4AXVNUW6yk_LlTd_zhLGcQrivukc*8)I30qEQN;uK-Fhkc|lYnWZ}%Pfb?}c(sU_|`dt{qX3L>c zj`##iqv1CQ4Ia=CJ&X9fP}&inxiISYV0?78N|DO)KUv%XSbm2kX|~i4X!h2U92ubq z_aXG0E!j@OR}cb!K$vX%etQ-TLX|Lw$Ipamv1R^*XTHTlBUvg;v-gGM$UYbXf5C9n zR+2IsCBHkB)GLD$#$EbHB}#s9Dp?ML?uOyB*>a?eBkbBk5IhjB&6Y+FIS6SG0$vC$ zUbpMP>v-F~U-2%j9J#E7eegW_x|9mn>|H#3V-t=r2S({n+rm3vXT802&=K+D@aQ@` z-CviR;hMeIAxByUiA)HD)t0d96}c321Z^7(dMFGVUzaa}4#}9ZcKM9x-(P-JN(XUjx7a`qw&dLN=J3uv0>IEDAX zqesE>#9X;l+0l$Nse*7cg#Na0+CqdgsyKY!29I79p23E2r2JS#vro;*k$O>Rs0MYO zt--yBcKzQ`jznJ%k6s;~%(*JvD#@@Yt#NVeBcq|lK;1D{+C@7OZI&X`fbia2+3qCV zR)kmxpU#!aRUHy9R)tU#!o|5V+e!FP5o$s3&y%03I?8v;Y6QPFgz$M*(r3Ow%_?2Z z5&SLi=yl+!G*3RO<`9moj&NNFwQXVdVub(g6rKx@UJssb^JG_bhwyJoxITp5ws4vf z{(E(Y&qHGnZU9fpJb5$5A^a7Dz{3zm*}|8V@H;UM;b&?f+z_6X^JGj7hwwfKe7Wh; zH`u~mGZCI&!y#NR7U4(W**Z_U#X5wSLkKj6P-qJmD&gU=4q<;ygqy(Qn=g;nbO=v? z5O@?q>G@V_H+d7`&NUsv*Oc&M@RXY`WotQvd)Gp^DTEkXc)b#CP|G3wAv}6Bc)HA& zpPa%iYa`qoLb5F!T!L`v+796@@aT`j(|5jnR@>ooWF3TCKp18VPgBDGb_&mhM{fzw zhWWCqjzjo22xVG9*kTFO5ALty=m&?^Me+$4cFvbK>uR;@?X(z`Sxea#4!cVha9?gx zvJd#MT&}BCbRU-A>T1;p>Ay~Y@?e0o?#t6{tv1`rk%P!^+XAvKLxZeXsW)iPc&gwPBbuNXtB zXmyO&VuMIs<0l3Y(>_wqX5DDUNj$*&Bto*g1y`19lrP8Px~#Dl5iDF%QUH`Csz44l)*1x+EiVyK z#&k<0&_t^gj9gJdd&s6$l!PW)AQ)rORCx+FXhWMAA)niXu+DTyDm#9G6gJVS5X+0^ z<2N4B&Lnwh%&TMByKY$LD;NSz9yJ8IJZfkiVg8zHJ~o+-#~;<6rxrv$rp1?hc;os@@Oz)5gKvs( zJUlhF$;76P4(p&Iw1ZG@n|$vi)N4lNY!9IccdI)tmQ@B}+jgyL48~!;psw$Icamlu zY2Hi=_h9%nzN@a@TnqQUXOj~6<-x++uQ>wyY}bv-6)UbGa9Rl*uu1n733F|k$F=$% zth22i*AhKn!Md66W;Q;qh5L&P%dFc~-n`I}Qz@EyFt!>D)my-D|3QX?7BB?U^QX7a zhIu>{GvsC~!crY`o^j4y(; zFfM9MP$feywI=A84NJArF1ZKE&W@Zf;A>03Ok1Ga6>09mXxvt->%shYsW(%kaWHr= z`F)bek98Ol-2XNuL!ZQBEPGNd68nDBC$%W=J$^kB#jjLo9&C40p40|&uEpg}T9xcL zJTi@PYP(1LVQTxsaaw{0i<{w577U(A(@l>GptwIW1f^~~9$`Tc zn8(({Ykk~a2__Jsh<3PP0NdV<@W!>%;@nM4!YW0;&IO^5n=+}GYqrO2@C>DZU2g4R zX2*{rAFD*wXW<`bIcDMLpJdno+{TOlb*AlZ{l zO6x9gGaXOtqV@4I`!>toFM&UaE z$;0fJQqJf1vc4xCCp`!IldoIs>CaK_o|fCaRFI%}n9&|eqSzEYhYzbwkxog7Y_vtj zB_Wb)isVA^FdIc=u-hYDUqDSM2wkCRn;a9 z=!rsRFNW*^MG2oLpY+t4dn?Ve_^bEAwe~!dKcN@=%sCeIqJd?KVHSY1y-2_mTOiOI zfl-D)9}lwxLw6RAUSG1@O^Fm)3|yWUzfg| zFofxaZw@0_>e;SMhig%OdRmv-GyJG|jA`m{ZQwIS47Torh%{DfK_@T}q=RK351ay5 zfI8>45@-q%zz~oDR)O7In5dPT+L(3xPGB^c1M9$6rF0?Yj;c_{+-LBvFq zfdr5WW`d320Js3|fQU&b0|{Utm0lMu4bFn=Ag~BU zpabX&(m@v34NigU!1o3`pf%_V#(^x53r>M6z_*xG1Fb1Y)*u;-0}EurXf3vK>JkzOtOI+&S#TYMXYGvd=FT3YRoCb7 z+3cFTQhSV6)x&f9AEEoR$7*BPM`G+&pEFjAXf_|719#02a@lXzJ|*>KV^?*Cn*!o> zxypMeFcw|S+DZ|quZ@qz%!|*zmfK^QYw>th=f1J`xO?ntX)?}mGOk{D$PnP_1;rFo zDiA4K$7yB!#X2Q8mC5GWaasiQYkX10LwnWWu4O(tzRHC4YZ>|~v%jw$AM1@B$}ONN z<|lO_hA-=3f%Bj#ckxy3K{T(mm?!mK!<4gt$ey`pMpja?vHy;Gt=JAUPgX0Qh47rS zc~)n$(DVRL~1kX1%&*f~)o)7S3DxNps`QGMn$TNohLXVep?B%15WqhcGl4kETm?v!}p*I`xgTKq*Nm>oJ)!7F%||<*YRNOwm%K zxu`F1G6s!@|1@Qk?L;$VK1L?k(&4Nd&h9CgO~PCyTi#TOy(n#_VE1V0a1J$`gYWy> zyXVQiDHsEU^y}vGN`r40Uf!Rg1^oPCxPsZkNO7q-mGwvS?8ABT;#5S~im3NwlKA>m z?Fq}cH%~rP6m|yc{h>_#$@8KlWoQv0?CsMhz|oGOK%%x;XBV zq^;sGqf2IWUu-(pJkP=3^ZU%!279fPcDpq5 z61fX=wF{ig!QuMK48Zqf9BMRAtK>COl(Shv29kXwUw-@f+T_rwb+c%>K{7}MGeHh0 z0M~(UDP0oi08+tBup68LcR(PU-T@?labN-13r+)<&@+I>pc5DZGQcXZ8=MkX2p6)k zqkP%U`2FteZ2E)8+5dQCrPR*Ws(O#GSn+i6bd@A7(`tkrwS-hLBK=l! zLS@18T-jK2r4}JY)?1W}o~QdvH?DCEmBqzBN6&WiiEQ!Dymv|k+;x;`GPd4nOSNq+ zt>Z2+l=Jiem3#%?-Qf$K=&a;>xbaS2;Njc7%Xzg|cAk1YMP zRaYLDSy1#Rpj=od+gE6{gBRA7)Cr}zF1uvuqv~1*TCU_Qv@0)hcWvA)zL->JT6*fb z<&(;#nZK>n0{SIGTpGR1J&to$GXH#BK3s|Ct?{Dndb>KVqB^$0bQ#P$gc;g zV}@BB)h$#))dc$p#>4Gz8T($XgL72A+tq6TfmeC|P&B8)u3L>w>erR| zH&<(qx;;l%<=0rN)pmPTav0~Z3|z-l)r`8^l_2XcW5-&&PRsHdVOEC`jb5+$JWs99 ze{H>X-tFJcg*j>_^@QAxY)%mk~zZg2tI0pZI@Q4j}ufpm}s zuqV8wJrXjE@UP-*7$Z$OZ6rh_memC_*Rovwy57OfpOvwMHT9%y+d& zAqD2Uaa`hsO&Ip$MJ-Xtee>N|lSq1)TfC}oHas;PMk|Lnhr?p!Fu>uEryMdI4yTpF zI)}q8oVD%zYicE*-h8QE?Hau*@t5i4NUsUgL=KEyzKEQlmt===t_k-$vo%w!I zy%(78f2j8&^PQEBD%m-vdS0cv`OcCD>dkl7Jy37Hv-nX_(sPW&nUzEJiI+|0}WLPAkfRtws=TZ`G>H z#b@-=goF1NX$GHrN2{j~r?>@b%9MAs8XlgByZI8R=pF4NwE^20I2UZwBJ@dE$< zT77>~JyTf)x%@7lag1xygl|>cyU`oirM0qJxZ%=e7p>-KXYy zd!V|bj%Eg^QDjGRowAJas#*hMB-v3N@>fL*H(XU)U>uUyQH*uUvWBa%PFc=)jk!m| zx9VM11v{$qQmbg?4d*nqI>{S;TzglmCgb;VIC8{pW-=Y6-fm_q9UcABYeNT)8T7LG z6|TyFj*_yQv0wj(OG2)6b(H11wQ7-0$&{DP9!+IQM>(^bG3k#Dt)#a~Pe->@oypm- zd1V7W;m~h-4L;p5#)xpJBH2;e?7_Ppe6pgPRY_IFv!lGahk@y8J|9ueszYToj5FT@ zwI|bm*+V{kM33_K$E50e#WRE9GU7dE25Dr(bxTxIRa#Ci_c7y zdbzlosYjiBt%23k4wv5f@SK9Df`g};JUy{^ZZljyhescSUk^8xKl8Ol!G|s0RsN`op{p?@=X+Ilb?BLaVpPd4q5xlwJE|;Gk$qF9o#HYeb9d}; zxs0&>8b0o7CZ!HI!rlD+PyGfz@l`YXz<$^oBxpF>SOaF~G2lVBBiE*#eChh!P|?+ur*0?NT8 zyn3F2s!rKanZQF3N$ShNh-&Y1rCaV-#L zlT;e{Bd%-fp8p9w|FM(8>qjwggm=l;Q-( z*fGI8DB#pT2u$^pS|#n2VwQ{lAcV;$30#5eyVeuY-;gYEc^C1jqEBilmq`3Pd2n!&rZ!7gba-{gHim(vEk+!nt zBO1aZmbWUAh>B~gG#RN^aw_w|Dc>Ji-;ogexiDN`f<+)CQ}MF%c!jOVy9* z_3ef(?PD~)3GbkGvf^V$7%oEyEP*hoouwpxGfJMQRBR2SS^5OwEO-vIlZl^b^pNM7V3an}@ug`$UTV*KVK4)IUGbo}z*3_$g|aqPBH=8TqLr zvG*xLHiWV5<=amkfvtBMfxjNUTE!`2yd6s9`&Tc0{ z{292G!xhp&hMj>cq=U(o=j8fMajk%>atA5%nZx()pFvm&p>YS9@)-+YJgLnkiTsCR zSOvq!9i;X@9Fimc0bw0#-OV7bdit$fdRFPT!S}g% zi9TyI=_zN)tTpJ_V{u5z2N(t4J*x$Swv(z{Y9Ntl9JwsF&N4|zG$&@^pBwL73Sl0j z-PruiS>v3?td7x6G98RTS6+Zwf1+@LcBCx&Tq_g&yCYPpc}P^B{Z@=jbi0fw;NqG9 z?8==e>ShT|4Y=UsB;)7>O)$7T$``&kUA2_i36LmFzR>D~HGirkT{KBMPvti*-^loa z7A?^tDj#%3jF4?#Xb%y{gIvN9?F>ljOX@;wb9<5+gC)xCFSJL3-cBXz)ffz4zhq+` zgNHB4ptU4yTqoJ^B|S`>#i{&Kk=?JR{^mEu?)~z|mzsUn%5Z6Oj!apH>>^7>;vI2|T(k!Gsucfu7*9BQ&Zf zNRoyZ=y?*JEy*8cyiGDM5HX5C`UR45pv9n~ss`mrj{8@VWZwnDH&hY13tCe$w$?@B zwUKyzmLQ229WBOk2!Txy!n#-~-8F<>tmvW^UfFh1&6~QKvT-X;L}Q8&-9<`W(vq#) zAcxDKODNxrjuG8u(Iu^I*of|?E+Z#oT9KNs^A)enW>Cx|=_Jmv}h*{Tr+@wrs5;WOI<6-9r-jv?@5;l2!hz z4Ctmh*lO->()9`#H+PfcMT`PM`*7j(ts>@1-9)>rRSP!nY59nh%8YK(>@qV+^Uh1^ z#${4!3%)#K@yWDz!lG14`Q+qfE#Spn-Cz7%@tCXOw~Q;w(=lvh_>r&8_*W z+qFk-mtqp0URodM(dy@aTbgep{C_v*L~d7%bd5$ZP)@JQ#qF2Nvr>^%PUrHqrZTb| z$9z_3Du>jQc}&-DSC+*QdQ<--W169EqG+;)t=(&zn)}#F9K-cZcl`~C<>;205Xb%I~kyZ359>%RV z)stcB$SA$Ohf(Q@D1Ez!LFlv5gp{%7qG+P1MwQXf8AO(ELG5m3J%Y>0c2{FWy!PKxA zqOiWLPkyY<9k@lx^+?a6RX#D`FvnacoYO-+tQO^VOI zS5u`2ONs_gpgR5 zCj){{>XN~9`J@Kh@9ODIJ@o7-XQN>~0!S}@s2=G?r#-Sh=|vxXs6JV+09>ZpP6}VQgH~|`i4xlf{0L#EJZ~@#05i3~$0Ubapm6TwtFbSGq}6P57{W^y$OWgtRS>$y<*E+iKrb*3EC4y6 z09*yGwJhp`)?fe_50-&Ea1Pu8;p;F`gCsBnECxB?6u1IH*H6Wx^(@DL0bl{x2u^`3 zAg}>XKmr&DGQcvh7n}xnK;SJ>4RiuSKn7R`_JRxG4v5%Ds(=JA5X=Otz=5g!IScNB z@J%EONC2b39FPMFz!h*GL~Vu#B!g72803JHpa_J&O^iVT7zmbuJWvGgf=W3A79@co z;L*kW$pNRqRZx8kn?67TqeQajEekrD@?9fVq(SP`dJ4c3~ZS_*R@$HUcM_QB$5G)cZ_ zrzco_6hVkbu03)+CP|-oy=s*nmYnLshj>Xm5RE+UQmw7GbFt)iO0olzc6z1Y+r?g(L&O2%ZtiVU$?P^&qS{?uC;VM7 zQChXv6TK?&M!m$4`a&O1RXNgLui*U%r^CwWPJ2Dv`>p+}dIvq+e{Z6SzT4G6&In5y zNgedYUXnzfTubx1s)OFkZ${MZs%q|a4(~`~N>uuFq{S!X^E&ENo~pE!VhcKeUSKqs z308r<;54`jT<=iC!NZ^f=nK+87RY_aIN>gr8!NsiVs{#O)Jk?6x%I7=3z(afV)J+> zJwpE%w6c%LnofG7VA)5^6?!!q@uU3>+4&;F5FYB3eYhvEN5fHZ8*m#>Q%Vh`b?p}Vsv$#CMSgUj?&%9!AUtqL1v;J8yv3+=?8ALPz&FQdLY=#K~(9qSbj;=)k4bi&*}97*HjkuG=nAa+cAv1^_(6I+D(9b0|=HoE_ql!4~7PF2KAiAiE>NT$S_j}-GU zEs3aQ%H4OavZw zc5tdflqp@i>aoEd4!wA#6f|eub5&RJVvVrL_Y%3CN>cMs8@$wNJ@4$%;a1Ac zdZ>DTNevB>iE{Wc@jAMUL!FfUXlD zUy8KruGjYPY}HebmTxAoaeQ%i8lr9~rUz9er6-;q=&nb&v*b*7-QMSQRib;K7&**WyxjhnVq?yKC)mSAtPFz7fCB8((cFy8wxE z;o+)u>_a4fLbU8q8QDj-PY>XFYeo1O!l9vZzK>ozcxb2@PJ8>vG6}w*$I8{ddYDAN zz?P6MFYvvpIiDn>py_uI?>StyzM$Km(O;Ec6yX;L1BXl1zNG5F;UyWRYUOh2+Lt&k zmo)Q{X+CzEk28Hq>PiFjK$tqC&ras$;(n3BxLl&mN6Qx}vDH#b6syErE<<0`>jZmQ z&MFsGGqPNr9@9Ql>wd^&bRxjWEL}O?F}>J=$Ln#@J43sBx?! z<2Dv}hT!Y_7HegRNl{g%PH3ov570xUR|*Ng>i3XPd3XSsU3;XdQpHUbzZDO*E|~)e z^Ig1dHd6KvAj~{pdWjh*72hWTbOoC^G@!t>QZBb(UesFAT3R%_30Ns-mgt>Hi%lu$ z{SCc$M#(2BdLs|d`Y$sns`QdxNvk=UKyfV~mXw5-^oU>s^&8c8=B-kVk5Y5+B`PC1F5G4UcJjK8kCyra^?v5M*Hzi~GD_G!sP|4Y zlvI#LyTWw&>t#Jy52q3pQK$ezQDM8Q5b@KsM$R0-%Cts;Wdr514`Q517^Ihy*9KBt zj~DAOEgWkeOyU~@Ns6`DE6$}!g+WxCa~8jdKwWqm6$;T$yW8>LTDhUgWu2QwhPD)EEy@jekgJVu5MCWME_n6Xqo z5#)x7(D>YUozWF&)eHt>w`O(Y)!6PEW4fwwQw{T#9e?gv*)~G2rqwiD z)E+>0ExDmwY8x)MU(+l4Tj41ggQqc{_!~>ZA$qys6)Qk?@~)GvL+FJ%jil_3AEJl5 z*U4NQqSrZEKF&>4d%%oBqFTjuQV0v27tP0S<|8dzuV`EaxK5f3HRxT2(lV}-_`lIk zqz@%A3&z=*ZW^=KnTeUJXeTY23Ylv3*GbxbtTY#fQkP<1HRTjdb>Qpd57URpVTMP| zhB0;sf6Zi4jiTCyfX8lsHJLMvL4Er85|34}BJqdOq8zfEm0q<+VVztv6>7t2_Q=AD;Y`n3O#-Pz z>4!-rA);m>^1$FDEtQhQK3P31T~?%0cEi$3bg33}y*ZdzZw@AS6b~lWOA`u$8wRy~ zRPFcUJaJINNEMT@e^iZrP+_`IcB;wUQFJA3M(U-d#aOPYPJfs3F@Qo6 zeA)_!-K?#b_^D*mVnwSxxg<`iS6y#rZ-JsUv}h`+RUuk07e^W$X2Vg$l-<4hjtuEB z%F*jBSA@SH9LSI(qey}S8K!!B<$r?&#|G+1uQbB;@MzuM({fctj7HMM7T9jnBzrW| z&2H07$yRu-67MaeMg*Ff-+!x~=Phxk=?(njEyl{?9!ujMwUEX=DUHUx#aKKUn1=1{ zQ;Vg7q>R-gWObTeC73+@!HB=5HafGcK*)kw4w{PiTk=O5M*^7J=xH*>5LWgF>p9b9 z*ciROKgZ&)Et%s~5XJ^7$+2;IxSYD}EhFEL(aQ$UI#i<3wb4xHD8lGJXVWBJi6^w@ z(#-@2!3!2aWq@k@5L!U_%^0h(mSA`Y#-bVW?O44=y+t$ZD0zc-8ermhm?041 zx80Q*<@Y8DF68=`xN(f-HmSyhaosqI+$I?`j!HR%i{b4NtSSG^m6?$3q-vZRz-%@L zFq_Q*%w|M%JC>_%ED5JlWn(0)8 zxKV62UOst6K%DS!|>V-Zv+RWiLT7bh44xLOk_eHvldv{(`+GGo}Z zxFoiUlQTBxH^ta7pJVpa1x2iS=E#Q=DH`@jH#mu+p`+)rB`@oDGoE{Xk{lT% zU&)xHH!qerh=d-3M59dkeiGJ=Mw$OlK5t7$PbhkZWy%-ndL!?!%>T{17bnB!hizx3 z%$}@28r=E+=3Un*=qZJs8<{e33f|rLU%hirB|S>R7V)MTD><_Vqe17Xde9T`ru3Vt zR|qb&NOpzZA_u2ZiC0afle+DoscbN4YQ(K&;C}$cZI?)+3`W%Ez8pr>iVy~2`x4oj zq1#{0T$SGxp$vqgB~oLWgOD~2!b1?sX2}XC;TnX9a0nf;%)q;nQd35b95hB6Phe_j z`}pE?;>ZG*-qB){uK9e2^wxBm1KY_Sy#4>~=C~>`GYCdm)U3^tXJ=3Z*IMfArsN&7 z2&!G;QulR=bZQcfa={GRx_1OSNkvUn@psg8Ha57$5>_6os{W3+YlfCHR?Xj$hO~0Q zix!7Uc2%F>k(8MXF5Z#JiW;-jjIyGt8PGebX?!I3PPXZ+)T*ld&VyCC*(~BvjyN38 z=35NL{yZ1W(vynQ>N~{{0mHA^Qf4*`JloEu5a?2(7`-e^9lV4U(3;S1nT=R^#F~f_ zt0>p_Q?E&}j5m0zEk>9pl>ts|9sj>{jd-2xs(`Lki%ll)rAX$#&Xmh`QZ3J3w7KH2 z4D&c=Ym_sCx%T(|>-wX`y+N}%gsmd_S}c=(bM*RQEtZ+yt9)}wlX(PpT?|X3P3O^E zRbT4yNwRv2Q*Yzu>6IjWuHIOU-RGjH5{lkmF2m*)Ta1}~D?%iMM^?!Bxs;4YR+RXl zvTnPad66l>t>Iiy-dGK{wwr@89>s&Q?dG6tyJJvhiJhFM2asTvQ(k_Ur`ARMJhkT2)W@zgeOF{vw6@EO^C>vnWx{-;EiIf+a4QpBStUQrcT}{N3m{a1 zaCw!PixcSoy_Z*c%oA;M7m%uUL;9WK-N4kT{Aww)&{4lr7D9+ZN$u4#Zy^m>?bQ$F z_97`v_Sm~9u1eS<_}@ZNyrGDNx<$0UcHLbFH4u%qZk86=wx2cVbBkzuY$vWSHPUvmW8gVW5voI& zutv5nc9ewMiVy=~;u@)(NlBQvrlcgO+MlNkTh-iosz6}Q%VbQHr%W>p!!wD}3X5Gu zNj0bNWwN|MP~Jpw4HRdsm9}r{$;An@96}%#!kx9IPtx!Jr^;P@Q@2lQMR*CqHQ|}J zPTDTfTSd=XXJ-kEB%LvzfmFPEN4d+kENVpV5a8S9jS18H7MnCYtUmT#sRuQ~NgA$JgNBt@5cbHn zm3o!1Jq`=P7@4NX*G=*tD=`b~Q8sHf&8#ZkQHdRI70K5GUm`cj^i_K8u*gj%MNgBI zH4M5J7twCdTtf?-5$1-!0ZrWLCZD3zT1$%!*le)@I=tY57}0x+>0uslG=;%zLUB`m7<4kE$%( zB#qV($Zs8itSiCI1Ttd{0cyILpsiDH$-HqOP1C;w&M@%hOT&#u;84d=vj)$LrVARX$l{Gg9sO`41@kcqX8Jby zX(Npf&#IgB#l`K}o=q?`h2ht2a%mImK|B-R)@#eUIJS-NHK$dE0d%i9a>-N1(7h#V zQ)Tx$O4Zm`M{=8rY=2v?AO|)(#ty%1#+zn%^Wk=>`ZiOl54S&9(Dtbg1j|`>iv9Sv zX?sF`-J7ya&ihq)+X_*;?BW`=J=rHN&OtXRYNV$RA4uY`yJsN zGAL!>(2;67YnJ}~l9|KtlJ-dFjMDWux;o~`y&S!*w_~0$ajWRulzmk)x4_l{w#qwY z{}x9NU4AQsmJs^xl(t(Pgyo9R3c|#la>Pl9euuX72?%9(nV}Z<5w#ig9X%LkI~fs? zv|K8cTNdVGFS5gX18KcA(qHY83b}go;8&Iw6+e}D2jsbFir$tK*96Nx1g!k(=A~wjQ2v z*?X{=SMGoz4u+NQ$<`eVy;i>WV3r?}?{+wnsa_t591s6?i%-@c#S$<)kKv*1WDgGy zo5RDyW(81F1Wx!ghVE*Tz`J2CQk~*q^Ri|&=*Lx=jFjz=S7laJ?IAjpkx0$Wc*O`W zcXHkKS1VWL^PR+^9iiHiFMsaD*taF$iiLDl-xqY)g{}Ii?Pe9&0vWLj8;89Vx@Q+U z+M}c5Ub(c3l&HA3B>Pkt3RU)*VJK8~FZP$bOHLLVUoyz}J!*{fF8*}2w5{I*qpbN|IeAL!nwquOc0GGdOwGqA7(cT?)lGb>XUP z+078E13`XcpU3H2PLeEcddcOHp<4?WfQpvUQs8rKnt--FjTEq2v{tKxcuJ#_5Q zdvgz)nXbymd&uyP__1KWsZ}N)v$t#4eUD;lyQ^GRTMLew!`OnC$l{~snJYZhgv~f} z<*0e)%F(4M>YJzc^iT=ihnCT)scI-~tc9pRa5!8(mGr1Yn~#<}q?6)g)g*B9YVP9*>X%(AE`EvG$D;iA`B-*a9W(>4l2GO4QStAkRNG^ZE_=!Q zr-)>=!}8i*y)CZDz zfF^F4#b!tT11UT}M)f+3;@nnzH+=m7k@?!-5~+DXVHxODV`9ni`M4kx79+*_&hfk5w=-MsFk4pO&Zj~m8Qx2uV{KmB^y5RU4|mhI)x zn_LdPSU34G#&4P--L6w+A!r>DlI1t8if-2oBar#mBUC7{6y7UO=pI>-Ke9r|5jIt= zGNZ>At1A8pl|p*?F|Zj?Zfbg4Pzi69RV^~4x!*LNxm{IE+JH!C7|OOQnrZ*CY1x$_ zjabdc1R>i!7_9!ROzL2tN~{u6-!pMd{=_OF&$|6thLy|Ee`EdT%iIc%T%zGt)#!?4+A%pr$OODbfgqUKa8`XXb5 zhB;K!*k>Y#<}hh*NrfntGPQh`;}j)^IYqwGoC;qwqR{YvUiba^Y#)6ezu*7y|L@`D zd4I0ceO=dm-Pe7c?(6>3L62ZkbFLw+cr(`zSl2ML1=q0dYRl|FD<{^s(9)cJSF=R$886wU+H{*^^z58-^YH6YQ!{+aXb# zshX{@uAEHNGMqF~Wlj`DGov+OTdhvJ?QiRyfuh#j4p#HeZX0REDDp0@jn$m9+s0dW z>7u(d?oz8sWVhY$70J7``Hq~m-o1BgL!6H2P2T(N)kfMKuWXi2?xS4r5WRjMQMI0Y zsv1hZm#D71U+ZNztcQ$>e{!l(!yDONqh_SGUfY4}{N+1o`G7VuYs;ssjz^bK#7Y*W zqZE{ea?mnVgbtxHq<_XreAEv0Lg~nZ7N9~@g3h6!&sj)?I-Q_99n?#Q3*PY!WgY;f>N^hFAYsci_tbziquF%1Zs1aAyjP|2*sNuJi1vC!jpk-)1Dnt4fQighS3*^>nmKhD3SLb)*855l&JTPtUg5$ zoGZ!dMZmf0J>Y0*-dPKm1hvUmiP{k$rL%U2Jn)F-mUMOW97oFKBU)`a-B}Bj`HyJf z7<~MQ7VUm(j}@@L6*yOZdPIB3ULaAAYH_YLMB(*)^2noF0|(@lb)NT+YW`XD0@;kK zP%o~2-e-j)vEMVPSEaM&cKeM~`%ZOHSYpoZFw$d^-CUfmwu&;Fwz-n6c8yW1Hgc`K zWK=ILS2m|HR>bZW;c}?67RF-qGo7`1QMq=T8*B4#RC-#*sIisf7cB4YqD9NO$4O*L z7cHXtjzg8HQ;peNyL9;3(axIQERe6e5c@)6fBdj7_U7x?RURYuej^q8YIvPz#@^iV zW}dYVPMB$G#$Cl|o)!1%<{@#nR*cM3Z*9{cdW>enJYgdo7T$bs=p0vlT#Iw(9jT0< zy1tx6880ujjQxGCdGg}p8eerdX&I}|qtkT#+2dL(_u1bnU8}+|PtL1AZUh*s#1oYi zj2}E*=~`VDPMP7TZ4P3PuoO=7T7U~RpkcX?q7*HNc;h6xPIInSJFK<@I8|587g!bZ z&~)j+Wov%cJX3kvP}90+SFN5E9z%j*A-o6isy&I4x1lQ~?`y6~tF!WJR|)Wj4WUo0q)o1{s+^2ec9GS3wQA2Xb-KH`^rB&&zIny z+`E7KjQt&``EobLb>`bE?~t^?&zmC_DzE0th@RTxMDFXJ6#EUF%yYqtl)Sx-amcLE zT4T9T%u48XMPu7;li~E7ae|=qfco5r3M9Z_mfx@VX@|S z>HlPa#aGH=GZw*Ra`Z{9jXSvPf6bG@y>R~x?i-iM>|UCGMM;7Dj78|TSmgQwkmT)j z@b7v`bJz77sg(pt+ zu&4356|dU@yhe&%CB#3g$iy0MT;JiQ^(6^;hE%q`^uMMu_Zi%OkNaMiWG(LN_Ns8t zDy$kjW5R8=r%1tY!t1T&`-TIldV3R@ZFr3P!e&){hlIgy#Pl)jq(1^oh<*q1Z!!s&`D{_Ee3#5X=wu}xNiTvTp$9yBD`7{cbNRw?)eB$$z+Q^c*MLhuhhINw?>;mJWDZV0&;7x*rE^uli0r zde=W={qO(+Ie?paS7qb?&HqXWw*?kqKVq@N=h@cz$=0%ZSJm)Nr!;}7BjF2JB&q9Wx$+&H-%#Nz<_dj zL%I7m?k-lkBLe^BZuB5B;|T5=T=!*0Y6+QfTUe)XrcLM8eY`lv_y=}fzsJd@T91VL^ zi+iQ8+-zO?-;w3!8;Z}9`23|@nhg!8Stno-dJ2p3a$js`?4>!k`$XWqp*;VJn>sh7 z?yvyQ!-nDcH!RxR@Od`&{nPU?+_+BT=E)lpGCbh&KQ$bSGgvIVDU*f=WWrWuaTbf! zxA@`&A6v7Q5EV$`3t0RIi!W};voFw0_~MpzTJ<<2)$EbiQ++4i_FtQb704C*YUl9V zlKqII)3sPP2NezM|BL6Z)A4*B&!6D=M7rkR7rH@kN ztkwlu-B6y&@bnEfjYkG}8a7gk3%`iXc3-&~b1p3AlcR*!(kGl%rU zti3E3SiKo_-z~6u1hvgWvqunN9$r*#Il@7|7in*|^PNy-uzI#FkkpqnYgOq2S^Xld z$U9#Qk4@**-JF=7s%$9IVL>4&i=dT#^SU_aAgUo>JPVeu<90BVatG*O|Qg~PMvj3 zRGF`^j#co%s%K<|?w`^u5Mw-fev>?pa{2On^dYJY)e^0^sM*TRE!@22ce7f#*)d*o z2b)H+`c*ADZvyQSW}a>I$eH6t5#rAlu)T4HnEE!np|y_|Y+bh2m%98*+9%_@A%LFMCA`ciFLv)@9=>T1$7d zZpFyoL|^FZ1FNmw7n+4eGOT0zEiCA;j+dz8e2yjkg8dHJoyO+LCF*C+1qNaBU!^a( zQ1vD2N!VpGAoJ^wssp{y+Ei6tUxHVgs;aISZy>5e)$Lj+6<>c;S8}1bwX(UNx4N39 zLq_K_%`@PMnUH|vvVh~TiIr{=0*-qG9A{X^6DLx37s|U9Hdy%C0=oz&M_5&f%2WUJ zPC1czez*7ONg7+nv?%dDo25;5s3C}>*$jjKyw5v(vbHA3as06Nk!jj&-LSfdc3VGj zzt2M9vN>9&Bj>DlRQAIv_JU9I3bpx0P4k4tJ;-5@)AQS>}c zUp?hbZMtFgdn(MzFmuq;>GlO}%K7v8LGPyiTiWN;Y`F^w{PbH|6Lv@6@D9h#^9aD| zh^Wu{r9K^0!&{Q4rQ01JUX%_Cvn(nCe47FEUYESX-&OCKxOYo#>OmT_KjL+*; z*gC^IckC-)}g+8Z?4JKEcjv^C-K`4-<`kpDI9_^;FM;WWf`TMK1!3K|M zGpWsd7bRco=u{8r?q4t&l9{hfck)n{R;NSiNX%+}spqe0w?+L@&s=^jaq@_@j6=V~ zc!mF0KEE6>LEifcwEG-Rs&&iJ+%*`#Jap0rKXw zryDGX&qABi<{1uoThQ|gbig+t@4|Tm2EmUYLt>sUA@3PwdA{X<7ll0gA#VbCN+B=q zc*-E}>3GT^qlljB4VXQLO(3t3csfAd6!G+ey!zo84tZ_Evn9eh@a`-QnsLBlLC<~gKKM9f z`JLxqkR@lHbl4GQLRO4<-h>arPatb;JnJCqTRb};D;zvWU89wHS zU=KJ8rb52h;b=qscS7M_Oxfj8kf7~b4wI}e+|3$P>n9X<`qU^=`AC&No{ z0sI4g4llzk@CrN(|Ab}mFX(DP?WQV$NDi)H&>CKco#EfGKP-pi;0-tv-h_+cEw~2S zf^42*Xoo*T2Rsj*@EQz)VJ(?;gYnRS?O+J(3adnN(2s*qI1GltS0HVC&rE5tTdQ5? zYko%Xb33d955v0fSLwG~YnAnAE9xSCJ_DP;L9i)&1-5{5VN3WSYz5cD1h^L_!V|DH z`~%(vZ^3(DSOOD;Fb1}RiLgCPhRN^=_+XGts+4F()<}MI!f-0=4D(&Tu;H4QIeKI19cAXTzy*9?XMp!VjT9FI)h> zhi}89aG|*Gwt!1uC&=cro~Ixi$a)6Dk6@@Me}(%o{}UeIcbzsi z+hKkuz@so3{z48;N#o!o4yM5~SO`4J@3ruEe(!;d)_ab_%a{k>!+i^zz?+!2g}3v;_t@J(11E`!xz0jv(U!Wvl|9N?ff{1ryPKVc-)+Om-!tPNvf6W9Q@ zg>kSuYzzm$CNKjwhuN?N%!MuC3fLNc4ex?Kz<&A_0k8|qfL&oW>;`k;6L2Yf5`F=D!5?66co_D9XYaLDvpvg!{XT9t zSY58{(*|XY!t9)8N11bod`Q18VJPAk5^TK9jh!VG^7JJHfedILw8wz5hxB<3;8{q?49BksCJ1m0F z!Oidm_zip+eha6;E$~ga6)uL~1>2@c3g!mN)u_>F_F;c2)Po`DA-1YZnK*i`JDn~Kj@%Tn*C=)G1 z>(MzB^gXdbDJT=oM_bSlq;JD7N?RD<7mY)UQ6V~lE~Cg2atZay;=gn>AFV|D z(K!^phs%I^p>#AKtwhD>B(m+Ll%fRG84W<=(E^l@O3-Pf?;|p(BkGODp&YaV6``yn z{C63J?I-I{XEXqL&;qm#m7?$iL`^B) z6b1art^a7Tt``|mZn{c0n6%Z2{br547=`l;rMU zFssM!TBzgmH0l4lRx7F??e-Xa8ZcBoPV8IliM}`Tn#d2oGo8|maJ0d4>Gz6R@FtR2 zhQ*y&)EpwumQ~F3HIe1YqB$1HLu6N=MV*TbtRE$PLx(W1Rk_Q&N=9IkNz&|#45AX- zNmHCG4Zo;mI5>U(OWL2#n)v;th%X;y{K4obr&#!hHpHny9JMQm&ooX6ttQPbYjs-` zl2s+>G%82ohbT*^GfGEO&O6v{&qo;Qo?-gT-l~*H~84 zL3aPGVRMbuxV|5Ge`{CmZ+Nf$t$k&8m%&aNa$a#_YDF1?ACL+<2vu$j5TY2NQxrKY#Drk}2oRYo*} ze&W7D9Z_$Tfu^ICXbU=xY=^0QQ9CpMjYo@60V+YKQRu&MgF2%D$b%N30#uC3kbZ>Q z3bjRjkJvQZI1X}--PtZVC&w;XpR&0{yKp_!sea9gb}pB)aDBTkC#9sO z9Zqjqt^qoEPPx?Z_KYfb@Vvn7k}V#Ol{kAc|LEZ$JEus++T}zR#ge; zW>^7xH}#aMb%|v!VtJfb7wYQ%H3L26in4eLi?eS_{dz?IEc0Cc=&OL9H(wHzjCy*I z{dwyx!JK+*c9s&WhsyLR>YXQ*mK#2A{y9mUP6?`4GfAVOB$#^%soz3h6lF;)aSx5u zBU-%gGgIE2>TI+@fcZCeaQa}rzh~BKL6{JeNIlve=q1=R&W_aMDvVVIxJ+Xi+3-d??Txd zXcJXmj|=UMmv4PZkUjrc7SvO6apUTPo81d#ZT)~?gQKx{7K?u`l$Ox}788`kzp(gi zp)8FKxK3xV5Kjyd`D39}j|uS7F9t9D@N#RRydIzK2=wV0z++(7DEXh^&1*sJfWnGa6>Si&=z~ zeOToy=u!}`ha2jOt8@)h+bY$@o;~PlO9HWXkMo^EIZ=1tFmo%us7`lK!G)<($4HgW ziJA~ri617}4fR$=o(de4(gYim+|NC3Oy=HJ_^M_TjPz=TXB0?y_;C#-*m?%zpb`119e$cxgl`1muCiObPMM`F24Qh=nXGB5H*;QG zW|vR*1~b1^`JFy$iDo!U!&&fh>EA5i7W^0s>3F9eq`Q|}5s-c-SUmQ7Gu^)~p{GRM ziSHr!j#@5{+!^3IS6MudMbqW7HqautITk~)xSI_`ng{rpfQ9xZ&-Ucyd^(`A<)faW z{+3T?lAn_!7n z-LR^EJFjH-tiyYE&F|GuJE#=9-ACC@xQ~KPJ;;wXj&FU2i6 zi%$9z4&z7j!m4-N%+~>99@Uxg^_hiRW*L|{xH9IsiXP=$?&WgyQO-q%n}!LUF(i|_ zb;gi9H4PUl!{p_%v9tbk)-oC;>(PF66@~pwI~;XFy-^0rLCeqRVMpnmpcFI? z<)D1D4V^%t-Qx{)$07$WBPw+G84`V6h*GJF@J5_B5bPSA%!2`B}np($t)Dmd|FV#qi4yzTaIHA7hO z_XuUOU)XObN_bKl=1)4!(ET!^wO&`?_bnnmtM7Qr213? zs*XuDzf@rEqL8XuA=WMm9JXcG|CqkiZK=|S_bh?KSj6|PteTf}_)3APeC&wdpdGDprTGg2$uK4Rrbhl>8q<(tcI{RsI zD7&qGzrNaQpw;*T{!d;ERFA7@`#@{22vtc9w6+$-#J{yDhiW5He5pMmR4vY-Wm2)V zDB<*{S{*3%yF%(o+f-uuz;n7Gy;7-)Z@uISmLAQ6gUl^NRg4Ep&*!L&2g-=&cn%Jf z8)JFxVbOECUS|MNZ%ouneNk66zREa4e$`$(N+oz;!1H3z*vj{3hy#K0y<7?#p?re3 zJ13H-^4TCFku*S$s8fRZ(*zNbW#zRBT|Eg0n$MG{G^~r!eHbMLI8l#=f%5hM{qa7k z0I5o?rLCFyJi8o<9e-=^=Kt%0n`u7pwzN?%j~ep=4{)bjePE*q_sXr`UX>{Ia33V@ zY+i{PB#9QdEcJrxm=?S)U)x;cRM-4z?ygM>B) z%}u%osjZUh1;?0HT(5e;vF4$=X2A{2!$hu!d9FCi(M!~QTsb|sVdd`(^}A8!@44!C zeC6+a^}BK9?-G7X!>3vB*Le_4v_aBu5JhE>OthfB+G{rE2C?zFUN3b}z~y~mM7r7F zR+$@UKKA7#(_CG<+s*GX&D90F-MqDFt{&loWOa>@8nNn$9q44purXt4-kU8C)y5kn zJ=179)HDxAr0Mmd+Htn^T)ssVu*W==1xS^ELFNY>vdRgyklzDwGS=rrH67HA6?n2V zvm@bjCvc{1C z*snC28t)BmoN#*pZTz>sFMyZ*zF}7a`1uXF`Mh2?su%V}NZJ4F3shA&%6XdHJydU> zV2u#`GiF28<>W8Ug84t66Ls~;IcatL$ZlBUG!b&h6eV z;bs6*Pr={gR_uu6@*7xc8ONmQt>GILW5J^b4Z zC&Pnq3Jjwdq{F-6bl4Hjgb%`5@G&?C_JkLHzv+1rzRB;t@GUqB3S>WL+uQIRxCkzR z?{Q;#*xt;Ri@_IgDP;YW?E_dOH(sEfut@Gn*Pp7x(h^_oYOko3A61E!<>`9&tW9_z zbXyTz4mZQq@Ef=RZh_d@w!&}W_Yj#e-tGI%n5gXs%+J9c@K3lCy2uIKcv`_d@E)jA zdav*IgKUIh+lR#f3>b9v42J~f837N%mmx!8o>!m>fSbw;;7!P|mFEzoA?S%EiFNUY#NAN6kv8cgDtUdRTNf+S#@ORh|UWAXp%kT|Isyr|KZ7-30p$Bho^{Lz+G;8X zROz)~Yp7Dt0jd=Af-1|OgVERzfiZ9tjD-_n12_dXgm1ujI1e_4Z^NeWE7%NHW#dgt zNifMKB_s6^`xrSmQh&$jWvgTBiH6G9QF?dTI7+XT)&6yL`}4_8BC7s+A(ncWe=P}+ zI?u-S_0)n1Fcv1l=CC!q2i^rAgh{X~yc_n0ZQvkCx$umHZQ%q+`S5UIZ0#u@9&Qm^ zG6o+)3XEqBd%gp$o}y*3clxkI1;Xcqi8mH*m%g60e8dE@E14+ z{s)eQ4lW0G%H%sBcZw$-(xCRVhBO;J4?-G#9#*&6sI)xKLKW^f=z$(M1?Ir1a53bn zd(^WpYZ?bzIG7Gg;0#y_XF=8m*=9qHQa%UPgL7eHm62#N!T@F|bVS5k$3g3r+!NpLgP%eQr;8Iu@egI?Oa_@{W z`oHW(fAdjew>@mGkd6HqYxU6o1gfUuO4t&94m-hoi5;g$8`e|LZoAK1#N56B+fZ!R zz&Kb4?}ck&Ra+}=rF$6~eb{E$Ld*?~3b3=Dadz9wacj$>tEDEyA_|HM}e-Q@RM{}Q76IYx--A2&O|*adX*ut-&Bu+kLp>+s#_r) z=Qx8LzuDyIf#A9_fFC%@ekrJiogI}Y(sN76)Wb0H4~2!fPx`{IOZY*=_BYARq;vas zz-fa`J{Go|Go6KC9rAGum8mGK<%~swf z>DJiw8M&CH$5q{_tnj8z&Nt>K>;5l>6v{9UXWzit&&SC;kKW9E-se_bXZ0L9D~TC= zDro(QDs1aNN7wVR8F@HsjVi}vGXgoTp%u7FKP3$hJtq+-Mue3+H5e@E9M_?3;Kthg z8%xHSk>S@_nU&2XM|z{mIFe@=o1>s5<|zW~$N}umlT1Pno{Ud7b+bQps`GVLQs1C7 z_L!`PyWbD63o-2iCW#8=>&c{^MXjz)@p62!-oODre~p2^fKkvw>GK+{HsPu?UM9b$ zH*>&{sd@t`d5xj(oT*Fz@HHI1F#a0Z@ms(dRjkfQ)hP_IL^k$CQhKT!NtvQY7^f@D zmMF7;(QjggCsz^Y)SJlhDSEsEK0QqzA{m^{5#L0%Pa^`08RC}E>72VfgB|uuzTvJY zn##a(6U^9VaoiwPtEnravh=*V8uetna<9Lxhe@aDdIY#zq#k@v-6^jt2N5%Iu<%Y<`-a{| z`p)E<2Q~L)t6Y5JpV$0{nVjca&eN*7T$;&wpko$6hw^OeM30v7H(OqFX@i-Je}j43 zd>J;2c&=2(SLNMV`ZE%iLwcTR;X8}(%9p8IB3e?gv;QgWXX{;kABiZG&vG~^jS*La zmhxi`CxvHc>kTD-mR_yujFy$TYL{ecLMfd=`RYq~cYolsR5_~d{EHGhnYwwdvO5!C zr>^cr`HXoe`$akS24M`Cqen#L(2IC7WIY?aUa~6jOI9U*NzD(%x!WaHo>P^q zOMzbuDU_dZKti=5xBj)PS+8`@j z`8`+XQ=N0U=nMR3lGu6wyy!J^InDQ+=1QV;$kkiAulO9R3RsoJ%jSbNPd!2}ThG}T z>$q|t__F+*%VX!VT+8Ja?M55beoHHRef?V9=YEykK#(qUMzsXg#1}O@~n2+Bd@LMxUTF=*8x2Ty^nHapP4r9er zq-*N1kzE-oQZA0)}m`4y8%h0^6MCbD;6@wqQ>Nj}Fg z%$&C>=B^55gK|@ho3H(DCMq}1Jl*Z~8>wtkar#Rd<>~%yvkPT#9_Qr^2Ul^D%+3oq z?@!8N7ZwMT#32<^-9$*R_?&T+pOa+c+m56NYZyf}{Q@VqcGr-N!sOQZ8s2IP^o_cM z7TvDJ`h(8x(N1fl$BggQ9{)>Jg&ytgutaAOPL){i+NFAbhohi@x9)QNrrmKq&Rh2* z{enY1>_R>vywZ5@v!Cc|>^x(<)mJJ{lbd>Hf2Ol--il`4o1g2o98^W#TC4Tp4yp(5 zT4ZW61|TVDg&@$%Ya_r;>zK?U$6i^dw{afC^v*Brtl3g-e&*Mv&aB`HTCcauI(drDG7A5d z&MoSJ(oiOvk5-~0bO>EWp}*0IMxD`6!~klCdZBdLvr+#eZ=)U) zx{d3fNU>2RSyIoltH%Qy^~S!U&@rg8D73>t;!c^gQSTN!g)o+R38TAR>q-EJRUSDmkL5sEuYv8iGxp*TcoI<_XYQArLZnK{0AP&R7 z(a#!qHSMCU*F-bE)tl5@PfAMAX{3gaB2a?lZquL4+oH#~=)$_5%9r>pG}2(VA;u8N z-=aTFA4c0sABL{2Yk9u3*{Zj8FV9yew(1+e7LpUTR@5=?$mXqN2|ZxfxqLahRZr5b z1iWLHT{EiGl6K$eq1sy{FmCm2Q_U&{{=0Dsp%ROQ-{~_A>ul=v+T=~lgmnC#Ax=V` z{k^`_se%~QnYDH)+w>+;ok`LFG#)KRg{T;vMCD$RI>#Q`mlNl*EZZyv7cZz%u$?N$ zZ=|X^m87kbx}7?At4y@;wuOs*9BL;5WxsPfHTPC~Wo?;?vA^xJRc>tONm1xKkup|~ z1VY`x^Qq$w+EZ5o>|B1k_P%CA7g@f8OzcNwr+H=94l4O+-pV3{bK7_37Gx4rOgrs6 z>pgyR`}pr9JB>y{-(o$%-bH2=6HI@Cng6w{DJGctUsndB6U_IL_+n^1(RcFfHSKuo zh-Ys~rbCy~90#kHO-IQ)neO>sQY~cfByYZ#cP(Vk;0@`^4#aGX}$lzT>_BkTEZLQ4SRnb}QB0H7E04%Ppl|Ogs4cym! z0jVdR%2;-sRvQ+0mhs8L@)DX2b)TY_np2`Dm=j^@7ThN4MStIeu#248O^~Ssd3>Ez zFVUOXkIUe_dX}s&(e*nRzNmNz4jTG`+}f+h+L^rF$HiN@o7R1&eR{WwpoZ`fYY`brN2DL}w zcC)?!vr5SD?XqXDiSxj*os9(Rht^l@Uq7?~wo!ZZhbtoW_CC&&#(73;l5h6W?;OFa z1}bvuJixZY+M8xaK+)MDxoW$b9kSZO9t&(1a@)5Ay2z>htQI*=;8TlkTPGV>N2wvp z+%?{359p8C9n-wt4}a9zKVkmY-ey1PuiK4n<`q;g(wi^l7a!I;Ig2yX+3{2D$z-ODj%o@U}jxAGSM4O|?>Pe05@TIqiVhpdcwJ)f;vTKTlH^rJ$k6 zgBGJgRDw>UAjZohQ9INNjYo6Q3RHwj(Nz@odv5Z^ya9Grq#b7&0VC(GvzZcqoD~OW zGoA8yydznrAJ->SJKpiTR#Re5;OcK&UCosDPUuO#%Y9v5Ji%pP=-K6%c)P_xNdG zp@^2AWS+K$T=6-+t4a-f16h5V65Q^T9)V5vD%LS&oZ_}jnN-<+RFzu|$vwrq-qka- z_P3wXYq^&MI8gU(4Y_!VvbG{Tlpoin{jVhQCTWSuk|DoVG{~;YYAix;VG*C@d+uJm zNR9i)uiP0J$qTNKVUqD1&8dg7WYTY}C%G;^{YGFm9>?dh#Bo}0R`s0EugZX`a`7xZ z?7kkm&Nd_@HrlM8!X^7Oc@i#5PSaivm&7xAf{Z8()}-t-)uUw)nyTgrtxPmc?#E)p z8U4KH`XH7XavPyDAF>3!GGG!w- z+_cGN1J*YWsLG}Pk=c+FsU|nf=4#Uui-Ztk{Ta;^c z;XJnS@QA_Y8yED;j&oVwX20ufIMIVI0+;DSoYN*d<@ez<6ce82GX$5*^yZH=VXmni z>V<|P51Nlwq9Sw%m7{RRMw3tqN=H-BGPEA;FUw6{xaJZoNY#p=m_PKEtXcPVzpP(# z)H;WK&_(W3)DiVY=@)a8m*!oiox&@@u9m|k{;J-<*>bqke51guNCK_ds))nY-Ne)Co5HzQngJ z%Z@u;(lRlGt!&GwIJmo9V^7F?<@8R+o=_WwSN7!&S$(-4YFnN|jG6>7BwWf zYs!&Zq>h`*b>R>B^A=a^!XFNKUkmAShtB;p7co(4yN=;sT1ZcO)>~VRI9E3Af4%(H z1*2K)ua~VzsX9?joAgC(@iFs?W!^wGj|*n7&u%m{w))I!$uVV?V>cq)$Nu#Dw_>xxc-s z@5aoMCAf3FhPyBRlI;$one&Uk{`(V7S<=;M#Dz{#8Q}{~>{n-RQMdHYLw z!{~qV)-M=u)9^Oi?`?zf7O?AHmK?y1YdUV`T$P)_hJRH!iF4t31{QPuo|FG1aSu$W z*laUPHseP7j0#MMM8Nt|bzAsru+ChCr%sq3)DVwm1Ubf@@V>4YwW?5(z3){w=GhI( z4;RgDyK3!4pAv4&cl>(Udpz9u)$VwaOHj+0X>bWlN9}y8IBOe8hL!Jjo6oFBnOQk& zx3#w1g+*XyWm|>W0L+}^iPihhk1)cVbNs)K@XImxs$7UL+889uJf|j`?_k5wj&+Q7 zBMYbiiqT1=Gs7E$l28g7iqx#{VpNDq&}kI<2UFsxGa7)Vqs3?&Dn&YDMKLG^rJ?C) zF)F;QR%F&SVqDdDz?_;Y@pX;*&QntvxA48A(p(n1sszil!1uN2BW*O`i`j*CXrD_sGO_Ee@RhBn7Jfg zJs)d}JJN_Y#`r?1C40tJ;qHtyTKitsswPt-DMVqM()+r69%(didjn3X!ieBC6eHRm zA@(Sv9*BzKyHF9bd2AI0dm;f2h^i>?)g(8Hg2iB(>+xwk3?>>irG&^i9-k%~qm3we zKfOxTV0C-f5qGS!j%Kxe>qu%tgR4~E2n`-UvA4^OXd_M%`Z$|e8*^8a<@JeZb;4ab zO?K5c{1bQ8q$)05HL&=2nzV^F?z2~u(aIDapZPAsoIdduO}@U8nyEp7@_WwJ`etuQ9Uc; z5|rJGK0EcqP*<*=aD5qNon^2g(@b_ z2)9QDZt7S~Cd3(Wi4lbIr_ZKV5D$X4`(~8P% z35s^t@EQMCT7GUwTG*At<$Ob2jg0zkC#!1wX;I8n&u8BU1$#6iTl^0E57JEO`MQy; z<%Oz7U^V%w5dm(ZB5e0YU`tNjwf=f=JPy^Jd&e|mf{Rriwpy=yKZ!S#p-SOuP?~g5%rIi%B?Otn$DZQ1E>1_7~Rf>9#F(|=k zGPs1Q=OijekyohRP!BW|dC&rskG7#B=rRgrh`Ax^h>2f%g}mMimsw2*GL2!kLIHM zYq`m-^A^(J3>{*GyWV3wtJ!LaA7aEiAR}tW?V}{|dG4@L($j*P$`59Oz&1*9eHO2< zZNFOMF-rDWCM?{xmI99w_fXR_3%9Kmz=UI&j2=oYIZ8$^WvOq`f#4vHmta(9RKRHd z$g$S=l)6_5-12e8@^1_?8oMWbVGZl4dqcIRM@jN9GuS@EjC!{PHHMz5D&O3JD&{p9 zKw2@(2yOcQmz5!?zG~pYqIlhZ#Y)g*$T8cykD?n(3zMaHDoqU=Znp zhm6CIyuy)@UBNf}4rWf_iw7eI%QOj8$qwZj3 zRm-&Md6WGFGp92{+wldX4Q0lBks#*7-RN7%&$t0k&8{M)RV%IJW2e{RDd?gCR%1ke2knQ zNel}zj0lMw#YZN_sQJhm=F;#n(tZ?)7$bc~5z%;7BdN?&0jQLZky)dRM~Tq^Y+bC2 zaxE{Eo1=JoEcdxo*{ynZW32@fX^Z!%}`aYjFoqZntiN% z#TpC1a+uoY_$`MS#NxEitI9={>0|jogZet%Xma=uf3Vo8oER(iHoO@!;EA9lqPcuD zPuM)_@q({!8^u<4y}u$~PgXZu?X5e;_$J6f={fq6@tq@rp|Ff_u%2Vb<%AjdHvkF%JQg+&&$@+t@NP!2H_-HFJW1RUS|Lo z?kZB%)Hr zQvtycDqo;FKZ%0W#KSqwFCa!_aY>r2uPij`@{X516KTgSexXW`eY|wdG9Kcrxmkq0 zpRnIpFKe?%)EhoussO3NKfx+My|axZ>BtEjzpR&q*$jaU_0VTL5pWKb1rsFKW2WXO z58)ml+&UY?k!|pW@C^Z(CAm}lt*KYcVrI4R#!WTCWqLNX!35=6HcwW!N4C+%*B~g7 zi`fMGBf+lTAay4b?COAEgL%7?U>Co@Xnay5f+`EA)Th(VkVTV?F#D@=aS8?dRdG+H zu2k!BJ5yAhT$}HGp{VPklJTn8Uo)cJyL`r~z^lA?RT5vLA}EoGuMv%dM5B14eE1r< zR=lw?b?QdVG;__KDWlig{j*gi(tZlw4&klSCK)ots9&`cO9hp4mD&F+@L| z<0bdew&^{U3!mz<`>$wkp33=u;{5H3CH$1a;^bmRDeH;v~l)Rgsa8c!(e`Nkj%HD&sIW3AdxB5Xb-viDo2 z7wmD%v4hPaiWV8+-k3ZrRI4pRNS-<&Jgx01g05(d8nv8J*$(M`knT;$7*~SXo2+q~(&H~cbBU`RC+~kn8~Wr*(%GE*rLziim5aTL zTnz?F{O9!D8w_NI<1-c~Caf|-h|T@0sH4%oz+id}9zQN{C@flfu4WjB&6Hd#eC{OGS*=Fk7fYgLGj23C zT5^5Esmv9(oxd=`HMU%Gm13e++*ViC{@m(Cq{)ztUl`9iNO#>Y>DQ3V{$FytjT$I3 z)$i#8WtaLrXP{hHzgG;D4h8U=fohB2$6OwgUOLdbx4>9vHwKUq<4}%FTw}!5OSjuu zMQ*n(L+jCgbPk0%?5mTz+Vcvz$h#S$x|AgGg$!R0stTp26<+Sm4K%MSGJi}tBoK?g0d>e)@ z4zg9$$fIN?F7o_AbpMTjIRIRo=xxrv4)n}wCeHDyIc5$$O_F}hez^iL7QRvfFe%(N`w@+Iu zEy}$*)!$|_Blte$UG^05TpqE}XyF^#-YrWua_X-*_1ivwk{w*FuAJRyH1Q3@?v^^6 zaI*$CUj?{{l(bET|HDYT`SLLF*hf4j-79N187+e+-Agt#?SaPL^n6FFBkVTJ~ThKh&FDy#O^W@{Nnpm^-ypOH*Ayx_jJDwj&S7^{o`m@^48>RB~l>RmR+qiz=BNw=gW<^r1>S z)j+u+eYVj2q7ZB$5eG=b+)lE63pd2vPL@kmh*T&y&7O+62Ecw(HYf5i@|(VmJXjXM zvAwl2;-l);2kLLiYGy!W(FUh3)4%6(Y};yt;*8bRHCeY}RC6ajTp1UYrR^O?id3bRG9s5S+p!sZ|7 zkR5;2%0d-A)!DlxS1@jR&1bACKXsD^MlhYoDd%c1;uhawGgH%V`#+LlW)Ciu%c`c! zT+8KW+l@QjUv;Ux(lt!mGuw$xhsP?7BTVC{9WY3(_wx>;m3u~jaRcjQ#YT5Z{)l28ng=Oo*Sb2T z@dUg7^ESKXXKY-Du!-#^uAPQ|3l}Q=omhCO4I6ZmF*^!jbl6`_5%$6JrhtxjN#fSYjsyWBZ*iOVwVE}_1UZgWNazXn&t~l+y+nheFu2L z`;Al#RkiF;L-^5lhosJCNGRb)BZ%Yd*;RORXdiQu`XTDm`F90{N9~W|84zu=eTgU6 z6ILwMeWNa{Lvnv4^6h=bDt4-xb;wqXjZuDM>3N9qk-pj4j=W1gNZuVIl53xk;RlVD zRoD8Qne~&zwjw%32e}cQ=E5fPlRr*tNu1i#L;AL2z9IaO5hg3tQS(WZx{OwQFC&F0 zIqL*THaw<)-R^twOa-sCZmp%QH!6J*@ulW+6j&~KFw=wEA6q;Q=GHpf$DEw-Ej?8&V1JAJBqyO2OhoN`t7r5#tS5>*!t6s%8!yX9s@Wa1 zS8x7oEH$iVrrp-cns!)!)aY$k?L<5KaF}0NN%(~sSF0^(w{^4@f_Z*1Iy!0R$)@qn zI&$O}Bhv9zTe<#=(Z(_9UT^DCV~o@BWC!nuCyX{u2Tg&azZ&KCsq*jNjAX~>k9g~! zHfFjU*Sg9l7mR0}vD9eKttOn9-z^_sD>2{_3ZbVwOT@>%k7hR;l=KOASGOQZS z&IVCE53;23-0#LpRa-4AGxj=CyUWOnoYSmGeBM$V)ECt*8Dku$x_c*IQZqE%(TD#q z{xq!n#csRH>hhnvth)SbpYT5Wr?K7PTujFE<@YXt-t0ws8R-Y}Lk_~8BPmT^ar8dB)kG9=s^85B}oqs!Z>O32Gu0^lcKdU7b~BiL`4PvQ#;18nO;-3JIy{&2JX+1Q}|jG@^wWs|Q+Qv7klB zBc?^GkQaQ8Wk5m*J2-jQC4}5EHvwILS4b0W7Po)#X8#7C-sq%|)x)zobG7=SacBX` zN83;-Do5c4r2_RpnP@&LK*gvG@w&b(0d+>>P!1|U#poOgszMP(?a%-;9xX_-IEklP;8B$NNwkQo{qI|Rsm80SZNqDS*5&#DcxjM zI2ET<@X#bq6&SO1ydZhVjciKEhKBo-Rb^M``iOUJjl8v$>;v)!_ceB;rEw%{jyEqg_eg!CP zo2{w3y~WnTT5!iMgzVN;W8BhXtF4Q6Nu_Ls`=8FDW&GrxiSicPcTtxs6 z<)}}#*&-Yd$$~E14GOS^Z0@ zk|chC#FMY8KMRn%Prlj^1XaMPlz80Or0ub_JCUPficpaz?6A3OV9_`2sU}V3nlx28 z4r9be=RgLaN<#6Ny1gc)jVM#i!EL1-wy?+&v8E_f@~3JIBT<}OH3o<@%AcwN-?ueK zP}LvU9zkKve;@Jv74hwhhlAfoVfD>r{~H>o_JN0UN$--1+zI*Xkl&a~O)@}L_&3tk z^E+)0kB#I~6%^WD2Y z=g>s6yEct)7%bdvq2G(hek1?Rr_5V;*v(7b`p{Cn;;-9>Z&uO}xR1d6b=0F{Y`4 z4^R-(?#|W3l!5(>oTXYl&6%ZwKoB@KQ1_wDd8_e~I!*F7A@7N|b$8h!%)n;5 zZ8O!{BBQC77lHo=`S*spQDh6Xo_Ir&tm5}TEezgk^TFnNd=YBIOs;X*yDzjgHChqX zu9+%lw^8#??}k@+j>PimI`#K%TYJZ+>)0zQKFa;)xcH1i$Io%`&7cFw&vEf(^KTR% zee@QKjp)SXX+!uur6c^20E z8kdwu2^jbujHTm7)u{ye1H3E4H6Awiqen$3YxRd;!8C!?Zq>P zlRmNyaAxu8z3|~L_;4d%{k@kuxBLbls8*#lw0A8{#eIaVPU9R;;~Y;j+PK>J5vpAu zybME`N!<(upJr6a!0lKu@(I9X7`%fb;%w+?O510&5SM`D4!_S>9a zZNH?hkw85JY@1ZG{SW}&C6Kcp0{Co>rR65IcfU(M))NEY(XoVYQV|ExcEdL{B$B$y z*~Y~()%5!$|2FKeyV(02G-Rmgjc4L!8zry0(1&7Y ztFZ^sH+GURohtzlSs>bSwkkY`mOoon97F@2a~L`KT>5j#lO!ieAI?_VAwwjP!RSeb z9fC@jtrmUchMVJu;OdM^7}Tc0tH9~elP_a#wUGp_yCj^H)@-%^5aMRt+)!?`f<0T^ zJcRBg+{K#Ke`l-6QrnZzx{FGYp(cDC*!>-~t<)Ck;rc7+eeF?o^J80E zH3q+}M~Da40V?_kHCno6xAL&PWMn8np5+5TWuWxBcA9bIwCRN$$2(o1SR_0NK zq&hoC8Q&cqe8kp`QhEe2G$V$I+tjurw)SS=+%gxP7hVPdHwaX3Q$xz2SgN-*_y_My zbMMx9)U-^|Ro?cy)Q*D0v1BTJ`NQEKi(|Vw_K7XPe<%3Fb8P28DW7S9Wga&G zs`c|!;HP+3lh(cG8M@DSI&~g@RlA8{TZ&Tfpf%%pI8ckPYWo^Ljml5^dh=NA(SrCq zRZpH_nG`<*kK!k-DI>J2?#=ORPsnFfA)L2@5k`&P62~nPv)%Z$Zz`*Ks*v1Kf^hH@ zKmBOXJzEmsEH#8V)!aPrJTk9eTa&2}B4Gv2jODsCPif`0mi}|V4hH*-3!4-j((;tK zc^vt02_joz)%*PhAE+0dr!@>pX5o|`Ed$Sk>_t#_@ZT4CYT`6jny2#0ZDIbw$n*zb z?D|1Nrc>jar%n@l2H2S}dhTL2xu!-qPdSdE8dJlYr=pG_>f0eX3dU_BNu@{X3psYo zHmJR`GCUxaVN)b{_?yIF{BJ>JXji1ZI%aDfa~a;vfDG~56*-gY=4b=Esh~cvA9Tl_ z=Q{IAUE@RLpV=awxw{HFpO^INU<5>Ox83>kM5rspC(|=YvmQ>G_Egfa>B-Y@wvjS% z3qt#{z46|g$tg#PqjFimr{fn;lWl6uS_V|0CHNjk-@kx*qNc`S_XXVO-3=GUsPiH` zJqb?-z-skwXY#l%EWj;c+e2my?siP~Y}Vw>J2AyV4dQxkxBBzAEg+D-1W6xnB>p)U zFGxH?MOWCGM`E6AOajSjX40&g)O0CH{ow2p=nB0vZK(#K{lH5Fd8aKDXi7p67H7$Ule2Q_1%| zpF?FVJ%Rteq+eUej(&MZ!wuCi(yj}QYxwe-r?d7rUo&0Y2@?4GjluZehDdbZqk190 zz+s5MFvt+U`<{lXOM;8&TzgZM{W)fki)c>LTkHex=C4;2&;G(@b~j@VJ@;#@4Pq|*%h$G3=7(~M51+wunHdwjRo~c#n4f&L z_`)}~zcn-FM;EGWPg{*y4*J;6y!Jfdf~}90r!pE&#wGq?ZCbqVf^DbSjM4wJYTGB) zhmA2j#mdnWm&}HJXFFoX`2O#!I^MGX-ZmJ6_TmNK+wk%96K@p1bIFFMK0aMn9QuRJ zW;SC$+v&3HEo(<(SgM%@^0&;dUbaoL@=#SX%~y$AJew9zy<%&lnQ!D5ul~t~OV1em zO}mPeVvGk2P=~G}`54z-xQaeFd{eRQ8s;Bn_jigr{fc!)bFX)cH(a+hGg}jl-WPA` zaUPz$VOwfO&phfkWDa`VPQTku_%DPm=MGT2(@}0f0nJi=H*LK$ws_(RMi}1%(qWwK zz(gQD?DrH9M_U#q3C+9hM1x2lfO00UQkc4{&$}e$?T|6Tm-#PXqq~rUGvR z(}4BBxj>T_KK2PT1G9ndz}JB|yKTI>>j^A`*$TvG$W1!183q-0U>L9ouoJKa5F6Y^ z#4`rtM=My20=5R?eyJ%4xCj^k%mIc0Hvq$dJAo0vJ-~LrPl1s@Y+su?0kIKmc#O?f zQx}-Aw`w4^9ZfMXUjp6>yb9dqiI-G8p$91oNgqB42JYgRdIGxxdjtCc`v6A(V}VnF z{eU^Zhk<*61ArmWPy>PZV5jL(U^n0(U~k|M;85T&;3VKcrO4Db)&RA4=D1`sFoOf!KvNoRTvh%c6z(t!Ak zpy_!aJ(@cQI2yPBI2X7u13$9y<3-?Gz{Nm%6?X~n3n1mpY2b30uK}}wK4{U|z);|7 zUJPfP^ehmB`cm(*H z7exmpjTnE;}`5If*#btrLw2D}f5BrF^Nv;axJA_)uQfjTe+ z=nb3+Yz*8D^Z|Yf#G32E3LuiY@C#s5;29bS`{Bn0STqA(0r~?;9|i#HfUSU}|5^jF zUt$UdV&}jV3Je2=0i%I!fDZv9fP;bUR8GC^1v3VLjs8YDyTF>Vrz_A0cn^?fG2MU> zz!+dR;Jv_D;C(o;3Cd=faH-zBf@dM-X*#}fSW^6sriW@7lTf4PfU-fGK>I)^L6kK=bP;q5}2bgQM-&*akzf}nn&F`#*%*FZZ#M?sfBw?Qoev7ZSV4w?#D z3|a@;8HnAyWNnQ_54M=Grjh%iim>Rd-E#33$It-tX!RCMYH>^J{VMww7PD?!bh~4} zyeSeOqwi+Q-xKQx%~atxc;;o8r|zz9(S_}mAGu*xx8Pv#EP4dzsn)5qH6m8d~7#xfB(wkb`VSVf+ zwbx6(U(T50`H4Th^iYQfILE~|)8kWlT4Dv%x*a5*Cles+Udg(ctro#PI^B$zrw5<{Gh| zh+_q(&tla?cjY{$gJT0HZn2t+-)7(jT^}slBna;YN$8MBTdV@?D7>`AIEvzY+uV>z{Nh=5BfXUw zxv`^>{I@1S*QtovA-;H3#VpVLXzw#3YHOk=&BTOUYtrWU)gG29`(2O8@O z%xQ~@d->?ww4p~)@6LmM2eoL8dI=f~ngp5y$_8x#9Ri&P{SLARVP7582Q&gS1GE&h zF-XIQo65B{YdnHIF@UsqeQH*1*LVb)y*{NEN%rFOJY6Yy+)t0R;LxL`$ESGhqqW-T zhf3E2LsMjhvFM3GDxSl_{T*yA#Nw{_?dG~o{TZn@QMVv!O%~B+D!#ei)Ej4DO|;QP zuJMSLhNF3do9XR6*Bj683|8}->0zEYT4*UeiW?eh@m0`$&2+m5OjwUt6o47r(0kn- zYI^_SzF-K$z5AZ{;{lZV?IhZDdiZh3;@T zIjs={yt?~n{a~f}>tPn0Nwn-fuG;(S&i$#uDvcO8R%khPTy5~zov(EaR@cDrj0fYh z<7V~#>!@5^0+8=8-Iedh`RiDu7>+CLA?&6fS9ER}ha78v!4msLcdTq5R}}$z+a?t* zZYdj%o793gJRU^?<69yy9MH2wRTxj-j8$h^>b@2nbh8YqP#d;up@EpFnI>aM(F`hP zP(?!|$Rn)DP~p=<0UCa1Y0mfC9#eU(;PX4ky2Q%69u%Sa=3Ho)054GG8U^Z4n|pj( zJUdW7teFds7C#WAPcd6LXQA(T3F1%)+68j)LWq8^+cD&gad50lDB2U}4INuE&V`K$ z)wjDD3BnOBiyc`ssG@jOnBK(AoLH%*Md)*f?m;s+4!Q(#4@Tz)>INDNngv=3+6g)e zx(>qga;7$*9-!f%si17o7SN#(Ehn~|@0GVh=8Z)P`=3#-N212|X@{cgk9#DPTU14; zx}Bs;#6h^zXS^1ao$c<9-#Am=(zyA0()ggI@$kx|$d9Ca=sQw%CqWh72wRMJJ^wvHxeIbO~#sZvF@ z*JFeD`21*>a=HYkoCur>;uj6pwbxIY5zMp>`trtSkPE+q@XDR3U8sheT6Nl*PUsym zTeSQ$Qblxvg8c`F=YGA{x>sqP^)U2`A%9|XxkqOdUo>i3%?UjV42_j9;lG3@K4=;4^DH~qY)(!6&MZW z(GEFd#8yhvL&ZlUGf%o$V@8RvmPPBd>0b#)mLCwS0b|sk(RzgUfHCX=#mcG*yWtqd z&KEqqG>eMwio&s|R0eDr@!1%QDrB2VhT5(;#_JUW-AG4Xo2lp+WJyQF(;pKELkS^# z(~Rl-ein@k;PpKiY*uLw37uY%hVoR2=kRc$r#cNu$E5Mhbr!0pvc~8^ zO;W|0sv|WMPaG@Hz^jhNvGPkQGX{ZNMj+=Vs2wr-OwTL$eQSd88Hk5u6_eOb<j2TdqR-=<`uE z@dfSzk9pv)Ee5}UPILX!SEn<6&pu?p*9;H!)9FsjBp1N30e3Am#7Q;LUbyGsjqqaXOL`>XKWcrW4BF3s07 z5fZc=P{vvlEb56OE!1-&-S3-*>wiUB?*`T<#Ci%WJ6ONo#kzMlSd+jC0Bihi zEzp4hHYroB9)I4Yl(R;~JkO?Yw zFsc?lf@H~_uBHsuoo@+EP+P(9dBoI-Kua8PB!dTm3y=>K=mNJaWTYTjS>XPPiFg%|Hp)6}$h46Lb=8MYhu z;kmy<@w$&2Rjz~kw71pl$Mk0AtZ8c1WBOaxY$Mz0Juu^$(!r1Geawfat5uKdqs%Cp zpB~qjTRF2d(`s5lYOY=zt`9IH)fa~AeXU5Op&^>E`yL5!KO$8vNPzp~RCNxRauKb| z6pq#hx*s$QGy}90v;}ks^d;yjh`y860@MXG05l0S50nks0@?@q5_BDeuWp-Kfx3YP zgC>FI6z4yoXJ{6DV#{Kkts+LC=d{i?8gNfJA-dXnFE$a~&2lRA{0QCG^L2=~g_z6J z*Lf;>B#QVAaGsd0Mvc^+kDlhKTw<&PW5H~701Rp6d3f`1fwh_P8Kv7j*Mq$VKE5&> z-)g-dHV&AKM(u34t5xZ6b9b3i!R-^bJVPxT;Oxog)qzoWYE+)8ABEuF1S8{l6){?m zFa!S{gVE9C(YmkW)#n?$C0$XXvPR=Au@bd;G+M?M;|bF|b!9Ya*hcsfHOE7Z?rm|_ z$~+Y}2EONmGiZ*QJ;o*2B4S`s)-rC6x-dp>?HD(wAtVH3+N-?Bq9+X=r?*f&#_Gm>$C?vuDxuJvRqhrl|*-;#T8WbMH>~KCNMt@H~7XA1UYe zsYTy-H1~I9rwf}p@qMZuDY}dOgv5siJo{ACgnzT=vgb6K*r&$+oBe!OW@9xN?5zJ{ zr}OtjY58rR+W&9%90}XoU|;($wzzI=umcnS6}5DvjM7bA&^{Fhwzq4#=cNDkOXso4ki$8f<577Lxp-MJ^_JK}~Sxir!7lz~gb|PgkhNQuJPG9~ru>R2x$CP&K19jy4-l zwFXZ$M(}v+u$hXTibbgQ2x!wvHEJpblABgG3?ymX*_w|21YuBUoG5S2M}DY+v{tpu zaHJUgXn+IX#k!-hsL8Zei78MmtyOvohM~)aORbXn(AM;%pC2y@_rs+eqNR>GaZLk9pa%h#>F%9cyheVP(YzUfy zT;C6lRFTsm-x2a|uc*hSW0K(ZN<+f!_)Ih=3C2r+!76_$O25x6eAFeF4~Cte4&{7E zJPYH*G8Yf=nTs#*UhvM3Jle~O zBQ-Los_BL*8^5CX#4P;*vw73XV%zijS7s|$B+c{?ze006U7u%md!=~pTnrS<**V3p z&)0FyEqZnFjRlzFSUETihwY7}#(4|%Zui|n^Y(3zMRm{s&;-yNP&Q~g=m_W%=r*WD z2aIJv13Ew*_-kuk#H^l{2E5Lwh!>#=fJ0u?chjZWi>RZ)FX{9yoAJ2t)R&+&Fx9lQ zIHQ)lgf`H^W$^-8i5vQPA6dGKl675g7yzc%8MEqrKUPfJEY`c3;l-%M`kKZQ5S4|X zwV<68B~4qi1W{Uo9RBk&6|n@t{E3}js%6fm_POgh7uOf?Ntd%QP2TvK`z88d&!h1C zVh1ehRO7iBT-aF(rE~xVGjp_xSc+_(Ioe&lU+-12W|@xbSv;wlu?&el2%#@WtXg%xbzvr zE>vPCTm}DZx$f{VtW?n}deE8`ShYw{))i2D2`X}h-oarS%ktDFspC#iNh|a)^T4rc zN;W#5O)Ic6x?E(aDN>_KP>H2(k7x&!|4PL7Fhc!otm?Z`cRpi-=n&&$Fs_YNAGk8= zz;GM^!+RWuYf2uFgoCLo^=Nthvbd~N<$6wPMtLgOXD*bu|zqBV*{wk#W302Bq9Pw<91U;cN@!y$O&^i4&PIb-I`>J-?X!*Y5@6N?1@SX=AfgS^%IcB`tovTNv zY%+`;uYMxKk!;<^d!vghiz>~<%(H%wr>DA2UVb4=DthWJo>2ZddS^%S1P+O;Nryh6 zM&{@bTJ=PUfT~;rbvp*@FvhDVNNWyq{2nJ8u1J|m{OqfByZ4hWJUhh#k9WY{VNitNLT8D@m`SR6j-GJ@k}X z^{U><`=O^AQesm%3gHeb#Id?3jhjct>Ch*Qi$`cy;NocJYq}j=EX(2I6@IJN6mo3g zonIS;|BBwyxGDZ5KEa0W1s^~l*TcNA#*J(DujtJKw<8a3H^LD{)c6l28q@%&iNO`J z0FsVuNCsoX*aDIV!AY1Tc??NvD!9>~i@crfVoh2f9@HYxGr8y#-w+;^7PXuwRRMfe zK5NjbLXy}!YE{%>KB;=Hfp;ZhP4S^}$MXSXecr{I%3VU)vj(AfJl&9!G(MJ4uCLMi zAmgJIGX5wszT-1$l+xQfIzH1NPU#rYa1lZsU5gs=+(cH0lpP~fg~H(FF>yn&qS4U^ zy77fIy<48$5JcQs1W}G4UU){$UJJGQf=du2K9Y~Rj^u}+M;Zsw*WA{ev#0|qJP$q` zgAe;At08&tVc+D2NRkhuc*SNEe{^YSDT@Di9u`_hsj9p?iy{Y9$m{UuGx&2TSv~r? zi$=;J#&IydPF8ze8QL3QRDkhIvTFYZc5)7=R9JbQfR)D-cYfIF)*F~Ne-4{4*wCH( z#@Cx-r^64YeFAXYVv2il+uzJXwH7=FAg9ibc>>~&zF^yW{b}o$hBnts4psdOYRC+K zEctZV0IdLZ-)jT*HGIYtzq3IL7Pt6~9fNZsnq&m*|Z5>dtS|ad{oN{OET5 zlo`3yx1L#!F1GvZ(A~{pQ;M7I&<{6`zl9#p-Vs|Ipgy1x zpsAq6piQ8Cpo^eepcYXW5r77RCV^IhHi3?VE`hu{X&Bf=AJCh2*odEdKxaVLK|Yx)&yA?(_|zPR|&LwYX_w@gqspa8wpx>9s^ zqt)h8==Rad`%|>M^QFd^!&uvFcNpF9S$I*iSoJ+jE76O&&V{0qqu5MiRP_nW(5V@W zQI(&-`S05`=kxq$RLx=3oO5vh$70p!W4){6kAJxztKvV_oj3H(sP!L1{u{{0XR1#= zMtJd=ch~W8sx}0BbL03<(>T@hh#qF0B|-seQ5iJ*yd!!Kd^@59EX#TLwL4RNcLduP zyIuSuO*3AFlp)#URV+hdncfzrWo+7729@%)I3Wc@dSJY&0@v|_Sa*Uo>9g_5`xAXU z!c6%DVOAl`)Fo=oCr~7*OB&)2LDK}vq#$jAs{I5SbOPnLbGh=2ivJX@FTi!q5;gZz zy}fsii)(!3_ZYJGdM2LhrH>@5e#fBNeU`vT-$_<&U|eIxbxfb5nBp4DU@NW;c07s_ zPE;{RF_L*#{BtVuM3s6J(MVKTN70=3FjobAhKcgYqq?v68Ih;tyQ{3v5WZJAI^K&e z_LP%}D!d#WZ||2mu}*cJ=(-erMr|!e^1em#hPoS{EM(&xzjB$dTb^f^BA!#%(m zRsT6E-IthY99-^hd?Q14ok(Rl`vx32Grex;49zr%r)VorVu}WRWUIuA5cJBZN~}q< zp3o2(`a0m6QxHM3UvLVGIcSOxd;!s%CB@6X(D7X9ke7=Oe5vCrUC8bsUm?5Oe1$_@ z$VM3YO15a&M=`!Lxcw`5_5RZ0_FrQ|%ZiwyOf)Pv7!SH!Kcn|~<~TI&CD3h9t1ei6 z28{vD0%e1?fKGxggS?`l%t8G?V?eV&D?wX8hd}2+zk__bLbHSVfyRJlb;a~4dCfT} zbR6imti-y}IcUd~D;l&56~!|=Ovz5LxT`tmP=}lX)EvNvK<+s`uEpJ#cj!0{&E4SZ zpXcjVJfKQ`aBmrigUXgB7*SEe>0Z(JzUi})o*O>>$(hNsl3ZVLn4tn6 zftr|%cRf2~!jZ45qk+%SqYqd@!PO^dcr3r*bPFCmEqABy*tJsMUexcALtf7Coi|Z% z^Xgl@Y0Of1*~#gp;Tf&SxH*o(s{zm|!HA%f?`+E}Rqbrp6_BwovCT>i7RE{m%P_18`Kx-n9J+_~wrBq)`s!816)2rGI_2YhXS9sca@t@&J1@3 ze1_CE{^%^U^KTV=U-6mx<$3$Rv%;CnvsB_k=B905f#5sNtT5^!XY6@+ibMNYLNS@Z zSMR@sJ-ab~dt!5Ojy>XES>W{ZjB;Gkn|dM(El1$y=Q6K*y4+pH&PuY5I#2v{XE6TH zfwN1<@k@H^M&}XqWXKSo?5GshrQ3bfp6^f;d(!P)pZcFmfj&7xe^VHY|5wA~K+F>E z6!+ldY0l!_h(PAR4aqxYoK^m1ejtLJz07w#U#9!{xS(94y9a&=m$TrK&W`sM-^nG~ z5X5V1^hY9{CFRT?ADX4(ZwQ0&KQ1d+URG6mwV3F;v&!jcmN>$+2#R#lqmC8I+f zh+P2VBt7=wj0*>JVw*}GSC1A_`yg{L@I{!Tfs293z)T=U9j2u~@J!2<-%t8IR@P(m z@ECpVC3+ROX#b`hAgYsrSer1t3UfFx7Z@Q(zOPZaKk04F&`k$^(gWg=e#7}2Kr|X7 zGUUw$n0fzv{g**23x#MqFn= z*Fo<0U>FJN1{w^S3R(=>1lk8W1G)~vS2;|rKs`XiL6boXL2E%fK}SIsLAOD^G1#2| z^#hFn%>XS1t&7oGnfBqwm!PX4_j|D*0qO!8a4%L7=4)%NW6+7CWR{1{s)*}YMF37K z(Do|#TD^<;@v~}gfH}bXnVAizf={WjwU||&Qt5!eQ!e}MDd{xUVo7)4DOJdl6}6Z_ zoKm%H^1eZfd@iRcJq+2{8(3xg$;F!L{3!+NApav~-0+35<++A4nADRagd6&u?=!ag zP4{g)0cm+x#7sk{si0FHon>Ktyh{5GL(fD=ynjw@`0dW(*mzY#jEP|EJf|A{erH2s zyo&!FjHkdjcuviAW$Y)$Brr~#Q$M&eB5#6`1V+_4_1Mij@vyr#Edm;6AJ@f#!i;18oN# z0iC%I(}P&!L!Y}5zs{#LS_Hi7L!WG<=75R8y*K&qAcHh>A&=J6)^*CE!0w+)W zsutAi4`_Q-Nj-eo3#)_I)pzxGigJ&N{2Ppq!01-19{XGG6xpqoqh=gOLA@M?`j(8i z_PS%wE4sMN{*je8ffvy;^c}1}i9~2_Er#=6|LAQTkKb^5#?#|PDu033BZyDtKL~ao zg6;L2+VKyTKYIOkcaFTsr@x2MOF}QI)ODCmzsRTYjR%NcRE4loYc+f0-060Q+N0Th zanjY(uDzI>kGl!rr{LXetYo<7p10er+kTgbs7eiy+cF(rQt{ESEV)PZ)a+rN`w^A& z{~%-OYQQ|rjvF%nX^0RtxtCP@i+ITOB|cb9pJB!CvzooFqw_76q#+s=D*AQ{tapkv zO*hdXVU6?RogMqcnpOm-7(CT##uKEfAm_9%y^9bf-N^i-XCz|$V# zP$KCZODjt%kJEK+oN)bQ3}S6 zzi>Opg`ru&I1I*-zf^lGfk86Q7%5+_nhjfNb`#CbuL;lo^z5nI_e1 zw!N7LX~RraYqPgR?7Vd&xG3E)4Fm+bhC26|^qJEkPkvB$o2eGD_q|gQFG(x01Qn z7(!menZ@8nsP5YvHAuEJBzrcpx4f%#67dl^$|D*jp>!I-|7kuAu4ufPsdD1*o#jJ~ z@a$}+Dr;nq^?cL^i-)E?%Db^W%)Sn@i&vVm8x`9FFLyuL*xpu-2<|bf3mLeywyv?= zZuuD1Zevrmqp`h{W23lu0D;3V%z=z=E(H46bxnSc+SuKv+JyHf9H=@=RVqV{12ti( zDq_=V2a0vFct@p0-r{kHCidnKifm$U>ly231f~w&aPw1Bo7h`9y!;z-%xcIdE=3va zY-0Cu+;-v7KzpgGgeQ(+t=I_#LG=^XW01+gO;Kzsgh#8!l+R05&!&h~Nb3eCG;&<3 zVn8B3mL1aI9~Hq;Wz?KuzKB9$ zXakSNxCkr84bO0;yLW;5DuQ!M8S?-0P<6rA-l@swF5-|jEiK#``9T@h{ zz<45z^Fd|xY80fV|7do;NWVv=wSZ&Xld{YVQyW^?ofozCs4K+4y(i0sFg4fT?mQg6 zN5%VtaRQ8A{>3N(!}D`6{t3gd=zxd6y6tbbyOF6w5BEWL>iyUN$en~-VmQvaT*O(I zjmTgRn6S@Y6=-j+<{k9#!A*k1?)WI#^#C+j{9cOr{Jw*@FS1-YTDo*92`v$wO8C|; zLM>?N(nXXJ;}jTOBGfM}U3#17R$zPqM)wFcs+Eh2d}4eFM&Af^td+f!Ti*yoa6ew- zTX4jq%bobg1w!mJ#CAof*@5;@$F2y@UaGL9-B;u$;&I3oD)l>a^ED+FFSR`g6=>~A ze3s`Zep#m`PE48#IXt!&f*!wPYrN*WLiKEo_Pj!kZH`-cW$@sQ5CSWe1#Ar z+NnQU+ntx@_Ne|rV0;Zm+jeSN5cE;ob{rK_hE#=DDs34yw+{u`aqKV@vA7;$_cHcZ zR$^lnt?HUMpcYJh+e#G}jNDbm1=T$&F&F{h{E{UpQY{Zg07;Sm?*k~U#bMEAA@(MY zX6@P4{}Rgl5QKsWgXKtj^-hSrlNop*%M#!{{pm?28jVoQvK0Fl3jh2%H26oVE$i-B z&kse#$JD{{vdF3GSSa*oF1u9xn~<@51DRDFRO>L8JWUCM@&)fTVr zZGX{h?)6)7v%Yqm$xHuF@nik$M_F4L8cs6>a#Svk zxA(DjzuT_I1VrzNFtuQUeUus6?%V`;e?eq?*xi^!$Uv`cNQBHkVa0zY+5rg(lE?iX9Ikb)YY~V>$j=_>8)0 z82XVRR}AyWfQo2vc98*<&&b`YWI%dSk?@CC7MOihV%Fb<7pL z?#KEis2^wyXclNCXd`G3=nUvO$hSKdDM0-|V?eV&D?wX8hd>uWw?Hi(!1@Ge7-%wR zF=!p=2^dMwF_dkf|jE3RIEYM2OKG2sS_a0a|0Sy360IdXV0-Xe12Kn|xL_otp zlR@-O(pu0?&{5DO&}~qQUWf>2IA|(pDQF|;5a_%e zkf{%jiGX^5CV}RGHi7nmE`v<5a1ZJSngp5$S_|38R!aOLRT1FigRSy0r=9@yczb@v`v?4kF@wf+W(;I4xO(`Pld8*2FBxH zH0;p%s%m1i1!MR@V~0+5h>Q@SE1Vk>M~r6>0^31w1_ezq`yY4e{^j1e8Pic|i`<%8 zBH@1KK{a=#{r>U1tnUoSxvYPSrj_J5gYkbyxLWND)n#9<3uKRgNY=@B?vK8OW6Soo zYD6lwGzV+QA$rnXc8Z)~_LUbFakRwvn`0!4f8(_!OWi@W<2ieT-))4k1v131lXwKE zL~NO<+t1nUjrxGM2^0^fL8WSW8uqEC&M|jw&W|`agLCHPU{yWFt*N~eLP#y;ylmL~ z`(Lt!-dLhPEN9>O>kJRF!~@sOKU(w%hCInS`K_gkTx{Go^jip#RuFj@B0Izj90<oD&q&O;>K zu^sRr0)^fGwxcLlw|qU+w5_&gO=wE#{JRIfy?@x)L5%;OYj6*m8R3tnl+M3yaCOX? z5iZ+_n-CW-$dfGi|JqKB=Dj>;x|~gf_U7o1mhzo{F$mx?JaE}tbUJfZyGb-F!yoNF zIREa2GxNv1x3~%3c7Y7>$?m`R7G-9MoqXDMy2y=nLR;Map6yA-y|cH(6C+XvIX zDe&7V6CeZ7|9d-e9bD2W9;$|8#dmT^YJ#^D9nSbT^9S3lFW8$}?nit!f2=O-)w;vZq3|&{+PE6|0Q+VPObx2rv`~)w7s9eG+EanMML>^J6q{0&pzwY2XBv zKi}Tj%32Hy#l|_wj7i{9^M!=*CKeRx!YG)NfwTdFVq5qy5L1$c@X>^o|AnbQ=n7*8 z?>XQ~nA3n8fzJa!1kME>0MbUvA>cfiOU3*#a6ZgOXv1(JepJ9>F%a8K#ug#AnJ~XL zEyPBUX*sZohItc^ZhVu6bf+{6<_O>`Kw%;I-ZY$cfU|)nE4G)Yc3c8wm8uOH_JEAH z!MDKt4iI(LKnHLO%pt&Sz_vh&dL*y_<_Cd0fRwlI0fz&30w(|qfhY%K!|(;*ZkUlB zraeF;+q4(BN-z(V)bx?+zR*6@3|(q$fF1;&;&TWHEn|dB@j|{E={f@Rhq(;c2KWiE z9k3MG1$Y#AAFv!43p~afpedxKXan?f*t>3kLY*2LpkKnC!bLF}8=$mXNR9VvAf@{( zusiS@-T-~y(2BGH8uFk=b3bxf4GCJ@`VL4s?t9++B>iY?e*Or1lDiC~wr~YVA^gOf zpHPG7aA;pX^;fGel41zg0(~Jw*-uN2zroyG%#;nk!%WF>sKU4OmS!kGV-J)z5h<)X zAcgfOki`E2b^_i8-VdzjJy6zdclJOL3u6yd1A0Ts45YSAk)XO^fth@x4M=LmR$zM| zZ9tOmwDEWkuqlwr!WY;R*bGSRlKi2vX#q3!qy9i>2$MT-7`!nB;>Rdh1Zm3li$27g zD%fU2i)wg}jxP3u;0m{~`HN;`Y=*W4J^(RXaWeeuppq8bgA5%x{RFnDHZHce$=C>i zHhnSH1q}yH1}y}w1?>c#1YHJsJ*1g}K|MgjL6brBNZ)qQ5zr;jZIDktoRS0e0gV97 z04)V=0__8R3Aze0^~YenzZPohh#&nxlR)!8uYtCM4uQ^qt`}D>v3J%~mk+fsmHQHV zD+}IrwJg357oqHZM9+WjvL#2l6Wj$$>_a@g9!6vy#+GT6wq~i_E2Gai9QZ(;sUC<| z5FwXPoXG8j|EpYn@r?*9*C z`cTH|y^P*yX&N2p*xyHDEFQ$*03-#F`zZ_hq2iLct^=DxrZDCeF{b^&Sc4Wwaz)D+ z6R$GXKFPQYw{D4_6w5e}B7`tanTuJV2#TBpQa3Y}_hpP}!MI+s+7GRV zWeK`un{QrRMF z*xdaHqt=G;W@9l+Eq^J%G^R*{cFo2P)cLh}*kTiIMQjd9=^#*7?k*G1CY>dTn1 z|0%}QD#o(2jNwq<?0yyr2NN*QOZW^-x^V}Vq3WKFnWB;*s~AUq5V=x z!!cB(ghonE6_v0#W3%Y;q%5|G@5<;gozWpGdF(4}uCOzfN^{(bp&fZ#D*@$PX0xBP zijk6okr&xsb7xH3Z(xQgMzSbLba_oS3zSMF@&1O*R?*=_5`iiy`(-UTrLj9$uFTo% z3D&h1d%+T^ym3ZOqx}8fX915|M!)wM3rZOSC56^TZ0^~N(Q$!s{d`9MpBalpgBc&bAP-;^f%M|0&Qn}8G0@*4>a#PB(>IrtYRhnbo z5H|adWz?kess4q{QEu#Se;ENK#7O%O5tY~-(_jj?>;dsWRBep(>wfpM{b?+ZliX&h zbh%R5k{d|?>Eb?w@uuWprL+?32DXpyf&3?rawMQ-d)OS+i*diG+{iE4Oz+2#d`+U5 zMPHXQ zk^0fh&pgJMeu}a32IIhd#?AMz{LS8MuI|9*j7(8H$)b9_Wh9fhOFWWFSJ;Qm@kbbo zB%*295}}CX{=oJ(S2G5R{#ew3&HE*%9J|@<{fB`Wreslt34Y9oUe4$cmAPIWb}{(Wj)L0R4LLlM3W*KFQersqj{qI2TE;s{KO8nN-vfv`XFx% z+n?UYn9!NAZYtxVy}}nw>b;81x!6>q04t`kIaA!%VDd@!H5h&y?LX3o1rntFcb8_= zeJk5n_Yn_-A9D|zE8Q3a4=^UpV2lz?nw7)mvmT6jhZyJQG1fqn8vTFx0=B5?$yk3M zW1__LW&p>yR4_|$q+rc_mLDh)sQQ%6S0o`x;(wi}>RM6hSGGy}PdLmDl0q1JHWCk| zU1xD+G37}!OprR0C6%vCvbwe_N3>3A_kJ0&jhH<3m;&)1i{lW;!Y~%*!FBr3TDg+6tiG=L2t%Urs`HKFw&nfq&Z_`Gsg9z7e+eR zTraI9R>lE-g0(j0j}@%L_xSA1Gd!eE8>pB)vKwQR=%tE9Y%Vm^0kpwzHdh33iD!lh zKa9;O(jzQFb)XtiF0+J^Z`m9#UDMg2hB?FJc$gVCqs4&?H|ln=xlqjgrDQU%vwd7g z#?8`rY9s>r5`iL#K&9xnaA^}`rA?F?Z2|f%QZjD6WK@=sY=2fNU1@JN-;{-vx@tBDN&;(sXY;_Nj2Zd&@{hA(kzT`QKk2J-+}WHj z%_d1Scae0O>&4ytzAU$2^hQ=Pn=6YLW2Mselx7&y->}ax-CV{3wNfVK@348lOa;@{ zhm&z+_4##61Bwu%k%qagW!pQH;0%cPf zyYFRmNFR4Pi_KM{sN(jq*JbpWDbI}=)l$3j zBAcuiDuounv1RC7!O^Ar0qCQW1v5qB{%!&@Xpme3CQPnDta z8e@V8_J4!T>&1gqsf^dgvwiB{jG7ch_$oH%O3sAHOfdZ-+b2B9=qDQUY$ThDGDP7d ziONL6jR=(#G8RhrS@t@c6U~eXQs#>!;xST3$|VBfeK_YFqCu}o1HD!#6Qua4P*_^xu zi11A{(j2O%Fk{(n#zG0m>dWTRrHuZ6GUkY;taOgrzh(Op(U_T1#@D0|sgGrT(safU zC_JP6_b*|KYs(p9J8@Y>9%FOCG{*D~8Mp3WtnI=WCH%U*Y%V|*rdCzDlFiE+F&4@= z!s8w`*YA_|pDq)rWKp3-t5_gmJY%9Kqla@WC-$XMH~i)@KlLmlPMR4J$T`4RFDX9V zk0X}g!}dM1g>fy3EeeJ)7Jb7QS<2|hW9+$_F-fv^Q8}Blwld~>F&2q`Y2u&1V*6TE z{gwSm)#qz_a1%|MbfoxQr0^Y3d#{WXyZC7lHBM3N>4meO3lyc-_Rn$9}vMW7&l8j^0#vUX&2Z&dMIN^IAi8R zBJaj>c~ajZrF$uC%lvwsG4T;GZ)Oanp#s7;)qT$vXC>go-`JcYJRDmj|K-ARV2-oj<%@6H0@(v0@s zVsoyve@(GDZWE)w%v;N2*_Z@bgi5n zjFsA+C%EWGwvUMx4^tS+_cB(&JIcu{XESzV`~6as1=8(ApJDsVNFcTUaH%xi{g@FG z##kVl>YC(C!U49Ap24_T`j;y8&w%ByUj!ewsCTE^x@>!khfKhG95 z!x=q-IRXii6M>D{K3|%TpG0VxJIfXAWWJwddA0Nfey7=fSx3eS3AkD+=~z2PBvfWG z7g#_O9iJM`=4vUD%-$@QyMpb8YR@p0 zh;FZ0#{tBMMobnRUs22U;gTbXJ=vTq0pwPSxdlfkHI&U2(h4e`5%(W5rbtet8Y&&_ zFV?|~%uL4gIuXoeT=W)WT_48v=NO|UMOl;BTq~L}NpyX=RMz;7%#ZBNSk+$KCj$|_ zDM56))|45!FEfsntPGSg3{PVFQVFpCEH+0=Gc1)Hyea&;cbPw5G-#@{f<>aLwPI=i z@i$p8P0F^rG!wtYY+rGe@k$J1ptR#i8DP|RWBX`P(SDoQoGDX*q`qvfs9{{+iE->y zY5!@Dvqg+FoB7fjszedZf1dgMCF|mx5i4W+T-ne|?!xA>6vkxf@4Ypy8&O$oUnE$S zgZ!svQxd`G{WfFP$AVoMqeQW!i0%%5h3);HW8B<>G4L{D&PB%g5|ICDHrI;6x-yf^ zSsAiNGXGn)@Hop@$CrRy1Y|9?xN?nNlp3RO}M!%OBH%pP_O6w^X`55sxS|XZY z)_LSV#iai{#=Hj@t-mumHZs=rVq7Lg;n#u9nv`is5t~zkID#>v z%14SSA1OteDdD8gV)^bFGWtz;pDn7TEJun*1){U#MQ4}qX1PT-84G+F>z6W?O4;L6 z@Ui_VUc_M7#ccqBSIaw?nCO9Vw_$E;v;>=?#@ z;@?eC*@e;!H~-B1dX89zspx*TDCokNlfoD+y1S?7?wc#wzD&xzX9%0Sf5KQU?Y`bD z_Qw1kTZl63-g<`ZudQM%D8}{egBTM92mZ+BEb*{P>PYNawoeyTeO89& z71P;1R#Y{8-iYd0nxSw^rbVKnqew*~d{bH}3skLTOt6cC)r=#htfEudoFBm0^FuNJ z#F$dcIR8Dy@Q)b_f*H4p<~#i=n-kD{jrLzF?XpNPTzaW!S(-@{)m#|NwYw^mJ=ols zF{U|VnFQotC;`00m@Gw8K8np1mlUlpOO8MfxeAvobE=3hU5PaUta=WN=eLdL^d-6b z6|Ca)FgIrJ_n7ar@%kw|x{4;W4IU~N} zmCt&&ZOqQQ%mquCOX8TjB{C0rgV_ep$H4N89BHsv-fr!%v%%UAnU~9y^%1YWewOvg z5~90J;Pj*;%qQhiY7+Y)t65+0gt=!A=1Z}P(F^aota!AS`TRS~$!_8sZ*e+b_=i<9mZ^v4i8ar2kjd>UgwM@#GE{odEQLsh5u#_>cl)r zV)({uoKBW6QG#?t!+_ppeUaFE58||U91o~Oygv!A>Gb|j{+10MjbQeb4)l=@T>6Uj z*Q+t-uVL<4n>kr_Nvy1Kvdd}ZlshjW-B;|~#13(d_y24$923J8j+8Yn-o@z|GPPsG z>t|eGeTa1YzU-os*H}L$o<}-HoO*{`XlAeC{BS?!N3UW2)%IE<4d?rFda4I=f0>Ev z$2omnDmYV}8)#d?`a54UyCpH>7ZmAwv!sLJa`h@nWqqG6%qR0?Dz3|v^|Q(-DeMzZ>)TOU&23c_zFiqK)a!`eTQg6N;I8O8G|vIQ?X?W<38(fns^xen-Cg zU$}w|r?%k+F3H`kv)q`1_H({(e`ebe<^$s8=jAp0mET$4Qv#BQ1R&FoN{{t_^dB}T za;h^ppZ|f3kjROYV@(%KYdM>vKjiPm;%ZTUAbP6lcyCryL>!@K8TAf%c7{ z@1%m!%>AR7i#}mC@l+W*KIU|ijC72|_LFjD^N=;S$zf%Zvtgtx(aED+K6xzjm>@a- zomE(INA|UcgVSm9_A`cjA#V2}pV!f$3`@+a;oSq>e`Mfx3(z~ob z-;lX8+SKjlonhflPstGPo%#!>N6J?zUJ^)-NnqJ}lk+b{Gq077=7(~+!M~Z8d?j`X z%t6bU$4e-thr2zi=53Yk+?S*8i7ZgE+%}5DxnpB&<}p`%Kmxn}@0?yP9=PK+ryt#7 zzH)=vSGe1+oZfhad5J3s47<#VVdt2OPcx5~OTqO5PS0D&Tr`+DSv>2CID}2sF;2F? z>~?Gy+L+nD7V{%-<{ZUvLgR2%R`hXa9wK|jDV!`Lo+`oN*ebRwmKn>6;q)0f!TNY` zdYHVS4sFWm9g;uf15Q6VB0-?-C03l5HNPZhY5v!&Pl#i_`IOly6*y(hz2QX4rSmhG z52rBCUdLQ4Gvb9)U)gz`5W5Ky1TICeB36C~Wvbk@he*%e#OZRfq+lU)|KFI;%aJzb z6sO0_UR$!A(^(SThRH!QqZ{jsUzH$`ECmtbb$}^ z#*@tVW%ECgbZ4mknU=JS!7^NiVY(kzsdW}yU}(5`GaTb#@JkkexZGk5OA zobZU*B+fZCR_y9B=g2*6hy=J9GQ%hJK(PMFfjp9|e{q2{X}GP7;F5T2@m0=Gkdr8B z7^hF(W-h43oZODNo9vFxZ%O{E%)XnM57Y#sePeA)RwT&d%lTwZ-;w>gRRWZ+T>j&( zasFXBY1SU#^xEOfMGcsf{Fq~9rjq4g*(e9gj1jW`bL25*-XJc}U0;*`kf5y0h4Lz#2rEGXKI`B&THfE+Tze&X~QS?lp~hT1x? zKJ5wf_#c=XNcl4o`Lb}jtNLz=m*Y>ia{b~%_s4VoTDA7DyOJl{YKcU)IEiRpa@%lD zWWyOg%-!tFu>+V3B%hHp#?OW_y$M zJ0zkFlZbZzJ=UK&&3s9|49q{zX@3b^vn4K!iDvy08ED(D@me|QY@c{w`@ggs>YO_KW0$P#y(1AF+7ku0HcIfq1} zL?U8?aZ>S2<^vKLb9!_7kwiMvLr!;==ddTTO+(~s5T`8Z)X8kuUwmga2CiQMgg)gA z{~pYJq~fBwoDP)`S|lO#rbM_&b2-181SGc)IqfZn*Cmz^Gu zWm_dn4`+n3q3>JFlip+=_8s#jb{^x=a8A3`Vjka`eJ8&^r=3a6NoMA?SB0hg^~;!l zwGTUsbGXS!Jmdn>{{ZJ-l7`0D=X8mryU9qmN(Yl=gd=6mkG0?qP5oBNjbJWV%v_u& zBTth6ksr<(X%dPLWOLd>)~rMVN=Yv3N48`>vx|A2*!O&m(@W|x4-;p6B<1?Z0P-4~ zWrIF$%%PYMH6x~YW{-BvMSpODUtq>1`#XU%$!uYsJ}1 zny56^-O_E;wG^EdUfWTvV>PsIDJw=c}O9rpPXXOnJD%W zvWqStjrNTYnUeAHnj=kaC|AU*FG(nE@PI3rDsK_SByc)>74xHq%#&ohUiwV*e=%oC zNbhr*)ARbs{`Zwf*zt0TdCOE4$dZhKq4J3w=}0$;>G=}VV-It_QzG0jxvXxLeV-=f z+e-a$Z%T*aF@9BXAKBNTqdB9X9kW{_<`Nlkk%iMXdH3!iPeAtOfB^V(GAOYY1) zC1m@{S>Y`q+cp;SuR3u3SLS3nmk)SzI#diNNr*09!+MYJnRCW5-+lo!KF!c8hZzlaUminDFC@(4#tI_Ws)Kamdk%C^hd z!}=Mrlvxs}g6vYCM8GAkfTv~@?HjgEY|vS@(b^9)Ddr60b zYH>sPGSV|XoFDfJv-fG{dE!g93{K-uMDzYHk#pN$BH)bqY%n#Sc~UrYLMHRc&dhON zFrVqb>>(W)Cfjq^c-AM&Or4Z%>|Db7;v<-UHO01U<{?GQOHMK$c%ONpyrg<0OEFR+ zD|LA$#^2?1@&aaG@tOMpoIhJ;?opn+4lBrE!#?uuf~g^=L;bjb$68J| zkOpSU+QOIg0PaiZow}LRZr@0Gxh)q-2!0|VJm+PuH}8yi_mgkAz&yDcnO1Y!w?1