From fc6f2fbf779cb6ac798b46dd5f0b4aa2010848df Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Wed, 20 Mar 2024 14:01:17 -0400 Subject: [PATCH 01/60] Adding time keeper code throughout the kinematics stack, the mobil base and all associated classes --- .../kinematics/AbstractKinematicsNR.java | 33 +++++----- .../sdk/addons/kinematics/AbstractLink.java | 13 +++- .../sdk/addons/kinematics/DHChain.java | 16 +++-- .../kinematics/DHParameterKinematics.java | 6 ++ .../sdk/addons/kinematics/MobileBase.java | 8 +++ .../kinematics/gcodebridge/GcodeDevice.java | 6 +- .../sdk/addons/kinematics/imu/IMU.java | 8 ++- .../sdk/addons/kinematics/imu/IMUUpdate.java | 34 +++++++++- .../addons/kinematics/time/ITimeProvider.java | 14 +++++ .../addons/kinematics/time/TimeKeeper.java | 62 +++++++++++++++++++ .../sdk/bowlercam/device/BowlerCamDevice.java | 10 +-- .../sdk/common/BowlerAbstractDevice.java | 3 +- .../sdk/dyio/peripherals/ServoChannel.java | 2 +- .../bcs/pid/LegacyPidNamespaceImp.java | 4 +- .../namespace/bcs/pid/PidNamespaceImp.java | 4 +- .../sdk/pid/InterpolationEngine.java | 11 +++- .../com/neuronrobotics/sdk/pid/PIDEvent.java | 4 +- .../neuronrobotics/sdk/pid/PausableTime.java | 27 ++++---- .../sdk/pid/VirtualGenericPIDDevice.java | 22 +++++-- 19 files changed, 224 insertions(+), 63 deletions(-) create mode 100644 src/main/java/com/neuronrobotics/sdk/addons/kinematics/time/ITimeProvider.java create mode 100644 src/main/java/com/neuronrobotics/sdk/addons/kinematics/time/TimeKeeper.java diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractKinematicsNR.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractKinematicsNR.java index 05ab5000..f5b7451d 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractKinematicsNR.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractKinematicsNR.java @@ -16,6 +16,8 @@ import com.neuronrobotics.sdk.addons.kinematics.imu.IMU; import com.neuronrobotics.sdk.addons.kinematics.math.RotationNR; import com.neuronrobotics.sdk.addons.kinematics.math.TransformNR; +import com.neuronrobotics.sdk.addons.kinematics.time.ITimeProvider; +import com.neuronrobotics.sdk.addons.kinematics.time.TimeKeeper; import com.neuronrobotics.sdk.addons.kinematics.xml.XmlFactory; import com.neuronrobotics.sdk.common.BowlerAbstractDevice; import com.neuronrobotics.sdk.common.BowlerDatagram; @@ -255,16 +257,6 @@ public AbstractKinematicsNR(Element doc, LinkFactory f) { } - /** - * Gets the date. - * - * @return the date - */ - private String getDate() { - Timestamp t = new Timestamp(System.currentTimeMillis()); - return t.toString().split("\\ ")[0]; - } - /** * Load XML configuration file, then store in LinkConfiguration (ArrayList * type). @@ -1199,15 +1191,15 @@ public void onPIDLimitEvent(PIDLimitEvent e) { @Override public void onPIDEvent(PIDEvent e) { - homeTime = System.currentTimeMillis(); + homeTime = currentTimeMillis(); } }; joint.addPIDEventListener(listen); - homeTime = System.currentTimeMillis(); + homeTime = currentTimeMillis(); joint.SetPIDSetPoint(tps, 0); Log.info("Homing output to value: " + tps); - while ((System.currentTimeMillis() < homeTime + 3000)) { + while ((currentTimeMillis() < homeTime + 3000)) { ThreadUtil.wait(100); } joint.removePIDEventListener(listen); @@ -1691,8 +1683,8 @@ public void asyncInterpolatedMove(TransformNR target, double seconds, Interpolat } public InterpolationMoveState blockingInterpolatedMove(TransformNR target, double seconds, InterpolationType type, double ...conf ) { - InterpolationEngine engine = new InterpolationEngine(); - long currentTimeMillis = System.currentTimeMillis(); + InterpolationEngine engine = new InterpolationEngine(getTimeProvider()); + long currentTimeMillis = currentTimeMillis(); TransformNR delta =getDeltaToTarget(target); TransformNR startingPoint = getCurrentPoseTarget(); if (checkTaskSpaceTransform(target)) { @@ -1717,7 +1709,7 @@ public InterpolationMoveState blockingInterpolatedMove(TransformNR target, doubl // of the translation // the new tip point here calculated is multiplied by the starting point to get // a global space tip target - TransformNR nextPoint = getTipAlongTrajectory(startingPoint,delta,engine.getInterpolationUnitIncrement(System.currentTimeMillis())); + TransformNR nextPoint = getTipAlongTrajectory(startingPoint,delta,engine.getInterpolationUnitIncrement(currentTimeMillis())); // now the best time for this increment is calculated double bestTime = getBestTime(nextPoint); // error check for the best time being below the commanded time @@ -1743,4 +1735,13 @@ public InterpolationMoveState blockingInterpolatedMove(TransformNR target, doubl } return InterpolationMoveState.READY; } + @Override + public void setTimeProvider(ITimeProvider t) { + super.setTimeProvider(t); + imu.setTimeProvider(getTimeProvider()); + for(int i=0;i links = new ArrayList(); @@ -114,9 +116,7 @@ public double[] inverseKinematics(TransformNR target,double[] jointSpaceVector ) if(getLinks() == null) return null; - long start = System.currentTimeMillis(); - - + //is = new GradiantDecent(this,debug); //is = new SearchTreeSolver(this,debug); if(getInverseSolver() == null) @@ -483,5 +483,13 @@ public void setFactory(LinkFactory factory) { lowerLimits = factory.getLowerLimits(); this.factory = factory; } + @Override + public void setTimeProvider(ITimeProvider t) { + super.setTimeProvider(t); + for(DHLink l:getLinks()) { + if (l.getSlaveMobileBase()!=null) + l.getSlaveMobileBase().setTimeProvider(getTimeProvider()); + } + } } diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/DHParameterKinematics.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/DHParameterKinematics.java index ec60362c..0812d9f5 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/DHParameterKinematics.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/DHParameterKinematics.java @@ -12,6 +12,7 @@ import javafx.scene.transform.Affine; import com.neuronrobotics.sdk.addons.kinematics.math.TransformNR; +import com.neuronrobotics.sdk.addons.kinematics.time.ITimeProvider; import com.neuronrobotics.sdk.addons.kinematics.xml.XmlFactory; import com.neuronrobotics.sdk.common.BowlerAbstractDevice; import com.neuronrobotics.sdk.common.IDeviceConnectionEventListener; @@ -836,4 +837,9 @@ public void throwExceptionOnJointLimit(boolean b) { public TransformNR getLinkTip(int linkIndex) { return getChain().getCachedChain().get(linkIndex); } + @Override + public void setTimeProvider(ITimeProvider t) { + super.setTimeProvider(t); + getDhChain().setTimeProvider(t); + } } diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java index c8e889ad..512ea070 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java @@ -17,6 +17,7 @@ import com.neuronrobotics.sdk.addons.kinematics.math.RotationNR; import com.neuronrobotics.sdk.addons.kinematics.math.TransformNR; import com.neuronrobotics.sdk.addons.kinematics.parallel.ParallelGroup; +import com.neuronrobotics.sdk.addons.kinematics.time.ITimeProvider; import com.neuronrobotics.sdk.addons.kinematics.xml.XmlFactory; import com.neuronrobotics.sdk.common.DeviceManager; import com.neuronrobotics.sdk.common.Log; @@ -1020,5 +1021,12 @@ public void onJointSpaceLimit(AbstractKinematicsNR source, int axis, JointLimit public void sync() { doSync(); } + @Override + public void setTimeProvider(ITimeProvider t) { + super.setTimeProvider(t); + for(DHParameterKinematics k:getAllDHChains()) { + k.setTimeProvider(getTimeProvider()); + } + } } diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/gcodebridge/GcodeDevice.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/gcodebridge/GcodeDevice.java index 937188b5..746967fe 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/gcodebridge/GcodeDevice.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/gcodebridge/GcodeDevice.java @@ -203,15 +203,15 @@ public String runLine(String line) { // TODO Auto-generated catch block e.printStackTrace(); } - long start = System.currentTimeMillis(); + long start = currentTimeMillis(); String ret= ""; while(ret.contentEquals("") && - (System.currentTimeMillis()-start)>"+line); diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/imu/IMU.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/imu/IMU.java index 19fd5d02..e8686940 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/imu/IMU.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/imu/IMU.java @@ -2,12 +2,14 @@ import java.util.ArrayList; -public class IMU { +import com.neuronrobotics.sdk.addons.kinematics.time.TimeKeeper; + +public class IMU extends TimeKeeper{ private ArrayList virtualListeneras = new ArrayList(); private ArrayList hardwareListeneras = new ArrayList(); - private IMUUpdate virtualState=new IMUUpdate(0.0,0.0,0.0,0.0,0.0,0.0); - private IMUUpdate hardwareState=new IMUUpdate(null,null,null,null,null,null); + private IMUUpdate virtualState=new IMUUpdate(0.0,0.0,0.0,0.0,0.0,0.0,currentTimeMillis()); + private IMUUpdate hardwareState=new IMUUpdate(null,null,null,null,null,null,currentTimeMillis()); public void addhardwareListeners(IMUUpdateListener l){ if(!hardwareListeneras.contains(l)) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/imu/IMUUpdate.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/imu/IMUUpdate.java index 459fd911..539a9d46 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/imu/IMUUpdate.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/imu/IMUUpdate.java @@ -1,4 +1,7 @@ package com.neuronrobotics.sdk.addons.kinematics.imu; + +import com.neuronrobotics.sdk.addons.kinematics.time.TimeKeeper; + /** * This is a state object for the IMU * any function that returns null has no new data availible. @@ -6,6 +9,7 @@ * */ public class IMUUpdate { + private static boolean notice=true; private final Double xAcceleration; private final Double yAcceleration; private final Double zAcceleration; @@ -13,7 +17,28 @@ public class IMUUpdate { private final Double rotyAcceleration; private final Double rotzAcceleration; private long timestamp; - + /** + * Values represent current state of accelerations + * Null values means there is no update for this value + * @param xAcceleration (meters / second^2) + * @param yAcceleration (meters / second^2) + * @param zAcceleration (meters / second^2) + * @param rotxAcceleration (radian / second^2) + * @param rotyAcceleration (radian / second^2) + * @param rotzAcceleration (radian / second^2) + */ + public IMUUpdate(Double xAcceleration,Double yAcceleration,Double zAcceleration, + Double rotxAcceleration,Double rotyAcceleration,Double rotzAcceleration , long timestamp + ){ + this.xAcceleration = xAcceleration; + this.yAcceleration = yAcceleration; + this.zAcceleration = zAcceleration; + this.rotxAcceleration = rotxAcceleration; + this.rotyAcceleration = rotyAcceleration; + this.rotzAcceleration = rotzAcceleration; + this.setTimestamp(timestamp); + + } /** * Values represent current state of accelerations @@ -25,6 +50,7 @@ public class IMUUpdate { * @param rotyAcceleration (radian / second^2) * @param rotzAcceleration (radian / second^2) */ + @Deprecated public IMUUpdate(Double xAcceleration,Double yAcceleration,Double zAcceleration, Double rotxAcceleration,Double rotyAcceleration,Double rotzAcceleration ){ @@ -34,7 +60,11 @@ public IMUUpdate(Double xAcceleration,Double yAcceleration,Double zAcceleration, this.rotxAcceleration = rotxAcceleration; this.rotyAcceleration = rotyAcceleration; this.rotzAcceleration = rotzAcceleration; - this.setTimestamp(System.currentTimeMillis()); + if(notice) { + notice=false; + new RuntimeException("This constructor is depricated, please provide a timestamp").printStackTrace(System.out); + } + this.setTimestamp(TimeKeeper.getMostRecent().currentTimeMillis()); } diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/time/ITimeProvider.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/time/ITimeProvider.java new file mode 100644 index 00000000..f3ae9a22 --- /dev/null +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/time/ITimeProvider.java @@ -0,0 +1,14 @@ +package com.neuronrobotics.sdk.addons.kinematics.time; + +public interface ITimeProvider { + //default public final long timestamp = System.currentTimeMillis(); + default long currentTimeMillis() { + return System.currentTimeMillis(); + } + default void sleep(long time) throws InterruptedException { + Thread.sleep(time); + } + default void sleep(long ms,int ns) throws InterruptedException { + Thread.sleep(ms,ns); + } +} diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/time/TimeKeeper.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/time/TimeKeeper.java new file mode 100644 index 00000000..b9b19c5c --- /dev/null +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/time/TimeKeeper.java @@ -0,0 +1,62 @@ +package com.neuronrobotics.sdk.addons.kinematics.time; + +public class TimeKeeper { + private static ITimeProvider mostRecent; + + private ITimeProvider clock = new ITimeProvider() {}; + public void setTimeProvider(ITimeProvider t) { + if(t==null) + t= new ITimeProvider() {}; + clock = t; + setMostRecent(clock); + } + public ITimeProvider getTimeProvider() { + return clock; + } + + public void sleep(long time) throws InterruptedException { + getTimeProvider().sleep(time); + } + public void sleep(long ms,int ns) throws InterruptedException { + getTimeProvider().sleep(ms,ns); + } + + /** + * Wait. + * + * @param time the time + */ + public void wait(int time) { + try { sleep(time); } catch (InterruptedException e) { throw new RuntimeException(e); } + } + + /** + * Wait. + * + * @param time0 the time0 + * @param time1 the time1 + */ + public void wait(int time0, int time1) { + try { sleep(time0, time1); } catch (InterruptedException e) {throw new RuntimeException(e); } + } + + public long currentTimeMillis() { + return getTimeProvider().currentTimeMillis(); + } + /** + * @return the mostRecent + */ + public static ITimeProvider getMostRecent() { + if(null==mostRecent) { + mostRecent=new ITimeProvider() {}; + } + return mostRecent; + } + /** + * @param mostRecent the mostRecent to set + */ + public static void setMostRecent(ITimeProvider mostRecent) { + TimeKeeper.mostRecent = mostRecent; + } + +} diff --git a/src/main/java/com/neuronrobotics/sdk/bowlercam/device/BowlerCamDevice.java b/src/main/java/com/neuronrobotics/sdk/bowlercam/device/BowlerCamDevice.java index 4c50a85a..5b096607 100644 --- a/src/main/java/com/neuronrobotics/sdk/bowlercam/device/BowlerCamDevice.java +++ b/src/main/java/com/neuronrobotics/sdk/bowlercam/device/BowlerCamDevice.java @@ -106,8 +106,8 @@ public BufferedImage getHighSpeedImage(int cam) throws MalformedURLException, IO //System.out.println("Reading: "+urls.get(cam) ); ImageReader ir = new ImageReader(cam); ir.start(); - long start = System.currentTimeMillis(); - while(((System.currentTimeMillis()-start)<200) && ir.isDone()==false){ + long start = currentTimeMillis(); + while(((currentTimeMillis()-start)<200) && ir.isDone()==false){ ThreadUtil.wait(5); } if(!ir.isDone()) @@ -353,7 +353,7 @@ public highSpeedAutoCapture(int cam,double scale,int fps){ */ public void run() { //System.out.println("Starting auto capture on: "+getImageServerURL(cam)); - long st = System.currentTimeMillis(); + long st = currentTimeMillis(); while(running && isAvailable()) { //System.out.println("Getting image from: "+getImageServerURL(cam)); try { @@ -370,7 +370,7 @@ public void run() { e.printStackTrace(); } if(mspf != 0) { - long diff = System.currentTimeMillis() - st; + long diff = currentTimeMillis() - st; ////System.out.print("\nMS diff: "+diff); if(diff listeners = new ArrayList(); - - public static long currentTimeMillis() { + public PausableTime(ITimeProvider t) { + setTimeProvider(t); + } + public long currentTimeMillis() { if(!paused) - return System.currentTimeMillis()-durationPaused; + return super.currentTimeMillis()-durationPaused; return timePaused; } - public static void pause(boolean val) { + public void pause(boolean val) { if(val) - timePaused=System.currentTimeMillis(); + timePaused=super.currentTimeMillis(); else - durationPaused+=(System.currentTimeMillis()-timePaused); + durationPaused+=(super.currentTimeMillis()-timePaused); paused=val; for(int i=0;i{ boolean start = paused; pause(false); @@ -35,7 +40,7 @@ public static void step(long ms) { }).start(); } - public static void sleep(long durationMS) { + public void sleep(long durationMS) { try { Thread.sleep(durationMS); } catch (InterruptedException e) { @@ -50,12 +55,12 @@ public static void sleep(long durationMS) { } } - public static void addIPauseTimeListener(IPauseTimeListener l) { + public void addIPauseTimeListener(IPauseTimeListener l) { if(listeners.contains(l)) return; listeners.add(l); } - public static void removeIPauseTimeListener(IPauseTimeListener l) { + public void removeIPauseTimeListener(IPauseTimeListener l) { if(listeners.contains(l)) listeners.remove(l); } diff --git a/src/main/java/com/neuronrobotics/sdk/pid/VirtualGenericPIDDevice.java b/src/main/java/com/neuronrobotics/sdk/pid/VirtualGenericPIDDevice.java index 20b77451..be76f9e8 100644 --- a/src/main/java/com/neuronrobotics/sdk/pid/VirtualGenericPIDDevice.java +++ b/src/main/java/com/neuronrobotics/sdk/pid/VirtualGenericPIDDevice.java @@ -5,6 +5,7 @@ import com.neuronrobotics.sdk.addons.kinematics.IHardwareSyncPulseProvider; import com.neuronrobotics.sdk.addons.kinematics.IHardwareSyncPulseReciver; +import com.neuronrobotics.sdk.addons.kinematics.time.ITimeProvider; import com.neuronrobotics.sdk.common.BowlerAbstractCommand; import com.neuronrobotics.sdk.common.BowlerDatagram; import com.neuronrobotics.sdk.common.InvalidConnectionException; @@ -189,7 +190,7 @@ public boolean ResetPIDChannel(int group, float valueToSetCurrentTo) { */ @Override public boolean SetPIDSetPoint(int group, float setpoint, double seconds) { - long currentTimeMillis = System.currentTimeMillis(); + long currentTimeMillis = currentTimeMillis(); sync.setPause(true); synchronized(interpolationEngines) { getDriveThread(group).StartLinearMotion(setpoint, seconds,currentTimeMillis); @@ -247,7 +248,7 @@ public void flushPIDChannels(double time) { */ @Override public boolean SetAllPIDSetPoint(float[] setpoints, double seconds) { - long start = System.currentTimeMillis(); + long start = currentTimeMillis(); sync.setPause(true); synchronized(interpolationEngines) { for (int i = 0; i < setpoints.length; i++) { @@ -313,7 +314,7 @@ public float[] GetAllPIDPosition() { PIDConfiguration conf = new PIDConfiguration(); conf.setGroup(i); conf.setEnabled(true); - InterpolationEngine d = new InterpolationEngine(); + InterpolationEngine d = new InterpolationEngine(getTimeProvider()); interpolationEngines.put(conf, d); configs.put(i, conf); } @@ -325,6 +326,13 @@ public float[] GetAllPIDPosition() { } return backs; } + @Override + public void setTimeProvider(ITimeProvider t) { + super.setTimeProvider(t); + for(InterpolationEngine e:interpolationEngines.values()) { + e.setTimeProvider(getTimeProvider()); + } + } /** * Sets the max ticks per second. @@ -369,12 +377,13 @@ public void run() { long time; while (runSync) { try { - Thread.sleep(threadTime); + sleep(threadTime); } catch (InterruptedException ex) { + return; } if(!pause) { sync = false; - time = System.currentTimeMillis(); + time = currentTimeMillis(); synchronized(interpolationEngines) { for (PIDConfiguration key : interpolationEngines.keySet()) { InterpolationEngine dr = interpolationEngines.get(key); @@ -405,10 +414,11 @@ public void run() { }else while (isPause()) try { - Thread.sleep(1); + sleep(1); } catch (InterruptedException e1) { // TODO Auto-generated catch block e1.printStackTrace(); + return; } if (sync) doSync(); From 177099715a00da88868eba4457c66d7c813b94b7 Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Wed, 20 Mar 2024 14:53:06 -0400 Subject: [PATCH 02/60] Adding wait and sleep --- .../sdk/addons/kinematics/AbstractKinematicsNR.java | 4 ++-- .../sdk/addons/kinematics/WalkingDriveEngine.java | 4 ++-- .../sdk/addons/kinematics/gcodebridge/GcodeDevice.java | 2 +- .../sdk/addons/kinematics/time/TimeKeeper.java | 3 +++ .../sdk/bowlercam/device/BowlerCamDevice.java | 6 +++--- src/main/java/com/neuronrobotics/sdk/pid/PausableTime.java | 4 ++-- .../com/neuronrobotics/sdk/pid/VirtualGenericPIDDevice.java | 4 ++-- 7 files changed, 15 insertions(+), 12 deletions(-) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractKinematicsNR.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractKinematicsNR.java index f5b7451d..7b7595b3 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractKinematicsNR.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractKinematicsNR.java @@ -1200,7 +1200,7 @@ public void onPIDEvent(PIDEvent e) { joint.SetPIDSetPoint(tps, 0); Log.info("Homing output to value: " + tps); while ((currentTimeMillis() < homeTime + 3000)) { - ThreadUtil.wait(100); + wait(100); } joint.removePIDEventListener(listen); } @@ -1728,7 +1728,7 @@ public InterpolationMoveState blockingInterpolatedMove(TransformNR target, doubl // incremental tip failed, fault return InterpolationMoveState.FAULT; } - ThreadUtil.wait((int) msPerStep); + wait((int) msPerStep); } }else { return InterpolationMoveState.FAULT; diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/WalkingDriveEngine.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/WalkingDriveEngine.java index 1831b444..93257ad9 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/WalkingDriveEngine.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/WalkingDriveEngine.java @@ -56,10 +56,10 @@ public void DriveArc(MobileBase source, TransformNR newPose, double seconds) { try { // lift leg above home legs.get(i).setDesiredTaskSpaceTransform(home[i], seconds/10); - ThreadUtil.wait((int) (seconds*100)); + source.wait((int) (seconds*100)); //step to new target legs.get(i).setDesiredTaskSpaceTransform(feetLocations[i], seconds/10); - ThreadUtil.wait((int) (seconds*100)); + source.wait((int) (seconds*100)); //set new target for the coordinated motion step at the end feetLocations[i].translateX(newPose.getX()); feetLocations[i].translateY(newPose.getY()); diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/gcodebridge/GcodeDevice.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/gcodebridge/GcodeDevice.java index 746967fe..c6baab1f 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/gcodebridge/GcodeDevice.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/gcodebridge/GcodeDevice.java @@ -208,7 +208,7 @@ public String runLine(String line) { while(ret.contentEquals("") && (currentTimeMillis()-start) getBlobs(){ send(new BlobCommand()); while(gotLastMark == false && isAvailable()){ try { - Thread.sleep(10); + sleep(10); } catch (InterruptedException e) { // TODO Auto-generated catch block e.printStackTrace(); @@ -375,7 +375,7 @@ public void run() { if(diff Date: Wed, 20 Mar 2024 15:19:03 -0400 Subject: [PATCH 03/60] adding a listener for timebase change --- .../addons/kinematics/time/TimeKeeper.java | 28 +++++++++++++++++-- 1 file changed, 25 insertions(+), 3 deletions(-) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/time/TimeKeeper.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/time/TimeKeeper.java index 3752c2c9..d527edc5 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/time/TimeKeeper.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/time/TimeKeeper.java @@ -1,9 +1,11 @@ package com.neuronrobotics.sdk.addons.kinematics.time; -import com.neuronrobotics.sdk.util.ThreadUtil; +import java.util.ArrayList; + public class TimeKeeper { private static ITimeProvider mostRecent; + private ArrayList timebaseChangeListener =new ArrayList<>(); private ITimeProvider clock = new ITimeProvider() {}; public void setTimeProvider(ITimeProvider t) { @@ -11,12 +13,32 @@ public void setTimeProvider(ITimeProvider t) { t= new ITimeProvider() {}; clock = t; setMostRecent(clock); - ThreadUtil.wait(1); + for(int i=0;i Date: Wed, 20 Mar 2024 15:45:21 -0400 Subject: [PATCH 04/60] adding helper functions --- .../sdk/addons/kinematics/DHParameterKinematics.java | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/DHParameterKinematics.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/DHParameterKinematics.java index 0812d9f5..bc7e9a4a 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/DHParameterKinematics.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/DHParameterKinematics.java @@ -837,6 +837,15 @@ public void throwExceptionOnJointLimit(boolean b) { public TransformNR getLinkTip(int linkIndex) { return getChain().getCachedChain().get(linkIndex); } + public MobileBase getFollowerMobileBase(int linkIndex) { + return getDhLink(linkIndex).getSlaveMobileBase(); + } + public MobileBase getFollowerMobileBase(AbstractLink myLink) { + return getDhLink(myLink).getSlaveMobileBase(); + } + public MobileBase getFollowerMobileBase(LinkConfiguration myLink) { + return getDhLink(myLink).getSlaveMobileBase(); + } @Override public void setTimeProvider(ITimeProvider t) { super.setTimeProvider(t); From 1a4fb209a581fea633478256097c456919ef5f91 Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Wed, 20 Mar 2024 17:50:04 -0400 Subject: [PATCH 05/60] fix old warning --- .../neuronrobotics/sdk/common/DMDevice.java | 20 +++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/src/main/java/com/neuronrobotics/sdk/common/DMDevice.java b/src/main/java/com/neuronrobotics/sdk/common/DMDevice.java index c1300770..add1d763 100644 --- a/src/main/java/com/neuronrobotics/sdk/common/DMDevice.java +++ b/src/main/java/com/neuronrobotics/sdk/common/DMDevice.java @@ -1,9 +1,9 @@ -package com.neuronrobotics.sdk.common; +1package com.neuronrobotics.sdk.common; import java.lang.reflect.InvocationTargetException; import java.lang.reflect.Method; import java.util.ArrayList; - +@SuppressWarnings("resource") public class DMDevice extends NonBowlerDevice { private Object wrapped = null; Method methodConnect = null; @@ -17,8 +17,8 @@ public DMDevice(Object o) throws NoSuchMethodException, SecurityException { if(!wrappable(o)) throw new RuntimeException("This object is not wrappable! "); setWrapped(o); - methodConnect = getWrapped().getClass().getMethod("connect", null); - methodDisconnect = getWrapped().getClass().getMethod("disconnect", null); + methodConnect = getWrapped().getClass().getMethod("connect",(Class) null); + methodDisconnect = getWrapped().getClass().getMethod("disconnect",(Class) null); hasGetName = methodExists(getWrapped(), "getName"); hasIsAvailible = methodExists(getWrapped(), "isAvailable"); methodGetName = null; @@ -30,7 +30,7 @@ public String getScriptingName() { if (hasGetName) { if (methodGetName == null) try { - methodGetName = getWrapped().getClass().getMethod("getName", null); + methodGetName = getWrapped().getClass().getMethod("getName",(Class) null); } catch (Exception e) { return super.getScriptingName(); @@ -41,7 +41,7 @@ public String getScriptingName() { if (methodGetName == null) return super.getScriptingName(); try { - super.setScriptingName( (String) methodGetName.invoke(getWrapped(), null)); + super.setScriptingName( (String) methodGetName.invoke(getWrapped(),(Class) null)); } catch (Exception e) { return super.getScriptingName(); } @@ -57,7 +57,7 @@ public ArrayList getNamespacesImp() { @Override public void disconnectDeviceImp() { try { - methodDisconnect.invoke(getWrapped(), null); + methodDisconnect.invoke(getWrapped(), (Class)null); } catch (Exception e) { // TODO Auto-generated catch block e.printStackTrace(); @@ -74,13 +74,13 @@ public boolean isAvailable() throws InvalidConnectionException{ if(hasIsAvailible) { if(isAvaibleMeth==null) { try { - isAvaibleMeth = getWrapped().getClass().getMethod("isAvailable", null); + isAvaibleMeth = getWrapped().getClass().getMethod("isAvailable",(Class) null); } catch (Exception e) { //true } } try { - return (boolean) isAvaibleMeth.invoke(getWrapped(), null); + return (boolean) isAvaibleMeth.invoke(getWrapped(), (Class)null); } catch (Exception e) { //true } @@ -91,7 +91,7 @@ public boolean isAvailable() throws InvalidConnectionException{ @Override public boolean connectDeviceImp() { try { - Object value = methodConnect.invoke(getWrapped(), null); + Object value = methodConnect.invoke(getWrapped(), (Class)null); try { return (Boolean) value; } catch (Exception e) { From ad33397949c8f15699db52a13d589ce03bb64bf8 Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Wed, 20 Mar 2024 17:51:21 -0400 Subject: [PATCH 06/60] removing the compile error --- src/main/java/com/neuronrobotics/sdk/common/DMDevice.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/java/com/neuronrobotics/sdk/common/DMDevice.java b/src/main/java/com/neuronrobotics/sdk/common/DMDevice.java index add1d763..82f13d16 100644 --- a/src/main/java/com/neuronrobotics/sdk/common/DMDevice.java +++ b/src/main/java/com/neuronrobotics/sdk/common/DMDevice.java @@ -1,4 +1,4 @@ -1package com.neuronrobotics.sdk.common; +package com.neuronrobotics.sdk.common; import java.lang.reflect.InvocationTargetException; import java.lang.reflect.Method; From 326d9350e994e61fbd178e62de1ffa74dbe20f1f Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Wed, 20 Mar 2024 20:46:24 -0400 Subject: [PATCH 07/60] adding comments --- .../neuronrobotics/sdk/addons/kinematics/DHLink.java | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/DHLink.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/DHLink.java index d0017543..cf206fca 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/DHLink.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/DHLink.java @@ -221,15 +221,15 @@ public Matrix DhStepInverse(Matrix end, double jointValue) { /** * Dh step prismatic. * - * @param jointValue the joint value + * @param radians the joint value in radians * @return the matrix */ - public Matrix DhStep(double jointValue) { + public Matrix DhStep(double radians) { switch(type){ case PRISMATIC: - return DhStep(0,jointValue); + return DhStep(0,radians); case ROTORY: - return DhStep(jointValue,0); + return DhStep(radians,0); default: case TOOL: return DhStep(0,0); @@ -240,7 +240,7 @@ public Matrix DhStep(double jointValue) { /** * Dh step. * - * @param rotory the rotory + * @param rotory the rotory value in radians * @param prismatic the prismatic * @return the matrix */ @@ -336,7 +336,7 @@ public void setRotX(Matrix rotX) { /** * Sets the matrix. * - * @param rotory the rotory + * @param rotory the rotory value in radians * @param prismatic the prismatic */ private void setMatrix(double rotory,double prismatic){ From d03c232af71083f665cff93a28bc3d94c0252a1b Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Wed, 20 Mar 2024 21:55:17 -0400 Subject: [PATCH 08/60] catch null excceptions --- .../com/neuronrobotics/sdk/addons/kinematics/MobileBase.java | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java index 512ea070..de806e7f 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java @@ -963,7 +963,8 @@ public static void main(String[] args) throws Exception { private void fireIOnMobileBaseRenderChange() { for (int i = 0; i < changeListeners.size(); i++) { IOnMobileBaseRenderChange l = changeListeners.get(i); - l.onIOnMobileBaseRenderChange(); + if(l!=null) + l.onIOnMobileBaseRenderChange(); } } From b636fe4ce88b0a90bf3931eb946a22103b17ae19 Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Thu, 21 Mar 2024 12:27:25 -0400 Subject: [PATCH 09/60] revert changed to reflection code, this is the correct way to do this, compiler be damned --- .../neuronrobotics/sdk/common/DMDevice.java | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/src/main/java/com/neuronrobotics/sdk/common/DMDevice.java b/src/main/java/com/neuronrobotics/sdk/common/DMDevice.java index 82f13d16..c1300770 100644 --- a/src/main/java/com/neuronrobotics/sdk/common/DMDevice.java +++ b/src/main/java/com/neuronrobotics/sdk/common/DMDevice.java @@ -3,7 +3,7 @@ import java.lang.reflect.InvocationTargetException; import java.lang.reflect.Method; import java.util.ArrayList; -@SuppressWarnings("resource") + public class DMDevice extends NonBowlerDevice { private Object wrapped = null; Method methodConnect = null; @@ -17,8 +17,8 @@ public DMDevice(Object o) throws NoSuchMethodException, SecurityException { if(!wrappable(o)) throw new RuntimeException("This object is not wrappable! "); setWrapped(o); - methodConnect = getWrapped().getClass().getMethod("connect",(Class) null); - methodDisconnect = getWrapped().getClass().getMethod("disconnect",(Class) null); + methodConnect = getWrapped().getClass().getMethod("connect", null); + methodDisconnect = getWrapped().getClass().getMethod("disconnect", null); hasGetName = methodExists(getWrapped(), "getName"); hasIsAvailible = methodExists(getWrapped(), "isAvailable"); methodGetName = null; @@ -30,7 +30,7 @@ public String getScriptingName() { if (hasGetName) { if (methodGetName == null) try { - methodGetName = getWrapped().getClass().getMethod("getName",(Class) null); + methodGetName = getWrapped().getClass().getMethod("getName", null); } catch (Exception e) { return super.getScriptingName(); @@ -41,7 +41,7 @@ public String getScriptingName() { if (methodGetName == null) return super.getScriptingName(); try { - super.setScriptingName( (String) methodGetName.invoke(getWrapped(),(Class) null)); + super.setScriptingName( (String) methodGetName.invoke(getWrapped(), null)); } catch (Exception e) { return super.getScriptingName(); } @@ -57,7 +57,7 @@ public ArrayList getNamespacesImp() { @Override public void disconnectDeviceImp() { try { - methodDisconnect.invoke(getWrapped(), (Class)null); + methodDisconnect.invoke(getWrapped(), null); } catch (Exception e) { // TODO Auto-generated catch block e.printStackTrace(); @@ -74,13 +74,13 @@ public boolean isAvailable() throws InvalidConnectionException{ if(hasIsAvailible) { if(isAvaibleMeth==null) { try { - isAvaibleMeth = getWrapped().getClass().getMethod("isAvailable",(Class) null); + isAvaibleMeth = getWrapped().getClass().getMethod("isAvailable", null); } catch (Exception e) { //true } } try { - return (boolean) isAvaibleMeth.invoke(getWrapped(), (Class)null); + return (boolean) isAvaibleMeth.invoke(getWrapped(), null); } catch (Exception e) { //true } @@ -91,7 +91,7 @@ public boolean isAvailable() throws InvalidConnectionException{ @Override public boolean connectDeviceImp() { try { - Object value = methodConnect.invoke(getWrapped(), (Class)null); + Object value = methodConnect.invoke(getWrapped(), null); try { return (Boolean) value; } catch (Exception e) { From d4f7be57c2ccacb5d5c152979a79e8b951570678 Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Thu, 21 Mar 2024 12:56:37 -0400 Subject: [PATCH 10/60] adding helper functions --- .../sdk/addons/kinematics/DHParameterKinematics.java | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/DHParameterKinematics.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/DHParameterKinematics.java index bc7e9a4a..d19ce61c 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/DHParameterKinematics.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/DHParameterKinematics.java @@ -846,6 +846,16 @@ public MobileBase getFollowerMobileBase(AbstractLink myLink) { public MobileBase getFollowerMobileBase(LinkConfiguration myLink) { return getDhLink(myLink).getSlaveMobileBase(); } + + public TransformNR getDHStep(int myLink) { + return new TransformNR(getDhLink(myLink).DhStep(0)); + } + public TransformNR getDHStep(AbstractLink myLink) { + return new TransformNR(getDhLink(myLink).DhStep(0)); + } + public TransformNR getDHStep(LinkConfiguration myLink) { + return new TransformNR(getDhLink(myLink).DhStep(0)); + } @Override public void setTimeProvider(ITimeProvider t) { super.setTimeProvider(t); From 9d6b05793c58ea89bb95e73efb0459e39fc5b199 Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Thu, 21 Mar 2024 16:06:25 -0400 Subject: [PATCH 11/60] add helper functions to detect if a link is a foot or wheel --- .../sdk/addons/kinematics/MobileBase.java | 39 +++++++++++++++++++ 1 file changed, 39 insertions(+) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java index de806e7f..96c7c9ae 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java @@ -717,6 +717,45 @@ private String makeLimbTag(String xml, DHParameterKinematics l) { xml += l.getEmbedableXml(); return xml; } + + public boolean isWheel(AbstractLink link) { + ArrayList possible= new ArrayList<>(); + possible.addAll(getSteerable()); + possible.addAll(getDrivable()); + for(DHParameterKinematics kin:possible) { + for(int i=0;i possible= new ArrayList<>(); + possible.addAll(legs); + for(DHParameterKinematics kin:possible) { + for(int i=0;i Date: Thu, 21 Mar 2024 18:35:44 -0400 Subject: [PATCH 12/60] working helper function --- .../neuronrobotics/sdk/addons/kinematics/MobileBase.java | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java index 96c7c9ae..d70d0a5d 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java @@ -724,14 +724,14 @@ public boolean isWheel(AbstractLink link) { possible.addAll(getDrivable()); for(DHParameterKinematics kin:possible) { for(int i=0;i Date: Sun, 24 Mar 2024 11:23:50 -0400 Subject: [PATCH 13/60] Fixed a bug in how the masses of tags were loaded. --- build.gradle | 16 +- .../sdk/addons/kinematics/MobileBase.java | 41 +- .../addons/kinematics/math/TransformNR.java | 5 + .../kinematics/xml/NASASuspensionTest.xml | 1290 +++++++++++++++++ .../utilities/ParallelArmTest.java | 2 +- .../utilities/TestMobilBaseLoading.java | 24 + 6 files changed, 1359 insertions(+), 19 deletions(-) create mode 100644 src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/NASASuspensionTest.xml create mode 100644 test/java/src/junit/test/neuronrobotics/utilities/TestMobilBaseLoading.java diff --git a/build.gradle b/build.gradle index 0825cbf0..579d4581 100644 --- a/build.gradle +++ b/build.gradle @@ -9,14 +9,14 @@ File buildDir = file("."); Properties props = new Properties() props.load(new FileInputStream(buildDir.getAbsolutePath()+"/src/main/resources/com/neuronrobotics/sdk/config/build.properties")) -//sourceSets { -// -// test { -// java { -// srcDirs = ["test/java/src" ] // Note @Peter's comment below -// } -// } -//} +sourceSets { + + test { + java { + srcDirs = ["test/java/src" ] + } + } +} manifest { attributes( diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java index d70d0a5d..466e59b7 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java @@ -333,6 +333,19 @@ private String getname(Element e) { private String getParallelGroup(Element e) { return getTag(e, "parallelGroup"); } + + private String findNameTag(Node e) { + NodeList firstLevelList = e.getChildNodes(); + for(int i=0;i + + + https://github.com/NeuronRobotics/NASACurisoity.git + bodyCad.groovy + + + https://github.com/NeuronRobotics/NASACurisoity.git + DriveEngine.groovy + + +NASA_Curiosity + + +RobotArm + + https://github.com/NeuronRobotics/NASACurisoity.git + armCad.groovy + + + https://github.com/madhephaestus/carl-the-hexapod.git + DefaultDhSolver.groovy + + + basePan + dyio + servo-rotory + 4 + 0.001 + 1000000.0 + -1000000.0 + 1.0E8 + -1.0E8 + 0.0 + 2.147483647E9 + -2.147483648E9 + true + 180.0 + false + 10000000 + + + + electroMechanical + hobbyServo + standardMicro + + + shaft + hobbyServoHorn + standardMicro1 + + + + false + 0.001 + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0.0 + 0.0 + + + 16.0 + 0.0 + 0.0 + -90.0 + + + + + baseTilt + dyio + servo-rotory + 5 + 0.001 + 1000000.0 + -1000000.0 + 1.0E8 + -1.0E8 + 0.0 + 2.147483647E9 + -2.147483648E9 + true + 128.0 + false + 10000000 + + + + electroMechanical + hobbyServo + standardMicro + + + shaft + hobbyServoHorn + standardMicro1 + + + + false + 0.001 + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0.0 + 0.0 + + + 0.0 + -90.0 + 60.0 + 0.0 + + + + + elbow + dyio + servo-rotory + 6 + 0.001 + 100000.0 + -100000.0 + 1.0E8 + -1.0E8 + 0.0 + 2.147483647E9 + -2.147483648E9 + true + 121.0 + false + 10000000 + + + + electroMechanical + hobbyServo + standardMicro + + + shaft + hobbyServoHorn + standardMicro1 + + + + false + 0.001 + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0.0 + 0.0 + + + 0.0 + 90.0 + 50.0 + 0.0 + + + + + mahliApxs + dyio + servo-rotory + 7 + 0.001 + 120000.0 + -120000.0 + 1.0E8 + -1.0E8 + 0.0 + 2.147483647E9 + -2.147483648E9 + false + 0.0 + false + 10000000 + + + + electroMechanical + hobbyServo + standardMicro + + + shaft + hobbyServoHorn + standardMicro1 + + + + false + 0.001 + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0.0 + 0.0 + + + 0.0 + 0.0 + 0.0 + 0.0 + + + + + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + + -75.00000000000001 + -23.069999999999993 + 38.0952380952381 + 0.05455892332782112 + 0.017903047010183144 + 0.0077571528961058725 + 0.9983199043252653 + + + + + +Front_Left + + https://github.com/NeuronRobotics/NASACurisoity.git + steer_wheel.groovy + + + https://github.com/madhephaestus/carl-the-hexapod.git + DefaultDhSolver.groovy + + + fl_steer + dyio + servo-rotory + 0 + 2.0 + 255.0 + 0.0 + 178.0 + -178.0 + 128.0 + 2.147483647E9 + -2.147483648E9 + true + 105.0 + false + 10000000 + + + + electroMechanical + hobbyServo + standardMicro + + + shaft + hobbyServoHorn + standardMicro1 + + + + false + 0.001 + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0.0 + 0.0 + + + 0.0 + 0.0 + 0.0 + -90.0 + + + + + fl_wheel + pid + pid + 0 + 0.33 + 1000000.0 + -1000000.0 + 436.7392582541836 + -436.7392582541836 + 133.7089552238806 + 2.147483647E9 + -2.147483648E9 + true + 105.0 + false + 10000000 + + + + electroMechanical + hobbyServo + standardMicro + + + shaft + hobbyServoHorn + standardMicro1 + + + + false + 0.05 + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0.0 + 0.0 + + + 0.0 + 0.0 + 18.0 + -90.0 + + + + + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + + -78.5 + -73.75 + 0.0 + 0.008725098943435386 + -0.9999619021083685 + 2.258102901239317E-6 + 2.587955605911594E-4 + + + + + +Back_Left + + https://github.com/NeuronRobotics/NASACurisoity.git + steer_wheel.groovy + + + https://github.com/madhephaestus/carl-the-hexapod.git + DefaultDhSolver.groovy + + + leftRocker + virtual + virtual + 1 + 1.0 + 147.0 + 88.2910447761194 + 233.7089552238806 + -233.7089552238806 + 128.0 + 2.147483647E9 + -2.147483648E9 + true + 105.0 + false + 10000000 + + + + electroMechanical + hobbyServo + standardMicro + + + shaft + hobbyServoHorn + standardMicro1 + + + + true + 0.001 + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0.0 + 0.0 + + + 24.0 + 0.0 + 45.0 + 90.0 + + + + https://github.com/madhephaestus/carl-the-hexapod.git + ThreeDPrintCad.groovy + + + https://github.com/madhephaestus/carl-the-hexapod.git + WalkingDriveEngine.groovy + + +fixedWheelLeft + + +Center_Left + + https://github.com/NeuronRobotics/NASACurisoity.git + fixed_wheel.groovy + + + https://github.com/madhephaestus/carl-the-hexapod.git + DefaultDhSolver.groovy + + + cl_wheel + pid + pid + 1 + 0.33 + 1000000.0 + -1000000.0 + 465.28403437358656 + -465.28403437358656 + 162.25373134328353 + 2.147483647E9 + -2.147483648E9 + true + 171.0 + false + 10000000 + + + + electroMechanical + hobbyServo + standardMicro + + + shaft + hobbyServoHorn + standardMicro1 + + + + false + 0.05 + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0.0 + 0.0 + + + 0.0 + 0.0 + 18.0 + -90.0 + + + + + 72.9999999999727 + -75.5 + 28.999950421262387 + -2.2204460492501225E-16 + -0.9999999999998482 + -1.4056873444211037E-22 + 5.508748628022816E-7 + + + + -74.0 + 0.0 + 29.0 + 0.7071067811865476 + -0.7071067811865475 + -8.120692378444618E-12 + -8.120692378444618E-12 + + + + + + 72.9999999999727 + -75.5 + 28.999950421262387 + -2.220446049250122E-16 + -0.9999999999998482 + -1.4056873444211032E-22 + 5.508748628022816E-7 + + + + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + 0.001 + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + + + + + + + + + + bl_steer + dyio + servo-rotory + 1 + 1.0 + 255.0 + 0.0 + 233.7089552238806 + -233.7089552238806 + 133.7089552238806 + 2.147483647E9 + -2.147483648E9 + true + 105.0 + false + 10000000 + + + + electroMechanical + hobbyServo + standardMicro + + + shaft + hobbyServoHorn + standardMicro1 + + + + false + 0.001 + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0.0 + 0.0 + + + 30.0 + 0.0 + 0.0 + -90.0 + + + + + bl_wheel + pid + pid + 2 + 0.33 + 1000000.0 + -1000000.0 + 447.8731410788662 + -447.8731410788662 + 144.84283804856315 + 2.147483647E9 + -2.147483648E9 + true + 124.0 + false + 10000000 + + + + electroMechanical + hobbyServo + standardMicro + + + shaft + hobbyServoHorn + standardMicro1 + + + + false + 0.05 + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0.0 + 0.0 + + + 0.0 + 0.0 + 18.0 + -90.0 + + + + + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + + 28.0 + -51.5 + 29.000000000000032 + 0.7071067811864403 + 0.7071067811864402 + 3.895273510727024E-7 + -3.895273510727023E-7 + + + + + +Back_Right + + https://github.com/NeuronRobotics/NASACurisoity.git + steer_wheel.groovy + + + https://github.com/madhephaestus/carl-the-hexapod.git + DefaultDhSolver.groovy + + + rightRocker + virtual + virtual + 2 + 1.0 + 149.0 + 90.0 + 233.7089552238806 + -233.7089552238806 + 128.0 + 2.147483647E9 + -2.147483648E9 + true + 105.0 + false + 10000000 + + + + electroMechanical + hobbyServo + standardMicro + + + shaft + hobbyServoHorn + standardMicro1 + + + + true + 0.001 + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0.0 + 0.0 + + + -25.0 + 0.0 + 45.0 + 90.0 + + + + https://github.com/madhephaestus/carl-the-hexapod.git + ThreeDPrintCad.groovy + + + https://github.com/madhephaestus/carl-the-hexapod.git + WalkingDriveEngine.groovy + + +fixedWheelRight + + +Center_Right + + https://github.com/NeuronRobotics/NASACurisoity.git + fixed_wheel.groovy + + + https://github.com/madhephaestus/carl-the-hexapod.git + DefaultDhSolver.groovy + + + cr_wheel + pid + pid + 4 + 0.33 + 1000000.0 + -1000000.0 + 425.3213478064224 + -425.3213478064224 + 122.2910447761194 + 2.147483647E9 + -2.147483648E9 + true + 128.0 + false + 10000000 + + + + electroMechanical + hobbyServo + standardMicro + + + shaft + hobbyServoHorn + standardMicro1 + + + + false + 0.05 + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0.0 + 0.0 + + + 0.0 + 0.0 + 18.0 + -90.0 + + + + + 72.99999999999918 + 76.5 + 28.99999132090427 + -2.220446049250312E-16 + -0.9999999999999953 + -2.0632536132425642E-23 + 9.643439691231537E-8 + + + + -73.0 + 0.0 + 29.0 + 0.7071067811637124 + -0.7071067811637123 + -5.682767991797112E-6 + -5.682767991797108E-6 + + + + + + 72.99999999999918 + 76.5 + 28.99999132090427 + -2.220446049250312E-16 + -0.9999999999999953 + -2.0632536132425645E-23 + 9.643439691231537E-8 + + + + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + 0.001 + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + + + + + + + + + + br_steer + dyio + servo-rotory + 2 + 1.0 + 255.0 + 0.0 + 233.7089552238806 + -233.7089552238806 + 133.7089552238806 + 2.147483647E9 + -2.147483648E9 + true + 105.0 + false + 10000000 + + + + electroMechanical + hobbyServo + standardMicro + + + shaft + hobbyServoHorn + standardMicro1 + + + + false + 0.001 + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0.0 + 0.0 + + + 30.0 + 0.0 + 0.0 + -90.0 + + + + + br_wheel + pid + pid + 3 + 0.33 + 1000000.0 + -1000000.0 + 412.25607714480515 + -412.25607714480515 + 109.22577411450214 + 2.147483647E9 + -2.147483648E9 + true + 133.0 + false + 10000000 + + + + electroMechanical + hobbyServo + standardMicro + + + shaft + hobbyServoHorn + standardMicro1 + + + + false + 0.001 + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0.0 + 0.0 + + + 0.0 + 0.0 + 18.0 + -90.0 + + + + + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + + 28.0 + 51.5 + 29.0 + 0.7071067811865444 + 0.7071067811865442 + 6.818941599633328E-8 + -6.818941599633326E-8 + + + + + +Front_Right + + https://github.com/NeuronRobotics/NASACurisoity.git + steer_wheel.groovy + + + https://github.com/madhephaestus/carl-the-hexapod.git + DefaultDhSolver.groovy + + + fr_steer + dyio + servo-rotory + 3 + 1.0 + 255.0 + 0.0 + 233.7089552238806 + -233.7089552238806 + 133.7089552238806 + 2.147483647E9 + -2.147483648E9 + true + 105.0 + false + 10000000 + + + + electroMechanical + hobbyServo + standardMicro + + + shaft + hobbyServoHorn + standardMicro1 + + + + false + 0.001 + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0.0 + 0.0 + + + 0.0 + 0.0 + 0.0 + -90.0 + + + + + fr_wheel + pid + pid + 5 + 0.33 + 1000000.0 + -1000000.0 + 423.4183627317955 + -423.4183627317955 + 120.38805970149252 + 2.147483647E9 + -2.147483648E9 + true + 135.0 + false + 10000000 + + + + electroMechanical + hobbyServo + standardMicro + + + shaft + hobbyServoHorn + standardMicro1 + + + + false + 0.05 + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0.0 + 0.0 + + + 0.0 + 0.0 + 18.0 + -90.0 + + + + + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + + -78.5 + 73.75 + 0.0 + 0.008725098943435386 + -0.9999619021083685 + 2.2581029012393413E-6 + 2.587955605911622E-4 + + + + + + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + 0.1 + 0.0 + 0.0 + 40.0 + 1.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0.0 + 0.0 + + + + + + + + \ No newline at end of file diff --git a/test/java/src/junit/test/neuronrobotics/utilities/ParallelArmTest.java b/test/java/src/junit/test/neuronrobotics/utilities/ParallelArmTest.java index a8ff20e7..4cd7202c 100644 --- a/test/java/src/junit/test/neuronrobotics/utilities/ParallelArmTest.java +++ b/test/java/src/junit/test/neuronrobotics/utilities/ParallelArmTest.java @@ -24,7 +24,7 @@ public class ParallelArmTest { @Test public void test() throws Exception { - main(null); + //main(null); } public static void main(String[] args) throws Exception { diff --git a/test/java/src/junit/test/neuronrobotics/utilities/TestMobilBaseLoading.java b/test/java/src/junit/test/neuronrobotics/utilities/TestMobilBaseLoading.java new file mode 100644 index 00000000..171e75ee --- /dev/null +++ b/test/java/src/junit/test/neuronrobotics/utilities/TestMobilBaseLoading.java @@ -0,0 +1,24 @@ +package junit.test.neuronrobotics.utilities; + +import static org.junit.Assert.*; + +import java.io.File; +import java.io.FileInputStream; +import java.io.FileNotFoundException; + +import org.junit.Test; + +import com.neuronrobotics.sdk.addons.kinematics.MobileBase; + +public class TestMobilBaseLoading { + + @Test + public void test() throws FileNotFoundException { + MobileBase base = new MobileBase(new FileInputStream(new File("src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/NASASuspensionTest.xml"))); + + if(Math.abs(0.1-base.getMassKg())>0.0001) { + fail("Base mass failed to load! expected "+0.1+" got "+base.getMassKg()); + } + } + +} From 6a6a069aa4cbfacb9eb203a943ed169088c3a7ee Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Sun, 24 Mar 2024 11:50:59 -0400 Subject: [PATCH 14/60] fully robust Unit test that checks loaded XML against exported XML --- .../sdk/addons/kinematics/xml/.gitignore | 1 + .../kinematics/xml/NASASuspensionTest.xml | 54 +++++++++---------- .../utilities/TestMobilBaseLoading.java | 18 +++++-- 3 files changed, 43 insertions(+), 30 deletions(-) create mode 100644 src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/.gitignore diff --git a/src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/.gitignore b/src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/.gitignore new file mode 100644 index 00000000..c9cc22b6 --- /dev/null +++ b/src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/.gitignore @@ -0,0 +1 @@ +/NASASuspensionTestOUTPUT.xml diff --git a/src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/NASASuspensionTest.xml b/src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/NASASuspensionTest.xml index 57d4f3ed..2e059a73 100644 --- a/src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/NASASuspensionTest.xml +++ b/src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/NASASuspensionTest.xml @@ -557,13 +557,13 @@ 72.9999999999727 - -75.5 - 28.999950421262387 - -2.2204460492501225E-16 - -0.9999999999998482 - -1.4056873444211037E-22 - 5.508748628022816E-7 +> 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 @@ -579,13 +579,13 @@ - 72.9999999999727 - -75.5 - 28.999950421262387 - -2.220446049250122E-16 - -0.9999999999998482 - -1.4056873444211032E-22 - 5.508748628022816E-7 + 0.2951945417837649 + -75.50000000000001 + -6.460453388562168 + 4.866904542229674E-17 + 0.43837065166596395 + -9.978614964896946E-17 + -0.898794287786676 @@ -901,13 +901,13 @@ 72.99999999999918 - 76.5 - 28.99999132090427 - -2.220446049250312E-16 - -0.9999999999999953 - -2.0632536132425642E-23 - 9.643439691231537E-8 +> 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 @@ -923,13 +923,13 @@ - 72.99999999999918 + 0.2952267711251224 76.5 - 28.99999132090427 - -2.220446049250312E-16 - -0.9999999999999953 - -2.0632536132425645E-23 - 9.643439691231537E-8 + -6.460478568916969 + 4.86689829712371E-17 + 0.4383710601144136 + -9.978618010838941E-17 + -0.89879408857322 diff --git a/test/java/src/junit/test/neuronrobotics/utilities/TestMobilBaseLoading.java b/test/java/src/junit/test/neuronrobotics/utilities/TestMobilBaseLoading.java index 171e75ee..3701338f 100644 --- a/test/java/src/junit/test/neuronrobotics/utilities/TestMobilBaseLoading.java +++ b/test/java/src/junit/test/neuronrobotics/utilities/TestMobilBaseLoading.java @@ -4,7 +4,9 @@ import java.io.File; import java.io.FileInputStream; -import java.io.FileNotFoundException; +import java.io.IOException; +import java.nio.file.Files; +import java.nio.file.Paths; import org.junit.Test; @@ -13,12 +15,22 @@ public class TestMobilBaseLoading { @Test - public void test() throws FileNotFoundException { - MobileBase base = new MobileBase(new FileInputStream(new File("src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/NASASuspensionTest.xml"))); + public void test() throws IOException { + File file = new File("src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/NASASuspensionTest.xml"); + + String content = new String(Files.readAllBytes(Paths.get(file.getAbsolutePath()))); + MobileBase base = new MobileBase(new FileInputStream(file)); if(Math.abs(0.1-base.getMassKg())>0.0001) { fail("Base mass failed to load! expected "+0.1+" got "+base.getMassKg()); } + String read = base.getXml(); + if(!content.contentEquals(read)) { + File out = new File("src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/NASASuspensionTestOUTPUT.xml"); + Files.write( Paths.get(out.getAbsolutePath()), read.getBytes()); + System.out.println("diff "+file.getAbsolutePath()+" "+out.getAbsolutePath()); + fail("What was loaded failed to match the source"); + } } } From 728b103a8654d7eb457c27f67f13f062a7b81751 Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Sun, 24 Mar 2024 16:11:59 -0400 Subject: [PATCH 15/60] A refresh of the Vitamins layer using objecte and properly integrating the mobile base and testing --- .../kinematics/AbstractKinematicsNR.java | 17 +- .../addons/kinematics/LinkConfiguration.java | 109 +++---- .../sdk/addons/kinematics/MobileBase.java | 58 ++-- .../addons/kinematics/VitaminLocation.java | 150 +++++++++ .../addons/kinematics/math/TransformNR.java | 19 +- .../sdk/addons/kinematics/xml/XmlFactory.java | 14 + .../kinematics/xml/NASASuspensionTest.xml | 299 +++++++++++++----- .../utilities/TestMobilBaseLoading.java | 8 +- 8 files changed, 477 insertions(+), 197 deletions(-) create mode 100644 src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractKinematicsNR.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractKinematicsNR.java index 7b7595b3..ed6bfb2c 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractKinematicsNR.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractKinematicsNR.java @@ -326,14 +326,7 @@ public void onConnect(BowlerAbstractDevice source) { && linkNode.getNodeName().contentEquals("ZframeToRAS")) { Element eElement = (Element) linkNode; try { - setGlobalToFiducialTransform(new TransformNR( - Double.parseDouble(XmlFactory.getTagValue("x", eElement)), - Double.parseDouble(XmlFactory.getTagValue("y", eElement)), - Double.parseDouble(XmlFactory.getTagValue("z", eElement)), - new RotationNR(new double[] { Double.parseDouble(XmlFactory.getTagValue("rotw", eElement)), - Double.parseDouble(XmlFactory.getTagValue("rotx", eElement)), - Double.parseDouble(XmlFactory.getTagValue("roty", eElement)), - Double.parseDouble(XmlFactory.getTagValue("rotz", eElement)) }))); + setGlobalToFiducialTransform(XmlFactory.getTransform(eElement)); } catch (Exception ex) { ex.printStackTrace(); setGlobalToFiducialTransform(new TransformNR()); @@ -342,13 +335,7 @@ public void onConnect(BowlerAbstractDevice source) { && linkNode.getNodeName().contentEquals("baseToZframe")) { Element eElement = (Element) linkNode; try { - setRobotToFiducialTransform(new TransformNR(Double.parseDouble(XmlFactory.getTagValue("x", eElement)), - Double.parseDouble(XmlFactory.getTagValue("y", eElement)), - Double.parseDouble(XmlFactory.getTagValue("z", eElement)), - new RotationNR(new double[] { Double.parseDouble(XmlFactory.getTagValue("rotw", eElement)), - Double.parseDouble(XmlFactory.getTagValue("rotx", eElement)), - Double.parseDouble(XmlFactory.getTagValue("roty", eElement)), - Double.parseDouble(XmlFactory.getTagValue("rotz", eElement)) }))); + setRobotToFiducialTransform(XmlFactory.getTransform(eElement)); } catch (Exception ex) { ex.printStackTrace(); setRobotToFiducialTransform(new TransformNR()); diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/LinkConfiguration.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/LinkConfiguration.java index 4050d6fc..7e5cfe2f 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/LinkConfiguration.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/LinkConfiguration.java @@ -96,7 +96,7 @@ public class LinkConfiguration implements ITransformNRChangeListener { */ private boolean invertLimitVelocityPolarity = false; - private HashMap vitamins = new HashMap(); + private ArrayList vitamins = new ArrayList(); private HashMap vitaminVariant = new HashMap(); private boolean passive = false; private boolean newAbs = false; @@ -275,19 +275,7 @@ public LinkConfiguration(Object[] args) { protected void getVitamins(Element doc) { try { - NodeList nodListofLinks = doc.getChildNodes(); - for (int i = 0; i < nodListofLinks.getLength(); i++) { - Node linkNode = nodListofLinks.item(i); - if (linkNode.getNodeType() == Node.ELEMENT_NODE && linkNode.getNodeName().contentEquals("vitamin")) { - Element e = (Element) linkNode; - setVitamin(XmlFactory.getTagValue("name", e), XmlFactory.getTagValue("type", e), - XmlFactory.getTagValue("id", e)); - try { - setVitaminVariant(XmlFactory.getTagValue("name", e), XmlFactory.getTagValue("variant", e)); - } catch (Exception ex) { - } - } - } + vitamins=VitaminLocation.getVitamins(doc); return; } catch (Exception e) { e.printStackTrace(); @@ -303,12 +291,15 @@ protected void getVitamins(Element doc) { * @param type the vitamin type, this maps the the json filename * @param id the part ID, theis maps to the key in the json for the vitamin */ - public void setVitamin(String name, String type, String id) { - if (getVitamins().get(name) == null) { - getVitamins().put(name, new String[2]); - } - getVitamins().get(name)[0] = type; - getVitamins().get(name)[1] = id; + public void setVitamin(VitaminLocation loc) { + if(vitamins.contains(loc)) + return; + vitamins.add(loc); + fireChangeEvent(); + } + public void removeVitamin(VitaminLocation loc) { + if(vitamins.contains(loc)) + vitamins.remove(loc); fireChangeEvent(); } @@ -347,9 +338,7 @@ public LinkConfiguration(LinkConfiguration from) { slaveLinks.add(new LinkConfiguration(from.slaveLinks.get(i))); } - for(String key: from.getVitamins().keySet()){ - getVitamins().put(key, from.getVitamins().get(key)); - } + vitamins.addAll(from.vitamins); setName(from.getName()); setTypeString(from.getTypeString()); @@ -422,29 +411,23 @@ public String getXml() { for (int i = 0; i < slaveLinks.size(); i++) { slaves += "\n\t\n" + slaveLinks.get(i).getXml() + "\n\t\n"; } - String allVitamins = ""; - for (String key : getVitamins().keySet()) { - String v = "\t\t\n"; - v += "\t\t\t" + key + "\n" + "\t\t\t" + getVitamins().get(key)[0] + "\n" - + "\t\t\t" + getVitamins().get(key)[1] + "\n"; - if (getVitaminVariant(key) != null) { - v += "\t\t\t" + getVitamins().get(key)[1] + "\n"; - } - v += "\t\t\n"; - allVitamins += v; - } - return "\t" + getName() + "\n" + "\t" + DevStr + "\t" + getTypeString() + "\n" - + "\t" + getHardwareIndex() + "\n" + "\t" + getScale() + "\n" - + "\t" + getUpperLimit() + "\n" + "\t" + getLowerLimit() - + "\n" + "\t" + getUpperVelocity() + "\n" - + "\t" + getLowerVelocity() + "\n" + "\t" + + String vitamnsString = VitaminLocation.getAllXML(vitamins); + return "\t" + getName() + "\n" + "\t" + + DevStr + "\t" + getTypeString() + "\n"+ + "\t" + getHardwareIndex() + "\n" + + "\t" + getScale() + "\n" + + "\t" + getUpperLimit() + "\n" + + "\t" + getLowerLimit()+ "\n" + + "\t" + getUpperVelocity() + "\n"+ + "\t" + getLowerVelocity() + "\n" + + "\t" + getStaticOffset() + "\n" + "\t" + getDeviceTheoreticalMax() + "\n" + "\t" + getDeviceTheoreticalMin() + "\n" + "\t" + isLatch() + "\n" + "\t" + getIndexLatch() + "\n" + "\t" + isStopOnLatch() + "\n" - + "\t" + getHomingTicksPerSecond() + "\n" + "\n\t\n" + allVitamins - + "\n\t\n" + "\t" + isPassive() + "\n" + "\t" + getMassKg() + + "\t" + getHomingTicksPerSecond() + "\n" + vitamnsString+ "\t" + isPassive() + "\n" + "\t" + getMassKg() + "\n" + "\t" + getCenterOfMassFromCentroid().getXml() + "\n" + "\t" + getimuFromCentroid().getXml() + "\n" + slaves; @@ -950,53 +933,57 @@ public void setimuFromCentroid(TransformNR imu) { // private String shaftType = "hobbyServoHorn"; // private String shaftSize = "standardMicro1"; - private String[] getCoreShaftPart() { - if (vitamins.get("shaft") == null) { - vitamins.put("shaft", new String[] { "hobbyServoHorn", "standardMicro1" }); - } - return vitamins.get("shaft"); + private VitaminLocation getCoreShaftPart() { + for(VitaminLocation loc:vitamins) + if(loc.getName().contentEquals("shaft")) + return loc; + VitaminLocation e = new VitaminLocation("shaft", "hobbyServoHorn", "standardMicro1", new TransformNR()); + vitamins.add(e); + return e; } - private String[] getCoreEmPart() { - if (vitamins.get("electroMechanical") == null) { - vitamins.put("electroMechanical", new String[] { "hobbyServo", "standardMicro" }); - } - return vitamins.get("electroMechanical"); + private VitaminLocation getCoreEmPart() { + for(VitaminLocation loc:vitamins) + if(loc.getName().contentEquals("electroMechanical")) + return loc; + VitaminLocation e = new VitaminLocation("electroMechanical", "hobbyServoHorn", "mg92b", new TransformNR()); + vitamins.add(e); + return e; } public String getElectroMechanicalType() { - return getCoreEmPart()[0]; + return getCoreEmPart().getType(); } public void setElectroMechanicalType(String electroMechanicalType) { - getCoreEmPart()[0] = electroMechanicalType; + getCoreEmPart().setType(electroMechanicalType); fireChangeEvent(); } public String getElectroMechanicalSize() { - return getCoreEmPart()[1]; + return getCoreEmPart().getSize(); } public void setElectroMechanicalSize(String electroMechanicalSize) { - getCoreEmPart()[1] = electroMechanicalSize; + getCoreEmPart().setSize(electroMechanicalSize); fireChangeEvent(); } public String getShaftType() { - return getCoreShaftPart()[0]; + return getCoreShaftPart().getType(); } public void setShaftType(String shaftType) { - getCoreShaftPart()[0] = shaftType; + getCoreShaftPart().setType(shaftType);; fireChangeEvent(); } public String getShaftSize() { - return getCoreShaftPart()[1]; + return getCoreShaftPart().getSize(); } public void setShaftSize(String shaftSize) { - getCoreShaftPart()[1] = shaftSize; + getCoreShaftPart().setSize(shaftSize); fireChangeEvent(); } @@ -1009,11 +996,11 @@ public void setPassive(boolean passive) { fireChangeEvent(); } - public HashMap getVitamins() { + public ArrayListgetVitamins() { return vitamins; } - public void setVitamins(HashMap vitamins) { + public void setVitamins(ArrayList vitamins) { this.vitamins = vitamins; fireChangeEvent(); } diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java index 466e59b7..662b8275 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java @@ -51,7 +51,7 @@ public class MobileBase extends AbstractKinematicsNR implements ILinkConfigurati private String[] walkingEngine = new String[] { "https://github.com/madhephaestus/carl-the-hexapod.git", "WalkingDriveEngine.groovy" }; - private HashMap vitamins = new HashMap(); + private ArrayList vitamins = new ArrayList<>(); private HashMap vitaminVariant = new HashMap(); /** The self source. */ @@ -547,7 +547,7 @@ private void loadVitamins(Element doc) { } } - public HashMap getVitamins() { + public ArrayList getVitamins() { return vitamins; } @@ -559,19 +559,7 @@ public HashMap getVitamins() { private void getVitamins(Element doc) { try { - NodeList nodListofLinks = doc.getChildNodes(); - for (int i = 0; i < nodListofLinks.getLength(); i++) { - Node linkNode = nodListofLinks.item(i); - if (linkNode.getNodeType() == Node.ELEMENT_NODE && linkNode.getNodeName().contentEquals("vitamin")) { - Element e = (Element) linkNode; - setVitamin(XmlFactory.getTagValue("name", e), XmlFactory.getTagValue("type", e), - XmlFactory.getTagValue("id", e)); - try { - setVitaminVariant(XmlFactory.getTagValue("name", e), XmlFactory.getTagValue("variant", e)); - } catch (Exception ex) { - } - } - } + vitamins = VitaminLocation.getVitamins(doc); return; } catch (Exception e) { e.printStackTrace(); @@ -587,12 +575,16 @@ private void getVitamins(Element doc) { * @param type the vitamin type, this maps the the json filename * @param id the part ID, theis maps to the key in the json for the vitamin */ - public void setVitamin(String name, String type, String id) { - if (getVitamins().get(name) == null) { - getVitamins().put(name, new String[2]); - } - getVitamins().get(name)[0] = type; - getVitamins().get(name)[1] = id; + public void setVitamin(VitaminLocation location) { + if(vitamins.contains(location)) + return; + vitamins.add(location); + + } + public void removeVitamin(VitaminLocation loc) { + if(vitamins.contains(loc)) + vitamins.remove(loc); + //fireChangeEvent(); } /** @@ -643,17 +635,17 @@ public String getXml() { public String getEmbedableXml() { TransformNR location = getFiducialToGlobalTransform(); - String allVitamins = ""; - for (String key : getVitamins().keySet()) { - String v = "\t\t\n"; - v += "\t\t\t" + key + "\n" + "\t\t\t" + getVitamins().get(key)[0] + "\n" - + "\t\t\t" + getVitamins().get(key)[1] + "\n"; - if (getVitaminVariant(key) != null) { - v += "\t\t\t" + getVitamins().get(key)[1] + "\n"; - } - v += "\t\t\n"; - allVitamins += v; - } +// String allVitamins = ""; +// for (String key : getVitamins().keySet()) { +// String v = "\t\t\n"; +// v += "\t\t\t" + key + "\n" + "\t\t\t" + getVitamins().get(key)[0] + "\n" +// + "\t\t\t" + getVitamins().get(key)[1] + "\n"; +// if (getVitaminVariant(key) != null) { +// v += "\t\t\t" + getVitamins().get(key)[1] + "\n"; +// } +// v += "\t\t\n"; +// allVitamins += v; +// } String xml = "\n"; xml += "\t\n"; @@ -711,7 +703,7 @@ public String getEmbedableXml() { xml += "\n\n" + "\t" + getMassKg() + "\n" + "\t" + getCenterOfMassFromCentroid().getXml() + "\n" + "\t" + getIMUFromCentroid().getXml() + "\n"; - xml += "\n\n" + allVitamins + "\n\n"; + xml += VitaminLocation.getAllXML(vitamins); xml += "\n\n"; setGlobalToFiducialTransform(location); return xml; diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java new file mode 100644 index 00000000..c55c7036 --- /dev/null +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java @@ -0,0 +1,150 @@ +package com.neuronrobotics.sdk.addons.kinematics; + +import java.util.ArrayList; + +import org.w3c.dom.Element; +import org.w3c.dom.Node; +import org.w3c.dom.NodeList; + +import com.neuronrobotics.sdk.addons.kinematics.math.TransformNR; +import com.neuronrobotics.sdk.addons.kinematics.xml.XmlFactory; + +public class VitaminLocation { + + private String name; + private String type; + private String size; + private TransformNR location; + + public VitaminLocation(String name, String type, String size, TransformNR location) { + this.setName(name); + this.setType(type); + this.setSize(size); + this.setLocation(location); + } + + public VitaminLocation(Element vitamins) { + setName(XmlFactory.getTagValue("name", vitamins)); + setType(XmlFactory.getTagValue("type", vitamins)); + setSize(XmlFactory.getTagValue("id", vitamins)); + + NodeList nodListofLinks = vitamins.getChildNodes(); + TransformNR tf=null; + for (int i = 0; i < nodListofLinks.getLength(); i++) { + Node linkNode = nodListofLinks.item(i); + if(linkNode.getNodeType() != Node.ELEMENT_NODE) + continue; + Element eElement = (Element) linkNode; + if(linkNode.getNodeName().contentEquals("pose")) { + tf=XmlFactory.getTransform(eElement); + } + } + if(tf==null) + tf=new TransformNR(); + setLocation(tf); + + } + + public String getXML() { + + return "\n\n"+ + ""+name+"\n"+ + ""+type+"\n"+ + ""+size+"\n"+ + ""+location.getXml()+"\n"+ + "\n" + ; + } + public static ArrayList getVitamins(Element doc) { + ArrayList locations = new ArrayList<>(); + try { + NodeList nodListofLinks = doc.getChildNodes(); + for (int i = 0; i < nodListofLinks.getLength(); i++) { + Node linkNode = nodListofLinks.item(i); + if (linkNode.getNodeType() == Node.ELEMENT_NODE && linkNode.getNodeName().contentEquals("vitamin")) { + Element e = (Element) linkNode; + locations.add(new VitaminLocation(e)); + } + } + } catch (Exception e) { + e.printStackTrace(); + } + return locations; + } + + public static String getAllXML(ArrayList list) { + + String vitamins="\n\n"; + for(VitaminLocation loc:list) { + vitamins+=loc.getXML(); + } + return vitamins+"\n\n"; + + } + + /** + * @return the name + */ + public String getName() { + return name; + } + + /** + * @param name the name to set + */ + public void setName(String name) { + if (name==null) + throw new RuntimeException("Name can not be null"); + this.name = name; + } + + /** + * @return the type + */ + public String getType() { + return type; + } + + /** + * @param type the type to set + */ + public void setType(String type) { + + if (type==null) + throw new RuntimeException("type can not be null"); + this.type = type; + } + + /** + * @return the size + */ + public String getSize() { + return size; + } + + /** + * @param size the size to set + */ + public void setSize(String size) { + if (size==null) + throw new RuntimeException("size can not be null"); + this.size = size; + } + + /** + * @return the location + */ + public TransformNR getLocation() { + return location; + } + + /** + * @param location the location to set + */ + public void setLocation(TransformNR location) { + if (location==null) + throw new RuntimeException("location can not be null"); + this.location = location; + } + +} diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/TransformNR.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/TransformNR.java index ff39913b..4a8acce3 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/TransformNR.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/TransformNR.java @@ -97,7 +97,20 @@ public TransformNR(double x, double y, double z, RotationNR q) { this.setZ(z); this.setRotation(q); } - + /** + * Instantiates a new transform nr. + * + * @param x the x + * @param y the y + * @param z the z + * @param q the q + */ + public TransformNR(double x, double y, double z) { + this.setX(x); + this.setY(y); + this.setZ(z); + this.setRotation(new RotationNR()); + } /** * Instantiates a new transform nr. * @@ -461,7 +474,7 @@ public TransformNR setZ(double tz) { */ public String getXml() { String xml = - "\t" + getX() + "\n" + "\t" + getY() + "\n" + "\t" + getZ() + "\n"; + "\n\t" + getX() + "\n" + "\t" + getY() + "\n" + "\t" + getZ() + "\n"; if (Double.isNaN(getRotation().getRotationMatrix2QuaturnionW()) || Double.isNaN(getRotation().getRotationMatrix2QuaturnionX()) || Double.isNaN(getRotation().getRotationMatrix2QuaturnionY()) @@ -472,7 +485,7 @@ public String getXml() { xml += "\t" + getRotation().getRotationMatrix2QuaturnionW() + "\n" + "\t" + getRotation().getRotationMatrix2QuaturnionX() + "\n" + "\t" + getRotation().getRotationMatrix2QuaturnionY() + "\n" + "\t" - + getRotation().getRotationMatrix2QuaturnionZ() + ""; + + getRotation().getRotationMatrix2QuaturnionZ() + "\n"; return xml; } diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/xml/XmlFactory.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/xml/XmlFactory.java index aefeff63..6e73e2b3 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/xml/XmlFactory.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/xml/XmlFactory.java @@ -12,6 +12,9 @@ import org.w3c.dom.NodeList; import org.xml.sax.SAXException; +import com.neuronrobotics.sdk.addons.kinematics.math.RotationNR; +import com.neuronrobotics.sdk.addons.kinematics.math.TransformNR; + // TODO: Auto-generated Javadoc /** * A factory for creating Xml objects. @@ -53,6 +56,17 @@ public static Document getAllNodesDocument(InputStream config) { return doc; } + public static TransformNR getTransform(Element eElement) { + return new TransformNR( + Double.parseDouble(XmlFactory.getTagValue("x", eElement)), + Double.parseDouble(XmlFactory.getTagValue("y", eElement)), + Double.parseDouble(XmlFactory.getTagValue("z", eElement)), + new RotationNR(new double[] { Double.parseDouble(XmlFactory.getTagValue("rotw", eElement)), + Double.parseDouble(XmlFactory.getTagValue("rotx", eElement)), + Double.parseDouble(XmlFactory.getTagValue("roty", eElement)), + Double.parseDouble(XmlFactory.getTagValue("rotz", eElement)) })); + } + /** * Gets the all nodes from tag. diff --git a/src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/NASASuspensionTest.xml b/src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/NASASuspensionTest.xml index 2e059a73..80321ef0 100644 --- a/src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/NASASuspensionTest.xml +++ b/src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/NASASuspensionTest.xml @@ -54,20 +54,24 @@ false 0.001 - 0.0 + + 0.0 0.0 0.0 1.0 0.0 0.0 - 0.0 - 0.0 + 0.0 + + + 0.0 0.0 0.0 1.0 0.0 0.0 - 0.0 + 0.0 + 16.0 @@ -110,20 +114,24 @@ false 0.001 - 0.0 + + 0.0 0.0 0.0 1.0 0.0 0.0 - 0.0 - 0.0 + 0.0 + + + 0.0 0.0 0.0 1.0 0.0 0.0 - 0.0 + 0.0 + 0.0 @@ -166,20 +174,24 @@ false 0.001 - 0.0 + + 0.0 0.0 0.0 1.0 0.0 0.0 - 0.0 - 0.0 + 0.0 + + + 0.0 0.0 0.0 1.0 0.0 0.0 - 0.0 + 0.0 + 0.0 @@ -222,20 +234,24 @@ false 0.001 - 0.0 + + 0.0 0.0 0.0 1.0 0.0 0.0 - 0.0 - 0.0 + 0.0 + + + 0.0 0.0 0.0 1.0 0.0 0.0 - 0.0 + 0.0 + 0.0 @@ -247,16 +263,19 @@ 0.0 +> + 0.0 0.0 0.0 1.0 -0.0 -0.0 -0.0 + + -75.00000000000001 -23.069999999999993 38.0952380952381 @@ -264,6 +283,7 @@ 0.017903047010183144 0.0077571528961058725 0.9983199043252653 + @@ -311,20 +331,24 @@ false 0.001 - 0.0 + + 0.0 0.0 0.0 1.0 0.0 0.0 - 0.0 - 0.0 + 0.0 + + + 0.0 0.0 0.0 1.0 0.0 0.0 - 0.0 + 0.0 + 0.0 @@ -367,20 +391,24 @@ false 0.05 - 0.0 + + 0.0 0.0 0.0 1.0 0.0 0.0 - 0.0 - 0.0 + 0.0 + + + 0.0 0.0 0.0 1.0 0.0 0.0 - 0.0 + 0.0 + 0.0 @@ -392,16 +420,19 @@ 0.0 +> + 0.0 0.0 0.0 1.0 -0.0 -0.0 -0.0 + + -78.5 -73.75 0.0 @@ -409,6 +440,7 @@ -0.9999619021083685 2.258102901239317E-6 2.587955605911594E-4 + @@ -456,20 +488,24 @@ true 0.001 - 0.0 + + 0.0 0.0 0.0 1.0 0.0 0.0 - 0.0 - 0.0 + 0.0 + + + 0.0 0.0 0.0 1.0 0.0 0.0 - 0.0 + 0.0 + 24.0 @@ -532,20 +568,24 @@ false 0.05 - 0.0 + + 0.0 0.0 0.0 1.0 0.0 0.0 - 0.0 - 0.0 + 0.0 + + + 0.0 0.0 0.0 1.0 0.0 0.0 - 0.0 + 0.0 + 0.0 @@ -557,16 +597,19 @@ 0.0 +> + 0.0 0.0 0.0 1.0 -0.0 -0.0 -0.0 + + -74.0 0.0 29.0 @@ -574,11 +617,13 @@ -0.7071067811865475 -8.120692378444618E-12 -8.120692378444618E-12 + + 0.2951945417837649 -75.50000000000001 -6.460453388562168 @@ -586,9 +631,11 @@ 0.43837065166596395 -9.978614964896946E-17 -0.898794287786676 + + 0.0 0.0 0.0 @@ -596,22 +643,27 @@ -0.0 -0.0 -0.0 + 0.001 - 0.0 + + 0.0 0.0 0.0 1.0 -0.0 -0.0 - -0.0 - 0.0 + -0.0 + + + 0.0 0.0 0.0 1.0 -0.0 -0.0 - -0.0 + -0.0 + @@ -655,20 +707,24 @@ false 0.001 - 0.0 + + 0.0 0.0 0.0 1.0 0.0 0.0 - 0.0 - 0.0 + 0.0 + + + 0.0 0.0 0.0 1.0 0.0 0.0 - 0.0 + 0.0 + 30.0 @@ -711,20 +767,24 @@ false 0.05 - 0.0 + + 0.0 0.0 0.0 1.0 0.0 0.0 - 0.0 - 0.0 + 0.0 + + + 0.0 0.0 0.0 1.0 0.0 0.0 - 0.0 + 0.0 + 0.0 @@ -736,16 +796,19 @@ 0.0 +> + 0.0 0.0 0.0 1.0 -0.0 -0.0 -0.0 + + 28.0 -51.5 29.000000000000032 @@ -753,6 +816,7 @@ 0.7071067811864402 3.895273510727024E-7 -3.895273510727023E-7 + @@ -800,20 +864,24 @@ true 0.001 - 0.0 + + 0.0 0.0 0.0 1.0 0.0 0.0 - 0.0 - 0.0 + 0.0 + + + 0.0 0.0 0.0 1.0 0.0 0.0 - 0.0 + 0.0 + -25.0 @@ -876,20 +944,24 @@ false 0.05 - 0.0 + + 0.0 0.0 0.0 1.0 0.0 0.0 - 0.0 - 0.0 + 0.0 + + + 0.0 0.0 0.0 1.0 0.0 0.0 - 0.0 + 0.0 + 0.0 @@ -901,16 +973,19 @@ 0.0 +> + 0.0 0.0 0.0 1.0 -0.0 -0.0 -0.0 + + -73.0 0.0 29.0 @@ -918,11 +993,13 @@ -0.7071067811637123 -5.682767991797112E-6 -5.682767991797108E-6 + + 0.2952267711251224 76.5 -6.460478568916969 @@ -930,9 +1007,11 @@ 0.4383710601144136 -9.978618010838941E-17 -0.89879408857322 + + 0.0 0.0 0.0 @@ -940,22 +1019,27 @@ -0.0 -0.0 -0.0 + 0.001 - 0.0 + + 0.0 0.0 0.0 1.0 -0.0 -0.0 - -0.0 - 0.0 + -0.0 + + + 0.0 0.0 0.0 1.0 -0.0 -0.0 - -0.0 + -0.0 + @@ -999,20 +1083,24 @@ false 0.001 - 0.0 + + 0.0 0.0 0.0 1.0 0.0 0.0 - 0.0 - 0.0 + 0.0 + + + 0.0 0.0 0.0 1.0 0.0 0.0 - 0.0 + 0.0 + 30.0 @@ -1055,20 +1143,24 @@ false 0.001 - 0.0 + + 0.0 0.0 0.0 1.0 0.0 0.0 - 0.0 - 0.0 + 0.0 + + + 0.0 0.0 0.0 1.0 0.0 0.0 - 0.0 + 0.0 + 0.0 @@ -1080,16 +1172,19 @@ 0.0 +> + 0.0 0.0 0.0 1.0 -0.0 -0.0 -0.0 + + 28.0 51.5 29.0 @@ -1097,6 +1192,7 @@ 0.7071067811865442 6.818941599633328E-8 -6.818941599633326E-8 + @@ -1144,20 +1240,24 @@ false 0.001 - 0.0 + + 0.0 0.0 0.0 1.0 0.0 0.0 - 0.0 - 0.0 + 0.0 + + + 0.0 0.0 0.0 1.0 0.0 0.0 - 0.0 + 0.0 + 0.0 @@ -1200,20 +1300,24 @@ false 0.05 - 0.0 + + 0.0 0.0 0.0 1.0 0.0 0.0 - 0.0 - 0.0 + 0.0 + + + 0.0 0.0 0.0 1.0 0.0 0.0 - 0.0 + 0.0 + 0.0 @@ -1225,16 +1329,19 @@ 0.0 +> + 0.0 0.0 0.0 1.0 -0.0 -0.0 -0.0 + + -78.5 73.75 0.0 @@ -1242,11 +1349,13 @@ -0.9999619021083685 2.2581029012393413E-6 2.587955605911622E-4 + + 0.0 0.0 0.0 @@ -1254,9 +1363,11 @@ -0.0 -0.0 -0.0 + + 0.0 0.0 0.0 @@ -1264,27 +1375,47 @@ -0.0 -0.0 -0.0 + 0.1 - 0.0 + + 0.0 0.0 40.0 1.0 0.0 0.0 - 0.0 - 0.0 + 0.0 + + + 0.0 0.0 0.0 1.0 0.0 0.0 - 0.0 + 0.0 + + +test1 +hobbyServo +mg92b + + 0.0 + 1.0 + 4.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + - \ No newline at end of file + diff --git a/test/java/src/junit/test/neuronrobotics/utilities/TestMobilBaseLoading.java b/test/java/src/junit/test/neuronrobotics/utilities/TestMobilBaseLoading.java index 3701338f..88186f40 100644 --- a/test/java/src/junit/test/neuronrobotics/utilities/TestMobilBaseLoading.java +++ b/test/java/src/junit/test/neuronrobotics/utilities/TestMobilBaseLoading.java @@ -11,6 +11,8 @@ import org.junit.Test; import com.neuronrobotics.sdk.addons.kinematics.MobileBase; +import com.neuronrobotics.sdk.addons.kinematics.VitaminLocation; +import com.neuronrobotics.sdk.addons.kinematics.math.TransformNR; public class TestMobilBaseLoading { @@ -20,7 +22,11 @@ public void test() throws IOException { String content = new String(Files.readAllBytes(Paths.get(file.getAbsolutePath()))); MobileBase base = new MobileBase(new FileInputStream(file)); - + base.getAllDHChains().get(0).getLinkConfiguration(0).getVitamins(); +// base.setVitamin(new VitaminLocation("test1", "hobbyServo", "mg92b", new TransformNR(0, 1, 4))); +// base.setVitamin(new VitaminLocation("test2", "hobbyServo", "mg92b", new TransformNR(0, 1, 4))); +// base.setVitamin(new VitaminLocation("test1", "hobbyServo", "mg92b", new TransformNR(0, 1, 4))); + if(Math.abs(0.1-base.getMassKg())>0.0001) { fail("Base mass failed to load! expected "+0.1+" got "+base.getMassKg()); } From 7200666ad762a9aeb6a03e00a9758b40b37a6956 Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Sun, 24 Mar 2024 16:46:31 -0400 Subject: [PATCH 16/60] add cnfiguration listeners --- .../addons/kinematics/VitaminLocation.java | 45 ++++++++++++++++--- 1 file changed, 40 insertions(+), 5 deletions(-) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java index c55c7036..8db1603e 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java @@ -6,15 +6,17 @@ import org.w3c.dom.Node; import org.w3c.dom.NodeList; +import com.neuronrobotics.sdk.addons.kinematics.math.ITransformNRChangeListener; import com.neuronrobotics.sdk.addons.kinematics.math.TransformNR; import com.neuronrobotics.sdk.addons.kinematics.xml.XmlFactory; -public class VitaminLocation { +public class VitaminLocation implements ITransformNRChangeListener { + ArrayList listeners=new ArrayList<>(); private String name; private String type; private String size; - private TransformNR location; + private TransformNR location=null; public VitaminLocation(String name, String type, String size, TransformNR location) { this.setName(name); @@ -45,12 +47,33 @@ public VitaminLocation(Element vitamins) { } + public void addChangeListener(Runnable r) { + if(listeners.contains(r)) + return; + listeners.add(r); + } + public void removeChangeListener(Runnable r) { + if(listeners.contains(r)) + listeners.remove(r); + } + void fireChangeEvent() { + if (listeners != null) { + for (int i = 0; i < listeners.size(); i++) { + try { + listeners.get(i).run(); + } catch (Throwable t) { + t.printStackTrace(); + } + } + } + + } public String getXML() { return "\n\n"+ ""+name+"\n"+ ""+type+"\n"+ - ""+size+"\n"+ + ""+size+"\n"+ ""+location.getXml()+"\n"+ "\n" ; @@ -86,6 +109,7 @@ public static String getAllXML(ArrayList list) { * @return the name */ public String getName() { + return name; } @@ -96,6 +120,7 @@ public void setName(String name) { if (name==null) throw new RuntimeException("Name can not be null"); this.name = name; + fireChangeEvent(); } /** @@ -113,6 +138,7 @@ public void setType(String type) { if (type==null) throw new RuntimeException("type can not be null"); this.type = type; + fireChangeEvent(); } /** @@ -129,6 +155,7 @@ public void setSize(String size) { if (size==null) throw new RuntimeException("size can not be null"); this.size = size; + fireChangeEvent(); } /** @@ -141,10 +168,18 @@ public TransformNR getLocation() { /** * @param location the location to set */ - public void setLocation(TransformNR location) { + public void setLocation(TransformNR l) { if (location==null) throw new RuntimeException("location can not be null"); - this.location = location; + if(l!=null) + l.removeChangeListener(this); + this.location = l; + location.addChangeListener(this); + } + + @Override + public void event(TransformNR changed) { + fireChangeEvent(); } } From 99cb4cd6c51709d6d10527e85d624febd78f2bca Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Sun, 24 Mar 2024 16:46:44 -0400 Subject: [PATCH 17/60] use vitamin configuration listners --- .../addons/kinematics/LinkConfiguration.java | 34 ++++++++++++++++--- 1 file changed, 29 insertions(+), 5 deletions(-) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/LinkConfiguration.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/LinkConfiguration.java index 7e5cfe2f..e8533f14 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/LinkConfiguration.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/LinkConfiguration.java @@ -100,6 +100,9 @@ public class LinkConfiguration implements ITransformNRChangeListener { private HashMap vitaminVariant = new HashMap(); private boolean passive = false; private boolean newAbs = false; + private Runnable changeListener = ()->{ + fireChangeEvent(); + }; /** * Instantiates a new link configuration. @@ -283,6 +286,7 @@ protected void getVitamins(Element doc) { return; } + /** * Add a vitamin to this link * @@ -291,15 +295,30 @@ protected void getVitamins(Element doc) { * @param type the vitamin type, this maps the the json filename * @param id the part ID, theis maps to the key in the json for the vitamin */ - public void setVitamin(VitaminLocation loc) { - if(vitamins.contains(loc)) + @Deprecated + public void setVitamin(VitaminLocation location) { + addVitamin(location); + + } + /** + * Add a vitamin to this link + * + * @param name the name of this vitamin, if the name already exists, the data + * will be overwritten. + * @param type the vitamin type, this maps the the json filename + * @param id the part ID, theis maps to the key in the json for the vitamin + */ + public void addVitamin(VitaminLocation location) { + if(vitamins.contains(location)) return; - vitamins.add(loc); + vitamins.add(location); + location.addChangeListener(changeListener); fireChangeEvent(); } public void removeVitamin(VitaminLocation loc) { if(vitamins.contains(loc)) vitamins.remove(loc); + loc.removeChangeListener(changeListener); fireChangeEvent(); } @@ -1000,8 +1019,13 @@ public void setPassive(boolean passive) { return vitamins; } - public void setVitamins(ArrayList vitamins) { - this.vitamins = vitamins; + public void setVitamins(ArrayList v) { + if(vitamins!=null) + for(VitaminLocation l:vitamins) + l.removeChangeListener(changeListener); + this.vitamins = v; + for(VitaminLocation l:vitamins) + l.addChangeListener(changeListener); fireChangeEvent(); } From 0f25ece857506cb917a509cc69158b2e61bddf20 Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Sun, 24 Mar 2024 16:47:03 -0400 Subject: [PATCH 18/60] renamed the api to add --- .../sdk/addons/kinematics/MobileBase.java | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java index 662b8275..a7f44fc2 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java @@ -575,7 +575,20 @@ private void getVitamins(Element doc) { * @param type the vitamin type, this maps the the json filename * @param id the part ID, theis maps to the key in the json for the vitamin */ + @Deprecated public void setVitamin(VitaminLocation location) { + addVitamin(location); + + } + /** + * Add a vitamin to this link + * + * @param name the name of this vitamin, if the name already exists, the data + * will be overwritten. + * @param type the vitamin type, this maps the the json filename + * @param id the part ID, theis maps to the key in the json for the vitamin + */ + public void addVitamin(VitaminLocation location) { if(vitamins.contains(location)) return; vitamins.add(location); From d17fc037c384dc56309848f8afc9bed810d46533 Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Sun, 24 Mar 2024 16:47:19 -0400 Subject: [PATCH 19/60] testing adding additional vitamins on a link --- .../test/neuronrobotics/utilities/TestMobilBaseLoading.java | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/test/java/src/junit/test/neuronrobotics/utilities/TestMobilBaseLoading.java b/test/java/src/junit/test/neuronrobotics/utilities/TestMobilBaseLoading.java index 88186f40..9b42f51b 100644 --- a/test/java/src/junit/test/neuronrobotics/utilities/TestMobilBaseLoading.java +++ b/test/java/src/junit/test/neuronrobotics/utilities/TestMobilBaseLoading.java @@ -22,7 +22,10 @@ public void test() throws IOException { String content = new String(Files.readAllBytes(Paths.get(file.getAbsolutePath()))); MobileBase base = new MobileBase(new FileInputStream(file)); - base.getAllDHChains().get(0).getLinkConfiguration(0).getVitamins(); +// base.getAllDHChains() +// .get(0) +// .getLinkConfiguration(0) +// .setVitamin(new VitaminLocation("test1", "hobbyServo", "mg92b", new TransformNR(0, 1, 4))); // base.setVitamin(new VitaminLocation("test1", "hobbyServo", "mg92b", new TransformNR(0, 1, 4))); // base.setVitamin(new VitaminLocation("test2", "hobbyServo", "mg92b", new TransformNR(0, 1, 4))); // base.setVitamin(new VitaminLocation("test1", "hobbyServo", "mg92b", new TransformNR(0, 1, 4))); From d266c315a2fddc364befa695adec28bf35a66c10 Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Sun, 24 Mar 2024 16:47:30 -0400 Subject: [PATCH 20/60] Adding vitamin to lin --- .../kinematics/xml/NASASuspensionTest.xml | 753 +++++++++++++----- 1 file changed, 544 insertions(+), 209 deletions(-) diff --git a/src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/NASASuspensionTest.xml b/src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/NASASuspensionTest.xml index 80321ef0..f5688dd6 100644 --- a/src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/NASASuspensionTest.xml +++ b/src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/NASASuspensionTest.xml @@ -39,19 +39,54 @@ false 10000000 - - - electroMechanical - hobbyServo - standardMicro - - - shaft - hobbyServoHorn - standardMicro1 - - - + + + +electroMechanical +hobbyServo +standardMicro + + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + + +shaft +hobbyServoHorn +standardMicro1 + + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + + +test1 +hobbyServo +mg92b + + 0.0 + 1.0 + 4.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + + false 0.001 @@ -99,19 +134,39 @@ false 10000000 - - - electroMechanical - hobbyServo - standardMicro - - - shaft - hobbyServoHorn - standardMicro1 - - - + + + +electroMechanical +hobbyServo +standardMicro + + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + + +shaft +hobbyServoHorn +standardMicro1 + + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + + false 0.001 @@ -159,19 +214,39 @@ false 10000000 - - - electroMechanical - hobbyServo - standardMicro - - - shaft - hobbyServoHorn - standardMicro1 - - - + + + +electroMechanical +hobbyServo +standardMicro + + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + + +shaft +hobbyServoHorn +standardMicro1 + + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + + false 0.001 @@ -219,19 +294,39 @@ false 10000000 - - - electroMechanical - hobbyServo - standardMicro - - - shaft - hobbyServoHorn - standardMicro1 - - - + + + +electroMechanical +hobbyServo +standardMicro + + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + + +shaft +hobbyServoHorn +standardMicro1 + + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + + false 0.001 @@ -316,19 +411,39 @@ false 10000000 - - - electroMechanical - hobbyServo - standardMicro - - - shaft - hobbyServoHorn - standardMicro1 - - - + + + +electroMechanical +hobbyServo +standardMicro + + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + + +shaft +hobbyServoHorn +standardMicro1 + + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + + false 0.001 @@ -376,19 +491,39 @@ false 10000000 - - - electroMechanical - hobbyServo - standardMicro - - - shaft - hobbyServoHorn - standardMicro1 - - - + + + +electroMechanical +hobbyServo +standardMicro + + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + + +shaft +hobbyServoHorn +standardMicro1 + + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + + false 0.05 @@ -473,19 +608,39 @@ false 10000000 - - - electroMechanical - hobbyServo - standardMicro - - - shaft - hobbyServoHorn - standardMicro1 - - - + + + +electroMechanical +hobbyServo +standardMicro + + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + + +shaft +hobbyServoHorn +standardMicro1 + + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + + true 0.001 @@ -553,19 +708,39 @@ false 10000000 - - - electroMechanical - hobbyServo - standardMicro - - - shaft - hobbyServoHorn - standardMicro1 - - - + + + +electroMechanical +hobbyServo +standardMicro + + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + + +shaft +hobbyServoHorn +standardMicro1 + + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + + false 0.05 @@ -692,19 +867,39 @@ false 10000000 - - - electroMechanical - hobbyServo - standardMicro - - - shaft - hobbyServoHorn - standardMicro1 - - - + + + +electroMechanical +hobbyServo +standardMicro + + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + + +shaft +hobbyServoHorn +standardMicro1 + + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + + false 0.001 @@ -752,19 +947,39 @@ false 10000000 - - - electroMechanical - hobbyServo - standardMicro - - - shaft - hobbyServoHorn - standardMicro1 - - - + + + +electroMechanical +hobbyServo +standardMicro + + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + + +shaft +hobbyServoHorn +standardMicro1 + + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + + false 0.05 @@ -849,19 +1064,39 @@ false 10000000 - - - electroMechanical - hobbyServo - standardMicro - - - shaft - hobbyServoHorn - standardMicro1 - - - + + + +electroMechanical +hobbyServo +standardMicro + + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + + +shaft +hobbyServoHorn +standardMicro1 + + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + + true 0.001 @@ -929,19 +1164,39 @@ false 10000000 - - - electroMechanical - hobbyServo - standardMicro - - - shaft - hobbyServoHorn - standardMicro1 - - - + + + +electroMechanical +hobbyServo +standardMicro + + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + + +shaft +hobbyServoHorn +standardMicro1 + + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + + false 0.05 @@ -1068,19 +1323,39 @@ false 10000000 - - - electroMechanical - hobbyServo - standardMicro - - - shaft - hobbyServoHorn - standardMicro1 - - - + + + +electroMechanical +hobbyServo +standardMicro + + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + + +shaft +hobbyServoHorn +standardMicro1 + + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + + false 0.001 @@ -1128,19 +1403,39 @@ false 10000000 - - - electroMechanical - hobbyServo - standardMicro - - - shaft - hobbyServoHorn - standardMicro1 - - - + + + +electroMechanical +hobbyServo +standardMicro + + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + + +shaft +hobbyServoHorn +standardMicro1 + + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + + false 0.001 @@ -1225,19 +1520,39 @@ false 10000000 - - - electroMechanical - hobbyServo - standardMicro - - - shaft - hobbyServoHorn - standardMicro1 - - - + + + +electroMechanical +hobbyServo +standardMicro + + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + + +shaft +hobbyServoHorn +standardMicro1 + + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + + false 0.001 @@ -1285,19 +1600,39 @@ false 10000000 - - - electroMechanical - hobbyServo - standardMicro - - - shaft - hobbyServoHorn - standardMicro1 - - - + + + +electroMechanical +hobbyServo +standardMicro + + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + + +shaft +hobbyServoHorn +standardMicro1 + + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + + + false 0.05 @@ -1418,4 +1753,4 @@ - + \ No newline at end of file From f86ae42c7dc67080322d328a2387434e91fd0e68 Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Sun, 24 Mar 2024 16:49:57 -0400 Subject: [PATCH 21/60] runtime smoke test --- .../neuronrobotics/sdk/addons/kinematics/VitaminLocation.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java index 8db1603e..dc99a350 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java @@ -169,7 +169,7 @@ public TransformNR getLocation() { * @param location the location to set */ public void setLocation(TransformNR l) { - if (location==null) + if (l==null) throw new RuntimeException("location can not be null"); if(l!=null) l.removeChangeListener(this); From 7cd504d8abbb19ec510de292c2c4ba25350c6fcd Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Sun, 24 Mar 2024 21:17:42 -0400 Subject: [PATCH 22/60] loading of vitamins using a manipuable object --- .../sdk/addons/kinematics/MobileBase.java | 4 +- .../addons/kinematics/VitaminLocation.java | 16 +- .../kinematics/xml/NASASuspensionTest.xml | 598 +++++++++--------- 3 files changed, 294 insertions(+), 324 deletions(-) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java index a7f44fc2..4d318163 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java @@ -344,7 +344,7 @@ private String findNameTag(Node e) { if(elementTester.getNodeName().contentEquals("name")) return elementTester.getChildNodes().item(0).getNodeValue(); } - return null; + return "parentNoName"; } /** @@ -708,7 +708,7 @@ public String getEmbedableXml() { } xml += "\n\n"; - xml += getFiducialToGlobalTransform().getXml(); + xml += new TransformNR().getXml(); xml += "\n\n"; xml += "\n\n"; diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java index dc99a350..4eb1a57d 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java @@ -70,12 +70,12 @@ void fireChangeEvent() { } public String getXML() { - return "\n\n"+ - ""+name+"\n"+ - ""+type+"\n"+ - ""+size+"\n"+ - ""+location.getXml()+"\n"+ - "\n" + return "\n\t\t\n"+ + "\t\t\t"+name+"\n"+ + "\t\t\t"+type+"\n"+ + "\t\t\t"+size+"\n"+ + "\t\t\t"+location.getXml()+"\t\t\t\n"+ + "\t\t\n" ; } public static ArrayList getVitamins(Element doc) { @@ -97,11 +97,11 @@ public static ArrayList getVitamins(Element doc) { public static String getAllXML(ArrayList list) { - String vitamins="\n\n"; + String vitamins="\n\t\n"; for(VitaminLocation loc:list) { vitamins+=loc.getXML(); } - return vitamins+"\n\n"; + return vitamins+"\n\t\n"; } diff --git a/src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/NASASuspensionTest.xml b/src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/NASASuspensionTest.xml index f5688dd6..8f2b3038 100644 --- a/src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/NASASuspensionTest.xml +++ b/src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/NASASuspensionTest.xml @@ -39,13 +39,13 @@ false 10000000 - + - -electroMechanical -hobbyServo -standardMicro - + + electroMechanical + hobbyServo + standardMicro + 0.0 0.0 0.0 @@ -53,14 +53,14 @@ -0.0 -0.0 -0.0 - - + + - -shaft -hobbyServoHorn -standardMicro1 - + + shaft + hobbyServoHorn + standardMicro1 + 0.0 0.0 0.0 @@ -68,25 +68,10 @@ -0.0 -0.0 -0.0 - - + + - -test1 -hobbyServo -mg92b - - 0.0 - 1.0 - 4.0 - 1.0 - -0.0 - -0.0 - -0.0 - - - - + false 0.001 @@ -134,13 +119,13 @@ false 10000000 - + - -electroMechanical -hobbyServo -standardMicro - + + electroMechanical + hobbyServo + standardMicro + 0.0 0.0 0.0 @@ -148,14 +133,14 @@ -0.0 -0.0 -0.0 - - + + - -shaft -hobbyServoHorn -standardMicro1 - + + shaft + hobbyServoHorn + standardMicro1 + 0.0 0.0 0.0 @@ -163,10 +148,10 @@ -0.0 -0.0 -0.0 - - + + - + false 0.001 @@ -214,13 +199,13 @@ false 10000000 - + - -electroMechanical -hobbyServo -standardMicro - + + electroMechanical + hobbyServo + standardMicro + 0.0 0.0 0.0 @@ -228,14 +213,14 @@ -0.0 -0.0 -0.0 - - + + - -shaft -hobbyServoHorn -standardMicro1 - + + shaft + hobbyServoHorn + standardMicro1 + 0.0 0.0 0.0 @@ -243,10 +228,10 @@ -0.0 -0.0 -0.0 - - + + - + false 0.001 @@ -294,13 +279,13 @@ false 10000000 - + - -electroMechanical -hobbyServo -standardMicro - + + electroMechanical + hobbyServo + standardMicro + 0.0 0.0 0.0 @@ -308,14 +293,14 @@ -0.0 -0.0 -0.0 - - + + - -shaft -hobbyServoHorn -standardMicro1 - + + shaft + hobbyServoHorn + standardMicro1 + 0.0 0.0 0.0 @@ -323,10 +308,10 @@ -0.0 -0.0 -0.0 - - + + - + false 0.001 @@ -411,13 +396,13 @@ false 10000000 - + - -electroMechanical -hobbyServo -standardMicro - + + electroMechanical + hobbyServo + standardMicro + 0.0 0.0 0.0 @@ -425,14 +410,14 @@ -0.0 -0.0 -0.0 - - + + - -shaft -hobbyServoHorn -standardMicro1 - + + shaft + hobbyServoHorn + standardMicro1 + 0.0 0.0 0.0 @@ -440,10 +425,10 @@ -0.0 -0.0 -0.0 - - + + - + false 0.001 @@ -491,13 +476,13 @@ false 10000000 - + - -electroMechanical -hobbyServo -standardMicro - + + electroMechanical + hobbyServo + standardMicro + 0.0 0.0 0.0 @@ -505,14 +490,14 @@ -0.0 -0.0 -0.0 - - + + - -shaft -hobbyServoHorn -standardMicro1 - + + shaft + hobbyServoHorn + standardMicro1 + 0.0 0.0 0.0 @@ -520,14 +505,14 @@ -0.0 -0.0 -0.0 - - + + - + false 0.05 - 0.0 + -18.0 0.0 0.0 1.0 @@ -608,13 +593,13 @@ false 10000000 - + - -electroMechanical -hobbyServo -standardMicro - + + electroMechanical + hobbyServo + standardMicro + 0.0 0.0 0.0 @@ -622,14 +607,14 @@ -0.0 -0.0 -0.0 - - + + - -shaft -hobbyServoHorn -standardMicro1 - + + shaft + hobbyServoHorn + standardMicro1 + 0.0 0.0 0.0 @@ -637,10 +622,10 @@ -0.0 -0.0 -0.0 - - + + - + true 0.001 @@ -708,13 +693,13 @@ false 10000000 - + - -electroMechanical -hobbyServo -standardMicro - + + electroMechanical + hobbyServo + standardMicro + 0.0 0.0 0.0 @@ -722,14 +707,14 @@ -0.0 -0.0 -0.0 - - + + - -shaft -hobbyServoHorn -standardMicro1 - + + shaft + hobbyServoHorn + standardMicro1 + 0.0 0.0 0.0 @@ -737,14 +722,14 @@ -0.0 -0.0 -0.0 - - + + - + false - 0.05 + 0.051 - 0.0 + -18.0 0.0 0.0 1.0 @@ -799,13 +784,13 @@ - 0.2951945417837649 - -75.50000000000001 - -6.460453388562168 - 4.866904542229674E-17 - 0.43837065166596395 - -9.978614964896946E-17 - -0.898794287786676 + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 @@ -840,9 +825,9 @@ -0.0 - + - + @@ -867,13 +852,13 @@ false 10000000 - + - -electroMechanical -hobbyServo -standardMicro - + + electroMechanical + hobbyServo + standardMicro + 0.0 0.0 0.0 @@ -881,14 +866,14 @@ -0.0 -0.0 -0.0 - - + + - -shaft -hobbyServoHorn -standardMicro1 - + + shaft + hobbyServoHorn + standardMicro1 + 0.0 0.0 0.0 @@ -896,10 +881,10 @@ -0.0 -0.0 -0.0 - - + + - + false 0.001 @@ -947,13 +932,13 @@ false 10000000 - + - -electroMechanical -hobbyServo -standardMicro - + + electroMechanical + hobbyServo + standardMicro + 0.0 0.0 0.0 @@ -961,14 +946,14 @@ -0.0 -0.0 -0.0 - - + + - -shaft -hobbyServoHorn -standardMicro1 - + + shaft + hobbyServoHorn + standardMicro1 + 0.0 0.0 0.0 @@ -976,14 +961,14 @@ -0.0 -0.0 -0.0 - - + + - + false 0.05 - 0.0 + -18.0 0.0 0.0 1.0 @@ -1064,13 +1049,13 @@ false 10000000 - + - -electroMechanical -hobbyServo -standardMicro - + + electroMechanical + hobbyServo + standardMicro + 0.0 0.0 0.0 @@ -1078,14 +1063,14 @@ -0.0 -0.0 -0.0 - - + + - -shaft -hobbyServoHorn -standardMicro1 - + + shaft + hobbyServoHorn + standardMicro1 + 0.0 0.0 0.0 @@ -1093,10 +1078,10 @@ -0.0 -0.0 -0.0 - - + + - + true 0.001 @@ -1164,13 +1149,13 @@ false 10000000 - + - -electroMechanical -hobbyServo -standardMicro - + + electroMechanical + hobbyServo + standardMicro + 0.0 0.0 0.0 @@ -1178,14 +1163,14 @@ -0.0 -0.0 -0.0 - - + + - -shaft -hobbyServoHorn -standardMicro1 - + + shaft + hobbyServoHorn + standardMicro1 + 0.0 0.0 0.0 @@ -1193,14 +1178,14 @@ -0.0 -0.0 -0.0 - - + + - + false 0.05 - 0.0 + -18.0 0.0 0.0 1.0 @@ -1255,13 +1240,13 @@ - 0.2952267711251224 - 76.5 - -6.460478568916969 - 4.86689829712371E-17 - 0.4383710601144136 - -9.978618010838941E-17 - -0.89879408857322 + 0.0 + 0.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 @@ -1296,9 +1281,9 @@ -0.0 - + - + @@ -1323,13 +1308,13 @@ false 10000000 - + - -electroMechanical -hobbyServo -standardMicro - + + electroMechanical + hobbyServo + standardMicro + 0.0 0.0 0.0 @@ -1337,14 +1322,14 @@ -0.0 -0.0 -0.0 - - + + - -shaft -hobbyServoHorn -standardMicro1 - + + shaft + hobbyServoHorn + standardMicro1 + 0.0 0.0 0.0 @@ -1352,10 +1337,10 @@ -0.0 -0.0 -0.0 - - + + - + false 0.001 @@ -1403,13 +1388,13 @@ false 10000000 - + - -electroMechanical -hobbyServo -standardMicro - + + electroMechanical + hobbyServo + standardMicro + 0.0 0.0 0.0 @@ -1417,14 +1402,14 @@ -0.0 -0.0 -0.0 - - + + - -shaft -hobbyServoHorn -standardMicro1 - + + shaft + hobbyServoHorn + standardMicro1 + 0.0 0.0 0.0 @@ -1432,14 +1417,14 @@ -0.0 -0.0 -0.0 - - + + - + false - 0.001 + 0.05 - 0.0 + -18.0 0.0 0.0 1.0 @@ -1520,13 +1505,13 @@ false 10000000 - + - -electroMechanical -hobbyServo -standardMicro - + + electroMechanical + hobbyServo + standardMicro + 0.0 0.0 0.0 @@ -1534,14 +1519,14 @@ -0.0 -0.0 -0.0 - - + + - -shaft -hobbyServoHorn -standardMicro1 - + + shaft + hobbyServoHorn + standardMicro1 + 0.0 0.0 0.0 @@ -1549,10 +1534,10 @@ -0.0 -0.0 -0.0 - - + + - + false 0.001 @@ -1600,13 +1585,13 @@ false 10000000 - + - -electroMechanical -hobbyServo -standardMicro - + + electroMechanical + hobbyServo + standardMicro + 0.0 0.0 0.0 @@ -1614,14 +1599,14 @@ -0.0 -0.0 -0.0 - - + + - -shaft -hobbyServoHorn -standardMicro1 - + + shaft + hobbyServoHorn + standardMicro1 + 0.0 0.0 0.0 @@ -1629,14 +1614,14 @@ -0.0 -0.0 -0.0 - - + + - + false 0.05 - 0.0 + -18.0 0.0 0.0 1.0 @@ -1732,24 +1717,9 @@ 0.0 - - - -test1 -hobbyServo -mg92b - - 0.0 - 1.0 - 4.0 - 1.0 - -0.0 - -0.0 - -0.0 - - + - + From 9761964dad71b5e64aef375d9487f89669a249e2 Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Sun, 24 Mar 2024 21:25:38 -0400 Subject: [PATCH 23/60] mks having vitamins into an interface --- .../sdk/addons/kinematics/IVitaminHolder.java | 9 +++++++++ .../sdk/addons/kinematics/LinkConfiguration.java | 2 +- .../neuronrobotics/sdk/addons/kinematics/MobileBase.java | 2 +- 3 files changed, 11 insertions(+), 2 deletions(-) create mode 100644 src/main/java/com/neuronrobotics/sdk/addons/kinematics/IVitaminHolder.java diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/IVitaminHolder.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/IVitaminHolder.java new file mode 100644 index 00000000..3ecfde5c --- /dev/null +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/IVitaminHolder.java @@ -0,0 +1,9 @@ +package com.neuronrobotics.sdk.addons.kinematics; + +import java.util.ArrayList; + +public interface IVitaminHolder { + ArrayList getVitamins() ; + void addVitamin(VitaminLocation location); + void removeVitamin(VitaminLocation loc); +} diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/LinkConfiguration.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/LinkConfiguration.java index e8533f14..1700f950 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/LinkConfiguration.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/LinkConfiguration.java @@ -22,7 +22,7 @@ /** * The Class LinkConfiguration. */ -public class LinkConfiguration implements ITransformNRChangeListener { +public class LinkConfiguration implements ITransformNRChangeListener,IVitaminHolder { private ArrayList listeners = null; private boolean pauseEvents=false; /** The name. */ diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java index 4d318163..08d5512b 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java @@ -27,7 +27,7 @@ * The Class MobileBase. */ public class MobileBase extends AbstractKinematicsNR implements ILinkConfigurationChangeListener, - IOnMobileBaseRenderChange, IJointSpaceUpdateListenerNR, IHardwareSyncPulseReciver, IHardwareSyncPulseProvider { + IOnMobileBaseRenderChange, IJointSpaceUpdateListenerNR, IHardwareSyncPulseReciver, IHardwareSyncPulseProvider,IVitaminHolder { /** The legs. */ private final ArrayList legs = new ArrayList(); From 65ccfceb9fe35725c3a761160c66bc60c9867bd8 Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Thu, 4 Apr 2024 10:42:34 -0400 Subject: [PATCH 24/60] add print string helper functions --- .../sdk/addons/kinematics/math/TransformNR.java | 14 +++++++++++++- 1 file changed, 13 insertions(+), 1 deletion(-) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/TransformNR.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/TransformNR.java index 4a8acce3..ae45efc1 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/TransformNR.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/TransformNR.java @@ -223,11 +223,23 @@ public String toString() { return "Transform error" + ex.getLocalizedMessage(); } } + public String toSimpleString() { + return toPositionString()+" "+toAngleString(); + } public String toPositionString() { DecimalFormat decimalFormat = new DecimalFormat("000.00"); - return decimalFormat.format(x)+" "+decimalFormat.format(y)+" "+decimalFormat.format(z); + return "x="+decimalFormat.format(x)+" "+ + "y="+decimalFormat.format(y)+" "+ + "z="+decimalFormat.format(z); } + public String toAngleString() { + DecimalFormat decimalFormat = new DecimalFormat("000.00"); + + return "az="+decimalFormat.format(Math.toDegrees(getRotation().getRotationAzimuth()))+" "+ + "el="+decimalFormat.format(Math.toDegrees(getRotation().getRotationElevation()))+" "+ + "tl="+decimalFormat.format(Math.toDegrees(getRotation().getRotationTilt())); + } /** * Gets the matrix string. From 838acafbf087999edeb4f853744837d9bf8c3d96 Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Sun, 7 Apr 2024 14:38:42 -0400 Subject: [PATCH 25/60] Adding accessor methods to dh parameters and abstriact link to access the configurations vitamins --- .../sdk/addons/kinematics/AbstractLink.java | 20 +++++++++++++++++- .../kinematics/DHParameterKinematics.java | 21 +++++++++++++++++++ .../addons/kinematics/LinkConfiguration.java | 20 +++++++++--------- 3 files changed, 50 insertions(+), 11 deletions(-) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractLink.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractLink.java index 4e978588..9e27d988 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractLink.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractLink.java @@ -21,7 +21,7 @@ * The Class AbstractLink. */ // Kevin Shouldn't the Link's channel be kept in this level of Abstraction? The way I designg AbstractCartesianPositonDevice Requires this -public abstract class AbstractLink extends TimeKeeper implements IFlushable{ +public abstract class AbstractLink extends TimeKeeper implements IFlushable,IVitaminHolder { /** The target value. */ private double targetValue=0; @@ -45,6 +45,24 @@ public abstract class AbstractLink extends TimeKeeper implements IFlushable{ * The object for communicating IMU information and registering it with the hardware */ private IMU imu = new IMU(); + + public VitaminLocation getShaftVitamin() { + return conf.getShaftVitamin(); + } + + public VitaminLocation getElectroMechanicalVitamin() { + return conf.getElectroMechanicalVitamin(); + } + public ArrayList getVitamins() { + return conf.getVitamins(); + } + public void addVitamin(VitaminLocation location) { + conf.addVitamin(location); + } + public void removeVitamin(VitaminLocation loc) { + conf.removeVitamin(loc); + } + /** * Override this method to specify a larger range * @return the maximum value possible for a link diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/DHParameterKinematics.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/DHParameterKinematics.java index d19ce61c..1e7ab036 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/DHParameterKinematics.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/DHParameterKinematics.java @@ -861,4 +861,25 @@ public void setTimeProvider(ITimeProvider t) { super.setTimeProvider(t); getDhChain().setTimeProvider(t); } + + public VitaminLocation getShaftVitamin(int index) { + return getLinkConfiguration(index).getShaftVitamin(); + } + + public VitaminLocation getElectroMechanicalVitamin(int index) { + return getLinkConfiguration(index).getElectroMechanicalVitamin(); + } + public ArrayList getVitamins(int index) { + return getLinkConfiguration(index).getVitamins(); + } + + public void addVitamin(int index,VitaminLocation location) { + getLinkConfiguration(index).addVitamin(location); + } + public void removeVitamin(int index,VitaminLocation loc) { + getLinkConfiguration(index).removeVitamin(loc); + } + public IVitaminHolder getVitaminHolder(int index) { + return getLinkConfiguration(index); + } } diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/LinkConfiguration.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/LinkConfiguration.java index 1700f950..df0b0ce1 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/LinkConfiguration.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/LinkConfiguration.java @@ -952,7 +952,7 @@ public void setimuFromCentroid(TransformNR imu) { // private String shaftType = "hobbyServoHorn"; // private String shaftSize = "standardMicro1"; - private VitaminLocation getCoreShaftPart() { + public VitaminLocation getShaftVitamin() { for(VitaminLocation loc:vitamins) if(loc.getName().contentEquals("shaft")) return loc; @@ -961,7 +961,7 @@ private VitaminLocation getCoreShaftPart() { return e; } - private VitaminLocation getCoreEmPart() { + public VitaminLocation getElectroMechanicalVitamin() { for(VitaminLocation loc:vitamins) if(loc.getName().contentEquals("electroMechanical")) return loc; @@ -971,38 +971,38 @@ private VitaminLocation getCoreEmPart() { } public String getElectroMechanicalType() { - return getCoreEmPart().getType(); + return getElectroMechanicalVitamin().getType(); } public void setElectroMechanicalType(String electroMechanicalType) { - getCoreEmPart().setType(electroMechanicalType); + getElectroMechanicalVitamin().setType(electroMechanicalType); fireChangeEvent(); } public String getElectroMechanicalSize() { - return getCoreEmPart().getSize(); + return getElectroMechanicalVitamin().getSize(); } public void setElectroMechanicalSize(String electroMechanicalSize) { - getCoreEmPart().setSize(electroMechanicalSize); + getElectroMechanicalVitamin().setSize(electroMechanicalSize); fireChangeEvent(); } public String getShaftType() { - return getCoreShaftPart().getType(); + return getShaftVitamin().getType(); } public void setShaftType(String shaftType) { - getCoreShaftPart().setType(shaftType);; + getShaftVitamin().setType(shaftType);; fireChangeEvent(); } public String getShaftSize() { - return getCoreShaftPart().getSize(); + return getShaftVitamin().getSize(); } public void setShaftSize(String shaftSize) { - getCoreShaftPart().setSize(shaftSize); + getShaftVitamin().setSize(shaftSize); fireChangeEvent(); } From ffb1087d0720842e89ddf52b54df0f9edb2a8110 Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Sun, 7 Apr 2024 14:46:08 -0400 Subject: [PATCH 26/60] More accessor methods --- .../sdk/addons/kinematics/AbstractLink.java | 3 +++ .../sdk/addons/kinematics/DHParameterKinematics.java | 10 ++++++---- .../sdk/addons/kinematics/LinkConfiguration.java | 8 +++++++- 3 files changed, 16 insertions(+), 5 deletions(-) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractLink.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractLink.java index 9e27d988..36d36c73 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractLink.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractLink.java @@ -62,6 +62,9 @@ public void addVitamin(VitaminLocation location) { public void removeVitamin(VitaminLocation loc) { conf.removeVitamin(loc); } + public ArrayListgetNonActuatorVitamins(){ + return conf.getNonActuatorVitamins(); + } /** * Override this method to specify a larger range diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/DHParameterKinematics.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/DHParameterKinematics.java index 1e7ab036..dc39b327 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/DHParameterKinematics.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/DHParameterKinematics.java @@ -870,14 +870,16 @@ public VitaminLocation getElectroMechanicalVitamin(int index) { return getLinkConfiguration(index).getElectroMechanicalVitamin(); } public ArrayList getVitamins(int index) { - return getLinkConfiguration(index).getVitamins(); + return getVitaminHolder(index).getVitamins(); + } + public ArrayListgetNonActuatorVitamins(int index){ + return getLinkConfiguration(index).getNonActuatorVitamins(); } - public void addVitamin(int index,VitaminLocation location) { - getLinkConfiguration(index).addVitamin(location); + getVitaminHolder(index).addVitamin(location); } public void removeVitamin(int index,VitaminLocation loc) { - getLinkConfiguration(index).removeVitamin(loc); + getVitaminHolder(index).removeVitamin(loc); } public IVitaminHolder getVitaminHolder(int index) { return getLinkConfiguration(index); diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/LinkConfiguration.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/LinkConfiguration.java index df0b0ce1..0ee853db 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/LinkConfiguration.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/LinkConfiguration.java @@ -951,7 +951,13 @@ public void setimuFromCentroid(TransformNR imu) { // private String electroMechanicalSize = "standardMicro"; // private String shaftType = "hobbyServoHorn"; // private String shaftSize = "standardMicro1"; - + public ArrayListgetNonActuatorVitamins() { + ArrayList back = new ArrayList<>(); + back.addAll(vitamins); + back.remove(getShaftVitamin()); + back.remove(getElectroMechanicalVitamin()); + return back; + } public VitaminLocation getShaftVitamin() { for(VitaminLocation loc:vitamins) if(loc.getName().contentEquals("shaft")) From 93bf0b036f75fedec21b90c18cac06d52c254c98 Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Sun, 7 Apr 2024 16:03:19 -0400 Subject: [PATCH 27/60] add fire of the change event for setting location --- .../sdk/addons/kinematics/VitaminLocation.java | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java index 4eb1a57d..2bd38293 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java @@ -169,12 +169,17 @@ public TransformNR getLocation() { * @param location the location to set */ public void setLocation(TransformNR l) { + if(l==location) { + fireChangeEvent(); + return; + } if (l==null) throw new RuntimeException("location can not be null"); if(l!=null) l.removeChangeListener(this); this.location = l; location.addChangeListener(this); + fireChangeEvent(); } @Override From bcb6ca6be8ea63497353e68bc252e8173035476b Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Sun, 7 Apr 2024 18:56:21 -0400 Subject: [PATCH 28/60] add configuration change update --- .../sdk/addons/kinematics/MobileBase.java | 38 ++++++++++++++++++- 1 file changed, 36 insertions(+), 2 deletions(-) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java index 08d5512b..6cd950ce 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java @@ -64,6 +64,7 @@ public class MobileBase extends AbstractKinematicsNR implements ILinkConfigurati private HashMap parallelGroups = new HashMap(); private ICalcLimbHomeProvider homeProvider = null; + private Runnable configurationUpdate = ()->{}; /** * Instantiates a new mobile base. @@ -71,6 +72,14 @@ public class MobileBase extends AbstractKinematicsNR implements ILinkConfigurati public MobileBase() { }// used for building new bases live + public void fireConfigurationUpdate() { + if(configurationUpdate!=null) + try { + configurationUpdate.run(); + }catch(Throwable t) { + t.printStackTrace(); + } + } /** * Calc home. * @@ -212,6 +221,7 @@ public void addLimbToParallel(DHParameterKinematics limb, TransformNR tipOffset, removeLimFromParallel(limb); ParallelGroup g = getParallelGroup(name); g.addLimb(limb, tipOffset, relativeLimb, relativeIndex); + fireConfigurationUpdate(); } private void removeLimFromParallel(DHParameterKinematics limb) { @@ -222,6 +232,7 @@ private void removeLimFromParallel(DHParameterKinematics limb) { if (g.getConstituantLimbs().size() == 0) { getParallelGroups().remove(g.getNameOfParallelGroup()); } + fireConfigurationUpdate(); } /** @@ -592,12 +603,12 @@ public void addVitamin(VitaminLocation location) { if(vitamins.contains(location)) return; vitamins.add(location); - + fireConfigurationUpdate(); } public void removeVitamin(VitaminLocation loc) { if(vitamins.contains(loc)) vitamins.remove(loc); - //fireChangeEvent(); + fireConfigurationUpdate();//fireChangeEvent(); } /** @@ -816,6 +827,7 @@ private IDriveEngine getWalkingDriveEngine() { */ public void setWalkingDriveEngine(IDriveEngine walkingDriveEngine) { this.walkingDriveEngine = walkingDriveEngine; + fireConfigurationUpdate(); } /** @@ -877,6 +889,7 @@ public String[] getGitWalkingEngine() { public void setGitWalkingEngine(String[] walkingEngine) { if (walkingEngine != null && walkingEngine[0] != null && walkingEngine[1] != null) this.walkingEngine = walkingEngine; + fireConfigurationUpdate(); } /** @@ -897,6 +910,7 @@ public String[] getGitSelfSource() { */ public void setGitSelfSource(String[] selfSource) { this.selfSource = selfSource; + fireConfigurationUpdate(); } public double getMassKg() { @@ -908,6 +922,7 @@ public void setMassKg(double mass) { System.out.println("Mass of device " + getScriptingName() + " is " + mass); //new RuntimeException().printStackTrace(); this.mass = mass; + fireConfigurationUpdate(); } public TransformNR getCenterOfMassFromCentroid() { @@ -916,6 +931,7 @@ public TransformNR getCenterOfMassFromCentroid() { public void setCenterOfMassFromCentroid(TransformNR centerOfMassFromCentroid) { this.centerOfMassFromCentroid = centerOfMassFromCentroid; + fireConfigurationUpdate(); } public TransformNR getIMUFromCentroid() { @@ -924,10 +940,12 @@ public TransformNR getIMUFromCentroid() { public void setIMUFromCentroid(TransformNR centerOfMassFromCentroid) { this.IMUFromCentroid = centerOfMassFromCentroid; + fireConfigurationUpdate(); } public void setFiducialToGlobalTransform(TransformNR globe) { setGlobalToFiducialTransform(globe); + fireConfigurationUpdate(); } @@ -942,6 +960,7 @@ private void fireBaseUpdates() { public void shutDownParallel(ParallelGroup group) { group.close(); parallelGroups.remove(group.getNameOfParallelGroup()); + fireConfigurationUpdate(); } private HashMap getParallelGroups() { @@ -1057,6 +1076,7 @@ public void clearIOnMobileBaseRenderChange() { public void event(LinkConfiguration newConf) { // TODO Auto-generated method stub fireIOnMobileBaseRenderChange(); + fireConfigurationUpdate(); } @Override @@ -1095,4 +1115,18 @@ public void setTimeProvider(ITimeProvider t) { } } + /** + * @return the configurationUpdate + */ + public Runnable getConfigurationUpdate() { + return configurationUpdate; + } + + /** + * @param configurationUpdate the configurationUpdate to set + */ + public void setConfigurationUpdate(Runnable configurationUpdate) { + this.configurationUpdate = configurationUpdate; + } + } From d799358a9ac39fb430bbc4c696b3416450dddd5a Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Mon, 8 Apr 2024 21:01:10 -0400 Subject: [PATCH 29/60] Add a frame definition to the vitamin --- .../sdk/addons/kinematics/VitaminFrame.java | 29 ++++++++++++ .../addons/kinematics/VitaminLocation.java | 45 ++++++++++++++++++- .../kinematics/xml/NASASuspensionTest.xml | 32 +++++++++++++ 3 files changed, 105 insertions(+), 1 deletion(-) create mode 100644 src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminFrame.java diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminFrame.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminFrame.java new file mode 100644 index 00000000..3794aa0c --- /dev/null +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminFrame.java @@ -0,0 +1,29 @@ +package com.neuronrobotics.sdk.addons.kinematics; + +public enum VitaminFrame { + // the MobilBase root, or the tip of the link + DefaultFrame("default"), + // the place on the link where the previous one ends, where the shaft for the motor that turns it should be + LinkOrigin("origin"), + // The tip of the previous link. the place where the motor that turns a link would be mounted. if the first link this would be the limbs root + LastLinkTip("lastlink"); + + private String text; + + VitaminFrame(String text) { + this.text = text; + } + + public String getText() { + return this.text; + } + + public static VitaminFrame fromString(String text) { + for (VitaminFrame b : VitaminFrame.values()) { + if (b.text.equalsIgnoreCase(text)) { + return b; + } + } + return null; + } +} diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java index 2bd38293..1d44257b 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java @@ -18,6 +18,8 @@ public class VitaminLocation implements ITransformNRChangeListener { private String size; private TransformNR location=null; + private VitaminFrame frame=VitaminFrame.DefaultFrame; + public VitaminLocation(String name, String type, String size, TransformNR location) { this.setName(name); this.setType(type); @@ -44,7 +46,17 @@ public VitaminLocation(Element vitamins) { if(tf==null) tf=new TransformNR(); setLocation(tf); - + try { + setFrame(VitaminFrame.fromString( XmlFactory.getTagValue("frame", vitamins))); + }catch(NullPointerException ex) { + //use default + } + if(name.contentEquals("electroMechanical")) { + setFrame(VitaminFrame.LastLinkTip); + } + if(name.contentEquals("shaft")) { + setFrame(VitaminFrame.LinkOrigin); + } } public void addChangeListener(Runnable r) { @@ -75,6 +87,7 @@ public String getXML() { "\t\t\t"+type+"\n"+ "\t\t\t"+size+"\n"+ "\t\t\t"+location.getXml()+"\t\t\t\n"+ + "\t\t\t"+getFrame().getText()+"\n"+ "\t\t\n" ; } @@ -187,4 +200,34 @@ public void event(TransformNR changed) { fireChangeEvent(); } + /** + * + // the MobilBase root, or the tip of the link + DefaultFrame("default"), + // the place on the link where the previous one ends, where the shaft for the motor that turns it should be + LinkOrigin("origin"), + // The tip of the previous link. the place where the motor that turns a link would be mounted. if the first link this would be the limbs root + LastLinkTip("lastlink"); + * @return the frame + */ + public VitaminFrame getFrame() { + return frame; + } + + /** + // the MobilBase root, or the tip of the link + DefaultFrame("default"), + // the place on the link where the previous one ends, where the shaft for the motor that turns it should be + LinkOrigin("origin"), + // The tip of the previous link. the place where the motor that turns a link would be mounted. if the first link this would be the limbs root + LastLinkTip("lastlink"); + * @param frame the frame to set + */ + public void setFrame(VitaminFrame frame) { + + this.frame = frame; + fireChangeEvent(); + + } + } diff --git a/src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/NASASuspensionTest.xml b/src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/NASASuspensionTest.xml index 8f2b3038..097ad488 100644 --- a/src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/NASASuspensionTest.xml +++ b/src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/NASASuspensionTest.xml @@ -54,6 +54,7 @@ -0.0 -0.0 + lastlink @@ -69,6 +70,7 @@ -0.0 -0.0 + origin @@ -134,6 +136,7 @@ -0.0 -0.0 + lastlink @@ -149,6 +152,7 @@ -0.0 -0.0 + origin @@ -214,6 +218,7 @@ -0.0 -0.0 + lastlink @@ -229,6 +234,7 @@ -0.0 -0.0 + origin @@ -294,6 +300,7 @@ -0.0 -0.0 + lastlink @@ -309,6 +316,7 @@ -0.0 -0.0 + origin @@ -411,6 +419,7 @@ -0.0 -0.0 + lastlink @@ -426,6 +435,7 @@ -0.0 -0.0 + origin @@ -491,6 +501,7 @@ -0.0 -0.0 + lastlink @@ -506,6 +517,7 @@ -0.0 -0.0 + origin @@ -608,6 +620,7 @@ -0.0 -0.0 + lastlink @@ -623,6 +636,7 @@ -0.0 -0.0 + origin @@ -708,6 +722,7 @@ -0.0 -0.0 + lastlink @@ -723,6 +738,7 @@ -0.0 -0.0 + origin @@ -867,6 +883,7 @@ -0.0 -0.0 + lastlink @@ -882,6 +899,7 @@ -0.0 -0.0 + origin @@ -947,6 +965,7 @@ -0.0 -0.0 + lastlink @@ -962,6 +981,7 @@ -0.0 -0.0 + origin @@ -1064,6 +1084,7 @@ -0.0 -0.0 + lastlink @@ -1079,6 +1100,7 @@ -0.0 -0.0 + origin @@ -1164,6 +1186,7 @@ -0.0 -0.0 + lastlink @@ -1179,6 +1202,7 @@ -0.0 -0.0 + origin @@ -1323,6 +1347,7 @@ -0.0 -0.0 + lastlink @@ -1338,6 +1363,7 @@ -0.0 -0.0 + origin @@ -1403,6 +1429,7 @@ -0.0 -0.0 + lastlink @@ -1418,6 +1445,7 @@ -0.0 -0.0 + origin @@ -1520,6 +1548,7 @@ -0.0 -0.0 + lastlink @@ -1535,6 +1564,7 @@ -0.0 -0.0 + origin @@ -1600,6 +1630,7 @@ -0.0 -0.0 + lastlink @@ -1615,6 +1646,7 @@ -0.0 -0.0 + origin From cb55defa4bda7c380d36f13c5b18adb2f42f281d Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Mon, 8 Apr 2024 21:21:03 -0400 Subject: [PATCH 30/60] default methods for getting vitamins of a given frame --- .../sdk/addons/kinematics/IVitaminHolder.java | 18 ++++++++++++++++++ .../sdk/addons/kinematics/VitaminFrame.java | 2 +- .../sdk/addons/kinematics/VitaminLocation.java | 2 +- 3 files changed, 20 insertions(+), 2 deletions(-) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/IVitaminHolder.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/IVitaminHolder.java index 3ecfde5c..79cb9d2c 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/IVitaminHolder.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/IVitaminHolder.java @@ -6,4 +6,22 @@ public interface IVitaminHolder { ArrayList getVitamins() ; void addVitamin(VitaminLocation location); void removeVitamin(VitaminLocation loc); + default ArrayList getVitamins(VitaminFrame frame){ + ArrayList copy = new ArrayList<>(); + for(VitaminLocation v:getVitamins()) { + if(v.getFrame()==frame) + copy.add(v); + } + + return copy; + } + default ArrayList getOriginVitamins(){ + return getVitamins(VitaminFrame.LinkOrigin); + } + default ArrayList getDefaultVitamins(){ + return getVitamins(VitaminFrame.DefaultFrame); + } + default ArrayList getPreviousLinkVitamins(){ + return getVitamins(VitaminFrame.previousLinkTip); + } } diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminFrame.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminFrame.java index 3794aa0c..374ce31b 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminFrame.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminFrame.java @@ -6,7 +6,7 @@ public enum VitaminFrame { // the place on the link where the previous one ends, where the shaft for the motor that turns it should be LinkOrigin("origin"), // The tip of the previous link. the place where the motor that turns a link would be mounted. if the first link this would be the limbs root - LastLinkTip("lastlink"); + previousLinkTip("lastlink"); private String text; diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java index 1d44257b..b0816567 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java @@ -52,7 +52,7 @@ public VitaminLocation(Element vitamins) { //use default } if(name.contentEquals("electroMechanical")) { - setFrame(VitaminFrame.LastLinkTip); + setFrame(VitaminFrame.previousLinkTip); } if(name.contentEquals("shaft")) { setFrame(VitaminFrame.LinkOrigin); From f3dc7de3ef8a8fbca1fcd4c58380cd641369e1a2 Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Wed, 10 Apr 2024 06:42:38 -0400 Subject: [PATCH 31/60] fire the event from each vitamin added --- .../neuronrobotics/sdk/addons/kinematics/MobileBase.java | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java index 6cd950ce..f03833de 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java @@ -571,6 +571,11 @@ private void getVitamins(Element doc) { try { vitamins = VitaminLocation.getVitamins(doc); + for(VitaminLocation vl:vitamins) { + vl.addChangeListener(()->{ + fireConfigurationUpdate(); + }); + } return; } catch (Exception e) { e.printStackTrace(); @@ -603,6 +608,9 @@ public void addVitamin(VitaminLocation location) { if(vitamins.contains(location)) return; vitamins.add(location); + location.addChangeListener(()->{ + fireConfigurationUpdate(); + }); fireConfigurationUpdate(); } public void removeVitamin(VitaminLocation loc) { From 560aad308aa8f12c53cfc5ef6cb71691d1885335 Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Sun, 14 Apr 2024 10:49:06 -0400 Subject: [PATCH 32/60] only force the default frame on the motor and shaft if it is not defined --- .../sdk/addons/kinematics/VitaminLocation.java | 13 ++++++------- 1 file changed, 6 insertions(+), 7 deletions(-) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java index b0816567..aae66ae7 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java @@ -49,13 +49,12 @@ public VitaminLocation(Element vitamins) { try { setFrame(VitaminFrame.fromString( XmlFactory.getTagValue("frame", vitamins))); }catch(NullPointerException ex) { - //use default - } - if(name.contentEquals("electroMechanical")) { - setFrame(VitaminFrame.previousLinkTip); - } - if(name.contentEquals("shaft")) { - setFrame(VitaminFrame.LinkOrigin); + if(name.contentEquals("electroMechanical")) { + setFrame(VitaminFrame.previousLinkTip); + } + if(name.contentEquals("shaft")) { + setFrame(VitaminFrame.LinkOrigin); + } } } From f5117e14f19e03fdf4c3ef6e661e285c2cc336bb Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Thu, 18 Apr 2024 13:46:41 -0400 Subject: [PATCH 33/60] Remove the listeners from Gson load and unload and make a unit test for gson parsing --- build.gradle | 2 ++ .../addons/kinematics/VitaminLocation.java | 9 +++++- .../utilities/GsonVitaminLoad.java | 31 +++++++++++++++++++ 3 files changed, 41 insertions(+), 1 deletion(-) create mode 100644 test/java/src/junit/test/neuronrobotics/utilities/GsonVitaminLoad.java diff --git a/build.gradle b/build.gradle index 579d4581..9d609d8f 100644 --- a/build.gradle +++ b/build.gradle @@ -46,6 +46,8 @@ dependencies { //TODO change as many of these as possible to Maven repositories compile fileTree (dir: 'libs', includes: ['*.jar']) testCompile 'junit:junit:4.12' + compile 'com.google.code.gson:gson:2.5' + compile 'gov.nist.math:jama:1.0.2' compile 'com.miglayout:miglayout-swing:4.1' compile 'org.igniterealtime.smack:smack:3.2.1' diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java index aae66ae7..f4b4a64a 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java @@ -6,11 +6,13 @@ import org.w3c.dom.Node; import org.w3c.dom.NodeList; +import com.google.gson.annotations.Expose; import com.neuronrobotics.sdk.addons.kinematics.math.ITransformNRChangeListener; import com.neuronrobotics.sdk.addons.kinematics.math.TransformNR; import com.neuronrobotics.sdk.addons.kinematics.xml.XmlFactory; public class VitaminLocation implements ITransformNRChangeListener { + @Expose (serialize = false, deserialize = false) ArrayList listeners=new ArrayList<>(); private String name; @@ -19,7 +21,12 @@ public class VitaminLocation implements ITransformNRChangeListener { private TransformNR location=null; private VitaminFrame frame=VitaminFrame.DefaultFrame; - + public VitaminLocation() { + this.setName("NO NAME"); + this.setType("NO TYPE"); + this.setSize("NO SIZE"); + this.setLocation(new TransformNR()); + } public VitaminLocation(String name, String type, String size, TransformNR location) { this.setName(name); this.setType(type); diff --git a/test/java/src/junit/test/neuronrobotics/utilities/GsonVitaminLoad.java b/test/java/src/junit/test/neuronrobotics/utilities/GsonVitaminLoad.java new file mode 100644 index 00000000..2e8c14cc --- /dev/null +++ b/test/java/src/junit/test/neuronrobotics/utilities/GsonVitaminLoad.java @@ -0,0 +1,31 @@ +package junit.test.neuronrobotics.utilities; + +import static org.junit.Assert.*; + +import java.lang.reflect.Type; +import java.util.ArrayList; +import java.util.HashMap; + +import org.junit.Test; + +import com.google.gson.Gson; +import com.google.gson.GsonBuilder; +import com.google.gson.reflect.TypeToken; +import com.neuronrobotics.sdk.addons.kinematics.VitaminLocation; + +public class GsonVitaminLoad { + + @Test + public void test() { + Type type = new TypeToken() {}.getType(); + Gson gson = new GsonBuilder() + .excludeFieldsWithoutExposeAnnotation() + .disableHtmlEscaping() + .setPrettyPrinting() + .create(); + VitaminLocation src = new VitaminLocation(); + String content = gson.toJson(src); + System.out.println(content); + } + +} From 2ca90c3ef082bc0cdda37ed98f68251ff94a4836 Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Fri, 19 Apr 2024 09:33:09 -0400 Subject: [PATCH 34/60] do not have a null constructor --- .../sdk/addons/kinematics/VitaminLocation.java | 12 ++++++------ .../neuronrobotics/utilities/GsonVitaminLoad.java | 3 ++- 2 files changed, 8 insertions(+), 7 deletions(-) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java index f4b4a64a..821b054b 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java @@ -21,12 +21,12 @@ public class VitaminLocation implements ITransformNRChangeListener { private TransformNR location=null; private VitaminFrame frame=VitaminFrame.DefaultFrame; - public VitaminLocation() { - this.setName("NO NAME"); - this.setType("NO TYPE"); - this.setSize("NO SIZE"); - this.setLocation(new TransformNR()); - } +// public VitaminLocation() { +// this.setName("NO NAME"); +// this.setType("NO TYPE"); +// this.setSize("NO SIZE"); +// this.setLocation(new TransformNR()); +// } public VitaminLocation(String name, String type, String size, TransformNR location) { this.setName(name); this.setType(type); diff --git a/test/java/src/junit/test/neuronrobotics/utilities/GsonVitaminLoad.java b/test/java/src/junit/test/neuronrobotics/utilities/GsonVitaminLoad.java index 2e8c14cc..f7a90e24 100644 --- a/test/java/src/junit/test/neuronrobotics/utilities/GsonVitaminLoad.java +++ b/test/java/src/junit/test/neuronrobotics/utilities/GsonVitaminLoad.java @@ -12,6 +12,7 @@ import com.google.gson.GsonBuilder; import com.google.gson.reflect.TypeToken; import com.neuronrobotics.sdk.addons.kinematics.VitaminLocation; +import com.neuronrobotics.sdk.addons.kinematics.math.TransformNR; public class GsonVitaminLoad { @@ -23,7 +24,7 @@ public void test() { .disableHtmlEscaping() .setPrettyPrinting() .create(); - VitaminLocation src = new VitaminLocation(); + VitaminLocation src = new VitaminLocation("Tester", "hobbyServo","mg92b",new TransformNR()); String content = gson.toJson(src); System.out.println(content); } From e4eeee2edae9016b17679829135f7be02baf59ff Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Fri, 19 Apr 2024 09:53:06 -0400 Subject: [PATCH 35/60] Make sure add vitamin rejects duplicate names --- .../sdk/addons/kinematics/AbstractLink.java | 2 +- .../sdk/addons/kinematics/IVitaminHolder.java | 11 +++++++++-- .../sdk/addons/kinematics/LinkConfiguration.java | 2 +- .../sdk/addons/kinematics/MobileBase.java | 2 +- 4 files changed, 12 insertions(+), 5 deletions(-) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractLink.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractLink.java index 36d36c73..7e8c3b29 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractLink.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractLink.java @@ -56,7 +56,7 @@ public VitaminLocation getElectroMechanicalVitamin() { public ArrayList getVitamins() { return conf.getVitamins(); } - public void addVitamin(VitaminLocation location) { + public void addVitaminInternal(VitaminLocation location) { conf.addVitamin(location); } public void removeVitamin(VitaminLocation loc) { diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/IVitaminHolder.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/IVitaminHolder.java index 79cb9d2c..483c9a52 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/IVitaminHolder.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/IVitaminHolder.java @@ -4,7 +4,15 @@ public interface IVitaminHolder { ArrayList getVitamins() ; - void addVitamin(VitaminLocation location); + default void addVitamin(VitaminLocation location) { + for(VitaminLocation v:getVitamins()) { + if(v.getName().contentEquals(location.getName())) { + new RuntimeException("Vitamin Name "+v.getName()+"already exists"); + } + } + addVitaminInternal( location); + } + void addVitaminInternal(VitaminLocation location); void removeVitamin(VitaminLocation loc); default ArrayList getVitamins(VitaminFrame frame){ ArrayList copy = new ArrayList<>(); @@ -12,7 +20,6 @@ default ArrayList getVitamins(VitaminFrame frame){ if(v.getFrame()==frame) copy.add(v); } - return copy; } default ArrayList getOriginVitamins(){ diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/LinkConfiguration.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/LinkConfiguration.java index 0ee853db..c06d386c 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/LinkConfiguration.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/LinkConfiguration.java @@ -308,7 +308,7 @@ public void setVitamin(VitaminLocation location) { * @param type the vitamin type, this maps the the json filename * @param id the part ID, theis maps to the key in the json for the vitamin */ - public void addVitamin(VitaminLocation location) { + public void addVitaminInternal(VitaminLocation location) { if(vitamins.contains(location)) return; vitamins.add(location); diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java index f03833de..cd7977b7 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java @@ -604,7 +604,7 @@ public void setVitamin(VitaminLocation location) { * @param type the vitamin type, this maps the the json filename * @param id the part ID, theis maps to the key in the json for the vitamin */ - public void addVitamin(VitaminLocation location) { + public void addVitaminInternal(VitaminLocation location) { if(vitamins.contains(location)) return; vitamins.add(location); From 8667f9814bf86266018c9b3136b9fa36d44328cc Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Fri, 19 Apr 2024 10:00:57 -0400 Subject: [PATCH 36/60] Adding a tostring for all devices --- .../sdk/addons/kinematics/AbstractKinematicsNR.java | 4 ++++ .../sdk/addons/kinematics/AbstractLink.java | 4 ++++ .../sdk/addons/kinematics/VitaminLocation.java | 9 ++++++++- 3 files changed, 16 insertions(+), 1 deletion(-) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractKinematicsNR.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractKinematicsNR.java index ed6bfb2c..7314a699 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractKinematicsNR.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractKinematicsNR.java @@ -1731,4 +1731,8 @@ public void setTimeProvider(ITimeProvider t) { l.setTimeProvider(getTimeProvider()); } } + @Override + public String toString() { + return "Bowler Device "+getScriptingName(); + } } diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractLink.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractLink.java index 7e8c3b29..95fdf2c1 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractLink.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractLink.java @@ -720,4 +720,8 @@ public void setTimeProvider(ITimeProvider t) { super.setTimeProvider(t); imu.setTimeProvider(getTimeProvider()); } + @Override + public String toString() { + return "Bowler Link "+getLinkConfiguration().getDeviceScriptingName()+" "+getLinkConfiguration().getLinkIndex(); + } } diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java index 821b054b..c19aa78f 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java @@ -33,7 +33,14 @@ public VitaminLocation(String name, String type, String size, TransformNR locati this.setSize(size); this.setLocation(location); } - + public VitaminLocation(String name, String type, String size, TransformNR location,IVitaminHolder h) { + this(name,type,size,location); + try { + h.addVitamin(this); + }catch(Throwable t){ + System.out.println("Vitamin "+name+" exists in "+h); + } + } public VitaminLocation(Element vitamins) { setName(XmlFactory.getTagValue("name", vitamins)); setType(XmlFactory.getTagValue("type", vitamins)); From b4b4cd008dd4fa92c02252fd4b13f782346bbac4 Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Wed, 24 Apr 2024 12:33:15 -0400 Subject: [PATCH 37/60] updating the defaults for servos and shafts --- .../sdk/addons/kinematics/LinkConfiguration.java | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/LinkConfiguration.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/LinkConfiguration.java index c06d386c..35e3e239 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/LinkConfiguration.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/LinkConfiguration.java @@ -963,6 +963,7 @@ public VitaminLocation getShaftVitamin() { if(loc.getName().contentEquals("shaft")) return loc; VitaminLocation e = new VitaminLocation("shaft", "hobbyServoHorn", "standardMicro1", new TransformNR()); + e.setFrame(VitaminFrame.LinkOrigin); vitamins.add(e); return e; } @@ -971,7 +972,8 @@ public VitaminLocation getElectroMechanicalVitamin() { for(VitaminLocation loc:vitamins) if(loc.getName().contentEquals("electroMechanical")) return loc; - VitaminLocation e = new VitaminLocation("electroMechanical", "hobbyServoHorn", "mg92b", new TransformNR()); + VitaminLocation e = new VitaminLocation("electroMechanical", "hobbyServo", "mg92b", new TransformNR()); + e.setFrame(VitaminFrame.previousLinkTip); vitamins.add(e); return e; } From bbb7af0766662dc89897db8e260a87ec92c65a3c Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Wed, 24 Apr 2024 12:43:16 -0400 Subject: [PATCH 38/60] force loading of default vitamins --- .../sdk/addons/kinematics/DHParameterKinematics.java | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/DHParameterKinematics.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/DHParameterKinematics.java index dc39b327..1158b43b 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/DHParameterKinematics.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/DHParameterKinematics.java @@ -87,6 +87,10 @@ public void onConnect(BowlerAbstractDevice source) { } }); + for(int i=0;i Date: Wed, 24 Apr 2024 13:30:54 -0400 Subject: [PATCH 39/60] change the way vitamin defaults are loaded --- .../kinematics/DHParameterKinematics.java | 13 ++- .../addons/kinematics/LinkConfiguration.java | 105 ++++++++++-------- 2 files changed, 66 insertions(+), 52 deletions(-) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/DHParameterKinematics.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/DHParameterKinematics.java index 1158b43b..15d00d7d 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/DHParameterKinematics.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/DHParameterKinematics.java @@ -87,10 +87,7 @@ public void onConnect(BowlerAbstractDevice source) { } }); - for(int i=0;i listeners = null; - private boolean pauseEvents=false; + private boolean pauseEvents = false; /** The name. */ private String name = "newLink";// = getTagValue("name",eElement); @@ -100,7 +100,7 @@ public class LinkConfiguration implements ITransformNRChangeListener,IVitaminHol private HashMap vitaminVariant = new HashMap(); private boolean passive = false; private boolean newAbs = false; - private Runnable changeListener = ()->{ + private Runnable changeListener = () -> { fireChangeEvent(); }; @@ -278,7 +278,7 @@ public LinkConfiguration(Object[] args) { protected void getVitamins(Element doc) { try { - vitamins=VitaminLocation.getVitamins(doc); + vitamins = VitaminLocation.getVitamins(doc); return; } catch (Exception e) { e.printStackTrace(); @@ -286,7 +286,6 @@ protected void getVitamins(Element doc) { return; } - /** * Add a vitamin to this link * @@ -298,8 +297,9 @@ protected void getVitamins(Element doc) { @Deprecated public void setVitamin(VitaminLocation location) { addVitamin(location); - + } + /** * Add a vitamin to this link * @@ -309,14 +309,15 @@ public void setVitamin(VitaminLocation location) { * @param id the part ID, theis maps to the key in the json for the vitamin */ public void addVitaminInternal(VitaminLocation location) { - if(vitamins.contains(location)) + if (vitamins.contains(location)) return; vitamins.add(location); location.addChangeListener(changeListener); fireChangeEvent(); } + public void removeVitamin(VitaminLocation loc) { - if(vitamins.contains(loc)) + if (vitamins.contains(loc)) vitamins.remove(loc); loc.removeChangeListener(changeListener); fireChangeEvent(); @@ -353,13 +354,13 @@ public LinkConfiguration() { public LinkConfiguration(LinkConfiguration from) { setDeviceScriptingName(from.getDeviceScriptingName()); - for(int i=0;i\n"; } - String vitamnsString = VitaminLocation.getAllXML(vitamins); - return "\t" + getName() + "\n" + "\t" + - DevStr + "\t" + getTypeString() + "\n"+ - "\t" + getHardwareIndex() + "\n" + - "\t" + getScale() + "\n" - + "\t" + getUpperLimit() + "\n" + - "\t" + getLowerLimit()+ "\n" + - "\t" + getUpperVelocity() + "\n"+ - "\t" + getLowerVelocity() + "\n" + - "\t" + return "\t" + getName() + "\n" + "\t" + DevStr + "\t" + getTypeString() + "\n" + + "\t" + getHardwareIndex() + "\n" + "\t" + getScale() + "\n" + + "\t" + getUpperLimit() + "\n" + "\t" + getLowerLimit() + + "\n" + "\t" + getUpperVelocity() + "\n" + + "\t" + getLowerVelocity() + "\n" + "\t" + getStaticOffset() + "\n" + "\t" + getDeviceTheoreticalMax() + "\n" + "\t" + getDeviceTheoreticalMin() + "\n" + "\t" + isLatch() + "\n" + "\t" + getIndexLatch() + "\n" + "\t" + isStopOnLatch() + "\n" - + "\t" + getHomingTicksPerSecond() + "\n" + vitamnsString+ "\t" + isPassive() + "\n" + "\t" + getMassKg() - + "\n" + "\t" + getCenterOfMassFromCentroid().getXml() - + "\n" + "\t" + getimuFromCentroid().getXml() - + "\n" + slaves; + + "\t" + getHomingTicksPerSecond() + "\n" + vitamnsString + "\t" + + isPassive() + "\n" + "\t" + getMassKg() + "\n" + "\t" + + getCenterOfMassFromCentroid().getXml() + "\n" + "\t" + + getimuFromCentroid().getXml() + "\n" + slaves; } /** @@ -947,35 +943,51 @@ public void setimuFromCentroid(TransformNR imu) { this.imuFromCentroid.addChangeListener(this); fireChangeEvent(); } + // private String electroMechanicalType = "hobbyServo"; // private String electroMechanicalSize = "standardMicro"; // private String shaftType = "hobbyServoHorn"; // private String shaftSize = "standardMicro1"; - public ArrayListgetNonActuatorVitamins() { + public ArrayList getNonActuatorVitamins() { ArrayList back = new ArrayList<>(); back.addAll(vitamins); back.remove(getShaftVitamin()); back.remove(getElectroMechanicalVitamin()); return back; } - public VitaminLocation getShaftVitamin() { - for(VitaminLocation loc:vitamins) - if(loc.getName().contentEquals("shaft")) + + public VitaminLocation getShaftVitamin(boolean makeNew) { + for (VitaminLocation loc : vitamins) + if (loc.getName().contentEquals("shaft")) return loc; - VitaminLocation e = new VitaminLocation("shaft", "hobbyServoHorn", "standardMicro1", new TransformNR()); - e.setFrame(VitaminFrame.LinkOrigin); - vitamins.add(e); - return e; + if (makeNew) { + VitaminLocation e = new VitaminLocation("shaft", "hobbyServoHorn", "standardMicro1", new TransformNR()); + e.setFrame(VitaminFrame.LinkOrigin); + vitamins.add(e); + return e; + } + return null; } - public VitaminLocation getElectroMechanicalVitamin() { - for(VitaminLocation loc:vitamins) - if(loc.getName().contentEquals("electroMechanical")) + public VitaminLocation getElectroMechanicalVitamin(boolean makeNew) { + for (VitaminLocation loc : vitamins) + if (loc.getName().contentEquals("electroMechanical")) return loc; - VitaminLocation e = new VitaminLocation("electroMechanical", "hobbyServo", "mg92b", new TransformNR()); - e.setFrame(VitaminFrame.previousLinkTip); - vitamins.add(e); - return e; + if (makeNew) { + VitaminLocation e = new VitaminLocation("electroMechanical", "hobbyServo", "mg92b", new TransformNR()); + e.setFrame(VitaminFrame.previousLinkTip); + vitamins.add(e); + return e; + } + return null; + } + + public VitaminLocation getShaftVitamin() { + return getShaftVitamin(false); + } + + public VitaminLocation getElectroMechanicalVitamin() { + return getElectroMechanicalVitamin(false); } public String getElectroMechanicalType() { @@ -1001,7 +1013,8 @@ public String getShaftType() { } public void setShaftType(String shaftType) { - getShaftVitamin().setType(shaftType);; + getShaftVitamin().setType(shaftType); + ; fireChangeEvent(); } @@ -1023,16 +1036,16 @@ public void setPassive(boolean passive) { fireChangeEvent(); } - public ArrayListgetVitamins() { + public ArrayList getVitamins() { return vitamins; } public void setVitamins(ArrayList v) { - if(vitamins!=null) - for(VitaminLocation l:vitamins) + if (vitamins != null) + for (VitaminLocation l : vitamins) l.removeChangeListener(changeListener); this.vitamins = v; - for(VitaminLocation l:vitamins) + for (VitaminLocation l : vitamins) l.addChangeListener(changeListener); fireChangeEvent(); } @@ -1132,7 +1145,7 @@ public ArrayList getListeners() { } void fireChangeEvent() { - if(pauseEvents) + if (pauseEvents) return; if (listeners != null) { for (int i = 0; i < listeners.size(); i++) { From 1d8f5e417fc6adad3f09e8a6941c4d3d5bebeb67 Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Thu, 2 May 2024 12:10:42 -0400 Subject: [PATCH 40/60] add comments --- .../com/neuronrobotics/sdk/addons/kinematics/MobileBase.java | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java index cd7977b7..eee4597b 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java @@ -902,7 +902,8 @@ public void setGitWalkingEngine(String[] walkingEngine) { /** * Gets the self source. - * + * index 0 is GIT url + * index 1 is filename * @return the self source */ public String[] getGitSelfSource() { From f02816a3ffb9cf8a8c3669c29421cdfcf44fb9ca Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Sun, 5 May 2024 13:44:48 -0400 Subject: [PATCH 41/60] set time based on the best time --- .../sdk/addons/kinematics/AbstractKinematicsNR.java | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractKinematicsNR.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractKinematicsNR.java index 7314a699..8e88e252 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractKinematicsNR.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractKinematicsNR.java @@ -729,7 +729,9 @@ private double[] _setDesiredJointSpaceVector(double[] jointSpaceVect, double se throw new IndexOutOfBoundsException("Vector must be " + getNumberOfLinks() + " links, actual number of links = " + jointSpaceVect.length); } - + double best = getBestTime(jointSpaceVect); + if(seconds Date: Mon, 6 May 2024 12:54:51 -0400 Subject: [PATCH 42/60] frame can not be null --- .../sdk/addons/kinematics/VitaminLocation.java | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java index c19aa78f..30053908 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java @@ -224,6 +224,8 @@ public void event(TransformNR changed) { * @return the frame */ public VitaminFrame getFrame() { + if(frame==null) + return VitaminFrame.DefaultFrame; return frame; } @@ -237,7 +239,8 @@ public VitaminFrame getFrame() { * @param frame the frame to set */ public void setFrame(VitaminFrame frame) { - + if(frame==null) + throw new NullPointerException("Frame can not be null"); this.frame = frame; fireChangeEvent(); From f34bf8c832bd7c0dac25772b5c7287851e187d0c Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Tue, 9 Jul 2024 15:42:53 -0400 Subject: [PATCH 43/60] less dramatic euler fix --- .../neuronrobotics/sdk/addons/kinematics/math/RotationNR.java | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/RotationNR.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/RotationNR.java index 8de27039..8b698fc1 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/RotationNR.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/RotationNR.java @@ -372,9 +372,9 @@ private double getAngle(int index){ return getStorage().getAngles(getOrder(), getConvention())[index]; } catch (CardanEulerSingularityException e) { try { - return eulerFix( Math.toRadians(5), index); + return eulerFix( Math.toRadians(0.001), index); } catch (CardanEulerSingularityException ex) { - return eulerFix( Math.toRadians(-5), index); + return eulerFix( Math.toRadians(-0.001), index); } } From bf8208affa835e1b4a8c36693a3d5760f61cbab8 Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Wed, 10 Jul 2024 10:48:48 -0400 Subject: [PATCH 44/60] Adding a field to the XML, and to the test for that field --- .../addons/kinematics/VitaminLocation.java | 16 +++++++++- .../kinematics/xml/NASASuspensionTest.xml | 32 +++++++++++++++++++ 2 files changed, 47 insertions(+), 1 deletion(-) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java index 30053908..eed6d242 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java @@ -19,6 +19,7 @@ public class VitaminLocation implements ITransformNRChangeListener { private String type; private String size; private TransformNR location=null; + private boolean isScript =false; private VitaminFrame frame=VitaminFrame.DefaultFrame; // public VitaminLocation() { @@ -45,7 +46,12 @@ public VitaminLocation(Element vitamins) { setName(XmlFactory.getTagValue("name", vitamins)); setType(XmlFactory.getTagValue("type", vitamins)); setSize(XmlFactory.getTagValue("id", vitamins)); - + String scriptyness=XmlFactory.getTagValue("id", vitamins); + if(scriptyness==null) { + isScript=false; + }else{ + setScript(Boolean.parseBoolean(scriptyness)); + } NodeList nodListofLinks = vitamins.getChildNodes(); TransformNR tf=null; for (int i = 0; i < nodListofLinks.getLength(); i++) { @@ -101,6 +107,7 @@ public String getXML() { "\t\t\t"+size+"\n"+ "\t\t\t"+location.getXml()+"\t\t\t\n"+ "\t\t\t"+getFrame().getText()+"\n"+ + "\t\t\t\n"+ "\t\t\n" ; } @@ -245,5 +252,12 @@ public void setFrame(VitaminFrame frame) { fireChangeEvent(); } + public boolean isScript() { + return isScript; + } + public void setScript(boolean isScript) { + this.isScript = isScript; + fireChangeEvent(); + } } diff --git a/src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/NASASuspensionTest.xml b/src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/NASASuspensionTest.xml index 097ad488..4224c98e 100644 --- a/src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/NASASuspensionTest.xml +++ b/src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/NASASuspensionTest.xml @@ -55,6 +55,7 @@ -0.0 lastlink + @@ -71,6 +72,7 @@ -0.0 origin + @@ -137,6 +139,7 @@ -0.0 lastlink + @@ -153,6 +156,7 @@ -0.0 origin + @@ -219,6 +223,7 @@ -0.0 lastlink + @@ -235,6 +240,7 @@ -0.0 origin + @@ -301,6 +307,7 @@ -0.0 lastlink + @@ -317,6 +324,7 @@ -0.0 origin + @@ -420,6 +428,7 @@ -0.0 lastlink + @@ -436,6 +445,7 @@ -0.0 origin + @@ -502,6 +512,7 @@ -0.0 lastlink + @@ -518,6 +529,7 @@ -0.0 origin + @@ -621,6 +633,7 @@ -0.0 lastlink + @@ -637,6 +650,7 @@ -0.0 origin + @@ -723,6 +737,7 @@ -0.0 lastlink + @@ -739,6 +754,7 @@ -0.0 origin + @@ -884,6 +900,7 @@ -0.0 lastlink + @@ -900,6 +917,7 @@ -0.0 origin + @@ -966,6 +984,7 @@ -0.0 lastlink + @@ -982,6 +1001,7 @@ -0.0 origin + @@ -1085,6 +1105,7 @@ -0.0 lastlink + @@ -1101,6 +1122,7 @@ -0.0 origin + @@ -1187,6 +1209,7 @@ -0.0 lastlink + @@ -1203,6 +1226,7 @@ -0.0 origin + @@ -1348,6 +1372,7 @@ -0.0 lastlink + @@ -1364,6 +1389,7 @@ -0.0 origin + @@ -1430,6 +1456,7 @@ -0.0 lastlink + @@ -1446,6 +1473,7 @@ -0.0 origin + @@ -1549,6 +1577,7 @@ -0.0 lastlink + @@ -1565,6 +1594,7 @@ -0.0 origin + @@ -1631,6 +1661,7 @@ -0.0 lastlink + @@ -1647,6 +1678,7 @@ -0.0 origin + From c147d6b2d9f808a2e50c1d2cc0518d5a5b938cf5 Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Wed, 10 Jul 2024 13:29:49 -0400 Subject: [PATCH 45/60] ensure all values are set when instantiating a vitamin --- .../sdk/addons/kinematics/LinkConfiguration.java | 4 ++-- .../sdk/addons/kinematics/VitaminLocation.java | 7 ++++--- .../addons/kinematics/xml/NASASuspensionTest.xml | 16 ++++++++++++++++ .../utilities/GsonVitaminLoad.java | 2 +- 4 files changed, 23 insertions(+), 6 deletions(-) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/LinkConfiguration.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/LinkConfiguration.java index b5ccfd63..0ccba290 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/LinkConfiguration.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/LinkConfiguration.java @@ -961,7 +961,7 @@ public VitaminLocation getShaftVitamin(boolean makeNew) { if (loc.getName().contentEquals("shaft")) return loc; if (makeNew) { - VitaminLocation e = new VitaminLocation("shaft", "hobbyServoHorn", "standardMicro1", new TransformNR()); + VitaminLocation e = new VitaminLocation(false,"shaft", "hobbyServoHorn", "standardMicro1", new TransformNR()); e.setFrame(VitaminFrame.LinkOrigin); vitamins.add(e); return e; @@ -974,7 +974,7 @@ public VitaminLocation getElectroMechanicalVitamin(boolean makeNew) { if (loc.getName().contentEquals("electroMechanical")) return loc; if (makeNew) { - VitaminLocation e = new VitaminLocation("electroMechanical", "hobbyServo", "mg92b", new TransformNR()); + VitaminLocation e = new VitaminLocation(false,"electroMechanical", "hobbyServo", "mg92b", new TransformNR()); e.setFrame(VitaminFrame.previousLinkTip); vitamins.add(e); return e; diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java index eed6d242..20385baf 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java @@ -28,14 +28,15 @@ public class VitaminLocation implements ITransformNRChangeListener { // this.setSize("NO SIZE"); // this.setLocation(new TransformNR()); // } - public VitaminLocation(String name, String type, String size, TransformNR location) { + public VitaminLocation(boolean isScript,String name, String type, String size, TransformNR location) { this.setName(name); this.setType(type); this.setSize(size); this.setLocation(location); + setScript(isScript); } - public VitaminLocation(String name, String type, String size, TransformNR location,IVitaminHolder h) { - this(name,type,size,location); + public VitaminLocation(boolean isScript,String name, String type, String size, TransformNR location,IVitaminHolder h) { + this(isScript,name,type,size,location); try { h.addVitamin(this); }catch(Throwable t){ diff --git a/src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/NASASuspensionTest.xml b/src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/NASASuspensionTest.xml index 4224c98e..9107e33b 100644 --- a/src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/NASASuspensionTest.xml +++ b/src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/NASASuspensionTest.xml @@ -1783,6 +1783,22 @@ + + script + https://github.com/madhephaestus/TestRepo.git + myFile.groovy + + 13.0 + -18.0 + 0.0 + 1.0 + -0.0 + -0.0 + -0.0 + + default + + diff --git a/test/java/src/junit/test/neuronrobotics/utilities/GsonVitaminLoad.java b/test/java/src/junit/test/neuronrobotics/utilities/GsonVitaminLoad.java index f7a90e24..2b280f4f 100644 --- a/test/java/src/junit/test/neuronrobotics/utilities/GsonVitaminLoad.java +++ b/test/java/src/junit/test/neuronrobotics/utilities/GsonVitaminLoad.java @@ -24,7 +24,7 @@ public void test() { .disableHtmlEscaping() .setPrettyPrinting() .create(); - VitaminLocation src = new VitaminLocation("Tester", "hobbyServo","mg92b",new TransformNR()); + VitaminLocation src = new VitaminLocation(false,"Tester", "hobbyServo","mg92b",new TransformNR()); String content = gson.toJson(src); System.out.println(content); } From f35e1fa437b56f1a81b82363c91a553ebf1ceae2 Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Wed, 10 Jul 2024 13:34:35 -0400 Subject: [PATCH 46/60] Fix the typo in the access to the script boolean id --- .../neuronrobotics/sdk/addons/kinematics/VitaminLocation.java | 2 +- .../sdk/addons/kinematics/xml/NASASuspensionTest.xml | 1 + 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java index 20385baf..f5db6c91 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java @@ -47,7 +47,7 @@ public VitaminLocation(Element vitamins) { setName(XmlFactory.getTagValue("name", vitamins)); setType(XmlFactory.getTagValue("type", vitamins)); setSize(XmlFactory.getTagValue("id", vitamins)); - String scriptyness=XmlFactory.getTagValue("id", vitamins); + String scriptyness=XmlFactory.getTagValue("script", vitamins); if(scriptyness==null) { isScript=false; }else{ diff --git a/src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/NASASuspensionTest.xml b/src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/NASASuspensionTest.xml index 9107e33b..538678ee 100644 --- a/src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/NASASuspensionTest.xml +++ b/src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/NASASuspensionTest.xml @@ -1799,6 +1799,7 @@ default + From 44bae57aca3358127ea721b7c2704a80c3b323f6 Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Thu, 11 Jul 2024 15:48:56 -0400 Subject: [PATCH 47/60] Allow foe no script tags --- .../sdk/addons/kinematics/VitaminLocation.java | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java index f5db6c91..e4475982 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java @@ -47,7 +47,10 @@ public VitaminLocation(Element vitamins) { setName(XmlFactory.getTagValue("name", vitamins)); setType(XmlFactory.getTagValue("type", vitamins)); setSize(XmlFactory.getTagValue("id", vitamins)); - String scriptyness=XmlFactory.getTagValue("script", vitamins); + String scriptyness=null; + try { + scriptyness=XmlFactory.getTagValue("script", vitamins); + }catch(Exception ex) {}//ignore if(scriptyness==null) { isScript=false; }else{ From 1379b93c00f79095c01d8d26f943f2ed0a9f1cc0 Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Mon, 15 Jul 2024 14:09:48 -0400 Subject: [PATCH 48/60] compatibilit --- build.gradle | 33 +++++++++++++++++++-------------- 1 file changed, 19 insertions(+), 14 deletions(-) diff --git a/build.gradle b/build.gradle index 9d609d8f..f7dad150 100644 --- a/build.gradle +++ b/build.gradle @@ -1,6 +1,9 @@ apply plugin: 'java' apply plugin: 'eclipse' -apply plugin: 'maven' +if (project == rootProject) { + apply plugin: 'maven' +} +apply plugin: 'java-library' apply plugin: 'signing' [compileJava, compileTestJava]*.options*.encoding = 'UTF-8' @@ -31,7 +34,7 @@ manifest { ) } - +if (project == rootProject) jar.archiveName = "nrsdk-"+props."app.version"+"-jar-with-dependencies.jar" //apply from: 'http://gradle-plugins.mihosoft.eu/latest/vlicenseheader.gradle' @@ -44,23 +47,23 @@ repositories { dependencies { //TODO change as many of these as possible to Maven repositories - compile fileTree (dir: 'libs', includes: ['*.jar']) - testCompile 'junit:junit:4.12' - compile 'com.google.code.gson:gson:2.5' + api fileTree (dir: 'libs', includes: ['*.jar']) + testImplementation 'junit:junit:4.12' + implementation 'com.google.code.gson:gson:2.5' - compile 'gov.nist.math:jama:1.0.2' - compile 'com.miglayout:miglayout-swing:4.1' - compile 'org.igniterealtime.smack:smack:3.2.1' + api 'gov.nist.math:jama:1.0.2' + implementation 'com.miglayout:miglayout-swing:4.1' + implementation 'org.igniterealtime.smack:smack:3.2.1' - compile 'org.igniterealtime.smack:smackx:3.2.1' - compile 'org.apache.commons:commons-lang3:3.2.1' - compile 'org.usb4java:usb4java:1.2.0' - compile 'org.usb4java:usb4java-javax:1.2.0' + implementation 'org.igniterealtime.smack:smackx:3.2.1' + implementation 'org.apache.commons:commons-lang3:3.2.1' + api 'org.usb4java:usb4java:1.2.0' + api 'org.usb4java:usb4java-javax:1.2.0' //compile fileTree (dir: '../doychinNRJAVASERISL/nrjavaserial/build/libs', includes: ['*.jar']) - compile "com.neuronrobotics:nrjavaserial:5.1.1" + api "com.neuronrobotics:nrjavaserial:5.1.1" // https://mvnrepository.com/artifact/org.apache.commons/commons-math3 - compile group: 'org.apache.commons', name: 'commons-math3', version: '3.6.1' + api group: 'org.apache.commons', name: 'commons-math3', version: '3.6.1' @@ -75,11 +78,13 @@ archivesBaseName = "java-bowler" version = props."app.version" task javadocJar(type: Jar) { + if (project == rootProject) classifier = 'javadoc' from javadoc } task sourcesJar(type: Jar) { + if (project == rootProject) classifier = 'sources' from sourceSets.main.allSource } From 5862915551adec65bb3a11603e1a87bbe892688a Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Tue, 16 Jul 2024 18:07:37 -0400 Subject: [PATCH 49/60] replace jars with gradle imports --- build.gradle | 4 +++- libs/bluecove-2.1.1.jar | Bin 663800 -> 0 bytes libs/bluecove-gpl-2.1.1.jar | Bin 66195 -> 0 bytes 3 files changed, 3 insertions(+), 1 deletion(-) delete mode 100644 libs/bluecove-2.1.1.jar delete mode 100644 libs/bluecove-gpl-2.1.1.jar diff --git a/build.gradle b/build.gradle index f7dad150..36b4a277 100644 --- a/build.gradle +++ b/build.gradle @@ -64,7 +64,9 @@ dependencies { api "com.neuronrobotics:nrjavaserial:5.1.1" // https://mvnrepository.com/artifact/org.apache.commons/commons-math3 api group: 'org.apache.commons', name: 'commons-math3', version: '3.6.1' - + // https://mvnrepository.com/artifact/net.sf.bluecove/bluecove-gpl + api group: 'net.sf.bluecove', name: 'bluecove-gpl', version: '2.1.0' + api group: 'io.ultreia', name: 'bluecove', version: '2.1.1' } diff --git a/libs/bluecove-2.1.1.jar b/libs/bluecove-2.1.1.jar deleted file mode 100644 index ce9ca6c56013633565f7028e5b791e262c96816a..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 663800 zcma&N1CVU%vaa2>ZQGjNJ=?Zz+s16$wr$(CZQHj0wQrn#{uBG$z4on$sxd0!dA}Ty zZ{`9lNK?K+j8({KnS`?+rzyFkcQEtoWiv*)ezMbv9jf4r1_;N zm5MOf?G<3=HjJw9(Vds)RH8T2gj}=H$gfVDoPMu

IwOC*_&lq4rQI`nyzj9Y9HK%d@^I6%-daAkX%p{@0Q8v+2J@Grza-24Y& zZsTNZ^*^|OUFjdj{r{YSm9w#vt*w*U-zc#Djl#gm(a!E~bU6Q3XT@Zw|947^f1@-t zH2Ir&_{u`mKfw9})#QS&2aWb^~4@!vt3h3x; z^Ed0m{13{|$nbAS_4}{yV~Yfu<`M{7P2W#h6&v&y*6b`OY-(U>=cP%4HiDR(Uo2Y_a$93CDrpL5b#&0%TluCbs)!lg(elxUJ-MZVH9}KMlvQP8WTEkiD z6E;ng9tZCtw-2hFagXcoW$u>EvyQ9ej_Y>K`>pm#*BH-~o97Ns(ue+T&KsTf%lkY* z@DFDUUJmw0KcCOD=C9!;T~2Qw@U4)m9dZ4Z>m10J78l&DA2ulb_8;Q*oR*&(r<~lK zk@>Fu=MAAiW`q^JGJ?rwBWSkm+584%+FSa0O4G6bf1

_&)~7{tJ;ofe1%hS?NS6yuzLR8VyRheMxYcliX; z25W#B7rv%@`H0#>oHP2AJ<%kfuUp+@8KNy+0M`Gq870h2!Wo`6))p(urgkX zmRE;tsaoM(a`U`Nrx~e~zYyh@&EQv)2M)zF?GsCa~+NfwL$!x#P?0=CNOIpfJQ2U;kJnm``^5jc+cQ~4=yReXP5ketoAsRJU}V1ptCQFRnu-M6sbmhRy^b*282c8z_UqX=d!c;a z;_IT@0G~DZ5u}hvX;i2j)oE==q!YjiUc2osON!Le8=u;@*==`GMy)Sn*0K} z>5uSExhaU?iE@pK;0-e%h-$#2^jm)aWhfYQEkO>B>tw|B1G%sAh>FE+`F^{gke^ z@>|ROeb$UII(|dzx3>GkkF|S>X(HPh^~A@@l8F1tcgX#!QUlj>j0Y%T6*oZ|@#wb; z{fTUdU9{`&&S(7EZP5_X^3XbVQXrrkJ9=6hyg? z;S4}X#q^QIBA7mDU#fE26+E3P)mM`5jg=8p=^2op^0@!*CgmIPbXL;$>AQPF7N_Lr zgXXt+%Xfu&vk#LVBjzj=KftJd*%L)$7W$tUY#Bso>Hc$|qJUg?K~%nIgJ9+EJZL4-Z52%RV!q4=zq8nShBBL5k6cQ*Gym8hD2!%rw)-KvmRiuU)zrl5 zaCFFd<4R#51^cls)L953kFX=LnKm%)02&{rxd*DlnX6=$pl`|*l+7tBj)>MVC`Hr{*rvY(yu&<4Nger zQh12Kcy2PGfl>$RFkmR(e&KPjak!d=MCtFVQO}G|%{?#>A(cvBj&{O0LW~DN8Xwfc z8*rNabm4ZQahFHp6Z~rbLbMa*XUX|3q=5Wh^tc>`(!lsQZ;nm5?Dj<^H!n@Eb z;gHP=s@ar#Ubs-604Td~bimD?URcjUnJR8AVGe*_kI%=%v1;&jw7x z=Jfoeif&{y%=_7Q6q8&PC^d9*O4kE^f&%QIskhx0S`wd`l0$mN2*QyQ;#2jmS9UnO zfPJ387wv}P3@5d8CmkiL;ZbRmLkqmK&9_kw08At{!%ssK&qoQAMf^qLvLUd@Pe05z z=};xd#bP5gps|=XqIGWqJ#t$!Js_*eQ+wxa`J}RjcRzJWU-O71_Y(f{hzcrS9e#*X zBW5xOK1!ZaC`UPXD>7uL-pLD4mSuYrV2R@bMhz4Z%FJM1Pz*IKL>S@JA4lnk+8$m1 zTqs|fs26?Fj?tT|yHKL#UHt|yODG1^bXFUNkMoUKY2Yf~l#RDulTndjE7;K^*51gA zP;k|}Xg>MvBS~~yn;Uw1@%7i_6=2-;5Y5wcDFb&w97m7 zsD7d&`=Jx~AZ#J5!=Mx{`Dj|9cGD|!;Xv@fDZJ_V)3W^UmB5mp^ib8p!xpy*(!l%a zpj}#2H!{%PYWyn1Ca7hNxAjb-%NHaGxNxG?``0&mzl|je_04VLxhhTcAE1~8F}~dv zjl#>NV)Cte)5$qT$Sh?pHQnSjtlC?h25+bl4sA=BJLAmuyVnP8GeGW>*BwC0PZW%* zEkVbyT;DBXCl0z?whSW-8a{HTEdnb)qGq=Z2xmKQ3F=f)&*fUl>PG4UC^I65QY3a^PhEeVJQGks zxx5PO@;JTu?@I`gSS_`6hG(%szAZ&a;7lx$;vh%>W^*;IzYqAp6`B+>SP-fgCm5S7>rI$v zcX%8claD-n-|>5fZ%1PV5smB7xos_wPdtF4LL;I z>2+vPQzW`Ba?pkazj+A7#b{ZIM0V5CtpH^rW4uQt}ztXGW>= zUp%TIvq31Xps{1q`?Yk}Yv|^;FR!s<=@eJfIB)+7eY$a*v%!8uXDLAUi%P))|TyB!dCYT;(+LlV1Q&ABLcP6EWDyR7H zT^a~O7sCp$ZZq$9!-YCPz%MoGVTaufELTH*LVzos^bByA4qgEy^d;G%dp|Mc?k53t z(aUn{0NXq;10`8vQWchKB<7$sNmA!YquY*6$3o(wv=MSit@Y3KN8np92nmjxM`+5@b_9A{ znai&1=W)(v^Y_BGU}?T5a_TvR?)}8H(%|0J0i>o=4mNlO{WS~OsZlb-c=Qg`=k!? zI#uC#rzT~u1g;VD!{2m3D;^^bTa1}~-sW7>MzUBjD-Ac8F{G7{ctca05gS6oo}hst zs}gZ$@ioV>FBm{IclHC8o1u zSc7&!tKmf=u)bS}j&K5*QV25IR?U0P0C{URk6L;X{uy(-JunD17Pq?QgdMX}A<;;% z-(zUkbm)NutrTj2uo}LTttEZB0=WI7MMf;A2guXG0YEkG%CWRp$G=<+r+9x^@|^WY zrsKb%lN{90Hpj|8Ej%!uMMg}O^Fka|fs3p6^u=UduxS=nWOBZ!vb&N6>=Rz%$)pNj zcKOz7fNN(E?6i0LIk4=ReSjIP%dNI0D2L4$Huss#{AiCKSB3kof0E}0$?OgIQ)=G> zX(xKS$BEC%DnRC6emX7=wK*cA#t^G!Lq%H#dPNYlLiDp@k$fOTQq;Gu%G#iU3`8=o z`L*zx%A^2EK*w_7W9By8<+222Kyctu8S?U(WfCfE0!%Y~M2$&tufXWB&jwm7R!jpG z5K!<0HQuE)w!L`b@bvEWlcUjtFzxRWaA;kQ6`4bUJn3S1nxU^tWK&4%1P)b=0ycqF zQgl3iDuHt6T5kz0Q9yq@egD~`OUX_4Al{?sfP*b4$c_Gze^Pe&w%3;ERl*FTREwhD z@;X*$?wEk%78Jq*-nUr+59Mv2RSH(af&&G*oBIV1xEl`PafXzMYOzV(HU}6d5*LT0 zKLa<)POJ+nT`ohPv{JbOCoFPg&u)~P(iU!71!!4_Wo<}>_Tf!GJ0?9OvbHJd7IZ{t zel|!KPnh6u1ym>NN!u!7TR^Ci)LPL@bw{FMxTlx#YYGb*BA%8<^!6zUipTUou{3QN z4RTrprxP%~dzUo&URXe$b>FcO0oRDVy7AUe0Wm?Cj9M(Sp0t!@c1Y+|t+kS3G9U=46*kqZyhoBS|F&CiiRo*CCn=(!m-09Mz@KUiYKRE* z;wH;jsZ|Qjm=p-RYIe@C2WSRye8w1J;^@mwijRI#PtdlQD9qT5FGH9WE**&F0jclG zaHHFk3mlnWM!J#WU1UDhvu_RI+#Yp(IcH~Pt0wDHd@n?r<6=GDI8m5LjBvXEk}P%2 ztmVw+W&{cOKietLG#soGW znKD^xNZp}+*Hf(#!&7I7?ki>Ngm>kwGjjypm*PFlIj;w}_(>T7xg(3kPO(>>HMP~4 z09m#HLn`t!Yqfj=GXMUIMd#W0zFw=s(zdpvFzE@)^ypzu^^+?3t5^r2aYu_@;c4?R zu=zj>7BS5+Fd!x8GNUR({p=$+LlJiH58W`%1FaJ!f`er~rQ zRI3w;&i$0>tQE zf{Or@n0~${rv5-yJc3StaA2zz6bAe<0d(1Y^NCv`-a zJ2dFjLo*N;w4$Kb*MT~)3R@gN*ydFN@Elzs;+;c#U9uQvQ(~Kxa34snZbRSSDbojR zUz~V9geP~N(+B#`Q+1ShKLGBZlG6tjvnaqul}(G3QqY+~*1|%Yx2D~pWXeCTVn&+5 zC8{CpyptRvj^E4!rpTzQQLOAfULve!8fnt`3T#k< zJp8!4!wA7+X`_?mM%CD%FwvqOQ*Ruy7Kh;D0#{sNDk^}6zX_JU0qeZktg2}?%2C1Auhcrf7Z@-@ z{XAbLdVB;Ru99S+??321JOUm)mh-9_E8%wP4Z?*)a%SuCiU+}8&TyN5y`^(S3wI07j^6(IgTl^AHm7)ZF9tx*}3>)IcM-dl{VoHC7wLj%Hhd5(gaB|`}KAXP%V+q z5+rIzbwNtmzeapJj?8qkQn8B2mN(BV+y%%nNcBvovGV0dPwJ!Q71iaY_EJm8{AX4E zxd?jSacsa_nlqP6l491^b(b_fZl8Eh!Dcp1B7mmHzow>kPiZd5&$S3r9?cWm zG+c)GZind(k2y2gGO?pq;GCfMoITwJ8)Z>PHTz18S{}Y19mE4~_XSPY=m50?ji@Z7 zT@hK%lk86G85Mi%iuz^kISKx#ueB6-#KXg*?ym!352W$x@& z{YV;VK3>9gXakMu!Eqxa$u^HQ{5}ofH#eayL8d?@(g$EUFP-}SVCC?W*{TeqpEM7= zyAYK%H5qg|xwNe6S&N}H6}z29dWb!i|JN<-qpQ_;Kr5@H`(>2l5sybF2~|u{lVqj= zr>LD*EUUpj;S~9qQbg@d-me%Ak`@u!2LwiFIO?{3<yG=Hfq? z&zS5{RXqNsl&h#%)Qeaz-vq6JjX7xr&Uy6-{Gmk9tm3IY-5OtGm7{Ew|cUNyF_UO{kMIFF{T{POs$8Hq9_Lg zsnAlV$^%TI0y%>=AHpcGr|I59U6L`Uep-1Dng=pZdc^fo$9AkTzC4xWBW^2}QHI3D z++`~}Yp-kt`6cr3Qmpds?x$^3=|!rIs=49Oh#d?YEX*4(Zq3<9a>-=4!6t^*E&A)0 z%xAaU;cJ16Lu84+1^@bz8Y>c#1I2;MN<+j^iIbK;pqEK9H7qqf{7_5&19)!})C#mW z!@P%YpE@vN!+Img14Ko?^iicxx4$q1t(YmXtrOUF#zpP#8Wl1f%_m6E&%;hF;1x=8 z`tJFJh(dH!EIysZ`wE?p>6iWU5@I*1hBs9Q-4J)1os5}K>4`pT93@&Pxd3i8V8Q!w z!f&Tt0q}!3%r09#d!c>Kr7E|#374fIM#G=JX*z$HMF>O&Ebiwi3uAX{#~lY@bPn8P z6bB}}I&*wS+0VUHNMM-G{?n6D(~mj3=$VwVmHb<`Y0>-ojVcSdFs;;wcpsaB%?$Zm zl5m9ZTG7p;9qVH~6coYt5NPY-69C=Zi#3IzI$D-jDmT-5E#yhb>PH&0!b9<0vK=J0 zZjXxLRCkSFKC8ei(zUr;m{2LNxuLCurK*Ye3;y(O)h8c(x&RAWj+LKtn5-f0A+k+` zbL!W;1J@WPvO)4H1I6jbF4dzEDw$z|JyCqk?tQ)M3EZf#C6~w`2;vIZkY}uYT(c^Fk_GWm>89nZ=^^iacQ-v*uIj0I`_aeHAOpG-C#c);ZR^HV6mtwJA`$2_yXOZg?!Y0l?0r5#Qf|5Y-`$gbiHNTUn5Z zbr=reZfYP!`k;$Q)h3>0Hbt65sYz<*=<_akyWIhSRgZL`PCTZ%c)Y*W#{G8k96s(@ zl^SR&PKfhIoH8jixP{xTIHK9By5VTX{gL{L-mtsuEP0~T*k0yu2;Z$sc5q)gzW|N; z?zE=hN0y|1Pi;`V|201n>uGxJxa)oLuRyNu8F0p+qvk`WQE&d?{i(z~F@v{*8@FFO zbArYYiEEP4Vs4)chuPmutF!^FAz_i`^tGImaZ)j5rD%aE2=cnrJ;79n`vM9VPkgIp z6R5o7R+m41r&iba+(I+fW?tC8`qc=7yfO0TztzTUX6`=2W7Okl>aH^J@!2NiS)#PgSOm6ylk+V^8n#nY_pj0=~w6k%59a> zCm8s~9bPf*i>y^!?lr@V)#_}a0uDQeDrxSugHr6xXM%o#-Kg|Nw2+-GVZX1iasST` zdJ$(FSmoO5*xZ1YW`0vViic%?AXSROlX5#$zN=yWBPy|v6a-kC*F_&GPc|##u(mg4 z!e^<_$7zEj@yU8QFBn8Pu3&m5JqGm=fR})*E}qlM_k9igtky;igjyj}K!zZ^XYI_I zb~G4QbB0*MYa+4wguE5mN7zCB8dg^bY65ZzZbxDxPwAFmPtFfS! zu#rkpO4rUQw4+|jc~xRy-e#0*Yh*1+n(Af)Y+5_IX2XGI)CCUpqRoOt&iQ$CvJIM4 zjWm5llT}Slu+p9A_Ya8h%gUaZ-O=Bfs89)2f4-&S34es$*rJKyC@xo7$F=aCW`jJI zntAuac*wV1ZLH*%|E!Ob>Dz9oB+u9yCFHo7ig|>>=75svs{@XD=-10@Ud+L|INR`N zz&shMjv|0SqQtCMV7*W5d?K4V`q_0<%B z+-!UPs60+askf5+Mr)DAD|cKrwM3as6|mmS;WcH~D&ZyC)lHzVx{?|xp}IRh)k`J2 zHFRgbkq39)c*T;HPyu$OOo%fN5FZ)%$S3FaC!q#Jh?L)hc8^d?cw&TGwlr%Hf2g|j z&pBk1Htj<>J}+X{DjwbkW9TIl!rCx!)4>h6wNDKB?eo{QhGwqw62sHB|1b|_%hWT$ zzBQbr(QS``>bSK;8}4syYx9CQz*w-(rsbD)>$8h4t9L4zmMHqieoi=x9)BEGZ7vZV z^mom3upan*Bv@|-wcdDAOW;cqHg2U_-XQZUq2C+|x=X*FVWv*8ucVt(J#+TS^Ka%j+As^}z!3M9 zfw5P#yNGJPW5bqWdQQE2_WoUF1Q0oNFrHGytiW!3n&Y?&F09XdriN+8`n-q74`a`o z=?4Z4`a7NU4>IW5DHN6r>>U|LtVKRfQ&_qguWi2k`K0+ePeE8AWn&i+6&)ZgW&Q{e zSW0fjYX|*r{fepLb1Io7!pvUl4S9Q}Tzy~Ep!z*x+GZT?1V8cG&MR-1R-VDEc z*J`KZ4I*odR84Pxf=VTJltQZa%+>%%><2_mfUUm#TM4VWbb45YpJ-DV$6YJ!qF+}h zF+YINQ}m%I?7{9qqYmH?n9Ep(1wXd?_X#K8z&`b$7ucn%TVZuP@`DWs(h0$>_myiP zM2Rc0RTp;afzA{v7mPMpMQPA*M-6z8jqQN}M2M2GVcb>DeWck?kw<()e&_2XkS*27 z;1ewA7Wvfm*`Zd-+RA#0x(~llEr)mzmG|%8kuCywYv-zJOL};d2jwQC=Yv??$`a!y z*4WZ!vDLb**I3=#h4&}mGI=LhyeKYMBxWHgs#{$O7Q!yt z6r#ix8HebIO5R(w0DIRQz6~e+)#>k?9ZgQ{FWihK1whY(4c2tO%koZ}tIHxZM*m7o zyGZ{)4WBRRySzDYN{mrJaIE_ov#I7X|IU^fG}ef2&sFrpK4f$-UcT&i%#s8j&9~Ur z&`f|I)rrQCr$K-z8nto3g2U1~Xmj+8k8&Gu@Xl`H^3?CBcA5JQlx5k_3$#}aO()Jl zUt4p{m6Y5p$=n~drg|LWe`&)6hRY4gj((cHI`2jTmD~kS@;3e%P8DpbRbGX>;lFDV zSg9+r=A5{#*ubs~ZF%7n4jgT;ojAVv+u5j&wRi# zE&GWVRi4N!ckdMTTUCv`sV8b?M*LfWu*X&V?dFYe?jW))>`8WsY7un`4x!#^;fy+M^_xe zl&z%a_$u2icwGdMOE02t7QR_*KU}HoDlXq8906QM`I2_41zhuZKSAzd=c*!WMFB^q3vf{=4!Gzl-1 zKW7{%D-S~O^1|(y88;!fR2*7Fp055piXlnzaF2im=Lg>CHgaq=!<$e$5TB3keTUTe z()(AY)p;oeo<^}|Ezkc#5Detj-_cZEh3Dah1Za2t#YBJa-Z=mbpppS3JX@f04 zl~+3aO0T|J>=y9*-Q|-*;&-|ZGk5n%_NeF2(8$>>&fT~CbV%?*b&~T?g!z6iEL-~2 z8lW{fPZLT3u~D03sODj*4F7tdgL;1}c__(v4f`^AKZpu& zvwfmJn`7EYmsCh>5Q1os)e*Z?ewKh*6}uMx7bSMw;42k&UN9@QLoE0PO~xmO>)<6n zu;Ys*QQ#Gsu=KfKwf#4MoJD)CrDU+(eM7Qy7<8rU@bhz6rfA}WIh41=HPPw?@^#R4 z-+=FCTFuWmgtV^!x`;9&)b*$GcFA;RePPMmg=S>Y?RI3s4l3D^HU_b!PPEi4IA_HA?8O4 z7BC;q-OVGyzFr(#h@H_|Wv?v#3F>TtZ#;2u;;X25+oJnH;V+vqf~8L)#rcHQW!aP9=n zg9OH2aUc1fc!4QwcKwIteh+|!pxONAU!(cRg#FiFsi|rwbWRrg3#3A#c-0|!9S*2T z#H@P9B~z1%gb!#^un4`Re}?rInyn~@I#RtljxNt|c6;vaP^AUvkaqZbeP-qXMb*)- z>$LV#7PXqpGrFG{!v&qfYVp}D>GJ%Hywm}yQ-!|Apq?nQX%FPadtDuVP^V+hp88Y>_VB|^7HqaZeup~K(? zi|6?N09|L?X$Km<#qZ2`GmFa(sFLpak%gLmvqYb;kOVVr^axFCjITXFO=tJfvICH_ z3RVTkyL^zBvSOX)g0Zl8gAsM2@2{28V?}c5R3g*`o#o3aS`F zMkjXbun@88C)qR>7rw&dBLe4CwTVPfrx^O<78buD=_@Vit+d}wrj!sAvCx_nz{0df zS!hp&TNoil&2++=NzWeXW=i|I{p8Z)E)%+gnp64mVRI)xCB2c$e}@4-hzh~0m;|X~ zKFgl_&t4sgGaZs@>l%Kb<=#p~gl`~>gEb`ijOWd^aXVpv;oY81&qgOWJtMQxjo?uK zbyo`7j?hffZp@ifr04d>9$2XUY(iwN{w27A{12-4Rp`zEnYa26W{)KE-NuUHuBl$h z5q$5pL4RbCKlpBdCeZ8)oxmWOXvJXE4wH;FVPP%rUk@OO8G=OQ=1bn%v9xS^?a5OR z=a!^Pf1y8XCnR5xqsWs7bK{`MVV2K#Fd_s%6WpE)oQ|?8MrFd@9GLNUPUXKyW3;|KXM}XpqOQy47BnztJ=!7g;qDxm`fw%}RD-CBwrrF@+Pr$3g?0 zOx!vE@yG_p(TN^O6UpyG)^J!hbP{01*A zVt>0zb!(F`5-sO;qV_+(gb<0lw5i9Vn`y+$*8+mIS%0Su{NZC;!hqKzD1PI%9(jRZ zL zx~~hfN^dRZhjx*(j`lH&luWDt*cJ}P2>l9uXGC^8_!vA`xLs{wt@PdleC~*tCY)iv z-<4SX=jOy%1b`q%`B$oCf;`o)qutlZr>tOysFBYP<69EnrY;Hjq zAxkTjzi>5(s`i7E5p96#@x#q$|3@)2xgSdsZm##idJNU&DsL@c!G~0vJ_tLo`6yYDTo(NxWwcez9yP$_?mP zBtYNwR5)8%{7J5 zB~2bIS~OBfmISr`>})C@Q%wsY6q(I?J;R@v2m=VrmU-SepLVIE68!cYMMgEI&IiH6 zzVJdfw0bpeF8euE4<`YT#Vb2nM80{BkOu0u5-42BW1{d3?8hjeIFF&@B*%0C#eVBZ zdhXF45s~9fpG^8mNUp@7a(#5M`IKSRd*k!y_OIXmZh_O}o~bT#w)ZJ~xz6a;m_Q38 zWTo`do5+pbSmDK3Lg}EXn^xRZ(m{umT-5!SNAS*EM{lKSW<<%U+!hRNT#i&A5(_{% zD>i3s>wMn0guGEF*LU|OonwU$pg*}LR+kA?cdEbErE^!zLd$ROVxTIK@V8`?J$$_~ zt9|~|kqT={{E+-qn_s-)8Eb_~W>6DLyRFOW04uK>oEHcZ9lO2O=EX$%p>+R<@XA%A zCE6#Mb>N1po2wZ0?X*?PRehph>0#IU53B>4fv%@?vxZA7uKRNnMaKcY?PR~I1UbXI z2*L{WHz8Mw0+XN9l^or*&cR}kIIZf%rg$*j!Zi4J_c}AvD zwsf~-Uq@a5z)18C-(BpkSs?-?kJm{B5UX#wEhXeS<-Se3ER~UjGN$QA##^#)0*Idu zDZpX0Q_3zDpQfC=vH{b!1ty$0&eGGdYBQD4vg;L6VW#O)( z*X&dFnTRzBsq`-V27a!gsk9kLa?K+CNs~%!f&HA`N7L=Y{AKj;+bxkhOSGql7o%z( zE*Ba_-*7li^5_`2w5=T)8$3oSmV9JRHkKY4yS5O1GG3y#P=ViieG*r(4sWdNN;DS0 z3Ncok9I1qDN$iU4_=~Os{Wm?Hsf+2rk6CMt59qHEL<^OWy+s#Q!A$_4w~EV8aM zsm7n5=cVTWmfr81_N>dFYRA=|gYNZjd{;UT!b<#TW-ntgU1otUX2#-BT{WQ_2vtOg zMcj&E{m5;oIqU!|PkpNFYS&0C3_co4f=>DsW)6k}Oy&c6x8d~jAZV~u$M!G%Y4X-l zti11fU;0%$eRaG>C%duWUT+SG9XeIWE@~{;S@0uM%oF&7SF9{-$>>_#{x#YHGiW5Z zjyIs1Q5UWv>f3fDzFOi-D!eZ8ey)OB94#%%D4igzr%3Wn{kj z8SmkdEFEk)d{Ggv%Xax7gh8Of3DPynWVgbEWg|V|Jmk#8qMQ)aay|U{+C+4>e3$?^ z&)4^9p9fUyRH&d7K` z5CK?%faj>DW^#arFk5Es$g1#04Xk(I__OESb3I4%P{cE;PCemf@0kep%oKC_Q~un< zuv`~%`kk(`k!@Ic=frZfE*9^a8?^2Kyo*5g(C=bSl2`Wb(2VZmE>XfeD|ET>I-S;l;gdmEq0e$B9v9P;+nW zA-4=`@Qr&aYf=)KcGC@b91=9$9gwI=Sp@HT5o#m#7MG?_h}%?M5x?aYEq1_f3XCUO z6s>~4nmAN))#z2O=;cIwK20&bTUO(HqbwEtHkbk|dNEACxua8U<6t=JV4M*6@`@+< zg?Tu*-c!-0ymw>`in@GXlcuLt4qOKyAqKyq z*pch*;N0Y6D~lKVZ$VuYJ7M|$C&jwztrFw2DjQMdCHHl+rwTXC=oxX!fGP0D=E`MM zUL^}#JQWM36%f7MSCBJ&d#s_$MK5+atPNT#$v^Es(4XO8`)oslH;>;9cO8eDukK*` zroYL(4Zyr5om*N}Mx^Fbpm#Y(1rR%c5gktmJZ_z}UdPPk3}qyf>VEPE@j;5yabdzNV;fu23%BZHWMI^xsH8wpn}M|4 zH!I*3K(;(&r`4YsF-8g&pW5AF!tM|-v^t>*b&15_m_p@)G)^UH@o=(18pyST2P=$J z5$_5qMXJW@RCw{k2U2--8sZU_Em)T%a3z4Vq5wCMqX9(Y5%G*#1P0%QzvCiSS_CX> zNERT3?GMGQtnK-Jge^t$W=Mz`Q5;okvCVL1)G)&Dg2XpB1$a8Mmqevw(4 z29F&$lXh3du`Gn$AhjOPogv>kD$Yi`Th7Q5FwzjLY2=zUu;YUMssvS?AYgBto# zsX@gGVfc~ogXHcQ^?1cpa^j8fqTa^rnM1nyye~aWwZOl%JWOpOl-?vU9a@sMn6jQ5 z1iM}qv!3oR=SE-;Mc7sXgyvv4*08VZ^me-iVZSweC9GNAPOg=uR-Kc$XaN7}zxE^B z9G^P}X$FeAu+%tw0cM_iX-bm#VR2cq6Z9p++;(camZr~dD~4rBNn-4x)MlS;h_3A` zjJy1_-a7PxgSJ*=*k?Pf!_JuUbGf^xOv6x{^ zBH9|$A{N__p<2yntEk1FV=wSUv_EnXKm)`r1f-_gTT?SB;#MK$cEeYbwQGu+^VC%D z$5Fw*qVA>AfmQqq+~amb;WdaL%tu!uOF0*9Lzz)BD~A|OPd>^--t{Xfxc%0tiiqn8 zqP9diwDeeD6r3N;EhBo``jy$>X85x_?Z;tKwhHWbM@m4HF~S);)k#}fq7Q$w@%lvi za+hCfJlGs2K3Xb@smmF*vef~dmNC7H!E(lwz;m~hr$E(Cg0h>?)If1L`^)6V#lFpC z_uynVUj0iXVvE78pvf&21X=9rG0g~ngo>F4en{6NKO%DNI}*e($AWEANPcnLG}ZuD zinkDG-BLd)2;LeMlq(=zkMv%C|^`ofV{EkzH)utQC(~PGO;*lw}P^i9A=iv5@bFN*nrhH-Tr-2?-7!bHt@QP{l1fjlw3Zm zZ{B3RDy?nC5mhba15Vjes67%s&b1~W?w^c~4!#Ap-(gKSmS*T&EM4E8@ z!uykmqx+0CeY`?e3`%;e@p_Ln3C)uRt&Dzjp+3i)BYBmNhk8!QIiA&=GQ|a^(fJCZ z(XQQah!8%M`Jd;azCe$}>A-_P;g*5#vcMXFyXUb4DS`Pc9b zx?OyVr6cl5iRqy}wIK-fT&oQL?!^He$*o3>C0bdkg&K?Uv^3PChL6kFM^#&x#SLSN z>cZvPu6_7MUzk>Yhs)`y0aPq8B2IAyCvCtwQTSbY5yMpX+W00 z5aFazFJ+jL29>9^h=enEnV?|Y{c=Sun4hN7hsgpLR!zNrvkZMdu<|)+Z}rb(RetX z-G$p0maFbRE?0tQma7i9+tpF=q^$}a0eyumE(zEd=&yZ^CW?ls^$tEmgvEde(J8Q; zoh&2=1#G6>uy=3(aw#4PTF%9%(vM?}`F}y#L4$iTvF8eZIWF-rWG5{786N!vO>T?= z7u`ks-%?_M$KA8j*@kSqmV>fUco5V@;0urrR5~f?_>CbQ;V641R~HVPN7RMmZnsiX zg#1Q=L93!N1Y@*;gqx7~a4(-$D@7)zZ5FtUn(wVJ)*92N)%J5fcd5lTJnwDJaDGCc zkk01^(ol`EiP<`z1D9jpt9M{Ka*)rFxii+li!1N?x8L^_H~gFU=JtIS7oO@R;Ii?` zM=dV)GQ8ZpKHnrMe-4|8Yx~=`zcBP7`5tp^ox=$_hDy65@ zQin39y>PEmcU&pmU6?#UJK+*_``SvMM~_yKlggZq|5fI^q0H%2<{XkIBubxGN*#$( zM=)jyiBaLsq?Wghw)l5r@2{3JwFsb2Y;Eb!YU#>?f<`E%c6C<^n{Z-Zyvw4Lb|fAE zesRfG=X1N1(tTUDgAr4BFwi0mPgFgR-*UzcJI+Qti?mVW=Xg;XT$GlW^L!`X}be^)(rVf1upey#L@z#?Ya{?In>2YJ0DTJaLI8oYs>KVi z=>?3XYS|N|cBocZyx*+V;!bQ{k3qZ<@nweu%9;&mDvLV-Kr49jd-21wP3f{Bp=><+ zrKWM&z_{k1DI56MywQ{md~9woWdk3Z*O{_`kIl8FY~W+_8dEm#u~{-@10S1LnzDh9 z%_~gVz{h6Mlns1rUTVq)J~l5gWdk3Z7vcK^ddJ7+`S|XncYJKF#CPoszT;!_27LdN z-tm#9i(-N%`Q66F{z-#G?z7K(at&$6p+$KR?f^LP-Y%CAKJgwIhV~On{cbCNde8d$ zz)wi5J6XJH)VhT zr*~#&xvcW_F&p!PS+yX(?6eSJ-^E9z^e}GOiv-!T_`0C2^fcCp4Z*Ip?yw+VqsjK3 z!H{#r#Sq^bff`OZOfL0yu0uz$BXj_`{&hLF72cGb1?&ny0I}&rY~IC1^~(+;Mu92q zfX(U)0OSuYP9gKo%RuNn(-`jHBLQZkNC?%tk@Q$0iGo|EbxhBQ(x+_7AA{>J>%p3R(VJj z3qzrSJqzT~flp*>p*Abt=8S)IG#b$>`#ODP;Nq#-Po1&2VvZVVXcaqf4UUK{kn4ML z*~b?^rHj}HbfYh9EpDx1+abjQ_9_In3AhZaFuAxjFcfVuIqS35?%!X7AMKg#w@qvx zn>?}a!gh7{MZ!_Qqy3)2YRiI6s-W2Xt(T#V&?xkDbN;EM{nxg}1Jdn<$@Rb`4bTMj zr_ju}XIOmtR;Z;QWq1Fs2>q;+@l&>Yt~~Kh{5`AWn7F?w7tEG;w?*z#+grNq))u_E z;P!I-eQQg1mX!0^{{rB_Jl)5b4hpEjFTC4YyMGGe9%{36K?lnEiijE1W9(ziINU8a z!aCt)0pIaTAA)Zg6pAMY1zFitoS#}SHo2e}qRu5L1;eY{PbMy=ao@OJjrsk8J`116Z zI7+ZU`sd!(zUJ)DuwZf=FV{adz$X_*n#C@I>kH zU|Z>NLh56P?tqd)VNkB|qysw9rRq3xG_3lOebC)4cBprrR&P74b&-0Vzu+O8U+cnb zp>QO+RGlJF=X$!WwBP=y-~w{V4o&VyWPkoVf^dKd74P~|o#Rku*p{l(3Gm|6N?@r% zh3R^ms%!_4rvZ<`WH1PQ;%QBGYqEH7W1rG7gTCrkDy1k~UuVA%7*QV4T>M?Zg{WCT%DT~$h%f6D z+DZ?tfN=6g5_38WTa?l+wbTP*kKGX11*Kqd^s1$R%hC9<&(A>ICZxKi#%WwbVkf#Umxe<`TQPpP4CK1FXGKpe zW`Q7WrH6jq^o#V8UG(TeTE9R?8Tybh*7yZ^2!uf^u*$VH-RogI&WUX5I){=MfiTtlDDF06t&%sD+*-E&9M4e~w5HMQJU zmmMg#ug%63gS0sgb+KKM?eRK?Q1`N0>Mm0Xuqix&8pmo|;In(P+21Px2mvTPjm(5< zfbS($a@agPC~O^`dZ?7y*bI16w$sPTKvdaPsmPuosyzVeN*V-IgU;euF`i@)VJ=Jo zkOGuRb}TxF7^Ifl0>`9bYD;{LO^}aOcb8Q1#N{@f^E|{-@nsCG z7gh-M1%^0EJartZR@_$F`z??mWllfJqRvJvQObC0YqBQexaqXmNFv5=B3|b+`hTcq`OrTA6LbitF zeNGTkrOeTj8=vd&#s8|+K*soT8}yMhC82+SSsoN&&`${q@GOc4HLi{L2@lIplsSZA z$sJ*dn{n`U2Ntvdr~9jcnANQ@w^+Ub^v->k0w-!p-C?EfP|U)Vyirf{L zB86>5BHomwazZP`&zOjXOK_uP^)!IHEq4((ZSwXA zyNn8HHG26GWM$YvZVpRUwe%1>bqRL&7WT7o*uQ}Fuo7$blS^=>da7(kDh|>s> z*lUkMGXwwFFX?D}H?&AMjU^_hE_P5_=?xI02s>awTo#}1D{~Y(8*#&0guOc-?HgQg z8)5tT^BL)a2zv>hTl%vT(;A<$Wr6qn2aH<~@0xH>)lpliloUv$*<-{rAhI5%zc* zkPT@-)(rr%@+*L>lf3MvF`1P)bRMtFoWt7G#fRk!q4gKwU_qkP6%2zyim>HZp^O}k zMA`ETXkXAkx(4%gx=zH3w>C2nz}79uWsS*5%v~+#Hsi=aPflP@U9P(4X^e^4f=paQ z-R^>?ktgKwFta| zea#m*xs=VS0S9dgmc@1)M=n7thENE!+%tN5Ih4BEHL(SXh$q3+eS0ic9S`K<(=?Pk z-tVp(Leb3>jaqX+lCOsN>oF!o@ob0>kI9561_vJa3hFQlp1lK9K6VW)>VE5uG-#|s zY*RW66>e+bS_zj3*Alqq!xe<994@uw;loPFBZuM6;LhOQ3-?~QABFo-xF3i6ak%%x zy&vwU;eI+{OJLt%J!ht!NeO&;8}!g zBV6mttQYQYnq`fDLe%?|sQ0@x(1@F!#%!xkASJazQ(DT6Y3U%5*=C-Zn(SPj`0q-JK%1IyB+Q} zxZ5(@hSR7Re#_yS57&y#X>C(x1+3HBg5ERRAw4Xk?b75e94*8zjJbv+>)f-@IXlsL z;&1Uz`q-_4zFLXj192m9nAnW+K$Lq(Ql=xRFni&F6UT5J68!EeJTULRxjkXE)A-UC zM(pp||IYr8_je9CC?AJJ?I)J{J&)2*!Tx)O1t8ICJKQ1Rz4nPEe)rf)zX$FPxVz@v zmwV!GCpzPQ6KZfYfea=ep0v5x4gFk!TkjNj|G-*Cruw-jXqG^BfRX76d?B45_)H$h zgaPRvO{MRNHRFnn02o<^S6jgj(PVF;v z5%^-Yi~V?nfnhg(l8YtaJx~WYdO5!LUWNmxuHvAM@}(SQM0Pe?f+ZGRATMK)5jYsp zvq;6=T9^=wUv}n8BQ4TW_QnzJ7k8%@L9T;h@3|0YZ~-P9FMHUa5t%gj;c%m3 zMpFQ8=CmAps7Gg`0H z*$a3JSnJ+FZKa2i4|}q$N#MjN;6+@Bhy__YO`!n!)qZITa@}C!I<2&;$H5tIw+-#6 zG=|i}w^2Bq?XtHOykFOV5scAvz@58wfPC$9WnzDeD^=N-GUdw;we_*52Bg2zO#eLr zzY6znYMhg>T?bW8$sJTWm@aBnAZjx+E3Hf0YgR+r&LN7wvu22*lSFa3vS{s@3|Wkz ziH@@Pt`q8oe|i<}a;6$=5jw1aGa!pH%Hr>xDOtQST^6I_?G~`jf2+&lo;vGtzoE7QW0#p(`3ZO=W3T*&2|Z)-`#Hkx7pc92d<542LtLwoDGdauGhh$!U07Z>%&D0 zc;Z4txmL^DO+%fL7<%lO3Wq*>{;rm})V1Jaf`4dJN?qXBfrQn6q}?wFsZ>;AmXuTf zny`)p>*?YzFw~{)YkA*p-5;|kdF2rD^lbQ1h6eF>dI|iptDR&II~(vzVyympT9Q1N z-3P(lOEBo*9kl8T3VHevTC9)71mWp@c(6s$TufY-%cc|qWjk2w?f72nW3#?R52IrO zTQ-4@UJlW+J0K5z_nBP>UU$#lLJhpvDO0CoxbxxTX!Z}q=c&_c0Wmq7{m=)htj;BW zhYbtjMB{bv^WHGX8iTsZ3)rUXaIFna`B~T+bmWf)PAq_${1QM#v?+FQOtdM7EP(Tw zYeA^!)VR^n2y4BLL@)1oT#z%@rYSi+o(Q|N8!YkeJCPUqt#WRZIe_;U6ef#lgv%j- zC%2vaU;G5VPn3_kmXn2W+piT>cqu^Da$&xSMa`Y~m^RP!FVQn9z z#?fy6ffxv3uY#VWv2kZZTn}n_n}XtJEV3V(!WRY6_%(z@aYp({NN<45!4Rla9~Nbm zFUHJkX@F6-p3e)ChM!fw?qGp$)iX{l?N#mSpkRnSdj~np>N2Ls7be-8;03hCYyEZ$ zw8b;X1(M%pd^(C9LH8Dq&;x!)?Gj;;8_}1;QH*CESRjvP(;X;6=*ZEK1ZWog;`%ei z(olAR!;r3?4?u-IW06KZ<5H?^&W1+R%yaGWt~1Ior3`_^yFQJ#XD$Dw!-B_mRNKJ$ zl_#;!@Mxl>59sV*AJKDh;HW$lN4dUzCuh0b2)h6t7vR8#-4b;+;AkC4k9uvQ+@cIq z=Xxgg-w^mhnQL1+E*iv~&2-!`j&b$OiMRWpJX9w4sdF6hlbSR(e)5boN^Rl3ue!hG zRJPUjee?iRUa-w4;kLqXh&=-Ix^NeMS`l2si=fo?bL>s_o>7I`tSHWqVR1L4ikn(@ zS{kHNsmBiHAFW=fSy)Y@Vc=Cp)MI{hh1u2e6;Oq85wKT>1%|f2VsS|$ z)S-tvptZ|a%DIfmI6nd^BaqGh3X!9*=Bao)d+sh8Q-jdH;+0vlJ6^sr3yQGx3|8#` zx!8u0d^9_;&F?s^Y4yEQY7fFoO5;&b*J|TwT5$DaJMBOC10H4>)&4*y&uWP|o0Zbt z%HmF?ZktlqtJJkCbxf(-r_?nobsg+N;IgT8yXDK6dobjJKdz#q>}T|;6!*HiX9TcT zO1H+Bto#z$XSN*-loQfx&gVuI?p+>u8z&Fzx|F)@O4T7}!+3~|Wz|?u#OvOGE^CK# zg9AbmGrN{gpD(O-I-lF++_`R_1R~$%#8Y~lFEq3qh1XbaOTTSFphYQt-1*Qiz#IgZ zM%XU63X}0U3?y-rQrfJPwkxF|J-te4M|T|30JJ#sN!P}iRk{q<Slr(2%%#!dJCcK)&%K-|u>&sc-KWsVSjL3zV>vpEaTzd}Gx0VifogQWnnP3K z=>S;wA9Hw3`frfRGnsV^I!=EGAjF5p=9IMi}?MM8d~t+a#II%h?p z2Dl-ID!SD9$S?4Ow+7r>7w-={A9))RNi}gcLvleA&Vb84vCY|t+lAx1d~KzhXw_cT zA*f(+yp9P8`6!JzDe_^Zw9A?J!h#b748M!ijr$vxpD67uu=DTV5mC^b;(@Xa1JpW( zCp2W^6!rbkUVWv#KHg@^;=|5{LsnY%XWz1K56-n8jxXyH8Z}iu?0onWh+3c10DT31 zA{4~Sxic9GveJ9`h?Zn2D+60=YF$_DJKej`m}2vt4c7xsP^oWCY;iUeL6KOwpWzoq zpR+>Yg?(jIzTAOwTDnoXtf@4aDBT=XOE>Q+Z4tEX*kLD1lfgvk(IDF{=}X}21}SoL zk8Qb9dK4l6O)wC<=b}bHsEtX0CS9hM+Zy*u7h~lGyYodsnR8fjJ~45Z-Zb6kA&$#B zgzgdWVAMCrlB+;zcb}mKTIqb`A!;ufSI+k@b8hIS@NYREzJq$|+oc8Z{=1|J@&3D= zjjuo)RA*gV=^-2!mTo}K!_mQFwUA2&D_Qk_hSQc3t zTGEJNFrek=ATdY^w$CcDlkFPbtF{3`mvOlqr`+dpckRh7U2WHW@_E*FEvZ}^#6Zjx z|74VG%RW(^Xsd5kjKpakf6 zPf9ju0?ediW~PnSn4ojjRa0EvuStjcu4_X;bus-HOC>MQOoGO3LNxt|z6@(6~bW0rdaR>AHXItjW@FEHOxH9yD*K?-?j! zNE()898{Pula(Rcr z^X4}iYDl$Hw|89(`iN=7*7edtM`1Bdhjt@3PmwQWDy8)#Kt8Q8ne4k766X7lc-;7A zdTSp0bQFvVP)WTawoXtSV|~FNw*ay5VoY|n zTa_-P+j@=%AR@WC$so8HlF@b+B&YQ9-y4h~kL5Yp;J<07exGje58D|f#^Ze|)I|r| zt}H!7r0(?3(n~v_#LUtNRXXUgoho#t(oyV$FHoL4NHw~7?E7fiLRNiziI@ZzP7;a> zT~ol1e#wsIG0W9Q4AOjeU(F+=8hU$|YVXp=iO?9avDiUhT&WKbimkq8j4Ew}(HI6} zS_P4qs_UTz8cNn3^pBG5r&NDD6p9l+fhYfz;Iv(JGk#l)NNPps>$?piNO!xbjN}W; zcNH-mID3tR1M`|Dpk87mVd@rN`2ip0zgS+v|G6kSGJ&t zI$ORpx$3-U&fn!rBi5K*@rzmr_n`=0Ez!9!JGl}{tcPy#PH2|Bd<#8#pLRlUQ|Cbl zz?|L zZynGqjcfr2eQu~%s^%qE2cycQ;c|5#x-uGczV;TEX;FJihBq@84_g#Ac^SYKimICx z=61yLu=BWRwaV1V?T8AJ(kcSbL}+G|rk^B*5KdjFhfc(Mga0tZ-%^zE_Yj!su|hHy z75w51HFL5ToNA^z$@GH=GHSI{pjcI;t`4e6JxJkke^CfWB)2B!TeC2H)u&}D3m^7d zx;XN~%4EDRZ9#a`dlZd(W`1`T%GM~|>fyelaHq_u*eZZnJVkCxrl0;;7dFg!@<3YE z38o*n$Z0Gj^fv!_NHE%kIrpPWF`4C7#Zht%XB6X$)sw}v1#P--hwk3W*A4J64pw!s zkV{DnBE&GHWO85*LjGTtEyij@fW@@;F{rj7Rf>D79jK9iH5}EAe5JZ4<4opQR`|(u z(MX2RdczXJXT>G3g*A!yOk;`7yjA2#oBzkIWO@Y`1W3SoMH1-Gpf87DRQ>|jFj`{J zc3d-WmF{K*QA|HVwXy^`*Nf?ePH1qnAp8~xasJ`TEPreB%JtALzXtl}p(BtG$&iW`XJuF{NMFXnZ zRinw_lYY;pZJM8&uPd!U_oQ2qeN{o^_B}i<&Drh(eRNjV-4drP(x0uAALOjRx z9!3$AZ7?+dO)$+dzl)<(VS##D^JlNpXL);-(dX*LTsPGR!lL8i|H0kKi|%yg8uB zT_P<%^0Gc$KLz_Rw0>LQaV48qvN@P?ACWG)IC6!}aLr!{rf1D;*3pv!V<3-9GiZ?J z`IP~ted}eVD7Yqv98N#h>@$1vEwkl00ab1|i&KbaV-PNi1+L$~fSDca#YYF%R!iXq zAENO)bEOYR5j3+vbN~|MSzyM4;%4)nN6dI!+-y!>_DU`r@%O!gt)($9r}5B0bG;WT zs$qVPWQtqMu?7Ym^6UN+w>fwXUapN~W^E*cVvt~Zsy364(+glUySe#mfgHYOG`mO^ z1m!P#=UUI>MmZU$*ex&<2rm?YZ(oa1vkfqPV!a@|Xf?8R_vTC7T=~*NiaoG8#`RDM zT**?-x|El4TLh7(rsWRVlUAqi_T{7CC}=ayRCZWByd;XYnk!X5gr2 zi3aCTAGhEjY!7;J?+YrtGS3)CMY)FEdQ++re?R*}&ne%^zBhB^w ze%{9140Xa$X`~)8MCwXi3S(w_zPla9ObGJWC5{YB2Z`r=sBzi@HP{}k{X)GFoAD!@ z^$}iL0=Gs75EbYwnsT#LXIx&33wjnSQD=>cny|iDnqR!pha1cX7S*mU)_byVy1jg1y%2Thq9ciAkNu>y7&!K zn#b0w0d8ABkP4k2zZ9|PUz8SHdtMy$BczZ_Epn1oe8%)zhW(3?0|Sha1o>Q;dD?Rp zF&@M()3FTm45}Q3);r%!@_6m}*`rMRoz$1jl?(21*dU%V%U1`G1sSPa81Kuxv{a=q zD3*D0pEi(r>l2|smaMlB6WWl9H<6F&hH_N6@UzCM+;#I9BVk~GQ0c?kDoBc$#*!70 zjHqjp@$H8!8OdnSh#S2B#RIctN2;KbW1@Ji2>51t(JSlT3) zaiN-o9vT7r-SqZyR{nQqR+z<66AtH=1kJ4|&t34XpLypuU?7m|L8tSQq`J*4Ar(=|M`1LU}t3hpN; z5cO(yayM06{4ra^*s49p;M;0P3yb79s$k3^=^}U^aq)D;w+yt)Q*s_}oTS%3oGGSJ z5PK_U71Q|2Z^|?@HHdTq$Uh^n6@&kA&EH(N4eFr5?C^IlZX=LA(1N^}I4C=SUPeR-MF zYcT^)DbsPQztLv-4MJnlNI=S0r|-sCA03BCVRia0e3*qGb7n-QiZ{tm_i&ljJ(cmG zP7|chI;VE{zpe;EdYgJNUwODSUBNGeXTw6w=RkxWJ`TtIYKuXdq_9Ll%3l2j+kwQ> zFF}ik)SWPGSjdNVHl(O;F~ z?{4;n1=JR{9a+m0=|tfhb*--jzQpjxC{wSc1- zlP{|`SDl9+L0*Gw87>pORDpXT#uA}^DhloNnS%28kSx{GnjCsuF}eE&8G<8&EXqhAXek+d|Z3H`TM zY!;Dkjb$}H9D|@Qx6&`!$svhOdZEN%$d&^$OIFWt(k~I?ea>oXb(!AYGJu>F5J~zW zP{eM2l5P1Sr$|PhmW=IM6#l4;zKV?yuCR#KmS2<9by^s8+SSBX7NYFh5T#m(3QMZd zP*EXbhPNzZVf-1ci)vB;)kJDNCr*^Fs$#0nndi|WRPU!5C1`GeD{Dy`anT9MLtCJv zYo64KUQB|AXP(rGeVktG(oKv+fKEfE7q<9>*trr7=e-?s-l9&&3tgTPvJPY865evS z0;ny!Xlu&bcdLlm*@eGJJMnky4*Z?I6@Rm~z;F46q(kfyzmHwUZf2M0P3$spBfCuA z0GBNRVOMT@lZtD>{Pu(R?Cyr%+7@k4k#5Rp*oL0l_Y5G%%TD->;|$)m z=v@OE85Nsw6*m&iZL4RuT|p$+$93lI0W@JW(x0Ij362W5%e7Qz6F0$@n;JDWaEzmf1bdf zm7e!dO_+<@9YHiZ(^j-FS{wfo31nPOzbtj5>O3_8@VR2;oVQ8PL zRPFE)8&8TZx=)BUlg*NT0HlfxFR2cIpmpKjz|VhA|6k=ch`1M>A;rDu+=~ilk;QZ< zy?mn8IF5Mm2PO&h3{F14 z4eOCk5EXK;@fPp#ZrN*W>Brp|gP7bHB_A+CG+)WhMtG^K{{Zr7h&##&cwqcT!L=3R ze;?xiv)mlzZ|KW6XM?8ROFj{&$?HI6xCc?n#u)$PMw5!?R~@6f(+!3kd6p`Tq8}ie z{*1dM3puv?A^IykAqLMWTz3*zkUhK7_yOFfSsN9xPjeB)GPi;8l>HiY0GNM^$)AxA zReckART+w<1ED6;9tMQ;DpI#19aN;DWn*B{o zNl8XugdvaMmJqlJueGN|M)_`9WR(A&c5Rd|e{Ynvf_psLEPp1{kAZ9BsEqdd69^ZO zIu&VGL(x}4{Wq~#0o6wgN@iaEwy*u*tZr{(@YjefC+RGKptcM8WEywz$*d0mI?JSc>R%3KM)PqpJ-T`nUYX{4zFv4`Y-XiNT~lT8gtC>2*O(j z9N6rS7s80`_BPtSDiKE$dxu9lLhqP_$;qkrVmqim5RD2b^GE;>-%HV2{UHRWl0iEB zMje9lIt~MmGYAgUXEyxvbLI%{1t9F#A_S)a#}8;~km>A9soPU}Rzu*Fb|GfV)5h=z z-3);fry+3Y6kd|_()6#;9b$C{V(*qOsZ#XY41m+dp|^$Cs!*x!66*KBm}eabZ_{@X zTUVQHAA^Ow5Q5dXAR7c*+fxbg7 z-qdE>&G!D|8}ow=wzF(+mxY9H`U((C6ARH;3`G*m~^JfO9C z+P6SM(|p9xG*m;=9MRD$4rA*so!R0vGM(%nxl_AK_wzfW#NluUL(f4CN#ji~?MyE{2sOfRG#wt>5e80~ zpyOx`l4^AG*bmW1KwyJ#8jgmBaWqG$b%Ks$*#{r*6bszm8at8L5Vki)wQqK~Vm$7% z@I4qOHs(30h1=SNp>Hk3%sh^9Hh&@^2R{LrC36!~C2 zu3{+=F$JmU@%DH<1-lrQW*2?n9mLY?GL(?grbbh}x54%mB55{|>Qjv!zDWTP7uSA< z8{3gcnhDn8}baq<(qL7BrH;0@YWkkEtq@{6hZ zw*J99PE1x;am5aLxBkUA6r}wo@L}95@ICoi-q2>mIK?>i8IFF@#LRi|+-@nlX%VJEN>)A6gfp78cU2T=HMLq>D?xWcYm_%Mvx^exW>204oUNMkzv|9ndh?Yi zhiB$yx)$*T+c5!nK8Jz>doleXIBv(3Kr#_3jZ25f$-_aL7shF;91q27nsy(1nT3|3 zUCE2eTIAaej4!}kF$Fc4xu9RrZFq(ts4uw6606?Wgnl^$Y@xLfQd^#bVp6s9$xG(w z=1z!}D0cBB`&U58daAoGyap;5v4Ot7RIvriM01~k7hwXpXvluah-4|M)T>H8FyL!U zRLE4)X50iX`yNIk5o{3n#5DDA1wH%rAj1ng(17IQO6XjVgRgziAkJnd6wl|Z&0?b5 z%oi-AN59pY4C?OwiG49qVsu|DFMi7?;SDgZz@t(8d?#~{5Ys)R<`&JVoP!%A=ZSsc>K+_fSRJ~g>|e$EO=K0XNIf(*{FY{(A|;B;4XDGBW?V{f@fB;al=g#)2Ff^S&v)tT-s8z^ zJl*6LMjHav3F&vJ&m_}RO*mO=N&gVuf>>tQkca_u>HDj|*gSb+WDCKjRxG6|3n@VS z2AOsrF(;S~o0@gj5Hpf8(|$Cl`Yl?KA=}JDhE|(us3`>97MWgBNVb_IyU%!5ay1#m z7HIC~6vo7+K9fRX9MJwu(3t6uL#Ka8!yc7eIro`$U49NCGOE}M0@m27H_8?_+SK+I z7uWO#atQ5Q1Py2ylF&9G&Jf85n3){plP<&?dr=usvdFO zUD1n0CxbRiKEdsBiC0Q{5Vp<4sxEbPvd4DNLG#|h6)u=#>B|^XEki!qPEikg+Q6PV z82U-sjeb;QAG9b9=*QND(V7aaM>Px7LRCsEruFYIEt&!0p}GBp*v?XV6{hI21CbITadkD}#=ig?{{o(rSr9=F@`yFhyeb(tMO%o2vmUO=w$9<#S)4Ex#;XN$ZKy#i+@)EOHYfi{wjX5@pwdFL1w!M{^a3w_^p|0WzhM#NCo3_; z&PG26{Wi#IKF0R}gC8U!P;X^&{Wx(BT^fGv-?Vt!~_ z94fnzI`^omKRM*{&k;T|_Y96p(?4h9l9sS}!wt;jzB<_;TCn#xajGp*wFX_CiZicd za{5iGluEDu3EUsh%wV0g=@KJmXWZ4$^|H}^J`ee#$fIT!OW+E|G6@B75Wf_7xm3s1 zLesCCWn!)BQv)I+U&Zy6rdl@CJVbwv2Wzt@x(d|)%vdqKZWf#ECg4e!QtA-HczWv| z{j@2;O;}S(me-jLQZ#)RI}lnM2OLOR1&K;6rvLONBpbJQVR*3G0;?7mS|6y&hxu&X z!zABK7Fb{qH8qnt7h$-MsRcPry34bux6hOi`HOY(3Ec=|5lm8BF&140BK z<~EGE@^=jK#m4fxiQQaCN|Qly%))#*i*X#s@n$ZLH*l7}<2XAy_{jf(AT%>;FI3Nb;X7eV=@r@sr$%VSjg zS-FMFw4Gh|7u8N>+eHhSpsd^PpM;IB^dh8zP1sU*xaA?HmSzW8R$0^QMHcl^9D1sg zYpYWX;xIf<>w$hOw%TeHn#F%$nqzS%avaOP@H`p^kaa0;RjB_tTYj$VXO*K3rZkpA zQ#ky&Y6{Q5-{PuFb=u%8?3AKagq}iD=_h}{1SPvvCrhQ7{+wmf0vV^TK-|y?wiz9Wfc!fETt%3*!ksYbz#rgwd_xpHv=Qo3m- z)-ohls&=UkJzMWwWZCk&S$1o`IobFsW!)1%g}Nk{J*ZL83Ldt(>Nn z6d8-DS5GSIu{c?dP(Orc%(7CmvUU9-Xe2qU>+vX)oF*^Cq2yJ-*DVFe$VwmW2yMjK z%u3!0#J_Gs<7>EASFfPsk%~1mLF0-veen#63TFD?F;)%58h#FSUcw zLd*~G8lb@ex`1-|;80Ejwx!G}EEx}%JI8jIhmab?Icd>OaLwq0uO=3tjYTW+{;k2G zrI#7}fQHbeDZ41n?8f4J=~Ffmx%-6rud&9lZfrZwzd&SIr6&cihU9+bMXNzOnOAURR&qT z6;lEUSQ>8OaV|6U#Q-d&lw;2~m&xS2xb@*d-xjWR1`m(0aeNTKov>U51QiFwl3_@1Pc6=#vk6r^t6c&W3 ze?k2zLJC;Bg*+Xk-yyuHSnXI^M*dO?ZbiheG4e^#Z{u8AKu&?_?TtWIw{(Rh1XC{%>=0J3@PAf@bO)ZUc(xTcsF4bO&QmQvL*k2d%%rhy2 zc<{^p#{h0Xk-z(zjneHj*oFu#_*i$_(2qT%ea!a}$T*CLLqIGVR`v6Duw`^7ExA)? zy6I!vPJOv14)hiuO4yivlD#6MJ#$W?$5tA9R^Seqz#R>*XzBSFy9!H(LQq+ zd_dUmbtv`*`e%(FS{ehYpluiES4;2LG~ob?1F__9Da|db5??#1Dy}2UVWx-9}-<=Lo5= zZB}ht{mW(=MQ&!4bc?VzA>%~3dMP95|YHGlXJVFi|H+aWyvEc7Yg4{8YWZRO_ zht;V_y976i&7o$#TUfsw1K4+C9j4p2cx-#DtRb$tgB0ynZMz#s&aS;YOd19sYBj`X zL(w)^@VBmd2a=#v9w)u`S%VH(2gGN!ypXo^R)?p4I=p=faT3<5_)MQmGPB6UJ(BTv~bG1V1a23IMb zPHw@iG~Dg*r(>(mX<-b*+DMd*(QT=nF@~9njiCk>I0c6`z6FO@WCk*&+cqyH$TXCx`IU2XxT$YOD7jYZAgRzHeEM^}bfKf5kK>v6k^y!eX7LspO@z&@~F#1;B zMt48}Wd>~wheJM|VtUH~4TITE4mDqj_M~{&VBIT!Iqs>xNo2V2*1V~l{5PZco`e1% zPve0mroP-MoKd`Kkf877OH4h+m9?Ab9pO*Vd)Y^k9r)U>FMtAjpi(+q^MB4Z%uQ!(Lx%VoIHq)D0#J3Q1rdi*A(v?sH)M;uM> zZN}}09)+hP2a|V$(wKKlFO6T@wBry!@p96yAdG|7kJoqfo}=Br)hV%96B200Z$q?L zOF_C&qYqs&T96CNY?S5~;>=4yr~sMxT|^j3sfF~SW|*$TN~1h^iLNLmk5^(ADS63C z9_NoI4=FXgGD|5-R?4`#`R1q*pu%T(7iVkq;Br+OXAtjTMCOc2+#-&4(h1w4g_fHU z%r2KF8|2#!aygIeC^?ZDb-w)E!_6I8b>yFEb0@top4#hOj%0->2qj1heDnq3A@K zv4Td^PNVqfPF@;bpe9Yx4#S#Bq;4iQX|2$tf%g~+UWsWmHRN&3KHZaNcF_Co4K1{{ zqj;XjtG4bO*@npZ?y7&uI72RA4AWTzF{pnGM@x;E+WB0qzp^!tt8<@`qFsH9{KH7g z9Cqfr_dACUmk!9PD&~Nq^-ys*ZPS!l+SzS^C<$Z9_QxTO9tXGlV5+v?{Ge#WX{3?f9u zVV-=mLpz%ma@GdpHWq!L@;}x4Y2HgA@&T@H0Fky;`H`Mt=l&I!l-+8HbVp`% zFZ7PpJ3`mJ*Jw;HM=4gUcK#`GNsU2|#?EOJDNILpq13N4b_x=8x@id3yL1sz( zr{`HLkd_i@GM)%2{x_rA&!U1sa4mMPBZr}TA?-XUM;qV6efQF!%d}Lf?zUzj9eQ;! z>2Llrit(PCS~HWyT%D?4aL}u{IwQPEwe`qqV$~#_uRlg(1;-NBDfeUO*YsavL!?+A$q#65BmF}Bu&K6@3JRzp3bGfy{$%uw1)hN8>^_xL3E^yG-{(uUa z#`GW4qQ)@hPtxlj1=>ubjaThvx) zh>Y^%KxCBdfor4O8~DB`ufzBbB7B=b-(w)(ILJ{>hBwo8L@C`PZ15q<_i(K*wf54Y zHSrqGmr4xhOYBWgdEUn-On%6W_uFTr1*qVg;E%25rw#3>T2K?r!8qr?2s@OIt zw#|yoi=2Trs@V4ViU%RTGZFHep57|nI%keJf+6KHkw8zP|8u~vTmA0?esPrcwOxn! z#VEQ3&wqpvzpvd0@w@SR5Wj095Wg#~NBr*b6^9VN^FxSV+xH`WHS)Y0B7XPy;&sGt zw2t__sv~~C(-FUa*Ac&8=!oCHFfP3&_}>Qt^$rI6rGL5OddzP|5Za4|`Q0Pb?;FJY zjsXwfFC#F&A_JcKLYQBqj1m`zFu$`ynBRFJ%%rAluhk$-J37&%ypx@a44bbmy zNXdfqth&fPR0dgMR<@zXSUH2VN&f)!o6Oc3 z_8EM_5Y%r~8lrx$ggEqSS>acPP`_V>P`|I}sNW(){ocY*zlU|yFLeJKA%3|u4e@*Y zdlA1Zd%lJnBYtNiU%~*%50K)Z??++8@0<{_^r34JzxPBSejf|qQlN(T-Rk0X%#?@1Fk=-uDK)dH;Xn zeJ@NH#QSav;eEIK1H7+&5byhN1l~7eZkQjh9r^JX;FtB+8vuUU5%4DJ-THxyeznd7~cT*(bw*dja8>U78ej5<*+b{_D{T9#Pt=@Da!0*S0 zzX$M(NMM$NtqkzHmFB&GFwCt8_}vo%{NARaea9i%xABkHqJ2mA?MO`MZdwK!2fCZw*(B9(eUqp|3|=2J2VcIKSc@<29E*h zuGtsskMX>W8^z_qPh#MIz6E}qsqj-aMYs4{fEItnXz{lcoPJWC4L?72z|ZO@;HPFK zcsz+#fImSiz%^(ExNfEAE$rYSTfprEz8PT-n1UzIN&(d4OUv&p4cZSpJ)U zm!Woo|&YC*Y zKT%41iFB4!_dh(0WXo-v5c*Y*Fkzp_1qUKRa&%2Y8!-yV7kvj)etuUib_C zG2vn($D4go7hWTfUK5LyKu$1=7cq+{iGrZK76k5_5DLuGSt&@Ii$XT^;{-KA#7d&s2+X{C{5I>W0IOOrq20;|Wq6Qxs>2DUO@=0i+q1c3`g`6IM- z2TT=x(!I3l57)G4n*Rq~X5Yiw@a~YzUd*G-h;=|3N##Eb5%c{Y2z!Nc>rq8I#qwg7GP(dXuo>JVKrdy36IuC>QT-j*yFsyqa8W3CqQgTMvMMDbza| zOJJ<(OD)tGxF*AA@XTk z1o^ZkJD+8;bGdx!E@@ntw-*ZZkl;y<;GQ-|a8I{~xTpI=+|%b`^e9pyqo9K4qY(A< zkqGMP_7L^--WV+xfw`g$siz+pq@LaqK|Q^Z#s1I=DZwvhPkNevQ2m<#ek!8~*w9R-JOXIaQaSpn-iK<#fP! zW6J4Y8}#yEl%oG7<#gBofO2}LMmc@rmVZP!{SZ=4w~7@qjTP!2K+b8%-Hsb_PIu{? z)B8NOoepB#*=qZ9m~(oc#yLH6Oa$ljj%zum?U9_*UH>)bbaIGudc+XU>3O43UcMTV zm#?vsqak_Ob-lcNMCY7ViaM|7o9?2gk~MjG)fJQyZp1geW6-dW@lAI|@=fQXy!zFv(>u{DPT1ef zD5txwrJR22j3zMOkaBuwm~#5XGrB}vE?0MkDW`XaDW`uD^1q&P8m;7%BHCu#8jIPB zpqy?M>i;^Fa(e3^<+Ls}zt1SAw`!Er2N~sbt0Hyy{yl-9p!WrQclM~B#d&p^G1}@)BBms97#DHO6qqZ zsd)>NnzvAkj8gL!keaJEk74*MRb|7v$qcW*!$ITUc6-HcnMeJYEL{=E*m z?O423#M!-(D77^B+E4aU6sGmMDPBHo8=iPGB)FD&#_U!)0aXvS?3c9`0#M~MBRd`VsPFbOn&73JXsYjfrO4!RQU zjC!pXO2j+$*G&V(PK@BgtDy+yY<~=Cucj}$!nTM^q0`|C3bq+cQ5LkRBw2HC|L6<| z^ewKaQfadKF~%yI+oCZD8~?^@d$Mw1trSPz-;VD7XchyaY}`l?2z^Y@-eia;+)69Y zyp^GzzrB=UqUlD!j3)ZjjxJGe8 zVPO&KU}+Fa{TQ_U1h(PxZ#B3*vn0(z;NPhx7liti zP=qsX6^CWdNS3bPPhWa#HlfgeztDTTWQHha!V5m6RfiIxa~s*PraR*(!r$(xckqjetdSE=A28m?Q26;H&9m( z7iMOP38eF>GiJHjZ2HvtLFKupyk^q@>!DSAW+rr&X0$s+lrdSvBOzokGCo|-k*`Ec zX54JWli$B)4o0E=Gn|FyKY_HXcC#}72@nVIbWnE_y2tNEux8dC{5@{EWc|20?WuM% zsaYZ~%j69ti+PVl?}tr)g>+d@R{bYx(T1!S3F z&-!`j8QYD2R@T3Sp7BI0|2d5%5?ld*;4%+c|0Qr3q114QVW}}^cs(_i z*I$2~;rn4wOmA&8CpQewu}l4)7slc=hjM*mqOoDb?D-Z z78ZMK^$vA4rzSnY;1KT_m;(6?D};vn=*^J)Y-?NP#YS6Wy|>kkX%r<4e99TMI$ zSr4tbDZM${;n@_AUar)I^rt^%!*veZU6VRpFeaEiw$1PnN3n-R;6MgKnsX0gnF_%j zT%k^i!`{X4Mj@SaH%f51dH`c&0JcZP0-0E#v<$DXcb;uC2rptn?Yx+=mc|Xy7$;~% z%~4_!I;El$#L}=K2FuCMx7M>8mc3@b-Lrly)6HsM#X|(!@3hsDqFPUV0=k+yJddZ! zS4OWf*Un3T$dA_^Nc9Wy<Q3TEGsN)Nrx>>Ft8zaao2o;JP` zvNKpy0ZNl~Iy)Wjes`ZZ#u;I9Frb+nIO(W02yDPWN`3`lp;1xQ3_?PE3&Fqs7l_mY zA1L^>ey{_K!5~BxdhEUQfsIg^0|Uxf&V;AYw?%Wh5TYjC4I|l%(x7M~_JI6@l~?^U z<$2`-0zSM`vU=eQm41(nLR->Xwos2&ixt?pJUJ;& z2R*R{jgKFOrkYtqk^Op=Sy&%1AawN{bb({2r%B&5Ce*hJ^#@Q%e=AQF-fH*#)-WU* zvW8*dAeyJzr@*-EdBbpom9+n^#ylek#FK=#W+6TVilDo(_ADfm&$W()*o^ts!0N9- zs>sU&5nVbCwV;9;+sez;-5f+v=_75BuC^RT6hhyCF6@d?a?G9_i$}Q#@jPBmrp_)` zrp(UHenh%JF3^#OP3O1`Y3~K@oa#Zhd04kuki@w2R=kYr)YRzL2`TNx#|QL^fb z#@+=Y@n7HpT6q4;p)QoeZBH~I6F0v-nO)7>Q%vl@5okbx=xR$jnU`ZJSIjmZoU{Fu z`D9_WSI0NbOHOHM=x#THhfnjsVY3=Won#y?8XD+f^!rj}y)K;WQLHzH6JEIr6FwH* zK%5TsNSvMgQy{SiUc&C^pNLSR)VeF$TZMEczD57_SE1bjKc~|K(9b}_ZIQE3^)W~z zU011-(Z@#b2`jZYzc3Dv_51Mo@7DK=#h+w#ABC7J$ok!=H@q*FWloYFC+nNEr<>tv zl!Lb7?#EmB7Jd0Hb{x(6JwpP#HW=VR7C?Oq^v=_F^u)m`&Cr`}X7k zhBW#C1R(3tDu-=#rMEfgeCE`lKV`GX@O?VHl1UMs{im>b#Ac;pCT`B$iK&tV2c0+x z2A~IM0{f;b##7^1T(>Sj(VS`oiG|M(htESL{QVgSkol9KIFjUZgU+YXS#GmDDz!Ul zJ3g?fR4>0`t*JRdO=6`60-ec$4^5E|dm1QOGbOcI2* zjI)&lL>#uj43zP+5aKYdJRT;1vpDz8=UCtwk%8MFa7-w$c(RfJX;DN1=SCzj z>zV{kzAk}ilOmSEnC-D$bVY0X9yKHMbxpy&0%fT)nWeoo(=bINNlfFsu@@WoaHFWq|w8;U}6 zQ}a)7ZgLibrV*-Pg3sL&l8u%;;R4;x;vt=0OWJ)F1kr zkvmpQYc$HuID^mE9HehhS~BPqzWRk2-%$q!YD^t+ubOc{ZsvY(FdFMbN@fS)&HL(m z#I)Zdd678k_gF1rl>bA|Y&`UhOK)!R%pM5eT@Bv_^*db>!^W9$#(F^bUvo;Bm`iX^9zU;Esno zbN{FPo${v!a+sVXpWt`O4&a$+8=?CdG#2hT&}dsUa{NuW$l=XCz#BjyOWueyj=$Ed z5_;6>7>@4uvQq`E{Zb+FNzjz7@N8`p<2B7a;L*@kYBRV1zn8Sg@fkriiGhppyW z4AJ|)x(%ipI)HF&mJHDGHKkrX4Z@oLUOblFKn$STXS8SCY%qAW&PA5fy6P@`h9R8S zEV@x>3G>u+)A5k*7TrFy7+X97L#lbwOpcpctplrhYe0A&Hykx<(8_Ug)(&=Rz)i(Y z`71&GQm_t`EtUAPrKP?vyHvHmjrG{1W?z*2pC5cwW<=kH$T-sBk_`VA_~+r@0RI6< zM=$(S_$Rq9^eDM6_P~|GmBRHbT+hO_7p}c$^_8!?5E_ge0C7f9of5`p3fh4qM2gLv$eUI}S~l@NdR!fQeJ zZpTFYZvQ7x(zO#=enWL~Nvo4|tdmn|tWGfS#vUvOxS0a~jd`XC#~boZ@;O#|->}mA zV?@-LHa*N>U7drFtQHy~LT-!*2Z09b?3_vd29qp2kJ}GJEHj&j$3Y2vUT$ACN4A(@sCc@PMSM)c-6$XqKc)0R#<>1NW)NJp5S z3`!QgJsvbYw$lm^GvL9$d)bR@I+YJ5<4zl!cV}}54Pob4i-^wR$s9i85cNH&szszC z84t``X;D`u(pegitdxa;Y$#D^U}=Df0Lks{RG&#vpGj7qnM9NHfJn^ZEG{Hp<3?7- z2|S-dJ-!&E=@#-eIZv8hMkB5^P-#W^!ghlIVe z6APWf-e+PmPPqGuJ-K}H>RU+_RL>l<^-^UV6us#a>lNr72aK|JlJ#`um&k9qn6Y`` z(2pu13c`5ImSrI${zrqQEU5GJ1CE9CpV>SIF6ksYt(lJN?~uEV`Vj0-)rW2vx1%G+ zZQVb^OKX3H+;uns&4ZDDy90k7!=FVsAF*u2<2H#i)4_=ra{j44vk9hG*=x48R{Ec6 zH=Cep%B;<+qA@@e6plI_->0{{!%nVAtyqM)IQ2_?0#m9xaVz!8@OAUVB+}xFDoJk^ z$HPAl|I5;wrCeI^uD0mV=>`D^C5a#40w^YL8~*s8P}eLWC+QQ6HAHUZNsRw-(jrp< z@n(R+TMqw^{g}LM_~XB6KjwEE{`iOO#~g3NpEg^Mk!h~QZ==f5 zU6SFItGkWbp^}-lZYkDfqE-K@s+qPP)cD&Pk<pr$h9+zTLVdJU#SmME zlD`aE!s=gyTEY{ds^7i>@3aLxWIvkK#N__5D^W<|yipPlDt2weY|W zM9%n?&TOi0|0lS0Nhc5`-CZ$L`-Fqux0h{iZm)&+#KelUko%auDC1ONMdJ^VdabSE z)0xv*xaAI7zLx=kAdM3}_Ok^pkUYB!Tth&aD=uI|)!=`S-Eao~)NPnC`06AF4ZNj)4O)(vylt)KA*fQ&LAx|R#y+WU zv4Fce9m|Tor+KnXW~`?|G#+*qi#!f2)+=jnp#@MbuA9n~DO#F7*V05<{aHw>YrPgEV#xxLSu#t_(n#iA+5##~EU7lLWE`#^l8hzcWPAkgLK<%MA0|Z>>q&NdT&_-3 zNvk9@4r}1EABKe73JLL#4nOh>#Awx?D4oNXqZ*PSjRfD31Y$G091Tli)J49v&^H=x zrH=Z+gg=j?HG<`Q$J39C z;|hMA;T3*^zNJ(tI;+@w*<1}yMet5walZ{0YdJB2ma!AML_BmH_rsz2(U-w#`ws1p zm}^wqVp469Mp&<`j@Q)IC{%3y>vT0&=G8hh99*~h7W$j#Syix#P^Qpn&xfi4RMceD z{?@Mv>A-@Up-G7?u{=vPtiB(bn*g5}UR>y;rn-)GFQcCF@xJCVSP(x(B2Hv^{ z8o?ww3BNo({N;D**q2e4tdNk+4 zESa<{`3lhjJ#5n(w(V`yPJ~DM+RfN(R=kL_I?MwZs`am+cw5_~u{5_XG#P5@;YYQh z_U11Po$Efs#ZgtpmFwzYA^mYZqr~n8g>g7p6_n4#;m(JNNa5u-lpQmxyCq9u_{`r) zOrs>N^zIjt2vpU$lp)?@&*MDASgJ^@PM>@iqfbsF**f2Bl17`Dz-SZ2*eoQ>mZE7i zjJUN~2Vu}NIK}bmbT1Bn-ZwNzM~Mh(>jrJ5LyU$29@}KuQV2T*QxBsr|1+-sALwJf zi+9~b4ij-wF{cZbq-^K{$u<3tUK7N~;uUtx_$PZ}9N(iK=@IX zV76)*QAUTy*6G4sR1i9{kq^gqN-Hamt;3;#U_d1L5ezt*t`9|3#6;|a_ZbDOZn zhEnZp%jrvr)wdp>FP0#TcuYcK7PZpxF@fpOkrNW>jse{sgslv!>hR{)wk^ z4f@Se9DMg;vh`y+b>$|*yNs~sx@S2|gJdBEX0p(nS-?xtENd-=1@CfDhyLOE4Z&|c z$}2gX@|3x#z_F;Lv;=wk)sE|yuaV_ydLr(B%$Kv$ju|Zj&>vnI1$o2=To;bPbz%QX zCk&8`R*5fwx=7Iu#CuZC!gr&jGlQtI4u!?%bh@HZa6y76-r-b}Qne$_7;8;Di~N!* zZg+Z$dKWq{V1b&Hrr}#&C}(CwK_q**>v3F`ZHvYz+4S^z#57yA*cy)zi&cf>ypA|& zM%(W&y;f^qHfI#4U@*LbM$r|D=4Eng4F00beGjppVcvf`u$9N6>v1-iq2oF;;CQC}AX;q9u zY*^J$c*x7oMUcA~*lgW|!|rzqlB4pZ4dFihL+CK{$s44lGG4kL`ua;X8tnl-j~S$* z7;#q9<0Rx`QS(Af-*gHNw52`bSQfeb)wrkBNnu3M3}lvAfrSI}{hJC7yJsLB@Rh~Y zj4lxMx9f80$u;7874RPBpc8YDp|F_=rj28(?{Rf6!u3(B&3ubDTN+1A&tWN=!xPA+ zpXw+X-$y7X{K0M}=M{;!_DiOWzC6b7AP;o^KkdBsR6l3I2Xjw2vLUINHY!ZN8h{o$5GW@@UWAXG_Hcd_(=g%XVE^ zWTVg{??WChX~{a0i_v#d%hsZj&hWlSCx*f$k!Kh2!75^ZK*Im>Fw^3F;at?o0MrRs zAFG41aw+o!nu@M8A10ce;kL*PoLE}4TESI>c#P27iHiZmjk@Z*7M?Q8(nupT+xhJ2b6O$f3HM*auKS;Ho)-q{0Dr9g`WONCY ze97AbJ<%%OVqJ$JP&}L3F|?7#T;tU%*=y8Ty^bZPE%QcrY%q zr!J8P3+lwZjfeUEgG0iLs{QZL5p9dpLa7+NB`tad|3_T2rKR9N$;$KTw#n$kc#-Ej;LECcDXrEKNcI7~8 zL+BLiH10(o$7;V2H?*CneQ?uZdH4*Vhfn2L$<}G%-#nBS2S&Y#Zr(KJR3PqG36Wy zToO*Uyjpi59+UYufidD6R=6Q0tl*yj?uTJD|LVld7K}gsJS(l=KhTd*xmRsSrZcFo z37@+`7PdFFC4~kpT}*?v#`-}h;y6?INZln7Ynb-843lkR7m?XDfIha-E?=25Y(&!c z{JS>&w(^rZsi#j`VFYSYsNWB>jwDoHOU{w@VNo1qmzs?pOs{D*^;h(x16ZSz7vX_5 zJ70$(BrD?UhaeQQV(<4-XoR=k&EM~(wiFy%c|}@tsq8%Z-ULd0dcqsOi*w}SN^A^# zGrGR|OXfqQ)cGv3PWaLQ?*Zu?+@?s%QsajoGDgcl-YkrZv~;}y&24Q*w#!=%hK(g9 zn$F4PH5-@EQdEdaN#~hz!3s)QVI!>eGvlV!;BEcMD~Wg3X-h6@DM$m4@{GemDH)d6 z!rwQ&g65Joc5|*JCvCATV?|Edz1#W1epvSpgSchO(B}I^30?LYHIG?}6|)Y9Q(6YJ zWF)W1QMBlc{H>sA)`${1&Kyl1yj`9AcRo`|r+dFglWs$sZ-B>=tod!4x2OH^1Ly|~ ztFs*`Hrk_He@5gG?A4Z+F&-VhjqTV$D=CX2cNg->G6*~)1~s*&tjIY;$HE;l%{nx+ z*+y$LJHv;B)xLCOzCt)w_fzU9b;OgB5&=PYXV|jc^4f}m!$X_tC3N)J6Q{L>B?+)E?wr-6v&wIw-1?hjJ#O{=p9iMc;3qNm&+!q|QOwgHs; zrmZRM=M+UgoZ7VjEgkfkW*}yEh7XrX(uh{!MaWM{NjSNrqt56lDtq9R`{2_dku;OKeSt+v<%d zWRxokI%N2W<>%0c+Xiy3Y~x(nR?v+rhryLjAa0^F@yjC*P8IjS9WLjUdnhr*WX<>O zBRlzLF2J9na(;yTfylu@w2pa2xC6QV;iGfEzZlUYzoR|I^zo(P(obk`j;HZy0fxsy?>yP|MbBJ}J$U*KlMD}xc zQRI_cAq)Jtk;psb`xMP0MYi)>{^^as@mrexi9Eq?Nfk#P3>A@c|q_|So*U!1)oQ_Pu&QMF8NI%BX>^b8Ht^DUM9X-#6_Q0%3~{&2DgR=HN7Mo z`f&1y_Jj2Glvg_8-?Uk_asUt7DjRx#@`&KqEt{dJX1^jiK>hgWwRCbqsZl})S5N8` zD3O|@Y4@_ooQG%_mzZwgJeV5>NIvvECA}bfZd_tc(v#-ugT5)R2)L~-}k9}=f=ZdMx zOU^5&o-gwJgW@5*N7|=0ZC4Rli*et(S0Mz%eMF%zFN=)$r?`-_py{aWUMgjH!1o!Yvha|m zqeQ?epwXA3LiXP%{$qr!7iR}}16v6xP{8`@mKR{+pv9kA_k z{zZrA%LKm5@VbuW6aJ!}4+HJW6Odecx_hIo}dITsVPv z&Wc%W?K4b^ceR{HKH)Ty^cWV;Psmy}Ulu9YAT-t$Ic=e_Kq-nNS+>!HV_W3>OfK|o z?L(Rt@9hlrr>{54D0}A}+;q4BT~k0Z~A0tzs={qGGz1g z{Z|7k<~uOzTQ!lt!V%VMmb4VehrALhpq^)O>eHEjx$-Fm^-H4$?^`)AbP0N*i_sG` zZIhY53=A-TR-csgg?St9w%~57xeeNBzbyQg<`r{WXb_!q*%?Us;U6uVXNYUnq}S?+ zoinyXmta?oV4BvI*&|X)T6S-4qt`wuKfJ`(ZlAewF#1FDYoRxrUkP0@IKF zviUQ4*^u2WgI}a|+bx@0e$c$uucP0OO$R$^3HO_ttxYc_Fa3m8afgSGz1q&kx;xkrB_D82cQGy@p~pBDN5e+A`$;f;!Q2KeK%`f?NpN*8dqgqQfhb|CMg` z=PsjeweLFC^}?MpHtB8|(*iC6oDN6={Ob=g_9;UWm8~`NWfw+J%06icdPz|U9+yGb)*a&zYup4j~FaY@*1{e>p z1Bw7M0X2XSU?t!#z$1XS0bc-;elKGRfEF+jPz0C_@B$VA)&TAXJO+3f@HXHhzyZMb zfK%_1vGW0XKt5n5zzet*uoiG1U=!eZzLco%qm^#7X7eO^VC&lOa7eIbRb!5s`K zd;x_!s0g?`E@#kHMKrtMhkS|=?=K6gk&g>Q7XVM9PJ(Q*%j*g_Jv<@uA3rmm zQc1{JxnO*y-!IUc>nbbUNSP_3SC+3{;) zHJBA6!;Jh(#EQzQae~Jl_$$@ZC_h4kXz)~LtqWn`Zb^1#k)qgD=?hdTa-H5Pk4vBx ztFLNb*joiZH)E5)C#tb|u8^X@6{_)7ezb`s%bIX#}aU_?BA7jKrHU+Jrz;P!@G zo(XfKGBcsXVvPw(1n_W`O-QxU`Z0=6W%FQemaG)f)I}ys_GNM=RbcZJS0tI1D z$nE#I1knfz@&d+(sNFl!!X-MghBupd9#~d94Eidr6Y4=*0g-fjpgEzbh!V(Ey4-cH zs+__}gv0%M$wVxSxSu0R$qJc#Vy_Fu{x#}LzPRaNT?)1KZ+^$pc{pFVbqgS)G<-NsIbI!;x7rrRG*?c z;F9)HL9zV?kt0Qs&*u?kLQ+Fwbe&UhE?u;)gFnfNZQHiBV%xTDe6elYwr$&3v27bE+>!qq@4fXVs`VpC0c!AdxTR7jpjgC}Gk!FY3IXmc_*Fa)Sb&2w7C+3{d8< zYjdxnQdH%%F&sjnDIwf(iF(m>jT<$^={A$&RK?F#z_-miI}rbgDZ&Z&K)MY}W0B(> zFD9o->z-&8h&q93PZ+b4cIOnLKZ8CJCzyw=#eRq(r)M^ezAm3q5S3aaQC27s*XuCU z$u0{NFAdG|H!8;x{mK_8BsqL=B7~PLx5wi9sTcqI!7CD=OXPxT<%E<~W77=5qef6d zNRq%H3#@${gn0lzd@J7l*Q=bs<(l;_;&4NVaaAQeMh`K_X74|-Q9<6}$6yd9xs5-MyY>qW9(A|v`bAF9sLWjl8JZ3E!aIWdGIQae zZtE(pBRB7Lr4G`8)+JyY65K-S;0D-S`L0NR*M%Ke(#0o@he8-U{zB z9f;l235z1rQ0pcFpP0OS^ncAry$d}JAV0jik|B@qYfLhSKCdx?K^wZX=qGc?1{f-jm(> zRUS4(2*Y*wYf%hb%xDVOt8L{3H54lhGu2>rq)#0~+T3F6IE0`D<9Trd>S__OKENz9CS1NCS-?b5Wmw>RHgv z5D8)^gLOK1&uS|4Qfg6``+g&yZR@BY(4JtO{g<&wDu>50G4C$!1hn`sAqIDOSDKFb zJq36cFPH)K%TzISCC|8U>iAe|3*ExMZ&O0rsj9e{@H(L(Rpd91|Cr{OeOqzd^Hnbx z2(qwq&<82ACOq%a-{RvG>1hLoH*6>^`8Ql^+dxbjA#L_ri3gz`7Yu-lt+%7(ng^8d<>YH^%ZXpU7m4C7$hZ=q)4Mu#rc^K6C~b<^@Dw4%rFAzC$Jm^J5tWev{TUi(z3= z&X-Y9$AV%Q#z7o`KkT#SszVBk?A#G5bC!7I$BTd@m9RGnN_CLF42QBv;+BHUE*goL zW~{;{FV_fChMV`dDvndTzhsu zkR9uMrupHJt5ALdThM^8Z)K%mrm-SUnM8LOo1uVp5ZSo)0ri2ZA!G1d5ab4|<_?d+ zBcXKRXosOlbuCp2Zps0vMF3*ZbtslbiZLEZ#9*oQuxyGWp@nWujknw%=!f!m`?v?F z^XiRp7cF=WU-s#Wq^bR26eS|u>BN|qX$SsDB6gNiA zo;Ga$>0<~>m6aF=s(V%C$=^rqe{@H}+~N!;Ba{^b1NKWJm>bA@HI9#yjqgH8N5@|boBPk3f_;8(-6ItRZm(Stbqy0fxM<$+^(V1^*JMs6RwMdc4 zd5K@<%sm3t1DFBTVL8*q0ASap0evU%1AmYQjzcO2|4rPf;PK29!%ZCAL2lC-IWgqu_z)-B`DJ#6j9+yIx#eIG z9_3}DfO&s5V^#*6LbYjUi3_B`hGE*4>M!YK=&36bz0MI+k7sge+>bRtLo+>;Ncvz< zuTZmYD1n=KB2R%My=amz6IOKTInAU3~e|$T+7phK=Gd)@c8^OZ2Uq z2m^`{PlzWh^p%iDgz@}fkry|qF&R4C{5TVB+5*~)W7fq2$WQ{;s~C$i3p8zlmb|}@ z2Wn8qyb@K}e5-VEV#c zL^n*AZ0S9KFv-Oqda0b_G<+Z@Za}TN?5~Vt<>cgpGbL70Zlv~mkffY`Q$U4IT@6L< zjC;xc0|*PNfd4w4oc|(iQuai3iQ_}+h_0TyZZy%USa09DNW+1Iep-@V1>I-DRKwi_ zH67|JuFy{DtsrO&zpwA#hmspz!u=B{gJ&Y2;Yk}f8L9c;VP${{ zoM|83z0U>uFc5?hHGgzfjwKldpZLl5n8`y`&MN4LNo}tN?k%Y2BCc?JTs(=z%{CJH zy2OkPb9r|#%1piV*##6a6unx<@L(b4X^6rn=CilkF9MQ*S&?DGL6z7jo6eK%p^^52 zR~XEffQI|0)f(t)9D^&s7j(^!#KTcmRu<6VEU7vak2+Fd0jiWHSWZKaB@PX1UP~sG zuEY$1ZUp-cu1(pe52_&vm4)(o8ejaoMyB5+ePo_*rl$*+5jaU4Bk{qcWh!EpESRJ_yOrzTNH zY0IT)pDnshcqp#F>li7H)|c+Rz^d(RVXOuK>`m7jOujIcsIVikQVWyLQZXVYuoY|> zO3T8Y-6$5YQ`w2oK)oz2Efp2P*<1GA?g%ntN<=WMOx-G^7{JE;Sf%wxATa6Lc(=(~sNOpM=F~~T z$sgxuPoT?xK5P5dgxqIS(d``4g|fWO7?Lz3x)tMR@t>Xe_cRCwp@Q1W!+S!cT}32h z9h%52Jp6Ly<|C*%&CB7qSl*%X^ogh(w=vrKEw#iKo0EZC^Wg%Zd^9u9wrs-NSm!5Y3Zl?d>figG&& zC6Nn1x)^EIJ$>VqZz|Fows^-J_z%QW)n9hiUg8u-uX=U5b2HBiZ`mseWIT9PMULHY zdqw5po0SloQ7D|losN#SnAz(1@UVe%uOf~EBd9@4o&8$;eldH8chw4~R_vK{Nu>6k zI0IMZT0cvqSr!2AxMt+@qxkiu*bUatWG0}`=@RH5RG{5ak!`&3JVhn(-aUlQl)KAK zK4x|sd>h0@&8B(}pYQWgA%aDMt-R81IGv#9a_P&KbV$@k;kRsQJ@oZoU$I}k zA7fDCACAIZMVvmQ^N+dSn7~L1m~ECuBv{b{-yyT676TYz6tJgoaI{`ze$3TPiAj1kbGpbJvanB7rK0#Y26OV1AT2t3AUa0g>aj zW%Ao?1!{ltE6V+NKK&?XTMw|-zFH@Lc4U75-ul~KuRqA2v(v1rD;dE) za4Kyhlu-7Rr>2B-s`3o^6_x`+e67mLed?ybx#W9xXJd91wREm}e>yX4rA}SiPSY`S z(BTG3vXGwbv6KdMzyC2W;_qf!Lz$z%xg}WH641;T$T)bu(Jm0a|4lVVqAd_+L9ip7 z&wE8l-LFF;4^dGW$heRIX78o0hJ*+x&}*-pxIn^}930T`pPl5D94NSeQP7SMdkqrf zK$&TPDn-*(;0n0j3q~LSfni^=QeP!w%y5_e(2SSn#YMyZ6u(h$5$e6;BNdEq<=3EwuQNL=Aku zv|3ym@Lx_c_5LencM*NG82S&fEp)Z`loWH0TDY&3*EpaI`YO85t4E5@ZP$Z+ zH}15zKGj>X3%9$7ST8+|eRzU{_e|ujxXoFl#qhJ9iBZn!_A-8sAS>sdB%1w(Y=npX zpd`88Omut=t~sh(mB5G}bfI)&jis;JZ?sg>Oz{AH-i9`A{H)1rV6DC3gfUQh=qhd( z?+r|Qc!|T-bF$tclBBJ;*KhNWwxiY%$57{p(NO+H*;ubm0k%(#9&OjbCG96S>mBDN+7A^&!&dHfFI`{0Jv2nfJ-~ER#Uxg>0 z2{$J9P2J%~Nyk5gLA+EU0D}9%b8x|)Pxhgs$Va~>9unbextQsl0iW(tsq6UJ0}t7^ z0<&*j41@dl_y@Vw23>nSM>*}KB*Z0nt6R(J1*0_ z7qUsYO+RhS@VUS19z0`vUx^-P(Z@ZHav62VX658y?5>0WOKJZW@fq+Od30T+zj^X` zT))LGVsUkiIoQ6)qeo-(%=lbC19gN9B5u`xc7kq+ zg6xETD_ozpa-W=Sx7G!OP^at)nK;&`U=#jz=~FrrTyO$fWK@td%wvN%F?td;wzfEb*Mn5OD{qt^BIa-*hTjq10H5e?y zjAvC@dYp~g#oIpc04qLv{Lqgrx!Of@4|L{)ml111PUCFhww*Q_cHCwfCbJ)S>q0Aw zx+CTp*LW>$3gQm29%ns-HRo;E$3Jt)04;5HlHZj{&ZJ3|OaXmQ2k46k??r6SgU)xa zLr-M!W`yDfx+CXX%20}C3bW~jgNqd>^Gg>|bCzmF1$BWH?(u|qzqs-(?$^D~4AmWE z+Qa)@^>h<#*OJBl=B0kP+NJ!}U)U z(^Zn_p~-=@l6%8n_nPKs;%%AF|9;+67j?nEZ!HvSsWsQE*GYPCM6`_*=`?7EthhSy zZ#0IU_&Fu^u~Mf_P5nS6yf=wxgPl~4Sd{ONKBuUX!=y*>ZqzQFA&Q}Mccdp=IKRBt z5xt^!pe10W=-@nRZdVrhl6#%5Nv-39V!G)jlZN9F6dJZSq9)rDBz!0OUD z zzLmYexA`vaNt4xggJK;+H!($Jd=5KI$AWT>wnoZ^6ZFU(V^7ZO@lGm{7jOVxX+?>( zH@88`q`n36@m-TU79{f`Y9Bgqd|St$t^YqMik1tE(+NTJxB=P_{%6tqMzJ&L8%fh z9etIWs{)kJ)fZPHRXj@pXzl}e7Q6$6aL+?(cJG z?_11=d~uc?z?~lk3TaN5U_=T+qYBOo?0=tZsrj{{bR zIQ0WSY|EKl3g0&2-ZB$B@L_g>-a_hcebs3JX#tznq%xB4I`qx@Rq;=(Rr|#P72?M+ z;_p)S?LrtpfcV0{Vla4uo{f*uUrP3M`^^F!{E!%_f#yKqfJ=K|7>W0(`duQf zx%*uJ+X02}LTy6d68zRBP8%_`VANs8J(^)og3~};0%f%$w)u?$Upin;0?~kU{ow$q z<0mwd@sk5G`UcrVyd~P*0U9Mc1fGKu_e47Suj)T*u&g_jQxH5LZ-_Bp%@N!Gy#HXl z!CVUU>E$4rZX~Glr%b&!0yo{K!WssyBcx2o8vN?^rDtS~N*kHgv4YNN)Ex)c)-Q2f z>9A*Jj7}P%(*ktH=nT;t5v@tEhv^K?tXZ%JM;aV171?rR^d(CSElUhEON=~C^+ins zrcDi0)tz0B^)YD@WsEgwGLPycteGZFJglKQqmCLu*pg8PHrjEXB_SiP6iak_3@4Vl zB82Fl)-gv;7g2TP9@jNas`@b60>mo9Y#1uUx2kaPwNyzig=(I>WaA{Q`*gIYX{%^_ zuO+;3a`G2)X>|V0enOn0yzBh?0OZ6SIB{K(vCXb`{tIPRl&%{-#n>*H^P5dFo`$*k;^i1X&eP@ zI}AiKijtFUJZx#>-;b_43YHNPufq6C6^X8x7WZBI((oNAy=&vaDn8vr%ueZi94$%+SaA< z%yB+JE}r3TLRR)xz`Bza^I|fVY$(YwH|V&`;|s^D+XOd~m2whFAmClQR2vhpzR?J_ zuNtm3h#;vkzUMP|{#3gslZ}VF;;8Q;Su-FXg7l>rh9sk7N!C*ey&EH6M<0dER#w9y z2VKTiQ+xyuC!><35Dv$^g*+(PtrsFgpoI+z zB$tp~>%p9w;LK-&Iw{Ul-*8@ol%ZkDKiV?Ste$f-ql+2AadwC`gjO zuav6fs?_~)@RI2Nd6Qd0<}_h$T=jJuoe0ZUJ2M&SKB83WgLTZ!Ijr$^kIIMT5IBw6MoBHtsyyjCz(^mxl^43h>Sc0J;k)H?v{T7@c8*0M_J=vD#i1C z@H&0)@tYICY<~a&aJfU=fGA+K-Q+HPrD_1=-Cb5xREWbTDkSQ!fd+PU#wl%&GiHsSn|q6N5Bx3DE}b8Q zKA7|u(Lwv@tS_T$&Jo;P;zH4Z)T`QnK#A3w_8Qk`*JzY}S%s9Y(TQoef%6Kw98isP zhjL4(j%t(Mk$UA_;@{KX$Lo2;YiAGdGcCzECjt)weF2v;_{!q`tUL;kUB*fxZVMK0 ztHWRuL2^q)NnOjw*JwX-!`gTJIRxaN)*|OJ51-K7wTnk7(Y&XI*|v)VI?`Ii9&1ga zawi1w;V|I-gn8f+?6XIB=u&m8M(oKLx;KiSkOAQ?yS2W0*QVt@8G6D;e9J|?c?rV+ z^kDGWsXnpPWex@%TQ^8ab>6wL?IPd6S>6R5pC=!*jQTs`Y z5beWXLP3}~#}{SW%=&cTQ;pX^Q{h;rLcHL%l-o`Qwq25?WgG7PY(4DN1b6{&Ik!Qz z;rga$9p2Z;k@fz$W@&pQowsglvJi%Tv6RHWM*O|rbS4Ss7Fzc4LO9zgH1L3CvURm# z=X{0FMXGkNt9OjPVPWO`^X}1vpwZQ<;@FGzGXDT?7q_)T(XL0_-Yekyaa1thCQF=5 zNKjf4_Md8Z-D^gV_=fkUX?yuruuuKBC|Z$hLSu1w4ZdsF1DO4a&^@K&rE0@0_&9Xf zH;cGd>H|FV_`GBf^7Ya??nM1Nqi;{$`BhhWz2&TXp;Q^pe)4Xg+@UlPIBaV6;W2N&HYLMCKg!CYP<8lZ2j2XG#az3|8x8{M>+kKoAnifS`cz!t?&E4;-r1 z8s5M8Q3ERhnf77yar*W9<@!CK>cj7<^fmeg`z8PRP>R$KjnV5rJOPyj!_k>J)C1)M z=>m2KzQx$J?Su6r_0yR2!Ww_k@lo4Zc6<8YfwViw4Nbxup<2Hx{@(${aAWBH-oP8I z2=D7+mVylYHw!uP!{vT2xZ4Ga1P$oR$51Mn4RHd7PaMyCR=l(x1icYy708d%E8Yu_ z>R8D>C;SijUQSIfDZoj2Ob;osW3=P?S`34fW(Z_zy2~1`tUW!nU0{8(0yF!sE9&q7X6=BSNQgs_%u*F_VB#*_&>Nx&d|;iWQQw2nv{vU^L~PC zk>fj1aq0!W%JGO#b%Jo>&pJta;3dV`Qr>2br9yj30$vN(Ya!tlgNpor_St)^gR3Kh zBat#1CEAP5i;j!aCEF!(GCS#9GG-a{43*QW4}=d24@{GMlX5AG)q~Z@)gmj@)lVy} zRbEx0Rbthp>od*e)@Yk5Ejt@IEjBH<4Y+|PpSFcO+X9(abO&C-<8bw`-X9_EnY7}+~e0f`CTLs=a>m{F(8buw7F3lAh zE{W$a6*3jGDm&#|DhEq!F2x-hK7sGDPkKvYOOzR{tUHzoO|5xZSUM%wlG`>N5YF^x za2G`Hgdxs@B*O6qB?di&#%&w7??`=<<7q%B_D}*f?Ex+1L8@qMB#^@HSOVsB@T&Pi)(8>9M$)D~(_>DIf z$%uRBBfI2S>Kz5&f=^KkHBJ@Xy3^me?{GDomwB|&t6x5wnew0JLp{?T*RC;zpQhac$|)t%}+O4?^W5hh+kJp4#k znN}C{HO$_|9OnkA-d32bqFv&jYFB7i09pW}&bg8%)HUsvx+}g-;ub(&)7KUHn%HLa zGxcTjv(+W_WpAThon6aKJ-}*}qlD9x+t%T;|1SN2AemoS{e?-LQ$eFFtHzn~Yhrmq zt3TW>nJHPQS!lTitBgT6NO_%;66W>IO8Dq+>L?cIIE z7`b@f^3T+#Z^M>#EvLEL`l9a3IMcd!>)X$#@(cO{Xp~~qcytG66W0#fMRjP6kV9fZ z`G}!dB^|QeN4#B&Q{F_aT6sHEGcu3#MGQJ8jE!4csi0ldiObSF|C!Dvq(-P!;w9yp zdRwl8@m<@;-?yYk;|Jo)=bilNDC7plC|YAg`v8WRIhyS#O>!QsQW{zscu{E4QoLYA zTc3`V`9h#_%d^BK$|XR>YPxZzMO72Ksx8vUeC&|e#fwP^}Eie@Qc!`!KlrsY49{HjO{({ z0P~+HJeRL)9p`ULwKIex3iF2c36Tl3Bi^#&(&QcL^mApEjB}i2kqYNzQ4^&jp~>V* z)AHkT)pA>v<;qkcyXt_RjnZ$;?JA9G56wo6hn!<2*u|KIm}ONfbOG+|yzL?%l}_k{ zNoP>!;*PhDxNFsIuBKg|4%uyjv76<0uP4B=-Tciwb0Azbr?EOD<@X!{qqhx*F^1Vv zpxy9@#Ymh3spT8xfmGR9peQnnroTn8MYRR4^ZM}d{P85=y3@4G@$#|UG{jWsG--idFd&;)T-6OLeX$@d~r`$$C~xoK3M!^p(rzN6S}BV2jdaZ++=z z^E0MvYWIB4R?p0L-j~7$@^kDJ;>YT<@N@2^MT`>xqwJ_n+ygoRdz9Uld7x7XlTNwn zF=b_v?UBlyQ)W^vm74<|oL>yF?-y?O0DOhbIsCF-MeXWmUV7-uq^3dnOnHR@bmC~@ zBRQ7pr)DePTk5UnUg-$A#1qKbA!tD4x_ zbCXFc@``Q~d5%H&%IvqnHPE41q|RR3O1+%9iT8pp#B?=fb6ot}?jGwY^o=T>qOE+h z5L<{v^hTpInNEvs&NZb@D4pI<$v3o5hC$UH+#qjAFP1KAm(}Z({ha+8!<>5v<91r~ zclEFP`kH&_oyURdZQ-_ig+;^}*5Xx(SDpeMqYaAV zcbO-zQYzygf^pi zAIeR(sJN>TT?VZ3cz@eO8GhVMBpH76%~+_I;V zFDEp>~ux2eb&+Ff_`=^RA9TrTjM3ys+U?Mx0pG{ zta7e)VK={%-z)Yb_G@iUo(Ir++I+M--C4c~2ItD-|4)bKk0-^nea{|J;D$cCF{Y%x z-V~d1|AeOHZN3T{_9`|$ldoaN^rzW_+A)b#PcaCV8_=bHZMijfaO1>c64p^;1!bK{ zB&$gVHEScQ6YKKnwpKpkh!wd-_bG4h{PSY;V!3nT9DP^ehx}@dm-tIgV5~8Hx>)vjQ*2feO7cePD2#>{py8v9TRI$xWW8ADN0%iD{c?t%JEEOK?WI zc(o|C&|x>x73?N#GO>%7wRGA-z6 z%h|uB>|*@t+`QIP<|mPNrY~=wz;CQCrmvf)i%0Co*nBg9>`#Jkr*G-E&rB=e9I%AH z`~rF+%a~<=0sb!<DZQHe7G)P= z$Le^!>DUn>`sX(@kL4J*nkyrh$zNZjPG8Swoq3qHpLR~+n#5TX6wSUW7;;5)m@k+d zJ3oo^^s+(kQi?4dau(7WZR=G1M&-2DHP^M)h2r@F{(wJqlg`f++k8svDiv=MVv=`- zvnf)iP1k&8{j&CL?ltn9a0R-VdRpq+P<|;>N7=f;-}HmryU1sxRdBxH2VGyJZ^{Xv;Wlg-Zpx%1!0WP}w>5(@{ooM%Xb?wL~Xe!%ob+ zP=am^zZRh0H^UdsvH_A-AJ_6m>M(!*}_u*mU$UuV%Y?DFA4f zYSd~}TMWs-u3av$tFvTof;Y!sy`Jj{jPKL6$y6=DuFNd1Tv$Hk;o`5V0N*BBL##b_ zJ$F5Gy?8#ie&_i@t>gI+Bwog_iUxi}jm64kCQAp;xL0VgDAA}B+{S?SHGE%CwyF`+ z`I`T%djoqwd-#YO1U&|%b59r2fG=tJ7h_a=QNEA*qzJC`ZfM$Q*+BdbM{Y3g_$!fn z!xO#gj6iIQu7`3u2)97(#39-Nj0&vt6VAf?TQ_7#l{>IirA#*S0xosmsxi@aKSC$i7J#rqzG0%a5W6P_8y3|mwXo#)bR zd;TAvy+Ddhtr6i7=SBCWEk&h>H~N*-YG&&P8@0`vz-YJ5E8k7-7T;&?D~~yHa|s5| zGo526$xtfz!UilAAmaH874|Y+`D7!MZ*Y!J`YZYEV6JF7F|`_}3*Sm?lQtCIyU38# zdF&e@yDX?|J)oJIkdzw+(=@a6TJ~1M%U@+W*re!YXdU_V^BV@CO?|Hc0NWMK$I23C zVXJtfdZW@(>1xn@KkmGaN+Y{KF4(!`Y_)Hod)qw~QQXPco8P_(V#~^|@g@-0vrm?- zH0lMLyNTO?AFV$|vskN8tFluE9T(bot-+?f#ak=BdWmhCZINwM)ugiC!`fH93${fB zqnm9rWmDCk-l{*nbB?~c)us=_uFwW~nPTBCm3v44)F8nC=N( zqnEX>=eX|vo1UQ^S@I>&708_MeZqLVCAsG{$cG_8Z@XLUFu;vB;nzstXp!TaCF z;PswWlhxP+GMkLH;{L}IVD#aML%lA$OR~2V!4Cl(0>wEYNJ<{U6i476t{-$uTA{ql zgl-hLB60k^M$txvMx}*={VQW@e-y1I93+dG@QG!69g`iS9f==BLlt9Om5U6knR@Jk zC{ZV1)^_lAgOXq|DytQ0RQN!)a3}uMDG>+`J`q12JZg5Us9tj_3HkF`6hmQd`)(pY=CiF*Y?16tNq2VZ_;ogq-TwbKZ*-!BY7l)_!;lmG2bx; zjC^->FMl&}v~ZK%;9_{-w&2$@i!r^fp1ZI2yH31vUlT=%l~9^do%9u?I2J3cMJPBI6zG3YKtMo$fK&(Q78bp zkC^QE`|F5?BmffjpS{PVumD0Z=6})zd!_^jN0ul=RF^e19X+|?VLZZNm;q&s1w?tG z(M*GR;86&833@6nFFwX(z}q(;Ge4iPoMudJ*H<+)6*Vph%nZ>%Z-?!M1y7_s<+OL80O%qNMg}UHiHo`v2_-2aCv1EZ}?Gf zXVk5lz_RW)+U14bw)d078LzKA+bB-^=4J#)B%4k@%Hab{Wc9?~mHBtbes50=!F|E! z$3_oyfI>uJ>AU-VA=CmQdzvh4QDQ5K(az+Zp0_z@VLujO3OQDV zjDUKhedZ@%j6xJRum{#4Ty73_q8|=wz@Vjjry0OKX&3(Z+5{OeE~j(ZU2l23uz?>~ zfWi>-)4xZ~}!^R6e2%Piv8OJ_jb zcZz8F_GaYB^4j?Y1y>#;Y8hwbyhMLWX#PI|X5xeT5u&Tcx|2|mCM+xZCDLn*m z;%|q@N3tJVoRNTGr<)9RGymsJm_m^A=e-@7Tjz+(_tf}Bgb}b6lub4Y*Vt@K-|Q_9MFx&4TY!7r#kdiBrb4 zZAZaShq--?$fQ-j!;Z#|dqR8?Hxj+AboPqXc}3^p_v3C+qsqiU98dR}3Dy!Sp~+%q z|8ojyTeM<%JfunU_k`V@B>{K4zX{}acZaH*q3=8|xh~JFpbRO0rmK!CDk_I^ z#I+>-d?+{f-`nC%8XsVTFWba_ve47iJvcezn_tn-nX|M+Jpoj`z(=) zTEmy5%a=1XU*C`$uQ&6mos2n=2FaePMm{+m0*hpk`#03o#Z~@(c7}c|_o8f);EmUb zUAH_~zRN@e^Ozl%p2dh#*>SGU2j|jz9T+qLc^+AyBi_9p94W31sf2(y8~GNV*LsjO zdD03-(lU>sR^iA+%ny;Slv!n|I4#2ngmQvT-_OZ3(l9&q8Z_`g`o~!F96In zczegEzI@-y08BRz5VcK6z5$ zU1RCiA6UwP)yiUC9rGtX*HxCh2qNKuNg8WB;t?Q3C7&M5jza_6pKnF=J znB1%%AaK5m)CPF46p2WS)sxv{cNaEgh#AI;g2RUMw%jO-;XLkqB0rQd^Wu$ zKJ6D{J6@p6VYTfF&!hAiQj9SB?(`+s@6TSqG?2%SE&S3bOkn zG{CVB=Bx!{PVBc$p6?sqlu^O{tD$rtN&QAIhY89&#tV+AFZ3_+yHY(mxmZTpAxH5D%XujP^h&1Jd*b5 z&M*{VLvp&5OcE8v&&sp*rw(&+O#(N>E~LTJL@HFic)O&@RIWMp{sfJ>6yp#5fm0i= zi5fCQiT#Wsg1OoyO`?I%nP|4Ru~Q;B-!=M#JF{0Ld3t)9L^b#|83 z7&PIzabk^D%$rJr_8VEZrX$5M@7p16^=&jUO02U$9BVX($UDPs9o*&e4abC8lD+?O zpBc$jUJ?x~EYhJgPlXF5SYBx6Ytqg!<{#_uKNk!Ca3pFsOJyG5dZ|j0ZmXsUM+=Vn z*B$aj%I6b39x`MW6a5t5g=PI`ghi8NHYUD6b*Q$NqPJ7e9Ku z8DsAkKjBzZzvK9M7EY(-3pR=tl2iw=U{jckL$eH%^m8SE=+LjW^3+%aCFYqPnF9oOLSJisehFr4M`fDiNa;napP0 zR17plBb^Xt!b#eZbWZxCy@i-Z6Vv>phEQ6Lrf_jH)7iQlvu z$g$BXlZjvR_6bJ;vmn$h8l26kyw`3s&bILsx%m<`-f1j{UGXTQW#W=qJ9&mC?0Uin zY@O+Mk~&ZPdTRKSHJxKYz}#^`Qky(_u^i%B*JjYO*snNy|HO6>UHK0ja$!&f^U}b(Q$$)|5JiJyw zx0$|hB0e(^)KhA5uS^1c?-AFnqld3`ZCk-XrJv>+)X7AM7L&*|qc7hJPyrf^DZ^|F zkbk|fFsum)=ls=+T?_hSG)eXe5ctsSFhtA5MR@b-I+0+TRSMJIO{R~FnCay5bVUM2(aF+wCghd}l@g+ugd2$uQq%hB{ReuJXA z1xN=t*urhKM73)$Uxa03qR^)ZeeBhdn8zp__Ld^k>6cEIAsr7Ds%%NBgFWcoDn3${ zWhoK};LHmM3_l%56pkr2frlI%uBWsLm{dOz8};WrU4v4@Y^Ba^=;{2Y(ud#E^^JDAk`?(<;YD0p+j&hD-6G`a${iq z->C_XAoT7X4OsxTtbFPApD||bxHFEo`gmYzzy)>xqp%)kn(r>nvoD+t&pZ&4dIZccnip4cUR39F-6M3J^2nyMInCn+q&$~Pj8KZS@SeNaP z>&9vqsr5lf9b42?lzyP&Vj^sgS4ds|piC1^9FwWHXoIc{YiEX4iH`d;bD+%s09Qb$ zzcnwu@S5+LYku7G)D$ zQmAk4H}He_#Ejk@qQh7yZx87nb?G_6{$iv*#Y!`_@5Y9B4AQuhKp4dkI&=foC+#$Be zQf3oUW^YW&`Wz5a_OeFdn~^C*LD*;D`9#oB%o@Cr*q+I5f6x*gSa%2PcV;!HvYoRf zPzahYvCeAVKjCJ1C}!2M+2^JJN1VsDG@~LcJ^h8>{>c;Ha{q zRd{kgxCk<~X+eE{i^RDDc90vUr%*I|2(Ew3IHPTjG*K8>xsPn~lVpnTtZ&jlw=Xos zbcKZ)!*v@bb*IZ1n*-1P_dE&I`8&CCkIz!e=fC4?zVuI zDt~zZgLsETqoEl&OPM=#QO;6whrq`$v})nf%-|!`(9KG!Q%OJMEBT9SKhTu;@kKkq zxnW@z8+amDQ#&0Fn%aS(BLZ`M0IS3kz=nppsxRo!SmM83vuU*1CeL*k#mT@g6yyG& zLBZqc;wa2G+;>EbyOSz!{6g2UhLYRsP>Y1M*##vU+zMy|E%q8PuU+a52XNqc~0l1G4C|1XAX+XjmF_nA4v| z(E@*34Eu7DFP~=f)#Rn&%(t^D3NcQGI*FCOw75_!B`wZx#c;Hg(l5iFStFM^c`T$n z_y}*2b36NH$=ymxMRgST?0)1o`LsX)BQr)LIF?^AHb#c9=J!D`azC*?dpmK`lZ+5A z)gp5Y^1%C%BSPtOwH-Knw7won`}`UPSKg0FEt4jTrU62|G0DE2T|dT1;!YIB(>^NWzL;0bhibmlFamuQM$BzIQ0s1uh0wy>Y#~F) z9hF#F?kFrVM!o=TSFJfz-REA4uY%rHlH+`3prrjNama~KtkM?Peudkv^3CFV^)@|x@=b}+7d21H49 zy-6T=DbH+_rkFRCGz$9-k5OY<_;x$qNVBTes8DpXH0uE0@R)vSu}f=jLbN>KnbdG) ziISBTi}h2SN}4mdAIMUgGc%eiQAWW}b1V`wH9G*>^{(2a^jgQNlzIxJ!SfH{d1A31 zPsaYsKm#%_B}UA?Q0xFo6$VT7Ih2{3N=spI#u$}X{q64Z3oiR8W|4mv^hfKk#;yx3 z-8YJt7Wo9#bF?hEuT++t1fLtp*O?5A(DGjJJ7W&Ypp7CBz>()0Z!oIdk82cd~vMuZ!0dN_4z6D4yKVk~I(ovY&7rd3L;QL1SZm-fPwiUJF>L`_(SOjocNpKed#h>9f=mBtu zzO68M#&`Y1Jnyp9z7`VLveYDta5@{#Hc*H-^`F@mjZ&YVH!00VkybD|hEoT)ue9LGL>b= zHDjgt4Y}Al#8Xq=uvN?XTm9mr|M6CpyDbeP`_w8`!B$y25)G&Zb%+11x-8cMny(%N?HC-kk%moXUI&`C=K{r0o8RBd$l!iPnBQh(;)~OhLg0uhXR>c0L*z3 zsiP>0&TH9|S|9@r9D?%+{Kz?%4>ocUPKcXv&w|5M!jsg-xLJ%MPr8AmwGCF>Jp-6Q zcet51PFN*cjX8eTK7^;HSNmOuNJnSAs>;89fa$6I%xQM*Q?4f$ndzwd(Q%4=^=PQG z;e*?FOisRkjD-+?3UF0cUkOiz9?nBjT+aornn9{UqhIa;c+pc;e(g3^`|BAv4&KGA z{8_)N3d{ZSit4KJx!zRe+gl<|6{_o177)B*hCY(mBwRin8@~+hD{Xx8DGfPniDDcW zQN}VEHla7sp@O^1W*{1ud?=QzT>T;S1D3*BH1JGSeSKj1bf)a~U;~7+u`~N?ckx#z z`gO%<5wm;_Z)VLvn`usB@i>v~GW5iF^tH0Ks`9NEmUX>@73LZEfsEM7=$SW!HS*Oo zOv@Jg{-&hb)eYPk_cM7u$QMlzWy5KPp#%lSW|ws5Bv4}G?c??2E6kSqRWPJ zH$I$&3}fgV!Ap$E@n-6@W{O2Ki@wIN?D%nf4lqjQwmU?BT$I7uolE`o?j5?YjAOmy zi(CT8)3#xr^Rd2YZ8)hFUY{ zXbi5I+gNvwvLkkG0N9L%0FJeL?;>?($HZ;2ldQt_Y@LV=XB=cQu2%qhr%VMcS&C36 zYVnH%N*dNS+5l9uu?8*z|Cpd(giB&p#L{Y~1T&<-t|=A?tOBiUTh!?or<_7CoET=1 zC^i+L7i)N zQyrl#=90Gf9XRzm4^Gj)1ESlRC!yeFvYg* zVruP6uGZRqj)shDfWi00$T?7Gm{h?=Q8$R1UrS!vCE}l@E`)PeWD47yMQQcTn3kBHfYx`VW1d|D6dK_eq_4L#1 zd+o14rgt|KmFq0-IJqv$-AVQCh2P5MJfd3v7%mnGO#qz=%n7wn<)l(Q+?x3{dAYYJ zt5^OVc<$X=i?aoA)?2Jy9Xi9V(8DS~wEW&Gev9@Ej5Bo(_l%9p^*6lP73P)`?koK= zUP-JM0>wYmdQ-L#y*wDeZ5IarI_GFzBfOg^c-KMjE^#07Zp=>3yWR%gwT$AtJN5KH9*AME(N%ff7%)oWwRxg*GQ3 z{?;K^Ihd{HI?R`(fLPtMi;Lh(NRN5(6!Q7DJCVj%bDE)-QrDeM>lB+I@n2>0hkdj>w+UT4t7Yh~mXQ+s`<$0+)?})#E+NS@XAF zfHmqq#+q`^d|<{&M`8Mjdn%{-cFW&5kPlT3OG#1uFiC=&mOVMAJHe%6Scy*_)Wt#+ z_a2KB@7Cztt6c?*6cbk7qXvpU9*agF(k9kxH>CJSLGj$3oRn)Tk>Vjc%oG=Miu((S zt3PK1t~req|D;pwIt~Ef?x4CeWX7=?Ux~6H%ZSj7HA%*7%`|_6Q?qx)Wzc88~x%w58#CK)rvH zseexjj{LBLb0n<-IWl{jxqo-_{{6zji&;NoJczHuRu2J3qPf)ke;WuMyBU` zK~JAg89gIT3VK>_de)#8-AMGD5cEVD=y`b5AEf7wjNd`ejO`rJ7d}LK_H2nv&oM#I zw0(@8>=O;?Dg6njG@_?i&|@*sv;B@gNRK?~chFO~jU)Q`2T0H9&5`NZE$CVE38N?O zSN47GM=%ut+n+}ML2N(01LM@*YM@?6xhaf03yiNOj0ZJ>@mm7pZz~z5pZ&tVhjNVj z|51!PH-hm6*g(s+a-?SMMcf~GH-ZhcLfAlEIpV(_W8bTfqMF;y)tqN^WcvpwlW+fn z7S7<2jnBLddf~k-oRWXNkCc=YMec>CL@$j0m=Up+6H^vqy-+yf5B9=8fJlV~jakyQ zsM)~4fe{qwaOhE&U<>%4v*n6-i-fcH(mNFSw_8L!Z^{6R2AP%=|5bGzXF=Lix9E|# zrS#Z6k4+j~xdOmh1|~o$bQ4r+DxNWF1Xb_Ns!uRfpGMm+TNkl%zwW_xzKA#mV?rZf zo;qoWl*PmE6D+Xi`jyXXwJfma`i0MH$5|W0^}gXjrjsKus5Wq%SvRn(HD>Wrfg4M1 z(UwIA6ezExTCw?Vk_gnT+#-CN=e97EQxIkOt6@-BDoc%({Hc^XE=#pZn7&JmQBs|t z>uyoxg}1QitV80_8TtBT#{BpZjQPG)rz7`s3D>C4H!$Ajv;j$f0)Z2mZio6*olT( z_fV^zc%almwT&nb8!i&T7eh@8U&w-~U#G5}8SlB9nQEniC{Y@>6E_QP$8BcZ-nSdL zJ=*TAbl6+QJ%Tv=bopROCH|=c}ob(_CpORbqZO zBY{O&9fip@EtkxGU)11ttns&!9H&uVnhiHN^~p}$5_XwI&-!CRYQ4{uk5o6u)?I5P zK8YS?i}wRBrqigpOm(f_E}ZF|_{_B?G#wio0aWbnuTxP34--#7l{E3Rw10SyKSm&G zMUmnNMdm?~8QU?rum(h+U#KT0yzsIW;6h3jw^%Ub)A2HW4cKE>Bhm+kV#0z7CFq5^ z;AO@d=#5qY2=Dwhl)TF3imNsh1%h)ldz@J5)TP08aR95xx&8P?luw4@;;r0b_cc66 z91zh^7>mTCkyPR)%*r{|l%SJZq4}knUZCDlJx}v4SU%L$1=EJIF1UIqbwLN!^)!~c zbtrM4C~o!I`wh&JJ z^BVPs3I+8K7c%O9D~&{bmm4|tQbg*%AEFT!9Act=;Si1bV!cr55H5%s^-m5lQIGpU zlP|LPT}(M7$MAitR}9hixoWEtl#Cc{VM092w~4gbM?Te8pFoBTp^%3F2hs$P`ScMaP`-Q{zw!e4g}M&Za8!ZCO-6ONXHNjN(4j_887UHM8zJ`RmD zXqSYTo5Z#A`u*!;lN+rAR8p#DykGS=jch*exMa-G%Fm$oF~ROeJu z2>qiP`U}F)e*}Q|T`^qE;;z9Fan$!VnBoqn0qbB|aOB<&esoz%k`}8}KqP4O%Ef~$ zQt&VE6eTj>Adz03tcY?p+u65M$;WV#huJm)>CO1XFwj0 zn;0<)$5!6SU!q-l{WZYq7U0`&0D4ntN5_ip(Go5CT+ut)bXr4s@QsK$+Wfv)PENc* zpFNhO@$9RZ&mz|N`LBA7K^IixT|8DoAc8*amaeIZJ!ff49kq7qCnKcGr=@3HQbZj#;Y*)RdVf!Y-wtl;QG(mo& zvi-sVle&k9s^iYZp{Rj`m*QBrwpa;Id?&W8sP%8&hXgw^h;0W7fs(QYq z1sZD;paYea@z{-gj9mLQ1H5kl_jgvJgnKUXr?D*g-&A=yb3EA*D4F^q>CFR}sjN^H zUV#>94G7O~5LUPk+{QPExT=wkhrXcwY2I~E)qBFz1~-EP=n)JXSFMi7NQEsfxEvm_ z)pahS?cg*0<4nj# z10Py0>m~Hu>E29xrD1e|%{_8S*we1`l(dw*y_dnuFqLXXr4SLJk@&imG3Y_|S2Fl% zDL7?+i>S(ddg&VJJ@k=XhZMQDXx?>*G-NXMn%|N8AF4B=m%dg1QSMhSJH&P?xT+L+ zC_c}ibyk7jhV4*j}_nI zUFGA8i2;KzOPR>wYTOW8ya-jmYtvStMegATDcd-|BkSRruQskLfA1K4_8^8ks(TpY z5Z!w*e%*Ns&S7VJ=(AcH+{q&WZaRm^uzrv7e0#58Snq!2e-7&(4ql<3u)UFTH^be!N++CPdPa`wkVT!UKp(y!CXx zmbx72&Ot8)A+5o#A; z?c2556r;NwBRAPhM~${Rwx>n;mZM(N+!CwCAtjrp3sh8l`iEtQ8l5j+r=;KR4s5>c z^|E2U^sf{O3RyV5zdi{~=OO!h`iIY)k2F2EjqYHc+Z+b4mvFE#{Tt4lwUrk(bJn#t zLw~EE4*g9Y{4VUrX3nQ88_t~1^rM-RR9|-hDZDu*`6Tm9{(b!TpI>OnMPfIjFJFR_x9DD$-CQ=5OKSY#3`C%t)fH+_8EiD<86CUiRuRu+fV zuOBTh#`~EG+E$ONsSfs{vih}d77g!wH6IAfo$Ao)i+iY4GG0vX!y)!*=#HE?KSRJr{NlD5d?y=^cz zjimjmQ2CY*QH}Y%gMMU5Sx4@c=6EU!ZhT?qhVY%OcEwBZ`P%MFi?N=k9XrVF!4EO> zAz%a-Aqe?IG)|v!$v(Qm=2h=Z0m3_wV_#JR*cUv9xut@>oPZZ`p#v-7-FuRiyAj4# z_O|tyd2tU=7_FJiSnRxmaCtB^P{%9`87!{rsg|mM0jaX*_ z)#({l2TO-uR=m9t$<@z2$E@JT(8?_6FL=besH_lG!c}1~p8A_;7Y`p~)5!@(L2+({ zBR87drO_{NSJI0x>2O7CftyX;aAJ_#chMEXpue#pasz5j@7N#ld0Tv5F#bn&CJn9s z#!}v)^t6qkcFVt6G)CG{GkPaenM(|1ez*bi8pTQhKElk9LV$?WQD9iHhA^r{&0~y9 z$%qdZzsI&xmrqhOnQ31EZSh{f5`p)jtB?MMGO&>MFk?4Gl-{7l7>FL-L*_rtQ<|cQ z;TsY8lrXk;zJY9wOr?N2Pkuzm4!^!{H#B)X~c zO)m%^my3l>vFH-&0jxq+?+N$qy2!b&W8&sXR0}@AMMLtl0w={vzYK(IbS zGGu46$7D{Gw}#2fD+YNvO^A03mw!M!&wDrZ^)+EnYx@9_q>Oyt5yTkmF{K5f42b1< z$H33P_z&?Oo>fM+)gBz{2vKq;sPac)XcZaInu=((U?U%2nu0^{+!+Kgh5-CU;naQ4 z!61O`8~`f)tKJdHt2sr3@a!T&mEDv$%$K$M3?PEpso~*N<#QZ90sUYD@Ov&MqRWg* zNLMaypfS`@DHuq&owyuJ%;cRl7N6aKHTC<7rZI2Cr%^EG3;OW#?hlzA((^BvZWi;x zMC2)v5O!YF%xE^Nc(>L8^MygKovq;WzEj6wNQ5)}+K731-?l1#T-3{Z0gD90@z>Uf zBSKQNdXJYgjMiU|n|-i^qj2MXtlFU9Tr5~)w)n>A3H|kW_K(MjrwhqHf`ggU7gOTP zI;rwspOK^;xJSzn1v&znGS~-IpEnaz_+Ixh)=E09%%oo%aSHKm6XN;Z`zW@@db1$1 zySL(9b&M9fT$8=+37l*^SBUL8-WTgwuW#j6$>u~LZevj$BlYK#S{tD3Xvspri_kel zcbZ%mg(uET2h2lG#k+>Dr%>gBXH3DY&Oio{rpi9zt!N^7H}Jd{M@*G>LN&Kv*_IDK zL!bEk4U4zN;%yX-3-4mNSf5|N^Fl3oy@6kmwWY{xU!Ab4#$Xa+4w^zDwV|*B0&GZr z!E@M+;6Hnxh6{B|m-RT|jC-070X{SP-$YB~u3p>{iBsi&{!@|?PZ)^30TfzrfQ6>a zB+#o@(orx=p4P{zgRiYafC~}e76eF(M%N<}ZPDx6ORjcG5;|DLIRDc#-#G+O%k`&{ zLg|2JKy0X7^s4KSRs_>>h^kBoqXBuTvaz_1)^c5%y=^Zp>;QhNbgP_W`p>6z^*{R^ zI>`hW8gmp_eJ?vHr=XOdwWb!7o?>U6iIaYDzml&k^Z|1xz7DZ|yBo>d_GTUHn<*ib zA>^_`OhT!t)_Li?ki#6mNUBt$@anqF|Kih**hu!ftbX%fv z2z`Tk3td>%Q6V@&v`Pj`k5MsP;W>k8H}1`K|<&(2aKH#}xdV{FpKpdGxOsB*Kntp@qr6dC3s@X%O=v4<^tT z+{`ckMQ#`cfyn7%P9k?T1G^dL3a%63V{FiUjVj{{(~QyLmFTjrOeP4)%=L@r?qYbX z7;d=2&l9rwND)}^m0h@ZSe17?BfQbipJB=&`agisCThlYh$R6jHu-ZmTKZt;O$Jp8 z@X(_`H;QAs@%lEnKJIXm!|hu+keo~(-D{2GkD3_LjjVZA`56`kAZFYE*I!Pkg8Hti z8IGRvtkaUT;L;_n{X}q0lvE}BW8m1OP&m}mPi;`o$d7iz$Taqwg%n#HKWAP^?yhl& zJkW2tnd2{EG8KKA%Txzd_MbwbqD*pR0o%_6%q+)vKJ)LB<2z3AHZKw_7-|UkFkeAu z@+!*YQ#c>RW5th>dV9LbNs{MkMJ^&=WG(UFDxC*FI%>_}cU>(KLEcHg%ZxFG2=UJy zI6Ast#70Nqznb>)nTNlqi?%jFEV%Pq6Ywi=V;8<5R~wNHOT?N>=uofHpmyQsz93$uhb+=!u)zyLvcsem10J8B~Tq}TkoTa2PM|urT1Rgwkh0O&u zS^|VhFTa+ZRMguXC!A@HtJ!&+5b33md*DjEItDXmiKB3*TxWBvEV0nbB=E2be3^u! zlZ5Yo%i^E+;WJxe?_2w~g?%u^w;dy#co4l*=6YWW;+q6$p;d4J*%u{po%Mla0GrRj z;&Hui!{=Rzy(jWHtbn>K)Sl{vE+vQ|`*!SxQ1k7W?nn(@&8+_IXrcucUuz-vz{xC# z?HFzgEP$K+qZ})6*+l>5?M}!))XHV8gSf~6FtcctdtA$MQF|S^6%tc2tFN(0*;(&f z{H|*1dhn6)yIp1CiJWhxGxgCve@+Q1KxV+iE3UnmoIpJRWn+1r7=D(Bla9{IWFBqL zYbc+Qa~gdbb$-;+N$UJ&@C$ybDa{?jYeK^`%$8llFspFih*Y6xlvp3gyBf1I`$AVL z=@n>_rTOd$fkjtajMnQ#=kRQ(ep&l64>UN_jgL~1gzAntJJ11Hn6Oion|=jMclYb< z?jgqZFSG)E8+rPjFr*G8@q}nQkNyR_0q%Y)9#E(S1oIpC53Oh!1umNL#QMD16lTiB z)yb9WmUh@;onpfSd_IQqqTL_W0)piYj}@g>Ifwc6!>?XeitXxBD2&!GkmxtPS>t-V_Bs48BL&WNilY!^!SL1(-7h$6?qU0N*Yb1zWnAmN*ECc>!N;D3tQ z^J*|LLj%}jB=-f0o`AzVb-jpmoLpyefbyS1#j1nISUzH>+9yR+}+OL79XD0Ce1Uv5j=4i*Q;l00SGqXb~ zI%CJ^&jkAt0xxbx>lcC&Ra-O>%e4EU5CqDhb0qvme4fxR6Y2li}u7V2;bfbms#3Tldp+qmbN2zQ*%^LmcHKz1rOq+gE#=z{7!sj4W$5Ry7V2p=p4-Ij3euw5F_yk1Urj+-LF4| zJju&IKx+D7U;27H14lH%Kwl1^eW$WdSv}pwk;k3b%-gCtUzXI7ElF^4!h_RMETD?T z-Esb<*{7o1@!6-EdBE&@2N4UkgA1DFL6Y8~c|IC0ta=}NI|+8YXl3k(N$|V&(-g}N z@DcpMN`WUjqDbHYtV%kOmu(?uCPvA4hbg=_Ir;cP4?HKd@JSrU@37-x{jMUDI6p_S z{9GhiKCH>|`iQa|x&mdnNJ%eBN`GhByTMuK=s0$Kw5KD>w>fh6@uMb6IJdVTqO^5Ls`l|iD{>S&sa~P3pyjz2Q3s4&+f|3DzQTO3@&@^weqg@I!1S5c`~A| zhw@Ix%F)e8`9N<&oj9!y>v>k^YOLd=Y10FSVI5i>>rd5_&$MWLfmfGJ-ol3!&jvdhs+hFl|URBax z^}AkVRv5RzTu%!lY(F!?o@OgVUc{3gmGn|BCZH4JaKQ*#WRlS$LuCqxtdB#3dH+pl zkS!aUoxZC%V8087DmymGG{%U?)^ThA;@L6{o>RXZ>tKkH0XRP)L_1{o%Nl-cmpYWwa!K-?XE|86ZJvp^sZeBmFv^@x#x#I zfYzcxW_PJB69KOEc`&H83hAP?-ICrKbggJG78-2Wn%2usY|XV>&f0DDyiY^zX=WK1 z${cNv8trLh@L=FqaP}DrRWkYfn|Zi|Vl}OKi&<+Tq<^=k!)T4R$1h~g<)IrY2bv@H zYWjX4!0)Oca?;lr=-98g)-=jES9>I-Le8o{QkZ1gI4aM_~ zzJXTlO~&?k_P&r-sr@{AGY>;e0ki~cC>|@Eq9iZ$%<+|P%Kw<*_tP_Yg^#8V_;B~V<3Yn%I(+^ z^M~78^wW9Re4Ygp({Z*Kf|i}F<;&(MiSk1svlUjiqbN!eWft1;1q0V9Yia3%w&);r?#N9FJmTT1CO-Hs#u@Ng1)m3D_@m`#e7+Grhv5?k z_iu+!>t^QXOPVzef8%+c-+rFw|Lv!*75A|PJJ45RrQfxe&EGUygX?e_k{`EOBrTF5 zUw;wHg5QXepRg%>ndD#lo9nIb!pHph`#)A#Deeff~bfITdGkT)p(87 zh8ncm4JuI_gseyTp@@|x8Y@MyN~jis4^gERqSDX=ySd`khKiw4@1h~4daBTyIo@@T zqi|qS{ouS5o98E77m4bx8W(eF=f^AZat65p)Q{Tg?AhFmp@X1LxVigZk zqC?*aP8-_=4mhY)s3K# zc$wg)GnyGScD8hiaNzCRFC*qC@^)PIQ4 zPfY0}V#}9-N5a`y?b5)6XXI zD#}af^tSm$qR8>3O5>5^u!z?9WXy=is^F?-#reFYJD6L26J_b>m1>MnP9|PoKO|{F zkEaPM>G6rhelJE75TLi*eKUWbN4ypUi12n(sz9Y0zTp(#EalxNz*Ty#MOO!TMODab z$xPtOtnGpRm;j~Xs(g{cy+2GKgSznU=Cphnz^DcmQs|y=w)hl1vj&VD$~vN7tjbq# zI5P+i(=$|0rTB=iU@r?_*fp~Svw}gkgVCu_jo%X#feL&XqjxV4sRVF^!+9biZ7`l9 zNDLgN)O^8i9<J4Irx5@hWt_FvfspXmr~C_FL0pp zFFeO(k`JN@2%Na5tp58s-Q;#T%sWwOeJU1fBoBr}JWa#!W{tS+d93Bn^T6{??QRh+ zhmsmc4&x<;!-P}g@zy<;SQ@OV?Gm0d;;m8STt2c=v{t&3wKfY{1DU_NEVZXaSuu?$ z+y9$R8MZOQw_+x~gSDA&X@bc9rN)^vpkH6C=fg}mICUIy2#0J9hh&b!_bUm97GM{uol+In7l`hEt`KzJwt~_9;|e^QEwv}UHxRzNgZp?r zs(rQ(!m6hB#Zt}J(NZ)6Pv~_a#E@C`hU@;B-wm$ba&+_D(f$;6T3^BF_Uui-wuG88fW#~Hm-%M2CXJ*`)G9kC+R2`@osoVipUmC{tAtJ;_q zi>ys8&)|Gu3o%RN)7-`_5oC3|&gvED?E8}w7(TQpVmS%pkS;kTTppc{LRvIW28f-l zACh~X=FB*hbgP{N5b~_nZC7(K}($iZUsGGqrjL#MM$SIxnRRAs2lj$mL)9kmW zcw6^|xAj`+ZIf3WasA7`=)9>QSKY{bjECPf%QNh$>&UT<_F93R)Se9PiWb)hH-uL1s!PE*JS3yNHpsc!Z*X zhZMPQ3lLTtcnnLSSrnaXSo5Baiq@|6amog_<)v{+?Fe3KP^eGCgm)Tg+yzjQ9qv+4 zg1Z=K1H*kFGr^JgA{q_$iv_eWH=5qe5V}Nv&||G>iL*9$o4P~WHzT?OEUVpT3ERJ@ z_w_|qj9W`g0|u?g)>oL-N^mv=8WeHa7ZZOQ!X6V&A>l zc73D1v3IH{EBb574_^rC*u=Ce9Tw2rcv!&OwOsElY))dnf={7biJH!JUBpkCz<^?m zzEYHHB9LG1J+4C;q*ayV=}`{pA1F22O4VC?LaUxCyj=B9OhU7@v$(nO(??9oZGg`R zOOd_J$kfFnlD!BmFd7&aO3BVTB(Y)`r}2EASS)A7N+2O@k!h$5_ko7hZNH9rE%8=d z4NvQoBfT%VAxa7rb2l z7!9AR4W-i+jhs`DvUjj8n@O*nj6C)qh>9@w|BhoHkAdLpr-k<8B*SzVYor{B3U&jm zlU(skRXT=x;+whRv>lWhPMR| zA(wK7v{GF0fchi&YBfJWMm$*|&$X(&qhTA`{u2)W-#HlW5KJw}XA|_&*#P%Cf|pd{ z7+%3B1FD)ay*H{MZKv|t`Wiogwon=N)@)V&Y$;a~OfG3pm6p&-z}97=4s$H&oGKS5 zpe0kYUV4i=1G<|p)@JnU(_*M124=Sm-Wg8&$4HJ{*a}hrI?qJVlegzW^k;~Qi%oIq==x6+r-btX%JmC;^ki|}0r#FN*u z0s30sQF9?$G=q*fqseWws)n7KLTfQdqi>6M4 z?e!pAsCF&sb@sBu4n7x1@12WjN@ORW`&{<&;J=sa2i%CAFsoPx>kaU(<^7sfD`twv zSp+fhM3bu8@6G2OPWo({;QF+J9vYw0#zpS8@++ABG7yW{)kPdGMt z9|ycGguP(8yKC^FbAq!doMzsZKE{M|&lzNz{!H=a@eLgRehf7!VL(et=byt>O}Uj0 z?@U^M6Q4xwIn+DPkrmJrL)hu(bcOz@fCFmSxe5WOX-K6Hs#AIk+h%jUNx%s~Uw zJK`8$WjG2iGU9yRLAY(KU?}_#RMIv81b@d7BzxH@wpW#WR9ssoaSydjC99@&=w_cE z`S%D^489zNNAkFBJkDiR<+TfGUs(TyL}55tX(jda2LX8*imPn%Q$g}E)*mTX;dmh& z2|+YGF;&En%-H8BBt-LEUnpLzlb5ky$wK*UPp?uRQEy_szL{m{f{E6n5LMCN3q z$eauonUh>Jxl*l3MdMb@hrZF!0x}F&UZ1#mq!G`W@#R4##FKmw{ftz zZbl8RT_Ics3S9aLT&_3Za*d8l2YijLi)SNz8BW{|k^$4^rW2^L{x4fh3r1{_&hHU{ zYu?t)qOHG*wz?bIir3q^41w!yK`ZwhZrBPtCCJGF_k1EBs3hl_C!PR=?Y16MXZn~(lWj>~T>&RefJ&#Th16%ZO5=#wH1brT9 zFkhCFz4Hbv8HCQ`>(?C)kCFUuW$zj}6D5|iM4y`Tc7~v~DGEYwA|w#>zEQAtbI$C8 zs!_fSpysz&iNAsN3&Y#&&26gk9;|>fOyGl9gNaujY*i~YmOoqZt;nCXsAi$Wzto~X zyzo17{_F~ju<-m@`|tEDQ}bG>iToLl5@Xr{Q#%b(57U2<8m1mb{$hS-JQ_e|l)c5C zNye1dN8jqmEcylCF;d)*G-p-|mi$syzyGbsg9vJd|AHY{oc86@plOTU)})GMt$Zuy zuw+@PDUVf0W-|1`#^cg?Gi8fN3yz*6wBUjTjH_GbTwtbb#Bu45WXfiKqbF7FKQ2Yc zluiCdA7{glOU6vuR>Pw{$EEO0nTYnM+hIuX#Mkva@zo8pU2N@??yqXZ(M!gmKZA>o z8G7~tb6xt*DaPC)V(yjm1#>Y&K)Hu|V6Yo_&ch*Q+f@+rm z?8V2V$hok)t9U3fWT?5tQ1cVGujRrvRq5Tf*-+t=uMP448mW<7n6XqQm1-mx7M_WD z^e0Kn#C$Np&c$esb`itEcnvv<@ zMYpN;BNlb;f8Pb?^cqd$Z3<80E&Pi2>!rB3q3JYUSCPgWX3pQW{Yvkzz0d(+`MXO* zBd`Ay*2pUtkiYAkOZmGG87ETbHII+&E}vXod&3paak)P zE=xHs`|kZ6xkNn9ra>+dY>*2HH#u3t2?kfPuS_nZG{@vjwpGp_XfeCKo|cRz`IlX# zWK@ITp&(wS%JGX#L*UW-ne5e~?42j)@y2qb^FJRjI?v7hzsh-RKgc^}`BACqoCnRL z&hQw{t!I%+=+72PKF*ZozKSNxUuq~n$6P*A|K}iI{<)X&<;^Q2;~gTCa9*iPcO zmJKO)tRjDKKp#C1ha{HH)LuawugFd{{LQ5v@rIzO$qZ%kMY^Fs4LSDZHw)GtQM z1LfwT?^Vo#mVH6BdQ5VaG|!v|$_h&6T+XnZ3(fKc15_}3UMQRSKUm{`{rpXAe%2kwcK&q=?Z<#Xm>JaR)e z5Qt~+IC6JNB0GV{WK(b~UPtU!@ST$gv8-6-5)5NKs+DJ(m_u__dD%Uf1p8V~f(356 z3#EJGY>_{v)K@M#>O7Au&7@VHk@CL*DLe;s4d#HN>y4R_7atI)WrBwKezuVv!OC;S zqFGu|U)fTTsCi$Np8&jr|2W59IjLn&xH*Kl6l>&z6XdGCZX;eMm1VU8+OY1Fb1Xi4 zx#j%XI9fMLDU+xM(O0%^wp!VQS|+K&ky62u6G_J%!;W(*-1_k*osgO`pWh8+SDK}u z?jCablKfe{c)hZ&=lJW;10Pd8to5_GR>?hDoOs{)6DO){pCjV98x35~WKrK87RI`R zDAIN4F6NZtpb{~XKay7&_XG1RXoO}q9eGzzh!Oga3+)sNlSS;5O{m9{Y8=CAREmrB zgCWkMw!=Lntj$l+mTZa<83V2v75KDZnIWD$DY$~{^Rl~5%wGnRZfJT~I+Vq~zZdcE ztH8o3RpsoNk%spCxd7rSMgFRqN4wkd0euM<^%fZIcCXV=iK8tT0Bb;$zc%J2{AY?D zi!Yj`Ny3`*XAHo7_v>-*d>&tZ`9ZdOKA*?U^)jUC9%Nehv1$yUWr_gw@5`FKRD0oB zvj^*pxu#}I5!Jnn4J>PR=R5=bGaJjA&3(_9bShiYRMyN~_NgU|;-|m+FSBNE{c6hp zWr?g=Myav6>v(gC-UUBSVxv#>qyb6Tc=aBiY=kRpcJ$oOujqvY;12EDIakkp-->+1gLDw(&s8k6OrDxCA8~`noR6pnUq3jmS;Krp^u);dh)?grBL;CStWKDU za`O2!j9teZ(PGzh{LU3DL>(xb0$t%Hjij}EzhUvBNMZf!Ci1ZU#dnEx z#>py7XCQDgofh%P_&%6Cg14bgbaihcow2Qj9@)S4H1`ZZ{vNG zxR`v5r!z1X4|K;7-P7ntK`hZdlQK}<^9p8B*#sYDFMN+v7|Yd##ix`4Y6;h)po|wJ zA0cCt5*!6*>-m|CVVoEvIMHm1NN{w*mqioyiiZ6M3xN%vQ-Y&=6A6yO<~keV&tif@ zEuf)SVB^S*rMwCKVnZ5ttSmMtCqlUTjJOkq@GsLi!Xqd1t|Qp0+-sLM(4n0;M7TF4 zPTNfvsSy-U6wBMS%!xH{-6Ug{B=i;ohba;>!1p~YMG~1muX#iQr4cz=#a_Js73x(!POD$KnXPVH;%_K)jzp_a-&YpGphj{i$6f7E*;z4~c@)xXtAt%or?= zI{6@Of#h$hc^Ry*P&51iD&X)~h9$;v4@wPpCYA@MM%rtn84vOkTPeX}4&=5v7#7H_ zJD@%N>VS6llLLq$?bf&qk-8GbJ^R^W78~e@;=r+NOmD{kgK24Ox3T=K3geo_^7xhr zSWZ6>p8wFX?5kthL&tL7OcR!qXX;q~a}2{W_5ia^9v;I?AUtx6Y@lGX1CnHptdDmT zX5r8XJh>ky_whL1T>E@=xy7JPM}i~la_#$a!freRZN8&0wFfTY_=(U>K(`RYK?>%Q z!<^bP^ljjd{b;^}*Yo9s;^Piydhyc!#~tI-cOQ3jbHyHa+^I}?QIcjjdhTABpt$xS z?YKXd>HE7U3tyTJZW;e~G;4D9GmGDmTf|yHYkxUw-TMHZ8w04ibAprcU3egM@I;$P z=xsIo81O7J@cKJp(s)yc=pisIkiw9a=Qr+So7Y!K;cGcr2facpE7c&gy}7J`;>qls z*ds8LhK8u}wlv`r(c{DkaQiPBcF#}7oxs}9PjzH9Vld)=jpHFW! zIqK{G9+vkRDTU>IMotOK`!uB1)fxwe8{Zt;qAYa^%ns8eNiv_8yCXc`-483Ue0M?X z3(0r4q!zHn>8(xq?hc>w9O@uC2B*5gk$w=6 z8wTovL|shD#ic@MW8PzB&N4`T++dTP#cXBN`O_!scJ3d1A~IN1^L*-xBv<*?D(PM_~z5*Jn)Fb0ZZ` zxC@jGMd!|SI4^CAk~Wi0ix^(Xx-E@&+sP6^&N@!chDu|%jnj~(fZOAhxQT*y*cdZG zODc&?;Kk$am5&>An{hQpoFVZ&iei}`^C{i!z@KwJMw5kv}TBu?DAwb;RN2qm73``C8xhgf92@<*|Ae_ZR$=|JnLgt z{83WUL*kXy%_`uc4J&{7PP0BA{xOT3Zi&W1)TS~bUWwL{Ypr+#fvZ1eV(MwH$kAG> zxAIn_KcV6j#t-%r2q{$#a7uH`~d=IhNJ} z!Xyr1O+*MwD;PlrQry}p6r6r6HyX=DAmnC*3jRujN1d@sdNs1ItU;?bf+ld4EDdoD zd=v@S%8w%Buo+AH&4sxV`qxLshMGwY8(Q{}@birg&H9KjHhSt70zFI(PAh1|cAy2V-aHHeU`cB*+;kESCXfL^OD(SokRZbSjSGLvOHAJbO&z zquBgbuSd^lb9Tf$^3;<&j|`^vh$(s&x$(87mr$}a8Ai!&s#w)CzvI`}m=9g5^E z<=%BN{UGn!;r$EBC2r1_>$VEc-?xo%DD?wAYr`~sfkF_xCjt3V`rPkMH zFP$Sfa@Ub9TCr8qVoUXVC2e=@&@uXK(h+ypc30%ut-7uD36*vCXOl;!p>%>p5{q0{ zrK0zR3vx_$#>+RkXo~reZq|A^sTK6b* z8+!LhmV~|)n~BDK8QDwYBu^acleILPI=pzSLFvJT=mB8XXnH;;4gFxud!MC&RE;x?!()1%O|{Aq~Dp2l_O8bO0Z*)Sdak z&dCU8Bm)kzy8I4&iUE1v7;@D91H&ZW~Nv{aJpZBvr6m%S}*rV+i2>8KSUs8VIx$8U|*^P!l)m z(*+7;-c7g*hIXrX@#xdgY*l_JVn0f^6JmZ=k@j_`QBMv5DV>Zchs6ZQkXpMtOkmvW zf-^BX!5R;ZVHZ;927W&p2W$AW8pF~Wsqq2S0Qhtg zWoRgiTsVvOS@gGE^GTJzNXPRd3y@&kj6!^2{gyTq-OExGc4EE&>*~s)Fw!CeZw7e zBC(edCvtn(3fs66&$hF$9dUtq7~G(g-oI;5WZS;SMh!XP#+2UFJIyJ*?ocuKuBBm0 zuV+f+lwK5cRS;jj=qRM-S>``)^cx zDDGDO80~q57B1Hw#IgrZL`m9CL-zn=*gLFJgMOT<05sWP?A3l8$+xX z1&GG;07UKi|47niIz2VoS67x62mW?EX%Oai`_sDMo?m}*ckkDskB^?Q;4q zgN9>GPuZnirWvrPOlDXNMHkm}23b)ukGS7|etfc@kATn5CEDeuC1Ln{T%uiWD$(&t z;rMJVp-vB6pIqPI&Brg4ke<+bD@M3PihTFm!tC7eHsk$AC2VC*N<4VdMc4fmi`N9Ru4Z$Yr4{Wr4w_;)gD9z3we~$=lXJ;DMSW+U2yXzD;vU6v# zLmAygmG4N$lQS1z6uJw3dMg)Qip(DMcy|VM@#`?`Ze+^zug?m^Gc?52HyGl|4nS{o zya}TLycBBddv@Rn$mVs>eR1A0D+~E_Jq$2UCnc?ms_Yv|?>^1TBU5Z8>CQpEv@W4V z^0F=$smhU|c*wkby0`mc`E*}ZX$F*dCWcy+xem7oS>b=QBCmU0VEXy%4AXD6>uQF@ z2C!T3$=A$8GuWSj?YQT|E`o>-1*X18h74&p}y8ayd^nKjvgr@?~qvMRZ9 z2Z^1AJtO}HkhD&g#y{QQ(;q%_;4?Lfy@SK}d_8>d)QYq4=?>3MHhAtk5B%cuJRf z@@h6w&5zZFI}a754Pb9)UJspHjSd9W zy+i!rS0_TPG{}-R`iZ+F+^_pCTh8Q9c%fywDY(8IJT^$u-B_bnNj%eRHG;~ zioq6&u*~Ne3}^xa)Yc7ONPF%-q9^Zqk>RidGsCWG%J5YyMX_{B{}6l_laO;*Dz0bq z>=Q+37=4R}uV(%~_TC1*isB3(-7^Hl5CcNM01*x$K)?V=2oNGd2;n0bNJ#h+5Xi>~ z35F!*%bD7eii(PeiW(IywNz25r52T1YEh|;mMSV*+EUJa-rZ-u0HeSwLw_1wzw|47Z zlL9pQg0(qsJ!<{TXwO_$&Lw{tu9z{09R9OqMDXRn2Dj(#++_}H;S2hH4L8U~+~HQv zbQ&*^te+6E?nUD@hU5B(I`fDznOk23MD}OC-+-P-I;I#LN4!jD4CKnjtebG$$CZ_n zVR)Z7JI`jyY_Ax2*L~30`SCzwY#!)FeU*)OU^5x-Ld=Zt%xEl~sCib|Z+JCHno!^S z#33}6U@&(#WvVg1d;{l~TRKu5F;fjsB>p8o^ULL(CcU;BO)%FhoD-s?2}c@MWZ0G)>Cc4=^)f^ljk6)u%Y)fH zO6p?QR?l&w2&w7j^l$I@m~o+6{j)E=v)?~^ zVXAG)Zg0<#;1I&R58>;PatIsl)@=9CR!%Vw!8^Wiig5@fFZel!gTPj z(FsQ)_wn?vfp@W&Z@Tr>#pgV?EU!<|cxxss#jC_UhMA>v-(@e|yJ<%04nMD%->&vm zc_OXx+Xap1+6;cqnrlbEtTTV>)evIwp*>!$ZN{02jlvu^fE0)5uaw}01{4KrumJocP^2PE(;gR1Ae zW*J=YoWEHHgP-#|%OKIu8=?~n-)b;Uly#J zl&kmD^0o)(6}8>1&ntQvTl6A6^PqWf(|K_7c5AkIMHhPxL7!JNX18r#(M8^e7rEOu zuV}nD6{mdfBQ`tF?)hETIXX7nJiv@G#yJ|!b9DCrR8TvIZJynn2h79R^?;$XGW^8v5A{AgFBX?N*n8DEuz=Cr#%KJBlb z{fz)aQ)C2~c)Q_?Ja$E3U!>7ot5nVtN&QNnC*psu)uZOOijD6IL;d1ioNJY8&b7Md zDQm9P)1qaYYxTv`oNINzDCzt3o@@0GchK<4)7D(8`#pR8n0vkdX|1WbRwF$LzGZ?X zlE9o*^TmDK$qW|9RuKD4si)1t#E71sVuU?y3`_LMU(ZZMU(wcEehbZcKZgS)wa1j zaI5v6TXg?Fnx0!!@snq6(aV{+Ety*sug@*ol4N#DFO1U6xkc^z8gq-L+2|OH{el8YExXY0V`%6>pv7 z6wW2uD!QCYbjwcrTq5T%OM9|4Cnz~mjEdr|e&!NQ+9}6=JjqIzZl!A72vOp%)CN(DQ-2|$dXZk+ek}h7ri_&*P2~) zA!ipYd;EVeyU6YFqO0`TMd^>VYUbk{YaeVXI9FRA;#>Y&=$=ustYq_ z7wwGmay?#zjro;)F)`5WqWxpNXBRajdZn)#BxmKMd{V(PQ|O-2$g_sCi@Y~2AMKf4 zzpw7zOnoavoajMN&>E~@41qLP04>>_zFx?z$$)zxPgy}3tPwp6$0)o1(cqRSJ# zXBP!MrVj`W|JdO>yC^@>tZuK_MMwL|O0v@4Czh?#XTz+YSh?;NeYsd`zEMK7SN+^R z&@7ZW-$))QdFC6%#QQt5n_|rQMv_qf>O_m?8x7de+6@>pN5EwNZ^`3W<_!{ew|l|KO1(XA1q{+W<3# zjPiNr3(1?h`b;5NO3;`oWK0uknD&Uq2||DWR@&H)bl>zl2lfdK~OP7|G%y3my4#_JkGoy87 z8;|iDfj>p^;!RvaW@%}0PHwR)BX@}_Pu|GWOIR~Bx46nxSz20II5gW;UR{*u%5p6( zLP2w+#8%P$=%<)$d}&Du@@%nwc4bbb%Tm>As;G2mT1lm=yu7Nc(v_c<;b*gNoL;$E zRV9^0OKrJL8#g0u)`TRd{_9r}d||(e=zc{5gEiUx_|j_E;IwHIGm^B45yK&)diwerecs4-`W z>pI)U@p@ScicrQ0ww-HQzDrKy#L}vg{P8)(#ko0o*EmZ`E1k0EqMYKQ>s|R?`!`yI zb9`}5MTHhU#ZS5CqTqgVMZMYcnd+)6EX_|#b^2G;QuXMxl54Aq%9jN!nWjaj`?j3a zqKZ76x$E6b7oA_ z=1mxvakVq8q#9=~-&vSbl3(m{_A6q1Ms7uEu?wx%cS9;VvhvbpE_)KsrsAAss6stm zsnINR^77E9S;@zjng>P&KU;iv=~KqaWo5=*HEmezBv)m6XA9mXYn8 zvS0!xaRd95?5-GK70q%(9ge5{@JAkmDlBz zn}?WIQc$Y(i_0HEL7Hl3Ki%{2NoQ7>PX<0}Q*%nH3UczKQp@Ak}`@@uA+=DQk~-`*V3mX;NJCpTNr;>Hbc zu~);>lWJO8hSi)(D=J~_p#Lf^c9jo-I?tTbC5^{9FBWY+vF2*cmT?wNOaQHbIcw9h z$5p`|Ku?%c;S$qL4pN3mjd5DBt7LIyp_F)hVNN;D0%|k~BUV99Rk1xMtBgs=B7P(q zf0k=$X{C#GSzhEqr?|}M*M?`gFcP?`xe?vpC?EZ-?Cdmjim8o;IrM>Eky$Kfd|Xk~`Mc}P^m>S6o^FJ=?`^>zchQou*;qb8Up2`5ueZXFCoipH=IZQ!Cynvv}rh8&*;adQe)4l&QvOQmp!2;46Ju|UW6Y~;TK3ecN*Th&m6zu%(;D||$j-MtdJiM8r(KJ2 z?z9}qVRjK*^_;StyrRlwNn*(56qRT+AZ44WoupOBFlY;~MCtmFqsJH>;565D*5HZp zMem0->07ltTo>hfA8K|4Qa#nKamB@kzgYoC8Z|1FXKXQ|$6;sru9_q*CqLhaN#gi! z+DJ0u$>^L>zzRf!eyWNpGINULf+^F%+;2fnb!mA~rOPTu9{L)Fk~G7Mm{3x+RLnGV zC?&3%O5P-a0aEB0JmGyA?a;hxS+|Y43)X`%yd)L*)SWf(ASb(r}zK_tH3}S30x9PSPtOiB*!MEi|oZZJ|*;3(eYEh%2n9K*kNZ z`BaVb3T1nvTgd9y7Mc~kP_Ood#ifhWQgw?;ntm27`Xr+{1{g@p!zhxPHp-|i^f&`4 zaU+srlM;#&i{j$7>O|pMkpamDq!>^g7cZEc2sXlC$&$nj=;`BQJzI+6Mp$8N#E!HD z3vS3L%el77H8oQ|?6lMywd6?e9wQPlfjXB+EkzRtIN2!6f*bsdZC5N{j z;luN;mcQ9o7Zs;mD{Mja)y2h)%aEL$e4{L}gz_eM%D>K_ z+W&0ljgK}`>cqI1?es=iuzFXTotinl%H^?OhoK{=>~%8znI zewiNfSQ*B^|T}9FLI87CK>r63gJ>{nc@-*1Ua$S#ullDpaZO$Xktm2JjdPT69sBSRhby4;{LZrU`ZH!~|; zS87TJ2c!Sje2P*Dl2I|omH-`owc)5T(L6bhtF?Sfh4*Ijz2dIJcvI;ru@CKN4)!xY zE!()|=A$xmCOV~Q*`f)Urq`jyx|DuuW=RDc0hiqROY#$)UMhX66|bv#I=Pf(IKm{u zZ%lHPz;x5QU>W3CtXVlIOOlK}-o?#w6`Q1`#IlB0=oM-78KzyZBG8`AE7I65*JF8s z+{CwMo$nndMKdpK%`!hdQC`aW+46gEehxv?nm7cnY~{wzw3+GYeq!M$>iKIv+dO82 zC+*-dGMYsXgrS({DynulbE^spa9xW1SWsMgU5Pp1H97#}G%$TGnvOh48mQ|=&%1h{ z^aqlm^bJ;IiGH8Vw2~xx-qqH7T(#=Y8!x)-KD50R>L8YOn- z@!&m{zojSFp_hBY`f`djr9W%YH9TFo-cuDhOABO=`X){HX`BV+E|<*>so*n{3TIJ? zQ@=Z7?Xwgo#+eJBFjxF~D~-SM>AIFmblgBoizSt3SN1A3VyDiSsaIy>c072DX51=p z`f0Xa?uS=9^mq!I|LCHM3D;KT6esDHIQFhtCaR{N4JMHKlB4pe@FwOP-ArkW*YCk&8viOJ^c3I_h~8e9H;Dp~{sFN6j_PymVk_=2<QF4JE?I@QF2O3%C$GJk4VwGh$~Voz453R7}>@0Xt=aQ5)>EDiysjmmynPL zQ!FK=s0gNCHcUT{ow@*4Zo1uYl?bt9HSK>^Xg~IzpW}$E$SJ^vNb%w$n>eOO8OI`v zBA4bYF3O9`jVv};yfCBJjPx8cm0TVrVV*t}J1eLvE(Vn6RWB^cuR*TTr5O}G9*oWi}q*;zk)8d`8w-pID3K+35b^-5Cxe z2Qm{eV9DrEp$`xG2<0<$TF-&dUpKKazNwAFn%bB!&{h~@2-F{dY89@Me62WMKkV_v zMTUiH-WqE(KBgz53K|cO$RIDLOgA8!%ENbTO0bPhMh@1fq=&uDDetkyel|Q~is_DN zez)o)Od71zrLaRoy_d1wgE>U*o}=G2iVnXn%9x| z9a0(}s&|~9F~+{R$sxvP|9*!7yF!-CP$?){Tve`*BAzk9|0Vc;Vo1QBMD2f7p#RTy z_x{?qcW-akh(x8KC-&n(#i!7$^yw^RY)EXpZ4xdR-Mg>QJoc!j^{cSiq~;xP-|OD4 zgpMqr?dqjBY@p3r(>u{7^VI?!jX&cV8OUS>-dlIoU^J-kj6IF2O2(lk>x15``GB?{ z$+TN7ZKLDJS?ro&)KOB7^^gjivs`i?O|CoiOA|`+%9rU`o6n=;^4dq^BG~n4S37-G`sF(ZkCFKfe$Rma z`Zw%y#!8h>v)ypEO)e|2&DRQK#p(Ch%S+4PG)ks&Kg-s_tMt3bW*&TK*CKse!}M}? z=^y(|o#XYywWjsd`l9}k+Hd%=k#_@UGOR#Mc`^~ry z7~`}xxT1jmwvT<(=yKD$C*N4TqiWptrSmeLVxiivbS=}L$G`$*sSPs(?>FFkV(vj`Qm6w73zCdNM73lvP0EL67$_#K&9P(G_^^fE)Af{BO&ay`#a& zjbiUfV7A+l`fW;kgxrU{qht0YvzZafWRMiNke22c zPoAy2>ArW@CF~n#zY}k4GcLKt*CNJ_(md%N?T@k>9jFvi3=n;;Z?%2{PK%Gz&BaC+ zByR)wS{5VivGnP^;u>|@?E1?5UpZbLzx|vynJmuStUEAp$h@C}d5!IQ&QLK2b?a=K zL%Xiw6cx{)9w-lMN}iv}Xv)ay+v)l`Ad&1tmZ&U2noR-IwDs&m$|K)T z3;OJwyIUZAmisv5`{PaPNttEQkmJz%z!7Nw7XsE8u(pjR59#II=M|ryb9WAyhR3NV zZ5tGB9Ik%6HBg=LMazyi+&V}4DQb8BiXxmM{R}w~FEa7mIrn7&j!(9Wk1-88aZTvR z@*eY{Go%R}`F>nM6FPEi@+G<`99vck>M@$M!fJ z5j}a6eHZk`_|*&2cP?d}k4@i0ucWE6h8Shlj~^<_Pn>gK+SKtQS~Z+=UmdWFx3po? z&=TbM5w!#QuLW#F&<`=%PzNKKo-Q03(O;c&|2bgUk&bQeLR-2_XdFhmmmPu9S#9=0 zwpmG62aU|Xp&tmCj>l!&pPY;R(8xb|&ONG`bJl>E>K5pALV4<1pqB`}`&yv42ztAk z(UU%+4tj4u?{2?(MjwbnXRl`TEBip4e?RB03wUnVnpL-^Ez_Kmr5lmvffnvZt|58v z`BS9H_nXFOz-xkx{4;^wzB%VU)>N57yvtOJG;bhHeG896u9bSEN%=N#za({k3}gy) zUi6!9kY4xF_M|(EJax`}i{G}_&VEg?2^wv7G_d@;bM6Yi`3D<~HAJ%yM|!y`k*@#u z=iEgB%VqQ*+a!PJ-PlyUFk?AShoJv1^b7s!dyjEv5bX5BId@7EWe`0l@*mWUo|JVm z^iqEa)J7VQ$u;0LKQwi0RzD{CJHg+AerXHq;wX5#)92h@H&YkVmVz$Ov;)wM4A7QD zCmK3$HlZW?Ooz^X=v230pR)X7@Q>%*g97BIpMU6df=;d9{Ji^m{rp3}1p4j$wqx)8 zpMma_pU%1a2H3wJ+s&2Z$96k`JYJP7R>U{CPth0Kt>z!+++v_NXP4;x0^|+ouL`KI zA3Vo}AU%!rAt7hZxyLr0#;Yx!gzWpLQP2L$DljC1-ix14T0S|tQlRY>#cJAD!2O& zO}1~^W-^p(##nV2>E1-TnUbXE(5BCkaS7^vNPFz$IMV$j=|cUb^D^el?nu8DQ-Sxj zal0opSypeqrv{3Dmv@G=cz<&3>;-NPa=X8iUDf+bYhA~pe**e5+Pd8bME`}R z^`&fKsLTfF%PJK?yIWVbOr$;7&MluM)Pf#pzHBR@Uw8raw>Gc82m0;XQ~%E9^^Ze; zC-h~F#h}}o*Y6~Dz=hOb*L+*{K`*b>2Rw=A?ARMGUl+U*%^^yJN1OF>O}|w|iBZueD9mdSfu zUJjLpR-`d~-O!8O#(k4hF@Dmt_bQk8x_dgi-IH5bS9+h0E$<^uT);Hen3#;1BQ4Y| zM$9KI)Ro0_j<-H zN80(4c3khYPCG{=zU z`WCbe(JvJLwwv31VdFmZ0(*UknIUD`DqY?sEpHc6Z{q8QAWikpsJHfro7l?zjYd=! z(%jq1{pmIh;@&{o%L0xmw)-Ns`(l!IFE;HCck4cV(2D3*wXIVKoCxQ+UfQ~}vRZ7r z?rhT;El;bTf28d%X`4J=+xdrnRu8v+FQBD;iTJwPdbI8wY8WowLYkS_6m;)^z&1%p z@1ynrU;s_v7?_6fz>Zi zK=fSb1@yNy&0|NEKyP-FWwjcw)Q#9tn~|o2YC*mFT+1h+nmfqtb~WB#kiWJYfgHC& z|7O|O@qSIVbtzjqV!w%TyEEjx{n4L(;Ok1B8K@y{cTK>$@V@_4kJu^D-`_5fzW2Qq zxi|1hg4-?M8wgtBuWZ)+Pq{ZRakyK5&eB|2{9Hd5PV?i3>_vXd0_JCpxzY#dehBpQ z+6K~RJ$BVReSowldFEDmdCS|rlx@FIq`6ei@jX#Z)}xf|l@^cCxd2{pfU z^p|v79YwK@wjkfwX092zw{r-3BU^Zk(k@p*K0z9Jw=yW!Uzr1sow8(g=oq*D+%Kqe z%hO6(&p?uqHt>Be@3Kl7>0?$P&Ei%ZpL~n_d8Ap>bQ-_MC*L{z7t-ecjI>9g8acMP zK7OrF7QFugjml=zHtyr~`!CS=dTetxm}Qf!6hAAub=SpSZ22B({uD5cw{L#}vD?SB z&L5Hwi|s<1sDNp#`--X1-2vT20d)=ENy<_N-J{T5*j!mUTJ3HJ(gdZny!^VYf;63w z=4g{?yzgJ?whEN@Al>GG=gOE^n^gbkrJMk9EM&NIR*8$EZJ-h2q>) zzhkCfdsgowp|}BQeh~Guz5S%2bI?um^xu*$8Wl8og4^9SDA2xa>3CmP(k()|+%(?v zInc8GNnMJs7Cpu7UL7!<*Q5Y1JL?G2mQ104-hwtJ*Od5bTao4?8Eb9|yg$?aNQC~F zscyHl{h)`N)|cZc6u&Oh?S8tsw&CY^b|CO3(q7y2c{ZPS>uKb*rTKgHeVwZ?$YcfyUfxC-@n2Kb_vPF}G8e+dZxo*Ud^uCekFdBF$c=Y3X>W z+jWrJkY-H4G)5mP`O9~Lw?p@yfVz$6Zpr=8pzNPFKGur;m)-jDQI2cB*a1kJ+01d7 zcKut>y)s~b>TL^)UH|!vmW?Ho5z}pE3+xfwSh8Gf^O>z1Z}(u!ETnlSU>fi7Ru)@7 z)rx)S=O1a$B2D1ugN^S^Oh%fpS*;t_m&OThQcfY=Qy4+)3;CBBg^-o2`-;GLdMvkfV{j(Ygy#L%WANXvu#Lfqympo&-#aDCUx&BY zX3_mV$froVP163db!jEduSsSpg_P!TTkIn5$T6cd~?5k*`85}5$X5G^m0=);Dxi8_*|B!ncn@U?ZF4khp zw$kRF!+W0-sWX{V^#;;?BX#!YuqOL+Ij)n4U0%U^evYm!9(Sbfc*Zuz~B3pA@w)SsnX*E&145GtLnYr>|p`5;@c zDGa)20_u7{TR4Et$Dsdx3-qP@@&T|1YuxfZ>K6NM(XwS(Q)9OGye0d)5Bboz6=|;x zcrT{$wI$`;hOGx~Y+XGc#+Ji3Hq{2KKJqMLK5b?Gu`(Y7X;NB{|9q+T6|L)sHp!ev zr1`SBc4-?^qzxQIx>u3zW@(#GT->bPd`9j!u5`QIvWsW^>0hMzyRQ}taun(0`=hN% zR|v9wmD~NRR_ssO-FA?e)ox=hwcm99+nt|&?e$@PY>Hb~x7?<9V|DB9+lWnZZgtCT z3Mo@P(=<26>oz;2{~EXZ4^57djeR+pr+u*2?LN>7`$K=0CU)dnx4WzSatfP2TGu*TBnn&3tZUvDk!P{zp!d+vutnrqZ0`Ej^#Nj2l&o*P zEpl4y9;ACkY?0le&DtVS(CcwKZIQ!)_5Il*^8VJW+ncvVpuKWviI76bCdjjpUnz&L_W$R9M`|6~3CL+k5IXcQNR)K!osQq$9^!Vl z8PElKZOsHx4CpU?CEB-$s=PKi*NoW0t@6=eZKscF59xtq7Qeh1uT}VF6k(6(&wyM! zT9U7-G>d^|L@s0^WS0cKY*O_ainzs^yyNSoD#saPM&vUiISB1@-(3Bw-XMV&n=OE- z|4srOnk;~e8A&&&n$;rJ{0tbG6u076ia$Zjr!64&!CEwR^{IjjG zMb97(f4bNYX|R1?lNgXn(@#u)o9eX7B@;73W_M&ja^!r7OD0=KNuVc7qHmdNzqTrU zF0^UVcJ4DH{-GJYQmLdHYgctSjKk8m$P_To5j;gTeG76NCj)S%x%GA)j=T}0n_Qk8 zWzJh~b4w@R>%Zl7G9cToDzlYdL1sxZ=3S+XU3gT-+EryTu{h59xYh@M`q)&*^|7lC zV?cjbG+pz#COlgxs$!IC@&tXTx#e5#Q{U228TUK%-!GLd z4RT!VNVe~N3IqDLXNn+Kn_JFlMpqzTbhj>c`7Lu8)unIw!C_p9^74Z=i96G`lqh4Y z*SCm&+o}C9oRVEkq4ux@wz6jREx%BPn!e>ns;!Yg8mn2~QqF+BKcC+Sv)itAPzXbJm{+1c>qh_3*csZ@n_6m|I?qkfrL)`L? zsJ$Uwnz9|A-xH_Xt5fV-e67)WBkd967|_=^S_D~aZuwL*8p|cJ&!hG-w&SVNw~SCe z)z{UYz0CHPn$}k=xxuF-J>pq?x)~%d{#?@JR}9R;y-dVU zywr@4hjzmuA4%Z1_Tqi3HI;4y(|s&~!*~WWSW*>o z!1|>o!;;gc`oC#fCmmLfKf7rSu}7Hxlz#qXdby`*eF*sq(oGuB$M!O|Woy#647WF} zKtFk7@3g}x{P7hIEd~}sCZrCstGBT|s1Up!2PRY<5}k5zuR2XdQ3RC004RUt*QB9(oOxR=NWSt6Qve%fr3T(;_+cxYi14Ssx5BC7ZGU9#KVgV<{F8@R`z*BaS{r|Ch(3b6n4zw^KIzw^KIzw^KIzw^KIzw^KUH~zlq;Lwgiegk<6 z@&@D;$XeL$8C@J&hpzDbfC;@E+DPCaNN-3eL>7zw7V;V7DC98Y7m&S>Tx@?7@&M#6 z#JzV|6G8Vss$f7u@4a`BUZr=G-g^;{-UOs$BBA#tUAh9&i%16}p@|66J0V0+0U<#k zK!BU~{eAC!?sI?l{(X~YCi~g5d-j|;XJ$8ZW@jdJCepGmI9fH>l8jhS$e#J*$)6}B z6L&n6q?aU7MIEugwDEmn`*9F6%l^!YAmH!IbOtYGIWsfeD9NtAR-iQxa-q>g8&ypEPAPd^q(v z22BbSO%fH5wj`14k%nq2lGbL}V&&PV!>fuhn1JIGmWm_(m`@ewMElpj3NPaeuj3B_ zWU;+SMQBaBTTTU*w&Gg~Hm_UyxT5v>Rg`^H?_g2-zcjmSkm|gC+3LkG;qS6=#vt_z z>6{rl?!kp_RNw$0af~YdiSDm=)uX4X#M+rAHaCW{4~M1S7CrOed`Ha8plWj1JoFL;ST@>(XZfh^iLUS&^bfD?#)%~X&Mysokyv1A7_PmugRiE;O;l+ zHy`ivYYmS*5BH-^gzH17l&UM*D@yQ}R8*Cp9fjP9x>e{_U0_9zLxep+LN8@QPreK(_{5rl%vH1XWth}{OCOiN4XLxM0f6@Mi zAG^o8_)na#-a^q8nlKnNMq`gb2nO5v~r?0omR%04YBf|D3fBzrVM)g{( z;ain<;g3Wcd_}|Z3(goTL`%Yrna3)9-OSxB_~Kf1;nB?9_y3RYZ7F+9WW=eux|*$C zrLsi)N(zGx3IA8+*JPi~Ve>F4Sf^I6Ge?9gV7_^_f)G$<=W=)B0bAJLOMt?h@gAMrSB4^4U2K*Y|p)tAz7Am7(by)?3Nse zyI!5dD3cs>GC=L__N*whNC4gc;$)g^$$430O zG$Ils3IvYb5B4io${92cwMe)VskxJlTxldq7&Oy)`6#GUYEmX)7KrDr3KDtpaq>y> z6+OvC#*cXDsHc+iVN8f%gr2KNduC5;PfAZhPkv7ZZY`m>p1hty8*q{eJ>Rc;BZRRX zK0hfFvx2XQ5}A8$q(?j%$kx7{cCOBn|HlXdi8YKy&*XDlin-@){}iM0QbJ@8LV_WC zflJ%5K)a`db^)#20q?hD{~XnA-49TGqNF$IwxD?bkniZwNK^Hf5gVZd7Po=Gr9Ze- zy#AlU`d?)NLfl8FBZ&6+Pw)PP8TlEfuethFe0!lF5kfrfow!f2FEy0CCkD#bgv z0v)T9di(S(6!Vy5hF{b*Mr9-c<~mj=;qbJ{1sj}bP36nzJbr>R>R6ylgm4h^Zn)$? zT2B%xnz4oduNxMWNKQd6c}p>pl%mT3ezW5S+f7%6zQ9NE>>5kNltd(=JQ{HWI5~qy*x61Lh7yQ?F|1sVFGMurJn$i;`f;Wp& zS=7dqUC|^Yy}A`M3^eKngGuAM2K@i!@LwMPadTYpwddMsHt{Y|%2CKsc2jgybyIdz zhf{=8g;QQo9Hd;w7CyOl#XKCzbc|a|Xd%08bkjye`|GABr$)7A2uI9$=$;VhzMNCc z?DEe&>F<1X=b|j;7~;KOd<4a_oLGVyM<#Tt;5$wb5a>eD7&(pg~h?&EPy zATt9X3dzBb{;m+A4n^>d-T7h`9E<1-!WHX@TNH`p*wH zWcu7rMxn|IVSm>oW#P%c{KZcBtr^kE=3NJ0+%=&Z`?rE}@Z_iT7(k&0E z2!2FFcEqqT7}Cbc9TyD`q<_-gX3GhMQg&s+3D;hd{ha~hYt|)@5wTIdrF%=Up(w8u z@%rFuF%t&YA2A;rs;g#V*>QgSr6Md|_1CX!4zkEPH?0>I<40C+7G^Vzn6ZGZg=Ibinvw7 z8r_U%fBhKe&}FHitcc(d2rG4KOx-+S80>y!>uP&=oBd@4R^sOK?^h>1Y|nEnvn7ze zw5X`3(a}#uAx^#U6Z_ehgdO^eWZ*H&+u+X<{UKT_Q$7YWHw{cFBF`- z^EzU*HT1r2{Q9wr80VQeq#yn&5ghha+mT@4_lp+uGKECkhs0a8K{ttvRio}@$&yS* zU(`PW-3m7PjD}wuL-xPm-;bg~4+!UETEfkKy=RqF%wm#$)OVcQ%@U_G7SI3kTY0(b zu!BnY#!B;zVy0;xxuPiJS*qIt!FYW*^lw;tpYENrjL&L)5^If+&Kc`!v|lrK*h$gW z_n|_kwauOqtCxQ4VcvH`uM}P$&Q_h)PsC>)DLO40l9ROk$WiA1=a710q`Un$iev*f z;mQH?_G2Zvo9@i}^Iyi242cdT!fYLznC`Noea8Lx<3S6eCoA?R_4ZUDyhP=nmF~=UR)SGJlEJ2_(H8mrWMM>0@*nZ@KW#?z#>0LV*DwlCgTkqw z4&|md*W~H!Dn3@h8z+=*HQZz8#Lfy>wb>23aXZT;w-?EiNxwd zocf?DS=88%DrdVwGSbf6iEFlWPG0JjL-W# zt&0up55Vt?4drCv{qACbRBEW@ za`K?hbA#YTf=>BMv$vZ8eA+aPJbq@~ zQj1z-I3h(0$Q!Ze@k7APr}=CAL?uhgGw`ECUpu-;t_ar1`A`1@_P#$ zwyIW*MUR&pES|lH-1ngBWf^A*ju`39zapj+HS|Q6!5a}r#zn6hF4T+Z$VVdhry3f3kLY0pEvn21c+@8@SV%sagMk;&&thge$BdqfnZ4OO@R^#;d)Io^iGEE zChWmSp4byQr_}=@3p`QcES0NE%Xf7Q)ZbXA+*!VF&%p0 zrQtPoMs0rXHjv+)|1x{MO%?s} zA33*}$7a~bnf4IiW`7--2h~*UBvtbiy(BmppY)6cYu?iR(+!n~xR0>T4m`*_ed3gb z33K^2Ot?mI$#3nomXF-d(qVrx#6wJcd_l6f{M zMq`LYp-j}p?j!}NJ|UGA!-QDQ6}t~EbEvuj>pEr1GSUW|5X$+iJwQACDh!^muErir zkSjyb*~U82iiRr0tk3rUemf0zxJLd+t}q-zJbrjdvas%ktZN7&n=syvJ4lG3{Hjz* zc>OU!{sO7$m=&gRJEvx-sB=q$z9f(IX{bH>>wWT0frUQuVdi@X*8I)BI(kC2hBQ0y zsLuP2r=s0*{z|(oOXIrY=@2i~^1VyKS#aFIm9pV=K@6bfU`ovWR`&&Io|yVJM&k0; zUfd{WoNLn?ef@&PKf2u*pPYL*T0AphV3>MbV<@_))}J3tbUt~Fyl_lZn&i&;Yx}$<)n`Enn{8ZPGl;=*6ZJ9X|?@w#G5-m0WjkS5pjc$@Ryym|2 zdUul&LytaW@qQ86`?w&6_od_n{p-S9Fj?8U;j4uiYNU+ji;V16g1aIm8mv89t`e;7 z>@)=*oOCZ6=RvoQLuEOfA2=C^`d0b#70Uc@;&vvzZ7=4>kR#bEw={4ou0bxi3(rKx zv!|j8J15uU3Uj8e{0}CF?{BL+k>4uxHl;+o8KB36<3=|bL#`PemO>AWhaM;u4=`gK z&~*X1;SRR@GH6k$Yq}HF+`t0&pzBW1=ke@uZhx}gM`h9YkvtejNwl@ zQe%FNq!RZZd27N~Rri`Z5JTgFz5#!UFf4y~E7aRmdcoP-R1=CID|g;?tp!T z{t|mxPmP8}wslRo-+b>x3Wl@~t1D%}YbLWGVmx4$7@0`%ITiKtWQ=oOMW5dM5J%ye z;i9|Ju-E$FBsniPIM{YQnC;RYE`u!ne9TpNMsbnLe*cd3G7i3-ZEan}BGF{em^Gma zXyw^{03z&d61-x$q``>d#vo{5$&rCyw)-N)*Le_0xl?xU%qOWow{jMSiY@1f5rT7L zxG?L;j)EQM$yUNZ#dv?(0WqA`C3-ENPbbKy<*t}^I%E%PkiuprR_OWq{h0~PiwT8< z0Roo;zMQ1j&f1`RM-7P%ORR&1G5itAk&iLs$PTNYjA)Y+eb-eZP@3;oWDnm`4j6JC z{bqn^gK-@DW1By386w72DC1|H$L|sYj*pp%VBzj?r@^hU^&nLx>DiN|Tj(d*mY5@(Nv18A2WT=p|VW zzgpeVL$>S264^{8HvgK}1N3uS8XywcQ=?$p-80r;+tV{&wATq4H>s#^ac%Z;HR&V1 zR;73aE^+|40L#5%lr-sXxNtn-p0V&frAh9@1=(@_>k;}G+RD96IF#?Obh@cKq=lRD z?kk*MoK7qEn828~uq&(;mxZ%)ZFd0nGqE{}KiK&g2UroUoM57>^~q@U{VZfD`&d`l z;{)K4%cD!IqPRznZY<7vXJB?*U3tCDCwA{HRf&4p^qW`QaB9$D6nZ9T(2ra7!7V{= z6ZtF1fK*H2xpmvH#vO&GsPBOX&PQAMR1;NpRDx|=!&NWsPNx6K^y?HYZISSv-$+~weQGUcYuAG7mdiFT- z!O4B}MbHr&&kRiFA{_0V9G(}bUJ(@3043)b61!wM*+Cw?C^O{Rj*n^KYSqQcAg7># zG@z>Xmdi3^M*u1hmz{`BxKAIEPrAQ4!NJTIvk%aVWJhMfwwh57dYcH}s*C#O(&L(+ zKfV+0q(?YeUi~bbboW2m&Y4o!<)3sXJs{>|a#&)|44nzL4(%1Wp>iFK?AVLM?`;Bagi%fL`9|hVDJ)Fl_MPM5$}Z}0Z_{)PdvBBPZR!X7n;M)@ zSXJC5j@a@@MGu0VjYNGvI2+ z#FOsLCrsx2b5)x-RZUg3MSbDyIL^1KG8c;@Rb`xoU4x3w-Y;xDRd98Ct^y}R^M3AB z-?AJoySm7o3deWiDLh*N>xv#s+?6>j(F}`k!qKF$x5y5@yNF<0w`j`VCPgr=QYV3i zCv)zEksThFxR${PlZDHMHcn|p57x-J3j>+HaTLnzG)}m0V)`e4+TS}vc8uNdBhj0& zciB_j_;2S)M14V7{Doa>^m$WuzYiwel~0wCXx7B63EWmE5}lDC@UN6L&dP^h&vcKZ zMr5&4c@) z;`VJ*WN9{7_EHbo`vxoiFHj=%`7m;F;x1ImX-zef>!nfNGUuJqJgF1G4FfuVW%;=j z+x1ue)}&h@DYi=`uVCaI(72M3DrkwH}?>`lZu@Fe3wB;TfL!&mm4}m zwAZh2cTMzTzdih0)=Q&zN4e8iT5CJVJWAE17+wr1GP-S>aMFD5gg zZbqFEF;VuPhZAa)+_d;raa{7SAx66=Ga$?>E2rW?EBzLk8;G%mJ~;B?r($sA@u;Eb z@t61+>7D_?5XRmCMX3ZOx|sWsBoVy51MHo+=lkMSJ<;PIO1Q(m$Eb-OPh+2m9?v-_ zO~E^4#~%jsVAM1;+K*UdksAfw-JU~TNc z56j662DMo354WQN{RgI$(wqZ!rThoJj2(BNto^WU8DP)dol_A|LWWoeDpdCNT?Y91 zZk=Du$s*nG*nbXM_Q%F&IDh<%sPR);9t-S5(febCnFIT05jnEu9xrU^Os3jVlFY50 zsA#{K?hN)e)QBu-1AY~rW%PT)=KLgAn~uHi)KbB?6J>yl_Wn9JdR{DYq{9q;nbXzk znI7@G_+u3FU4B)~sirIlHg@-Xm;XP?+;ulAl?6Xi;TWG|^x5SmZ2{kMkBm9Wg7Pu~ zyHMl)Sa)Xddcobe>}^IyqeEJFCkiU7vNg898qt-}`VprIs4k;>oZ+0jXw5~7Um~&S zi2<(%6*+YlC3A9J%9r}T1rwf;p-dPulVaHp_LeB2%>c0J_%qowQ>-V{5f)XA$-BD!4;9zz zF6yd`>uDD^#o9n$B3N8iOozH}YTsl9hIv+=N<#PqD_Ov#A{#42#%-P7%$mt7Pe!cN%h!{!d9%BzG%P~ebe?H45 zMTDyd#BGqRKIp~oU<|Iqq-FOP?FGPGb+AVc=mT5nA#c8#)!^m%Yq! z{RTxeee)Hg^rw}Rkn>n=D`9}}G3*tVAc6s{I6;`bt(mE&5+C#6k|CG|O*p}CaH4HjcuM>U5Lj}eyX z2el`KCzU6qC-pu>D_05o2RYSExe6~(-wf7bTLTv%A(JSa_&IQP+%q+Um3F@W1N)j= z^@nH7In6LH%r|)y_8vy%D%hSLA=3WV3v|AO{pd{FUV>W>F0m&)LK#JXi)&=SXkn$v z!YPf(jVZp#U9i#=-;_PVfP>_N(V1<}IrL!n_2Sby?f z9saa2K}iL0pwJ6+at-2AWvy3Mi^;}N1Sz6i5Zo}`6vgB$N_Kt~^^K=7xfmLhcXcmJ zUX{K6h)+d-Lo+7R3uHHoeOGxYsD4Tf!Lf7ZTcUR69MX%)=*hw;phyv7$=4~vJVQ^h zv^bAj);is72&5*b+U6Y6NAd&Cvbu3f^T4lR+c*jFZ!jG2HP~B-N>As{My_}7$Pxen%hkb&DX`P<7 z9;MJz#id}C8a+T}XI!oV?cD9uITi7<3e^1+Bgu{_o5_3pCet&eVf-Z(+(%E-If98I zXRw$pE&iMelErVv@#nn3#gUiqQg088rB%ln4W(669w$dIN+ik`d4XDj1tbb4W^{e_ z>bR3|Rcs`MJDEEr1!fB4LHxwkYvE+KWH($4D+oq|h;S7O!VBUGq6(6f$dFHn;FTzo z&zH|AQvb$d#P31bnIe@emC~8qnG%w0O}S6CPq|Os$|uSp$|K6PM-h?|35%&tvr%&} zz=gjk3n^MT>8J~-^poFfg+%W7ru>8fU3uG6Z43u8Z8RNp2FfGwgC3)F5I}?>E(mA| zTZGBL?6_28YnpktG@7_uxVQ8ij5pLao(yC}C(l0s635H#YhLyqZknZh)$R? zY(II1+L_}o@6eN&6pUnhIR=QbMEJs9!Io13DZuI*##mmIA)+;zFnO47NIRx9A{#@7 zazsSKG-2Bm+x)i$5k(k91R-pjI*US;2c(59ig<$|MDW8@sj?{Vw6Je5o`@iXCu}Cg znZlUjP6L~Zv3A8r2_u$a!<5s3lXqnpQj|R|b{q~nPEo}LZNWUZT3A9{D7pd$ro1y$ z(#MjcSbi8Tkf;`fzog{(#7RK8PPI-c#_@^Y=?Mv67)K(77*`^dB9$Vg7+)A)7-u47 zKUF`a7_PDIr;etGrs7U6q>84DrY?i2z@E4|yVA6?x2p!-lPHnTmj55mkdK#t!=Rte zJx2Zik5`cIFb{|CaNWBxN-(b9^I29$-T!&#(1BR=xKa9ghyR8 zDLv8QevaUj8|P$pP&Um(#1o=ONF@QmygaOuw34K`_b1~GlAfz~a7uAV zadvWaa)xkNtM6&-sqZnHzgonb(3s$Ql8H)I-?6b&fdK?xKT4$0NafJySXN8r)aT^Q zHhaQ|w0rXS9iAD{2Z)7cOWcB5fqF~Q#ywlIUdj%Sz^;{ zQGH20AfYMA@3mk220<@t$7DpPg@57((JEdqaj+bcZNh5ef4}JOS+mDE{;zuu z5H0yvfbm@oj?5o&FHGEW=x5^(1Lm9svXqKyd#fE}Rp z)+ZyhF)sjj_RtHfan1^Lc%U$54G8)K$!dl>3uBgmpe~4UGu&7hGY15HgpfDGRfRF% zfuK&vOcPv881oef>VRZ5!P$i|V?av6ixUxAtRA4k3|e7v z!b^*N0$?|Tf-O#1X|Xzh3e#FvK};$TR1L|hhqDV|5`my9h;cofTnGaJf+`{8_3%4E z3LS6?S7Q_SqL8XwHT6n7< z#s>&0fn?RfD+DnfKu|HnxE7uzh;apiiXh~*aIhf82?#2L%)EyO3S#VlpaMwNd$_Y8 z#tI0^hZw(y8w+C0fS@-J^7n96L5z`Jfk(p3JGhu2Mh^(eg=D>hvkPK$fS??R@jE!V zAVvcS%7&1?d+u#zTT27V%5@iU|M0|C)U*Kj=I6bgZ2^od5R?Hiu7S@8U?hQ{bO?D3 zd{_V@s#lPi_jB_3q?oOTenCX;&)3gCu-MWOfKnjF)$l9<3>OfT3?Z+Eg9R{bKu{87 zrV1V?fMEiH5+PYtaAyGw9T1d&TW%9>EP$Z`g5n|MRd7`S3>gp<2brmaiwR(WKoA6y zRS9Pozz_gIu@K`*IJp1@4+we$__w>~=-UbzB>4M8$mpKS}ToCCuK zA%?BbW`tMJz_0-bY3s9L;g!F@uztvN%d=MDl|R6+K1fE(vkKvrJz!Wb#IWUAmhcJ! z7}f(JZFvS3UfBYMbwj3`p9Ko9tO3J5K{A@3ISa2W0mHf=hRx56g;(Z)VILu+&CgVY zSH1(oIw8|d&%}gRz5>HKAQ?^1*o9ZdfMM+r!=`8C!Yf~ZVQmo7re}9TD?@s>&^^nx za9Te{fTA^Y%(5+z*3TZ$Zw0NjZ1be`vjr$xK@%<8oN4{60sWRx56d=dT0cvGq9s(v zvdx&*&m7Qi0p+u7)1~z@1t?lT2`t-GY5j}={pQd;i#9o0KSO|`IdsgTO^nu0AJA_G zt+i<5r}cXZP&9)kTC}m#`so7tO`#qZZS=H$+5kmUsE$P&Ijx^2px*?_XVFGT>!%J- zG=UOWwB6D8sRH_qp?l_Ssx*Ge07YZyn0ebVjh`Z*-w0Z3-nLKU_ZXmP1Whz=+oti8 z1N0k0Jbih$_(%!(V;H= z4Df$%NR{slv-7hpvlp{vvh60Ov%9kGIYP5Tv+X$#IGH(^IlI*ZlKdbW_g6`JsXG9{ z^vHk-^O7|iu&=k)VkuDS5*}9yH99imYNlN!ui6W`cG)V6W(Fv*S z&1_H3XpR~6@}z-#tHhC%Xey-p!^5ZJ!r9iGt?K9M&&v|z-rOoJw6ml2CrTgQ0l8+1 z!5M8z<^}uHgwXBS0pdvV;D>1DWF>Hc=Z_>PnDFu*I(mX~A}KqIgIzOITUE(?%Ve*3ICm1BU9{~pkNSfU0*L3{{67t%Uqjs8J?jibo9kJe?aXYQ>>Lh- zF5cP8yW6dONzeT^_ckVP=8>SR#^c4u#HV_NqK||=yrdQTCejjYSx{g_Cu$&3>|{X` z>0)H*Ue)-nLx9|NE&T1Lk4-(6j6Z+ALH4G0I{wU6SkE^vw_dqY(leEc%-4R;YYW&- z(-(HwO-nQBL6!fiD6`ioZiLBo-Zeznw!Fm#Ek4#BecU_Rawk-nKwO9I{!LG&|5X2a zwfLLp-SA2@{z-kRZ%~YEe-TH{7}HfXfs+~P=8KdD6=Wm(^(58HT|6CXE-Ud>KRjE~ zrzL(bYDy1Di9{^?=0MpGZA(g@jE9L53ZK%;cDc3vnV+STpHQX$7> z{n5t(kXJWbcXyK)37dlUY3*E`~5o@C5xzCtV?QCH_@31~6X`$seW-!jEgmh9nD=z=z zVI5+x?H@8_qRrwf*XMYaj@N~yy5_7j`^eCN$-R14RsAQ#>hi6vXoaWgLABUx?}Emv z(AcRXfBzQ$TRbn1xZE4O#VIEG2=*5;%V?C4x6Ld@yRA!BMn*Q;*Z0dT=>D6+Wc7vH zZt1v&rVoMrG*&3y%83L2bBpe%BvF-ef~@7;h6|+#B1`)RDjQ}88m5AwGTW++?H*n? z;u`V3D0&^U^Vj1CE&ZMCLt$R?=1GkoQL$@#>q)X-%IRu_>hOhUJ?dFY%HZCVKWm<} zG5LtPywP&_Io&K$2zjrvpH}+t>~VKByx%ugqOv;Csk>=u6FB9$eq^{+Wi1*QCiC$T zIwENctvdSl!;JcAmH$MjKzE|Uf!Xr%)mupuZOxWBk~Hg_b;ot2h)=zGSi5fFBmMye zy$xRRl0_X!(cWP1)h5nG-^6y@n~o&Cs69IqL|5A5)GB+qY2u;JEZ$Df#M8q?F&g+E z-~%6HEqw7q#9Um=8}N-Wd~NR{ydK&yr)p0{{-XIP+t$qJ{4PnQT13Y1E1t7?O$(|p zxw`4Rw7H8E(k$+lETs$-dhN|tGT=S2C%yO?gJ!QhVJh|2vu`|5775kVtndEEpwMTS zJQ?xHs&M&Jgns2a#-^>c0zENode^)}b42vihHK%nOwCXjrM)cOxHNUmPG4tN?B8Jz zS=?lAK;TgNiaq_K*NiI38UNtoKO%2N+h;Ft5`Mh-Xb|WZ5a5s2>FOd#I|yTF1Ds`$ zJIp2jeldEkKtg2vQ|p>u$1-eqKP}Dlk#3@30lIH*jL-w~qPR+`8qK`ADza6wZa?^b z`t`eo-{)`KE$8;B1I13O7|pljJKJ4cK1lKFmR)Q}Tluk&DfOSnu76eIzkh;U_bB}4 zW#eEgG%f0u#qg%?J>DlpnQrTCLSZ{^qs(6~7FfWEZPcMEqvCLf))r^GYol;mqn~j! z9#mm91C$TD3b}s|&DATHybG(im}HFuv#c=lNsBY%7)0 zuZj3RN6>II2tAm#>wcJ2m_d%8^1^}$ViM`hozPTMnY&f|Jg|SzAmRPJ$hJ^Ks$QVPB7ha$e8@aG_Fvp*$lDrI1z;Slz^wKn|1BnO5XVY|_rnN?N z#)tLjv5Z`(rOmNP{=?12){Fc;8}d&3*}t?RBI5pbe{31^l^LX4Jx!Z?@9iOf?SIm- z`S`STA@wlRgyKg9i?M!@V^3REdvC#%p^?6Q9J5z|m!E%oVI1w&VKvRc12Iomt-{bJ ze4;voykv1BizepIjpysS&|u3%gVx5-ZPmdbQ)+1|kYlv)jSP(WG8^tQWjkME0fEXr9sj9E9^FcelgVxqPFwgX)dwMLUPqfwcdwqNeG8CBF6shdqyCph3bk$_! zXbkBhDL0yBJmV#m=^CoKuWKf!9Gy6B&Uz_7ei9UPo<4E^(RWj}y;=2gz^4XZ7yo!u z1^j6x?$1xAUL<~(maY#mrw-tu`)2ZhBvn12DzoMj8_m(ne50FPmXYz%v01xezCWL| zS8dA)~5S+ax{CD5XAFnXYx5nFr_)sC^FuGa~zs-S=O+xZ8abkZmg8 zH;dsMJ2SmCEN33sFZx{iP`{ms&9EmpaM9n4PqtgOh{jtwf!=H4Umu4b*p~p{k>1Wm zivKM^XOr(q@E|X#hdbVm3&10u-m{ptsEUfg&g1*6q*P)-vBVo&SFiFaU!yDoYaXt7 z`uYjJgrgp9za4j`zGNy=c82~+n^L<$cc&u4G>pT(EHb^`BUXaIT~y)VPYvDzV<94u zdEaM>#P~zq!h?tOu;MOK;=#~D4Hq`vdxMXp)|AFL@D9G{8`xU=+38X@m3|@pe8^G= z|CsbXLUO?pJOcA=mT4>|mH|YAbq2SlTugZR_5BP`Gc)zAa(nXmIgu@~gtp5rN(`cqURL2H*cgNj&)^kl;eQNt$CbI`^WfPm;FrU0TQw8>6s*wC?r~^;LV{*RJfW_5G!1CmXn%2T`WLGE+`lW`f+Ku5!mAoJao0cl;~K^ZP? zz43$zSO1lCU{_GuKil6Fx^%?Jq`(o%(#c}=pa-thPisn_j1rH)_G=4D_^!-@Cbg`w zY~}_ERNQF*DpH^&)oH+@r>Bd6GtAFIrPo$fKmFOqJyQLePpu!gN9O8_Wb)sP)1)=% z{cx{5C|2)P>oWCb2vGT@6vLci@648|*kl1M%X?qy=)g%dk#XPRkZ+XfiYm@ej5Uh; z-u*$B_C%HRK?r|VTr1mf_iVkLqs1FJ%kHQ@q-l2P6orOO>4^cZ znL1THb_+`a6jCo+!ljg$Y7D;07;XBzX%Whdmx!N*1obXyq?jgFwE#39RsnW{n*o~3 ztyE`1BBi`*Uw<4RKX&-#ASoxn#8@LU!zI%N>()Mhi53KxNuhN zu+0d&3b@#*FXeH5jUeA{Ngql!p5iLNp=GYXjS%2?j(be~>!F{| zbcdU2`?HW2^fET^QmuSr-cK)4)xRuxj*!V7Ebhj1-?(Jmlq6=8MaH$yomPsWkF%Cqsg`hxCP}A3FkYweX)2^jR0<$#;ZZxA7fPJqR90-oRIMU4 z>Q-GA4AAOpXrKLkRc)Q^ksr+WTZqwHX1?JEovmeS@#4~quatm#%r_3#)GS#~Lr&LE zW{*C)zBMT*i=zvBcj^1gytHbfn4w^tE@k>NTyBJ~QelH4O3 zsiUez;5MTW!cfussjEa$Xu8^UNno)CyS4aKf`w5Q3O5wTdXxp6j zJ10S@;2~jm9kv(mzfHVq7L$56y298%!*nH)uQC51{E_s(WRwQAb%B{rxnI`%y~tlS zK22#6A6CcA1v7IQ$Vc}Gn(?0b#QnLK{!NFBV)VN?$2U?bGRo-&Q?+UaPT&)o(%3jH zM>uVfSEEEy%FqkRN*m#~c(kts5hfDL!~}JU6(&v|^>$MvmcGSRJ|a>U&F*6jUEj32 z3W`50NlGo+dDPlX8Q_Q?a74>y_gWm$0!M6Ik_^ESTkNK)>z6tN8oC~(`iP`e|1ao; zgC#hKJGJ`5Qb#=wHsD|b4mK=x{KCOL9DHv#<%*-);9xBde!#)TrH&OG{Ny9T9REKl z9ryd@f6_Z2k@?0Ypyr~TOTC>iPUM6tpJs8ZW?H_6t}g~%Rz)9{fH;v|8tjB|A}4&n z5iOf(aUy?lz!7n0;zXv@?y}M{ZKgG~@YSaIA86i8`vV81anKM)#hqhn>8ovlgO)gG zjich=BOKK4vVxg4(@Nl=0S?;ZAnxkzmcFAL7XK?f!~ItNPvXGIP-)jV_($+tZsOeD zSVEKGPLQpeuaqo2Gwh?uqa}7oJk`!KzFSG9b|S#ec>a#*$G8-p!_@IHE1Ck}l08@HMfi^2V{w zJLVUYsZh>iv)`6k$3gbHQCn`NN|gX6QmWdj zdMCHnfA*tE;EzLI_fv{@PN}8Hpe^jB!_w8Vd204M?FI$t4*vj8(XQlW)1utpXGBXk z`|8({fBe}YiKF`YH|KXZjb*p=Qe3T2(ua(0vv%sAA0K@9qU*QkL;mYf7(I7djA4nk zUU=Y>&lcrt%GNIYGJ^h1Qg_F^?E9^~Hhz&Wfnf`Ys`ZvF2$$iLIVFyKpAVxgSCZrc z*{)9C<*Q7RjTd-HhB{V>)@*+i{gHY#e5r|{0JSSH3HFV@d8(E@!)$7?XS)J#pl6RZ z)vQ-N4&Eg9C0BW-$rY^m3Jk}o|B61qC@sG7)xZ>Y z(+f)Rm7YfJ-u=!5k@B$@21!i$0$rqf`m3}LQlI+W3-ZKG$fv+Sb6;C3?Mi1J`Q?@Q z*u9?8AB=Xj&lb#T(;65l1_jq%7rSs+SZ)u!_T3eDO{qjGEGI5Z68sADjbgFMgLf10 z;lj1NqrQ5?__Q0=&}6>e?z0;kB}yd_W5D0pSq5_$sd3EkNtwZTy}(_!+*X_Bvc}m z$q!%p^ik+KcXib^KR=*i#`4JaZJBa!u2_K+14)!1j0C@p1+#^ah;RDfDfj-ftG+7R zXY$#N%J3hEpL1$;*JWMA&uZIP@hZbCWuY<64u{_7pAa3Uw!O3ajSr?;0R?waS>4US zL3ApP3pVDv#mU=t12WHAfvxe9U{=zyzCF2Vzpu z%6+r(@5PRia{R)?Z8*EeD3|neM2&V4J2am;U1hggVk!HdM&=N6?sSIb^b<)-cS-or z?y?U>22G|$7#&Nc#H?*t*{-X-AFF?$Q$+vB$9Cc`+rb z=x9m<{EA@vCm1&aSrTw!72?EGE&s>v5XWL&sj{LXYCwqNhQfXo4lsiyeA-HHwz?b z2=p5m&hK0H5Z*x#tag#t%YiJmbQAh$-rWpocWw2JmEef{*v-91)=B6Y6Qj)s$D!9^}fF6FhAch|FvSc zGotTH_Lo)EyPmOraKuqX^Mk%vL?Xi8#L;}+kuxcr$ePE9N!$0|Ib%LvbF9E;>6zsL zn~KhF6dfWa#3~N;CwyT)?f)>d!yhKvP=6w6?s7L2g-)>hSr)h}+ju!<{(G}$C*WIz zH^05UCTT>7hy8$yL%p zN~}Z-m2Y5l$gqi{rjFg2g*EX$F)^^|RG0P$ej`D{n(0F&MchQh>$fN!@&2IjZU}qv zb6D)|)#dRN*!lJvyBOL*s~be1Kzv)gzQ{ut{>0Jf&gwb5;PQ}`vEm@{ZHKmVuH zUO|%O#|ea|5|(tg;$27XSos1t=WJM^F#B$6Oa-^Zy9J+Yl~LaK=G>?HzIL`7-Bn8Y zM16uo`x<(vPxXrjq zSCpmN+r*KKax2WXWnemYTNcONYTXk;q7hDP=I0=aTVr?ypZp&e>bb*)LW3Zdgu8i6 zouxo~iV3FS>g!iTHJS_c!Jx6B!ho(Rev(!JEB@=ztgA)E;Z6nLznXb*p-km?^lMNF z>a*n}vY~^hW++Ggd<3j={$V8crnhj%=9ksmFZoW^p*)$qWEw3iQz{vEmR7P0x^>*i z!6GQ*9J05#moze86eoW+1n|*J*|)xDsi098G7)h8#%PfxeQ(OXPUqK9&t|ZnKaCY87i{5jmo|K zKLBDtoxhH=T%c6M#bv?ot;BM27ySMWv3!Vg%+2}|cOU#WhM@AWyb3t2*e>dhxx6oN zYG2CQTD-N3Ch*rVPq+omj|Uo??{AraZy>0cHGYBeWCG7CX_-*O%NVVQw`vG@g&4Xq zasfcWU#{X$jER3bNSwxUvy#@z%I+xMBQF<7teMMAp&C0;_{7 zb<6l{p-Nbt#>hIX8{_R^?bN7s(gxArW+i*1#jM*Jgb`hTjHC-=%HxZ~uFyJlN*&8# z`2YJc>7oHInjT?JnFeDZPjLf@#F81co#<^$pAe4!%YR?~`|{tH|Gxb9|C4|Igt%wy zKP1E2m&HBfPq04IF1vkGVJF(TqM@#Rx%C-;qLu$%)IVFcrL{lo_BlhLeQLcrR&VP4 z0CRssZo9|&48mdg%WFet3#y3C|I!V zU_*B{-e*|27Lh9p)5-&3ygi;=dXq5?)QME^y?Ma!1eI_p=*88 z4*1RLbSrg$zAA*LG$Kt3jkI51PsC586Y!m6&(bn@*(&xK--P|SVJZ3A%R58oaGa3W zffI4hsC??P94M#+<8VXL6vfK12CY2l?9F_zdM4o}Ex-SfhPo_%l_mU7?fy?KiYhIXDcm z)2@?+{-Px$5$96jlOz*mkG75U^^+j$oMUJ~H1LX#F z122_0jSF_H{Zva5Ksx@UiQq2lfO1#>(yJ zxH?}#WeL9Pb?5mcimx+t+V5xhL^-0k0u+}lxj#Q0>?Ho+S|Upp;>Y6Gmp?|n8#l@RnJ~ zr1LY5*yy-F#rd?8NHE^Vuzz$841A1q%#qSJ&>O^c|BqqJ zUW{A$b&>{uV}o%dC1@o{E2~K|{LX;C)Rk_MNZTeOcEY$PR*@fD0!yeKl@M3wbtDOK z1eVihV+-8GCR<5zKu*Hn$?!b|X${B@Iu`KVLh%6{F0jyEs%V?s{3_T|peOu~UFXX$ zg!vP$i^h=D2{LW#bmufGKVt*Sd0S&h8ZQHWkc6T>cy=x5yg0CtO5&37S-|cn4LqKK zGMecB)eSKJNK#=hNu;zO?#Bs%v0a6DyIzF4*L)TFa)JOZNqPwS1^O*8;~k&h{Z+vC z$pExDR=x+};%J|XdSNXAIsw;Mz?~a->O^TiujhXVaDfa2`u3MXU6227 z_~h;$;2+>)ePaAm=t`qHa{4=wIugbb#vnnCBN_f~prPAAY49&kE2VTSAsH~PX zU^INR^VFb8bH97qNE zPADiG@e0ayl^x~*j2oA8BFRZ$*m!Q^p+X(m4QfT8#97-tTIA36(2YW_>aGGRHbmn5eWTL9L-qTbM^{2kneQT8)P5AQRT zWh+U9Km4@eSPkMi{w7AhRr}}3>zK{>AoLsdaLRh%KQz(D?Z$0vU8w9w9s|uAkv?bW z+%fDE?!{EQi|Yn)jygl1)==KSUJ&cu40Z_G5M8~kC%ay1JpuMvn#d;#3p_*}$ks)D zIc*DVuexjLdV+0HzApeh@_%0UDeXE)$}ZK05cgL~zdNpF{qBP`^MxD4bub8P-zr%5 zR>8Wr2G+e^Soiv2-CIZ3y(MHH!opbfI29bBy)*zn|xQ&MF8odz9MsNb{fPd!_EP$$@2m^hvwVrh)zVXJ_al z*#8!XV!NuapEFp1`3PWVVjY0JQMIG`=6k`G>J@naylI1RJBl#MzKrsr<~^S@aJCNc zG|6$c1YMo>YugH!fbPIL>YnWEGQhnL#>h+CL*5$k9Pm<}F9e?7@(%ZTjJhKe<{r>7 z7VG+Jl<~4|73%`-v0-g)!ZstuoYN0wuy2HQ9-d*}InI6hIm5?U&?oAiQ5k2wEf|Ec zBshkW3vIa5quCgqJ;lc`Qyi1Pw_)76|CTB3{+k5j@^l_lb%riH26R!~p};}eGx^mN zt_JHM9QFZV7pZ*$o<@vcI~_ksoEH-AA>ypt4EX{uoG)3l?HVTc(Ed-L?GxCxGxXW{ zur`f(hCGV0|M1J#Q9Vh01>N7Ml8U12KR{2QE$+YNDwNqyvwcVOHts$QBVjI1K zZ{zb9F0qY*A+#~)(%P7Nc<^mpI1_ar_~dnL&$Mr%&;P8pUbM$e_xX?JW1E}W|I_KC z`X1)Ugl@jRKTT{CmNHvOo6~gr@u-w*Di6#D#3uc-VuLf3I^?^?`!I-u`}DDSA7K;I<`G|odiN7R{$&XNZH z3VQmlE5daq$07D}J;>mE-p{0-ZD51=!5#%0Ozlh99#Gepr@#(7nXmQb^@+ar(bMVp zwx>CL?eoffgWz=n$j>28L$3dFHr_p*L~36MJYVMa1vY%ld7dNOtUza&Y!|B@N8Ci>Z$DDg zr=5_VK4R;c5BryPX5*{l7QW_*{*P_IuRgu641GJXX+N1|J~vKnl6IduU_yI}(0|YY zpA`X~nbcpnPLaVYTKO8Q@)`HX(AOkq=pQ90GrE`umrG~pR4G2kz8lG_vX7B0pa;Wr zA=+-J57BM|+w?<)cVhj_VJr?~7-v{Q)}x&!k1q3a|3g3HqxGQ31GELOZ^3HM4(OlX zn13fv1OIGt+%Shp-EB~}5chYgA0O%mp>1U^0PFnCQujv$@MI}|O|V@O5J&K-GOt-| zNR7#Vb z7ia<+soi-m(E6RDK;I#xkMgak7xo%`Dd@+^!hLYy$+SZFZq!Z|ZwF=bT=^2*=kBNb z+`{c7%>aHTz>WggeexL4cWhs7gtw02{q#eC?Wewkdv(5q6!fRTvjpl-TVjf51;?`% z@XUoall*ZPn*vWze^F+jm+?>YtC9qReYjCS)^ofix;=RK-U#i%3;9fcJOO*h_a|!O z3j1dqS6K5bT)$>5vyx;#iT4KNqu3wTuAA)-0=rQUd~_1_M(?5yRdrUF&8hg}BmB@t zayp;M0m=ZCg$Q{)dWOqG7MBNX7ekz?ENax`*ia*P2E~+&3>U@NoV4u+x zM$fz`^mt&MvPqq!iPK||p+5C(al6hL`tvEIG4Rqg$ze3kqBej+qsg2MACpcu(DE?z zJ0TrN52NM1Bb{JF;T-J*`Ilk-1(v5!oeX_R<83E(9U%#5e}L{t47}CjLf`XX#AG=w8eqWu>TEsQ%W9wiX>CoFDIo~KRBHF&G9oW z(EqWI?qR6B9Xf))aXc{|X=FR$oQTi?ajKs_8TLFL)Xkh`8Y2?%h3|2&54h&x{KCHE zR~gKE8rM6N-ZhV|TQ*92D(tE5eFx)O)L+DXv|~Z%694q8e6pR=WfN@ztc!X#|9$ku zWBe$z2ju{8*UEluS6~V&q%vUE6~p9JlF;@!}(!J?Sy@B zKHWE2P?nMc?}02md>Yr|guv^kOW|4KT}P6paQ+p7OsD#*PmJgMD+Ilw*jl@ot*!49 z!qc^T^p)dj-O)+oxlRfO=3hA;`kah3bf$tV&Lb)QlDmKBA7fAU7t(o=ls69LwnpB#QrDdou7m8RR`B_zjSkc`T-Zu^5Dd=Sf8@zKCO!#Q6DN zkKjH9+DW5)cnDyhm_h0Dpzd*L!Fs=5g@v1F$|xELZQ~d8wUbI>@_s zz-KOemcS?MgWoNJu}X80-?c%#8qix7YLo3C7Op8^ns^_FvCo-%%gQbgT|c#lEJc zqHpO~vXRXIHu_Gmi(kRM=E3^q8uw#MJ3M#Y|6-gHBVKu3{MeP#t*I;B@fjv06S!e1=gz zi6XDzxlutEo!7+<^44PoFN03q3BN%$aDGbzWE;rFF&WB1W(%bL{{#EOx3f{EWL9Tj zLf<1nsVWpgJEj0*{B9CwDvvx5RhN5)d7T|abGgg|{(awMbF^r#nU8b(vC!fCG?q)@ z_i4VS0=Bm+h3?0pF9&^2H{&PfhT0FW$bacBj6)Xoq!Wj<7WxVE5bVj~d>5GsJSAZN zkoN1GpeISDq9-wzjm8Sx)unQ`%jUcova;BLi{N+v1DL=3`e@`?@WG-)rf1$cCHe1y zeck>Ul$ZTrFVlR#x3?f≺Ffh60)gV80`Q*0n%it3f_0F;8KH59n$Fyu%P4bGKx` zJ@sacE8mgiw^@C`;dkw4G2`EK%05_6Wn3@!w^Djp?&%xSz~Rl3`|x^a==b9Q?lDeV zwhXi}-M4>+OzHgX5$sdPA7Avz-BlN`U%>lKC`ZWuUje@(;^S=*xqnSG77g^~_g0L> z*e>RNL3@}(nt|=H_TPG5ez2kx{h2sE`7gbf0klo+0y*S#pQbu*;JukW`Oy9$lIRQ_ z@?af+n}q$7-8Zj*?;hIM{y+%FQFd3PRSlp```eW)uKf01`5xv!r1)fV4sh1VuTXqf zL;r$?{u{mqhRZ4SBVya#_pX=Sm1i|MxOW}rS80&vN*b(J>*-qU*5|Jke23O|K>fHV zivh>VyKIiRyZUr+LzLGN#;4Zt~m7 ze!u0)1{kM8xqJQvntum%kZ;rng+Aw{82h{|DJ%w!YXk`ty@P8D$kCfq#oyHSPS@MQ zQS&o#+y@TLTxKJ~mhB>B*>Pf7ZX35tVG_s{>V@{=G9T1A&hwTmY-|ts;d>J8-#XZ*zBUo}>ZcWbN7q@j zcVM4_xxK8<7dJ8cY3~P$-s5>}NpyYhfIn&@5Rm8nol?5RIM!o|A8a>Ls1$6k4(g>9qOZ`B z3~i?lq3v{&wk6(ny3n>ItnK7w&^Bxt_Lq~dT#VIjbYAYc+i0xhG1g?Mh)C^UCqG#^ z&6uaCN2}bSP)whg+nOOiX$4#K*H`eil>Ejdv$asPi_j)Q+eoyF&?aKG5wTIb2<#&x zy9nk;2;neiS+?Is^!CxaezcGL)j)F`*hY3{8%@msorrbE-L_t`|1KGG0uc`L0=eF+ z`k$k*WS*YJ0|#T!m<;_0{%dJ;Yz?C^H#&_aGSEo=#WW`CX?!Obokqt==tup(md0C~ z^fbPGG6s!vp&v*8wKU$cFN{V0 zyJ>7Upq;Uj-7{0PJ^E|)G~Nuh9U~`X<2fHssoL#R>bnyJ?OxiB)3*#m_fWO0Zz8UrW+p7nn=0HX8^zWw`Pxm*0 z4ZJhI)3%H8>-85D8DM;kyIdN0)9VbqeG2y$&d>#ygt>|EJ!pwP=?wkt6!7-|@`L+w ze9MlJJly|q`CGbdCy|z?lYF+f*}tm%MEtb!KOdXsAiF#Dd5IC@An@0I5O{hLc)JJw z_QCfPoWHvq9r|A944pXxeJ>UI?nj$zSrN%gC8VajVvr%pgvyuDUsP}L2LF=#TH`rQ1(%M|BDVopX-=x*&HZqy#Iv`vJ?70qTetk z7q$Oy9)SMaq5s9K|9ivxUmy+agXjBs|NkNOzsVUojr}hd`k&iR?M0F9LZrK%(QKQE zec*H#1Kk!=x}(bMn|QYB*C4ZdINig-WVS>aczp-ZoyTPM{BwfLo&~z|fbN3=-CpDa z;s9Bl(tix|)ydN37BX#ZIw@pw`zGwcUwv!v@>)0+`g)qls%<~YF7Njq2iY;)R9?B? z(pdk!AyfU=iTZC3)qh9_^;hk%9Fhip1N!f`GgzO`jRHF2d7n$2p})@HdJy|tC|lxj z+$>FTBn|c#xq8}fj-tz6p2gx1T%Qez{(U<%`hR^#82ujr{RyzvEM@e6ItTZp8vTD+ zYC?ZpB>mIs&FSC%$QPhLO{0JJ$}sxRNCSI8Kfm!BqyN8G>*+uBnhE`uNcyL4G^hWi zH!hw2*9G}`?X58S_ecYKmI3|482z7Qv(Hmk=xHlB8HKiN*%d$c5^1vuv`q@5?Rjb7 z*Ra;?^DvtJeujOX{AL(!rRKD4TOF0QsCLJ1WX=7m6=HBh!+sFMVBR;cCO zCHqw0FqGZ3^s;I2Y>)Vi-j~o_vWw#%t2~EiI~2T_bB8jalwn?)LKBaTr}8);_BDy0 zr%m8-apPP(LH>Y;a}|E8IdN8?h5BOmY?fbT{FdB%VBB|ph%|7SlNf&-4zW-0yIBAG zR@y%vZ^b;3WL`gm*Dn;{lf&Q*^V?-NJG&_JGuQB$%0JU|I;@cV2lf&BM*B!}hAsqy zF6**jr*(yDUlv)H!TyiuPFd&~NVJ7fc7qn{T-jn>hWRJ(eV&87z~d(`+`&G7`Jw7} zbbDjKe&{&H8!kT)CPgE8~iC&d$cOawZG6mMbtp7vnE~UP@`?W!MJL zG?(krVw%GOzfs@eg@=WYl0>8h=y*eRQJRMp{fs2ajHXOR_b*m*m<oEmq5y(3B z7oN@H@pGt4ZCNf?)+RMKiR)c8H_2ST@v}BF_ABG7oC}4uAcgt4ttT+{SG-T=e11F^c7isf)08d^x`JabvF4G%*ERN8ZF1ZLYvUvDrMY2Z*E0g$Qxmt zu$}8+43M7re4HF~oT$%W^M@S9!eR0hdbDx+1?X36l{zMzM-gLk$$SF*j6d_)=jKoJ zeEP+(LGWona_?Fu4eYwW`1Dero=?S6Y(8!IoblinlOp-_^PL>#5Qn)kl22ROqwxv# zpFAC8QD$eQnJoT1L*?IV6MaVK8f4Iyyx&<&#_ea7SRj>cna98Y2jXNtil6N_(rvo& z8hm^5Alj=k^ob}rmfZIeO*Xin?Ff~To!0K)G0>yHV>-U>SL&sKS5cSxyqCqYC#bP@gT0WJLlqBu z)n}J;J57uS2H82MF`K!JN~-PNJ*{7M-+V#K8<^Isd=Ivd*$iz{`yJ~B$HYtW`|+8A z4Q`j*FPBOKJ7i~Q>wIQ20nGOJOn}P*Tt_u~G(H#FO@L3y^o~2@b$S!>L_EI@c&n5( zo8~tlUE#4!?uV!JGFs;#jO5<#Wp}2%yp5f&`sKQ4`4!I4p*}_K5NF=F@dqXQ%XQ)M z7M54B31g=4nW^L!Nd1=I80K#L0r!6|^-8;69t&&rXf}s$B-$J%S@Li-XOG(6d_EWQ z`JCw>&yC`?x6aOvI1g+R7jcFTzM%H81LxIvn`GaOGY9@d*5y-Vo_ovqped=Ka#Kb~uPR@rn;{%*M9_n>D-?Kjj1N5|*FUncxz(XpOS zbJk$&w=(b>lgI7X_u5cKlFPe}AL= zgS-TFen6RW-mu(r*|fl|@Av}iKlXJ@@9_m}2>48al zJv(l_WdBuZEIk_qXTRKM9gB04&Bx!rr21I!4vy~0>twfdQd{>XZ{y=u6>JB&HOQBX zPX9ZtdipcYN%j}kef3m018Za5=f>;qTgwKw?p}W`teq>u+9~4g ztmeP7jo00EtD>|Ow(kD!UEMr!PqN9~6SoO=C_P6W?4WY9N%LXno&~rd)r0Kbo*>f; z6IDHrwkylEod~*PQiAfF`Bx`y6yS2@?p#ULE!*RB>6ypw+$`Z)7JD{vz0hWcAhSCq z_vUhG;1}DRq30|;+pQ@=&Yfu+RP}_q9)Qf*v|W z&j;j#9RfP&db%Elo`3A-eDYSjYL9FGnWyA{1sX<#$=x4GswBp5y+pZD^a&GpKks*$&I2`9J^JTy}5jraJ_9y525X zlfI3vSIO%6*j;=b*hcTY!u)Qex!3yPl)X6KuV*_$7n>-3c!ys1mKtYh{go;&fDgbAu)}{^qVXXoQCR!t33Xu~ z{iAp3cjO=AoU=qHDq zp$o_H>@?H?xC;kGIJ8{>?i|4H1lZ>Qb~8Q8(!uD|&!^wuT^(cTT*LWmzmDxAVO~QS z?ja?tXHs5^wlK}xcHz48<_pY+*0+KGhCSw0gr03dI~ny`_`dGQMD@NOO|PDlS^ZC1 zdpfOid)8X#vEOgt{y&5ErJc1Y*~hT`brF{DeV47ZedDM;hVrhp*77iz=cV*`+4Ouq z+Bfe{)O7Ge;$HJi7V}-C=3?$5&!wXG2IcpMLQ?mpHO|n_20-WJ=6A-|@jQ$pJ!>yt z*0b~S73}xEsT_yIa4?^bY>D?N_XEq8%e$3xiLz_tDi)`S+vXs>+4(y`XHq-j{375@ z4g3E3he~}sOOH8*dcC-55Ady2`7N)#T!v@oK=Vz6CH~hx( zPD`o0)>;~VW{Bm*hW1mwvwE`_-ygT&-Kgx@$=7;Z)_EXPRqXfP)p&j$=1RZmeLHx* zNb$@33g*fY;l7;?ZCqsg)rm^K6*^DZiBW1sL6L7FFN<^)=c^wd z1fC=XPe7*kmL${tU=`iphT}V|yYt!9=6>ar-Zz%A1ATkkH|Eg$#(w6H>Kilhb2`ZP zu1DXb{3PrNV2^chT0E{DJQn-tIKIzv6g?^UIJ+-94rPzP^FqZ}K>Y<{;*~S#i4pr7 zBVXtC8`L`l#k*f&Z(fe~QqjGqvWId%-zyC~4?OwdPP7?%j>H#YJIw#N(#7o#(f{e= zWv}_G=zgrmLB4x8@@mi2cq!N(Uo6{4t!FWXG?hq0d?w)ED%ff?j)6XYM=yPvho?_%E?drrQ5w|*Zysz9>;G$Zyt80GAd6!mO}%;)8O4x_*#5q z)gsirp2rXl0O3X2!b zl#Y^{^9VijMew{Bj-L#5U~Yx-mmp1~iRQR1Ay)OCo<1@UehEW_Aerk(E3b zQEsR{*+%b5+=SzWb2`rxnkSC{Ib~}}A>JQ^`T_L9Nw)vk_6GOeR_58Y^yJ61) z`YbfB+&+lA3&GYzUQ!yt#ut5Il*Sj4#yzKY(=kV?XdEUrPR2M@1qQ}W;JXgc@<#E|EqMm<0NOh!Y(|>pE)Bv?Z zE=O9C4loiDsNQ8h{=zxqSYMI0y!%55Q_+?ie&u-o@Vm$B>fLs6tFV?7;GRjKe-obj zLl|7YsQquZjEA}4r|TKu4m@QU4=|}hoy~ybY~HksM@4?qbK@Kj!$E404wMIkMOx@P zIcN@IXcrx8wg#LO_>eWVGOXVM{ZOx8*#8(;Quj;$$oIA9p?`O4spd~Px3Z@*zNTj_>?7fKPf>h*k1M{ZCq3Tl z488aXw4vnw^{aQPcE;nmpyKdzmFO$P7_N4w{$({fn6>e+*NOKtJ@bf1J!dqaoW-K= znd>$>GobBFMiOn`v9*Np>ft_Ii9SC${F)Tp>&?x*CUmq&2D^8g4ex(WxvM{+AnhCE-vfsaWcf)_mOmBRcmU=h zyW7F?1bpV_p$_fpyKBcS)9!kzaQt1bvU@71PMm+0FYwq7)TQgyIB(cpER;TR`a z#}TSRy#hM=h$2hyeI?J+xs#5uf8ew<@XQIc>7AifmK*x$d!e?`wVAyavd&=b#HqXv z{_q{@HolIQ5@K5ee;eW1LEupuTbJWD=l9cf)hqj0Md*Ji_J56qlv4i=d!7N$9sIe& zL6$6M^nQCMTVIFa-Xk9NK~Se_)-t>=$47CAb>^`A9NST7GlBLK`zKpGbT2>f%mrtt zXEfFe^wWK{Sodn!r(k|y25)y9Yu6TpvZ(-a;~f67sM7iJ24qAigGpJ+=Yz^9Gj{}#_5w`D2oHT2Jh{aXp^(aIuHj&cTVyX0e} zw9`V$h5pDLe|i!6^P^;E=+RlyzlB0wP_JtzDIbz73j70EbTC=$ywX$_f3SxX^@Z@x z{$AdP0cO8g>*4z$CC352pF$gmzW=e0jOF8dwbB-hO&sI7Jb*qyZm%hD*9dSn4%d!4 z5#W-F`mBV*r3!FK9Bxja1MCu+-JKuNKWeYY+1x%kPUV2Vj|ps-UBK@`YM;@*EnSZH z*%vK|!||VA-kvl?vtgG#r`l={ssJk%{{TL*spv5(tobLp8IX0MSz z3AWey0@!M$XshA7)Q~oJ8X2aS(LgIc2R%?4_Iy6{_k=|4d}h}HjwX)dGL=uV!uP<9 zh{Hd|>hq7j*mPI_j*$p^*Kb~#roj3yFY`TCL}4wHdqW{JnE)FR@9E#c+lp7)0$t78 z>exx!N`k%-I#%QSxl4w&x(dhRc=_W#_R)JY@3{(nV!LSn zLDq5H0KS&X;Sp!(LV`Hnz>CTBeir?+n>kH4V*U;D&HjBVy>Cq>>m_UGGo(8|-I!h$ z|4``#J=Fd|EP5GzOI~8Kgl9I|zbV+#8Pt}hzK!-aEidRFf-h}XcOZZ6SlUW-^p!eHRjFEdvsv_K$i4=d@)@wpDFjoXR%y@Uo2-nt-u`K?_Bu4f$u>w zy0*pVb{&p~a{na1=VDV}Iep(?D!r$^>ond|&wNX%EZ-0CO6fvzuz=&tK|OSag+C(#^e6k`2D8ccj(`5`mLSX`%Sw(VedEX zdd@6Y4|HH5@|3Rk8^IoV_&VLYT>Ka5yJmv0zaA^>e+wela7!Zm*`oX*jKp4B8VBFw zR)m!=gFmq5EPLSZG?Z`Dms_LZ#`3J_<#C5&(Dw!ZtjpM(u+GKx0&NvK_xq{Ma#qRT zK%au_zN$&?{^|kP>ueLB<642wu^fE`Jio+;HcuE_9Kh}8a5e#Mg#Z`F+t~;0l#9=K zJNpdUnHdI$?d&mVXRHE;K7;mexqSe)i^8#bR`hLX@RqYM@Cj&_z@98V59TJdxko4c zM6!oMuy6bc?yc}%c^T!rh~Lwq_1DV#vIFtror`$SBAxem*W6B0EVQ*usf*`cIKRD6 zcbmlhF=6F#VmUn*S4C{-yW#jGftFzkPdOZpv4z7WiFo~g%154T1$bk;$Yp?aOoTjgCf;uwKE!Z#M^#k7JgTNcF z!;8AO`%0Rt0J;Hfhh)_M(1!%*!!Twyg~Fd-hBm42J6=8Gx*pp3HRfx4bv@Ea<6sNk zW4WpPz1i3%!c%(OKkSF~>MiANL8!Np=XXZvRn+auJBSsYx5rQS71I0!wzkFg@oosq z{|v$Y_wl2#e7q`N3#?yCjwQwm4+`gKFC_Ql zYuG#D&L84=lu2l-!`PtR=@9S7pyxQl_qn(iZqwfB1Law|Sn0xReHc$fU4*$K)K*d6 zP4FL>7jpi*G6q1)F8F;%zKayFyqgcFQhzSb?ZLSR>o(03&1b%kO}rl16X&nahj~fk z>A1$j+{E`00*>dky*$jh;gWStg8D;%Av53a(*>@L>*{eQ@jqkF3 z#zU|1->*sOg-z-n9>+L*E#JoDS?`CRH9v=E7ON((_rhc{e4lr+&u2$zK7-FQHJ`zc z&ftCUk#SKS%p1%$dMG{6cN*=tevE-etmz)+XQg-jmgw&K&7|+UDbe0{L*KVhLhq~+ z-&v!+Ls!Wqrm-6<`!4=Pn^z8UlZ)ocPG$GxvzX?Err>Z=uf#H==2dIw%Dv(FsdV3J zzmO^oJf_}{%w+Jf70yuCBl^3tZsK=!w|!`wqk7Xk@gA<&?S8fn+RX@S7xv9vqr%!9 z#@qcS`#tFsKS@&W z%*Xw_pEM~sNWj-z&UBOlGEW!LhE2EHpft?)fl@slfY5UB&#f;D?1_@c(T7v~zqLhyZs!LE2o%^k3E zUR&ccMVjfm=?&%tv{kR%oyu&4%P7BqMzlYbSV=HaW?Kgod4=zf@w*~`kC&B;XM(5= zM4t~kC)_E4a5HKCXCGUyiWDC|%?H2Cp@$t-BiujHB+#6~Xx5e2Q{B+@N8|iGQ`@Eg z1-68b4X?ww);00J_8j^7aAH zJwT}b33kL6D|>NTcT9Y-k{c!88(&yphdR}yiTeji>3K+c29zX)=ZvVn1E{CyHKx;S z>ktlcAuQsfx(&;pf_c(y>y1te`WizUqx1BKwR)a@aze8A>>0{=AftPD!3MaI#q6!g zX7PSJZ|Z*r=I2tLe^#SEug~(%{Mn{gRLFhj!X^_r(nQyg}a?Jhq48~&`fQv$7Kn1 z#dhZKx|mP8i?w6vW_j>W_kqrqf_?OT8>aDMTtlcV@I8*YxA0>w;%7mStG&!;Zb_o| zL;g^C$H&SY&QM#C{_a7GR~iU*gKlpX^!dU3dkK#te}98`4;0M_>|VLg8TuCb)%WoJ z(KVC$py~U}SDtf*9==++UmD>0Z-%k#df~K;`QKblyuw{a+wI9iP?zYJ9GuzlHNyQqdsp z6Q?$j$j8s}bux@TGR&!k{d${nevA2TC!AMe#GoIJC~;w)o5;uXyIyCgd$_WvlI^GV zX#1td`(T`lms#R#(8tB~|G}(lL!rQqLrK7ged1m#tgegM?u)kQa)ra}s_m}OKK~k% z`FS4p{{M!1|IeD*^PSX(?+pE8G>>m3t8=yXJ>RsK6DW? z)8TUnUOL{LWG0MLy?$=jj~3^) z*pH6dCrtMGmK}j7PGIh4LZJOU8k_d_{3@B9WeQsSUh1zer#bLH`k3WAuLl0^{_YBB z^H;#*yTj-lEA%f#=wBkn>Wcb8wkf#p;V^|te!YU1o@@E;I>2jT{r&DC`rd&~;_z=i z2)14ZeUBiX5l1@dJDHK@?x$cc`Mo>n{SttuW7Rdufa}+QYa8P3`1aF)>!IhuXe}1# zlLVR)C#>T4Z*Y8+zJANwfbSf~g}#tNgfr;FK7fOD{h_I0^?wV`k57?9At*~9%=mP4 zJ?*2uS4~bGuns-X^>G5~YtY5?9V)-VdBx{hrj6PkY50EQ;5tF)*!Z5o7N3dtwXqye z&n`oqBj`8kvz4jNX>x`>9maJI&sG0)e$QHK75n~}Cqm~?JLfyZ849e{{5U65HNElu zanP6CE?C#Q`tY1c=&;_OBf_r!oaq?P9iU@^^qf=oAC1q77_J5Cd7?=g&1<$q`j9>@ z5ZYYM+N?XG}*L#%@b4) z()bMO!;pbKTuk+0udJL^*>15Z=j`w-hSa@$k2BOx$DihE**}`AoeNquPHd~=wV#{m zs%_fYy=8|1-v)NyA30D!7Ay!nb+M_6ELi9tO}_6ZUu*KmkR{#G2deLp-tMPC-+w2G`ajsc zf);)!AiaxFzU$9kLEmHux-nJIJ+POHujBc067m@N80dW^ncp=9Ytu#T%t-|Q9{rHX z=Ypxm{C#w*vmS(?>%gROlM=EVMR9Yy7H zZRmh<0DM4$zs|X!3flU9SR9q+pPnIAZsPNQ3i5jObYHvV^tFGZ4EkI996QhS(et$5 zyXZURn`Qg)19+bh?6r%Xp-0-3wH|Y8H9uo*Hpb(WvzWqr$aU}Mq~lEe@&xaFB+|gQ zeeC_?i#tIcPcoZp?1#{IFXrdb+&r+qo=A_cf5H;KsHX_;CSNs2(1{La^M2-{_nraI zIDQ-8?ghN#upMkev(Jtn)^t(ub7+^IZK7v&*<7*UIZp@q`W4FAY}UpZc|&)Sh2@%N+0Ms9i{edOjREF-t{>>RnRr)cC>*b8g`SzMu~^&eXp zts{2`w8DIDZ5L@poRa;|%NVWkuy+gI0qqwcjr0x`PBYGJ2T6B@(Rzn+u8QV*UWDiD z9PZcipXxp+?f&*@^q)CHEgzyxs%Km=wzGR#LjV6IUVyz0%JsWJ!`Vu(XurJ=Ej- zFKk>sml?cg&`VU-1qT?DuvQT(%-zeeqg&!8_g27M`w(wAKNj^ydOzNFE2GxPYT zxaNZmqMf5MdhfvhYT7?sWlB5uK`XRtcf_gmdJX8UGN5;66ne7^=uM@2@9yxt{XbWk z%1F4sTsQ+7M)Ot!n%5c79E?Jq#AKbJ~ z1oYW>yu};nqUR+Of*mk_Re$Iy!pnUVWcDssgu}c#fb-GwlU+QX)@~F}yXS&Q?9LY! zyJPX!frpMu?yhcUsCMPhV|Vui|GBZdk5@&;?mk`-8N2)V#Gqn#X7BdX{PDSpKc2=- z-58T=kBrHw?=<>GztJ9RurWCyX1o>s>$>q!V~Cw+K_4YJLp7GjSlvfE1{bTl`@9yb zyZe+TTOaK*j@5lsr;opVw9PzL_t928?1u-U$Le(DQDb$3i{TvHV-mxu*T-;t1kYhh z-Sx09YfS%wF`Pn0X4JDu)Sn@*ptb5 ztuJgWPSjysvj5fin+l#{>*g1TLpq|xAtU3DClaE^A5V}N@yAuM1urY(;j)cHG}paY306rE*q%7&3*XhwC3q)J>-?_9o{b& z_Fb*Sz2Coa;RPPM8n1x!1woC&_=eWI00%&p1e&kH@a6&{m{(yV1DTgX^84 z`dVIA-u1#;$A!4_4%1jQqxZ_d6Dg!{n=V$pLeL*oNE^Nbozg?&dJlpO-@S#>fWDXF zcQ6*;Ee*7taE7Wr;=A*qMoyWc$FitaBo8CU!W-l4be?Nl1k#B{4u;(44uHDHR z4;}>Fb@77mdmsEhNppEoemd#7F&OW~!zpgOmkY+L2aZ;W`O*H}N|K$D)tB z2Ou&7F*-N&F^R+{ZWz9aP=9inz zGdy2S@9{lX%HqqPoaeb9y)-6=a@NnrJ7SD@IUOTbt{WpdCQsqLIw#ne;2iBcNd4v* zU)A!%&s%=JHomEc`+s}V(O2GaqpaQaRSrB_rRlB4VI40)iU;nzXOjL3| zy8Z10EiUn3w(g95Wcig$r_QPcow|wY)9{?~LB}l5j?%|0&+XOXfBr2IYX!CA7lB+> zAJbx%`?EBC-_{yEW~qba=ig`ceZiRJa{|ogBTyFpBeIq**YI z0H5`&9d)qBGV1UXMWc>Bkv{5J&(2XNf|gOo0nYd6|0UjF9KpRso@^PpRZstg^Njvc zCk6Up4|vZNI{Kjv$^OO#M*m2#O~AJ&bFdX-T62}Lrm^CF%N;P*8^Nwg4~tXn z(9dNZp5bDgDze|+4|U}cW6sT^uVc9{ayPR`TiD|L?|mKCT@bKC=JNOm-hFYatD(ykgLR5kd%f2?3K3 zAeaCVf}$cOBo`75Nz4a^8ufy)L#NaR5-cj(8@NH*VOq4M5x$m>ie$Ku7+>hK?JMa7c|39OLwa(dVf33ClT5IpK?>;5(AbIHM%l-IYh(vD)Jwih zd;SmJ4U^y9!Zu<4y2$k2`Fe{sm)RBCw-ji%+XKA5cvGMqZK)Fd4X!1i9MM~pl_mb% z@(t&Wtn$FZZ=(HvZ7ziTMyi+Z#O(Q!oNt6W>+r10xd*rC$zUDUKL2LS>+a&7zVm0~ zcgdmkjVi>&x2=_Vgx)R{Uo=-(bL7b9U1;MlzFV+jcIz91ko8;dMfuKP%(cP$UUaSv z{zJXHWYyMBu{P+l&JuanK1-x^x>}Q)b^+&IXS~ah{xH(P>$MLj7xt86K60N?xON8c z3k*psr2TZ9SsnaMJZ#*fuYsoaaHF^Tu=-A~yaQZ@XCb?~L9I9bvrGHtK&EC-+u`4; z5l?!{17%NYb*4LiTb*3E{(N%2eP)2~Uy=(@XPVU0^=spB)vqr;&vzC@Vec$rpYJ>5 z-zwaDg;O@KA9I&9)_t0H8Qz)6xi*iYuh0I_TKDd%Mc-;KKEFl2(Gz36duZ?KUd@d0 zu5O|8UER_u^{%cGaq6OuLEqKI-2agFsx`Lx&TPw7MxDE4|0&FM>+Sai!Yh5<+~!y0 zo`?Ou(Ef!>QiitYVSh^~PufqT?|CTPAO3AA{oC`_`jvH7`Atu9ytp)-&2!h@x5Pbg zALa?O-nY-Iu;eCZ*wnsV^^i(`wov@*L2b! zKwWE)C-~j_^~m?=vqqz}j?{gq5B0hqef5y~t>-=JJ0{kCd|4kV*=KnF-Y|lDH)J07 znvsQkXYBJl)Y(OD`SxH-%=7+Z^D8SfM|c0gIs*)Sk=UeYote)yvcfWB%G@Y@yxm=U zZ?=2j-aX}k(#@FjCTaYHeK~}7zI8YTKksJV<3WCk47%Ss&Z^(cD_=l>OG8@@KKk-OYj1`wW4T{HD%pOAl52k}(e1m$ z^gi)si?`!VOE0}o9o(nqvFaqPys!8E5^;viMbJmsY0Gy?8>Ou_E^BVVdnu1=w$^Wj ztnVwT`Va>hjykt9T`zCY{6=E5{Et4HTqJA!)){iuvL-d+lAbQ3(b8M#1L)-)z0MPB zPwdd^O^H^oE`MuIU$WP$%O5cWV)g$X6KnrMSS(=uZZcy3a7?{levwn}UoLW&tmqrs zH^t7CMt{G2);gQU-ovmy5jINRE%QBng#C5wB{N4j&S9h7n)YUCaIq|>>cW7;8 z#-a72j27~Hy^3kxNYUoi8Cw2P$Sdy~yGUn!SF&q`J0raj>p3BR^x%HKeFIbkCbk9on1fF7d4Yq_MvBJA?4O0Fb}C_T$s*Up4BaFJ;C= z_5I(6j3q_U_D+Py!16xlsTl9+9<;t2gP7-|uk!bwUa{FXBVK&;r5BFKJ1y{QX=v^> z=_2K7$%YFf0qQ7IPcE91tc5hi;Rvsw%ro1ze-_w*Cd8^d>&+otPz2k)= z)^BHhMr-Ij$esKRtMx82BlP``i65!=Ars%`x5+Z?cYuSv3vmxDMqM-KBHr3-?E}T! zTJ&7r`!hz+cwB{k%z0DVWzX@^jutu3+b+|R>wu@aJW&24zWY3)(-+Gc;xfoqt<9A| zp4Il5>ee_5>P_zZ+&duW4fy$+vPQ{EJWa((Mz%nfm)^6?sJHabTGPp0I{`XX^b|rk zXB)CC{kkgj%_F-V{M~=Mr15-&ROH`U9{6~tvZMbvUE;-QdzY7a&q3cp@>~yj)+^gl z^ozo!*6(2q`}Z)`Z(-iJEd_L6M*2(MOw6Z~5<9yR&kO%b3y(u*X8okoK8v9G*GKld zt@l$OyshLA=$5mcoU)ib-CA>ywU29(d!oLJ9rWGhAFm3%yS!&s-m1M{T<9(Nc7AAF-S&R;_lx77!Pq!7r1y(zJ&f-cE03!8i#LCO z{C!U^Gg=g%&pdDKFR*_X4_f(VS@@oYo|@!3YYka^n@Z0OOSirgYSkGkBO{Ea#in6; zdRTh<(`Is`wCm~OXWcLS46(6dtpmRhwhNGI+ob)uh*Y9>e$~uxV!J(>3*Xoy*w~|RoFYb zy-uBUl($&vWRARB->tuMi#l$i?m?bvjghIYK)_miFWK$iIK#-E>M}0m8hqwMV-t4( zy6m;)NB;glGZd%n}+Y|pq~ zsP>GzKh&OaKVWy4Lp1J^J@f?X|Xt#*}wHG<#8J*RPY?oojAo$JLr!;W_vR z^UqmxD-SI0aK@D1#(aEP*(X_}jJAh4+WN2Bi<_7+l)bpGy&gDfw^zQG+x5MWy_R{U z%=_)Rh80U%^Xr!|UwY}Be4|0l|6a44^80je_xH}ow|v;Q;JL-tZ=Soq zf7n~Q7jw;BhxOl~VXi2@pK&4GT9a}7)+1~jPk1a42%Z)Gu=6{9A}5JQ*ItYEec5Vv z8rxljw(MOzT79o)>exV_t7K%l)FVDXY`pcJEfM*=#sx*s1oJJybMJ)5j9iH?0NvKU zJ(Xs~&pdb7ao(`SgWB&~b8h?FX~8v;z{eYd`f1t0^Brr^25F0&KP_#PHVH3#w^{G6 zWB-=b)>-F%eBatEBk6`O8%6ec>DITBO60uj@bl6WPQ^J>JPlViu1e5m;pz!X@8o&u zhj5)m`o6I9$aCVHS6&?_-S{6qFMWfO<(=y>KMcJGc-2Vt)_$+h+x?;sG2rQF&#g7I zS0P)E^<6xf*K|gq+Zu(gD+=9~FuDZ&4DrF}+}8Kv5{xLceNkwWQ0@`0-$?NuFj7P3 za$EF0k!`?OFSXupS?8wPXQo4!lGi6l3^n+<=`44HeO9`DPP)z$v?~SeD%ARrCg-3d ze-ZMpkHW*8A<{~p<-OeTNB!!15!Reb%|8zffxo8O2W|Ks?KaZ&IziiwJf-rDK|7B< zu8~h{Ut`D~>^TD3(Ak{t8tGQMt@G4h^g8+zn>JZ!?YbKNqN#GLZLpKfK`kvpXG+G4kHURWCut1mwGsoFR*F~@4B z{Ely(%=`ZM%wMLh<^9gK`n%EA$|1E?&H?0}+-WYyI$qNbK;w_f7&}O z(Ter$GqMhje*CDlj@-RFNBgZ_TF--t8NJi2v6a&M&et{s^)1@B#$^3K+cRUIlP~>} z^XcRa8tJdvH*>aVV{!7CM~josJ^Fg`*+=`6&tUFdtiCm4X2^GJ#*b9r<%TbvD8KD; z!|wF1P3-J7jly2om|oZzwI?RA3$Sd{d+^(vj56Yeu^l$ULlXVdo^Wl`tbW^jEf(_RDezMkln_}1NBwV^yPX;|o-q3!lw^2+kSEj5n) z{E_L!YCd(w0^=oc}qu-I~-2b2XOz?LM;osp5{~d$g-^`hvTnk58AO41Y-5KiZpVnII1I59< zx@FA(c`JH~p-_wMdnmy`!`YeMTh z-#8pvmzncwCdRPkNhy&8f3Kd6(ZL<|NEI&@vhU%e%JAh_dn~bbT){m&!FOSidwG1(_wqb*#$NkDJ%vNt z%k#_uEzbqf_wr<%8QQ*xj8)Ek5ns3}`o4(EJ#qI%h`orm=PuFUcUa9j+Xu>CqDQxV zeV?~`=N`mi`o5qFZJ)_T_rQWB?%D-K<$-H9hT`9yr;u;A7Ry<`A5?SQo%^kC^dU`r zxq24?c|Wx?N!#bpqSdiQ_NkzrPS!IvRz0#_CUJmTuh_ZETl-D*F8-P4&g%OXy{xyOJ-scgA|h``lUE zPRl#qV7w5`cE{bLlzvUv9;L$29;HhLqU=$+%UwIq?;e<)Rvx(eL(DZob02Gu(sN$4 zFGrKDp0|d1q4QVE*_H=F`;?w5)!udMdFoZ3`5DL~ds2IR|6A=9fD zLv-%lql`MSXCiOJIJequ^>NSGqpv=f|I5BOs6dK&ZQBd_e&-Wu9tH?UXRW2f`4 z$odYdm9OG3^2s;JHU6Eu#KFH;2et?gQC>dUax^;s`h3y(H_+$YZ+FSmLHQTcPT%~P zb8fKZpu41e_mK8qNqiT1)_jk(7pgY7v^;R~2SI-COLlvY$^NVD=e)K4%HaN+!sJr# z7Jri3f7P25vHuF`*8Z!KUX0uAXRY*?Y5N}5_FvsB`>*`D-Y2)8VOnVa)y>-et7FNz zXiLt`mOa`I{qdJQ`pWh~$NnpcqeM5CqHXUW{`djn54173e+qR-T{bSUYViK)?S)qC zAiu5ufhxzYTWlffJdHXlg0y;lnaTE904Z)G&FmVM*!k$bK>PsZ+HI|Z7-9) z52?^SFgFYOw@2H%#Qp32h1%YwOf64|d!V?lJaEOkp>HtsSI5}DR0i4upnX1a|5AT` zjQvX$XcOi`S3IQcU&>bdm%taVS?L}qiCE(WeTCYO@ZArFzL)9Zich|mso-O$4)s;L zOXdvyJ0nBb%j660WlFvAFTa=R%tQ9KnnQb;9#4tf%QWKFu)Rz&N=S7<*{0sLY@mvb+ZBYmuM zFOwtfqOiS8-R?Jvmb$mh+FBmC>Rs+->MAoX>KA<}4}52`_m0O?_|3n@(4LFQ_ebny zvgT43ja7RuE;8lan6>ZXZvG~H(7jB#yWqDULR{v@_-~i97klO!?Xu<|=lAtofNPmi z-TRtRAANt*1n9!(-$+{r-``Y(v3}i$q5VxE`l0V{N*(6d-{jTyH+i|g$;Q-!2iW9KSse^Wc+!#<@;e`m!#LD@p4Xz#b(Z_KGH4`iCq z>*)KI_}i+`zNI%Wgau4?ce!-V((J1+Pn1Bd&#SM zXBh3h7~@_u`D~AwEc-$_{)hH4dAN_stM)OKoQBQ0HF6)**Nl)(<-e=%WAX*}F_~Ao zyNlD@Z_LE}E@NQueN2w>zN&OI`8`>)b(|d#7WY}}FZBsKrr!r+j^~ek<$7Adl{y6-(KMsHIuZoktG){UP{1N{$N#rf z4xZi|$3M5k<44DCr)~t_@z0Hel+hMJiRH7|7eO+ep8(OHO1jyQ=I;- zisRp#;@H2YIQF$Ej{Y{qu}@8L{6|w9|Gz5E_*xaG{8e$}8@K%2IO#$Eb#Kk;nhA|H zO)DqN>a6v&v^O+28M%gGOuTDM8>THrTYIaK2RMoM`M4$%pMvWq*?++Myu9%f4Fx5O zQQN#~RdZ97r>%W_ZA*(`tn#$A)vWZ`(8{IZIV>jP8UAUIgo*i;&CQK9%Nsolmf!2C zZ5LW;f9HhdjUAr$=H~YL35z_fs~c)P3q30v(DWMVPpD&2=u2#DW^+>$${aHNqV}40 zPl(jwV?*)T!J^{vehxY|6m%}sSKk6oEdif$Wg7!NcwHj*YHv9O`3p?!v7WY4V#HG5HeYeUn@ zX=86g8)_Pmx7oGQ)9ym?;C)AJdvmL61umVTHeGG22mEt2c^+^i8#Aqju4q65XK8IP z>O3OW+07kIbu()k8<*GA-sfs+Zg)wu8fqFFzUZlQv_WZzYi46jTbq;{CBKn1gvVe>*|&uq3k zNCGW?C@r$=u(r0ZX|dZiDR+*iy`s6crcr5Y(2fQiW3gKJI=c;KGU0CC4?PzL(B#ovCHO7KPt|hKu`L3C>VOA@en_Hy4 z3l=Sb!q(n5e$^_&(p+SMt@G$q4Na??@AHVkEvZ`2;!)m1shH8~K?9qjr;W+Y>x_0u zT0E{t<9Il?qjNg!xr5VI8F4rrUboF@_>9)p=GFrE08ecPbX4!~%4RX|wgL+CSznMk z3V+0$H?-9wLuA^@IQ$8TQ>9Se6wdxuKDD$D*+`B%+Q*%`4g;sA;wPJGW^?v&e8_ z-FRNex7szPE+U`J!mt9u>E_imb*!kV6)v}ir-gW2F|X3ay8=`;eoS4C3vvp3CN@>e zPT?(jprO6Cej%(+Th#Q*n%4W~HP?9}`Kv3*+*K`&VdZPOwK9rcu5{?7%0G8ONX?qt z+7U&;@HIAiTE~N$QgnGlp4l87eYias0Jw;Y4aBqcObri6|HIWNLXm7 zKiKc)TJc5jylUK96h@<`X=Qu8)rXn&HLZ{j7+oN~a79f=qqFQ#%L|OWn=ncidR8^J zd&uL~1`mwu8XCumlNWm6OFXNYEJ{6bYFM6yix$nb>}zR+168)v@q8hh3|lz2O)sXZ zwF8kr9opo44o=j=aW>S}v|DjT-jpcy2TKjv!eE3UMln1tfZuSnNedTwYFcaSW285? zFgYSkix4jlPKCSySbG^*=8OcoW&Nyh)>_tEO9=kOh$P7EsYP(Jut0^D9E(} z2Ha|Pw7fwsS&HhaZES8+w3_X3*m$QD7@I~sS9h+uU{oBIj!xADhjCb1TcgL*6820Y zSoI{59`b7oe^#@+IcmFLj8-)?arlOp6ID^?qwhhFx6KY=cutr= zhMT1c%RSQmcCqYr4&PB~3n=25J@_ntGOwdu++uNSYt5P{HqxRAtviG(tkXdu#`mm* zIN^_^xZ4}r>u1)q)YLY#uPLx%$(n{H@ljUwl4@rtkh0sv&pPkf(hAFq6{u&*cFy-a z5c1J&ik^-|%(L9rVl1^06jxDj@%qUn^(` zW4z|_jO86|Yl8en9roz9ZD=rFs%l>7k&%jL57el*1iZ7;WPWe8tHTngt(q&E3&L#y z&056s(vYt$sIz+!Mq_CU#;2w%c5yU$P-&&`D3;1 z9(zt8I2m?N$UGYNU`RKt5a%T;a;rU}nD?x3>hL`cq49f9ThQbi_fRnRG&ZlCTdHC~ z8DtANT`7nr_h4JuwFVJ@YPVIUHrFYcIHf4JAiu%gFwt7)Tv^hW6hh-1y(@-f{G<*7@+J`1iX~@ep{$iC!_II@KMcD=&eF$;5W!e{&R^Hm- z(c|z*XiITBg01D4$(Gi%*UW14tg=+kh?c|l5%yyVquc6QEIb$|DK}}vDjC7+1X<8( zbgW^Eec?)W8wX!AxKvYHFGAKAOr5k07FcKevO^_7y`4!iy_0Cx8go|A>%qj|a>8v5 zUxcvQYFisxWQo^WU}|Y?mL)6+0AQb&d-&Mk4W?gskmDND*w|o9%wNti}_WBIh zyA8E2EGZh76gj3FvS_CY9*l1B!U~IMFdB5o`rnGf!&=i0Y(d)+Eff66YBe!u#=E2= z68qGJh`6R*=Xmx299p}lNsm3CE>7K=zep`d8qOF6bc+{@{hGf>=mpNVxEbQBShdAX zZJ5(|WW}@~+VhHLvCE<7;dJ5Yav%OoFH5CKA0?$^4Y*a%7>r9gIvVPtJ-2PJX10;eKcw*{+J?z~A0XU|+PZyqN52mu-$ z^ZUG9rUk>@1uY&~yPO#Q{B{XPU@x3y$z;T`7gHS1l@-(0Q*Ha8sMI9;;n>YGT35)M z8@-k~=QC-hZCI>$&2DGtp@UwjjS;=K!RL-%g{Wi|Ei~^Mtf!7TCENVP6&2zAv7TdM z&dQx>!AL2X`^FjKp|i)TSi9EKu-fBV-mzi@Y>9;9D;k?0u=+5s@^(a2@ZyXSB$pAT z&q|VpUG8$Ip}bWbYsY}ucilZ!Oq^6yN4pSw-ej$M+M%TN{I0u0OOQgY(Yops+x2p- zx%I3Cvm>5KO|z|;u=Q3<`0Y|{ch!VdW(dx;9Fy|pvd$996Rmv~ZHOd$;#j@0 zY^%J_)Y)o3pI5b52_VXNxN(Nq5^D*^6;1th`{_{GQZ43>l>jY7-CEpk&7Dv!NsZur zXr3%Rb(B}!wx+4JKui=L%q=ab3(e*l+SCBBWT0qi3|l?uZj){+L)M`{)f;up7a;O& z?~oZ!Oj{8miL?&|qOBoA?MS~}S0cNCG0IZ%DTuUVsuPPKw3@~?dAL%@95k~rnn@QV z2rmawRflI0=FpyEd)x`pJ+&bd8jNRS*jN=-mNe8xi60}MG!&JTl-&OyjZcYXd#0C! z=w^aBn4dJtR)gjy$|cM1Zb^YeNRJOCrTBAs8Gc4QAg%zM}Hh7qZd6SemJipZ)S02RG&I=s!9uY zetEfJ&*>oYCR@+d{t-{Bj1c?%yD{-5M?KbvBz;uJX#0PQf@|#2TUti{CSRE`kdT*Vy;QAojVZJ%^ZV)zq@btVm>67B5=hJuFZBq`l zjlR3hqux6-=2;w=+1Q}Mc-wA=``n5m@FCLWB7bd7ixsp)6fuau%Xj!YRYu6uS@+H` zPxo88NP^xe>O$K`R#b_`M zwl>n7=jD|!{EVE--ZG~%4URUm9eN<>8Vnj zDyRv)SVZzdkE|+M0}!@nR#R>38mnY(K*-Be4qKL$JgrXOY|q2FgPG#AL8oI(?FuIuQ|G#IhPBhho)d*jBJ4ROq2h8r6V}hy*6OwW zfGf0pez77rsiUs7xdjtWDOA??G>z`CmfY^H4Lq1TkuF;V8+I%@8kuzeJ<>uJMN zkE^&=R!@tY>VyaCZ8UeIh4C#yQ*~R@%0w%ya`48b^R>-h&vZqY1gpPRTU2YEjWrCF z7B=s;q8Z2ZTaSrUO=MP^>V;#yK}(XbOs#z8xHRQzh&dNGjPP|%=kOAP6aG+HCiVW< zsm2BJE|l*f!NPLS8hhr^f z%|#LWHMLb#Ykf8BnJlLoj#ct6dW_uM+uRx;a!l?dYagZEKi4eyJUjBxpIh%_LMir6*kGA8 zHm9szvBC7P$3`s9$K!f9$F+AuAxC6{(}ngn!4L=WXyYw3HkDxy5`{W2rqiW7umI8FaN{ql3^;rgtfwDL zt%^ZmJ7G zQKUNPQ#E?|iIx}idjS1GdX~R6>FHrl4SzD3`7%dT2lHj)+8a3kW`$uSq&Vw|XqEg# z>_p)FTXNohezZEGl#h0q8G-YMvOi(FY+hQd91d2NK2A=mH1P5R;Y|fOVds>zLZlst zk+uYBXM$;IjYJr3ITq0uI$ zf_B#sX(9ikC!*>}2C1Phq=o!{u>|;`sJi0P^(qni|BJK0cSfbn(seo!`u~pftuvwx zAzK2uCBl}xgK=sW#gucFJ_eK01LuEvBvSu^T2vVt%SlCn^T$NDi^6Pxlmq!66Z>!? zicQsRF!VPG@_$!!>!?mUh}}ZJlFN+ye%=>li{>A!@2_J-xG~mI*6?iIzQ<8;?PO`hd>7&8hu0X7m&{| zjQ{^7{?8x7hG}{^JR7wBaN6kpad=hW{J&+2KZ=wka$GPw!DhznNA&g#-w-%|B5eqD zK<|dbm!4Q}gnWp`hv7$%wio#BnED>#1n85K0_Wd{Juw?&(x*H8moxU5es@^x@oSOQ zE@YdqEm}VuIw`To$#lT3aGxEe-$IYr>Eh;BrbZIAUWDPO<9=6bMYyG`nriT*O{?hKs&T@<~F&_bcbc=?^^RA+qJL<6+D z2WhWPi+JI8rz3SQn(azNym)2<@UugZkI=(kd{o7DfVw_i{~! ziID$)l>)DeqtiLcU;bAY@N-i3yl7(#+L)m-h_5RRoc}`^bWD1{5Fzd^k8$I~`_PJDXI z7yjF8(_bH-zA8+Cy|VphzyIpP|#3$*n^pq2LQ1no}1Ge{b@#cB^}8Ph~*kIc=` z|6z5Jwj^e3hCB)BfxvK?Ger2g81bjr@v=Z5S@7sK-!UghXa}w2tc+29x^u3b;0L|v z{`x3BEzH&?90u)C;4MfT`*eKUYy<)+ndHydC*srRg1(9}8`~YX?TOW(?*YCcj;>1C z8$f$H8sD|Crqk~W1TNTWMEJv)Z9fJ2!$yR!b=VL)M-d1z1Az<0K7{;Y*xX3sr6(@j z{JFl=-itPk2)5B{hU_}}f8n7a%3A1qKz}-NOlb7ZdDZ?v;Bz^jp#0OI7v0-3gz_;K zhPgn$U)Ed(89!ljyK2k&h@5RBmXZXoLKtdSPqCXkS4j#VBt^+nV8Tx-&HS&nATz_el zwg%j^)m+VPo&SDu-NId0~tPJXm&yT zDSTFj%+q?}+b9D*>k2phVssml<%kD%1p-&@9HM>*{V~u>TMCCpZ>EC&_z>yEpBI8& z=0~|f`cOPA{&Hy`keM2(`(bM-ExL^`VY4#j+q6+_geGs>E=ryQfxsy7BT?4Nqpsx% z&(9*y0hu%5@t9e$^)Zxl|K-%>g#19@nx)jqG5N9cW{ueWHGA@kIujZLfzi@VU-Z5? z=FB0>uks>h8NC-{FLg+Hefpd^0X8dpJ;y`VcOvDQ=Csp^uvys>6Yd>EZmF8wBF9k9 zC1GP|thK&Bh_BSv&1DRY-6#Giny(CMK#N1yVfV+k3~_A8?=NBZ$8TW_caS3-42^aK))w)J{Wb)RmNXZAdufPbQz0%$=}0ug(zzl;p=<} zb%DU-?oUvDALzx86vd!V4VyE-zD|~PSce^t!hfN~*sxY8>SOpneXR&F!IYw*w>z-{ z^mWEyF?}cp#z-Rk>rH8#4-dA+=yJYKON4E3i@ov=O-B=9U)_G-ONY=8^I(fHsE(q~)mWdbv#j+Ur=2yq#G8iqOX42cWG=3d=B)IJ>! z)(4w240FPwT`1$Al(A`$GD30kD6N0P4g~@;t#y!?`j@H8ZrC}{p8&pZ5L*)J!*&f}TnIhJ|19y95o@&3-wlTOudK;o{%dyk5OtsaYxXfC;vGXw zdibx|(zl`dBlxd5BBO}+B(eS19I>NYgY>cAZ_N?aC(2Jg* z7(&^I?aH%0LD{h1<*|5Yw<(zof1n!{^ep5H$=)ORy>jj z`OE9=q56|V#4i;Rzr^z=n6o89{uPam_NP12;lC?3#7Gw#kN#Ke8altke^tmjS*-V> z;rj;=zs-|1MDcecJL3C0#PUh#|GWdTmt!!07qaO=KLB-){`v$02^X zLwNn?`M9fY4fAn#$onOUJ+4?Dtt>~pFFx*0vESlTuDCaD-^9n=DRUNCzqrCPIK9kW z;p6Tql6ghQXZ>BmHxi#sdS=+x;ZG+&mGY#m?Kx@{f$uP+F2rbe%Y1E!Z?jC^+eCjqn?8t)uKZhDM%hY6%esyDeoc5FZ9F`59>_Y~Jz|rF z60?XM#yGqupX)=h#zVSu-Am$-YKa#j=EX7csQns&8m|#6PH?>2mN=wl{}B6JsOHf% zC**z6U^Z2YmD8Q;F(!1hZm97bjBWgfla6X?3k zqgRN$tA}8d^3^{Sv!(*?aNz9(J!$Vs(jiE;|;5{u1ZA zPRWDVZk61LPrU4n_<5vVu5i6WxOJGx)rCn!Y=MCo5-Z7Xbkne<{ujQu3Iihvh&sZ>ecf6P%N26;U{cw;uhrFLSOLt!gz#ovEX=Ilf9_w2oOR9w%uCyFFkf1Pku&?h+(ukcQyy4vjmFThmN`@9)mMyWX2O>&}`t@2^>FpE~=q_pV)a zs{2&SKD7&$W^NqWB8DxO{DU9zvdB-*EQ6wx&rSD~SH`t=>|0;mhU&c~AuoLmcX~Yi zB7(N-poB5X;}(OOEOCuD-o6}uABxx>{4O#m7ee`HzizZGSoFtYa_}vF001B0pn&yU z%HQ8l_D^Cl3S~i;z27Carty{=fA%+7Uv!%FBZKcv67M~5$cxtrYm8zaC^(UC24j{k z;muP}HX%BU4JL9Uo#xJZ77?Eks?S3Ut_}NMBfGTCdo#AWbk5UkBK9o;S~0eS%+gJU z`n7&maVc=V-oK8GTkqh?x6Zg&fJO$jo|<=Tkl4Vd*NS2t&`Fc;65F?7ymzcQP0$7( z>aZ``BI%ME@~lnrs~Jp}slPtaf3zuIk8WUArFv^-=lv;GsL`7`wwGz+Q>K*bNnK<~ zq%vo0SknG+@q8HMeLu(D=y*hHaiXt;qY6gE+;I~-TSb%BLPN|>u%{iP<{#Ic*KP^@ zzh8#GO~3w?3#I*L6Jr!;Sy8BjlNs3_AMe-#QS4#EI2Fmbk{fVf}OS?1> zxo_dtTF9WE1hs*cQTTXl4^dB{L5>SqSvf{enaGKygUt4%tXf7p`0CcSI1fcRiA77a zR3kA2e!*IzLSCaKqoyR?q9G=fQ9eK^0U;41)QeHEZnSo3yXNPrMbd_aZq|9Udsfp# zya_8&sRzQCamrw_zhxy;zd{1~>_SWm&Nm!KA&=N`{^TX0vu(@Waa$x0V42NJdT}NX@s%(#mkmIGtggExbH$ zTQ^W}e_5-w6hxQ0XtOs9Xd{{vq6AAadiW}&ZA5Kb-wwaG>o&@>M<$>)Kc{_1`xme4 zjR&oGC)O&_mr>=E-0gX00ta?3Ad>lhenqU1^!FbMIx-s%*#SJs^zxBeb@Wu5j?_wP zY@#VEb{=cTX1|q%@>JLPY%m4sm2d%xb86=$;f(t>d=gNc_Fx~iZK2tzKke9D91Fc> zR2#m+(lT8kFNL$EZ1|d=vnNYB){q+pPw3e%~Kfkas3AY);Oy zO^jGp$xqT^ME0R(jEHSz67Mu~+|bQ#9tf=}%@flB(HEBlH=3*n_gjg1--ZKo8G z9`&q3Y(n4Hy%)|acU0r(X!f6&S|u|MR1u?mhoNYb=d5hLO_~aI<`W{-W@A@uUk}?~ zg=$n<5H+gS=sSuw4^8*$X&%gi&OQSc zvLf-z?})m$xyOQx8Lfz#t7lfO_w6Jv*xXy29l4y5`BmrqKLpHk@Si{mbOq7YD*W zp#?Xn9q$|O8C+^&Q3rVqXJgiQq+YrC3&c%SdsB#K8ta0~OvL}X-|X1bm}GrL%&nL@ zpI)%Kx4Zwz_uTyCxPoK5sqEKu5Y7YnjDjhn_rvb$*n?=`9m9R7TY)ElpyBCUrL+(3 z^lbJp;ckZVjI6=CO|wH*y6&Ob?{HKs#%h*ip0LTe?#{m|DR8ExWxAA{ctv1-cDkkS zpvf;JRD1)6>0;l1Dfp$IH=wP}xbIH^BtSas5_f2yzD(-&<;(0fY%%)5O6yr)tB>r7 z6}kKE(y-cc$zuT^HPvRa`AM;ZSA=Kai;wm5Ga>nfU(tOxCf7qVpYc;q-R9Zid2ilq z=EozcZm}j0yxVa-;_b<7&$CA)^!v~&r&_*f@vji5sY$u$Yt3@ac>M+Wf%W}VghZ6* zrbD`=oN5u2mi!HQzjmq3Jr2Eb^*T9bN7_-3R>8Ag;=RV1@#ziz%AY^A_sg4Bfq5?h zcmI)jWe(h*r+4|-8!8ByPoFgTgG{h*rt^$`?JGjwL4fsZ?N+V>z|TfrD`seH$l6-z zqP5NRSL-J;i4GlGa#l{%yZdD}L!wrRB=o0KwBj=O?e=pPwkcyT(nU(c@(ZCkw{;am z5@(O?%E3^fTIRk`U2$R5>)zW|wbwWO3%F_*AuNU!VS-SeTC-NQ1@9&wkta^Fz1^Y- z|GB(8$DzyG{bKGQqo8s>oZ|`Ek8cnC;1AzTb!ScQ6Uk+{;JL6rX-0~0Pl6=7GU%PZ zn{fA*Wu%i#eC`y*eLQG&Dd=`n8?>L=_yJv~5|Me)DXKA>s^xrk$pMCTF3S7$4qhJa zJO~*oIv21f^;{q{Inb?$;EH6&c#fq!#**>`bJc~t&$V{nxEO*ho_Mdwj@D84zUTs@ z;{vr~lh_mU(O!zYj=LJ5mi69_jXMbHh*{J3#>2rcwvgOSp$NGf={MDxF5Xi~Bw*%K z4B6fV+$O{pYI9z`aLCW_^rM!;cgTq%_+~}qNQk=n1r@1<`7=2)UqJnfR59jn@x+a3 zK$h4N)cS@s?3x|k46hv^_1lz(RCC9Jbl(O2j`Z%ENZ%4+c-s=!p(dZZ6X|}Xm()Qc z=fr>(ylj^}*wK*D`OwBw*qI+pYuky|#iJ8r(0ievZstR};(4IWJ26-Q6*jc(jB|sZ zRNFDOK9|$n*#v6NwYE4*#q7Dnk0(l6a1WSv`DTsRy+e0%jjFsxEmpOBQT>{&JVA%y z$04W;+C&-~T*}sfC-tNtH*-hJ4Ma9$-7I@*C)wfYHULeQF_Tc-iYL_A_n4DA6P$GS zaFlseHJC^UmnIOf^B_#>+>(X_q^H&%``~(-WfoXNQSU0Z(kl;YqSbPoKBCM&N;X%z z5g+@1T0l}BLNhx?@)P}V8;4KyvEh9D7opou2>%vnsivRv!@wO}+AYpaAj|2n01=7x ztZtKAcC_7``0vac!gpqA^-4ol_HXm7DxTKRS`x$ZBTL_4|FWD{mOG#kbME)HGIP1Efzx@@Gj9 zQpF9mD74foz2fz!(~HLLNvPQK^M7MrXY-Cy0wd?9w;~WUQ8ZC!QD#xOQM}A-DV;Gv z#=wA(XH-lqGD}felsFtRY7rIhA7B~~BXBmv3S|-}SJRpG`4?XVM<_=MM+`>}M=(dy zlytgux^lWyx?;NOAsq`13l$433w1R`HBB{@p=4`veP(@ZeQte1eQ147eNuhYl;V;*x>K)A6d&tK zAd4DMJI2@M{~(rqtSf>nszXm0UOkdug+>BD?sdmrnf#B$ewA|qN8kO~apWHF)Vf5I zoiO)SXH|UJK}bN>5CCvJ{j2Xp#dFN=;=q@UBykdMA60<; z7)bQF`js~yx0 zO%uLckm#+HN^Ih@@?7{obb3K|=Y{*+!6@78mXuYWd_+2#Rp~u>*-;Vee&#>n(iZWu z(Ud#6{Hkn#>V|I`pqc@9F~aPXps9>VE&m4 zH$IkPzx|Wue-21hoP=U{{L#aY|O~CIK^`X)++7xJ>l?`a1Wn#R>Dm#_1WOJ~!AOkbV!d`p2J> z!cgD-+*uRP0NbUCpmd0G_Gj_gm5BBc+iaCJ-2tdA)cV67j z9T`w7?!E4R%KutrUtoF6r6J=EX8d>GtumLMuv;WSe#qtJ&FxbJn&b%PJoAvi&>)Ol z{iB2bome&xsCK=tEN~l)$p=%|^WyLR4&FUPqEuLk#R`+J9u;*x3Sa~%qMY5i89p%} zliyCu`kfYu_}_4gtyq!o?G$ZZPCGs_u#>;U$K8!C%F1=`7KvUzq8yd^H#v0~h1?j3 ztq5-#OFnUK0wj-HE+{~hlE-ZqC?Ivo<3ASyAXLd%#La(hE>eQ7#*n!*z({xA)kPWP znep}iSM~xhB&wiG~s^pqb`l0qS+xT)_+x|%i)A>-FL=;_TzJR%**EQaCbj> z8~>~>Z=5x?tTNV}kvgps)j1t_uc|ycScx>`yj(Vl0|rh2vHaqL zS$WW5)yF5n4M_Cj3#k)eWL33$kKP2b8nwuft9dYFWGsJ z+oW#5!1cfTa7oDX-8t~S<|YHXbw2*%3>lIfmv?pP*0o;-c&so1JjsfmRps5yPd;YA zO4a9ME68q{|4VXR-qo#U7hq%&)(IPvm!>+v#3UrS<=-qr^RDh@yPgEaN%A|9%exVy zWsw*z;8zym2dEK~FW~lsB_1)8Qgb%u!F=Fy8+#Zj_<9jtRVTQDi$)gw}rpSZq|CD?6i2hwlUnx!Bf;1$-jGABR zDWAK8q2|c9e#npY!Tw910vrB;j}5{8%m46@nWf|zW_tzqU`R^1Ic$)i8;np%cT>4tWnZG3!kQY&z@ zOZV)Y(~E9*|0&7U?LNbz?eQGaxk>-woKMGpm1V4h)+^A}3OX~Bh6@!f`I}?%q7NKe zTXUin5gRko;^5-%cJjuK9PvYMk=d@OZmLGl8?89x_QP2V=wn`QYcohg3QVx8`hvMqEa1bl*Os`)U2M zD;ua)Z!fXCp{clO4$^)%Fp>IH6frMvb2QH=&nRzg?4jXHR2wbk79a`B*P!94A!Dnc zudnZ`qoJ=a-Lh_Y-m%+A(#BC>U6Q|d{aVr1WOQ?})B$Z61ylRqx zxk_$W-<8IvOiwr6Z%V|{vPN}CEZ&oglTnoM-D^c)8eLlwSCVT`Tha`dMgv$?T0{M% zf@YDjv9b}jMRp9=QpQ(R(o|o@QeRtIEAFUr?ZW*vLH$+8yiv4vDnivk-U{}oS3(2zfV8WZ08D~ zQ#eu-KprTR)vGlcHc%pm3Y(XHR9Lg2+xz0qr|tP+&x>yFfWD;E3YOCw;`<3BJ*7gP zs1{F0Lq(9+P*->V22Gqa?#1!rU& z-X%_qKwe7gxw#E?*CMprPc##`xI4b%p*8eRuM8C1R#k)w3L-Dh<@CAUr$hTA(H38K z$qCxhx;aOh2s+cqwOX?c8X!{J^~%izSm8#M<8LsYMe(~ze`gDv>N)VcETyib;Ts3J zm^@FTFxQ#5FGAno$n!`TM6F!SSvv+F)i_D^p6VM#T_-*>v))YK-W| z1ufgN?1q|mQa>I6bEhKYl`8ZinKuOx`WjPR1~CS4l_@zhLr4tvPDMkVWFJxMxY!|I zfq8ghn*NprKsyVv<2^TW@FE@?fQ?ZP6h%2(yj%=lm)MSPjA4>?Gl^#MMqJ#!7--d7 zhEb*YfG`xWw8;Sb*#TJUX7(q0;>vc&#moemP>MqKz%BS2-+v|fX8=2*f;M}7u}Ns| z8T~2E6Ckxfr_f1Nq8hM56KhF?!zw03*j{}5XYwXfCwfCyz62Eiw<980UnIInEM>kcy z)(p6h&^5+TOj)H2p;!TH4SDjzWJKa+%Nyp~5FmLFl5uhg*kQiM4i8#e&D&KDzBkXg z5s#pzBT6U(dvTP?G^uaKd-aorj`|g0zm|Y8IcwQ-E5Y1b^M8|{1Ajob$r&NkVAdFs zSCn7M`i;PDitGIxv`}enQ6GNp_unOPg<|>WM|)`OGS9OY zIuGv{=wFC_6PZ!I5TJIbYPeE&57(YzqltGo&(!zP z*`K2;Zw4>w)F<|u{V~Kn9@BnG$)wF{lVUw#rjTJst#Xx{Wlar6>oqCXvl7j4blx*SKJ`!N zsKrhWU2EENuW(%XhWc^H$keK}5!Q?*b+q0~p= zSi7-LwV4B#D1ye##vuHyVJ+DGrZb&e1&}t9+^8Cwe7}^W-uE-OrDz5}_g!w>H?tf~+!GIVn6 z#NCJTEeTq2>MHs;k&?Te`E;{~4UOC{h5HKYZp*Ru?mO z8E4NRSmbRA*C~Wd&w=FYF^k;f5p&~=B@AqCeD))yx-2(WohOE7#(|B2;sf2cVcegEs2@v0nA0sEqc%oWL&oe3pIuHk6A zOfQC^Vz)E?LsE(Y=~Jq7K$!BtdCe7Hsv}Ox)>Zw>1% z;P-fwjgz;QU?vJvX`|e3J6S z<>Z0%Nj%o9fcWL(J>s@>&#N-X6*_>9I_GfMgFg4VJQYKt+m-#-xzDJ7`Zo#Tz2o23 z*6&;?o3EQaOZy+mod;MidOX)9#G%qlccf3$f^k&gzFqqqV9)I>tqGaX(F_8?NoIfi zQ-2H#Uvhs1jKR5psc;f@%GkR#f$swT%Q4qKrNo^&RY9(Rz8F$jzdgaTV`K2H%z*UO z>I+GrGN}lu>T@7QyAV`AbX1UhM=`=II=ZaRq>EhOk=-gSdb1YHb@=MNG9x%ua(TfB z@gp3?h25Ol_?+MQ4)DRw2s>b%d=lItH$i$cU{e3|AZqra2&<2c+pc{Ws#S!Pl`A`a ztV`M`C+`OxHZ#;mQ8~6-AC^P8BRJRyE7 zkSFTrw4_(B+cgZ6XSv3Vzoof4V{9_T8BO-mN{Yoo#-yKS9~Ex&fASJkrOvy&Hk~?X z9P8Usg%XF3woyDr=j>+3L&%vS(nF419+sH9Vi{(y9fX=m|djm9+|i6xitx|NA+kmt;P3F6B(o7je8#2BYvw)oVQkd28joccSc<2 zP=m4g6Ar|`E5Y&=KBA6vA91)Wjb$Cm?kZvNpRKBX4O~mYW3zH-b)v@5YbB?^FgVyK zbQW|PP=0QMZ|6zr+M!&^u7C~gn>N+G^u$KfQrB1ttG`MmIe|FW4He1jsXJln5`GUf z_Fv!!9~OJV5mwGv>(Aca=rw4I#+aQk4*9N(qor-mC>Kro7NR^9u^ ziNOEKydw#>%Tj2kCygTNh~=90@bP^rqZQ(KzG(6V(^z>SYv{ySK8E|j9=vPZxc!%O&!O#+`FS(o$i1mM+049MB=B%MDx_th&EQXe0e8tJYz9oy zeDXp|<1SDLtaKLauDrps$ro=-#A7?a8*h&k7|Gz3hD{IS)o;h5?j~)&8cikX#WnaJ z&Qx3J(s}cqJo{q=a-PVJFx!9+KC8?~bv5cVDuI3O z=oUg7`b*T>ZFzm{onWdc@ZeBqnQxn+@f6vfd%J|| zx5-3sX4c4^gwDY}PB?l-N4i7MX2vr`UXh90^CRi6{xyDfGE;B$eU~j+c9rA<*AHuJ zn@oliNgcHEAXm>>R%(2ykk6=*&?KKU>9Az}8MJ&6z3bia(p*!Q&(oVLz7F;Y>N$NheseP`J}gLPw= z@8TnD2JyZYqeCBn`V*|a7tNl$8znNo)@g9CzJ}D*JH#JB)|21b??Cb{1#cXng1^zP z^y57)Ii@pYd-~ocl`Ga)z1zn@o+Mb4GI}dc;I7uv+xOO_K#Y1{Phx!|I`BiM(hDAh ze(o%%Arv1?022o9MSTR<gP4PK)r3rOD0K9Y9orw?}i3@6ZTFb2Dsa=U=dK|9s&0OlYsU5pzakSXjV9f&E9 z8TjW=Lu^nyijJH8so5IU1?-IN@Yiz48hdp!oR8(n4`xRUy3CFpJJ zAw2r|k5=5&goJ7(S@#2u5A@A(4KW4AdhLpzOXSv-aC&7P?qGV&Q@p@{q*joCcdJ0K zz=(-IqDy~9loMqvAG@&(shEX}u*+P>gJQoa{|A^5zzQYVo_hT&P8a*&b1B>3d%em= z8SCP^inqPh=fE97jns8Uwq1|k!iydLv9%^k;AZ!CUHyf1pTj1|ExLKtm>wg`c~yN@ zuD(+UEFKD89kli?39Fk1pAkc)&=*JaT$^nSt#@ckUB1U`R)9?Az)sdT>^75ug`%$% zH;`C!^vNl(A$nc~NRbC(jJ~+yJgCD1k%uvEg9gMUP&hB7537qus;|t>yE!aS zudllTBt8qCrG%W5@Iu634S3#H5d)|~*gNF<%4{E8(E|HDO$K0Pp%cT&hq1aDC)5c<>tfpR5_5K;Zck?S-EVVJ?Y|vk? zR|V(@lJ#t-cy5udX(PsUjwdf-Vvk5m1CyS^rX^O_uZC1 z=}QC6TDw9{>gK{}aJr&T>RbZe66^<}n*6;LsI3D@+Gp2e6a2UiF@6M)vMHhADhm$S7Ywe19cc}}EYV8U?d2YpGr|S$ku`sOLTA}y*;e0lDD^%M( zc#Bla@A86M+v05Mm<;BtCEtF+t|i}jLWQNJ0z{rzwE|+_U8jYZZ22NDvd>$Q;cWc9 zWp9PzFS;0BfSycRq38tLyCL_(2i#iRiuQUGZ3Ei~J~H_1V$ z^3opj@$SvzHQ)0Uf(3*>`Gjrc)gXDZWq5FXw-LOw5bkk$V0?AucY5u2dUCS67dL#7 z#t=-fd?B^li^*%e+JGha6GKGtan+Yns38Y(os?E+SLkIz-7QTn%}-vI{aKb@gY8wp z=jU4BSKYi_xd$u57Ld^U(oxIL5L!r4Ot{Gdi7LI&caAh?DpN8L4bUGr9HNQhMCFdF zLd!ytEu$+ZkmHO58V`{U`5QtT!i}nkYK1*Pmo23$BajCE0CWYS0ewQQQ35!t0+$NhLYaMpqvmdY&P1?tSRX6wrI$F2ye(JsvYVH%9*NAErp@HuIiG6 zH#;aGBqpQ^B?~1B)d1y!-k#Q;+MfQD!ch4E&XgWR3}nXoc3dbgNC$-<3y=bK0oGyPVL8&QeO^*rl5NcZqXO%29Vz`2 z!HmE%)D|2usRtGiKME{&ZpbQ13+@vtGKv?Lm~3kjI4fk63PJ*lCk84$H~=rO&guMf z!Eb>Vu;`h80@yEPlYUL{0S7c1QipX;?VkeX1$M)3hX*0hCN2~a1P>&~>iYB$7lMqs zNdut=wxD2QcPT$e0R!nolpd&os(?ED=npDCu+eIV4rM#?66vk}4SE?@+~M(-pk2 zK`4@d*`6o=)E-3?an&IwVqKF(TyG)}0SY_)7{x9>=2$|A4vrao(G&v|6LRxP_tGu@>NNA3^?zqy3UHI4o5ipEN3Y6H zf&Y~qr;_}?z<-ecFS0FN9E|b*&({7Iy~4U)(^vN9zjJZ_{Y(CzkseY1+t7@^j&EcI z$!eLu^ckgnF8uK^jp2MuDH}Tn8wceLtwK_hyJAo$Pef~2JP+2G<;*x${@29s!lE^; z99*%h0_U;Rjz2jhbd`G0-+VUgeX;xzISLoKvU!nRxf;+hyG|)E`5KUSkpU)ccbc!z zEUTQ*9<9-anlQYwC%+PmyuRCe4ZV7md<-mrbgTWpi8mqWME@iGKi&eTar6F@?*8W* zhgnaGyUPE6>-@Ov-2T5^blWpnzpWI9XYZBwKSA?#A}jw%(|@^Z?mE_d3{?K#Mh>k{ zU!W$M|Jx|5TrA~vG5J4Bd7tl|MHIWUt_9t4h77~&Avwq&&oBw$h7imVkr0sJUEzY^ zrQq6v3WBcT3E;xuuiyv}*bv?$3&2ssJq95J;W~4ErRjO=jK~Hbjev(BgE#;;fDj4y zib#kIh8sYPgr^NsgvW(TgJ(lFgm1-h#^17)VEjsz|DFR?4Wk^+8$JnM6HXI8CCDbo z4o)k`Rsuc$gBo({2Q^G~qAi zL7Rvl;65O@_mIQE_mIPX>QN5Lf{%i0fpdJjhSd78o)Apm^D&4vNF4F}4dkse!Ioo> zXpkTLJvDh!=g@eL-{W$BGKDwt~vzo#l_5iSef z0Im-4H^OiD--sJ;QUb@P{5p9xIJY-lW<7+ zAHnPr$X_wH+%m))MRzPCcA(!W18!S+)dvE`xC4h=Oq8>EWN?RFJX} z1n`}Sx7>S(g1F%W;Je`+91ata41Q|5 zY7j0C5sKlB0LJV|3MvUIgL5xFCF*H}6C!SY4;J|<7!(^^16Tb9f-50guU+(#4z*)_ z=z>jSK}TI-6=F_yzqg5I{Wdn%LN3_hjgdML@~Q3IL*jpna(XNp58l@VIRu>r@x!@) zK2?VMsOSIRpUxy?fnp$^L!aiP(v-ARofKZ49`@O*5 z>>lzMqxW{S!~(GS#VMw)ft02OzoY7;vR%5ov$}N6VDEB4(DM^E@U6mlp zwyuXO@6J3anA~Tofo=<&-F^8{>!arlPwJ}kQYI5;&!)i(YKw7<*IFv!V=7mwN7_e> z#!)nCvWbVnOiagr(9zdvX?W@Kcv@F$Brbs?^0yYZjS8K&=!bKxWZ%P)pfZhZY~B~ zR#aEqXr*dt8G8{*ld!xv|7wZ;TvA>Q&75w=U$>JLk=%_6eCK?jWH5!l%2}XBt7wgkhFk-88WHOo9=vpmjHiiCx(s zo4A$cH_geRzRrGfnfeS8vw{t^M>qK4sUb7$7&e-A(6|t8tz|s1v13o7^BTuAA;VYw zl(X-Q$DRqk0_?IrZ7mZAa99V$t2vs71YVh2KTs+aW5(c|+)kDOpI#b= zTS>0$PEKAtx{7}-6wDAu!Dkt23GdX)utaJvR$;6cY6>~`PtxtRm0rOjyE^ZPP%EPI z^i72O1e4a@+kHOT)6+xmiu?sIQ5XG*7sFI{^PXYv=DV3FH)AxBiGi*GcZu~EPfy(o zEo=J$0W_azuK`-JB^nCMHuLCJJ?=kE3|`T)bn?|BVK_=&Oam&JNO9W9ISxk7(JYX^ ze?Jm7ml6hx3=z!N%Dohgh%T2ba;jkPn)$O5e&o#6&C^S6k`@H*SMjBIO}`bKdwFc0 z9oIW@&p@lv{aZRl-9aSkpTiq&rPK_~j6|8WwsYr6#2l07XqJ{5@Fu;zwP>XIek5;T z^kqUfm}pp(k1cc8TrPbOsGy`~i}gd#nMs+35C6lcP;+LOPHf!gqb4;A?2s9o=4inb zb+;mdB$+Yd6Vx3ppqf%nG6+2@wa}1TzHn}#yq#iRZED≫#p*WEnA==I(I{M`^86 zgv+0aX@rdDckTNPH}`}L-U;DQI=r_HUkX~@&kmfYCVoVeZoE;puqYXeZV4ispE+gG zKe+SgSgB@Mr?lG2K4Mj^)T~rm5)B{yJR`Uk%|vA&TiQRa!j{3>i!G-(`{I-1NnW-8h;C^uI?@}4f^?P(M&Fsobh+& zBP_6qV&~88dl%S5dX4W#&asmpOZH=7U`czDBxz|iPp4q{-{htC#(!F#kc#x!f=C$ za0SAVH$A-UlJsudOm>Br!&X0;H@~4Yd*AjvGGk)ofe;-W)SRSP)ya!$ZLTFl*BGG= zbens_uZC>Ep2dwQ6`}V^wYui$zW6kjod-71+;=#d5m7qKcT{N7j2$aSA1ofok@3+v* zH+tB)-?*vz3mra|3-E6Dx)k%^iUZPMC?EmQYPYKpGAOuDYhSoEp_D<8XLt)@x{*$*Sa1)=WAonW#r z%tkt##oRW!Sb0AxqKZnjX{FPN#nb54imT8kMhZs?-^lG^z5Bzf>92_y-d8XNSJNP1 zr8OY?%iYLc1z5{0r%Okr8*GNyQ+>)cS}1CGiIt2lE_Dgn_)LpjP)xhwr7d0O+RvCM z+M}P*CU#L>sSqUo^X>(=f$XSgLN9`ZRDBe7LY47#mMatVT!<&KNa>2QVcfLqJXk!8NTlVg6ZJb-Ou zbeMQou~Nc0v+INsT(s}cVeyS-0WLdq#GRbq;orJ>LD(^fCr|J~xHtC@AxC!N)n z92?n#!I{`$UK=aSpEGP0@hts2)FBo0L$UE*gMw%H(qd#kLjBiHQ6AF)I{}TSq{b*3 zD}(Z;M|DaXY>_qIC?9@rTgonJJmtv|Z&T|I4UWgs=BZI^Q@c~;$`}|rT12IGk#P; z39$Hvb9cT_iKw>m2&y{@qB zyG!3UoxZHPnRPRoWJsuVJ%g^!)0RByGG zGOnP;Qi`}u{a3%{jddzOA!tgAn&l-KuAqvEp4UQ5(p;hzN~t=&@V)%ef!B!y6` zXDQwllouK$MA<4feOLOzAWUDWCQ_AJZ_Pzd^4l&#LH5LhiY4lS26(99PbHLvRWz!P z#?ss`u9ljjjO}><=2ub5`T6;-C*93Hr{XW_1Fm|brx8N5bCGM|K49Vgq1uy*Q@gm9 zMj&COnvCX{Hm-aH=bN6bVl=L1mI&(i?;&AXB=tFVQQ`Oo28P+r4#7JtM*SJb^q->U z(%v&_m?rnrosQF3r=lfMgff$Iab4O4E)XYyq$`yoJ>)!O=7bp+DCY^)uPM*_FKVTm zxlnUUQikiPJoMAzlsG$De~Wp}#J``^u;QwA&S}dzAUMqX<*&w|5R^zIW2+qdp@PrW zh(_KZiAujxIr2lTr!|dXNkH;rTpFM+GmX8}NZ`CP$S00kF@;HW9;=8>q z<8)9pw`Am#vSxFwS>m-J$HOgj_EyG1mtXITOm+I62_hO!`DQ_b0Eb?{v_aI3ZZeyjYtsS z&?Fo#B*vwc$NE-C6G4Qhpn>ePO>;efM&GuRENA2+fXm#*tf6c4^e%$n769~CHJm+; zu+tZHQLdt|wYlx*ugQH=I-fMuHG+xRlim{!V(lNq^`MVo=ZqfEI>VYlBJCJ(npNyTgFbw9i8ORqmR z=G^gP!b`_kXp9|p*d`Uqd|Z$VBmCo(`5xESnzzm7H21oaqR16@VG*jUbE0nGUII8JYO4KNa9eL2=8AZ0pXzl0`vrlNptKy zlcbd@JTyw>E$wr7b;$x+*0L9ff>*t5O8)kF01HM&iO2lJNQ$qcvaul!dwe_82EehO9$wS{M8MEpbPp+F8%FtF73 z)Z8K_iNf=EHXR~hDxKXZrodfo$%jL0WT>}S`|+7CP)aAXXv|ZmK4tf_kI}Mhb&qaVt&Hnm#Z? z*6QK|rOvE%Tl@#KW(`Qmsi~9MdVCeGzS;}% z8hb1OgzvlXfJDfwB%35mJKwaw3}@D*iqnknP3ABRzp7(O%tz z@uV;Gr(xrOzC~SM$YOs?<1+x=`Bf{WORr=WSMn?X<=5ZPhtP=DqYjI~64GxGY<>rVuP6lwdPJ zyP_qmguxg?#?V47gfx^9m#|=BaB(|1mATA8Oh*daGV?yPpKjKrZ;5AxB~}@c{4(){ z*F|GAA8?7{CL}aEc%2oNx%3Gkn0KvgRybz!Mr8@z{W_tA{Y~HGD8js^BD1BImI_l& zcR8H&Yw?VHJb;2axHh^zMYT3I%UFLzn(leJK&!cV@xkYlV{}`un0vIB%tLJa zj7>F?^i-V9yz%DT3Yu51hx(zO)B_G>|KLVL=5+LSlc7p-@fHP>u7-i$bdJU{VmY4R z-iWK+@|$evd8A7B`gEGfP_hnfj!8uVM^*;lfZN zKo-g%t8GOxCPYidDrpMDNS3ntF*GE>KQ;ow;@E7PO}Ig{sH#qssYpP?#2^5ctZeo`h>G|)s{{%a-G z!Xeg(-sBH2BZ~v-%LT4W00v`%TK`}4(a&p!C(pbQVWp!#@E{9Hwb?(ME4QZ<+<66z zaDEE&7^ODIsin0>AaMfd>4~IHa7u1s)a5}*Q=P*1o87O_m-~zEz}J`Oi_O4SXy9GT zYnzmH+ zNq?oKygw5Di=|g+m!Iq3jXY~sx+%7K*2mJ)hFR5h5Ag1JV)^t^H*A0E??|R(B9!+%g<#4BhNi7^0oLHWt>FvHxmS55<@|>EK9?g)f&(ZYeJ)zorOyoH^y;wPprZ@bblHS>tXRE9o z-H9HrBUd*}!3?mWGrc-RZ@`g}=UCZ|LyuP-iDE3h`(9N1iO6$u`HRr2!Za*_n9sjMixVFuJ5yKG|ycV(A@F^mbdG4}rhR>arsF|R(kkiGXfZr-vr!F3#sq`i7!uBm5iq6t(h1F7zid5O(DHwn zM}Ge(`v3j=@85s_{&)Wzp2FbikM9kI9G=iwf14+4_A_mvv+l>2MT?5pxDY40^iN#+ zReK9{?*V>NQ;Y z!9u+nEcg$gd|y|fr(1u;t-q1AHMFP&j@GTWx&l24^-n=4v}i&qRlcuK|59IPq{AsY z^cOk%Yl)GyDYS^@GzGd5X0R|&m6=``@MZSdw0;q4e-pKDYX1y{`H8vN)c%6`%ukNf zBTvTJXJUS0U)B;XZA|NFNujnMq_#JHf1-WCY?y0(iz}ExGgVi4%8f3uCA53dm3W!~ z_%q-^Knq|y;7dRc6gdqr^)O(VP~9BN5Fg-cFz1KeHro}OvRc~jJ<-hSO=-aRj(INTo42LCwmzEUWxv96Mc3#E9V{)-F{pc z{f|gnO-`PXFX0oU4bxdoP6_$v^kU+_k$DrCp7CM^Cyw167BQ~Gc5GP4cw9^o z)3;e9Y(Vo?xBi1$f7O2bI#=^1`|T}h>wM?B0zeHw8iT!m+655{06zfyV9tI#Zd$QO za&rO(6%v}Y6*3%J1|oD*hVt@8Tft! zleCVpz*r?Q{=yh*3F%K^q@{#(4v-#|NYleeZ7G=)`meYnjN1fUcOWH`<^Kz$ne8we zP#9QJ1THr@LLdF-^zOGOABNs7|Mu}S$llO*`?Ayxe-`GGOaIQH??p>j@1jm-g(6E5 zI6VYqas@6h7QRK@et{g@cHdi4H>oKGnzFYr_+WY{6hdsOrg;rQ5wx?&*f689(2)1;PjhNpQ_D?Hj*vy+=vsDFq7G>+wl4qQXF!&oA-j3)j>Qv+yfp!$F*-ShWskxiW_ zn~G*kjc((GEGW%&vIAyvW{?@+28Ir;QSB^bfUjzWWn*PI|a=l8(8rI>4xn2L?1`x&oXQSWGGUR#)(Zbd}qZrt_DM<6MEo zlFEp*Fu}WR2T6L4!)Ou`_cgiZojd6B?E?K%D5~+d9|$Q%Zi1=v-sLvmfREu#A<{vY z-MJ2Vta|9lkVrJHbuE8no$id}(=_+iBxtbKutR-@({IO!Q{{@*#jZNV_L4Ar(^ zxcb(*AXhT_N$Y~4{H<+dAMx1Qqw(2STe%LO3(iKmOj~H|{~Aw> z?LW;me~pRnw}bonYs@mf)a9hKQg&p$BGMwr2<(P`uQLkjYcp5vY~E*Yx}74jKykVwm~za}EjMJl%GbKfcNFSBxr1|3&o>j-V2aQq181>UqdTeIGA={v7*T#17a zsRy8z^p*Shu&|UY#7|8ef;8`Q>)#>-apxIG zITZTf&_j+sU3(sT(<|Ji?nT_CYsj?yY*$1+NP43fS2TJH$Eb$w0FPKYj~M!XztL+S zXcZ(JpMBQx+3_fkPaAzu2#g^zWaK*{gM*@|U{~r2nR98@50XhIWAD)SlfB1qq|4#R z4G+g~85_BxN9DKl!2_}RkOu-iU;~x5W?OhXQX=D#CdZ?%9FKG!k8BJ?Veq-V->ZJ3 z-pSZ3`)}hu?zi6-22!uRNf1wOZ|CX2Pxu(Ef3@N>ri+P>aRUON_D@NU0;x`k`?18` zx}5@Q!v2@UHatJlp!GnXo=TWxE(Rdja_cYJn`n+hdBNUmxp>Cw+li+yI7CaMn1B#B z_&H1q=Bz+&hcjY#c+B96Fi|PczsqWoC5^UYxu8p5=R1buyB%EX)Q;mNnLlr5&O(b+ z^=5_3ZM^otyw(PV6(^pvirAIvy>jFY*24LF29QKHL%aTMZ+gwfJ-+3jrN{sFs_dGQ ze{+wYjrP}WA?S+xj`}18o@)(n*otv zdazhd4;IVm0SDrc1Y^ukX3YNonA6j{%jp9@{x5MF_(L~2{r-plB~IJ*ZgN`mzs2du z?sEFjLFUx0Z#wlZ zAFwHd+Uh?BH9x;uS&5E*(s-}gERFYOWmlEu_8$-A9m>1R`-z$C?be-Xqjj&1qt4j5 zVy9Nym%+=$w)~mRX3Ni&M9)K$3iV#_?z^05d_iWK+id+ey=3(rU&d{{sw&MDm=Uh0 zk6F*Ca6RjP3TJ`9fCIE@gVqAMbK#J7xb@93o$DJT zyYt{{+?@krx)UCg*&1YazwukiRv8=UpJIpVNZ|GYsgA93kpq-}BL^xIA7Qe<%9a#; z|8S%4`i#~GW%B5Z)~hlxR&x-N#-FW4%g@1x{PdJjbtlQ0`)Z8j{7W{q{k0g$IgwVC zWukF0bXU$%a-bk^U2+s=A4MxTKEga|Gb!x9WT&i0Y|}wqYwZ7=6uc!`$f9fjYrc%i z>Y~H30WwHt<>#pE&_l8T9Fh$Phh#}tu8d{-P0M7iS2b<*T{|x?qZv*1*V5wEqDR8L z=+aYvcdxMdE|uNaPj=rZv-=kIP>88^!pdq*eXU8*I>at1pC~eri{za1vdy;QA{#F; zKlM#0)SCK0lUmoOwQQbImY1BCbV_L%e+)b=c|#0%R<#wO&-Kuy88pMf>@}FPjYt0N z_WP(QOnht_5snaS-a0eYHT3lxdeJ(z#P0AH1~PYyZvL3%VXaKW6bz%h0MoLLa>u+m znSCfxmGKw2=g-OHd9(j$`pT1LACX+ANdD4YUXXd3Yv_9aF*5r9EL4<^>FY_rS#GHT zb6(?@-;oE{9d9L6NxlBEDfDQuTie5dA4=*zNs{j1c+yx97s@%jN$*cf_d zUsIQu{T)ZLwt&Pgb92&4C#UWQXIJ%d zF7&25+MK7cj<5Z!2fp)y0zOZmPh%eNvo>Wxe4Twej&lc`eM4)}-Esk%*;+RE^JA@*BRE0tap@d z4A6_;4OjUC6vaO>rpk}kkWuo#yCTIV=kOc<6$%B4-=%F}T0JqA<5{eC%o~`_uJ>KWcl-@6$HxDJC2_N zVR^;TZ+pj)f&BD-TMB}i0zIIbf6*Fhe(YX!g7qc2zG6&9&CM+ieS^K}@3bIt0XKfO z;^?#0;OH6R#W{3OU{t!(KK2twFlErtjdL?bBPJQ|DsOd{Z^y*Z74-EuyJN6Jf7Q|N z-;{McXT4!&8GBbVa|Qhj%013q{-Z0{aJH*_OQG0rYzx8zcqspD5iH#K^s^{=z`vHbr4lUKaLT#;@69FIH>(87Pxaw^HQQT`Kkfp1hy+dEc) zC$7`90p(jlEd};v6{nmX@TBW&`@KGNi+%LkSk_)Zxhue%0C>Rcg<0Q~Mm#LS5?C z_cJfBRbVBuLv@ky!9PiRXZN+)o8F;yGEbT_YhOFn?9{(4=uv(GS_@em`eA{6%6_xKP+<@dcLFw7u6e>3lfJ}7-lm{rbfOEDz#_})0ou=%eYqYpCzqxuA9!|ODh zroUu=(vt>p7$&x$^E;53pB7rHkLu$R>s&*>zWz(s{O>V%H(Y-VA(>XFe2eZm&7og< zS|I;~P|F4RX?p$%b9%PrpCBu{z&Hu*kx|>pXp1A%>KMAi{zslgA@{qL99o;b<+$2W zN;0*uq%WOy*g|vl@L7ldL(v*XV@BBb{$Jy4fUuqs`M<{9Uh#jm-|AAroY5w3@Tx85 zzAlUfIk47|6Kt&`F9Tf8Q<4oYs6BdmSoH#Z(z>#7JHEPub25h;HubH@*tcAMa~XT^ zZ4K=y8D}8(1uBm@9h<7v6-=zncofqCb^hr~qhqt%ranekkQTq0=ApCH(DwB}zX&}1~%8(D9SiaIeaMi%u_V0IDwD_Zs7^K4n* zvz*NzOAn11I-=}A>baK-G$UrukN1@p(KfF7JTvd{7mM`8hCmvvKVDk2PdU*TXY_HlrH`{F8K37pN)DUBQwo9M8 z#TA6lf8sf^40Cs5!duR)yoKRDaTyK%+?_0H>A!)fJ@%YT(bpRb@OA#dMZr*LIRzps zG@G#5o$KIs&c1@$nD>HTuwaw>OgCztr6#4`=U49s$vxc`ZnXp7iBc3`Naass(`H=pEH5s+&9Qmjzwoj8 zRU03M)7}e(jI$-b@81O0{zRyOyr*v>-i=?%rw1q}hu#gGK zNNN3|u=S$$qZEz(B8>e+!;RwHU|QS3XiLhE@kY}7##2x865GfVkXilNRMy z?m%H?A7lKxWajhy#7;Ap$XnYG`Tiph4y1Vtmx{vA+m+%WM93Pb6HKu+Hq`HWd4u*-qA;nj`cPQ~xlWvok6ua=rwUtH}A1pVax10kmd2pQP+F3`Hp8asIx+ zg?`IbJqAe;CTRgKz>zU>@kAqdogWi~6J@mV?o1E7X55MmqA^jK)|6MHX%Z||tGSl%jg;r|u*<&@GT+>rB(WTR$mizlz zEiW9Q?2W$8Wnb3Q6>4*>{V*-G2|q0LLUpVXt*V<58C({c&9ghqA=9Y;6L-6QO`^HW@EZ$HT^r@cYsOJm!UVIsmx zWZv8_ZT7`hBAwc@o2e~*GP*4%xXK&p&?pA2Aa!?at6+$&qY_b+=Us#rSVLaS$d)vF zDw^R{$w2Cqaj@7cq{sU??)0-2iQK76Kj3Pc7jdR7X`z?=pQFgPSsP6MNGtAqn6>)j%{~zM*$rrlK+YggW-Uh|z?Y5%-3~$GGpSO8o-X4A- zE^qtC{%3fjfVZ2xrG$Cw8=to;{zJUI^L)2?TUciDcF*#-ysa7YpW*GI?(^0w%-gTx z@D_72m{!zXuK6=%sG5myGE_aqHGg?HRPBw2aG;t6=k~$#91rY3@VWXu854c6jiZbw zn+2OI^}0d(iI2-@0fpX|h5kx~cF967aG?t*P)wJR##V_mhmbyqL>h~L*l}O+nyJ!z z$tloPd-?sD*B`Ul)Y~&dzY5PDKQo?qOwJzfeT-bwS?^5~e3Xp+qFTD-sAA6Z>I{51 zvfX`hRpCmtBwj({3}%4fpN+i_PqIa!PD>Y6!2m+210aQA)S|OUb2^*2FXG5 zeUYyl4~D;PF~9O8q?y<=9(~kCfhM(q!!tSV@{s@5O3=j|`4`lxw$wG1GT=9s?d5n* zy+Bm`sLisT9?W@mS!_QIm;IEUF8k@NEoMKh;?Vi-y zx7e3CcRLz)+hqtf@KO1OhV`tQ*`sHV;vPNlWw`Hbksdue(xU^Sdz2btT>1$2D79Ag zXfS8zbFqE0MfORZlARYfn|<;qN7i@GBiT7s^-0+d*(Wa_wDw60^@)N13IaUfSuM`y z7JGA}jn)uGe`sG;{Lva(FX2TK`;%|#8)Z+R2gJJNeaBGZ4)N0b@6V*KW7g@ZZ%q;5 zE;#EF?t+Dpb}x#2T^{Lzmgp`ZzK!t@a~IT^Ld9}%@Yyc|N9a3iJ94QVr*S)!fICUT|3D-6ywgwuPQw0a0TMozQlCLnFH_W|RA2Q_ zVyPbII((^~|6pgSzVVqZEaI21m_4y=X~ZJFr7U7#o9v0p4$wm6v*>}IvL(jxUr|Tg zO~%pL{Eok5U-NS0_GOdozr<`#WtXm8p%jnXlyJ*qr;T8!?i#|~;dO>;s zW5Is2MMtO>Ie;b`6lsqZ)1GH8KK%B4__w(2v31p+(J!0r$$B!7F;A%$v0s<%VK*=B2rZ6)z3DHR&AR*_k!EdF z%{opstKi@A^MNlA4k(t-`xz`>bw62Nw#(MJEiEf7Jru56Hkn*M@I-{`rxe#$O1Eiz z{f+$m;`0dCGYbx%>xciEi0c!Vb|F3XFvH*cJ;Lzs6~m89pJp8SwfxNcoZR}m_BMIubQ1&OG{`OwG_1R zY3btKNabf*OY4O%%`N&`G_Vp%v3dd>ocdKqF0D|=B@5&Gdw4zJETCKu6n*XL3c+#q z36FCeo`o(_t0*1A5KVoeqOaMR_~QHk547rh7Lesq6|Y}8KbGrP&X1&rT6r(Wi@9pO zh2G?yU&G6EyxXh4YD(Mb=X;Udqlcaz$|wZ}9Wm-b!T)~N>Ac<;*45{roM#c=OiTpwMolNYyBY8FF%=2PKE(WeNd3o@XIGnj=G_`BmOWOguTDiYj1oVG}V32j_8Nsd2Lb_USCsuDmEg*|>noB5%P5AZBE zu}@+gr~)g|d{BPzu@k_kazN=MUU;GOda_;_0eL9_Axes)v zZQ-m<*YF;TnekFMqvaaG=Z!Y~#d7V$KmQ`Vz~sM>v>37HM}s+cUSnP5?-R<R3DI_UJ{NyJh>wdyE5gj@5)ow7Ac?u=~czI~@U zn-Zyc?VViny%V|Sov3Z~gR}S!!N1%~G>Z)qIAf=804@%8x|( zVqQ#E8X;B0MPz&A(!xw2cT@Y$KPx`ND>lK@yoq5gvM(bK@;fkbHZh^U6v{Yr8e1XT zMBYW~(TCsW$yKlM>wmV+=*@R6Ewn!5WMbkduv@hGpYeSY3 z;dENG^MUYS#yM1NFfZd#I_%Tx(096eXh?2&RGEfb*OFiV%sBneq{DeVN`mOy-f81J%jy|%wTTXgbRFc;V4RSE@2?zXelor`GEEeMrf}J4N@aow%o`5I<`s9L=K` z%D5lT<_>i*XM0TUhN#@unA~Mixyxg6ABoC+ERtIoIQ_0E(Yt_mMdjWUm1{WOC3W-+H^v7ISuWQ~RA#-cv`660xhxF1;sB zBLZuv3S+R9cC>xh_LHXU=ER+irO};?WlqqG*L5DrLi_gPYWlGoqL?!k#QjGN(;MV``(6<}=-sM+=n(3`gT1QBy<6H$M8yg}! zxeltcH!|d2NgiK>5e#I~hrMu%d9EXCpMD!{s!}iL#XF5RZZWrNAv-IHPvbmhZ>39_ zICv=YSaka>lJl6iV8Sy0!P_iMK3-33bcGN1utKV@Vbx-#==fWdQpmA>L|M%_<*{cV zCQTzHtte+(Qq9?14YEdZ)@9`sKOwb9T8GOxQqDVvGYe&b2}g$&JG{3~2Wms+Sz3By ztQkc7E%v5o<;>(4T=dOQMj!s-+=#T(nfBa`p^W3pg&dDoAG~Ky(hxdJ;KN$XTmV|2`MEhRd(#+|o&08y#uh=+<`@=pPj7 z|0>jfGEUhjC1e_UtwSDuGG9%zo`|)M)6lngoc4?~ZIkc*#I~s`-B?Y$B7h6zZJ5e! z%9uo*ZI=yvq)he2y=Cl@_c|6fWsR5PtraHWkE?3#W*bBvK z#(}V0KcVL)#A)Go2Gl!y2hF22qiM+JvQlH-bVD%-!D~)^Gq3IhhV?X#drOWW-K8cI zDbQbDB)yZpse`AnUxUZDCsI4MPb3EIP21QegzSsgjc)#2UIvy&YwGv0|4hG^e8%cq zG^q5Q&#PM{K)G!=8w~k)LJxO2yzz~+E!t5$+0i)H7V@79A{!-ObzC+iuMo-CnOWW2*0%V&7a30KwCBu$gA7FM6; zI}JD*FAn9*W(2=P03-fW!cL63+uTcUUnz~`l~*fW_gu}z3$G$kZ_1n~E%b90L~Y1b za=8XUU@+%=u3(TvUv&i+rxFu5oclW`>~aTg=LEX9;R?ckHj=K)yvB5XxQf^B*8AX# zGsfP-0({h6EWm3?fNy^m9ZMph zuy4C$EaL~}bHX0^c#hQYN(%cLb8Wt}1I@$R>BSuX8S_>Z0m(+MGW*|k1y)T3Un~Ae z1HD(5%hTV=hTQZM(Rz>@g2y-CpmPP1if=^Y0nAWyZUI}qi(P@mu08B|pSp`rn_|u} zWlbm~*`@PZ4wgJxnx;uJ#_nEL(jsPYd| z`QFsbTMp8B3l0uGGn#ny{Y#_2&MWoQkp;RDIpZ4aea&4gW3*Htw;xK}`i>Q8XnS}J zz@>if+|eHvBSp!qe#n8A*LJ=F%(dn%SW3 z&-1e4F4`gu9FG9W-t;8L8Y3-O+jrmcp1?=Ol!Y*1ugme7yOEO(&q9`q zJ6vi+j}HV%qMA4PkDs?{DaOd=do8e-leQ8&IWPXjWZ@l*1HBCRnQ_NA=&urYz-bFC zet@n_3O<{e$(4R7512x-J9a4BIZf>c?OMQ+Ht$<0TAzPSpU*8<8qorYZZGGf*c+s3 zTW_4QdiIy4XQ#!NAJyGF_p#Eat{X`f?^}odCa;6jTM7MF(HNnpH-h>0M|tto-$IwS z-0>W-^_ILo5edL~b~Q%=O*b;ygA)~}cc{Ya!H=ZG}{$1L|w30iQ0xnkMnJf8*9SGgzm2~G5 zdd?_(l}4wndHct5Bi`P$lHNpx5SqiduXXt4(1KM&+!)G(>F+~ijfJn$2C-SP{YDfF zA;F)D%7gy+<`n}(&zk|(eS<+{$nXD zUSf7cDVY*k!nkb<#e#Ef?X*WmvFlEnX9iZ~?q&0-6|+Ac&r85hP@ogg=w8gGccrDd zoQiCTDza-l6?qH)cRcyRtvq?n7=63Cxiw_Wdzvd($R9HDyW?dbA56WZKpGQ-!mj3b z?2B8Pw%D86xS_q@zXN7$F%!)B;Wo1|M?AxX-Wsoh{w?F>RP7bs`EK6%F=xMIX0IJD z_}bWDPMevun!mJ?CaisBDeOyv43sb!&ijg*3bM~$G|HdCAfJupe0db#n%tMX7}bI6x!^n3}nv*}}Ya0OKFa#?TtEoQynETuzx z7ucklq_To<`+-V*?)xoDWm2itveYx-QmdAlicKZj@Be{Kv`n!vjhiWnc5!r;U`0E1%E>9^~IrUHZ@tduW}j zacvr%n{E95DF3H&2XpVm7Tlq^{$u1yi~L2Hj$@tW8IFnX*vKt8Cs){7GLT62P9-!$TE@m$GS1<$ooZ~29w z7N)Bf!j{}KSH3@`uQx(-xzSYYCVZW2KQFZ(@EcCLF2m6#8?{%n?T$2xjxzzVqZegY zm~)w6>NbQPj@BlgYYUpr(|skh^h|4nYVSoY6ttOGBwp1krRjs33#qzCf zDYx)or_fb#Y8|^b$xTZN$;?(MGr`nP3nCN(1Df~wQ^G=-Vj_R0YFkkdRa=@8#~5sN z8*I)i1-wnyOocXaq5VVC{bv^hj&LH5?u)Fg2vqcwRLg%!E#Jh=Zl8+o3PDNQn5e6< zHKp;pqx@@Qr2MHDS;{MN%$eVTJCe-&JvY}&C3zde%`VoHz9mil0pi_KpclW$VH zlc}vxtDvML!x#F0pxmJU2cvMdx+7I#51Sp?E#q4%6?O2DX9HN@5w=uwpC)-$l2 zo$=&s4m}~=f1XX}a_r02XT8&SAkDsDi}Z9PwR%hVM-2ws4zSq|9)Ga_?x$lNZtNJ^d2U4?ypW(^Up5>2%Nd^Vv$C8-IKqYqz~gzA@Iek``Nx-AEm#*?)f! z55rPVey8!HZyVPi+fF;Kj#aF1X89%8nR^8GrdN4*+l((}0d3xo!WAsu=-}7JPu}EM z&X+gsoBx6BV5p}{AD@{H8uQoEjrjD&T$^*FG`9Rk>QcFiUy!L@=9Q;c41E?UckxEo z{O`%>1uxgGzcP4vkKl+@N=P2x#>coD5{vk{_=45pF#vocYS%QYH4X@vr^Ke;-xp9Cw#FeO-JkIt) z{a+saWqPI8j;VX#6enWRrqwjaRB;Mb++G-bu4pd>g!>JRZ-;vDzJu~{h_njRhnkz< z_9ps)i-N%7IzCLg)!zI!o_IGeIVcy7ZZqD$}YbM zG?%oc%%{e{zBjWaCycLMjpy6^{W{VkEWX@6oo2&J3iUy)?Qc;POC0)@&9-(24Pv+p zTiaL3Jd<2UUsydjvhRH=v6cyc6=vN}(b$U@N+w@(H4e4;)-xVc{*tyg z%L@WQ+3rogD+0|+IhxGy&*dQMLj;X^wk_!l!aWNk%qp?XJ`enrDozL;>_!RO_2$a;=|rc(%Y1o^|aO=L0^m?dxzEIChY zVl@-%#`-m~2P&qsh67%4*L=3HC|gy>Jn?bJWdL=H;xG)%1!} z!I2*sBk$&=6e`Mu7GAZPuLN)|F)|v+&HRw!{}nOvV}oL3R}WdghJ+RJ?djHzW*`dR z8TBXNQ}dmH|9kk)aIB%)J5F@0VRw0qV-5SuBOGf|RP6f?ljt9MsMg7AquR_{6Cf!+ zlBAGZd9t1YQD+O9bL-9AoH;kqlInM>=gBdfeHYJsS|G#${}Sp|mZq>6L8O!w!i+9T%;W)If3-sn|{<}3kNlD(Co(7{te`?9r}wier4?~jMm9!cYS&-I-VO? zG%SVCMqANN;h(-4y~J2UXdE!~8Ku%w?uQBU>i^h6%of$Iv24kGF-Z3t! z<(q{%PFL3w<#1*DDH>b*JzqKA+Z9@0IJ9HV`|adC`AW*fH=M`Z4?KW>HQ@)}l)_;3 zmaKhQA>)G@H8XW?A%?EvI{YU@W}<<)TZ~VE)G^Q<{3Fj)-ND;4uf*qS3gxNLm9#am zgD`2X`$CPJzkXC3JN=Bhb5z~bM7I_5Jcf5*Nwjvak`C;}8adg{Bn5b>CfrdcxC3_= z$&EncSV|tce$G*jHm5w4GsGQuu1GD4e^*WV`22Gd6!wv|HuFZ?G_wHlPj{9j;`BfH zdr{XP8}oZn_x#~-e=mwW%OU(;)XmgC;opnmu{M7%YO2gK#@EDIC9wP&+RK*d=J3YQ za0J`-1%2cUkLO_rEc39Vk)DzSXy@^Kz~$tF>9=*Y=zRJ)yoUhW0X>lSmzeyowdC~A z=#e~sa~I`*E;RMvvxx=#k+s#CwU6eppOO_11RX+bV-d2ZPCb=9>jQUrJI*m~) zEU402@-OPO|Cap^q1Q|FQH<`iqHBy!ZnFJH-e1VOILzp88U5E5^bQAH!WNcazWW9K zG9_i9aD~>=?Js*^jkkb8imdI&JR(%QF_iI5UZkxndT@=T2kik_2=bk(Jl+ z7TSjn{WbI_zB4hxC3f3CWV?{Jk~aBXLjZIq|2RY5Kv}kciC;*~Eq@uNN*?Q$Z02%a zb{-$AJ6hro;*MDt$~ZUA^4!+`qO4`ES<4_<%c~<8>-}LwY3H!;agg$t9n0nBRL)k; zdu13S{(G2w=Ymd_v=5_|{#L%QXF2t`WByMR8%#f*zTn#mdjE2IDi5iB+1nKSjK;hm zkXMRYo%&w=tpaYxQm)}Kt|70-@40UZ^iK=)uk^RUs?P6F=S*Ynz6@oQ4HI$KrkXNUMK+BM}#)yu}`&(Y^s1^V{|`WI-Yrws3uPX5~`J*HKd_itm{7fNTB+ zs>E_;LEfKtX88WRjPU(=NArzx>GowU@@P1n(-{!wL?hB~wxqZ552M@6Ulxn~KP=_N z{dv9Pt~2@Y(_VTI)GY)$-jEqJ}_!ekMAm_2JD~D4amPSdQ*?4p2nGfq}V)v9Og>d_$)AF^-n6!W_umq|NzfOw8Ez@xKpo5(%wYL5M9IaK_E93j^XBN?kXV|k9SAivFN z+wuSC=8x&-_jDw_k;8@z{yhr!HOAeT!!~27X)^*VP2T&^`%H}UKu(lhDd_xWrNtJF zevD0P(W$1#eR5u6j~mRHkQ1Z53uuzrHhj3`hM(-q0zBml%yhYei&)MA^N5>J#>ptI z^G0=m|L5PX2{g(Ru*;Xqruff~zK+g(l6a*5gXH;H`cS1zYv2kjQer!15cP#?P^Su) zc03o=1EU`09;i9R?16PRB#SvL??>?!dJn-z>GC2z^Y*-8>RaHr*p1nibPRk0Z(!y` zc#W@LsOMm@wf%HnAoh3v2%$d;bDgRh2z};|F>A3SXF- z+SQ=2)Br`1v_L^YQOPHbFAy$5As}27ON{~y1~8_qp*NK^Oye}xn37}0n5i{ZOxa}5 zvC_JP6`84($#1Q-*FN{0bKgw!{r`WT-`o$Jb@twC?Y;JE?Y-AtdmpqJ!Cn#+ylX1- z5(`>kJz7sv7s!v_2XmIU#SV=;?W)F-+eA6sK3L}PhfS_>DDO9Zj7({{0YbH0il@6a z(Oe`9z`mKJ9Yp(==o`mjVb2Vq*;H)aeZ2vde@Yk^+{txx{;GV{`xPNS;XPT zigU%+LZD0H?W3K+6@!VjM_PpO&Ad(W14NrP(>6#Vu>7LMM}8yEIs$||EPfI~Q;8lo zmEMDV%&yxInvRHpwqpg2ko*gku4PJDnlVMv!$pC1Jb}lk+VW8ER9* zHb&nWHsjYo>(S<=`Yr3^3*2R239h(XAv@JVp3Yu#H7R##&umQ-+7#83O45R-pWm*P zjby+*l<~SjVnQqK`oK7>TcJqWr<84M<|Tj0F;rT>A}jd5gY8GeJa~~k*|Mj^T=?P= z{*bT>9VD%yXdBwL;qwdiraMj*(g#3aXrjx`@w-|H)s@?RM(eFNt${zw9u{0N$XDCB zCf$aeD*@K!ctpLN`q#CM-=O-=@vSZ`BnV-p|!`E%o;3C-0CnOMVBweM!?JvQrnbPDE&} z-zxg|_d;tHj00nNtYTTK_QnxvkGm92(vY#QAEbK3drv+Y!UTyju=PRlRg#w57q;Pj z%!W?7@;7#!G`Iq9P;5)?#PwVvFnJ$l1CLH(-l(+13a#zW5JUW=gGre$Z2MVQ$YFg1 zryNZ3eF13_aIsCh$<~*Mjp|ntYRFxZoK)BQ+4WQ~i%Jz`&mJFHI^C1%~dLI*8L9<8-L$42b-df?@`Al{XKZ@ zVP-uk^Ofq?lY9#-2A&nsB<>#(OC+jB@|IIW6$Oy*#=nZI6TbG*u%U*(4u zm|6BV3H~xUlDE}J`a>k`Ga^51Ut0MgZM^@Jj0B=50p^|~D%z>Lh?`eM;7|;FO9qN| z{Q6y@+F(5`Do!>@tTAV%86aCL(J09>sPgUV`&kH07ZcdcY(RE<44Y4lN~5*gzf{%l z>JFH!qTZLjjRQTEPIq0j{^gt$MwU{|y8073>Otn@=sfu(-K!*y6pVsgO|O#1msNFC zvTOS47T3KVhoZVFrRJ8j_RoaWN!25?HwuYUyI9`r;owWAb~f@qYi#6iI!i1bXBMYE zX|p0Y&_`$femkdST8tku7zE|?$YEh8|BxPW5g}>}<>h#$4mnfLih=AZoN3%7=3bT| zZ1)1?^3z&6+g`mtvZXD*wzE?^e~Mp>r%W!!FH9t@2A=TgDYg|Te~?aH#2M_6m7|fF zkh3;~mjLAN%|H%m4mUw^94+2HfNG_M~@8u1csL9hzAEBi^O~y$hJxGlceDqZNycthoX; zH7N2>_QeRfck@D)dzPzV7IG&DoJ-b{K#mcdSp)7yNlZ+XjBk&i7s%Jf5bou}Rk1Wc z?e9IxHa5U&Eu|CXQtIyv`3`i~5SEAijzZgDW2am^kU%;JU3Bc^I3A%Dc@MwS!tIxpr5CqDCO0 zx;)J6S3fd`_`(s-MCZt`nPgIvNzQx^dd!X_Uuq87)ytYBhd!;i zuWTI-?Yr%RU&w0auuauvXUV~LqTty6atmnzXmpRb6lKP{&|4|-CR~*=GN~kK?kx;eqImkQ) zS10bYhCN1CnBu{uMCh>7NfCv{O0#i6@pUnzjgipl7 zz)2NaaX_LkiiPKWSR&$E&eqYx=$?-r_&xz`o1O=jJFMbZgjJk1c@QsatUN)kM^dRd z{~23#Le&ci1YSx!L#+@AME8coswyyHuu86s<*>R z_|tU zvNlm=ZH$q%p$T{#$^N5!Z6CF17OsxI%jkrwmBiJ*;;Y}#a1~sEx@yT;aOFM1Mcf5f z(&mrk@K)RP2c=1vp#kFFgMK4W{nBd$sb9vboIw*UMT-=bL1?elUgf>2=ZDOvW9Is4y)5T9al6 z<8BjrRhvjtd5_7kgK>w+`3{Ed%O7~V)QnW0gEQtq6SzIX8kJ($s~C|Yav`xR&z39( zY#%&Viz(E+EOZ+q!4bT>FpLp$U!keP@f)}8c|I}&mo78%H&+2mY zY4@#ON1F`VEBBwACH5^!o$OnzUqe!I(#^bYG2Y_QzD3F`FZL~BE~owW%N^`n%%-3j zwji-@F`c~QF4yf_Xv#2n*9@Feh5<|!7TC9^TkC!+wjs3H-!{{xA9AzrP#3bPkcNt8 zQB>+TDeI;zDCB*qfyJ1_-?Up1e;SUgJ~iC+R>aVm>Q+SGncA(0r9{4HxZPI7I0_gu zT)Vw6m;924>$W0h4(F|icpdIE!kseQ)mFsigfn=!zLP?6*^cT%r+coub3J(;>&btp zBsEgN?W89^x5%y4iV0T-8jX40dZ{sgc9RQ@`NZGREO(Eudh#gW)vn0Y zVUBi1f_FRJ2kAS^lYNkJdM%`F17zw@5-ZmYb+rL9dnmR4p>`?#vHb;o=_S`wZclZS zxgG8@w`VRh=2mPJ2u4Kuogr^thWb>CZ}l{jMjG4hf4iH~Y*5oYu-cnlm!=EGT^Ch1 zEk<0lPnY8`PX6xxh1c7!S|&*~^~AeqwHIG~z}gRbU;Ly4WKMPa5LmD!qRt3Es2;nH zRqd=VGwoWhH+ob+mBl)Zy)(M)m*pbxzJqu*~-@=&GpeCZZ+4|H!l$PP$2;| z^(g&c(U)pa&r_}sGT*~q@9xmm^ZRrO&-7}c( zs~JptKeoHt@K%f9A-wSuAYQEV?!~o4LTH-)E+UWh@<)Dls+YgFpG`0Se!W32A6p_d ze;aP4BKSeEQ?OsCbFY`*XHWKO9iM+maHE$;-IC_!l5nAiZ~j>-mPoPs=bvmErP6M6 zkHEayb(YX{XvhPx1t(RIUZwgKYiMC-=cHFQn9%pi&A4huC2%G%J^;P^AvnJJQ2R`j zF&3Hqjj+OLyIiPtZn|0e_Ju-e>n=3u%|eqtO9Wb{ZxovJc3LJ5d(~I$YXw&vP{{P& zPMeNtKUt0)@zBPB0`&n6YRN6_OKsZQ^=~lQ^%-r3)P@tm4{%*K!o4?IU_eqpNdl#ARJj zL8K);Y7&o-l4oNtz%BsdwrA-J-N6+{6}e>rMYluTX(Kd#$<>F1+TZ4lhGjJikHptJ zOsXS1L3R->%`;z5nshjLYU`vAg6Dit{ekt^omjIV(P;B+Xs)cLmUXCNI07PWV<_2l zC5-yK`V;G8<%mwWy;a<;>!kiVrTQl=6Lj#PuD6m)ZQ#LGcqaAuo|jeC_&*DAVUKq8 zcO1YrnoxaQuY>Yj!#yLOZ|hnN3(WXMcw4Wn{Wl23YMfB4T2G&|HGJGScDN6Osuc{7 z-dLd3uizndly{_rOPKV1eDK^)@Z=$DAg{zORYSC>dIK*~yP>k}xmu}MtbENftNm8A z3tc4(;sUIz+LsyhowvqGedkaRc5gw8eS>V~C?D8g2HuKVb<|rctl=D@_L4qoF9|>m zr{&3-`wE4=et^&d-<2*Cf44-l{UBJssHr~x#Ge&;%npT6T(wQJeziU*tXjyYgE!!c z^gx5XPSO1i#KN-TK)k3&JbIUt9SH4k30zn| zJtLd6B?&JAF;kBV&q9%hm%Nd!-OAO1vnbxE7_Qr02mBf&qs@xH7i(7V`n_H!+TgO0 zQXAaxF=~UieynPPUz?(8gEQ&25&y4#QItJ-dTnsS9R_XiW*}>8b)*fxV!1&Z+$SGI z@}Fs_>3uqj@;(|yr#-`bq^2=Dk4{jamQ<*U%kWdV3%aAK*aWqfBb2UbLg|_=l&%>< z>58b;m07e;RYf0uif9uDXp`wE%rCNM18X~$>9nouRQhD6)v8r_aHo&HIz3mrP9yii0yp>fS3*~X~_c#ODO0Gu~y7ukQsJDfDoFVYi z52Q6lT`HtfU3uOr)W@`{uSpyvmh8YC#%K+qELOIBER^G5-Om!dZM5>bU6= zvrbDqjn)^CrAATeLo#(N`AC*#p5;qANY`(z#7%>Fbe5)fZ)_ho3Wcyt#pIpxjp? z1jDN+xn^YwnbwG?_HE*|wrtig=bcvQi}Uo!nrhT)l2&)=1XX``qj-(5PGCRl7?FOu zbyf*YKj0PQk#$OmluWq(St(@DzQ#h zEsX}Domg?=ba3Cq9dw%t%=u8L1}DNhxZ76*@0xZaF1-$->BF=*TtngVu)PrN$JKNEH6GtB)5OusQlxN~@#}Z%4bY4c11T*fKbt#&jI(r^WGTg>lV?xY~YeqhErA z0myv2A6vRFRL=?CrZEJ&X*@}wt?7J&#yP8BzPRsl1R7|@LdWvCS*G%BE-e-W7gN*e zlkvilo30L?hUKmAqf^1F@f$0KQ^Bv_AtuCs ziBirj7z1<$ApFp1dJ&e7Q4bV<^7(hJoySrATS6; zi%*bH-%DbaKfx8{)QO|N3q-8;K)T*<2oy@y3iO}y%nCl+0tNHb5)?L?1jFOY#NB6# z=1S$=5J!CQ?%L1=gm!BZOsM07?`w%KKkm~R@&JaqyztDq<^4NCowVy4S?X7>@Js`G zSE?;IAo*Yd5 z_0eze%Lvc$-dnR`Q*UZ@n)_M$6n>+qdv8w%8~5JkiBRp{+a1B$y|wwtw%iHXTY z_0E^NlEXYni9-#7bxedJ?zz4kD*j~})~9@gON=N{@!M~L4*CzOoQ3$If;0YfT61G} zEW9uMeMFNz1jPH1Dn_B>e|7giC)(D#{;Zii;?MVK4@HA_M4dtyQwo+-Ite!kEr5Uj zPDPnr^K^@#f652z0d|y(FN~Hd@E+ZWpwba*8%IoQj(qD zEu#-Qx9nRb82kHTJYAIdR(#cFQG5P({i3al!G5~B7$W$-Es*QtCts=yUq6R+alx1C z;(J7^*@!FGzGGd~g<)qm!UseqUan@n38-pr!>Z_I{d5f8;26hSYBUuC|3229W2vJx z%8uq>PvwraBvBIDr9|;v=1QVybjmd^I$GQ_lJm2jYuHFN&c3-DCxIz7t>e5{hc2WHccE z6Oi}#^d$!VOtJq#P}JKfLMm+RCf8gd&T;o)ZaYH)M6&Bdw~V1kqJ&>2O`i{f_XzU7 zj3RvnuZ63N9@~v>v+4{96Uft%74g-X=#hjzl+gbz&^vw5>qj5L?I9BT2l>6~<0C#h zk7&nyIM%lWW(PD)I${rDM+p6(57GX`$Ckk-F@~B)FoU$gMJiUhJIH#LM&a@n8uTi; zT8n+eRz*!c`gew8f?F1=Wf7!$vmd2#4J8=nqseuQY@^x60n}(@oBMhvqv1i5JATt7xZe=XtqP78ty%9>oT3m7x{HB|eJ53PK!yT$x6a z=?|C~T0xARkJ`EqgDdEC)E&3+Dl1;Nc$GEIM_edSGv!htf)s_$XLc&G+k|RYRYedv zesb$9$m4y3=vY?U!FipXWq+f~34<%PiW+zw=~34HT|@+=D}Z$0aB)y;_hQ7Y7P$K) z?hBn%yfFO?S$PxT-MyGT?HWo6S(nYD1wcy8u-lNt##Zz#;HEw4x{w?}xeyr)7j$9s z$l#$_NVt-roDV!_i&&!tR_Bc{h&JK}bR%DdnRhu}goK}BLb(}vR&%~MWRxaxW8JS> zLv?@i7wQbxdEE=Oo#E`WI1ER3)K0nNA`U9|J}2~@)~mxsSyq#5F44~Y^xOywaTo*e z=({*$cgHCdtJdYJl03K~3_t!;H|F=yOxqL4r~=DGt`VZc?RT&$KP63RNYYF`PWGks z9~oln?HF2?mv4k_Ybv`fLMgc-shkR2DR~Os8pTkLpMk~elcS%6;i5edZDi7<0N>M-FVdyeBT|ba{U$Mtxxeew%|WJ#dPnijl^B8Jcy zZt=E;F#1aSqkT`e-G-O{iCf`jCPsF)kA(-tHCVPJ+f*G^{GW#5n!B@PI3#|hOuR1< z^t2_O3n=ji69@SOSK{%dwhw<16(92^)YSUKnnbi3er6HXi)B6(c9mK$FE7B;NV_Z9 zYWN9(Gw^o>xIJ-b`?Zm;#W%Mc#S!GRxZ>2h?_1hMsBdooy3c3Hcpq9q zi`qL5q&cv2ce$(6_M>iB=PPPe{*j-Fog2+wO?ZB%=8M{*srL9xx1HmkFP6Dahl`cdCcE5TO>CgfMO!*zYc;Wv(aw@zxIk;7 z3;qR~iO_Zg@2X6p?U{{FCDpuy2~{O-1J5LSd)k^*fc4-DD~kr)kQS-ZRwj8i$rK`R zhg@!o#$xt6aF>JDBe4q9T@|5XvCumT==Piw zUOMlX{1n+x2 z3FX?swkv2@j2^#8%!3v=(z3jeL#?6t6FFn~?R?L)Lt^4e3bdrmR-9Daiy!ea8iwh1 zeCWzS5=p4v_(2Gz`09(OBB)+?1Tx!jp0DzP`5=bZgw6Se2HKRGDF=Q)QxCj%?AG&C zR!{zbc#lv#pVA`aTku79eCK;W+VdNXVM;A{&{qhj39>vQ%Qlc@t7J#MCbES;5cc&y zkVOpMKXxAJ#v16xGM%e?h{R1%XH|^|6h}PXn+}~7)|+Q&#vX@vnn5b}pHoZVuV+xv zd=_m9VPGDX@HH)$H=Yy40Qo;dCA9qvBHxeERKG8lM-QB#IZb@$QK0jq{Df7WA*IH9 z5Jl`c%33B7F4GdG+X%}y9#-%(0=@U1QdL;-BDgao=8QCVaIuG`ni`-z4lYyH_o}jX2d`-@QEz+?6e*gOhOB^*h6hkqxgTb%vb%9=gwj>hFNvhtATx^CQ9a*WY7v z?hHBky&|mCtN$+6(%Zhr>^zFWHv7q>>Q>bT1CQ=>(Cu8fQ6+Y#%720t-VY^L)+`3b z{P%=6r`0 zzVbWXB0;1qTU>j-r?@`v5OICj!MYMe3$UTxE70~b+RhG5lK&R%tI(FDKPB1Op-FO& zK$>Mk>gYhEuMjDSk?td;wSDwgFb41P3s7%h{F-lI>?Roc8*Sj=4UEreBPtiE{cxI6 z>qD0+qCBP~e~*~rw(0%tOEDZ!Uq4M4w?P}}x{f6}>I_rCs?c$oPDdkj&WyteYB($a~8%eq;l5_)PDs+JoRz3%zGoehq8UMzj@F@BXfAI*0lcj81-BB%!)wC#;l`=oEBfv%HH^ccWu< zVhgx+7g1Ix9>zoiSJG#b@Js7xtg*0#mQm^@kK)`knGe>~;rAtL?xVEpqElwd<@VT_ z)DUJJMUPH-NH<`G%_1^FAJo2FOsi`{uxy>pMRcXR+L~DXhHAc#AC4pQ{YJ7Q?X*65 z##XBMT}{pBAK$*9FI8KSlBz=%Ev_%rueDGqL%Hrqs9wF(dLkXOT_)C!mvK3Wx!jCo z$`};FsAMXH?02LNfO6`y+*Sy)^g&-N6NPZs0B41uD+6Ifiv}jD5p6vi(LVjXE%VPS zy0Z)Kk~Mr{i>(1Yvg4es>DWFbgqc6anQx}-t!_D#ctCt`W(6AG)eB>0%zq0Z;C}mz zBxy)6DoN!3ZJ9|r!{D<_lYf2C7fU(+{VD(U_P4gYTg7bY7cwgl#>3Xou0c z|2nO+93HhoV>vtsFI*wZ+vt~PNPFltGl=i}f9mXmlb71~p05uY%Y47pPjRq+&$o<= zkLL=;>EoWl;Q1HiX*Y`4%vVH|$d9#rIodn!5cZBUQfev%m%S$gmwTQQE6n}VCCAnA zHr_7P^LEb?!P~fg^g+-TVP<@~Rfn{C34ai@L%l7L&e=|T+qnfmiXtok?jkKjbi)i< zn^wKEJ9 zfz~ycrfLrm+gJCMFXMh{_rA9M)Zg`Syq}7n3~{`l>gbNh@|P(~!IcFh(ZkYE*HeR^ zT!;>_qHrMoz++#gu#6sK(pB#PRUtmtwsH zWXUzXLdANok%AullGaRh(f|CC*LR1%ROAj&A)c)jNrYe$4I+s*V&*>Jsy@yk9(M;h(>pj(TE z2QM*NG%V6uG<3g2W6^NU6k__V1mJRsD8;IYotXOi ztl-^=Z)Q)zW39W<&fyv&3TeUNmwIK%Eq8Gc)0AOA`Bk-5g8dgn0mXs)5^;WJ{(x{Vex|U!$3lpw z<1Uh$b?v$DAJGZuU61@c#)+oa|qLQnmS z95;PtlbW+XLu-Wlvxt{Rk)>w6+^c*$IHA>A@fD8XY;m!f3$`zBEJ=$CA5DqUG_3wp zMOs9Bd`uA*5gR^5qP^PEcg6X6Py3k0S z0YoTZt%3OWrTXY%nKBV*U=r4LCW6k|SdZ^@X$a9PNJDN|(XU9Q8vpE&tnsNgIIVHF zb`XQm4r2GcBvGqBu?`JX{!=@MG|kevpRj|t`;bFBh%tc<>>%D0b`Wu+)Xnu*;)ET< zt6tebJT#f@Ag-S%SHNYHVFds~MCS15X0hv%T|h1%b#t;5!{|6N;$ZB>a+ z)g<=8vjf<5Y7z(GYpWv8uL`RIyxMT)oUU3we4$!D9GRrB<-(qcdh3S=|E{PO3o)~V z^~3IpP%%gDy%*^ATqb5cf1N1fI2Ga8`eBYHu2VBbBdMbqfRnjwXV|!HFocIi({my{ zC(-jddQPF|4fKqs=QMgI(sKqqlj%8&p0nvWm!3D$b3Q#6(sMCAZ=&ZCdM=~q3VLSH zGn1ZXdaj~pEA~>G>CWK1a{L z((?s+?xyF9^!yt=U!v#B^!z(LU!mu#^gKk**Xa2VdcHx=x9Is#dcH%?cj@^aJ>RG2 zhxGiIp8uxjr`xc5*9{v5u+20A?`a&?8{Y?r_aC2x_aN~eg8mmw^zMW29VVOq3Gt5Q z+ICF5e~q+9#5>kcTZ?!%qyJ9vo{R5I;(ax~KdkYu7w@m)dj-dX@1^4X7ktk%+4xM? z;4ff4@jXer55xD#jQ<3@M~L@2^bghG57PMe;(Xz|BHkC``+|Cad@!s}edxbeyl3G14)H!4-?xeP2Ofj>2Jv2k{vijTq;JVK)9d#QSP|KOx@N z-FV*1ZiT4Na zJ$;ys&jsTBeWXni?>`{zWbu9n`bUWOH}E}F!{?x3wsPn-3_qTEbH>_?Yx6SlS6!P} znrSYylxTQHc>DQDYvHq*7~2jlJUPY2>3mC3ZvLw4MlDh%=jP{Hu2-gK$QT1H;p%8blgO!);C6Q-V< zk(Ya`IZMZbXdR|$c^SpUO886%y#EH6cMvO=pEj=9W=l>%R&s*LIl7WSLCN`RN^*KX;iaIe#tGUY02*BR?z8YzoU||G6uR3-Zj+ij4sYAmEA$)|<5? zYEWLrdMHMsD-caIBQq0ZosE22fy@{qI0!K&Y2eYazEGs9DB~h#m@O#INjofO=cVknbe)uKVo^~+Q7lM#b7l#& zMQt8e6`%;0O$`g0Qc`h^1%e_ww>SrI4FULD<+?l+TeS%ckO3q$q37n(Fz*zD+JPbd z`32dQbs0r6o5}gv1xi?C)>!@rnzg2|EPKAxVlzZwK%1SBUy_}Xi3M9^2$BRTvr|p{ z9t%m04a*vBf_gFdp`6qZb7jq6mutz)nFms(*kO2TM$s*^3$o1i{A-&;^6J7oJ-KW} ztLz)!DqZ6vQt?ZkYim{o#TJ+qflSNGGZ&2o60SXy85@ylNd&b2n9^lLr%7NQRFD%) zTO6?>FVk`|ilAVjkYeSCisPoDL`{SSJkPwkz+&dID9Sa1kXtY0RP;PENOtpD4g_&F z$$&p^{`_PRatU@r7sxc7=RAV%HsHWbM)iAifMvD#~i>O9tD&o#{zi@1Cp*5iCAG4@hiwIO2*a$Nha>RvP7Mxlf?KfR!c`;{y-9#5z^ zJi*T|zMV68ZU~1m%i`vz4=Bzv zn+pwoIAs<-ii3RVy)sr(#TtA;&aTeQ&#(`0)LHH16Xnm?p7etR%yZ4FAb!QJNyaK! zG7Ja7#5E-ud9k=^5KRU+fRjqOH`d^G0G%@!z{F-g=Q^r(VNB_k_Kq#vtbGg-@Ohj>eJ zewMj3mbp@$nIMEMj2WMoCyw zIKZRg0{NgREg36!BWRvb41f~rh~7rWo?1sIg>x(wNGummtg=GRfRz=Zs8-05 zTLHo%Hyg(ZR4A>5_6o?_cCdo0LRldTeFas)ioAkV$q6(G!fKqyvv9RMoDLi^E4f(m zf=^|II*FeeH9jsPHYPW6LT*%qvNm!8x|CdoaSW$2Tr04_TUk3UieKZR#zR01yK>Pr zZh|c=cU+VP8G@%q#VE^{-!``}V@-*9b}AJ@a>7O>ZseT#vr8<I15b?V0S zk;+tsma|HnU}^bn4#u=8%a`APOQNEqGne6W{<7RPQ`g|z^0mv>tg+`JE-r2( z_;u=81zNa17}qj5Q>5NT6G}5I zYGHsZ&b<|?tT?kMw-6PSVYy0SQ30x8aKZtj%StnO@>`x6ma@5{O<{R?)Bq#L&(Fnj zLoGHb6Iewn`=!uqVyLFP1PRRHQ3)j!Gp_I!&P!qKjcYu}6#Xd%mhfi*$K2vH4H1m6 zYsDgz3724=mMK{_6xPdT>HOBgplUI*I)+B)1?vmVvHD^pXYASxsH<2dkA@W-FQ6@H zIGAV7CVF-*64w)uF5ksswAEqK2Azo6Fn`MW@VWPe;bYXrmEI!OxDFykf z@IO`)=FCs6KgZF;I`B`(&)Vy zXD!gN^%3P2;97Ko&Qr)6IZN5(EM?h~ML723qHI+1YopH6`yp#mASkx!yXvJw#wt}D zX3jwt6vagrbkU+>XU@Wu6bHVr(4_bkLzp@xQEA6qk0WFFD43vTnse8hO)E>Xv!Ng3 z%r!f&V4ZBoG=SP=LR1CEu@YJt?mCSk-0&sKMxhMBNKu~HJo8CkCa16Hy=0k9e`P>5 zVb{_|NUOrcxzp|ZganvQD>&LS!QwOtj!l_d0O~B=hKK#tY+P1xxtVarMtd@Zr49ik z;c`s{*_bK?NxC@&rtBiKS+k@o=Dn3-Q*OQqH{%pNp9N4+rj@X^T#0%D8=amd1HKI{ zJaUu`lexw{FHI3^bEIq2W3E?(+QHU%hOm4!J_qG&q~}b`hr-XuD@M;%a)PhJn+_e2adk*WJeYr!nCHX7#T+lY z5lmt;Z4yp14|E~~#Z+u+Zl;4dm%UGJ+|;R4*WAW3V=9S^DN}8D)1ZK05}$|L$p!gH zum&b|6QUx=kI#f@-PEbMxiFQSFQ$_CTRT32r<2QJ5`81hi6>}$aF$HJUo8U;=8+Ea zG_p7&8v;h6c4VZB{Efu%d}Qv()fuaDGb2}yTqEA1@J&e6k!t=K$*dybn<{T1vFwt( zJOD+RYggoEl|rm2>clI|e;szXk-GfoP)5$jnQ&B8O4PLYRQtg%a*_xzjJgp9Um@wE zqRCrW37CtppU7QUC32!J1u-5+YyI?N8T{nHOGr5GI_5DpHj{@&_}N$z5}w7Iqf9vG z)t*y_*>%DE?9|0DG{9<7EK+%(lMn_p965?<=%5kIFudCKi$H$62#j(SIL=kz_)!{W z#1KiFrb@9nKTFArqHIsg%M~+SseZH@KU3nM2<(SX`sGDsW)#vy!&N-S@oKzgyb>|k zMk;dar(O2rkhWIT0mq>y&cCrD#aP3#oW-?b8<(`SwqYrC{%p;FBvt2BDw>Q6x1g20 z!oW4R#ImXYX5u)2twOaFNNaX#%FflWWM33|KL=x!FIO-Vs(L#$c5(Y4C`#c5tb7EZ1imFrio^LLaLf9>ZCNtxT~d|>?9{}zCGZ_ zR3bNdy-Z(A=!z9B9?#!RMwGBD)0peg#=>E3IIauZ{GUUx3g&1O=Ni+oY>nNRvl$}B zmsM0y2n$q<6m@QzR$oGza2W@0qe&Y+jc;j3L8rx7byB#o%i;#b=^+Gd@2H z%R+29vc;3@c59eY<`(N_m0HlK#`envTrBc!r{B;7VP-1%yhNWu~1r)blPDssL%$qRwjU`&BF@ZtRsp=tWMjlXOB3 zPO{;PO)R}giHfp?gP2gY_%gfWA{>X$$1;Kjh>C8#VVXvfOPX7)2Wo^Bor3ySvl0;z zG2S%Blv-3^Dab6yvnh*l*`h>5Mnpg;vw(YXS0hEF%}GSSW5wWMv&jLWs=nLx z0nOHpeiYL7BO$z1Vp|5nN=;;PZ@@1UGTT12V#Ch4t}hw`V?ny$U{AKZYjLkXQ@87$ zWzNnh$+H-nx26w4uUegfs&*wSmxM}2kzr?>`a>j5`|LUks{@R)f{9vRUfb*ZjDnTQ zSISZrNrjGEwoVIRtPhu@kusPTDX?JE@44BH&y)h7$${Bc6LNSa3=^WL1GB4mRC-5+ zW?y6queaO}+s?*q?OdJs5)6AXjJm2Vr{kP9J>xJZlC~R}jQxVENMPG_4x6`j7@`WG ztxa{uf@Hp4A(Jge2c1|;B8zUa{9rqjY#wE7J5sb0rKv{j5kr}8pIcK?<|#gC-DPsNP3WCPP>#{3o?t#M{U^Qy4$!JznR@IRC3Hae#Z(4^~M9^e-YFI#-;{M7VMz<(LX z)7xDeuFPpsb4U4Wowru)5*Q#!kP z8Q)D&27M*y`njc3>*W${y20R2)Uq!ZFMH#J#_PaNTlIeWV z8K3Np_zU3w%I*UH5fAVy;D2j(&*R?-{};W$$Mze;<_7{2*hwFUkW81f6I6U!3tT>dUX(pXlp+wfP6sUCiIJp5z~b#`R*2a(dNdWv9#t-vxm7hA_T0d&X<^CG}Du90YDM5dkeR>0o z`Pm8hJs96Xd-u1?KlYP$FX|sS-pBYoJSg7;@M&mw+Fk;T_!hul%lQ55@p~Haw*h{d z7x5nj{0WRd#~y#U5#J9)!2-s=Ud8Y3G{55kf2DJNbo~R{M;746G5$3!+s78aI)A@` z@KPI49(cE}%sshm#FLf2-NyxPg2SQ zINhZXPinid-8!$A+CUqhp5X5V{K$Dsk&nu9A zDFi*r^i{6M1;1J`&Xosj@m1*`hM+IF-~8l~{%+s$K)=C?5FoVyO#cxCHGac#+)etx ze?Q{C)?Y2Jq0nS+{#MXG<1GK0@=XE!6JFqN0Q}`0p5t!^{9|6=e+2mRzVjTv7f8}0 zjGt|f&+|wzPr&k>4EWtn3;esC#c!L(peWYOV>ST&Jf_cglOE+C@aq|Wfz$MC{Cx!Y zI~o6L*Zje7L*q`J|J}Y@umw~52aZ>MFX(r6A%9E3=U+^JzX#=C3;2`IxGPUvdF%!J zhtC-0g=0C3`8fsn_b~nsF7s38%lWDG)6kFZ1?$)!1pQq1<-pIBY@xdgJ<(LTE7AQt&CsgIzQ@qoW_4(`E?J|!SN&u@V7C3iPLo4 zk0;w9p0_s*%~jt@N*!}zcP=m(q?^tZdF zw`)&We|v#`0n=NY()ZHUAEtW-=<3gU(huy%HL8E`nSM^tUt&)mXsm}Uzz;pA*Mqpy ze{2OLKgQ3q$Jex%T3<>HGDqzn=wi+p*KLmHMOY3O0RL*nU+;`BYJ#x-qx(KL9ml`0% z0HKE>(n&Bv2sIEOl$1Bm_xIj=-*wlz-?i=^XL8P(GdsI|_MDkBv(LhC_-{$&cHK@y z!FIL3wxoN<=6nw-3vuZyc{nVZzXLg9^tp=$r#ZuxXROau71=n@F;s@J+D9?q*ZnZmzj=yg$ z2^xWY__UBrEN?Dtn)K99IpQrtOr$yaRMXBHAv9k{WGasA#eGVq*?~79hDi~reU3#& z?Q?r(8bjfSQ$)f0)yiZ~8g(FF|1{Bp#gT|Pf^NlF!UL`dMLkfNzeQ`>QFqtim* z9wHI4*>>Si_{25rTv~t{F0@U;Fb*2U_Iz|6)n^0d?4vGS!YUX{)F^A zYtby>vSZvunfs|`6deJod0BpJdr{r6()?Mck;^CM1Iomf z^M-w?Gbe(%Kr4Hof{_jORxS|4xv)G&v6`1y>?EB=Jkl&*s}lK3u=3|~Ydzdt={g|F zKWO^Y4(8h}$$`GLkFbvf^8~x+_%_0KMwzl}8M2OFh8SeU93}JmE@ev;ipBVP+pYpv zE@mr^@#^2N4p1MTcQ-EYM;P?%8cKcn#Jj=2cRsl_W8uNcnbCyZH1_Gg6&gg>p{QR8 zyE1I^^^SKiWAifTb`!wfd0?gnyhMo;tuuWT;XEt5l1ks(=k@e@X zK3s4G*uFw+8*3~~j7aq{)3`D0{zuQ$c2)hZ4o7?SXW)jG-m1Ec{LO{%hda?<3A?jW ze@~2?>UrGLzz{7Bdd~q37?wHo$$C8u%71 z64#gQuG|Q_+8f!*Qxus?TnMu8oP<(X9Z!>626?sTn*3HazZYtii}9QJ5e*~zSdF#E zTWXT)$Hj0*4}Qawp=I)x?~Ix|%-vf{-)^=OEq2NaVOBJ*Kj*vPQE#cJXv!vM%dtH? zSUo~1y0zI4@r9Qtd7{<7%rrCjbU|tIuH3~x+0aaQFn`3ucgEbfhF3&N`0cHGk`sm_ zqG_IKvykT-J0~vett>{v+fKcRoQ)e!DELRi;_bXgn0nsF`G?}IEw2Hr~crk7IO?#KlXT^ z-wgIuq8%SDGGhaX`C!){JdlS8OFgFl0KMX|jcTzUN06Q+5&OQK~PxSM*r|<7Ug@}>d zM>d-WzgIO}Iml+9t=TZv5%v8YC;Iaft)HA0(vx*!6%&YYdE><8zQAamcf|fnj*fYm z)Y^_5itWA4#iP(GS{9LUzI>WWLT_Z9Sk+(ZE#mV_H__M^P_@k{-ks1Esgpb+2 zal*m&iwy6w+|9hc}yYy3Se{8M{e6(L|iyu+3*_#j~}U zrvFv`ap-7fi>s2%o02LPZ|Gc;wJHcE%Sm1_z7HzSEa{zOfnZhdb;*L8@joO60^)uo zK!5V}Ig=8OhYJ05HB34-;ln1hZC#y==9xdnv#%OhF8;jn+V6_XBd%8mt)?yayo3vH zcNj&{uITrZPMGVD`UdNCQMz1C7akv~kqMS>PLg$9lOGJU&fTzsJ{-sRw`tKgnQ4gb z1bIjrd##$_Pj``z{7+*Z^kEC#949K~Tlw(QJllM24onrn9Gd`j$9xaeLJI|Y8m8X} z><)V84TB_0-C!^fP*1#bW3+9Dn|CG#F_+_{T11A{`JzS z)pmzlI^SZ=2wx>LSI@>-I7qD&WYLP%d$K=)F)$@!6bB zyRhIyXgqnQFSap4f%IkmkDQ{KaIBKBjcn>5VAH6}>GB`bu;Fw$KdzmflOv2oVs)5> zAC}H?h4xMH2kgdcH*HG_+4i_aBl{%rlxZ(j zz%OoDnnH+%L&R56UR1Utni&YgqUC4Y7=a|m`>D?31LtkmuFhYBw$;U1UE+5w`Yx=H zUV6%T<>6`UeNpT=&+V^!fufVD#3iKypHrB$lczDs!{icCptr;ed}gb_Pij7E%9}TN zV8S-!2jT_|sH=dmih7*HD#@kQajct+v8ayO7Ege1-h2gdm^yAwK_go){N>?Vi{sLg z@SEhY&mNu)G0-0mhbv~If)}cI6Pdm0B!_c=UQhEi*ihRIBf@*yHTDgUR+eFAp9ODL z^ja~DFbZ%Q4lbE1E$_p!7TNa)FANe!^}oI&w&h?-qQ~;?GzHFC0AB5zjOPruOU^Y4 z+&KRHsBEoYS90s@bkFX>Fy6$ERmx8_Ixi_IbAdfd-$mP!un`P8H{6utn?XJVRA==r zOad)0^c^81Z=G+3g{vZ>L{=pK^-ckJ)Sts#M>E0@^~_%JY)RXeEQJ0G_!86c+ZSL)aFE^q*)pxNb3dH#5ofr zClI2U_AJ2-o3kyB?YQ=fv)RK5dU=irZMI;<2J5`njjQX1 zI=!r)pMwT&Ey$li1#7^~En)Pt1RqFs@7*$6W|mWwIAMI~D1JZQr6c+SK5}S7-y-JX z^}8<1-*Z&P4*=WmZo?(2gO}0|kz|boGfMV5l&n$y=PiHm%_Vkn5X+xuIT!v|Pb&LO zbrV7*GEcnMcK!6y*b&|KHw8q~PTY07fruqew#oyH^v0ngBVf!fN1$UiULhL226!aQ zVhQYe4S}YHuq`n2P_{bD>JJh^NmE_hddqfE0+ifgT(qn>23AMU=Ce7iZP!JXuL5t1 zt+-%UMJK7bA8(Uj5p|TnlNbijMLYTP@srPQ()K#;R83A6t!rTug14i( z*36m=#`HGrS~a(NqAOyqIADDD9tbRPY@B~avGk_L?gh3}@SRs6sqG8!z@j6r-x135 zdy+)#7kX_zaSix~7#dHBD$(l+2OWOc7pYdw=RH2>7$Ib*|-g`zcV-=i1Lf9_^N;d|l6@A}Nx;WLEj<3^k|c=#CFBC$2^(wgZ@ zFj{Rb6AwonI=FVR&02zc9P2j348XIvX??h10#c1q5e6Jt?l9ys;Pb?hMn+OcRf}o z$D)05<*p}ludpx%R^S#Pye6wpC?5s=T;nc-4>O;4o5N46d^cI3fPZMvx(0UM?3d|e zE6zydKM_YA4%M5LL#|uCB>+R#F0^6gbePW4KD&F1u@u?ayP13LWu8=>2Irup>aD0f zUwpkYws^kVFPr|wKBCs5a*q(gxfb#T%+@0;j)6;V0LS#EE}8t*yZhOhosXGPXVwVR zJ3bWD<_F-up^-y$m@{(ETHq{#cko7SvbSzK;>be(##N1o`g?M7PE7P}n8U;SWT%%{ z=0~S}X9d&IzdEKZCM+ie-$J?nm=Ja+g3QD?&*K*(!`3G$Gc>Oh00y>cTnfh zO?c$oz_MUm_WD4vH>#{T1!I9QIy(D)Qbg(KFICa z?h*+!4RW@8AIydSs?~`+T7g=iXZJ=?X2O2PgoxwpLjoLc9bFZfw7>{&&rNlQND|ki z3V3=gLTRkww_p=|JP@tV16 z`~9|)joG|gMt+i?K;hVTYsH4T<~Il}2w&Uph-zeY?04Jh=Q_Nl)3azc`99>_rfr(% z5l5iD;M62HVsp}tx$B;KyQ{paz7_u35-}VhvSsQL!K7&%>w9`UHDlwrLEmC5q;2?h zj_q4ZVA((7)IWb0(Mth$3qPD~p5k_!nsByGib0E9kCH8VwRj>iNwh~ve2Bz8?S zPm33M5H0U=4pqsgp)@yKljC|G#l|qYA6(+IiIztjM5J!-OGoMDFHd)P~kwTiGw1qNLdZz zUShcj;>|o>v`1O@D&BLdpZ*|GYu&l0rhc4qReb7i+iMx~l_IwHnLngnMyPk*B;H3B ztFJ&hW3<^f==VNmc$n5Ie>zo}^h(0ESbFB=YjH;@y=5eLbwq4ryTkOKwr`gO>68+- ztye**uZx2#cDSh#a#{cbsE4;qV$&IU~#b1 z-&)3riK@oi+Se2??h@r7C>n{&4Kl3m8Io|6ty}i8@E?_8JfE?lRCF`ye(&DQf(CZvECDB8;SkZr#|Y?E8$0yAuUvLQRE3-J z@ShJNsfHJN4!p&=Y1dWlcTMs|=XLdv*r~?Fma<8^XycQl zq{QoJs+yT~?<0Q&^3th1%;CVvkuTq?WhyJ)Hh8-xL(X}Dki@YGQnOj|H^I_gwS`9r zUI{-G!=L{t)#lMJ?sd7h)Ax;hM-%5<);rVz-wo0a@WcUKVla|LiS#ZRu@kM(Axg zyM$m1RgV2yg>ipIo$n{s4z!zoua}UU2Uo(}$}_o)fggiuqbkW++$Fyi*(AhLIO4GC zs4n6c6LIDewVd@et#6II!v-w}w#4n&i{H37%EqkiZ*1%TnZ39xznsB!%7<6iX>ar| z=CkG(&DJI(**gk})N3sUYs#4t2`fruFwKAG)q{>L_m7s|;ZgAtLOUe^f2NJZ^qg{E zL_GL7Xd|X68dvW_jj7QN8h!QSwD?_HuzUK*s~_C2%OdrLc5N>jXFb#U_;g*yy&+h$ z-dJYgMpBh*qbQ`*_v_evcW`yFJL25l=Qjf0zkFYnb17dGzxvMn(JwTAu&v|Qy-sW4 zDGsm7*zPY9`LO)5J!}BU4%q6t~Jlhkm|3O(o zfyH}21lj2lenN*I^=~%Ui!NaNF{h%V`okxQss4icNb>_ejm3fa7g;UburZTn>MdQx ze*E%u8p>Kr*Q*XsG8AxLz0_8K+6p_<5s$LemkN@oK?oQw22^ zC47IfK?5Y9Ik_Y`jYZY@7X(f2EX1ztt?>4a-T;Vb68f{2fURa*4%n#SrR$M-+NgO- zVO>`ML^=uRxT@KffFgg;640Rk5n&7mTNEx%5Yx8PRq6fjBVaZK>_>8GP!;OuO#j1V z$lVuyb{m?y?@@*GUnp7I<)L8`41uyj>%}wXsi1aQG{qR0wAi#CoR7t}a5GABNzoQR zC$QresRi&CWY@&ohjW#8J8#)U1PYEf{nAX+&qq-vwFN+Ul21q)3a?3Bj%Y^=Vr!vQ z0~9#3kgY+ikrsV_y3fDB1e{TX5n-nm_fmh-E*QBV0$mse>1)J+Y`XKTI2!wNk*gq3 z9GZu6F9;Q1=v^#^`HNSnz4EV+a-c!STuv(zSb9js@s3%}DVhFz=sl-qdrdzNF9onC zSa2K&84ZAlC!y))Th;v)QiIq+aYD7v%QfnitQG;_-%AekG*wvp0ZNfg^gP)wyw8Lk zbMj~=OM)v`lbS>O59dU-2v`UeF&9Du!skNh7&tfZaiD~LpGor(J|bEBVqT_b#2l2F z=YSu*7$6Q^{(>h33t*s=|C$H(_+-{$eOmB5{hho+7UqV=qOH!q2Hdz9wPO4;`Z7~m zb4HhPwCK3s!LNU{_3N!2gJqJXp#GW6(=&Nuari9GbnBQ-y0sV#gx2npPSTG!BH8I#1Vc zjw7iQX->xWIUZIeRDRcL5mF#U z6zLCq&!ZQvk7LM#GcV3O9QOSn7TxT;zZVr{WFBG-jE3pL?OtSwQgx=lLpa9SV@vge za{WPK4NRRpfj_+n(|_1JS<49B_v8OPP^gv8!yxd}Wv5_~H64W=LsYdIhOz|=^CX(? zv6k{Ibj~7w58Laa*Wo=0D+i;)PgR#}+wXWr#7d!qqRPXfuD6;n4iuvq>hzlE;=bbA z=&y^3%r{s)p|bzSafx|O*qlV)!+OB=N=yRu)ZfPRo0Vkip&9Di1wpT zZTk5)i5_9h;yZRyC9Bpd`c66d`D35>iyc3E3Yc8-Fsnu?6)Npx&Kot?!hVbOd%{`3 zKS!`;oK3ahGSL-lK414pAO6D-vJSS>@@FSwmKye=dALxS0aIO<6*)G|k)ocH?kJ94 zaQ7FRWw^#iCLw*4M?A&mh)fDFktG6uBI$k>ToL9TPEo-DMTw5|6zciIXV<$376nx2 z0f5e-m%s4&xt{%zbIXq5qO`W4uW*Z`t z1P(fIkzEwloU=T{Zov=?8l7_df1L!;jA+0?aaJqQGG#N*Y*bB#>lKtrq7C1g=yj#% zkEgo)xlm6Mukis?pL;-376TF=BuemMRJ*u-UPz1<5peTz6B$;DbLB&6CYmsxq5ppo zxryTH2cz`)xRlkD`8-9CN{O!Gs7r}o`Nl=cR0mxj_SU>}6-8Z5+~X4yxvuiutvTLR z6?Kj|aA;J~?ICFz$ukE81kpb|fCNghmfwwg&NG65mGP{B*y2~NnyBm!R&Xj)7|z5Y zzI0_>jQ>6GX~b6`8nvkzT3)M@KVQ18=pM!f7n`0R+&mWwbf*M_a_tEd6IIRJn0k2a zD##ocRPx1h`iJx3sP#H=^Cs&S9%1KE!HK2fPCc8Pp&E7YocU|(jdk$&d4lLwDF>jG z19Ux&dojZ0VgI6s_(JFA?NANX1?7G4Fx`MH0ah6M6P!11!WSg+K>4{_n*^Jd)Bmm7 z;`c=DDT&}KSzDzJ9qVZ>VQ1jh)A>PP?;tX06;tzFBqgT2MFtLxc+CX^2VXwCh>WtC zM|O`=5|L-xv3oNjRHHVM3l6AQS=OzRUUL@{6x+{MLsBhcbn>h z=uAat&sVND21ZG&1Jzy(#JZkAgJ1P^;^-YmK%R;IvGir>?i(iFI6ygF1@M)0Ag!Ey7-e3?_= z_w(L-K~so~`BJ`$DMZ0MKVR+?Q>I)|$tR2lOk0bn#m!zp8AwCs+`}|cC->7`!kpne!~mXPks6oCl@ zdy#*!GtyrZFLl266!t&RW4ik}#W6o7ylAV2bb-T5DzBL%T~8rQ@{|t~;q=q% zX|5t@`o9Rs?x7R^$1MK>=wUZ~Z{62rs+VrQzJRRBp#jqWM7%w0{N|Kvxol^X#Rt3rs;JDNh0Nwo@&J3Y@Gj3Fd%waBr%8U|MCq` z{g-Q!E~-d*u0SMFHN}|GtG`8R-cW zxfQa>$iEX-FU8Hm9e08Ko$cw&A^Dft8SH}Geb)uEUj80>5@z_|I()6;1%K&vt69^p z6F3{wXQtMs*KD3iZ#1kls5i`v-Bq8o0`1gapM3QC_oKi2jSkfflsqkLJ-JS`o_mf? zu}1sp2NjT2Jco6Io`f#vSdY|?%*o#e2aEpToMGR1v2SQSGCvYM5FTGWNQGPI3E)P_RZYaQDKl((cJ!&0V2g1+^x=J)U0(u;Jyh9EiF z?xX#yqvC-g^${5_*&o6m<2DmF}m2Gsg>X-TY)K`z$@*#|Yy0*cpqu6@-#HcN_b8CM>1atSjlbS-p6jJg*3 zf_^x6xCaa+!p=P9s(N9N1K z;Ong5syWhQ3rkvpZI#1PHhl5caoX?1PgA9!lVq&WIcVq%7Ucidr^ymi@4Qlj37Znu zTIbzaS2SK=HD28H-si9wdq-UoI93?DZ-Hh#OsA@kuU{T+1evvT=^TIaXxCHy`$T{@ z9D8QH`}0f|$MMtSgwHMGc?tW6`>#DFpZgCsRZj&M`j` z6?GN!dhJ9W(Tn{Z{6Ve$N(A&z)1Oe+P-+pWh!o?G81ZI&RDzGG!#FC+;4ZN==ZAXO zk>A!kHm-Kl>YvL7vaZ?fe7t9U{%M1-j){5`LH9W#e3Om!>k{Rs=wj1PFmFimlQ6Jc zl!4|2TmM4R_N>6)s5{>V>a(WAmM5F0Ku_(}8P~@ohL;k?dlQ}iQeWSQ=$U3~wf71X z60#Tq1q+!;!+RFx{0IAF^;A_c2BA+1+B=E8%>eusYz zx;5&wczW@R5-fCF7R2bnz9@}+A+2>yEb)cjPuboytPrSRwO5+$n_T)YQ-&oE=v(gf zkdN`-73BQQE;9%l{ldH{N`H2-tB>mG*n`rhQ5| zBuBcb>y7FDzHSoDEz(KOg$p>R9oM&(pxkw51kHUX=Am0Sl9j0kEQ4 z>D=*aG<(>1krEVHl%ef_v)C)MGS2f2vlgs1pMKu`cIdkEJ!rWdk1vu#T_0y@7s?^`b%UZw$8GUDQyC=hsTb7@rRL)$xX`3TS45T zSjv`%LmujYyy#A;ytR2KcH=3pMY zDf@0bmaNi`MvHAsI$itwx`g4D}o_a5hzH3Af9FWkv4LJ zOBBo1!9@hcQ!X&_bbBsX!5oq36AsZ z1YM+~oRL76NMe)g(sm*)R0nA(&1>S<~tN6*z1hgoqkW)XF#t%J5we}z9>)DMdn+xDVovX<|HYNE$I(KYH z6o2|7C5a6#N(==>KXqV1O2R3U5=Au^GGHLhlwI3Sds56&8}BIa4k9NocBgG+!-cL( zob05wj1j`M3v{A^gIMd&h^GD}DTLS{Ug;82w+hMTB8kRnDWzACB(u@3+17*E=;&t7 zLA=5o&vJl7$I0a_10V~z8MtpZrT?69)`bo|GDcFPCs_*84$dY$sio`2(`i}_5o0_6V48(11FME4MXcd3E&f< zylT`|VA`pZ;l#VZwJ^K^bf=zd7NiqHNTTc_3>^q~xH^cS0u`He1`MMQ15Sv?Fv9ur zk`F?Rk#LehqbhFFFr^&h?hqUkz<=;i*&U>rxIf3Kp8$Cdh~4_RPv>fW%8P$%dJjx> z6o&BkU}!k2cZ_HfJS4@LBa+1b4iUd)%swH%><;@x%g1S)P9h4BjuKK3yiReD00awm zpCMvt-wBcUl&%qjHJ}SYWdDRmCzs=?JI**k5@XF&r0~0EoA6w?7~YjMw1Pl)4xG}Z zi;{9Rp-$|8svEEv&kHq2XL&^_7mB*hkt7{p>zvidqy|a0tWRyuv6ef{(a9p17qs^{ z&o>LKPVqO+K}kU`xjWdR1ZRRY4pQYsfhRC=-~$eb_^hDnzhcRfgfxxIz~O zkOOE0>)_vvX%AAybCLo{_kT_DL3wCfY#=s3j3cgnPV$&xkJGu&NQXq@Y>~Rq^+M#U zXClH1NP2hD*{qmw-Rg5n>1*%V0nBx}lo$lRemspVNCF@cO!w;aMCv+`c1uN=nZR8n z0hOnzDhE$UETmAS^vQ5QGYj=3F8(HpAx=6_BX0bMbLAAvkYl#9yi>O$FZ%KfuM>L*TblqC_heV&;C>f{#+r>jj%L;6rSdehQic76 zbO}7`Fw!HEqYF?INHrn3Mon$VyGVkMyh#D#nCdu<7zXR|wq3Gqv2G1-8`m7?^7aK3 z&Xq*yR3;htL$kLgi%jQ7ELMyG6XGS~~BA6#cDjMqgn{otBX zy7ju8hc4%Fw~M4@!|5oYb*?QgtibX%FM=~Iwva_52FAaxgUW_7ko+~#)TUEXd3 zb1HuGXcLSQqf*##f&dlz#j(V6iJ9! zoz8M((jQ)aiJs&rF2+3kQ&6a zxicq1KtHDWgX+})>V*Oi!Ku{UQwM{7HF`LJGFXotdY-D1jULivTi#al{AUru3GbYb zya&ui8+Y)|aX|UnPEs#sqv6p2su1M1`o3(l_#j>&5{cng?GU71PHFP&M7#J^Bllx% z<86P^Rb2pMg)FoFh!t3;r>k?_d9?6qHCr`HSbVtnl4Wdo)DjymA4fpy>Thzni1n=f zR8M(!+O~$X)DxWG6^Lg9`($pK(W7S13A z%iyfOF}K~a=C6;Yy{&YtS&kbKsL-0cdA(|O5A~kergbZ zsQ4AVA7kH1!--_03D6S`JkWD_Y*1e6sZB17SLXq1HD?mi(M1x=MCsY6lMbx#Kb@kA+|(Z(AkcyO9@m87i1&`+v~4Gv z{= ziaQLG)8|^o_CZb#;`bRZRaarDs?0vsN9d3vX1ilQlOrm|O(w z-)iyC7zEa|zblu+UeP|ejJp&a;2G);ny)N7S`;8i1BSL zC5CUm29m173+5zmDWx)Np>)pW05ZteeGpM^#lMU#ZI&EFsGi{>Z|Sddkhg@QxCRl{ z5WSpF>89;aVz`j$G0FE9K%JMpwhB8N zraD9=^T3_&af-WPvJj!!CMLlR(dCrwUESuB8#K0N_F0{1)m5XT)uBNId=Z-~hq<_K zEE0)y#EC4i=K5&NGzsgnL)mrtpl8|u%ntCvK^V?}^vf&f z$n3&Bn4P#fZY#zV35qekkM$1>Y4O??s|VvMvtt{FiD~Jp2N>;+sq!Ul39b+-Mw>2)*BwTS zl&2>(1wY^Vy;JAwLw^=blyrlm}xR&E*NsiRkuVC&gTeV-A z{9yYPpPDl6ih$D~mYGe?=qvd&LNL`PC*cQ8BSiNTerxT3OB=dSJzpTG4Yl-SV71S& zJ__ahvC;mbv^@NM+9YwOY4zdQc1#+$8qcN;y^98|9i(g1E7FL@aT9sv_!(kX`QIrX zcv1X_>xx{k_+5m)dBcifS?N6uH6Dq$v>WK6^5TZ>FT&b9*YXo~itewRnoPc@7|a)O z{%)aX=0Hw-V9_mMcfDUj;ff;X69fYCla7kqM~2^<<-UAyTF=U)M`m=|#ta}xm%1O} zyeaw-z+BfvlpDSO2s8>Dgb(!^R9=bX)`%9udLa1bNK-ct`wt)(rEO z3L1e{x}8s8a!(KhT5J^KlRHNiFPi}jpV=z;#H9(pc_z{dy*zHEqUijIb~4p4sYrT6 zdBs~UIy~no_m6Wk91<@CjEsx%BV%sAcqL+Io)kNHUHieS-FtXZDOg0CMWY6bwg&a?=% zvWAYxd84;hLXDD&P$Q?ArsC5U(Bp4#ME*GWi1k{+Z^QW!MK2-klM-=E&WlQz;%M%w z{c7adGcqkI9eMOcY=$G%kgM2;Y37r`LfV`XNd<{x)iVSCwH^@K_uuOa|7-n>!x!Lx zVeUcNQSs#wE3a$6_&4Hi7sroCttbVvGqoGfoY^$;Is4xmGbc#@UyWt^&T^+pKy>Uv z-z-@_Zi!bYlo{~s-LZUJtjqy6{h;^wP~2|w(g2|^P}pu$hBsBcStAK*9q&N+TNBo> zDLp`Ye8_6&#rG5RcFFW{c#MMca52`oW_mw!sp4^QEjQx!2d=)IkUH@T0~&!V8a%yi z`3h=J7Mpr^l21*_uUbmB!9ti6-bQjexFhX#<)kkM3V5J8T8B5%CQH2U>J&T!- z!(S^f?tUom+u^Mn5lLd){*V>4LNR{cIN7`Ntgg-C12$uczmEDr!SC(TB|E6)x$_KC zrT7u;OzsBYad?sf?9u@I@u8rdmqQn&H!x9wk%L;W&g?bB%hI{*==lnWiv#jnyJFG| z#1`XCG={P5G&!^G!`pN-iiJ+uTRbK0jKHj=?}o=Oz7X08O?qo}@r=oC#3UKf^#X&a zG+*C6di%=hO5Vw%Xzs6$tI3x>bAAP{WPLpTRBUqgFC~Fyb?2R%T9e$N8-1ZK>oj-L zW!Oa#?k38wq>BMx^@T2_R#;Z+6UJsfSv_=~3Rkao+~HU~ibiHs>s-pWz2dYLLdeD1 zcXYHI=J8I8^UBCHakE@8P-$dHT&pSE@096`M%1` z{&pLyRQ8!S!7Gy-tjbp;3!fXTzx)a~{IhN1$I-WNWN<}vQ1kK2lemQ3wogZn9-ph^p>f&6trF(bgFRyH56#b@(O!sg} z_5)|^-$eLzxCqhYIi>s3diAou<=?2grngJpJT&B4d99az5mU?FK*64pu2MO5UNfue z=anMGH!nHhnXmc)g)W-eCyxw~5`+x(s?{X^x9I|Bn?Q{|)|Zr8Hk7V@aTJmzJWk~~ z-NYqGU)aBM=i}Vs*DC`O(~8|QGEGVG0n1m{Ol(KA;?-Kh4V9`Sfg#`QjBw)nZ(F~o zJyd}zmcDQxfNz~_sVZf|g5IP_DL&l^ztvZGsT>pA=;gMPqvO`$-v-Lgjv8Xfj^|_~ zTL3v_@{KnuO$gePy&%+Io;!(Rzf=i*O&3I;WIfR|v4p1gu-%8o0oca~2SEyk?|jYg zx=uJ02fQ_Iy>-7!=6cI^nNVo7+KqisjAq*%1)N1_Qrz}J-`Owu#M(c92VQ)azzk1F zSm})}zwR1h_PINTuf=z-X@t6p*Me$b5j$GSRf zNcKNk3p;xR$9K)wAas=6Y%1Tlm3D;tn~l^f5g*^Aziix_oQPbrU%fdRnPb}lO+ff& z7>+#%_wq99MJfV!so%nx+eJHyJAB4v)>L*0t7UicBuigCyd?D2t(BQsTtnw2j zG{f{+{%F6AlXFwlM$SZ)jwrDA>7{PBH|sY083S<07W?Y@t4k;rGu^uLT+`gj6^?Rs z?+b$JA0|k@asjkAOO+JY7B&xj*ZQ;jyaX$Un)mI1$y{fBFq#R;)-u(il=Y;wa;Mld z~v3inaa#52fDOs9L2kRwRLh{kSSX!H8B2s`OL!V!b)H% zrnGtP?&sS$3|=C>2!tv272yQA2?$3O=v zL$lsTws#TUa$Eh(CDrQPyX@)ht2)>2&zf5oH-^|*ln`4o@^V84$ zlrx!=m)~3$+b>_V-|sI|pP6k~TZ{n<*-p#uqE(4|r01NXZ-_L8o>nFS}x$#QE;yxQjH8bfv; zS5CLRn?*O)C|Fc0OiZf${Uep87QX%_|HH|BlV!G%r7=n3UDS7n6PWicTHjuzYy@!N zTji@O7w?$;Y!2w=`UxFd_P-?Rj5VkVa^Gn&)*(48iROO4^0}=rLV3^EYbSwC>Pq|k zmFe#n=cV@A-@@#pKZEXGU3)OCT%XeKW&bkL&Cx;1wu~r)nz@=g9u_34Gj`Q|=WD`3 zyl=T}Sa73o`t6?qbx2>^vjekpA0+XE(mzb~z9-l~4^(QAw9!jieWOIpmeq^yP`AVQ z?W4yEw{J`63@&L&iyM|jO1Zx#jO{;45?bR;Bt}~anTGmWUiw`=GxUpCRgRXOO`k|K za^@Rrl*c1J9@>`Pe^B+?=GvBG1l#4c1DCQRgYO#e^{Ojw`@WbNxb!`(>0_{boj_h- zmdeNahFguG$?LaT!0)CDF8G~NDFy8|y&XR_dwE&xzEjotL&2wZHoZ%fZF}BeyuHo% zz%KV>#GTh3JNNCJB-W&CuSYXv6Ko!stqR+Zsh>Vf%S5h}ciUWM-T5j^`)6F@)eDD9 z)=g%Q|Cm1|z9KyiEO?Lk<@0=h?9qeQMBzT0?MAvV%)`6=lk5)O~XLiWMSG>*p zEm{TiGJ9imaUJ#LshP*a>U|DYLB*N=sY363U*nR{Q;(Ze%$z75-vQ3=}fd9PCTB{ldXb8n%R>hoV_{QNur z+#-71vXln8T*^tYe_L+CbK2Ox(6>CaVZc8mzP6#xap|KNz@rpdQ@FtIE%5n#e9yUn zK+cq1h>_LQ=ajmlKzQ%mrD);auC7}avvxj><6@Wpek!mkfn%Gy&kjC~%s611c`69! ziSSi3Px0fuof`RqxroL()&AiXTb~DB{FMQ;6Us`13bOU*#GW{B;KRgH$>ZC8bqiAq z9&Uar56_$R-{-XLZupq|E-(=3_xAG-lfojQvOSL03P)9Wl~m>Z5^WTZ)mQB2jMq1V zrWDL4{2k-$P-1t7&J4b`3i;x-Q2fa*>Gczd{wHq15x4!I&v?f#edQgO`OI7K%Mn&# zI$nOI+vBs`(wjcTfbXM^4b3v}MF6z+az^ThaaR19gWBd=jmO?2&+_hqnu)dN{rFnr zeFdc>44=RGX)oAL82dR9$hM-F)e~D(`|8`;?v*mfNtchtq7QA3xLtAv%8%?)@?KY% zEU0C&fv)5%eZQb(LyjJE{sg_52{-1$xNj_|*hHd?J%0 z{AJfAq(?o}ZZFhXsaERK(W|CWm;Px9HTfIUr{dL;U%xk3zEdw}-JmQ=x%~?r^yJ&O z(j4zrtBEEt6;qq?Rnv*jrKXjm)VIv9P(ONb+VbY7ki{Etp|?>1ef>YQqopgQ#}r46 zrxd>bFRIQlIFsmEotmj%ozthQ z=F`+UJ>C5*Ub0G5O6wQMg!~vpm7%OD#gSPsN8{gj`e0awCB)$bdO4?A}4($drV6y+nd&v=?97U^qTHZ5O5agC&ZEIiQKg_SU;-_f+=FX&|+DA zH&COMoFAAlRz-nFo|o0}seF79e-#dGGcNddmikD+Sf^OVF4I_{=O7+hnoLSfXTj=3 zW1%i(hh^S0L7=;6S)ii3x^n6+KvZvS)7E9JOGUq~TE^M76RQ$}gHtHYE~yr7$L5}` zq}&k~Q0CrmT;#6XJ=!hPPIZVQ$nkohdOC~WFj8WX{B6|?9hIuLf6s{e-V&BOIW~GW-lS*XbCW~bjNZf{jn&FDeG}9wL zR+yQ3bDeEKA%_Mz=XK1P)Q&}06;4x5w ztoubd3BI#9RP%nvlXYX6-D{GqI^*hF7d~l`nU?u7F^)7L{Re6xWjTr23jFRB4hTbJ zWtR+$66#8FQ=X@bW%m(n=*&1Tff{^0^;^A6w89o;r6F@_3F4@5K53=3dCbg>RZE!^ z4ObH^^CTZ>7Mx^Tr9!H)WL8akEbI9$v8HJ{N$E0TfJv6}MM<{HnT?So64&`q$?yg;=S= zJY4Eu*7MRU8)}qoijtC)N?sq4@J(@u7(YaVlCsL=sLP$RSksm<3jNj&ph8%{M&=Ys z7uRG;)tvMO47F+DRTs6=i^_E?Wm4b(f0UN3Y)Vx!2cwsD0G^d5I$)}ct1|O0W~?ey z?AfGuIm;|b+8Je3(}t;4nO*3awpz+QPFy@70Q_ZZFEyhg&{bIv6wBvvP?N=U3f#i$ ze@~^T^NZNZ*rB1A=VQ|BVwwqxX2PMeYomquA*y4N)uS~QBQ?8+&MfEnNjp}|IcfP; zqQcsj(=Qt3U#fWJ%)ajfuM_yl9zsKQ0qNimF*Fhk&y?XM#-E7;%1nN+bH$j82`@M> zN|C<7JCcyygy!)LPhOhww;x{Frq1_SC0LuF#};DE)r}URHjG_ZV<_;~Mt36fP#YHc zySR)b=^JBvrAG+s^D6hpGZtmF^g?B;A>{H+?hM%^8S>_>0jIxJjPzM-f&&J5Vzg7` zC-en_^qDIS9=`Cur6OG}fRjMpbmHDMsXtLj?Gc8f&Z&RDv>_%hw(YML1GC#x$ zjaH}Jd{;{pc9}}++iR>bT&+sA!Lc$w>D%<}b*d#Q{cZa8T5Akns#2Xe(i*h>Z&ZBa zOl$Ds8(059roR;$`Ht2gutm*5s7f_6_IvpKLX}nzm~Cn?dH;)cwHTn)Lu#v9Oxk~= z^c&wx{tv#Fw0=*1BgE=KqvikM+b`*R@_+E{SM)vlAACDBT0Iy$Rc2dPEhbDhde*h6 z$*V1&jb3T-uIiSPw_82P^fY>s?P&3$I8y(=XRxK7dR&E0SX{SyaxY5)l zEtYE0ip4W(1#F)!3c1uhl1jwqdom`(@8V>T2!6FOX_`D3=F4J;u*Mhm^Y##PHH1h? z@$4pWn`IpF&f&JP;({q|V)K-A!9TE*7j{L>ft+TG4B!)TQ(eVC6aXb6f8D_`yJQv| zK~kfz*$bmUhpryOhDt)!-m7VN%<_K}#B}hFriRz1ByxN2a`;4X*xs}?M2Vf}f?7rC zwH1rr=^a^biM&4O0!ZEr_;TTojqjK2{+>sR3mGf8#&${wd)KCf9in1O22>exOKK9j zIqM4fqQz8|yyenKMH9Sy6m#ee?jhMok*(yKP*#NshGupdJf%2Avd3LWb0a2%MOAz%yguA=^7?*WYX_*eBWEw^OLw&PEiYIQdd z3sK4=x64D(_FoW3Sit4^o62vq`wrH&4D?4EN;g zekFGfh5iEdMJ&q!Q~IT)dP8Rf#^tb>sVqBrAQ^YTKN)#YvksY6${ZIn)`Zv8H^xvP z?{W%hh8Q%=WpDg9M?^vH4^ChnxDSacZ`e$C3+{BXCNt+qaz+<-6rms#KKEwb@-s`a zvBKX>zAPcd=3wHjvFJJQiByy{e?nezO0y)IraMON0HIS0oBR-fpN~_JL0mdk#3_k# zMi_cA2Yx>bn4go6PI#%?*~2boXuza2n6U&OsTwS7LSBVU!b$*`bR{5 z!$G0R0f-S1$d9A)=^@R^gyeQiEGO^izXTtjFO?7+k}o{{Q7`Ysfa8ykP)0zKEKc`M zZDmUOwBtd^>)=2jsGT3BF3xG!pj{1D_RrWfPgFm#c<9#>Yw8D4VAA&Sby7q5E2HrF zDKzP6h&uwTl)#t7oIMgRBe2-kEM;PSM1(=4q}!N)MS{1>n1Zl+AQ-Y-`j7eK?LHWQgG!N8EFQ>Bz1 zA(s&7>jFqf1~?drwR9uD*hrw4n8OQ^*D24X$E2+!oHkk8X3FX9u#8i7pBiTVd18w~ zIb3FpN?_XJWo0X2}IebT0J$dZ_^ntHPxc3|JHO`L`HR*uF3!!Wt3Ep zFgCAZ13T)TD-E|3Or$CqI68nM7-5itcUqh&ZSY>_5!G?Mr2jO=Nsdld7ySCeV=A1R zC1I3WoQHfA=P!Fwb+@}yjpVQAb;(>h3h-5EFg~(D2bRD zMvo{TG_8rjiwM7)^rEi%G%-bnGt+*3{q_9*5}TEleRcMIm3=?idoShS5d=Tgo|RPv zHOOoH0J{fYkNw;Jia3xz=^wnj{&6YaT+ZH8*=bxTox&c+6A89lU9s#=^+-D*Ut;cG*j`Dv ze_jQxOZ-z_XILKwc86;-F%e>Ny}6l zWR+oWeZ$h(Ye%U#Qo0hvrX%*jdQ#34$Fk`9U0j!B)K!(4I<(Kqx80YxADgv)b(e|k zvZ3I9LEA~htW!=VR;-8N^l!RbuVl4Vpdg~A7n|T9!c7{ufl0@$Fg0||Om0L(W?t}H zQgK-Hip6vKEay%FOqh)(uY|g;JfYQ5FZd=e>dK!RY})V}1bqs3Ac_Afg+CMXqmAkt z1G^!Mfo2V>bn62xkm<=8J^VitM;P<S?jUzd!3Da1=AxOT z5m2a;I8r^)Fe}jB#smz){4FNn;nH*iF%PWdKvn>GH4N_hk%zBWRbsR#N0P1nq6-f2 zY1+^j;DQa;i5A_GDx}Vm-tB@PgBFsSV0mw7dK#(@zKNK?Tnrq*3m35`BAbIuB$3dq zu5+0KTHO*0{K)!iL8r1Kc9jsUz`;~tK^&;}=Z3_@pqOBRJ><7W3Y6(dMKO=hI z=m|_o%wS^~s=2@4v>RKtnpS?7WsLX^29 zR#n)jPKLVa(Bf0`lVsi;aFQ>w0;nk@%1vb4A@;2JO{`vtFK{mc?f-F;3# zG)hP#5{i1LrE0~CWqkXVQEF(y!+yB4#NA#B*D=dwDr&D)e|q-cK~xyC?&)0)_cpnvUdv|sl%Y55cW?lCy)_p9yR$wzhl0LuWt)K3!-gG0?LLfmaO~pDJ8$D-Yh-Xz1y8@ z7_BajMBnRp-ym3CF3#K}+&(ARA%aq2O88z86-nm&C-(K3k zS;%8xi9&M2Gn-ylMw3*@G$!aOd$ayby7a8OrffV)6`vu!Q&}X@NwTBFc@~v#+NDm zY!67_$?QIej95)_rG`H~9YV5rTgR7u{rj8*B|f-ptx|E5iY)rI3Q^G7m&lWD(~L8= zC1KKSV3LA0&NmxEJm#>A4{xDakT6uI@x)pWLH`ho*6KfYZy*Cv9E0R+0=%RzdPE3m zGsQZ`hO#$$LPXZ7R=k^(Q)|nNcyyFSeI^_Z%5;{Q#HRjOG*_#LR}WVwWC0%(E?N}O zK)M@*0;S8zwCXt|G?RC)=Ag{E;JBs~?$Tz|!#UTI)mCv3WWHi2F~{~ahb^Y}$Cq~D zggrn_0?Z=%)J-&r$0`vfTJk--4aCL z+;2<-fClpSMa=~Rkp_bqI%8LAf7OP0-J+G#&m|!_3hX5x3{>1;<_?d?rgo>rW3ZS` z<>TNgy_5d6U`3Cxrn=;mQd-S{{#g1bA^9jyW6>*M5#0*jvYxR)HBAz*T1HKeG&1VL zm2va(0=`j-#~PvReLgLAI=jMn%~#8^=@%c|dxKFPW~59;=c>dISO#;Oq0ZEQGt@&a8Fj(GrWE(pT{7v_$~zE2o40dnj$!}?4Xrl$IwIvf*}cfF zOrMk|qx>DJ&^SpKaXd;$A8{mcWGMAfw}Z7(`>;-XgByOOmU|(rw}zrh(A-@Tq9-cv znZl1P&uyI^c5;^h0l7nHfU=V~8>VyFOt-Ey6T92WuwXdhDAO;z7bn|-EOP0kqfS?l z5}3f`S<{J@T*W#|&3R7~+3Psg%1NoNId}fmGa;qkYv&Z7Q%uhWDC+dWa6vi}QM!Os z(k^Q>?02xsTbt5UF3~p=FDJP4Y8W`+24s77rj1OpjAt7!<>thE0y1rdU^NKqFY@l% zGrRbB8!bnz=^qxa8HES`x+qX8YT7Ve3d1iY6K`Q3AR~^?HnZs^WU&rjQ>3!p( z%68qvR^v8#X5nM@<+ zfw(eFv|LLpKT@GRo|jfhFATyy zG6-qNaEy%prrKt2B0a-Hp5oZs$o@O-(AJvfT&0!4-1l z(ZBcNm9R`oY2$p(MEhIui#Q>7xZ@ik5triizn!AIOmz5zytb)p{-t*`Zh(3SK%Ray zccdKwV|Cj2xg*7;PI7=-qQl?hCY3@W;8GkJ>bcmN1PX(6tcSW3PrR3hM@=BNwp1aE z=j2s^;G6S6wTj0Vdc)wj4k;g}(BLf3Ewi8^k=Lez(-m@|Z&h)yi8>Di&Kl&BBUR`VCqb~L;&$%dolGu2!~n16fgIZ9uZ zl)XNFTypOf-czc5h?u=dC%{zrxsN+KqPn6Yc~pE3UWjm?F{3Ivi&%|VoQesEKktSv zw4tD_CZOBbtrh)rG6)sg0@9!g1ncq%#y+XT=b30Z_Ab044>Tjh<_x{Q{4qt z)yogN+A*AprQpy$s32b9Y?EW9@-@KtoC_E9?R_Mq{x*L27QlJKkJGj`yr(cd$=ARh z5_hL}PI3sgg$BZLZ=K@Opg^z~>_8aQIK${kVwS*$kO+Y?@2-eU`^`rY%qHK6g5##L zH91AuJIaHXVDIEE29Olx(*YKMqPi7a=I8Nn|qw99wa zau{^a`!ctA=1E{z9j@L+7FSL!zPwH9>#d*tIe%?ljGZM?Td?%mQ^C`q6MDEM4);N> zBeBa}}_=B1<6-JV)$B zp7Ni+{HjG|iR#W;Y$AaT@Q;5EtTMC8UF0PT?BZSZ#%N{jGThq4epL7V{AW320Ac^g zRT%GVPG7~<#ENt%YS+$Wl*dM1v?U4|i|qs0tYVOZL&B&7cSIz@@2y*=Zq!_-yl>yw zPOua(r>z(WFH;$YEx;02M*@$UFDqoLR=>AB{dvFyZeF22x}|flQ{+a3Y%N46THFkq zcMcC-*O=vjgChA`($qD}&u%{>gr~ras7pY46qeN9$IPW#;Gq#L=RDVK z)ByP8onHO>OjV^^f@}Mhp&x#j;cT?$gN7zg861I zwieT9yn6(6z>nMNnb#HuH>Gd`LZW z@8TQ%vgf8iCOZnhBVTxcTts$Ol&(>_TER}$5k!Ju42@to&2%`XDt)0(a9+gxFy~e~ z$Clhq54OD>+xLZ#HRA;80&qh%5FU6q=^aPXgGxHFkZ0Lht;L2pGlNEbWmt)~k}ds0 z_C}=IH&vxO?T_$05sue7{wHxTN69Y8vPG7wAzv}4bn}?Oc&`A931Un*2bsxC(OsqXVsbYkse8oq8q8wj zO!4Y1-22@kmYdghzD5E$)#r))7hfiW@!h&5x3KY`c@)(uT%6TF%DE2f4_S6e3w0F2 z*^zljsiLksfLsA~O_LL)S9rju^V4ifX>4-*F**6(G2SadBTsyT2D>D*M#2jk&P$VW z0;flg0&z9u)aoJ06z2{L1NDfPwB68~6n)oqj><;q`e9L~)AJ0(l;kgvOGzma3S~8EGORC50nU zA?!%V2*~||TP__H*wQ`M1=R)tzd(kVgyxbSQ|oET`xFxTUzs(hqm^`}Qo9HIoWAA3 zIU(C+F8uU&s;Y9;gC3!iCSV&b(I-l`gwJXx5BXv+!)@Kq*D_V@Jz%(deCjj!0KmRX>4JFzLcJY>Iv1eupDH51wkR7T~R+3 zP@dLZ!j#tgpejoR-D@~zXdFk%c+(;)TDJRrX-(!OCFU^-k_sctD!3LPN%VAB8gf*Z zTS=Mi2s)hcO8U^x=iFSBXTklqn3p%z%uwg3A8cbozp{GP#tY+fiWmbefw(+>k1IV; z7lM4eA5=R7$CN9kE9ucH0-4@ZB(?YsX5f}|OqKzrp6zKky;%o(j+O~gs6*OP9&`?G z3iM?bfacoQ-Zlhcb;_9uT{XXenUY3#L$4^R$s)jxsRK}{c)bzG;+38|_`4Mg(#&r( z+2=2RJhPs`xzXYIcE4G9BRk(>Q}%P@SDU$YYG2F)3}8Xj5C>~)4|D4Cs(suI&~ z*iu=QxyK*WcNL#^1n9e<7cnQL!?hBLXcoqzS4(=XJ>$=Y5^c)zRFD)7k$-i5N`@Bk z4tvGYfesbH?MvS_YWi&gW61{rf6O_Gr%WS&|;OLQq({9`- z-)X-CNzZR!?;p6ITcP~JFZ^G2_=(ckF`eACs9e=jKUWoBRbY2(XX?Hjaudz&R&LFp z`kQq;e5n;~q-E0+#0HGZ)1tKLbCzadGAW&@026ujw}#NF19%7d^W`BJ^o3f!xFv1b_=m6hix*W{-mz?ftrLNF%1iByq)~#RnrrN*!kX*sHj+jkH%G5V7U=Vw zc>txTm!I5AeAgHbaRi#<%3Ahol}d9R3mP)Yo{0np)+qcbI8PP`OKCR zy@nlIdGz?Jfwv2VxXVOPyO{RV2U*@^)2VM$5Rw~nReR2*SK^v=%&l>(pIN>iI-q=~KKJQ>kb5S3SHFF=Elo z^9UT!Hgx3I`3Giio9f+lox*$vQLNs@*kKPKUuUa4+FI zik~jmkv+C{Z;GJbsrzL+`02aN`nYR1^-wS`Jjc$^mXs_@8DMTbVC}u0w3r$7US+w> zwJ{fRt!l8=>MF@R*@OV5@XPRrMUOz2ABe1- z9?lCRY~GLUwz$~%ZWLN0$=a_UN`OHsj9h~lw%x`S_hCoEbt&s$j^rYw?I~5YayX05&@!X7?|h3ht6me zaa${^VvIC z*0npeU4NYBaLFgj-@5dYENwM7+VOAf9#*H_S783Tijm|C`zOmV2;did=#4EO@VQh( z%uV`TGZqZN+1YZpGX!9OmY7kHreM|y`gOjRn1wGK&)wlBgBli>zqHPFCvAXZjs;B7G1L_Thulj==zXgSeTBL+4`5VG0A7aUb5jVPC61qx1gSD zt5?>ysbe`XI;1zJJLs6O(a#P@SC}|HzI!PGJY*X%Ha+NFW${Sl^A2Xo&Vt(^F}0q* z_aG)MbKrl?oUTkKv3@Y@DF)xlpJ*ie#YaUBFXx-znADG!sk^-ElT~$#xyUr8)+`KI=xBvTdey3xer^8IKOiH5;WK{o(iqwUrAnrF5W;4i2l5+tV_EjOD z^O2xxW2_R&+4=@oL`Uqp)j{>x^|)W8u|juM{CJ{U`fR!#))+lC{Bmozbq3rWCp{Rs& z24PL>9%>1BvWGV*@P4LifGG}Ep^-)A1H2PEfh%l*Ux$WlPP1)Dh;5<( z5IGii`DRdyR`S8%8NCroqu2OIwzBLFX!(Kt95y3^2_t_W=(~kelhEd-DdF1@w3ueu!ca! zCL9AaG2`c00-RLPuS196A0P6ovcno*+m#Wt$)DiE^RDw5Tm6UZ49lMl zb4c4Ag^;)k7FtuoorP?;iAEOchRiy2rM@VXtQv`)t^xW3HyeT@&m#Yr_ti_7oH{2wU#-V zjI!JOcQ>a#onCO;s*TjpeJfPOSqHcDJTE<+k}`cLgDuh$qc7p>Y%{X;S5u>|$!a8= z9ZJiQsx9#Lxn9c+fkCgsW#6Sxx+y>RK?(?vkV!>cKfd6w?g2hF#(h-S@5hPijK(z6 zHLbtOX8l5lVXqZmwWNVZHk7A<)k;a|86k-5z9i}y$etaoKG-PKIwLHFYW?-#ci`h=f- za@=RN6SqP>u`0KM@!R zd<6I2L9o#^1*zk2nZ$<1E8hh$E57Qx_eBg?qZor=a)*u4dg9|%K*$~xKxrr?A!-V9 z@_%eKGoblLe1$W`;dpFFkve1efvv$-B!#F*KKNIBltP)eMr$Se-(br{<=DOVkoZ?nfLhRuf z7MkB|&LRIENGvyGosMdEn5pHK_8!!#&#k@cuA$^7)Mi)H8^-|Y?6e%bk8Yr>1!{UB z)Bb}Ur3*zi>GvoENVi1fX(cqHhUL+JFe^N7kT5{US>_`hHx#T@GM7mCDW!6-M$!Vqzq(gU-tl_`m1rCPj&~VA7YZSit zGX()fMKkKHoH&)^HCRX^M8Dzec+JtwxzW)tDdHFsbnT2ZdUM9pV}azC17DRkwRBam2JJC(Up zT)0yOs0#zfyZ6?4S>;SE8?tU2dWd3(Clf~0W`FZ`xg-RWU`*M{_k|QNI_5ewWpNi; zKEV(yr6ZUbP&3LGBvvL3UN|pd43X54WO}i@I(kf#TMq!ddkFm;h6K=XQ;+0(5~g>ALr1ua+p=1+mF%s|*uvbm``Bwb=K7^*Li&i6wK z$}ZwM@XKS*#kIyn$%5R~P&7S>mR@EKCHS%AVc#%_>)B_B&>tZpbV+ux(REbc_;w+~ z8b!OTI`2CKH|=UV%<&?6$tC(Mot3_d+(BL9=H&U?wLwK?!? z93>_c)c-FHkHnb@2WIsVUrtDpco!RBh(=7Py%{}MTX@ziBFckBIsfNrA_a4?CV)fC zG+XjtEzZ!-%He-o0|C;fUNOX$7)+kt-kH#&$cG!AKS=W2Dtyw;GBbl zs)9Q(z(!7a1?8W1!4((+ZP&zev)&n-Vg#n=1YyCsvcrBM*g~Kq$)Yo*C!TN)f2G;T zIX#6to?gEGg*R@WrG;(DL%_a*R}NK9)In73NiZgts}S19{G^%i0pkGe*XM9 zrD03dzYKFSwLDvylZn0A^)CIVfj+?5glP@~aZaAO(9fXaeeAf=gxhA2`1+!7khdCd z53_~s~RGo6#WCvrt<`cO_g&{7jck6%ZlDWwc< z!Cd0zD8pPMePE_6zS`wwx91GXh|IFZn2~m0Vb`9sa%^5O;W2yP8wsait(185&>L0P2hqCqRr$LrsM z7yJe**L;2YUP(=6DlWp17&`iEc(3U*y)HAdp2gSvvS?(Zc#1AL*rdjA%9 z#{LvK_1{6L(UY&QRj;g$Dwrk9HL3H@4$79%T6SJS@!Uk?gN#}%Ibdohh(!cMKN~Dz zb2-}g%txC3P!^ldk}nK8L_TE#y8Jy^OMR2kKN3XaPl+XScEurJ6UqCLZt7CAA`WdILc_&9Z1^qwfxYHq7!VB@`2&y; zrytnk?hLtby=C}Ik{F!fS1$6W5vML>7%aiPGeZ1fV)JJ!BYr|GV1UFs1@(|SBJ1yH zr}?>9+LK*pO4KyHxvL1?^72W3Xx0hTIg|5Hbc|}!6cVuW&m>30F>12re!_l9kTcb} z;g3hb{j>!24v8PhIRbYXE0MM^L65cWgqT0(M_LUQ)XVr~kmXS^ z#T%xPwesVztOQQ?%IyXI{q?(@R~dNs5++u@nAsm}H5W9aUhF76D|hQbSd_3Nl#^3^VGm&aJ@#^SXD@nq3Qr}AHzRB)Jm1A{UoLejC{pG@q zp6a61m~U&KUME*~vb}Gm)Xn+M^dG%(tnTFVcTd%lJZ3S!!rODxT%QjAV-a6oWSC%`ecHf@KlZW6T;}m;rOXdR3Trp2eKy z;LjJbK>xVyxbx@;@zu$44rej|g72SpmXt5=pi=ulE zQ$ikGjepJjL=jU4G;Ko~cZ=jINtaA$E+FPegEqBVg8ccYNF|f+5EqfabAKK7_tZcg z>CcIgqTcXn@FmSrO{h*P_vxfROMPR%=7^V`OK)X*(jCEuR}8CN?rD(=yFC@W_TOkG zP=;=UfDRkWzJh7^;E)X(Utn|j@w0~W2y2=9eoKGL^t@XqR8Q?FoLUo%ku9bj7jH}C z^HADkj4634QmnsXX+m-u^#o0|k)7b(KjLo;p~$&~xc(VfaWtQ5gJ5r+kD7r*GOlh0 z4jIRa{1y{WDAcF7oQBGYMa=k>#igs^OEu;8;Momj8;#L-`A_8dJFlG={wV;@ICGpo z&3^fQ;eN%=y-6ax5_a|ap?DtHeijfU5#Np}na%MxFZt7}W}9W1o`v`W#gG8{!f%Oy zJ$3a81hQVHz-6O7M-Keh0{x>A{LL2fjSTnkKIXhc=)gBWBSih|`l%yl;m^V+A_)I? z%GO9vj^E6V=ue(#wc6QnW@8~cdIUG1!B2Fzq)Z`LBh6#Az5M$IUh~08%;3*f1v-+L zBI9Aavg`6|_y?O$u*s9=`-d`DLPpG6ydks~k5n+q`D@G zEs^iun$t>M;(T-cTQkelPU>=p;DT;8dF3fxP@=;Q9-MsZ5V~Mp19pV?o8b>FRoBPa zEJt_3AYU7~|;^8xU#^ylB zuS>S3@{z^UDB&J^%MhSK?uq`mJ+KX|VmLWbss28!d+MX{-Skj7y*qbTfZD6zGt4yX z$seHfyA~_}d3&j#l}L{-O*u8W!M+c-l@J#aA$(5HYL%T@2eZC%U~P`kZg>L88-p5- z6}5LM_>vq=i9>PT+;f({Ld@0}1!l5p7)I!?O-=p^dzaK-kskHUx3TQmd`K_^AL-^k zSi3{+)VuQU-E;OI+r7c7M)?K1#?NgN%~kJ(t2A+b`zyQHh8aEH_KH!yOBRFDr}S zHDI?SW@W(xGjaCG@!$c3qYDd1Dl zdo0GI%UeIfqLe3_x{@U)QLB-MXX%Jeu}!&zD4=0ay5gPgn5;L^O%@lx!jjm~qNBzQ z1V(L)JzI;+D;Sc}Dp51b&G#jV*Pc;4sS^cwrtX&@z zJO(&8GdQP3tdAAkUBa1UD}S7&yNqZ8(MueAgH~|XmiZVCCvBCo3({g}d^lnb_GR;g zx=#=)8JI;nf6p$5A>|hxb#)!beYZ&@-A&Q?c&T`WyG`O+X3^Pzyl^I^ALl>4lh z+-s)bu9%(FEh6+Bd`Dbn?K4+#h7X<_-Y2C@(1AebyPIJs!7(jbh}i->*5K#|0N2b1 zJ%<%-Kp={F76{0upg)E8*PPFfr|#cA!2{@(t$Vk0vDdnfQRTpsc*+JJr$(R+t-cw^ zS|jnSF^}@HDLs2H90I}7DPoS#f!SpW%|qol8uB7aX(jN=0LyFU9))YPR z-6Wf(?}W>uv|a6EHY=;Iq_O6Ll{LSj>d8Ge=C}HI)qf&n353Y}znv)W-DmkWgmQR! zVk;%pO)Zgkso=sZXp+HP8BD7qf@n6xaC20#hM#MpW~7*xe5}UWp#K6Xen;1lYZuQ9 zTNwJhVyvx3f5^Xcp;RAoKeA%^uXiVTS!9M*L#g>Z;W&P$g@2sk45h9!Dqr{x=w!5! z!07eC6r>a;!T3$WTr;5ig2Kq#gb&JE|D>e&JJ{v`Y_uG-9Qokj=kwQ*<<$cik|&%% zP_Md9V{SrCpIm`;fZ+hQ48aFinWz;<0JOLmY1DAMx~cY1D|I) z#Srx8(ut)#;;e-7m=6eiN?> z2HO>ao+`gdZSkR4%+<}YfU`TgA?uc@rw^(kLB0O63O`L4d*hmxf>qMi3ZeZ9$2ydO zRExZ_fqb{z4!Q?bH$@g^ z+5>WCYLm6$dHz1@By5qO#8ep)pH)^PJ~mb~cYTCEpd*Wwwqca29mOle?l@&oE=X0WVTsx>(mmPJS(~r6>Nwy5X00ci1!pB_lktI)g%? z7e`ojyzK8a6TVq*S#CY?yF9^`jUB-2IyWly06X=}3wP4!aA944M@xBRif2YjJX}>> zVQwJmHnWs9?{zIcH~FFOh2ODv@rNn=-1I8KmdTaw*K}_;6T~O^`t{e2U(L4P^4FU0 z*KeQhuhFM-?yt*_*VeCHUmv&dJN{!YZyZSIbSiK2zdciKQs%4XOF=n#+k^$OC-+`s zdW|r=T_x5udcud>mY2GG;ttRoI|lxERwm+LPjzq5o)M^xnn$U@sRCQ16`&bu3w>h{ zdyap>eFNBTU=6{1$L)<~TzgC=K@xJ|p!8t}v?7X|U+1ZKx8 zZ1nTWanD)~Pc;6lS?(ai?t?q(q!w+2Qlcd~5=(3Tp-fR2W2HINl1Y=KOsP*)lHm+e z3fCMHO=ZedGOb7DFaB4MD3t6-SN!{ID3Ow8Fp5%7X^bP82~T;eC~=qOkVVF#I5B|c z5LM=dx~Q<9_AdL~A@>&MxF|*UD&x3)!7c6DG1n^TqW<;J*Y^dxU9XD-r9=(6b`q2` z_Az%@&)2Ns3_3a&tVZ~HZ*0tL zgKQJ84^VPsJ4lb4JF0{AC1dgOSyNAiF{Xy0pKF9@vE1-mc)@(c1LiOiVBJ@t8;jh9 zq*)^1BC`@qN>Qrf;=R>J6a*p$+AD$Dcp|#lG1*ITZ>7|pBG}G~(R8*lAE@wAHK)O6 zuz=n&d=}4RL+EC#8I3qrvfrDJ(WW{qObaJmvY=s-a!~O=+5&|d8h%+#`kbaCxmCM(S=dJ0M+r7jD{^f37xv&@VZ_S6{rc9*+8Le^Bo+RPTxjH8b+*!}STb;cEC!?z19GZWcG+jkg^}g= zTPuG~J&bdbrvE|aW+Pf)Qn$#xm9iGTFod+`V9?;azp5;eAhX24n-87QCP{;G7GqO= zse05sY@btieNa`O(+o19kQA!2Hg+z#7$3b(JlLcgcXo0=BGmiU<|%A89^&C-HxudOxb(Y40?SlXGf>TR&@JG+Jc^qE$6s z*qr{K_`)ozJs|4GR0KY>n~;st$B})TBYIlKShXrTJi3MYKJg$t8YdV!H;G4tBi#a= z>ekN`;r38=2lD89m<4%4>we_K(B)Rge+K7|<51yu-6PkL0Ar=-XtZF}7peotSE6;5 z>BwqZMri9>I*nU;0+aJavfaKBXVIS@uR(qJPx4@Lnsd1`64$<&0V(0 zUMRj9if1-;`U+}7W0diIqB|YYeMj{i3{OPFz8nn=-Bm1aO{^GiQ=S6lF7KD*53vu% zP-kpY{)QxJMg5M$k9Hz~5_)X1NoZkXLAI6LWD;IQn}og?B#@uh(;^020M!k6-f*Ms z49KD^IScW!4ZM=Zf7lf*0dcpbaYQ!0yqdlIp^UvuUpEYgR(1YnP*79o`zM1;Qe-22 z5KfB3O`(3s|ByTWCC!-~;~`T~RI&sxnBDQ{d=u!LCQhb+Y~6^Y3d(~_fyfax)E|Dk zL$>1jo#C`LGb+=7+JxW(k(ep`nm$bF+#uziXW_p;))XMp`9wP1lbs*X%X$&(d>VHF-IH8*E3IMl4FVe`Qjsd;mD>_s2K zmYc;_vZY9qc>#>+AEdlyX-Ai&wzn|*xEOSNapN4CQU#*3k?LTgD$0)jd=7MiJpW}g z%#-@UF9;()Z-;o-BfhO$_al~Sz5a(kdTW(!}!ZY&`f_0|lDUfKid=J5VNq$9l;#H2kSx3q|( zyaLog6+lJdgP6F0{nPM++g0#CPe`Nbax6bP2Kb-GpwB_QT(*fTg`>2TAH?t&gaKq)5zc=p^bONVDplq;*h9 zqJttaJJOU0XG(NXI_n_8P{mK|AAd#{ws=24#ts7W<`Vp>3Q$lU#H#Uu*)uTwK6TGx zwMToYfA*{D?W}*GFKUe4#QLY%&_6+5AJVrA>AN4(6imZT2q>7=foZ!iZ9CvaJ%rtN zNj9bvW~_s-n+Kk#e>Tu}P0BP=FlwvV3DWK(Fx!B9%11##=xi~C>?GevP`4%9;ju$j zI?NMF7Vbn*YKny~LOEcBIm!t0vWpBb|3RzBZGG7G%5!+yQ*^|qJ8-dQI8H`1y-In! zkS8vpf%^W%v}AfJ-v80c=5b#`X73d(vMqNu?s8-cY$NUmSiZWZ@DyKvv{vR#paTZK zorT9Js_?4}E2c%ois!L4Bi_TL%P(f@N3%?9$C+{p<#D9r{v=Ew4WiUt%+59C^P+`l zWQSZiNQLtJJ;m~lfDA+Xdk|4U&lXUZLLNzfu676pQ%K6-iA-JIgB;;$3E4m|hqlqF zXOOZUU9CR3Dd=g|Por*}=kkgdG~?Axpp&ww7g)V@3L}->&zcVx=ah@_cm|%SBO0OQ&tFnt0H}9~tTA;%2uvEi8QEJ$u89Fo62m>#-WJ^v_BR=6^(3HT)$bY`xih% zN#MZA&QL&7tjF-N{H7S~ti~)`>1L-`2lHT|`HcLvs*_`iVo*By}TT{KcU zv^%mlJ(Ly%!=N!+vb3Y*j&#ff>75oXWDn^i$_Jt-UL`dS)RgTH$YL1{1G#qXBzn`}~AUO?+wegbu66(@j@zsE`AMgeFD4`m}A65izcHs{d zLam2C`z6wJ+nLmyr_#I^xcwZGRY5Q^<*eKbOhW!n)lu~#O~HmJqfRG3j_MfvBKaTM z#sec*5_5xO{|Qc7B8NL}U-E{DF{C6G9R{#F&c~_P=CD(l1EO<1#@zb6!6B8@(r>275% zKeq&PNnA}z2)JJs@K-Fm4RXdawU^TiG%p8!$)x;hK7T7935I66Mb&x#r^@)##`PuR zr@9zL-bj-135wvl9ZGXh+C3;@pB<%-uNG(uLDvFY@aw{U0SNoKtf_;!uumq;V6E-m zbC~2GXP}PNs2WC{lTZyJs)hxPWjA-9P&ep&;?4&-0|aRU4dK}a8p8A8Z70$YPtU<~ z7eLT>+Ll@tGQWUr0x=snjeiZ2sV&pSGOef;ja>X$n1=Oyeo3V z6kZOq(#s|0I{}?AnBt~?$)1%J@FE^l4qc6Y)EECu9+J1_fMsyzRdoNsxp4pf2+Vy) zy7JUzkb8?V;!1q39;FPLPd9_1_RZr7Vt>{42o#AukBkrnyD^_%bCI5;ow?q0 zcC6+_7V9PgI63PU`cm|E)$!E}_-YGCgTeVbmD4VxbtX)U%(1JDmiS=Bc~n(nKcGT8 zVgZ6|R^-yeQWc1=gzQ49=V&^2Kh9eBQa)&qSm=1E(8R*W--aZhbI69cx`T4ouy)kP zn?vb7bqA_DjNA{(t@678d8=|wH#=zpalfB9oWFSCDfCI=tH@DP_$;91neZ-uC%#+t z6t3sULH$i~uu}i(ZtA5-QCSt~7hd^nl!j7RUkQFq<;G99z;Rzbnb_^bo7D=gE~y zW5&3Gw9Y*o%Oc1@4hS(hq$_K$@{{r+$pt;-Ti+nxmLOBy=pkN&o->8=Q zR)oX?uesB^z1v&UZ4RZuuPNNmC%<`U`!lA{Dqp8xv^zst`8(w;{^%^T^6Ltas#}zU z*Rn0(2Pi1PR(C%7vaS0ed%C?wtosNf5w^?|a6KtX;Q$RyB++d1A!p$)2O$yxIa3r@ zx2TSbo@2nCf>O|%{k(OZV%_h|$i{i_3Yr-V$RFeG=%V^>#k$+g7{d{AmHq?IBgf43 z5n2qI=PFszzbL=6=5U4-J!5|neJJgH!6&Y6^+lEpDG@?W-wOYbU_;P#B|AT%!S5>b zMXrNah-O(lAilm?*>(+S)@cFxO)0M>VA&+$mce_snV3lSv!asxu5#%$Bt^x#+wh&* z5Mg8)ds^g1i7)58HPw%KN@0ewY%Uih66%Oza;NHddDXV~^~gNL zLgw%g@f8bn#ezsz#)3v{B6NZjX)znJoQ+=-@+%D>SQmI8i&&4cA<||B%tAxuw->+& z@GCcHufx@98&)K@`0_USJa3A3nb1X7<_ZSU)&-;2iz|~D>07@?tosdIBS&pw{q-2% zQ!xS+Og|hT)g#D$-*rq?S6Ha1+IFEF{88{V_{HFbvLEi+{OKhW!VA#je^ec=r_pH` ze}JB!05-mVHZ1||r||&{{}u-9>T8wUH-Rtf(%!~cdfysbT~o+=27wo9YSFjT*eiu>hO+*ua2WdjO+ z7{^{}1NN4LVNIAv8(pen&!5N&20_Z(k9*N1$J6(O)zDEoe-m z$J)c)*vvOmH*>XUpLO{CDrhat1S5q+nA+{0HsZF>N;aiu*O|L4Dd0Jy8 zCp9K>fuH#prN~D5<1R0CKnvn;7^N??C%AF?W&N3S-soONar0c!3~DyAaGGa+9l$`#4C@ zk5c}g*nP*4Lox_t>@EbiMVUTK5Ms;lTe4AGmDivXyrKTSn(3}#V%=nTtGtKtfH=hy zlo&1)IE9!5>3PS|U|&hP5QEmP#Dl%$M_mnUM+hp<-fPy(WT*8{L!gGcNbbNmjEdcn zqut@tl)Ipse6_Ja`Q=be5}=kue$H1tpNcDS$Cqcs^D|9?7-5ST2SInD(hNptJO#;- zuSQ8Xc9zbOt%tiS|fU zVx<^}rpCXXD=0Vb&E3uMx)sglGGRrem$HFH_ZkzM>fL-BGmJUJDuUw{A5!s?b z!Sk-dm9O|%Wk%n1|6;ICSGM>L9B5dNtIUxat7tvW$b{Zv`3`%rJUSrXT2P$#b*Im| zpjbX2$=?L!824AHQlr!!Z1ip~JWsqkk4%iKGUeG_K~INx*VCwiW*@`*2p+>3xzj4J z6G9^%6R1cFO%Wye{eY!S-45cS0o^vs7W-ImoJxy$F_0_#YS6raGIa>rFP ziU-g(mVo@W>S%*xd5%>xT>#iN<^C)2<@sKDuC=(Lm>n7p&$$81hs9tPF^3sQswdZA zyz-S8z5v=i+jHLHU&qc%J@l!!+N^@CPxMNVGzFw;W(`QN z?{Jwnn%OQj_E+wu>0js!NWKTZ>jWr3lRdkZv~aTN_CJV6oT)l-`cTm(S(*Y7*CssS zZBI%+18BSvKc0dWoiUj{7LwFhjPi$*Bd6>3haF+&8x+oA@eXG{RVfyfe2Zy~GP z8ozTrMx84+4$@Yuz$(2*ad~bMPwht7?BZ;D& z@$5ij*>MWx+M=8XZ&zXbz$v(6cjaRgUXh|xSiB5h%c$5bMQ2pwS8*(Rq{#G7h44V- zN48JL9+d_v|8yW4nV%*WG=NqGkLk2p;>u?1gsU4*9RV5MuI#>)nIaf5rsRHt{ng|K zMxjX0QEvd~We3T z7jOxiuA+B%>sDYRH@Q&64cF#mO7cgGPs6qSFL$eIZAFgyovKDET)+rp;jbcFNM5@^ z3bgui$lqRn7dHKE{3;*fD6gWaU*oAT38a1KjdL&_ul6*Io7fQ=EZ1N>TD`4nm`MoR zmA9|QEEbp?e>xO$6wbDXhSP$017*wFf!X>ge<>sIc6`-I5X@mmgz}hMXXlvW_JiUr z=7ZvLQ?GR;Yrw|?icV5+ekkPnmB#JeIEL{sJi?~1q8ElNE|#K=rFWUb$`{Oi=CGPP{* zb$St122_$`q09h&o*hs&4UC@ySmduL7FbPC%}8{Hsc%9}FidaF#+8MM;eqV+i!&7! zIeX9YxBEbV^t&aHNEyf(8ed~wt%R`>FP%Z|Ij15*aLB`J|v})UZk&aOq zg;IQDQ)#iKZnN;MNr-0z<&Aib5M%**7c37?z|teJ^iT?1*@)39&0RJYv9h`uOLfjF zs0sO${wHY5s1vlsC%47UL=zr~awPPMcf}N+{5_uG?8P6yPu>}9WS^wFuXT;_GkD5?^0wU$YRbti58~;*;N! zDmIejAJh)7R%bN9tL7tCsH;qV%jelC*4+W< zm5Oy=(9`_TkVw}xVx5DYD#SXpgJO~uO_Cx|E^pcco{ga?l3WTmABD#I#0_8c7vB&T zpYjl%n1n(uZ{v=x*eOyPaWIa=4g2~BTD5 zMOl6w^}7$+FapmTA)$P#Z$(iT9#Vx*4g5sa=%aLv6D zy-z+UM$Z6Z`(97O>^BnKuNPN3&t7Y3FT{nnz2Z;DLi*Eg&fTF`2N#;B2IlNFSU+dEr}+X+?Ek+)-}5q}A^Vx_!}0 zzHjimisN&A>+SrV9}D%1&j`p%sr!{d*JvaZ>#C38xZUIo*%maO6E`=WqtTSU=7gm3 zk%@uv*vKj3qIA4uF3u?C+!UWoy@oIb!LK)zUM#**)D<5B{Rfw9N=qxQfO~6^T+~I+ zS;d}>OYMO}yAU@!1DrvC7g>trCg`4}cHir4+n6u%#i1h4!6NbEgMLuDk(1D=b6rJUcbQLbM_$+M=7D?R_-;PcL z1mSxFmlyI{B((+W?}zR-F)|dL833kVjmIt4^(P1A78PE#THG-_1wA~#TXXzZVIN1b zkR#};?Z)rgE}P(szJ4W^s@SIdIYZDtvyDFVbTH-QL-91<>rV=7P=Z1i944YB2!Z2L zMW=Qguu?jM@qV>m-bRap>|;2s_;qmH1osScn4*uzsc!el$MTzMzpg={Il}MRAI2{L z{bLYJT(SuceLr=Jx;?*%upj2>3J-=H_hXLlrWX!_TIBIG@iaX#8FsD#g+RH zkuvsqj)b2k^y6dc0y+tIio}QN7=4IjyN+eY?N$JN$uPt^G$^T=-*!?K?J!xC&S34e zE6>tL)^$xL$xKnQRBsZF%$*>*~F z51scRa}PN!z%!5fXmXG?S?U;cM=7XZn zkPm*xhR%fFywDiZ90tK26FI0@8oM#Yj)R4Wv`vp4JWfgG*f+-+ajNjA z6o2O7k5nXo25n%9y%q8(ciWQJjYImX{G*`vy#+53GsSN2WNUJI3^f?q)j7e&a;I+a zYRm3U)qx)oShb-PJ>1c2+i_X(R9aEnRg|v=JZ)h+nxl8pE?--H9$1|6*2b)ba3k4- z{ul$WYw_%&hCA(nNPpGWI=f#+QRAJNkWc^*g&FX3E~b<~N-z*3-INiN~l|`^Ux`0l~$?39kBfPssM_zFh>mLkhJn_5u@xQ7mLN~xvvRk(O177$NHB%2!iyaSlRQ9m zTz9WPCVU`R@pS%DiRGbldxr zwLTbFw3Zxc{&8I=9<1m2TJ*Q8jtx;3mV-eQ7a~cE$o2SqlvRI@)R-^6+!X0DhY^}L z-Y?Q+30vXTE=A{XT+ijW+SJ*Z@oe;LPR6`an*|qNeCj3%y=tmOTzLsC_z#$XzKwz? z`Asa4pN`I;-n{~*o{Mt>@}2HtxuQUKf$8%~&C|3e7tJ(}RIdVx(R;Ah;v*u`S>IBT#Us<+}}qFR{=UmZNye7lj+aU1?Bmmo(dgz{<3Z7mwm;gwk;*swu_BEE)zs@%#)8 zGxm%Y_YkYlq6C!v_&^G%!C3xi7JkPzzbPQ^@JGFNPev$DZ3No9Y)v3A1?2!>QOvM-M|I>A7LRi*&LS)h z0v12`JU@hAKM58_UpreOVjC`3e50zXqE}gv4Lu{O&o&85ZwOX=4l1u~JngjX5JDvv z%9$Osp)y-paXAZ4OH*3`lq+&{(2_GD^OW(l=H9_}Pd#xDMM@51iF=h9A5er)20YJ+ zxIP!u7OXCQAB&z!k7>Jkc#sc^@6q|~4Ht#AtQtc=@w>sw8aMZE6H`fQhweY5?P$$U z;_&X@zy{_}DeCzBlYISY{5>quiqnuDzDKC*6%^)MRL6(+P=Gnja$^f(Xq>S7`3l9O zdfr-mhCz5^Kki1+jK{npT$I0`F8VfE{%YBg->3jU83J8>Dqkrut2?xkvE(>?LsgL( z|2+mHM|R`+idpx-y)w&B>mPPR{5DMZ`PT@#e zcPo-Rg3j@c5Ow!EnL69j6HwGujkHV*VoTx*8%gWDfa=JDc?;Z%X`mJErjs|{_8Y6 z6#i%Wue*}`*EwGs{MSQZhT50UHxDNFC-Pqpv7<}s9nF6ooNDx6U)w=Fb`E}k0p@;2 z|Ml3ZC-q+oQw{#>)}QFVp3~KLTdqFTcUydNYi!QX@LyZgPv*aVuc!a|<&}2#O-BE9 zvlPv2LN~Uh9p0|)ha04uzabZPu|6{)FKhe?pC-!B(@xSKFmM%>A zvKRip)R%o^sonR6(U*O+NWAzchW_>G%iiWwx1HRV-P+Ta{rZ3A%YH-iWfOwFT2=F9 zzoGfE_a0;iS@-f~zhUrYPwN&^`m$G!|B1frB`JK_UF6F?a2)r~j6Z=dyA5-UNy^d7 zmz{sX|LwkP``+HZY-#TaeAyp%{F}b)s{%jSm)+LUmoK|Dl`s3jj+6SbM|Y(5W&d;Y z$$Z(%C-(GZ=N!gEUv`H2MUJG4_4jrCWY6|>O(*wk&mhnCWP@kBfqAxT(X*YUdA4J> zFrRjIY=P$7zVgJ*?eqF@Zja~A?UCHMJ(xSU2XNYP!XoXdoHaS$Uq9dPGZ`$P13YY z)3i7wxzy8xm1qxOg4Pgfc6W3?yP(!i}Mp(ED!c_f`s|-dBtU z>52u(9x~R5n#&^NfV3BY0LdA%6AePhbY3y8$t5^UCAo*xv5;3_q(&;D-5HGQ=T2WM zTHk6wFU9x|%EdUxWFUDPyY*~zf$st1NbpQV!JBcoiE$D=WtwA!$; zp}WWyO}Dc})cEkjqVf-Q%d3Fg=A?^dU1!?vlZU7=Fc@5?6ir?MsgLS%XWC$MRsZ=Z zhS62G4|0QO8zH0Rd!{pO7IR|@HLk$od;hZ765BE-T`5S1Fki>#zJoC>1?j&hrLY^+ z_qK)<$)x`3iLGHJvVO`j)qMjQ-$J`TYL!bsWik^{t#}Nej6*A3<5pTkV9KBnr64PK z(Dr#tfoWrg1CZV^b<0W8K3?oQWQ7`#RX*S4pft*N`Lc8kU2fWs?-mU}Vw^J)hn9%3 z$-4sy(8bN4LObmyt26`<>oK|{^bS48iT7SUC!ymU%O8|yjDE)`zq&?Gf_I|9AwZVgrs&Y^qscvGZJHv0Mn{{vku^H#2_W!{Rq zT0j0D(bbv`waCMbFQlwBfo?ADi$QIzq3Rxde?9MddC>M-1%XFWlY*qMb+8XT&Yt`( zd(Fx?SQYek%=_SX&%pwc6cv}gg8;55G-!j*|2Wjqr*tfD)+c?liFut@W_fQ)!d>*d zv;#K&>og{@Q2A2FB32aIJ}@_anHc5~x8tFeeLHTZ4!`}N!++-~+K3p(_ylo`yAzQD z-@3QLKCTtUeN7t5p&n#@<`-S2j-IMdfW97u80HrT#W3Zka?UW0(AdLaiTvZ3=5w$1 zQKfxkXdej)oMFu3RoPyS=WlK12fJwb#l~``@uMR_}FCjA@f@SgzH@z1?%dZ1YWv&Lg!Pb*k8aH zc;jpdH6Lm!*?2At64tdZF3asNW80JKw7_5_lH$APc4AYa=W zgA_6FwR=Q1{CNG^z6<$N^N!OYmQ`XbYkuSDb>$Vl*4ydr*t?Kx#U8v{V_PxY0qGJ0 zw>Xtsv76N&*}_cgyB7dc_-9(NuXTKD3GuCe#_4-B%(l8U;>|1 z(jXjpVp(rvEGqyD`2ov%8?mgnb(1?8S=Iz#S)pDg$} z9X8cro~Oc`lQ_%z*9ex?Wmk^cgGWOw>xf=i))b!(BEcX z77}{MvO4mH0jZ3#*x<`B_Z`i{I!#FX;oY1-5&@bo&`D5lZJybcFR%&76b0tW{VN={ z_vJafNw*Z*I)S_Gv^QKrmX!+MIMMFkrLnk|KkAjm?PuQ=iVrvhIL)HZk5xbkml{d!(D>ZDXTd0>#t+s5$)e^=+b%rizBNXD7S)4%q8#20}? z;6z>I?SPGxOuAJTj{D3p?sG_yEDsw=1uy2laYecj1lkH&jzMk}~VFDj|VM z8U}ykyW?guyt*8i^>JNLihL9a*TsV)C>iQ${WFB>f@sr z<}K@hU2x+VVtMdp>=NR8R3lTra>ibS&F|hVRD(bk0pGD8UW^P3qlZ$rQxiq)^Jrn1eO8gKve7#(aua-g&ALS;}jC0A5=SbVB6Wot7C#$iq63? zZ1?kZJ0+K|yHdJ!do`ggX$bA(zV0>VruZ1bJ^eZ_LCY(qnkfX>RM^$QJGt|pxDOt+ zbiRvnjDBk82?N7b6~0@6N3HPP8#9Gs$DwB@+RucLToy7}3;EjI`6z^J!)>@?YJ#~@ zL06UL+JLTF%~gvoM7DnML-HsC55L_?--}r-*`-k2G0VfeD75v6Cf-!tUx#|J^HVgB zX7^pZUd}F5ZorjAt%P+=i_YvfVB>s8gXHY|3c?Efu0K=fIsDaPJM({?Hkwa}AEf6* zS)M>VC4};1jBByk{};j?z_+5a69)+IiURwJnR52ExYH-FA+prs5w!o~(&PTLjXz zxdL5Q&Zs#1&K!-bt8ggS5yjUu_RLi!BHFts^Z&{uA{Ha@Xh`WsUIh)?uG-!o$0h9u zT?i^LAqIr~F-63u*2p}%KWz$rHyr}*W~xDkg6%-e&ors$fUgQ9q16(M7kCFa7nAxC zFx z(t&_k9M&rOP6hYmwxZFy&5b9e>l)8Uqr|pPEbu)HzK8H{AU&jh>@%+MjI2NkEiur; z4>e)87(^w;S85T^{GF(@^=8k=Z>+$m>{PkMpv<(i*e%ev(?w;r2|IJV`t!-`)YLB; z)YDsV6Jp(etxLJhB>L|#ATEi^$8DKViXF+|V(~VR|G*0U@ zsSCEy2$0=W967X+0g+BMvZpP==h$Q|OnnY0vXF(kVSnpkp^ovDWKq{YJ6)ZC7qr+p zfCYe?fX69yOtK_H3i?7;>AeR+sXHI;?|TO}hayP-j~Z|8{^g z9i27{9r-$Kd(HPTv0}G#+(nna*5veEGMVpd6qxQ_!L8J@PTRh^g*)hCmux)4 zrv8ka5DJt2K^7!Y(7TwOTJj!t%$}ZxQmmRqRBqRocz!g@efCuFp!RM=%83htX4{zb z7*blnL$#S1iDIGcpWbB)-BHu^Elt4^KKJ}=4GTWpfbwxozV=7hff6Tc1$EgM=UIzJ(W{mA?fA47ijxoGb8BQ&KJ7Di*!T|9 zi9-AI=P~F*EXp_fkLR_}(A-*&k2?U##cch${5J~k0De7(Mkn^$Oj18s%)VBO@4^u8 z7x2gIdld@Uj<4RSzssj*lg*9mLtYQ(ldf8dZ^pSV1XPMBg`kEY9;E|eq;OvYVtrg6*vj9%4Z4* zpPUnf9T!lB|COze47Z?uw?Cy7VyZJyHv)}GcTZnE3q1dbo)adL4$5N}sg57sPgHB( zyLM_M;9~XFTl&a)=^IGk8UJ)YF0a=RGi3G^H3y@X?P1Z1Vq51aj{PR}vl)FvH&CV1 zuD>69!D2=6=5h51G%--P{oi=Fm3D6#Qy+oklSzMcyjb>@7z+dGde@}hIRUG*@Ldzj znJh54@IBb$!L*bzHW5kvs@MfY8?)|rx3>1!=x(`%y^}qJk3Y3c&h*Vl?t;OV2W`i3 zR-Xbcgx%kL?2?91d()v{GNs+Gg=9*tdYO`kWJ>IHrI1*uvNy3(If<2y?bC^sj=s^i zSn2)ONv!lpNUXFuQmoVzDONgJsC-$d>_*BI2@jMpF{#qbBqmitt_lcd|J*wr{=2Vr z_~%Yy0;Q8EPanb4bUV^uWJ$} zmnLD_t4Wx4Y7(X$nuKWumoUvG3DX5l!ZaL7-3WP1xw&a|ye5w+GHUXeG-D5W%oJmU zU@A`&Ox+L`ObzZ$Fco-2FO>>x5|zyBUS}eydDm+qDLT3eOM3!NWrV}_Sr4I9fXUaw zLaBFN(}Ysy2S(vli@d?+Mtq5Zgj4JZF!hlkeaNRybmC5?E4FVTQ$VsaArsROj+8U8 z#Ss!UwbGhQixf4LGf`8k5Z07HQB&Pzov7(Ui zkf`Z#K`(0BrWZBgb1orKQ+6z}LD8b7M_>JhqNbNF^$;~NF%u#NyMLV(#Yrnk+=Nre zzxX5*Hr*8#Hi;x`nyCq!(Eh3>Y}y`A3{HNb|65kY^rs%5S!Hrd?zrsA?vHs-}6ws!DPwB;wgL>{|@QThyl* zYRyR|hC+ONMKRR=w|j`8NFIBQQ3$=Hl zHzbqV&t+1FSrWXj0ekNHl_ZmL>t#|@;dvk7yo8y7>wTw{t=@ckbynaqsTo`*<$9XQ zq;T)%GN~un9#4f(;?7|)tanA`4m^KVIn_A>ms551E~k2v%c)L~oGQ?{_lk0=-}Wh| z`ay)8YGZ_)$`c`{S{^N@x|9P&LW9*)PPOX;rabXpNJcfLcNtYTO~}t+ zWr>}i3cX9Hjte>o)o$U+5-QYq3`?jU6?&CW1@2|ysXbQ{PqoS4Lh;lh6i>}T@zg95 zPvxU{%7zuHCTU%yXo@w5kr;!uNdq$lxxEtm_FhC&@8LyCK%VhH$tB3MP)endqReoy zCZ*bq9<5wT^{2<>I521mcPSP+in9)hoz7c)Ek z!O@4vua(`sQBuCujs#;+N(rXDgx4riMDQT$zVqI#A)BNTR|@>bkJn)(8gTg>up<>H z9B9CD@oRqrUVbXr-*6TIL{4v~$aIQ@7lPD3ZX@}I4}H3Pf`R$|7)sktHmMZ~Z`n!2 zO;ZrB_!)gj$4yK(9-)2Fv z6B*1^tBz>bd!$??<+kG(r9GJT;vz!p+)nPl$-?22=*R8kCaB%N#_>T`YZK+Gmq&3u z_U{BkSBFe~(V}iY%EThfjxO4rCo5i>(1Hm&oM>@PGOCaKn$#gg=Gw$uOPFgtb5$}| z4Rd*ztAx4MGS_@^DTKPo!_GWtqxBnypz4e5Ao!03e>NHkTWO3GW`GCxQAn8CEb*L%MkNizgvAOL**gZ5a1%p)9mvl*S=rI|5btZ8M$&;!qk28O?bG-Q7}u z->rg-Z|td^Lqo%Q-}6k*|A$Yq;mwQE?SQUQQXW0ZCU6$Y+RVYUFBal(`;O8uqe1lU z1&lq|%uLsljEIlTL&t+bHJRSil}dnlTSY^BU?Hjq*^jbIMWW88vi)#qo=j3wMjYky zmZwN z(6nL5#G-J2`V1*1c!17rurvL4#TqunHnz(D^5144siatTQ2ps4tZBE{Vr=_>QB%Nx zXHJ0J>TQDL#?;nKbjYypg+w{VL3QKxeaJ8D`>|UO zn8dREV(cl%U49Zu+VdXk^f#Ws(9wT?4>R{&Cmb*qe#Y=b$b@p_%pc%e^(u>525ME)Nh!hA665skHRYbJw~drj zb6cBE=WiKlez+BgG(`w#-blzsITh%KqtJ8)+M#rv z=nSL=4`KQ7`xEX$eNL!y(;+#4(?goqbVfE!w@SB7Pm~IvLvA*|cu;Mgz}Dt4wD7kH zD!hlVx2(&N~sOv2p|+y>k%wVN;AwUse{xjPK)ZiIDV{WJjc* z$fy3SPubLeX)wtX@x5A2E(lcSe&d(;fGw=&Vp_VYc86LvpMF;#DA=TVbPgT4@LC%husG3(sNRuD8l z&*hKn3g=7rB6+SW=x81r+A`xdnB;aC@>WMn=FRX;SFS@3f-TW5&-QiqGG9qa>qOG@ zBd7AV-7jSUqkKf3986nWtjYYP8Zp)UYGK1v!O#$JYx>*TZA$7lEuW*+{@5yxE+PXqx40Po_TXUIK- z?0hx`!LGVvE+QJ$Zu?ZSBi7il7rUzqD>*5g1*W46at{Hb%jQNPH_k=EY_Hr8uhu^Q zINntHH?mJ@ZhUD6XqP(MF)0yRZ*Fpt1hjBo=+vWe8p&m>l0^)*0+hQs>>9Tx*eaHF zVV)DHGTqqX{*>`WD6vxrl7VMDR1n9*v8l3Z|p&cx&9vw(;g6nR%Ivh z?sD=0ABkge+OKYy283>_=GTCJ%NwRWr1Qf=u)y4gX+P5WHKE_MhG~ACAKD!ZjA@wm zpw17q>H-5Aru`88l9=BnY~7FWizH6=V0#PIE092)14GzC9ntyWW!mBUu$Kq)_BOP# zYC9+=!UPzldr{ErLBBNl$@eBaIu7Zi15&bh7D_W#zlc3S)?5KU zxR{h5J{>OP#ZEbM-vT^2JN%vHVqANk=F!i^?)~SvU>Q_5)+)n=y1RNiG0WN)@o3=f8|iId@r3 zRwvMlI4KjEPte@BT@ZxuxrKu)H!!=hK)25!!~ z`p zO`8(BjH20LE(Qd`-gG&k?*9`aFBoL|)Rlwe(W31gDc-y#p`s-=KM%H8m>5_=&i*lq z^DpKt^fq;l`Z2P^`4=L{Qj?6xn~k5im+%09@|{Nq-aa$pB4rj!0Y zvYNrPL9=;6+dg@KSk^$2A6u6JRal7gAas<}H9NoAD~VRFEzJFkT)1kE!Z7Cig3hTy@qH&t^A@*;ZUR_>^+iiZ)VKVtT@&hB) zS6;x`6>WN(?0%~|Ia`sZzt1n0y=h1Ke_>W0kl`gL14FZOmxnKLJUfG-(7N)uXVczqmr_hxu~y!toD53=19 z&Nj*t`V*+LhF$U<=rGh5(^+005VE}f7+p~44h&ZFLpiC7C~uM3Ubm9G@j&2u^%hp- zkUoo?z>DnD`g$0b(4fM^sk5cr{60*am1K-~g6(}G=Fl{HThK`6i4?~rff+f!P4rDq z4@&vI83iZtAa^YA@aeuzgOm*GULHor%Yo$WUn4MXM{7mMFXy2lUd%-FCC8#+?!oG! z9igUv8$Nwj&9ph+<~02qn(JxmEEY$-CX_6&45~iKma-nG^}4ZQ89wt=kCc1FU2~X4 zZD$-7s5vkXahAY%_2PDx)2rM2oc^8Lcpu^d=+#yiUk)ziLucDXm?RV8p=54MevTr2 zEYPW>Z+&jEAm{q$C8|lkMf(rr&HxOM%grz0x#-zb!%mJmA9Um}5Yz{|e`A0vl z3pipkM7d;wrOGhY@lqCta~^ zcJtQ!L51e6OX6qyT|#;xaB0^lw^G8BAMVKvWS~z!-}5`&;FHMAZe;4$MUE>n+r2x7tZUm)Fyul6OBnviBr0(MjxdF3D4QN8-8F<5UCD zKQ}Y?r2R}RV8HrB%cjObSRUSSkByNA)F)ce2a+~7U{3`S_BXK0g!se`Fe`gv@Wp%i zrNFJZCowDNh+hI{Wc77ttT91;{+ZT5vK?LhAus>Tj;MTsyCEmrD_(lCghmL+#y>O$ z$t+tv=|e1ydOwe$ef4kju1U9M()==z+tNVMw+%(B0%|!vf^ynG4HLo6`4tIXf5~LG z*fqAyJug5+2MS7tcllz2@?g<#ymy;Uh-*~G`>_z?qxg7y%l9dS;2v zGXC|;AW0=n{yA3lpIbtjetA0Cw~l@?JqdVxbm1w)v#`yNK484*6eFX9Y3(yK3TlC# zf(jJ+E?kla955z_V*UkU243}DxF`=IV(fsi>kSsB|unMUQda= z9BjPyZy}x~4^5^ygCxrDw(XHqP=;W<7z}o%$KdRl@Z+6m?MYMuPM}ap!(nQkx$!!r zpkt3XV?V{4mcDaFZ)ZbLy@YBuaikvCN#A%rX5M-{nD*XuAY6dA{+GbCJII3AKW<^3 z`^j_ea5Q^|SVjHYCLkU*#KEit2KG)(xkjQ4bph?mQ?c=yTR7J1~2AM&a`iewa30{HyO~kDE5f0ef6hkl_M`h zKJN6jnu=oIE*kf$yc0UE;d5*o)>O*!eI5sd&*v#pG8#u4x|6kSCu`eI*0!D0w!4!> z{~Z>mfBoq=YLt0v0wTGJ7J9b{`|UJNj`immqYoT4F5-{t*)d){QLB6NLt5s2(IYv^ zIn<0NyGf$brCLzgLiq(QI_0?fA}L#R*b3szjSr#@CX$ru5>iDzl^Yb%qUUjRQ313GRfZTUc>8fcH%dWVi}Aa!;`1}67Nblb z$t^|?e!PJu2VH*SgPoUyzVpTn8DiOC^H#?kONG6qQEdIh0GJV@1U_I<8_wf2*)Rm6 zZE|D`pV{1Kc;ZMX66!)&8-lp(Hw+caj&Ewrz`YY=J#!Rd9l-FwyRgEKZ>94^V0wVf z-@TQ!)2KR{@q8omZ(CXOSR;n~3>rTUS)MV_1Ma_*@KmA;(t{wry5O%!%HrW`z?ci& z`nernwTaMdMhcIqS1x0^=rd$ABq|TuehC@iFW~P1<2|p1PCrPOH~J0WhHM(DH<6%O zhxgHuT(GrCt3<^|wlBfI)R!m7cZrH(HLwG{!M>^Z63NQ%)2SZjpx$~d9h9a=#&GIl zyk?~sn5jBR=RcaheL1|a+pw^i5SWJ^4V{QYR0E4Ig4atl=f@paPv1{|XeJ1q?=mN5 zqn>2nOGr=HC~jxRjYECg>B=9}YuPna7mT3(1|$2ww}ed7L-Y(7Cvoa+UD5ziF=Jbj zuq{S)1IF{++l@P+GS8$7DWi}BR-&zT5xW}s*yhap@n9QP0_MiWKCom3^xqw!sk)G*bb}lJYl{) zIt6}yHoL2X(49u}BtZ%(Jw)^LSAS07kDxO!j-40Je*_61KdA?ZO4>Xa5A_aq{LUgw z`l*g;$@z=!AU=ZYiFnUkJo~2jdsIr4%oUqA;i*I8N$H-a6XdU)+q4Te;R`y@sYS{` zG+p6}JuIF*>C8Rh9QBH%LeF+Xy4xGi09VfL)=Y)(8~FFNc>RWbCN-Xsx5GYfz}q$s z!)5w=iT+-szZdB5dHQ>f{&q*6GpvEGdMSx&-%mY*7di0N@jWKd_qjn1MCwT>DH%^Q zY;?#VPEGmr7;JeDx3c^y9C)hi#Iaj6vCD=TjuLJ1WKc z5`*l?>U&pbshNKW26slj(%h1ctdv!q{QF=KhP_tg278cF%vU>p%A}n6DCIOa9i<(Z z-7h57^9ozrYL{sH8jykQ(&`j?@*MZ$#s z9tfsAHyH)u-!(U##X@@aPdN|<>Vr@B*}$iM7i!>&=z8BldJ~`KG5L%7{w4l`wr})0 zR09sry&NanqCAh7U@~$@GdskyUjVUEm!%GRx;Oa^t;w;!qu1Y-iRQnaW0zc-f}+{c zjdL>Cu?Fu4A3Goj{$i8`2h)a5Cd?*J@Xa`R7*}NmDviAQGFcLR85x{s55!`|fj^)l zo;h^Sf%mwlMz_B3fx{%kSryPzfp6p6$qDLE{Ju-{o$pvv0M)qdfOZY1=`9gYMzD8X zc!YQ%QYbA|DRPqtstu3VbBB$8(L({U#Xf zcOWo}4Cqc%C)LndsM4+Ga#NcL576Ue$;0VUb0g#$fNge8Hf^)2;a)nuS!o@2DwSm;oP}tUf+zLIErN;kOBc^(2lMI83DF*^$pknz_ystD}2&AiHyu{GH ztfryG#%}!jwHM=I!D8rK9q*ETAB~PH&FuoCd*Xs80)qOJ;R3%LMR%wCDJPI1dmFDG zwHOVDd7#*ma_JCKzA2X(2r?iX=Jy1Zl+)nTxsB3=I%Ft zrKnEdB?Boapy7+6rqgng-Cq=|o&dCbq$wzwpz+_?jDpzQGfM%Fo+Kepjr@A?<6c5yqhD~-jh?5pOCq? zS^Igi6rUQg;Q~U(4 zpbrJi$d`C6*)JX}RNgOARQ3MNNQ<48;)+^i=-o5&_3FJ(_J))RKRo=aV6c9DmMC;~ z8t?(5+d+wl0$uyH6|VMN1iq=%;N&cH)v z@CpoYD)o3~hGFKdaiXuogvO!sH;qGGs23Gxlnkw-$wuF?m_R(5OOxYSI23PgUO>l{ z7Y*#n4pzhb;H|7~ayA-NlT7v(kmw2I)!WueDfPA`=!5kLjIqCf_eoGVchMrJV{CZ< z#xg=I8EUc8fKQDVDVwp5xhG-f+t2>np&Z2O7D9bz+t0MdNs0O97mxZna{@!{XIpWr zm&W@Ge~F&cGuFiVI<3C8Lw4Jdy1~9zdf zoaVxJbAy39?dHE;j6KJ@;h|kfHbI;?ITQXGw4-qtty* zXa>SCo0S<+00X+jy!8un(`rI!ht=zlgY{3i_)EfuU+-hOo;M;bk^Fr$ z1$$Y_Mn{lX*W+T@DY5N>QSG`PWh$raz7Izft$b@qQS9)y1FwW%;MbEPsCGEMdYwC$KE*c$SmUQNgp!LdTtvSo9LUX5WUo5bDS?DE74NkrGIqA+UBT&^WyCH-BEhux#t>zZw?}`5 zq}`Rpd1_Zw7ryQMg}S7juHpl2Gc_}NHxl?n!T3|gEkeO}%5@rjX>R-hNm0^bNH_gp zFs*Y85yZ^C7THT^rwhd=$Qb%Dpm5%3!#vu?u;7o6Q}AP<;8qHLk_Yc+!AnEIzo%dy z5B}Y8+^bK4|F7DZh~Zj@oyKAZ)9&KY>W>p`CAZ=63M|L!Hm37tENdg%lI57#c0ej~ z!KQdOrdW<^t9iQ?G3yC_ODS68hjPi zRnGuRWsu{|J5HwsZh>6iX~p7>OOw?L$Jk+EcCei*a$f`C`*`>O^(`K5qU&7Dxc*OD zaWCTm7Kd`Q2p_nAonmN@5qk{Z2eR`-U%HB!aOzF zn^OZXv3X4AgrR91z+f{3tG|6ro5xSUJbpf8>!e6IRRoi{zsUZal&uhaD^_m^R&M|X z8Xe7v0X0<7rH}Pp(b`A#YwHAT0ZzaJa=Lv}tTVXB-W=l$?uOcpCn3@&fvhP1Wb~Kf zoxVH*ms*T-hcBVdZA(Q%YsFKE<$oEb1*jKnearXi$P49*7%PdUMiKhPr< zonC4nR6=A5ZSW^suy2cHXd&x%;^I-sH{Ze3*{bjmj+P0tA;-Y5VA?;f#q;_!+b+`hbC?~kJ6h5v>_RNE4Ax?i$6-6Z z@kYCH$f@kHk2{*5mnS7TWB1vP%U}2o1?@`PxHkK^eRf;hh9rkyG&ov{Jb`#1?OF;U zxI;>%jB)e6b0#{TTY}K*EtDh*i}WYC{U@ zz(M5D6Ym(Q)qwRc^0<^j3!S+`bsf5X7Dr;o<1KD90j?|($QU^yQKiUKs2nFTORSY9 zqFB~tw{@8tucbT}p#l33lIm(TPve?AjX48qC$G6tXH^}?>VoTgbiufRybF*qvYnDf9Ehdn4^(&61lcP|r<^ve2liO7 zl7Uz!dY+PMLJfk7;LTsI%{XQR>jCLj))1&p3+cul<8OcE*xKZNp>7GJXsx2gKz9by zc0v|-=Xp+-W9lT?sD6$_i+>(>y}t@y59&NhJMvkV@-K(&ENZ*MH1Z5`w8$o97f!FH zpd1gL%Gx-)a!j3W#y(c@3<|m6&7_XKVJ!|L9{5ei_41a>U*u8RmE-iX3n@6pQpZ;!<-077*BS;3Rd2FUMW0ps{!GB&g>kSK#R0Q4kqs8~KpYGc4vF%H z9Um)$S*s|%`w!N9dFH7^TOLl?Q&int~d?*^hNq_1$} zKc-#_DO|P>@tuQ3`$|s0*A)~`+}UMoVceD!Df@?= zWb+zuF3pkHH-c$vGjVcvIBXv>Y-Ha>Q@T>z#^>z4Fd^35IS1c-)MoaL8lp)G#WEAV z+1WpYa&tu61@>M@2<1Az%}_2hFxk7HIPRtWb8PEAzyaAnY~g7v^P!siI-^NFA<{8cy!NBG5cF|rrH6c5Vj}gG^x`n z>6WZToy0!U)ok`*RY$OoY;`dE$Wc@1qn~PI9{K9U73^-V`W5>qRzG1MOVsz-M~Qlh zeN?K)*+-tbpM7}LUF>76`rL}p?OgR~_Km}>KF+?e+3IHYjoqO(t_WS;RoAj_GQwKT zzR40s3HwI;qAq0Lh+|ZdePcJN)7dvNnraUFM*S=`i+y+CcRKsVD?Ms5`|iSTfqkQD zllt!p`bK(ARoOQhlULtn-=tvB&c5-OTHVXO@d#VpRuNV__)|q#W8ew)jXDSF!|WSL zYqhx|qo=x#6aGc&{EoG98-7Cj~il2M&aDdw2KXAbkpV?Gw}u`{1B zp`2*W;G)*enRJL~Wf3pA*;E0a!OSPXe6qnOnfbiQd;pWA#4w)&%qI_gx*sK<=b2AF z_1I(eh&G6^lnf`@97!hG1)moDw8%5y zGaWzE<%vKySe?N`@=>R+V+1cm`k9t~7}=tP;Ljj9A>c!2=vPTj70m}l^C3XUtn@zH zhn1F@(ai9fJGONMGoJ|!nYLSA42_ZI0*g6Yv!VHZl;O-1I>VX!sBS*h6gHr_Iu-3_ zx?)dq^O7`s}$K6 zG{}khjoWYu%SpC#a^{)*5`#2E{V_ymmt>SvYBQz6hn z?j~rB5yGD#k;;20Cu}=sM0q3Z+!vm~jFJzd=yB$LM}|oNS}qxgvnMwZSFFi5boUwA zo!!tq4id_-+Z)4G*Cu{@W7MY5^A`NtI=j5_6Fl`}b4WB-3M6J4!&@l!niCrp~_LpE#^?%3&PD$HIO0fx?XN(ts>yDA`K`9vG z?O@s;2eMr=2em6{dstV3(*Q_Dqo!@0k6NQSXihRs5a?MJE9xPTgb_E_U|JE+1-ATY z12vnEOCBH*%aKUc_Y$16pU_6_RNB=WRs)gazsF#2xPTkL8j^(Mb4iGKYuvidUlJcp zH~ZQyoAS+Dj;VJX4hD%NLh)OE^K&H8%Wr-m3$Oa^Z_L7pAvpZA4S|8^+su4h$QNHz zfwEiZ))G^uQ0#+4$b@Iun{PTbJW?8Y};SGdF%p zDkcS%3P+1IFnkvs?cjw=dg7%5sbo=|U#&g#@*>)_GjH7+vM0c7$kLer-b|mF)QNVj zn5Xpsb6%66@QLZZJ3fSYTnm(FW7@@!)zMEPwYvA$x7rcQGiH*p-V-LGuH@$0TLP z!+eftJ81s?j~E@D7~*xR`{H$u8^W>`WZ|cC7Je>HnV2_&LH}Aq;3tL35n#8uAnCYH zj)X^aN;k@D@x`#**3O%e5*xED#Qpa_ARs4(0syiv3`M-@DkF`gmytm_z7#j4LKBn_ znLRQ8zcQl)Drm=k!2P4hc2=?}O{BJr=ll342M5`K5}rMP|4!Ludq}`b z6=ymTbvUMO5ajXUq`G7z9pkcq4^psIkXl+Smc7BuzRYe6GTR0Rq?x^Dz^Y9w(~~Jw zHoHUc=2En6aF!09gLtW}$kJj!!9>GU>>1$iwl2l2k*CT*p6c=WC`NLNVIxpWft3o5 zu7+HLqvs~$-)HFiWQuk>EQ0>?eQI&F49dcHyG%tWE?StC?i$x#WS;qo+ocR2ZK0lg zrEYMAz2O6)tH}Q|0p^5#e=PdST`mREDv0BJdo5@uhh3h-`nREAX2-uwe%r$L9+ zweuKJx=cr|h2pc0Yg?s731+9Qvi%`&BK>obCM+|1>{q>#!>fMb!Ba^oI z@2jJ_E*wreaV@=+LX?3gDxtnRat}4+!Jgl0ez;A6e?9u$P?-BxLmu9Evzs5@!!Ee> ztXltGil#b!y|TA4%U3gsdW@NGgGV5Rn6{NY!jz(7_40nrTl5d}9Nx#Fm&4^8F63|)htoJ5&*4xG`*Rq_;h0}CIE6z8 zhj(yT!Qp)zKE~m*9G>FvpB#2`XnKN|%i$OfCvzxrcn61-97-H+;_xvJ|HNS{hsQYV z;INCs%N$yG|7CHQ$KgT_y&OKq;d2}w%6Aqu`@C6QE>kjYAWk51;*l!Phx#e8AOH_Vr7q^ec!!nI{?k5pA#qYJO9y}>yz9FU~2JTp)R? zYF5~sJ-x=>q4h@%WU<=qa4(lv6qHt1FE1@yDP)iRR&V~+d2)l^BhK);n%L4LK?6>iB2)qt^=%cNSbwE}+i6F`es z=5@oov(~uRL<9?Sg<8QXxCJl#tA$^yunJst@UK)@0bf>FJ3FjO3pVWu{WX*q3&B~hEH8m0aHgEa2VTD->s!QwYw0Ko@1+v%cu8|g2 zLXVZ}mUn15(2qW!BDYjoTkdpNzd>S&LabHcAe?Q2u(Z%VZ<*Cuv%0jps@z&xT2o%_ zwvMji{_~dC)mFP<{K5hJhlM-bFac`UxyyS*(88-r*ICQmlt(RVc4=9eyRJ@)$>J5% zYL()VqVfrc_g+p^{iSstEy~sUo#81xW^+{4l>wsgu5$rqbJw`Nw%NU`iEnY#RqjSK zsHKS>tv<%<3W=^(UzXHa^BuX$yAE)=H)@7lp}f8m!H+{9C4^~fY9%W!{3__(@4CzX zgLqf%_bYX3sGYNF<(kNvUZH(GBln(9FSP|asG05Wn{Q$Jd;J6k+b2Zs_um^WTgO{R z%j{S0(s}C~8#Zt}un6iogRMFI(eUmFitLy zGljcv*Zd|=4B@X;uvSY~xO=UyE}ZAud%L3IjSofs58}h0 zs%2M*AN^BTTecFW2p~Jyn3j$%*Y=5tcOeR_UM^L#)XQ-P?h&hJJeY5oWliZScW=>q z#MjeZe9Dyr5-gMWd~<5^k4Pt;CHQ;gnusMf-dZj*@@fVlwCHl|kaMNm3-g(xTT81E z&#$vWJ~gnUgvAT&uG-p_vWF9FGl5{MiE6>pnLYC@uMJheIrsKO&iQxVv#@Y}krU`F z+F`E{Kf1`d?zK{n_^grEYKquPk6s~v_u48cgh#Frud=ib=#I6LmDi)!_@f1u6_4Wt zil(#%>Wt&Obo7E{-=G{AfvSpi)@r_8Ts3}Zq0K8R!)?3#D)F_9tzNezdu!@?&A$w5 zUCq;6ExgAN71osZ(N3603*4pNvPvGau8(-yPd4;u4q&9U!nFVRYpl?d&p^D1`7(N$ zQD*>)n!Rpob-LUdmKmFIg^pYsc_$_?Zb!Qv9}{f-PYk1pKf_5xAAsz(g=<0Zz= z?bX&+bbZ75Xfc6r2`@uIu8Gc}_x=gz6HcMeiQ)MxrQ>skM-2Pd!S+xp1M&p+yNqGs z+Asqi8P8o)=3VE}$6?tm9Ssaftp`?TU+YH~k8dHR<>g*?U0>@cTrN^Ld>6xACt_dI z=Ld5UIQHuQetu<)^Y1+$Es(?cZfPA+*wOJc@j=ZBYpKUmt@W(e4U?x13HZn^A8&=3 z6+H|UtjXAtU1ps~>pvuxu%fi2R+b|9Kiznw)=XL*UpO z>VSX4d4WD!e!avKqQf!c`2_vG;i2 zynb3fx_Z{RYr+lfyIyO&Rg$|$x;~nB)qL3B$aRYK7W(SfN?9teUDIRBy8?d1>_QVB zu!P6$_J%OTe@br>;pEa$b-bP&%l8OkG>x7wiXI0FcdznD>#mMpvFcaGuUg}@8o=ap zSFLsf8mg#(W`*PmJ<5SW)JN)NABU1*TJesH4tGy13rqawV@zjFMQzV`g*CWpt(%ZuEVByfZRZmy4U{eCB9ro^9(lpiqbymgNStBfZpQuUxU1Xz76Oo z1zfSpy=pm%WO$c-IjCe_uoY-<(-OAC{e#68C3BF)^rguA=cNO?)NP$S4xDnoeLHF96}{)Yq>AvRu!kFmrR78V-u=f)hNm=aj?ikBpqgqw4678fT7g4K%0_=2gVvIKqv zVXbE^{FoqykRX^$08H>N!KAH|T5loni^bmBGC~Tgpx4Ssvh0R`J$od+zW)CDhI*(_ z?EUrk-&a4#XoMOyH8mLpAt$H4xV{;3&%Q3NcyT?H2bC%=MwKFKc71a_q!OT7m6eqy zQ^H!0XN||xqdr|7T+Z}9@3&37KRYA)kIRk2LVKPbpC9P${E45Z31}VoO5^Kgr%fS& zLkd43S?HR#U;*QP;_+*=Ars|pYv@WN$M^}2~k#ntXo*pqaSjhA{RtJ?Cgofs)~@;BrU}FfXWH)KuXveR)E{Ou2%Ny>pIcul&lbSRc)OF zZC&Yx+_5>ZL&?>WwYI`q2CIvxMmT*)e#-0@2^Qw{S}s#vca3bkoC6& zdyuuZrp!I@oA-yloE$6%bBhwl^7>EC!*H2xh>_K(beDQqP8jdzE3|V>Rc+MRh11>C zXSzD6{0ixA#B?4RdSG>xSCUJs!-IsQNf9yLls@ynr?v*AST{gt0kBHg#8Cc|rbf0K z`AZt_T5z-dBfJ7JKJO>@S`Wz=sdu7RD#p7xD&8uXf>r!r2xi1eeHx74cmME2<)u=o z9vKLTPiQJcBZDyihck#Dd1K>XcLzELH}5K(1Go(28o3TTbxrC2kEj6JlQXr?_PA?c zBx`F{0VToPgYonFj9=V|6YGLONRS&a4^v7nmAQV-Vd28!x zDc8(zzdqaz7a5-W=tAD9ZiADEE(|+=iIgIAeT*DKV*E za!P-*C3V2SL1}}Bq-P8rHazp15!P!*j>;N6=DO^$*N+=NVd4!rlP2d*x$&l(^QKO- zO`mbgt@-wu1&+d5w~5Z#b6iDp=M~>Rf5E~TF-a9b&|Y#&DwR}{oeWw8}Ain@Ol8Dy~;z!l>D^Hg(Od{_qtFxiW{wB6)+gy zvdVRM^jYSu@@P@4GjW=-NOrHcbRAEq_YWt5P0^ao!WZIMWmIPHQ$i>j5D`qKGHt!B zkW0PgEJn$y(wfp0u%1@CX%8r?^{k876o75?>KahOuKmeZAEhvQ#0-|}@ZBcX~M zm6f|AR06{JY4O5XJR(MkyVClfR8bfIiZP@6Nmsv!414xxANhHz0SVyR=f~Ph8AA@c z0m~;kJR%grYgg4&(Kb<6wF3M?x!_!=aj#jrEMojuSJ2)NQJshkBja5sl+0ha(24$q zA`6$xC4O)KND0Dw^j1{;dX7V{9ifZYYnMih&lTqx-$Ki)>cU;Os?^iRyzO&7Ty1=> zHm-Hhjip{T9EiTd8L{+$MM{xm>!a(!<@b@EH6Y3t%cZ05aDPOs`|yGfRIFhZAO@mc?fu32I=8ooAJHo3GineIIgEKK>(tK`WEYibNX6H zKLdWR#k?S+TW;a_kv?tYHLXE^*5hfj0(6o-#+_%Mf? zIs5^K%^WszSkK{l4%c!hap>W&n!`#C%Q-CJ@GcIQaJZ1eVh&v#iX1w$c5*nK!#obB zaG1m4cn-5U%;M0>;cyNu910wEuVYZi-a!+H*vaG1?uH=kFh z8CH(IX`?2=;mmT`oGpy%7QLtR`Ut=%- zB4ae@{u#dEKYjZ9bpK+$;Xf^{_5XJF|3C24b4)A$PtO2D_}@4EiI@R~@V}UE_%A#I z{=5IK)_(jq2>$6^`mk@@WZv#b_cv{CxZTk{^dNfZr@rAnUt`n#-*0Z&r2N4Dz=N9~ z`r(fr{_#(K`pBb?{p|6d|KgWV{OZYHKlPj6{_g4D|KX2+`tx7@`pn;+{rhvzZ`rzS z`;MJ2?0WH~*0$Yy_U_w%;NYRdFCRI2?0EZ$ldrt`+Uswedh;J|z5UL+?{&QY!G|Ax z{Lg=>ou33gJ^k6|U0;0p)xWT@L=Y8Th^#^l!w#|KD!^|LyYs#|0>T zhyOp(|Drf;)v9Sa{b=|ZZ!Ll!D}JnlAM!6Mx}m)M2IeR(5(Ik@i|=rk(TSgyes1mR z2=_eT)zG;BRWEpeU0xyA0Y5TZuBQBE%QbX7Y4>=mkfA6-2@y{}%e~wymxk1)gxRGv zuJ$2z~R9wtM`(aOA1CIc|tx@sxuDrblA+N=N zXO>qiw^$cm5)~Ko=&jtmmcGj^fi%xRc=Hv?#d~ZAb>SWGZQ9f`KIWzQ>dSv7D(~h# z>Y39^o?3lHU08J4dKc!6`7G%puPgl+5)DG)a)1L3!oZmT2N;9_=uS5X>3WzEBV^1^ z%hBRxOpFzV8y*nSas=VuKZbsY1HbVx!cc>s+{Ngg5F-rJxqIY!70B{?h|+s7y$QzP z$zJl+>aM~52BH5<9)Dz18<*?c7;mHwqCcifF$gI$b#8>w`P`?=PlK3lWK{k$qrzwE z!nJ&d7=$63d$%qf!Y6h0)3;OKUl^{3=zpIsAI+`rU(Ky=Cy$>o&M0IUejyC-q?TCt z_;$oawfnxPeD3R|UeWy%4Kd!6x_0sY$+#{?NHff!a!(m_?T9l7aWkX(XJ%A8G5xR@ zA=!{h>DLOncG0}4W%D(bmpig&f3dkeKQy=TQY%Y4fz3Ir(=c>r3K`ik!eGO-(`Pt zr*I7oP7(%B$q)vg9MEOy=--~)n&e3=F%_p~BncUNlZ6bapO8_WggC8hU`J}Z=dTRs zmpv#5zlUF|gW=Na;d?*)7ISy1IZiN7Nf6AF`*|=8`lfFdgpu%DrNtR;6oxNPZyoGO zD;WfHNQ-w0;{4_zL1^IdLi0I3Mu?vuQ=FQaBxFh{LS}igkU0gu=Vx>bX-{j_(yxD5 z5N?BhcvMSoHV9^H^B|Kjs2up9g=S&Ul>Wk?XDuEBwo_~4!bBlsiV54=YDkI`k|0jf zv+*AGZ4#2^$9odfOhTHJB&3xm3Tfb%Ha|5~?y9E*Vajg=;crlG9>9zn`a%7^6PszM zh_!U}??`S>YBhNhO5%&z{IU*%J{XoH3@h(144aZ744XfsE3IQ-duppW)MroqSrA@> z-=q4zfVQNj#tW%al7-ayDXslHNhMnR&;KF_x$s>zi^sPn3)b>f!MYH5PH2zSJG^UX zM|%6<)-gv80l97DQENH2%qg$Y7Bgr!d&8;%I~U*2ca+-Gg&GR!B6wAjIV0K8)iE;|b+wK=~O^ ze#Ydq)>N!3jGYC>&N4qaGjf27y;xc*Ksgzf|kTf~oqv3?_o)?5B_^ssSJqF)x@Y@_wK1-82Fisc< zeKK&eIh6jIi-O>~7*1ab-;Z3>rKk0q1nV~u)-Qa|hxMBYH~`jfCirK9e2XG}+?G$Vw0fls_j7 znDTdFfZ-XTpNI7Wz7WpFJ0UdQnCCxI4MHx^!LhS+^U@oWlQ9C;))b3i@rGv(=97mw zpW53ma^B7lx7Rrs@*5J)GnLPEE&P?C2B8yvhihdHh==-GgaOa?_oS307qchlBk3U)s!t?NZBhMqcFW-l-kFAVfL6|xu3D&U%)`VFY;vLwP+F@=-tgFR;4rqqk zMj3=6txhy2Q(;b8U{0E0PWBfvf5_%!#u4oP zp9<+Mg85`WPsXH_8%IeNVFci|VNm9fT&Pi3az|3Tsa0F+d7*S>NY`I5KMUpdj}iJ$ zPRcPP#o&C%NhLg&0%a!)L*_@Wg}2aJ{0u{QKce~jJkJyA0qvzc2VlP>LB9Z;%-T(B zaXG6;HqnCp3Ns1@0cK6<>erFjp3rLa#FfP6Xl>Ngip9qmtbC*=pNDv+9{iu~C9H(= zo*Lho4!;jS)+1VoN7cu3so`+q#j6cM`#T1q>s8>}A2kT-WB(b?S^p@D|2T(RIBe(e z6Aoi|zQZ}ZiNm`%T+QJRIs6NUM|#vJq=L^>_d|O45n;|c&7WV&35Cq6swv0If^;W9 zhz=p&0)F8m6mpwe(p@2lOfjplF8U<~rZKs&;kQ|Ns1t=@;Q~9{Njz;F)g_9{E|=?=adcD(-u3{;ypw zULJ@4YnO}n-~Za>BB<5d*5l?h-bJ6$>wW6Q!nEG+cP|!%+c9K8=rZ+UypcWmp4`b3 z%TeX0(lE>Gc57<2_E=YKX*qX6%yPplQeWV@2;gIi;ra`O>>AZ4F(G>m?gDQWVy)^0 z3{MIt1qZ1xMf=-gUGCD=J-mf4g+jd3)Wd&H;rzLUF0ID1Vo?FL+KyLmV3&;HdKh-? za@#HXHrQeQ$IdUUs?%RdeK>g7-%j{(XsB$=s$Ls{s$DN zcGarV8YrX2Z5O5(7voLDSyixoSdELT%H0K(rQU_LMW{nQbDiWCo?vN6O}zjpi)VH2 zqS|t(#WE;EuB*g6X3|YMXvgTd`BL?wnl-Rf6s{H4$3YcDGU8KEE7!o}S&1!QAeA#u zK{$`OVh*S`D^#)2Qm-U?a5JT46>E*famX6 zi#~&6Vqr5!dt@uz-eMRG$W$1Et+<0}GP1@9!U*(Zb9ENK9smQ6bU`|X6qI@-*$d5t z$*@)e-f%&++wBpq!4^Sx$^Tz_=K~#8btdpTf;J!?gG!BpGGL^!2n>QYVt|Q&1`RMm zz|`Uk`WJs&jlPb&n@;jQOn-JHvVZoio=7>55I}yzYF&kG!@?FM5~0DX+WuN}c!a z%rE78svhB+q?cS9?Km*euu9cI~4 zQru|XIC2WwsBypzvO0m!E?OXqT{spX?2s00E~bttzi5Sdmpk zTa-I}49#3(d%pJMbn|qNem$?U!e3b-y?s(Is~b(xfJ0|SR%!fnF%{BI;yK=+W`o4^ z=->N}KGLL@ELq?$DzVk5a!TQIW`HH4r%NfONiF8hnj`uU`spHB6>EkZ0B}H$zd%{T zXSdS><`>ulv&Z%s^5LpuY%h_brJMQ2naXLA#tq1vF$Y7Zsp%sVdWLEF74{sIkeriP z_0pl2TF<=eahLI2$8-y6zr`5$8e@V* z+;=SE{*NQty380a9{l3v4&qlcpSYci4B{rvdoy|!aTW4BCi|B%zaUMGdANYeah~r+l73KvBFL=u`@<{IQ4 zGPap8QiuE=aX;ZQ`N;Q?y~rg`x=bnZ407sIE|ZCDM0O)1x4KO3Rym3;?imM|f#y_m zn!K552ARR;bTh=9VYnMMiDoD_7-ySv%rNssW)Vr|JafJoZbq03%!Ov8ahp+Qw7JM6 zn~TjD^Cj+MFEL*>W6h;zoEdK>aNj@CTxKSj$>wqse?vB>>WazE)$_W!vvcN^$OTf> zg(byKAa7+}4mUbEPKumEE4}3OUajfSyE!?!WJBN6^|-l_TbcMR&g>Qb;=X%x7Od!V zs@^LC^*y_cC9{J5c+hF)iMaUWB1ir4(sO->{-$?UXy{Mk?)4q| zle*{9KmAP~U+SmN>3hG)D$j6N_M;R<<@Usq2}P#!E@OXu^c)X+eh9Rre}iLhhgoHn z*_##PA9A1q#s(Xr(el)a<1!l!kkH0&z{|%)V&w)>W2gQfG@q* z!cR9A*$@6s>}pxYnOam3|M0N9pH2>2hOysXdaohZKR2@W42P;8he=cR^B|XV?dbWb zb>AJ>MTPpFuA-E2lEkI`nS522biZTTpVY_Qx9w;sE0NBQuToQ1;HCH`1Ns*j5X$0H@jb2y7S|YbBm8Y4#*M%IkIvNL%^}@zRq>dSrg7%Ua>@nizC?` zTDz==U3@!yEcmps;j^~yYx=*n|GuXGXWg2$p9Pg4>lPUNX({`+NgncDdi;7cKq=po z%kxX}eY<>jF5h>{FU89D@bYVW3Ccmr!MgAC9{awiX@zI1-$acYikzh)@uM{Uat)_z zc!q|3nr6PnFHqj7{=ceu7i;_q#BJ=eUn7t*E$eA&AJ8(dRo~Tq%YXEh__kQ4*N_(eEf+sKE;U7398F={RItYYj}`` zQ#2g!7BywP{bXx+Xxv`I`kVv}V#E6UglW4~*K5%5CJo0ITl8!Ad<~~+czE2OhDT^{ zm*0jj)NqT2M{3xoVYh~pG(1Yf?ot~bt>Hk4j@KG4)NuSgz-$fQrr`_?AJDK@!||VO z^ptd;U()BL?*_F!|9ry$)9vUlKimCBe>wO6x7?rQ_Rro24%6bx7+iAiT6I@^TzmX=%TT@L+Q-_RApqJAwFfP| z%5BGKpRRlw`xnD|!{?hf!yVzT9o_$(AxFD`3BV1z|7Ew^_hp~7e|gty?fZ?H zc&API!CG7YgZd2gjKl2zUh}@z7kkgw|Izll%(2_T`|^>~cdpTOj@Ie^Z|eFn+b#Uab7e`s4e3 z-+!2mSx_1hyw7EF;kn$^~gEsxiEr^KyQVobAyzO?uN^eOVI=H zm&j!Fc6c^7MQLIK|Ab_U&kKxs1j#}V!k3XHVh_)z;}nZMydJ5LeBlsoo>ogdtVGsH zUT}e%@keanYsd!lPWT3sj?JROkGPSlL-$-{%pFJ+y#{`SY(-B@rtc!pO4%+pCI@*A z-4C0Q9a1*9_e=D9@d*o47+=K(p3Y73UMU;A6M0Ac!?V837>(|Qg~$Q1hd&u>%)t9y zrVYN23_+I#IiEq!K@W^G=Eukg^iKF9gG@4dJKQq?Q*@8Vm_^8B^j!E;rYC9Q6Hc7O zH3r=aE09d_3E!Dan@e7o8&irbmUwv96|_IP8?Hr)B`-KKmGqJqtVdR(H^ZB*r2Wxr z;8afX`_X;ykH`ioGaSyK5fz^>2iYv;gij*b-=Y7&eQMJQlhV{4&PS5Jg*{xa@ip+@ zRBweHs&~T7sn(|terKx9s|Ge9by8;dYt`G}pH!E{PsdKPemwBLY1U5-{5f(dWoUz= zr`veXbo*SV=)zmm=|9qja1XLW$^++IO+S(P!q<>J5)Vt55bhOw7)9QZy1>66A4qv- zk|%ONjvXvU22uuj&NPY)L6>JstFED+NIcwnE&W8|;ak_*GIzp@Gi)1rU}=VJ6F+=B z!`d{%S2Jwg+u^X;*4_;ls-6qSTt^>6m*;Z}k(uazxDCmaeBnMMOVVD?H5^%tF3;@V zj4Tm*7)FXEU$|}#{R&;4(H%UOu=t0A7Sfl{6X6_Wvy=fYT*UDb9UerYVsj(ckDIB# zhyh&?>3nCmjSJX8E+34KH2;caEibI|2^;=dw==<;0g z#TE1+ba}Sya(wLdwAv=t~2y!dG7kxYiS2`c_w<+U9^LoQ*bZh zMwe%)*WJzaUd|CX=9{#GoENYW@u4@vH@|87PbZvkkL`ONSa6Sx_rrSCo8c?>*gn|~ zhgEAoggMnZZou``Iu5{}sZAR^^cO?=*93m@_z3FlpntTkWDM^^A6o;?TcXzvKU>s zRrP`2V@yW&VxJ8kP+i{H-S$1}rv={deXem2xl9(EzM1osv|jiVWW>YtVL1Fz+K2cN zaLS{$JZX;^vkKXY&FaVGok81fli>v+%7nceUJwhuai)=<0ei*hk2ViQQ zEt}9+&pZbk;kW9o{~Gvilw(PJCmhv8A4X4xH#J#5i(%;x>7VHGuJzC-=nv@Uz(}QOt#5cpse@>Y;a9+dU&+V}mwyG{X?RlGT z0<3u6<|X`J#D||Qc*l0D2cYK{)D2yD^Dnd?!beo!44+he2mBbR!QQ+;JG@}anFjZ% z{tjHZgX4(J2KdnqoAv-a_&Zx)v&)$4UZLHv$%L=$rhU-&z_VYq_UFKYS8cl$!hNsW zy1WDT{{cVPAAl?Vn|8xq-Y4JDVf%yd-45F(1K%=c(p$D{li|v@tp6%_$J<=L&;#({ zx3xXtOK)47ov>gZ{Zo!3+=}?og)i;1_B-MJKXNWe9pUtMZM+xm+0R%b@o?0KHa;2t zC(=y(F1Yw3TQ*_fBb%>q+X2R8IUnKw9I)|SaMfR}z8Xdj+WruQw{tg{ioP0_xj1*x zE8v&`F0%wZ1?D1>mvEEno8c{|x}3HxhW8>;&imo?)9^=HFU7-*?c>^RGoO_(!`J|g9W+2<1XkY(Up zTX*4yNiL@^rJe6G4x5C76)?Tt|q# z-Uct6$u*Y#CTnwDgH%&rS(mFwb>Ujog|bdoa*gE^stbRmHp0Cc@2vSW%f<`OQ(btK z>cTA5g@vjM*QzdS`h-*$KBKy*ZUkFD@h@CSCf<+r)zYi{G6 zzOu~ug&^mnDts(*+U=8PCUaJ2G_fr#$EMh+Z+Cwhl-N8l?a+^MR;?&5DW5vJvaDoE zd46HRioEi1E8=f$$ggHj$tzzme&xi`?iG0@MN13HEA(~6siP;3_l%x)#$dNQtwLT8 zlQ+`5ykPXSvS#^0Io1+ujct#$#f+c(4>5@pM*NYgNFY)jsflcg1S1WR=15DVHL^X@7TFbP zk90&jBV7>_O^7B&lcMfuO4Jigje4UQQC~DWnj0;QcKhEH4MrQH&C!-1vdp-f?dJHP*TVpN(p&F-cUx!7s?Lh zh6+ReP*o@pst(nJHieo)Euq%X_E1}BSExPI5$X(eg-kdhoET0DyTd7APdGK~4QGUX z;p}j3xG?MwSA_%N>TpeXQ#crI2sejY!mZ)$;kNLuaC^8T+!^i)o7#lh#M+cvd!(~# zbDg7IRU4?SuH97YqpqEGU3I2Dp+2!bsoq_mQtzoxt@qYv)cfj>IgL8Go!m}tpVRIC z08mQ<1PTBE00;n9Ab~uFs8mk}M*#o;FarP#0001DY;|R0Z+2xaWNd8gy?cC9Rn{datiO;dZi2^0rWXM9w~ z`(;LS7zZ51mI48htCs=M5$_ucV-*LAfO*$i`<$F4Ek5(T-yh!}pY1QnIcMM2UVH7e z*KO}J<@y#WLy{y5eByCQS|f?SV(EYXbC@Kl|2ePsmsa=QcJ3Ne`L=VXDYq`jn>YWC zTjt+zTi%T~+x~MwmEI@0M3Tx)nbJGguD(uxwqNRhZeLTDBy~cE z^Lo*QeJN@pOzDE9Lc}pCok75y*5OWtOL!`6ZmkIRhpNm zB50H*gd_c*qf1aH142)~2AG6{e>O$qoCU6G_Ym(0KEhTsj7 z^g)rh`a&88^6+?QRBz{x#wO%rR!TcNHn)(WTrZ!u9sBiwwbMJtR zgZKmYyw_w(P+e?R~I{P*+U&woGv{rva;%ReQr*zAZ8 znkAVXk=Br@U5*c$4%cfy`;*#RT3Xh8|Kiznq5Z9#{<_(bbl*JDX{$eE0qw1!)gSx~ zB|}BOWviVwc*qtz9q{A!v#hv0Ezx4!0-Vnx`zr`k~+Ofc3-2;kG{olSNtsNj3z zgQijbB!u``&}j{@<~?i46__ zCLRTq7E@Ul%X0hUEp$H(O7ug_1w8UfM3U_G^MQns94c#!2h?tfPIEduP{_fo^y87^ z%SM?6N_3dcK*YGQQvk+4e9o>#=fRKcjxKlR0E&|FqLQn_c0ay9UnaO=rodm{USc`Pfc zQKi=(mq)R|@Z*_fR2_gJb|`C*K=`Rsgc+*yFGih%vCjTbr@PE3C-4tB0q0h%Lna)1 zWF8ZcwTpBs8#D?g9TAeA<7qvINFS4)9!X6vPEWr%HN8ANy(Be#VtV=odb${299{?f zMveyT4HYID*IYz*gFd`4Ua4dIITC8WvSOSMIKmT=vVvCt9b_XNh@t({*sCbxfy2y!FPv8m z_z;Fal*_V|QScCkzKmr-l00i>qG8q_I%f0uh2E=ooj{A?G9+2beG}zgpPE|+n!J=~($>%#9Exj%M=7VAdnl((&*|rrXqmCV^=a3K zhqd+IkFeT`jt2PrGxQ}Za~;+c;PVFPPcp)r%mLndjH(s)7D&GFxQ~bpZhO zb&lpTQ~jrirMAzkecx`D&267r>p#N>c$blMhs(9v2MDb!vstlJtCKBw-K$y28onOx zvZ9l%!@q0Jwl)nI7tQV;{=vHNyUKQr|5}i#i8k4Qwu3oM4*YR6$tL`@Hp%AZ0Znp7 z(e7q+sHI%YY{H_^4%YxJz$f4UBoRJmhEJ zMoTTREW{AV6AH{owmnvwiyi>J2${~N%J!C@&JW;@#r$e%Zf!5EEZfe>=A|DiE?1wN|zh#iew& zg;8Tb5_Uc=gXlR+$d*N|lrKi=@wMv8Xp2pF2F3(bi!ZzJs;l0_f1*3sehpQs4MJM>dE%X*)u}`-v|x9DwMuxd|9K0 zfGof%JPlth>7yM)a?vD=fZGE^@(xNOAS*)lJ}?RW@j>%2Ppqo)zpXETGE|Ml4V5jz z%BGR<3BrL#hDUSZQN~ZykMo-?!+vF~XYO3r`i17<>jj;~h{EtMiG%?jK8mFMP-b{@ zys|yLcT2En(e6Nvsd?IE`D{D;fj^Aw3$vvHKm@bKBBjhngr~+LbBoq24EJ7+D;wjH z!=cRCGZ6tUY;r=PNf6asyw=P(`#lZNgj|0hYP-m_`Q9^u8D>Y~!RuhegJ5GI4qzk;@>!cm+f2`WY%AY{h|Z{rv{pi=+AUtKQyU4q zl=TMtBiBfL1mFPs1N`}T_!@+NQUd<_iMW;`?5@qB0qh}~AiIN^?CxBcA)6Ov4R2$e z9lhXo__rCIR6HEB1hiH+RV7VX)>gD7COOPzN37U_6F*jL#VH>vb^ru%wJb+1v!(Js zo&)GT3QWut?Cs}l9xVbo<0@*6nXoo>oJAdH1^MzfRBOmy{~M||jUBYmoKNF-evMDU z!h~Z56Chiy&535eiL?bw)1y}8#YzkCE>@Z^e#pPfE%Pu#A;44A8i~VNT~S!6kR3d3X8N+9P#-=Je_weD0^&Ms=52@o)UA)5lgLTXp5KTyVlnp8w(&WTG%IQacKjimKLZb4(4}4$?UX-@7WUGH%V>va z0-FMS6&CIGM_L2HGufRvL;{;#AKYsjJvwL~A8rF-Bh*<{2~>lN9u-SP5#p~IxTV}A zXY(B}?b7fI`~kW`Qcq6gF#FcN7`53&R!}4wzd>Y_7UIhB1zh?9zz@gZ%zYa)i7ocU zuZo=e?DsuKIddLyy=`CmC{mWywZ|TQK$K@A9*!Ih*?a+I-bAzGz!UV;Mm7cD74W!x zBC0v&??}xlYK8vK1fs036*J}X`dTqle#uH5kGNu?9M}7yY?j5g$7PhYdLt2238<h0h_e?VCbjeGgUMin#HJ0vk4fbDN(e%>jeYIdjx1i#kNT!>UfQ8KkW<9p<(Ir@l~3$8(4^$R0nx0;dCCdW5h?xxl(%F%38Be5*6Ki;z6Og0=F>v9M9&Le24fhuaG z03<$ufl1Jxp#Z{J(9W5pV4=w(SHLWk1%&V%O2W>bhv^rjr{^cqFT(VKM0#AL7hHf> z9@(wzgsw!FJEx&4oiFSgWu!KbiZ(c%7J@cURyLHN#p#m{-8z(4Q>d&avO3X$ou~ok z{{V)uplk-+(Yng^U}wEJl)Fb~m?F)^PE89DGnv^=X6W_MXB5_I7qVHUNCi8m2b#^}j1A3(_tOa`S> z8C8lTF@_#m#njiz6jE*HrPfwJb=+oTFW0j>sUokD9V^PCI@Wb0vSS^&@UX@t^GQbD zL@n8vW_I)82`GuVC^o$Vel830RV;LOpQszz-M4S*=RB>nOVK8eUkrrYx5tC@vzFiME2mwVSB?H$Zj5W=Hl%>d&8e4!57ft zm*5LeiK(-(Ea)iHOJ>x)0BQX)ffI6#0{PfN+^4qXd-IrMiO#&6^=}RlA@2 zpgQ z{s82S7ac8Xt&y57XDg_oKEilFor^2NL4McG<#C0nFf(Pk3=>CQUjbps%9E@ zD`qpAg-@Eu#WOKJNCM4^b^7^h2M8ZXxw2o$nMC~POMP}&l|LKxx!`eCQEO%W1_Y$N zCZonwlNTRkfttcy@z7+W(i=pjvY-4V62ZFd3!~E2Mx|fDEv~cBcP@SB!FQ}t8i}FQFlL*Q#yLA-&;OQ}nUeJ7nKz{9%aE?Lz9l)7Rrpl^ zIisc4nnf~S@GDen$)1vIQUv_G*qvULIRFFCN_0pfYPAuy4u+0AgIWyCv?MYV6R#Ux z`q&|8q6Lts{HaCiHVzK2KcL>s|7uz}M>u{fVkM+o^BVyJPvS$?glLa!2^A=Fff!hc zRpv*DOspMevMGny0A?=QGPYK_t<}D~jkUG2oB8GYpc=$sb32>TsR0Gj5&Lp>n*IjB zebB>vW#0mESj6bpNH`&Bh*6bbLVHW}^M3*34xP{6t$O&k`A@SE4l)*Vo z1`s||us-W)rm$G={7PX6XJVa1em0BJK(piJPpRAJ#8$r1X9vF(#8Ay$t_f~;e}jVC zxGEYxnlQA4X!H>fJpj0ykoyxI!gRl&MyioyMZQ#W;8lE3gG4TF>|Bg85$zC>M&iM< z*baV;gl7G{mDEnGF)xuP*T^%J^88KDldI*?^)W%LNT=a8pi_`r=A_%l`I<$-k%4QI z@)2Po^tmQ%fKt<_*#ie7T9wvGxW4<0beTV}LYIDr;Bq1>FA)Q~jPlqjg<@n?mQ&3` zjgr{DMwh`eSRFPa^Af$XQ0B@fO4HrjBEJ~KNUJ~SMOneBoTREdKOsh(yxL!7O7J-I zen`CniwA&QGUsUF2z)ZC$49GR4H!&oz(9RCHTx_Tfq_4#MoK9+kjfcLhvwhthZ(|$ z3SdH=1>G)Gvda**4WDYtS9n7K)C`-{{%fcj$6v`?9dR=@_ws73mlJy!12^SrdDgZqeR7f$*1oU<&H4jPwS8`B^;Kk&4pIC_y^ZAMPE4d6pnomsAx8t{zzBq5>~W<2$Ik$N*P~R$h7&Ct$`l=S7JUn5@cIdN4@MF z-W(T?QJW;wfw=vN`kX!0XYZlDKB@HyR>UJ8qK(bo@TEkdHndj2?FVpMW^ect{sezr z794?ur`&Tbwm5zt%^-&uQso8*dCc$3{Gm*c5Vq$L?hw&(H zIE&#)bAwaHpXJVJ@Y6KW*{^Auvp+OcfN>nMXA_F(yler==KcVGnW9{*k)!s=3xG0h zZLl}sT8xEceu~Un7S;($&VapS*PH+_6=+=YvG2qJ4wDo35G^Rm!-R$R_6j{xJXLy| z6YIi3NO7%pmH~jF-maINbWhtKWc#T%RMM&D^-_w*EQA`WLcY zj?xF-ty6Gt0Gi&H+T!l&d8dpBoqm(Yer4R;6pY*tglo(J}&I} zaemK_^SV7oqpVG_;&c9k7*h>+6tX%AmFxE;b*kkefM^_iro-nB_@vQqjw!Jo<(d-f z(V{(x^$0Uy{mVf~6w!;?s)E>=^o@>mT#zLV@g6?)H-cXq#f5cp0N{8a@oiyPmNm<= zM=7363P3)sPI6*(8eyW?O|(@dFHKslDe_es*}e2{O-|$YDPo!U>HG^5`FHo2f2CNi zVCZSN%F!_8`)6Xg$`&-_gw#B=bR&W;{I`xEoRWD71l@iYA!sPo6r|xCE^4ABE?c0? zBCb;8M;i{<7MSdTUvyE;0Gcz_ub1_sU$IY7$#p7yt z9uR=~`=E&S&GYc@;VBC`^VRS@W}1-B=sy<1)!M7kanT+GA?C=_)yxXeSF3%SWiw9k zCa+n24qIb&Ng5*dVup@y9ZAEnBe8m230CVJXuGJlX~qzyVg+tdL9zg?&9A&n?3%ym zsB2RoK^?H4w*eN5$80KA|S-!qWNQQxWt6_p>tV1lBTj* zm~IwJWS6uz{0*sAYu?^)9%j}GV)SZ>KKb4UVZzz=S!Txjph+O}kfW=2A#JS1t>Z_Y zMrR<*z76yEaQCb*4#W6AeAt!{JU%PQrbt8ftL-#Vm^OlA1DmCiGaO`#89+5 zN}Sg9{vsC*IO_y@aKNxHcIIc27aYh3gfk#^ahnadsMO?wK6l&rOe;Xw(Z<4>lwFS7 z9B@|TUx#yW$2L-*@-<8SVv+X8jD!aDFUUZYtI6#IWn`Z{GFy;F5v@R(Lbd>PJX46g z9+_E%jG(PZnF%>Tc#I{%k9+S-;m4R2CwaMZgz{WD&hVUVWPqHQ z(BMWWFJ&Zz>5Cwh1eFFM;V*WUTgX?=^S**|kCLyP1b)}Y!6G);hpu~a0e1lzIOPEE zdKaB(P_>U7YN&uig-)D_k=>ySA=e0{r5r(B@{VpG9ieP6KzQ~YeKJ9Fs9$*f>hswN z_O8B=gV$LJzC4WBr=Ks~ewv==Bou=~9@;EG9%&`Dw7bXBf*uct9OR5|BHQJb5U>{D zf5Qmle*RF8B|(Tm6dQ5i!?YL^zOBdXTBOOm@{~xEVak|tEcDkN3t=4D@sH7ZEY<^r z(ykMhUa??Hhl95OFS&({MHb5Hvx%ZZURIwYuC8Uvh|zvec9nl($2zw zWsoI7GYj4}W|ZD2R8$>ly*r2XuaN+wI};O1%TPV`a_O!@66B%55wfy@rghgAqlIBc z3j?49tdjBzh@K;eHYerJGxC4BB|*h&g@HX(sC={>_d+h@IozmNPdI`Jy2TywcTk5eL~4&+hh5>8fcHgGb{z{$4F-9`!5&rwSGb;y}&lS)lDN<9RR*;MFH#@3QZt2))9 z&UHG1ec8s$c_6lT;8ir-ul!Bu4W{3+~5-s{J(ib7OTmTF#Y*m#n+M zo$wE6?vsPAG!*t;PgtlW8M%U$!R32yB383&jMEBw_QU zXe^n(NH%3#c+<^T(67^GeFDDEB{6u_4grk$Ej?{_`Jhjs?;IW2tOot=m<5x{u- zke*8_?BM@vpmcl=O0q}Zvr%IQ?fPDmn)&FIvUzlTAEow!ABS7_^yEKHt1rKMeV)|% zo=J=!1*t(d3S*^+k3`5ry>q1I%T&qVy(O6C=P#pRsk=vo!x!*7{51G=()eFNsC|3ONoSs^aOmA6#uqVgc;d>BHj(gc^Tp%e3cZm6^GYb z!d?9reup6))0`G{c|E47%}+@Bz7Bw#Jkhr33QUUCKOqDJX>_09nR@vn6m@8-0lh`G z;f@--k2N&Dq2*0ZN|Vp(4_QfW*^3dY=;roE!&od(6jz0$)+HvRI`;oWoqlOkMDa^L_zytj(TW6Q%t}FHBSn+S;F!DDqJpn zkTJwRFggbt0OK(*7JfA*aVG&bwh9c25X90M329veSpuA3Tcl_M+4hq zSY3>s(f-JNq4Pn?qJ8(XDsbAq@|G?YCW2UDSeDQjuR!8-d)QX~4}}C7r>w=nDkG?H z@GV_BOe!3`eH7d3$wxy@S0d^|9 z1z5>t}6TA#bdLT(tS#7~t}K`qO*THYZsaoxHeYVlEg<0=xe4*!F!St3rtrhJ^4 zWX;OqaY)s7cqGMaCI409i2JL@&X-7_7XhKT>BH^ktzDpZomD+{t`xdb_XA>@2Z-&d z9|$t&`6aAL5Ju=i8Yn-vt~0a&6zXRYI=_1}@ibLF&(?iJ^@pS^w50^t8%{?S9_!!< z@R^#F?m#KM11TRE<7=mcA$%W=1vZbv#g0ovbTTYG*KJ(!1YQ61dOU; zZ9#bw?_jMTp|(cAO2ewIksQC3=pVwzbXJ%^Q+$4VzA83)>#i+~~&YU~Xkp)b0&05>1nBP;2q5H}#&Bg>KYN+;qHqM9jMRo9PXe&cuA zYG`k`%}jF^SA(N5v%TRh;u?r*FQDKuRyqn7MOn$0kx%{MwZtxsno7kXV?5yBfsdk{ zTU!JCqfp)TC|^uP9(-$3fg41D3;#}2+=`pnFS>&;oy+`yX$-a2eFn)j5(o}iSu+(u z81h`LO9A0%tS&eW;P86TnXW7*K=%L50Hj6~`yVLAD#~dIaO;GHJ=cdc z9g?H5yx>fu;+v@A`;#i3Cn}!!nm(;!RI8b;c4~_^|Jyoh*WE+?#Xxi`_VkE`qwN+* zq-iDhfTJ>y#;kH9g)J$^UUF zLH?oJG|~^tG=^VqL-V_0}ozMntWX*k(zncDUT+-Y6e z-eSlC4&k@6Ual+RqwEmKmRHXK5~{%kh9Q|fOosh z6d8iSXh22*BqOJ?(2ZnN@~S@cxys*-sw!XA`b1ubXoVbzK8%t6ZjcEF<3ur2cD^ zMFPrA*cFqHA6$*@l;yPCXLsvKa|6Z1(N=+m)?g-HIGTn34e#p!zj-J-fX1Orhbp0^ z>7u1yD5J0mvyb0TOu_~F4{=1#vm&sj*~D39v?sOnkLHHBSD~#NW8YcXmvR1%dxw2bQ{7$ z2T(>J*U|wx^^41*!-2mdzD%cj#uvi8RMJ)|!M;LnsLn0sS1t(qG{4SWrO&TirOTj^ zt5zYojjE9zVV&#;{>PIdBJ`hPn|)F%!Hd}nWO0I$Uy^D6)5}JkM~phZg2&3kvKWI$ zUPb69oa`BT+9c!S@4bSV&OWK>BWanE^;OdEQ2L0Kl1>ePjdiagO@P*ict zmWOsgW_u9ivtA}Iu9GI8I6V(7Zv?rQ7eH#Xc2A87M7vcWH`kcq;#q}6y*alKHC}`v zl^1C0AMQI-EFLU+*()U5l2EO4xC#t;wYe2ev-I)5B!U~2K}MTv{-T}q*Mo;&*O|mQ zRkAz4ujqqCWuADx$9V+sh}T4z*Qe*Sa^Rw=^IM0s85I&n}h?qy{_%s{SXK;EG% zG31wR_V5p@MZB$uD*K2W3ACG9DfXZUKY5j=XBF+Hr$Q$ik@~b7{F;BnN6HuC9=meK z!6XmKFq35P$pBJ7t-q&esP6c)L0#i?d-`$ zk`T;CsFisH^y@F_KK)!}ssZ%7FQM6t_yj6vHIlo=9Dg7A#g#h0P@p_$q-$T*Mkq8~ z=Sh(}MZ83KbKK~MB2y>-@E48jgjZ2Z)Yrea#S-0)x)3nbKd&JKt%l2A{hg{bilmKK zu1(lcRyzyeDuA@}7VZ+>gRt!jITGMtMm!l|xwFiM#+p$c8H1;=M-5(NJkPx-7AI}Z zyhBHdpRa=yHUR((j)^W8sq?%zQ$jE5L0I(gPNN8WF$oh|(@{pEM&0V9(f9L}e@+>F z9n8hfVgxe_MnK=Y?=3GPr5>q(g^?ok9dz(CH?c5qq|gavMR8Zm-mnh?xPCX$9@&i- zZ&2UuOE%KeGJC^^l9s#+DOA8$_;*1xxGQfoS{@7a{!J%5)xD6?>4?$k6_A3qN}&n?2X|Bjg|as-zm;Flz9^;|_1+FvTC`DVvE`^?y$1Re8#5M&4gMN9tvs zvYKGx&lkRSf?Rcjy}rQ9U0!@N?0KEWu%}i*I%3(d8^!~RnL=&x zq!VTb!B{gJ7GY>cwos)e3qCyopg4nVm-+H4vgw>*4i)0u#3|c}BnbTerNrFCsE6e6 zI?`ZYWBzhrWVu4m#o&*kR+wo^uE$WmUV4v7j%_GKjwYmAmq{oY6sQ17st;#mp|XKy zk}d7cDpD;Lp#87fwejv6+^nM`OB`|&$k@ZHU(}b> z08UH&C<@nJ`{EAZBOT+&;;D^LFIX8ofh1NE;3J>yKFrFaL;)_5bh-*si_9YHtF?#P zlI)N9-Ry1p{%&6R1zJV^BNiwTSkW;>?9Yy6ePJfkV5;k>o4;(|x#|A0veULF>P&0! z4^yP%{o(8j;=`xgAFkOOtis*~(=l`*?olzKHBUU95FC^IIeAid6`Zg7L{q;n0ih&U zSHJyy&C{rS`+3ViYQ9@lzyUBf2>qyW*GOJwhZ#s)w0N|1lus##SzmLLzFlPq)Zz06 z;t${sEF4TG=o7b<(fLic=d(RNFCXv%MZcn;gJtk&BRL>=AJiIs46!Do<7+E_rku#M zk1_&UI`BRuH1|a-KVoHH(~|E=jajAHjDmf{HJZGHEC62yyeHA_9pVPuOz9zBkd9 z70goqLe5x9h+2ww?U(ugoP&{NxY?vlC4Xt?LbC4%_{C3w8W-SM19~0_JagG3TwD$N zs@2J6;cl%~l`QeJIyT;F(wtz`_SYJ}r_}L%f`hf3v0|H5Pgf`RZ*CxSNQybatl21Z za|E7`i^m4RpvZ!j`KIe=JT4@QM1bG@Btb1ZPD4L;(H07}$^VFw2LtG4d)Ps~`w1id zsM(z0Tpdp!F$Q=BRc2-Hv-XtA()_Q+dPV0bkZVfQj#hr0SgnE+L6OCs`5r~470Q=r z+^RfgG=BRN z5#YZi*qiKZ#UFPIA7~M#bp%!D4oKqIseJ04lI67E-s2s(b%FP2js(f= zLgnN%tn@!HaM0!3(@kPp-E3+(>bK1ARB?CXq*1KGL5I?VAUBQde~;-BOOEoXfy&Cq z46$*prqovC;&RV$PERFcRvlh0)r?tp30%P#&(&AgC@*P92P<+px3_0(|eV(p;=3k_^tZ32?4qfl;i~;n6}4uz5c9 ze~exqH+rqWW55wK@JMnCuxw}q6m+utg_S?pPgzI<5Cr%-a>!=o<+tEXUqzvm-#$*` z4Z!a_sjb^Zt+R`E8&&r-pY`*WKH95G9vLXEZfR~p(qL`f_3du+-@VtE|CPcr0`tFs zW{~euWB%JRjQJ0b*^Xyo%eLS{EiKpE5fZU<5jwZp32He0(VeSFQwSvx1%1z7(tAcwo35Wn+52;1Fk*RA`=TV;U)A@HR4Bmd9 zk^g}eNqjm1c8~thAu|krXn~(U{O*6_56u&DTej{Gz5L~$@`v*9y9s4%G0ETwU+D7> zqbujebXO?Wzdm1L{xN82@hD>g*xAJok|05N{`gF5O8l&6ep0`Qnn&p#iiZ~Va!;~jG_Yzc^QU-b5A0Z`P`$B>)z zzzrg95V^~m0RwO+P_>E{2KYK_?WcWhudEu-1gsoB!{Bo^e9nPS9(>M4ON817PZ|dH zf1ad{x4`fDCfsHdP$yflk?}VEpE)GRUZLTx{%a(!fMN}x57y1AA3_x7rTbuY6mI2L z+(3uHl=b9_E&mBu?3*`;6CE^HY{y7#mt!>mg4>kPjwl07BjtNQjII_zNc?7>a26}y z`_ZYVZMc;An=25|yVIpQ4bUE(t6L>f#Bp;IyI43^%TWkLOEOzR&KS7E)tXhvnpgFG z-K$Ecu?PpaaIOaU;zxA(>e9%*6vt}&-B;@3=pQ=*Oel)vT$K;>G2wC3ttZob!W!6` z-!;HLc@TT|NV?}z%SIBVM*G6o>E?f?61SYD1TjGY>gqk6OM7Ml%MpNAPNX?swM;4e5#*^o zr?*e7+l9j3_fnF%=-0D#`&53$e`B9=+0*5>uAi_^VV!9WUNt+#KGm`7C+$6oDb{6CP-< zN#cI~{kGHd=pN*Q)7#Tte4rB(d!}LO{CC!c{tZy&3P!F2Y z*|CmSvc6FvS~RNF>1MVBZ=1z-!)oS(m7`j9TMSEDLAoW)ONKPS#+^C>#aa^Jt3>m? zPn`yVrLYn`5&(wuA^%dS(rgoZHzkjtZ$BX7my9BfgXiLWiOws)36qsHWrXtj=G$o| zC_|q{!58;qV!XRg?DU)ZjQ={6vNKH| zrSJ8uUyrlS)3crF+@;BOrlPmC$#}Uo3%z{K((V$NcwtDI0U}ya;0CCk*oGR+LpVF4 zONHf>1j}l6Kh7UFE$6th^RKS^38NH_=yY6}y!>BFU_`zAmh>s1_t!70=--{>Bu7@o z7#46)L}H#|nU2ipFU&B|tS}|yu^7`j#x9<#$pxR{?3_xbsok{rlT;8(kqYo_Eds^p zyLwU5wx%M#5#bcN^C>u2@7l_tMZW2)$*Wsac7ikBY42%-4T&J~g0cDAS&yV&@SwcLhWRr49O1M8^tkNO? z6UM68;v{3$>x+|&RofO*)d0s|PoAcce+um&dZgo8x5is%A+xukP_oHF^n*XDYy%-h+|q{Y`1{Og-4k&fT11FB>E5W#vSO z7pTVC{eiJGU9F>WwBmlXi}YJOYT%L?GOCr~DD`YC%^_x^ntGr&5lXXE^_jau)z zRSGcv0%r`%g zhzU!xUn0Ln0-^oy%QhJuul5C^>%I^c!C!*3$#yW#3x5yYcJbM@{VG?PjQ0kJX)uCb zJ1}=T&evP+*8>o&%Gu@wf!4ue%@go98egl}Hl92(px0Vy-7gex>n*VAQBC-OqM8nD zOsop(LT9eMVJ3UNk0Q@N`uVa^r=NVKK!?E3e{4icGlF|obSW8E%Arr;F7tvu z1lWOI$e&)Oj&D=vI&=6(ODUwG4}~-w;KcQ06-9-I_KRGgf$_m0f2F8RuVdOUvfodl z$l%W@GyfPex*(%{DRNCZd2a*(JfcxYS-vvX0C-BH?y)a-ItA0DnAP9P+{}cFUdT_f zk~4$OGmYpjdJ5>8U{qzssvI+jS&qQ~3qOxDotB0scw{;7NMcTY?r2I0$iacZz4jtn z=iU2LqP4U{osYjMu-p&2d~liQa_#fjf4E_@@C|;h6ZiH~I)Pj|R^Wo5TcF*LX%EOH zu6BEb-fsoZho5l8>`On@ObNHeDHwaARm89O5~um#%aQPeeQkTwEbZhI*PdE4+k*;z zQEN4;$Jv;8l;aKX-?kt*xlRQ8D?6uS&(0J*!f# z&*z{(8lM(O69D8FlD;?{6~OBoQbr_bjL1Al!Iv#0;ZL~-${eWwQQOVaO+KQTfTBOm zgiqEd;`{6kcyu%K;w;GVC{GbleG)d-&03?~t}sUN;rI;IxW?pw+L;z_k7Zh(mx03WN@43S?>imx2R1UmN}xWzCGA ze1CoXf{FN!i3^J18}oYuMHHdcxAoraNoeRhw&&P~;XRTT?uZ+5b0F;u1j$IsK{sPx zJlL{a9Hv^d``EWAki+--qTN$}Q_cO3w;lnHXpmmnX?SO zvNLwg@9%<4cU$2XGTvn!4nsH;<9gr@ejQVP)9cuW$M%Fjl&bKZY44=`p?;1w%D$VC zYD2wooBgp*Q4Bx!DL??J)QGtHG~?a$8tRT0FBn{RJa0jk{m(n!{h^($Z~Nh#x=+t} zx2qj4*!uQ&;unn3aD{*3{STuue&YQPMXhSdezoMJTJi-e`NCD=0PKaVu&Dd8GeR~s zWQ~`6(eY)hWIv8cc*@B*AApP}`MnNXU}}c%-7kd(#6vmp&=>KLEgrIRJV3KOe!(b! zN5D~bIyh_qNBHJ1Bo?x-s zK~QAJLk3aNv5hn3^VAPUEXU+rOUwcWsAO5m_dHB+vE)(mm_A5VVc7(1` z>d5-tyFS(6ko5<-tXF&&C5QiQ={N|}tN`1;0G~)RDr-#B@$G@^keAK2`e76T>|Q*y zsCRfQ)-QEj82-@|%nbi%4xP7hx@e?#!0(OkM12b`_@FqckO*)E-oJ}h{~t|ii7kW+ z=#>G`JH8dKM1X2CLKkAD{q*X=P{z3>w(z|+DL6o{+e&pqVOC-T9M1;e;ujPWC&)** z$0FP~zCouYKByBo#*B6ayR1+Gp6f7}jAOQT%)++~Sa|Mwj4wo?}`0nP!K2#X>+tKs7~c`&X;uEYVUco#m=Js#V#7CqNX%qbtrfVI)zt zx(>Hs#2WjNt{Z5=@4@(8Yf;yYqT93ZyN^2AB96nTjy2*Tnelk6vCt$AH&xf+ zQNz(CQ}KA&v5PUve;vv!>bmRj+k}v)>wNTN27S+_?;G%KM-IOv)mZpjwDp{hByq*) zgot5mGoLyQcgtGPfZD?;BLHMir=Rp--<&CGPuiaw5D4QYT(EZb(xW+x;sL&75gB^; zU0z(@0>R#(j{U(YNgY=14QgjlV8>Q2M=duN?58aU>R5chDlD!YK^uS1N71wxiO%{V zPVlLA=mp`3^=r|e($Nd*SiG-hgkG5|X9*|@eUem_W{;%vMJ$4lE8AHkA{*$jm-cFG zv_(^#T7`vN{$pxPd{8~E_54pB5fcYbhTK36D0Qz$4*rK)?Np^m+`hb3r5b_d5(z{= zO@fE1?^_A5T1$+w;a?;kbbykvz7C!A|EBYfE!v?v2s_ZPt4I13y(q--@6yNLLPye& zS(y$rxy~aFG|`RANDmbj;1vV>$|{7tvJUsZBBZA?Iph1by0=gJnFItQ0D`dz2y6sF zP6C20ZUKRKticfUv&MlGz8fkBeBUbGPdW}j^DFWy$q}PeGB;+{(QX$4F_c3&>L3T- zx5#)N914{@^&_gJAg8Aj`&gpQeG1Q@4ciqK9u=>QZ5u*EgIWgeb`hYhM7Ln4CWk}bcFan)6P|y;=T?@$j`Xr6O0>W=A;`ewh ziGz7HCU|}!!xv_-cLM4FCRi_7N$stzgB&@#$9n-U$(o_b@WK75hxu!j1L; zi|d#gbY|Nd7DC$EFYm(X&VD@dV)cu>wnFG=qp_5fr!V(xPf@EZ%WEan*-prm;yv=B zI?Gwcx85sJY?0T;S4HR*K3Ku|s9(&)cNaHgQwZ;^Vd&-M_N7^9kk9h2t3j$-+N8aJ zC3s#nE6W1C1D#RFd(S_E72{JI6R(v&TFvHJ>1-7*p9y86_x_QJZR#Zj-PKIas{ag2 z*8g}6;0`*&KiqUz=Ib}%fV~}^XH9)Q`lg8&{ZZ-|O5E|rz^;SgRx7;+=fElK?ZbFV zgvrbQb3Z{AD-k@dRh;;Y<{bo6>I9YJxHJb3lSbDjL2GZoeZ820?GoV&^`BA3AEZLe zi2ASILv!dX$Y`yuKW-Wr>;*p=13`wg0%tSh3y4!%p~6qmTB4vw?|roo>o*s!U|nYY z=Fx?f^$XI4t+_0#4yx~4v>WhZRee&&+`8iysJz&!mPj2{&|P{>qqSK!wS8*McpI)| zbGX%#xQT~b&2*zq!I0pxAK^=m)01j-iUsbh_{5|?$zo+@kVIh=RG%$cg7(`{=P3W_nIrb%JYX(hc1k%m=n?X4$ zfT~7;Xx48nt}N^n$TQD|ZUs7sP7UF?E2H>=^8vB?VLZc+vyE&QI|l4xgc$s{Vels$ zd5VrbaU}5pU;@Yr#-U*Eu3zQ2^KH6 zWS19hi5ykYJu}ISuk#WIRLXpm;N}!TJQ9TBFL5z!vbP<#Hcd5ERnBN%ixwyp0r4iy zep*h)&V-L=25Nf=OHn(X!3f>Tsb=G|SXXr$x8WhDKo+281Nn|cnMutuvIDbjzTVQ5 zQ?#%7`pn{{9CmiN-CSIMg7Tf6$k%**mdMi!@)TExPh|zm;k#F`v^pGjEXaHd7k>5$ zySn~!oIM#Q*bepT`r}xO(bm@Jd@GD>mocgt?MI$M9JaHw8Ha}13H9vycxtKNS^;{H zRL+dfFnI%hnP-Y<89>=H?3zeCbdYT>+C6+*Rrr9pvibd{DN>WqG#g(v3jF&YJ;)Du zo}L7x$jzNStz{VOa$m6?>=N0huV>nJpRGJJPTNPbl^+zBrO^qt=v1pex?mtISF!%; zfNEB3LHU`)cwshL3>6@g#oSHKx5+R}4H*!3m&( zWIGHUO;s2<8en_v4Nj8~8gO`lB+wg)9FYhE4UFu7y$P4=@F|CV=`mbE4~Oh;;$Sra zzk$zyj%>CKkH%-ajF}AVc>>CaSA!(*z79QT8QQT2RZ#BG* z-gb|sLzyoG(L-=@zVTGTnvfUnGC@nYE_GxVZ3%ao?aSN3Z5Gznk*Q0Kc_}2AnM9^Aw3PX;p{|Jc@%(&NGk)Rg*s9-sk{WzOeIN3%hN>b zP_{V2Gp)Mq{Go5DcLRG!oaW3&w-81Lpo)pUBC*yBky)srDMixOn`urweCepaYn zUMZN|cwGOj)odA>C8|{it4GTOqKS7*AS6s;{SLK~|8C~W&Q`L)c=+SMO;_S$R)#6# zSU*hSO^qll;UydApwI?r)DzzcsKLd`qKCuF{OVt6@1+V_VHC+Smay!KKmP0V_Pu)h zlleJD``M5(T5I2$)P6RFRHU{q^Jjjghef8h%TJ6KZ+=L$H(qaVG=DjgXb-jEe678Q zBSw1`dTqcoGU8f1Zfw-ruD>MPBlCh95^Rymi`#{N!lKsWk#=IJm?=uY$~lx}y~CU~ zeu;FEl(^4LyDt#s>w2H2e1S+x+!u;_;m5^@uw04xLLCWSp+4H1oB>=s zfi|7MjPeh>0HyB7QdKHdL3tDH6$|*9P6wZsl(?TL?z``Q_&UYDbYLIIu1WRPAG!(V zLUggyYNn$Qxoa~8WCr_5^mclDZ#-M=ya#WO+Lxe3nr#Qxx{IAa#`vOOj4wb1s7LXO zpOEksl^84mj~r+&Qd+O4H+bfl=zV{9gdqll!B}@nI&~KTtF;+xx9i)5X4+8z;vRh6z?v+p&tx7~E^S{jt-bcWw{f{?BZ_;4Qy z!sj$&98zRo0If$@C^QOcc}_TT`f8hj&Ej2?P6aD*%ke=^QTpA5iBk+P2RlKKW3X-# z^gkr4m3aJ!+siK~GoiRY5#8EnLX|ZpsMCQeG%q>|^Un3}P`}iwLDu$p{9gX$BopbG zn8hlx`Iw8e_hK&@w&Lvd^akKvbmaBJ?`joCz@rI{nz6vKWI7O z%c0ek6BTcwlieO4UqICae?W?80?F$ulX@F#FwO|Bq0m+f`mftqppjL zs0Bdgq^!8x$9KBKD*b)o=*%)68|&fKN$X+#AqOoO-{NjK6MASHi_NHO4}i6z`C4;R znYp=f96V`WF&@61=hS_6vWXrv(F6X>SmGsjvPPeEO4Bv2F2zX!5%nZV%x3YOan@iKuv4a>ZI%L|L%EUitBuW-e<_s+w_o z!*LwEB{Rsr?b>Q@#8X^A2EU%Iz#(?ME283}B+0wLzb(y1`C^4 zAa!1~Gjw6y51FAe>((KewuT&a$BXR^bx^YIcwO*!9oA7xFaZb`cv$gRRO3;~ z=L1EEEa6Jn8qCrh3^anoBoCm;%Ezy#cVt_{klN|dB-~rP1Uv2KF7XO&^)b8^i zAavxQU7F%iM-k*ftDpbNg?pB2O#Er_1|B|4B%K)^yC35ULJo}jer^Z#|4DpAuZO`y z>Rx~sCmtusYamZ`iI;nuE89W$82TmY9(Yq>;VXey z=#_BCv=>33Sj*})PsN!O*kQugycJ=G&ur95G+P@;Ok7X1MDi{fmPSxH~J=Udeq0mCaE5y zx~tX4P)b@fGMHZHzgW;-yq^PYNuFZaXLp$aOI zu@~>5kaLslTb0zU!8PWNVYubvbjeuGLkWheYHM%#4Z!>WeBAIk`HFbwZ({v?F=_oI zC4>A>bco)LqE^*}j_z^jP*TS^_(%a`jjqJm8!#eQQ{?OoUn7_J>~4%&Cv9$g4jnft z>1rI`bhnn96;sk{!i652UBqn{1KF?ZrS{U$Hc&TdqyxY|D?kbq?*{3x>e(@8 zihsK|J(?F@Y1#~2g69GQQ-QoJRZPy9Vak#-IsL|%X%8th?w&>9lZgJ)=rh`_1e zfVH&adza}VseTx_t^eu4{~HhpoA6;zo?k>*`$am!(9WrQe{sxlza)-%!v{OYSuWJ7R^b0s@an7=yIx!ouLk?W)m#9 zX<(9tFCR|fk%U9tahqz$Md@-opF8|CSf^bJGgGo__~_^nA8fC{$Ypy^hmlu)nS_zN zWQ?po4Mtv&$QrkX3t!|P5t4Q*ND~<+8=%8UM6q@|m$S_IDwAF@TZ0MddA ztG|vk3dC3NdKmNE=rRn3@vTK3&Q7rJiVm+K$Ka7?n?PoT&mi~=hR+cAio^1_)bIB2~RmC9!0OW?&@{-CBS1_{w`^Oh$P&#lic5qwxle& zwbFNQ`o@)`J$kJ)AIjjT8a{L3^E>#2;8PEuIq=cf%A>)2KCh5AnFj~(k-w#to1`za zbMOb{)CUHBXn)@rfMo2MX7L&a8Dnbg5ma63-=Mp!I`nD&5*P8q_J(uOP<*c?%N{w5 zyp=qBZ{^`ZSZJU;@@%C&g8MO8Nq*6m<|&sI?QZrJx;?V;(o9^u_*EN07sI#8gV6T| zX~4`^5EC!oEi~gxnc0;5Xal9Fi|I$`*6MQS7}UX@zekdElORZ3qtL2ZQjh%`0gPts z+G|AJ3!Q`TL=6cYmOINch~JgLj}P+22ep89S~a_V1ELayP~f4)O)@uVZ3Y;)Lo5lK$+mx|CBE1x`N5x_@Kom zbdjh8Sn!MI%{-jZcG!wd+?cEh`@to4Q8w-4{#ZZK_Y;cCKj$sjE*u z{5lG!m`O|w{HBLb;MR)~HJ3=#{1mPE4x4Bm z)_8bsYbudqCDd#Oy$D72@<)1O4y#C^)%=X;luXr^iLof-EX+$z@d@Y@Z=M1jpWU#< z{vbgn`WvXbS_<_drcF&Yv%6s_&-)^ z5mktnlr+y42g`_bqwed)JYIBv2prY$NHopW%( z#Nd2CNNn-iyZ;Yq?*kZBaqW-qZZ^r1Y{&u&1PK~-(Nv;MP4ER1+C)Q|));p;VHYJN z)biGCq!n=&(IRHqB;@X8k?&8WwB_|dwXNUkx8=3=`^6S9AxMH+AEH)$*nX+cUwhNU z7R4eUvcK~=Gk5pyZt%U|d+6TWJAcm1oH=vm%$YN1mc}u)Y;aveal!aK7nZuUe{z~> z0loxf1{PaP;b{T2*rWYMERX|A{`ic*Vyh`!q|WwgFNjbjpU8z~mf%2RHI|yI4mVai zbClYq=*aZwuoXADoKz@!!*_`+OVl$fwADN}cT!Ui5@N=SSjnQTTP~ON*m^7K(%A=E zgmcPJ*?O5Vdi~vIxAx~wwrw~~3%M@Wr^};*IU;Qr&sZ{}z&FvYHP+(F9iVBO=Ehvy zXJj>uHyNKFYj@>Qd_H}PwC(h_(Uq5xocEi2wDS8P)Z$mqNd+`fK-b5weg%#hxHCW+ zGU|#Ku8^(QJzjkLAFGD1f zI#G^}A;UdlM2|j0y&YJH*#a{ltt^IC!W)mEG6EgH0 z>d;7i7y}_Sp46sry2f;*iBs?>k@tG`9VZO0%1Rj=n31$0gO;-|p==C?>YjbqDlesL z3I|4-9$GgeIyk-Cq%=Ly4F++GnI1FPz9>3u5vNf+I2l>YEMd7(-iS`{0UlJtvDD{} zSLa~2Gef1r5U!Vqd9LQ>$-Vr_<`uboXET9aVF+PktOGYz~`1eq=X;9 z%9SX^r7j8g9SgU>=q!ALQZwEO6fiDuzY|aa3^aK7JdK~2*l)FMZ~^@mcCCH_C$7(` zW5I)Kb)@*QgNz}ieF3eR7TC0>K4xu2bs(Cs-A_^h_0$4~>LUtT;2d9|HrXf@1=}gu zsrnogT%tBPDX?^$dOl&j|5`oIt$d)Vftc*AL?^o;Al`rqchVagHuh~Sf~c6{&2O^A z)=kr|Fq8bQ*R5TT!}p^!&o)g_&wV#%wA(b}97p;++N@+;K~~(km-M*8thhfU;%1yf>y-@)oMUHk4*swWE#uU&JT&a~BrtOpu*JzZ zOIFab0HHNIhiBhBy!^jz?%ev%ImIQ730SerUTc~Ut> zQ#sx`Z_I%St?CGJ#9D1*`_3nXuXGyi;^NL+c?hraVIQn6EXwsX94RAT1Pn`~$oP3E zRxyEAV%~05&CxL{FYc?cn@LQ!l9}2x7=}iMkvj6p-m7UfyXAj{{`zXO>5khICld1!!Se2E$h+@e z0o%GC*&Ncl#eQtX`DQCkMQpCBEJQ#+X_`X6!m2@>@@bl;H03HyGiZ*Tmq^g}WlGcK zN&!QG?nQW@NL$ck$HwZg0>` z&_^0BM>h<3tlE#><3$LqV8fRM)TzO3l+&YK_C9JlE0{>+n7rD(Tr-DT({hDn7Nj&j zSrUkDoMwu5P74)wbqZ-;tdyK2C?cp(4}y;~R5UFRSCgTpZT^uasBKK>P&bWKw}-1a z&}!9kseWp4^zdw|q%t+2`iV*diqDGL=5TG@+PxE~Z6VjzqYY2U+TNHecVT!%N7a?M z59bSsaMr$spbS3MujA9nZy1dbqs>?E{w?VK0wRM^_;R4)bZJ=YTGlz=mETJh$450FE zueO@2=o3}UvW~+2unpW9Hm)wnjTT6K$Jp(UohmekFV6PRlw|n`kn9Y}NeQ{6%;h-b zZ{7>rn^;O~fH7Kv+2}Wgeg*U^q@SIBMd6|qyyM7n9}_-&u2|tRM7?!}ukVOI{0(e- z9>B1yeWkefSM)cj5>-zMrD&Cb9F-N93qCfIlSovZ)+sWlE1)cyN8DGzeCceDSNq!^g~ttN-|28Z zl`V?yN@gPbWZnRsWv?dr>BYtv`kMOlUFiWNt3S1uE|F$(Z1fqP&KZIxK3^#m5@{Cy zk%@^MHbgU&s`AvK?ss7W0Ea9Bi#ARR<*Vz8s9mSjd295VC0>L4`6m;rD$hezdHRqg z)Cr5)__t=em-@BeGncUwD?mpY%h-5%Um|o(S_5BO>c<|PwvUZzaRw+~o#p1O%ki1A zz;XNOLp`B<$y;K*T*nnpnnP|`1$`6IbwLpU7^^UCgS&1gn^zMt&;Oe=^$nNs>;UTo zDhtL@>MQPq*E&8b;qkIX)IwY>27DRxL9Bmw-d~?^^_3ANK-+Fmz6(9O)W7FvY2gd_ zS(wyJ4sSd0ipepD;QYJ%Yy8bHypK`*-{|*u`h7w_vkcFde~S!h)7JA;U)kC5^>d8< zEjxN%vZD=CGsO`S*l~`dE7RZCe-EBB9UjX!y^wFN_zP3P62Eq44puYI?uL!c#)7J2 zN|QrrqO~-wi<+)dW(O2MeKa`-no8);9HpsLX}W@9XVElNCJY{ilQK<~Jafx|OnF9@ z|HCmZze;U#M9)}5Ge}+xO(p7l5xZhPnuD2yxu(uZlSue};4xtw zjuL_=o=6UXCQJd-WC+kACq!`of0Br13r&>S;Ui5~uvnnlsMXGqCRTM5YSfv7F!T47 zat>u7zC^yH$t>|}7dHDo(0(a5oExC~phPL!gxfi=ck#NFjSj8vS3>GjTj#`ld|1yDZz_QO@-sXi^$vz^ z)Q-;N+D+|B?q9gXL^y}XzZZb&1R$wRmPvS*PrODaoNNZCJ^p8bkAD!B94_o@E`W+C zy1`XpD(=4w;a|2O35@56SAhn(PmB9-fI?mED#v!#X|TsP;;jX$MKKF=DH14MqOJ=F zaktH-wh|7jj?seMe~H@@9Vzt^C)5V7OQP>z7}HJ8rEcxPe-Wr4QV*c?9UKKer08YP zy(BO0ebM#4Qe*FHKXLM|Y6+1FxD*W>iLw=9Y6qIJ(Zi=AzWN+1pi6|0urhU)`U>UC z<&BGy93H^Nyc8!kHA)z*GBj;GH2;Z5)(wWSz^{^ylfvX2xdLeZ-$MF)MT3`$^aI8? ziX=VBYbXC-(PbY9m3av-)JmjpyVb5T^ak#J3Ggva9@n|WeQdqb;VK2a^PMiN3UYMk zXeTd7t#)zm4>()Bbqf2V4%EJVzeRnC&%`OsQX?5(KTUnrEf=vcj1GZ*OU?qJ6t7u6Me`3OH!nR z4>5-RQ(|PQ#mb5+#5kHnj4aEP|F*qD@?ZTs|FIZZ@R?#{3QT-y0f~`MzL_OPmSu>M zY2)e4yNtUjjJk|TCVOBB3DWu2Y5z^Td^OE@pEsMU#?y_D+s zCqvg`YXf^U_E-xMJ@F_MH_$p4{6MwEeFaKu0nYd^6S44O_9m-3E8(>Z0-^bc#ED7j zFda}U1B;sG=*6B&FZOmE?hVi~upu?i*l3C&@}Cu0yxW4QhG>VTngX+Aa5lGxYJvGi zbN!shAgq^MFgtt?+9DyLl!?I4zz^5W_8E1{7p8cQ&S7fb($8pMbs7-$+BJF?CfIfn8&}+rj7p` z7-0odeltmVnkAIa^7^=)1@`e=9#*oZWjz~9a>AV#Yx6&3w7IE(#6wKwGuiz@=+a5s zyga+b%k}og8s%|sJFEx%THRjZs$~)ag0y`x0)*}5v~z5G$yShMy43w&qvxwoBZry? zuL8GOplMWMh2!kZ;C%mPd`uQ|T0fzO40Rv?h z0jaMytdp)^{_F5;S?d=VRp%*9mVu^A2Abw-cl@5azQq6R95MJdmeSbMt}HT{(w8Pl zeqJtev;@>VNIt5vzps`_k--=;R%l`q@%lX*6AGS6nx<-d2N zgPbOd!BvrL?Sf!s2Yemo{7@H)=Ij&e8H-wU2j&$EAfZ z7w{E=?AB)d2%-p|=}~7M`nB-RaIo)K=o(lA)}9R6)ls!R4-!r1?ZdSnhV5!=UZ=uE z-af4Q@)S=VML^orHZ%NiZs!UXmh)I!3Sk#B`f9@I`^nE(>m|KM!Zp105!I%JO2J^J z5o2&`(>^clVJ;ajpnjS?Zl&ie?$u=WwixWniDbH0E%gs{&P~iLg(VerIaUkUce#WX z4X=5G$xOX8nb~{=AeW0p&T_708hwuBJ&Dsp{V=o_men?;AIc7`2o4`VTmS#_wDt0c z8KA~+s~@M=Zn5#g#u^<>4Ey}iR}$L)q>yHse(t|3;p$s`!o(Kl-8uBL1Swm6Fvuoi zgBW=yF(4M>6dn1jaDwKR zkKc+Ma)|@JdSTOO4Ts`ZBxBU4Iq$QLCTU2CBQU3);%^~7=sp;pQV*bYSYo>)35zMm zRx2(q;&EyS*w@TxmdC|_Ay7#XtVUV}r3Fq6DK2Y&Huob*^^07^i$ zzfa73T3B}1NJsRQF>$($Mu&sTjz8mqsVLk)R2}J}Rq|s)o$64k3HrJ;8IZzPo3HA) z`hn8nvT5JXWn`5`58Hj(r7eu8W_iS9xyU-KqiL$Zk{;~;4D7^P?a*Gdc@;Ca9qqd` z#{_Lh8Ju{iJAkyvIp8ZUj-|~#<`$$Bc^7zsWfdXlAP_|38vt&wFoLE4L5_hA*Nr-o zxArnsxx1a@ivwSxKZqHG z9m%fOqqcCNZM^r3z9xD0D^_oSN_Dc==OQz_A8+Nc(e5gVoJCi6=gmFh72_Z>R6gYz zK4UBiy*{$RRf=5U8v@juW#NUfcGnfC=#^N1%^%nyYAa6*Y|W}|V&*D>lREN%&m+L0eODZT4e=dX@Y^xV!{{S|)rx#c6-W`z)3yVBl!EYBGQc+Zz~&`X zDYnYT3S6SI>X^i?YQ(PMv+Bp4QIBB*f}zcjC>BvVTXD2WwxV7OOwC0%S1@`dLurc) zov~eGqD6S(4V<+6I-+P4B1v)IQj9*rXGL)z6hnBuy10)wEtnBuL`Kg|Qi0UyZnUs} zGcmmPyJ~o_69aS6IBN!nXn6O!I_Skre^=07$G|RErx{BL^Z?%(suNUM?Z37WEhU+$5hLy-M!bnPXa#W< z=;vzcyw45v?~?s=4N;Kjvldr{Bq|7ig34-#C4q(JR2}P*eONU}-N$FM89zz&ll&I) zG_I^|ghLQ_H!j_Bc-8-r;&ep*#N;9=CKoyABuseaAP_DX(ss!9jPiXu9fdpvexA<) z**42VL7(s9ou_3KIg&dnZM+|U895Fi$M7D*yOa;TK`ZPlcK?Cq<@tC`_jeqb*lxms zu4m^bbqH0bxwCCJSBXff?0%Ctxb;s`)7TuktGT%E5%FcmQoBT0?}a~qAXlnmB=1FQxJ9>uw>@H;{arhP%i7d z43KpBA0iq2jN46d$4n0W_Z`D8+5hFw zSse9*mB;ZCzD}#9s=FWGOQ5yg3#hkSuwDM+$7ni;9HfVR0!|jRaGl)ht@x=L*C*|Z%|M$Na@Cg z%(x~E=VsKC0x+dK9WJXg7jJqLsa#!L(=Usf!Z8C>gu^!uuPqL0om|oa5vO-zdN)7A zJ)|@d$tJjf@TGtaX+&L&$t3ZnoBj{(B3NTEi(<$f0`jZ>gCS2269ROTBYb7gVt^%> zd~1dgrX4W(Qga_Pwsx;uyKRZdB-?4@l3riICEX=TqE#i1jN{q_aWtp2+vW}S+TTBu zoJ2(Zmr4;8+oSudj;Pn~J9)t3ShVJRcuGL6 z3DiDl4LPENeW&AArK>Y;eL*{blPf|uRCU^~{UV{?=6SV5 z`r13y+nDh3iSUjJQYjTR=HXX$gv(Uj=lhO@^VkC2P^2b?s8fkozk#xRS{b@9A4{Mn zYe2n?cVIb@VSJ!H`iUX++^MH%8Q7)VWLIvIr)=c-u-D}Z4`QYMwU^LB8?|h*QZ?WE z8e=T{h#VjLL5e=7y3ww7I^s=M^q1QM50KjBH)C|D!gF8rlSIhYy-K)lRraYCTMkM(tE`}U#DT2{HjWE6~ z630CfZ*om&{;$hjPFc!CmLZXak0mDmW%I-I{@(U=asDkX`+Gx@AKobHWGUX%2Epd9 zpuv521p?2Js zteGK!Ud46gtKM!LF5dKe`WrlRCvLa-^AFjixBfIbs@8u-?{1k;4&_HHA8nK`TEpgIfu84Qq|V7z9XT_ zCdE#?-IC)?yh_-VRh}BOao!SRbJCXwQXeYp>epKjta=_s2B&`9)fvj2I~aW{kvh#} z=wCi0T9=zP(Uq)X>^!Z?j-By|WKW&?V9H%v6MRSXO23*q8C!;!@h5b{X&6b{a!6Q!uF%MX2p+Efb+n+tS49?b*aE%I@OAPsF$_a1n|Au9H3IhrkRZeH;RI<5C!kio)@w!RCavugNC%UDjfS`k~3K;qe)~O zQv|7PEbU8#uTfuNGK-9X;?%`&(evZ6B+0c{a@3h84#4oZKmhVh`@B8MbbzdN{^GK@E+0F(;=egR<5d)$=Jb<~8bs3})_yjXd+abq0g zv-Oec37%O6x-a8wcG){OT@Z)WZ=}B|WW6lN_V2Re213D6HgoHeS1g=`B30_iOV;}T3Y$|2d&M)##KI)To6HK}; zw-YoVGG00$1w|O7TTLW?f8~_P@k9EZqTk$)OtjR3>~~GkbJwpO?}}cy zzB4>4$@ZE#@8!aW_ny77;&YR}YY@VE+FaDpB-XUt%5B_CffUN)FYdd=jQft}3K#V7 zNA)<6qyr6?Xy5xVxj;!=Dh?q7YSkb!)yL~;ire4gok@YZ_wHgT;qrdQ9jy{%<7mK5J)Db9 zpte=6yF!<7NNyE5{?@0jD`XD%K71S)@nSv;?mm+tGe5qXM`ZYOI;dHC9kvUI|J0XJ z2jOH;$2Rm+><4Y8uws?fGe-^~ba*!t+F{=q@6XW>z}2 zwZ*r%j^drVd4urjSlWi^Vp;GWuzXkz5ErRj%;aLFmNUsp9ix+)?Mce9#l15L{-O@J zBfJ7{Ji?3nKA+E;3-@A^173~pPlyZKz953z7JoOr{iBC1^POW~fbr$b4aoCaaqoW0!=CsUhbLH52Nl%hAwj4TMLy|_+n&F>7 z90`txT&vU}Dg}oE(~cswP@M&Ik2`S;6YG{-g1)c^l{{74JDVyQYj@p&gahraI(4QA z)GN+%zWdKgi>pSNhr|j;X!n<}im!&`Ld-c|B4B$4B$8hGl<(JG20d&C)3RfJY3^8l~sj}I&Ssr_&^ z-1rsu-fLwSrhrH*E0o@4O$iNCgY`@=t0ID4z&UG&Ltjw0xS-%tx4WKW6)Mrl*UYRK z{RWfBx9BY>NTg(Jsx|3DbD6ul&?Eg+xU{KLm>rG1Pos2ChX4($)2~s=PS9J20AU|{ ziS?gSL0(TW_4Kz9l4FaP9_?)ee^qy(TU)?R&75Q31IT@{ldd|SNKg%L$3lcjhv}D~ zb<^7_os#cDmf&+D%PHI-FS4LQoH{^nD@AI@81CfQvs$Kpfl^a~uTg?dcu4IK5}kc) z2BkWHIY-T-wmBzjTlBCsa-o@$Y&bslo`pxjvOx4~PI2@e)M1EaYt`DfUpD4;3iSv& z`Bhr-dL);3U8vT_MrHcXrPBAMrFW!(e_bX&caBH>a`C-Q~!Y7qOKT%aIXx5pbi9|V0_9~KT+C{3XDrBKzL?GoTI zVaj`_3e;B}A&T8TgflS#ud(Z%rc`@&$}ImZSc%AD?2LXy6fxwNXr(|^tvVJxGYyq% zE8c$4i#w861ufHXW%a87yOcBRk{M2%6&YqwS|Yc#UN<{`Xm@o3SKT8 zD)fY`&`-`X!bFAe;x!Ty#Ev~ra?;SHDtHDVU?wmHu&cai!YUzCt3^-Cy8K4yx>p7O z|7T(;aVJ-ZiPX&vaEw9oyl1bhMwzI_GQmDY?~RA|JR_scXSwS-F-qlvWZVzF19Oz( z=({8k>$EZI)Oy~r#seNHB+<3x}r<*Og!VJ>{@vxZ1ce7$i1*x)J~zf;e3 zyDqWpqrBq{ItASn+|G3J&IVxybG;t%x!@X(7?u%p48^-e@lSG;oo197!ZH7i!=W61 z;&(a-=%s`lKx<7WLkn{jhxY#IM1o^Ra-Wt$YVB~ia8F2dmnCsjErQJDN&K#Jg)$GX zUA(&{<&JHmXHAZ`=y&Bglfy^9Pw3bDiOKO(`jwwIIlf1~_vu&msmakwzYzT%r{6L9 z)m|`>lq7!F%in7HeTRPEqPVY{%nprUpP}C=3Y$*fmGtvdoaKVh;YTL6n1%o4T@ax^ zsb9Lba0TBIyoCiy>-UMtVf6Uar(Ms0*;#MKrP6!xTHQm^@ovnnf3oxr29yJ3f6I3a z{J=#|Wvi2(p#?MnV42*#D&9Yz0=#bJXC?Gk*vSym1CbwJLEj^Z@y}5~GU<*O1$n&6 z&q^mrdL}`IqDFzLBle!|Rk2Zca|%q^ipbawJk@7hPhux~=HPAl4xd{$%Gu(A)EAqH zUR5Ownj`uCwJoke)@<2(&cTn#2AY1>2S}!Tm=Z*=)_U3nRpr_xOU3zRkDsk~+T6Zi zV>hqe?tCz*pD3%dt}T@%$oox8MWV&*n9HucF%`!fNP;e0!B;yovej#OZPAVeTI5rR zi(Z;|x0qmhAjD4pSjczv!mk-@0)dmk) z^a-&?g$oRaxIO@_+!3e6FL zgy@00D{8o+hCVBc9DLH)XCQ;+;mfkRZFe_!Tj6@{w#cDsvECKk0S~x~(Hq5^(0x@$ zRAJJi@Nx@x4)Jn>UhG^lwsxCPter}jsuoa^3Q@trxr1uKe2K0} ztAdp@bwDAQ|LQfDLXb%D5J>m=e_Myh6P2>d}EU}sZenTD7Ea7cs! zn-Ob3whDG5s8#_2YM5!X;IOYSFhR^zZYM(OggEGAe5W-*4sE#x?w)F}GwHDz?M%W8 zvRY)nn_FZOE#k9@dX*dHt=oDtW&27q+E*&uS7vA**5OH;7<)<~lvP)wO-%29RM&b@ z*Y>cnuBEcBc3IcbWS5AlYD){)a4cU>+N;+TLlm1zG)&#R4e18L?Mc;@qdRXB)s?Qa z3Z*Np%Cl-461Dv?UlwY=eo&TAqQF#REz|Yy1ZmFWSOo9ELdo^<Ow z12d!97)+Mt=X%g1ENc=8Wg#@b3TrKuYoYNCUmxAznx4?R%mQ`oYMzvyyie#vaPBJ4 zq~AV|#YFeQujmaTM6vAVTMi{M?%H)T>ncv=)UR}@EZxi?AlyaI`+_<%Bv zWe&X(lkVTKr(>~+r*HN6gRXCKKM&r^{pHiHmgnGMtZ-RU3;WS(Y$AXE-t>KP6`r&j zT`t8}Dz?yYP_wB_`J&b^UvzOI6iV*7jS7nL-D}ulE0x=8Jp0)^!5-rlTewEYMfwK* zDnUj?_a-;+?-Y*jlSULHP2hM!%>2*)P>BQS&JXJ0Frjk z9ZWKBW_zg#b5^${_q~h>Gh6rT7IoiqPe$GOst+c)Z2hlQ+i zVl_5k<1L3!aeeem{f3jt*jN$LAMQc4`NGfuf66!-LnwusW)d3|lFN5HK7+#_`j0rg z^IP1wL*Ghrc&Fs>)(q9Mqz`W2LSedEzq^?=+Qq%!F|jFIiCH?16fKN%Lwe4d!w()N z8baa=qdzpXNvgl&`jiEMo@EU4XK<#`bk3A5;kZScPJUBLIEH4(`7|tSMy~~-qrAS; zAxNwkF>bAdk00Phhn&NCChqTx$Ok;}@ZoHMd$#pW@>iOB-N6-Tc#Yj#ZD9Dfyw5QD6lAOKf;W79V%$Sd*yyFz|jxThF93L!xit)i>LdJ%J zDKg~X%^8C%lRYr@i@Fc2mbB9;QH?X^HdE-YDhq`qEBJ-MJMrJ=*F6Wd@EUs3R0V(k zfyYD7@p=rO2XhVSjOp3&s$S-;4QBDGKvO?aT-1&t7xq zWaO&TE7qp4m#fn0J8Km2HlO)3Mp8@qNXn+VlL8wL-YwY#uwXUw!ZB5`Jx_M&!@ZZ-PTrhJh=Cce1|d*3AI~Gb#syuW*moe4=&Gl*Vo<{^PHPsG6=aDvYgNoh-)_%xA#+f4obi9JtneIEJ;-)Eg_iC!Sd#3!~Js|M+- z__4vqku&T3Qj7-1(f|$-VY)5BbX&3ys*b87fki=k_>x66;aR=MLivlQ_?=d4X3&^FYMMYISuDrKggHB@zugpl>)d5tvV8G zCNfY8GW^5vc<%opQ_<@~wFberF1Tgv8l zQc@_the_d{Z%77|l9bs#MP0aF?EKGre7!CK712T@Psl*ce9cMcaAZC{&n6OQwS_Wh zTbr-ybk%X~SK_|LE26wFmk7_%{{3}6^}`#t;oQ#a2bT}C1+DgPpCl5*%5KmioCjPb zG>r%xL`JK$na|M6c(Gc9A;|$4j<^zs_t1$k&SD&7Z8pb-JBh%!?vaT~DKykEFAe9< zr$YblcrK1(m5D~(ht05F7EZAX+jknglIG~*?Lvd@6|A1txaCSUD@c<@;cm8?yu=gi zC0?53`<;_8(`^FpAKxXIsaV@pN@iMy<9R93Qpy}1BFmw>SRY(L*(8VMY};_PIa6}g zaUy&6dyL)F&;xvf)?!qpP1MioX=@9f&%egxOT1Y-9G)wV&p`LqZFO^0`vgaY7OT*t zLfO#n5+W-J+hXMqc^A)|A)HrdhovHzUb{MThS+6(mvA30jnq8epdI$S+xEhq7q1lJ zK*&Z8aflEnLRNE#Q-qWtv0YF$o`}BRBDF zNXjPMhO{oPiwBhOZ)Zz>6G5$OfD!1@_*bV2-Tnpj?daj@(V^+;=bM!U>OEHFZmW8a zO}X2q-eXtpwg=RQX>fhp5q<+_P2iYiMW8PcP;RoXD}!B^IuegTc_@5Ms+UF&TLQ|Q z=#Zs3{6RqZHT-yVb?!AM&sWp@27f*?&tddi!glSJK@cwj4Rc&s5N8;~95-XqIqoog z{qsZzr}t=jt~D=h!h_=U)_htQHzXCO_prFGtm2_lE<`P>7;JE4QKILdb&p8exk|Un zER{(`{UJG8Az4v1tY-bD*MN#^uAzO&RpI9{Uv0KZvRU;R&HBaHFVd{JdXDMbEVnlB^~_co=N~x!1Z%X@-^c~_xDE$E7N6E* zg8}frJufUIBZrU@w+vb@zJ@_FGuAN9ZfmYBFMSO&Td(56q}pkX#W6ll_Z4=j9zRoZ zLB|?y^MO0{B~D-wmCmw@HLXFIzl7WPX>fe#flJGMyk%@3CJ|KJFD07kUt10nIX{~E zm`Ku#OVnT;)|W4p2E$z>HV$`@_@?W-;1G?k^4sqME+Yvpty&egghB?lvOb~I3geMp z{)_X&+6RnCr?`|6P=*B&Ji|E_TM3P8r$;Wp+F@Pp0sM)7t8kn`z+ou_f1bmczopW{ z_gj#>j)z@3vZe;#T7%84onMnG0I^rVML}!@3CBdm0?I8`^%ZqUsa5XFryB4Dr{69d zXv>p^7TqS|KR8!+>WMv4Aa^bnr^L8pxu@q2dbzWg=Gv))+di{{pU^wlIcW!nLi=zimBWIbiDA%C0%Nr^k0?WI87 zR%Mp@cWJ<}!F5IQ{_Uz`!hg{sTIH`>1O;Lp03ED4A{h0Vn7v%Bjt>3Vw%`mq9*=LR ztCS`%H&MRYcGo3qk1odop_@+xR}`2`+$*d)3r;V4>qM|FtkwO#fB*sSOPeLZQHt4Uf(@_{+A zk`&14z9}+P!qbTXC6f?w@4b?Ung!30RqO0F(? z%>O<;uBxWT)t~U~@6bKtA{n@+M4rkrlyO^bY|cQ3_4@j+M9<`HIJFy%Ao^>kQtEQn z&ZXwvKxBJ8jpyLtT4=Jq%vW|etByhBjc?&CO+po+yRQ3EFTt&c%dEuA32>!+99=>8 z5;&#TwcRXsX?F_MP>Ia0Y({ba{Y}1W!WP6$pH-(5uYI}p)3r~J!M(dW?<0crTwOWanv~N3v*igZC$Bq*>UfmZ zE?43;SV=A-f~|*{+#0KDa{J;1mh=i3HK* zx?b8%9n*ItbS15WxEP!Yo$oLu61gW6?2qRZh?x&I&^ov8v~Z9XIRwfb7We1ysi=~w z_YWMp2Re|vsw3jOSnTC)i#MkE+oetRr=Jq3ZJLMj`8NyrL z3xgD{l)i8Xe{etSYUXphxP_{@PK?;~@g-N&XNN=Zo)G*4256{5Lytq)Pr_ z_%8ltcYtMZ!=@IyJwEL(zZ886&pEeXMWg;!^;s8;Muu2I6-Jz6d9|rj#~pa1(eyip7g8HzgZRBTM83_EnJm)31!$C9kJF9VPmd%%en+x zVU{d-A*#6oixZ}Gm#L$Nm$+^aiIrQ+;+{{3&e_rKe(PRZWBZg6-E-B-o(h?nX5zDIZdD+>$V2X*En&4i= zeS7#5%pq2^TM%4n&sny5+It@p^e@=+f<1b{5{4a_BYu-PUj4=>dU`Zo_XbF6=#TRj zj51~Cj1K)VM}4)KXGf-6!S!K4T4z1=1aZXReavf?3x^J=>&UeSO!Alv4V}ItQV!$s zLmZ?>5T|wRE9w%PJ6L)j_Mm2qs*V3zQZ7M1DfsQD?C-#)&F6KZkWY6SwW4x;9LiWP zuhGA?TZV)a%FV(+4ywmnf;*u|`tx1-0nNg0lRB#1YZ5n{a_r;q0j?cNCMoVVQ<7H1 zzzg_r)u8yB^dT8YQ5xJzL%Y(j zOljy)8dfR|tCWVI(y&@-SfezAl!o<6!v-Y+a~35sz|US&mcH9izvA9oE!dS_yqD@2 zbgqXE?@gu2D&m75-7f=d>Q)XoaX;+vaGF}(!2vH*fENJ{ndKRgMW%lO>6Ip&TM_98 zkX~sjL6%aPWldU^Wg<&iGE1Gv;zE{knWa1}i%n#yNM@N>$5|?orCMfrd7UxK)9W}( zO)|?Ck);k<>SdPIX<6Dumd0e3dXc3WSz2TkS6UXk$l^|BITPkA?Z~oBW;qcyW*H50 zmX2hWr$v^P$g)ai*_M_iB(emPS(b?`tC3}m%u=70#U-+Yl38pb%X(zlAhS$_MDO>5 zo`SE_m&ol&=Gq@Zu71!M(hV?28D{$0#`G1wHdwwM%;OnelZxRODxr~cKMd}9G{T(} z1spz~NQj~2@dg{A#XIqRXz?1e{10ewCO$UHq;F(BYkH4TUzPk0Zd+h>Xgg^T-#(m* zKW)+DBNN+L6-}dhFGh9KO6Da^9Xzr-En;BcvU-|Yt$ugV%#!tah!=~|kl;HHVw0WP z)6@|z2p)Yvv5FOZDIh}!p{zrQ^P<2BB&e6{o@e#MP%-&R{o=ub#(Eu}x-6o-WaYO9O> zbg8Z7^kVgB4>EV2AmYVP5tx0xtBCmiJPEWG$e_WY8e}U4qO=6?ZN#ha3 z%r(xJHBL=qdse;&dzhBKL7zX2o2)ydhgzU1hJhRW$&y5DW!cF39&4KNx;O;^vQq#y z+Pq>Xs5__I++9ZLEOLi1JVyvr!Rl{=D;zShEjQ;*nZi1|FU6vpO_H%REu-~ZV&(}m zZ-RmjD5y@RnSm(8It?l2TeT1+hpm?(-ep7C2+JJ*yxpj*BpRq9YMF(?*pEpC~HsOy+-r=mi z!nbk9zX|}(N}*l(C__Ty@?bXWwhT;*xy=I}bIdf*V9`@a`nQSud)RNu;>`<--^+tp6N@3 zI&r0R3$HZex1we3)-tI$!h#b61!|W{F&d|+9j*%D8Htu8awLL?-2TK&8>b0bX<_#Z zzZkD8y0A?v>u9KdrKrDs-(}2eDup}1WCQGASMsvyUKcX6dqj`+%?mn)tX`a(71iqE zYg$TK(c$_ek;r|=nuMAmKSw6oA(WQVypog@tf=vQizQ zQk7Jxw?5S?Ri3OArC23wd~PO+4vNIqZim=l^?2Rl-0#ca#oJvgad;2=Em$(TJ>BU3 zdV-=?f`$u{bhD!}HrMl{C)k!jAJuIC<%8pNnk4X*LhpW;6Qt4WvRjfjdiT2Ot?c#? zQPiZ|WRvV%tu36`i>e8(37*o9cAg|Yb`%2G>8_BWGzqclG<-v10P-ES#Nh5W=_)em zVXN2GXq8v)7?L$6ljTHTvEZD-B#ACFCbIH;Se?NF_%cjq)p4J{@BMXGu>+fs%lRyr zB5ve6^<(Lm1J~5t96ji${r%cM)c(F}?jW%m*r-G%Y(iEu`P>?AF4yfcFQq<#19rEY zS(S&~P$ax=ny7Y~_!79tAzL;9($MEF^7Rcu^Nqn7E?|P|#4yKHEha)aL{Cyth0-yh zH1~A)pWS2<{(-!wo*J>B6ge+0<5A5X>c!CX$!T+>t5a~1u|iXtjn=bgXpuXXmkjJq z1Pf1_9jl<9Fu7MLSjd|q6HgYhQ0otN+#!_h+G}%}z1W&_A-Rr1Ea`ReRXmt?01&5A zON9-v&8=0H3egv*d5D}!+2(1B3obLYpOi9f%dgMPgS&7-Zw+B*=v`~P@p`M$ay@j; zn4T236~?!CYsR67Mh>%6Vas?&E>9gD`eR**z!KBV(Gf>v2zvI~w*UbL z6xQxD+<<7qwR>Cs2@T*Y-L?q_1i zx-*W`xfujVvOv45-f)k-6Z1-iNh&4l`PwJ21@t;Qmnu)p+(q-YPsvG&ZH;oWV5{HC zVMBeb7&2z5{}KGT&7YFAAYa+bxG?5m5WXPafOAzHKZX4h@J8h_oqrdK6MW1U8F`>r z?wCeCeavnMz(~=?GR}j&r|^_6J(rrlv|hc|juyn7^{>7QuKosJflJ6}qO5i5AKYqw z++H7dwtBUFAJcMkHesR!EVI#7eG?&Jc4DSW;B+^7-Nx zPO>sR$u2Ql9j5>zJ%sI2a6_TGl6w?fePF*Zv zxKa`ZTc8^xjDHj@LcfKI;L@h*7_p7V4l1*#0aGbMwY<5v5m8tTt^_ZBY)G*g z+DG9Pih~+f1ksdG8zNLIIeaOfAV|y!UP-1@FpHS=Nt|cPYm!Bq7z?(vwTcz-?j$Vh zB>tgv|GfUH<7`hz-3XI362(r3?v5rBp#ZQfOuB-wx`kDj$<$!N?ns5$y!5MYNoU!| zL;n!at#f-_SMh;_Ev_%{mYmNL+wQ7@C2Jl|V|<3=PFvMKuW`U2GRHgR&kA$3n9W){S+x?#IA}>5KS*g}OQDdKa zM%FkHnuCp?OJnTtm)+goVjF0qI^CRyS&EoLiLpYS?#ga+@X)te%CrY}eVZ)->jnQ5 zYvtRAeQA!r+9{3ZH0hQkw`bU6Vl&bwW>mrzJTj{%Y4Wg3!$965UM&_KalxGA;tf&` zP3opJlzF-x|9|Uu67>tQsGnUw!aoZe-Q^N&I>>NY8mMJ7l0(a~$&FsO| zJJlk~G}+jbK3}kxGK^mh+T>%bR&-QiW{ouJFeI!2gZRK zcujbgB+~f0@B`@!?gLQ-&a-88?Z+XzRzUCC-{~=4p#1>v-=(#P4jXGMhVMcVod{4I0)DZ57|85b&z8Y~I?UX=~=5bt-B zP*+d0y-D~I8Wz-D1}}2))dlvY%4%1&!S<{6{}%WDGo?`$Kz@whjcKRMgL$uA5N7lR z>r#U2b)($SH~A=7i^~O%Mmc}MjHujdQY+O0N~gZ6ekv`KfJ6Pt?;51{c-6e6*rr4= zv@SJwLro}Z8JdYH7k7T6r_EIfWsWjy++LMPNiDqby0DUx*N%j8s4hHalCP!oYV*6r zAcqeJy?Z3Tqk&JLbFj+`DGfI9R!ZgsvAIqViMdk@rX+*G}RQuh@(U__FmO`UC!SZdd448F;T9gHhLd7v&u+)gW z5<*Dd;Br=$RtnuLmb6p27bMbh&`g0ZyKwwk=2tI7k0h!FKl~Z``{P%?qP~4|yfMe_ z2HQ%jbhrr1h^b;3VF$J<;!CWcjhB>?=pfp1Mz$qqm|CK;Ss?d&$W^J>;_Iz!p(gFF z^u~tR0-+>wfks3Rk*>3N`_KT+{}bWy!0~Da*lDG`cQ9Q1{F>Q99|iGp{4yq*7QRis z99~b#J>5B8sA8K>kdR)k6x|HTBWqdH;V zRBF0>}gvmmk_2JJxezo@1;y$>ti@tBgkoZgS zCf>9DL_HiUiM@2=W#Q7^BOzyOnVCMi%;BlgK}&SR(t9L)qH1tl*NlXhFZfH&hg8y9 zViXdR7H&d6*Iu)(01X8m#=$?JB*V&32;Vdw6u4-tCb`d{{x(TP%zpZgg)GW7xaRXS zdYhn${+7p-+I-^btXKOIBbHI@ux)~73Rn%zm*e5%R~MX(e~%@*A@yVR6Jw#{#m_c~ zmC3J>fR>N6oaKD+JFFsWS|;@%XT$C8yv&YF*rcEcbx6FQzgppm*SZn2(##SN(+<=L zevySr&+ZP+FhHII3s- z2i&etP}Q%5r^lPDLA2f7rhOZG)(C6xfsELP2l~7Fcy*$LM&O^5@Rj);Z*`SgBJrC*MAGB}8^5G4zU9qNsdYC4eX+1lTLb=>6DAqgm8on_3J(wph?3RJ@8myf2aivh?@ z@-2y;<}lc9DM`C}%{f-I=FP)-ri@eB`gr?5eFVKG`mS~;yhxpA!XDBiJOFm!>A`Lf zu8IklMn}LT{60OPPDeFRIM9Z-WS z=J7gU)UX2V)Kknr;s>xRq3kH&z;pxOK9$}VotA_)7Wgt@#mgH86d;~JmX|2eCK|Oo5A$y0O9cZR;fNc$o1rHW>jBt(xBC=vz z^jM%cE4E&b1%k6;EA`mblRFBcC@&U?O`6R;4nOEj~4gA{z{Eja^6b8`$MW)&1tGR zUwDsj_VVK2#$(;1qsh@O(Z&4TWB+2>SDvzMwb zY5ix}mZVT`J5dWOqO-2!lI^2O>g}c4UN}JPLj&W_F?W_tW*#k?`WSO+*~CgtBbtV$ z#2+i+l>8pWyIMfv>sPHxvsL}7O=-4)%)NHSZBL4skD?$k>BJw!7|WQNo|EIwI6K83 z#em98CDjxQQ@Wv3DeEOdtQ%*X>$B!g zS@za}DXCd=znJPpVfy^^v=m@V_|6Jn2T2fvb<;NzCvXmEo$J@g!z=iMoTk zcQc-~N5cjBExuN9i*M$A@k#jC!<+ABK`f#KCKdtxJAkGz8TF$rRK@;Um^HK z`;3e5iwY5y{H_$=|KWNf80?iI^jT9%#7-?I#CoHnH$(mhfygo4(wiawmm1{v-i$Q` z$V>8w>I|6uATE!HE8|M>UbQiIc`CO(D@8v@g$*=$StTKzk7m@MA_e1QG!q8bqcT;G z6Im%3Ms*6t>scvad9d2$aErzo+N$I3?iB7`j!NV^bbd(qD@oz+natX6NR~{YWx<_M z1KhF{+}>zLpKMFPToavSO|?C>Dq5Bi&#-G!up9OGDnp%nQt&G>>)e~dmNS|`M*}Ii zXEtTjc}oiBI~0fWnSLGS&fFx-Lz^b4FW8KP`*cP;!v+JAu(xlT1Rr2c68?tC;6Is~ z(>f-D4|XQu*G&c=j84KYoeVx$poDMA#0!|Agncq1^V$r97mQP<&PWEnM^kY3M>62P zoPzsAB%=?HreN-jOj2L4T?uzfWDP*3`$!vc~3TAmG z%+eIhl607YFK)$5Dd1XV8yTi61@q*?nL4Z#%o7i1)UzU0&(Vi7>RFkB`AjCv>J-eK znJ{ZoFb6VW)}>&E(qW=~p7;(-_yX?AhYd8^n1bofgxQ>eS(91MmQ+2<)9V>I3{gSK z&Sj~%l!l6@f8I!79Vd)P)ee{Q!=DL#m9D;l5Wwmuhe7?+Ap^H!veyOa78$ssG$*CK zs@JnSb5hx>^^|u{rfkB@$G}Srz@L$UJ2n`A@05Z4Wd`8Addix~fH&%~+a`-$qsMNa zOwYAUuULhlVkh-1m4=F)&?{DLsMzaz_8vp_3K7_Cjql*eP-w^W>;s1Em;^cd7DM)T zWZ;gSld0Yg>9LsevSOdsV=?1p#ctPQG2dmyZqQ>f+hxUe=&_jVvSRD>Sj==;v88$} z<~bdoCK=d|39j1)H+*7-V}$Itrx5bG4CLtmcR+~0OwYbw2KK*fPvP?kJtZcvtZMAk zV=;YY#ct7KF?nSpM~}tSl@%M*V=-Z6#k%!IVcJR(iJoO*TB=bFy;1K?GZ0CSPEI^W ziR=?SGW$n{?C;3H{xgQ`M`a*SM#-V4XU7brXWyj{dOy%a9$D31=@iWIrJT`zs9DM`hsF zN<;Q%^z7A!>^t@BHHPd1diFX)_K=>v-jIEzp1skK-K}SDHe|1PSSr@tGg69+vWK%2 z>nVL6Z`4UGNqjT-BTZ*4O3UrJ;=WEC{`d}j%G9AHfr9W%j1F6>MMKj3?B}P$#IoLR2^73AOSBzWPf!Z>h|SJ6F`Lm~kkbR7oE~ z7_)zM^9GrBFXwe}UYE?fi}RLqx^h|W0O!RjP~D6t@`ljH&37{r?oLO-?Fjr1tB-lh z#(;z`BI*%vTfuV;NVt*#g4M>i;%NYAV}RhZ@qRoF0N+O`kATSvR%-xw3{jiGVdGn$ zoRS9c{~+o+V6X9hJPiPMF+lKE!C?&mBfM|h!|3Xf==vtYwm!qC!4v4Z9br5lshfKx zs+VwH@L%;2JdyVcoc9ptJtXtann<66#NdyH-i)Fi-}~^HU zZ5nW#uaxtJ?^apzRyUV%p73&Yhl{^mBK<8Yi_7XGl_Gtuy0x0)t3~<+>W&)zt`X_y zs{O2~dc-Z#Pqyoy+V2O)@F|;^eWQXQ3`_T3Bi;y z6H1vdJt0_BW$S)|uki?U*Q6EidQWe$JYE-h5jD+M-{ zi4Q4FPC^A@$L^X%T4vEw+)Pgh){~AnFueG0Sic=(7RVZM zWfQYLmG$B=W_hd^S2i)LQ%#)SG<_08q=RRbd5oD`lojWjn5n4_R*T1&o3R#M*~DB- zWj%U~xmT36>6@5ysjO3vG1rQ+W_=TLER{9qG3HiL)}L=;PNlLIJ;q!r3a-?-LfM4B zNioS6+|Y}?ykLm_Xg_!}fnCqM6L}WL0Iz)qcnLeukK;}Q{bks)=yzeuqQ5+!H~DOM zR`at4+ZX-y{A}cXoaO>NTdMeC)AQJ(9Z?8cY)}GW4 ziw&4v>6;~y!yqYXnzXHV62(tyzfjlzI6g!F1Nz}bigPlB$$A;fbgQpcR_j?xC)1*I z=&@y!sVtiHSl47Ki|W4Q@)l$x)(m^!i-cEN#XQhpiEo{T>AIhv4MYZWauBtn z87$bGvd{b?n_cogG%Mx?c2x5d2gwI^)PZ^LfFDm~M`ON`0V_LNczfN=&-N*ZTQ)_U z30HP>aOg^YuEO5*j^Gs3lfJ;rcLe2WaU5OD!hdqK+00_J3CoL{WBoHR{Eo!r)@#*Z ztbc|KnVt-pCPM^!XS61bs>{?@v_HHGi;cANl9SI5vnDaYJY!&qQ&ZE!iGCTMV_;p= zQrmK`_ouT|W{Z_Msrd)&X|z9sHyUQda;K^vBqmF#Pt`!>aGY@#socp_#g82fR&zo@oie#QEqQxd za+gT%HY9J?lQR~VC1)=r=Zzyl@5Zj`NSW=FWT1*ifj;&2XH1Q&7&wKLh>i9>!}JwQ z!ThLilI~xfni{pfbovyq3zOadR=NlhIgIh=6*J#p-^FLXtod)&#pb`9l-Vo~3<}_> z0waStGDbtU&BKAO_fN7DFscVuXHB03e6Jo`lQmOP>`pzlE^DTw*d9H$K5M3=*kHe| zM$Au5GwmW!WjgH}46ThH0G)O_{M-N#bDQ?W5lQNy`65J;_Ynhm7b~|}mD_B}ZT9gS z1JMJ`>`Rvags!3C;1(y^;_W7jSAd=nC6C*UAjL?~D_5`M)NL@%s@5CXJ|%@ym)^Ez zhU~h^d25Fudx@TXr6Idb&%Vl#{k$$F1hZyx!sbVM?CPxfnPN2=%e1K%{Z^lxpM!?^ zd9d%|^E1vPL?+f3fzMYRi#6xQ+*X=!J?b;AEfnY#p*b#bh&21dYM-{o)YFp*qaMRmb_n8JkYFdEuX^Cu#DG z18H`4&La<@@az^jgjx=3Km8b2edOL35XI-leAcQ#Ppm12>f?^JS}4$GrV8eHyzclG zzEqYcE`csE4F^s zwzRchv9&cJNWfQ-`oKpkqP8~%HHu15WPj(Jxp(*O=AmN$`h8fK+ z=tc!;AB~Lgawz<3w1@D#H@wjpPq0c?;?=z-ysTsfJI@Y}SWBTpc(!BT35heMqYdzo zh=)_KW5Byw@#^kSk@mr0(X! zcusO7n&IQURfuzNmxi5IMc0D7r9ib3DU*C2M(~Kf+JWL;i*+chxQmP|*VA>6e3O~( zq{&P1p3he+`8{}d0*7Z@EWzXHJ*8dj{ukP;&g}hV_lG?mzdvj!7>x$z#4oaxA4;I@ zV)x$>5Pi+c;NIv8aoeZ9+A5s*y>!5ZmU^3iBLa1p7QT#cdC^>23LG`lF9N zi7Ls{+ZNC}a>>)%=Hq*flxW)zyRf|&^HgLhZ+1AnQ~77a`wR?W%CGcmcFeCuE$wz;JiFg64j*?s0+mWxiROJJqtbt-B~wYf%`8t!p3W{UBN*0dPdWqg@t2e{ZVR>w zzZ?eSb2JBMx2!^Ya(MRNsnBD)f`XuM*=Q~$jU=>aULad4rFce()!})MwSJ!E;S?4o z!|z*^g))VuRK-iUlO?oMLcBM4hl1h{BgGab8ZL@OoZFpzJPq#0XZQL#gv)T2aR_-o ziuas~Os!PJFQI)I+M82&{kRB^HsddXHsD_ryd@`!7hH;o@Z5eW(RS8IAC#wZ3NKHl z(mI7}&ZZaUAE7Ioka-M^X>{XqqjJRSw(zRjEOxJCmpb8^tr-%f3mK&u8bI$>z+=EH z-QYA+iYC^)6sw3~`}vSqD~}mv=rMUOonPP(qBx5zo>3qb-aA<;_$pqhuNEF1lBn;d z8;|w9>|&7YsL;;S&4M1`r*}}VF}|@r`j17MqpLxVYdPAv6)) z^w5~|r3|Mh6*QBlBFr5UdxTiV__|ZeP6fcTi!!90>G)24sgZ6(uQHpk8^&4?Z$-~w zH}%jRJ$S*(taG{>(~|Dd%4pQ2+(GTy=9YITfy-lT(TehDL}WXU5wh;=ZW&H`tf+ah z)N}E~>x9bUSmM%QiLrE(687E4`90ksJi!xXE!eQ3Dl@GP;WMLnABwJXl0s^9N@z=B zWe&2e{`rL{&sWj`EmdZ7_C8W+02NefLU>|8k$DOtFs}<08h)`l45~{P-iiaE)9~~t zJXuA9I?HsrZVmk}U^3IxI9@I@0l6Y}c_xxHBQ8LjAJ&C+eF|=n9+Ik6X zXk|#+%u(9F7MAFf&*h1BDCiM9lI0NAg^7Mw;|6o9aIH@4F#~B7Hw#bb$P3$)9S8h6 zH(#c5he|b+Jge8;XVHAF5Td<<3|9V1t{q^Tim=pT&hG?1AVq2Rt@?WV6 znK5il!SCte(p307H*8HqcI8Vocxe-F)k4_$d@1VFvv@0>=6Eq*YJ{&jVQV^k0Xa*j zL)7^|)^l;94uM@kk{hLS6%sT_Kmcu1?uiSCc_WZ8nSHl0N~}3L0trWDUq4GUHzAS8 zawxx{{of7)H9ASbztAB(IZ?c>TG#nntiJ_$(@P_(1boyH0{z;janSnVoz|2wI;|P3 z)4DIQ(;AfkVutR745dD7Gy=TL2yj_KA|imkmzDoE#y|gy<29_jF_1@vk`;i^mu_?3 z_ALwGVFh^TlkZZ19G0l{lMxD#H2&Ir%_z938xPrp`(;>pO`RfoA7LElF?WFNqjs-YPuv6G~>1#)ki zc$J=Cso`I8hn7p1?mcUzrDQ?7h&F4^VAsCkbQ5kFr12-aD$g3+rEW}%-35o8Z^Bh@ zn|rpaWf#F=^SMka(;AWZ?-Cs=J@1ynp>QZu!HLe@&83s`IS+At|Hx5d@7poAoL}W`}sGve|#3Rj6QH z3EtX1(IIR*gMEo{-Jw+0eL-vEU+Ve5*o8-!!3*9qH#z$NNVJ}Q>@;b*M-zpb}CCDTPW)mU!W}DWfH)1c_j#(Z(-|wAlDX*FolEi||AOqeHlGf;iZyNRw&vD9?4pY(Z-hfz1ffnCs#^l;b3$Dm|rJD1+Pq zX}lHO8;yg{Q+tj4bJEO$iN)2ixOfJ(uHzaN$30-}W;26bhy%0HS?%e(pg`O{_EH)@ETX>udN>*gr~@w@Bxz@b!kH;- zE`Gp(5MGB6ivZaTkhTPTZvtG)AjU?7vIvkzM9TrGE(U)wAcf_?D?Jg{I~o4h00x9> zx!KCI3-AzfEnkd!a8-CK!?oPJ9Ot9&Vu@BEuI1)BUB|!JY`ZstXNQXwfTyeS#pzf9 zPjkcT=TQpIz~F808lD{K!s|^vSBV2GcKSSwq44rqNZ14;D7v~Od z#?!7FIS--{txkt@K>vySizP5h5EK|(3x$yVQ`&~FA;3hohbj;#v4 z@@|FxJaB&m7Xr>5kdPA+Mr9?6K3zFgMM}$xD9hhK#nx1dPyG&Bt3-pviODR5pel?!Nk=^|_ zidv!W+=mx@?$NsQEu8mbjMZ0yYuuc0`%Td(Zr49{5O2Fnu;;_`M2H_n1u%Fd13LrU z{lsw=`Fcism$aUNSL)0bxk`8I60-M$cTdxu#9bTSPna{$z&Y(Anr1Qccn~ir9{lue z00%E|4VC0&ccbXQBiwB^)Z%P5Y^GUmI>EQxTts*H;PJ45D|knqc#MB6`xkMl@;}HK zPLGKpF!Wv$0uk03>#a7vA}`{|X;iam?r~O+N%NHkk5QtjS|<9T2IldXU?z4DJf+cB zpeYn}bO$cwOY*GISES~&OzMo^+d{eCnw%>w(I^@@JkaaG^@36l5GwL)aR@P`<6#ED z@?OG3FW`+Qc2e2wjZi%OucZ0u4(g#oCG!FchXHG4z>dDlnkC`PkH`FNv${?Q zV(hI%CC^L-K{!l;dPHlA$fg`9kJ{-mLoL{)lRH^0bi}kXS=qKSz*EJt;o*YQv7+!~ zMI`M%`qH8#L}K&g!6R8XVMk@sIIu84)Cq_`@>;qbSpuR-1lILiVx5WY8DFh#9on*3=yecW9h^YAYrm7sTbGJ|-Uv z;<6DXC8(uh{TS%{T!*t#*pKG}iPzhlQL~cR(*T0CB-JWZVVJnM5f7sp!a6}&f*OdC zYN8x(Du~xYy0jdk@ZKbKUPl;JUN{tMv;9;KKNTwf-)`{!s?V!OAJY!^4>? zozm&R{6x9{xd4TRk+;#H90xpn0iL>w*@3o)6D5sGRJqNKpo$oQk`9@`%_o5yJ{Wxs zXgPdbW@5#f{x%zAMqfjfQCo98VUsYPG>%3uIh_m=ou2;}6_4%|U_wF?dMG1AB4x;l zWDJ-c34M^a&7zohb0 z(T%;qBjw^Oyu*oigdL^n<7HMMcr4yvG&OVCoqukAX{t@o9E-QJSWxx>)L@pQ=>?iw zglJwJud7;w)S&5My_AZ9(|C6jcPEp#c36KtNGqz0O0jmyR* z!>F3Km8jbH7E#q5+-P3T1!nLiII}zzOPHkuMcs)9-)Dh7?Z69mVzgwj7b7Dsb2AkJ z#=dhENRVv4#6Tm(cw$t>`8FdcbS9_ZNo03htr6`l@F)F+ZCPo0x}BZ>>gc2K z8Ywgc&X3Ch!`)OF557s25eJ9XF~~I4%HS@Ic#1jZtAboJTdzFG}~A-*T#zgQ#R&m-J^8KA5}1aJb@r^ZE2kpB)) zDah^zI?&=gPad#>IB$j5zhI4L@5_H5M(w)0d$JF7Ms-_vbw2CAdYIha!BGDF8%)cH zq0FCYi=CS&m?<*KiiG2lfj`XI z-PnU>N=lotEP(G{z{pj?c+-sR9H*+R>P7VB=g`JWi*D<0?8;Kf?|`cqX;e zxHj`JCk@CdJ?j~VY<^wr=Kw=9>fCsJ#XKu5(KYJrFfsuSE~2)&2s%@Tr$|;o&}D}Y z+G3q)OpPg&=x1S>q$gy83z&HI9G+F0FyCch+6J5T5+ldvx4%XIAPQhKipu#3vwt{9 z3@pw9SF-^Eo%N4Ie2qjfJMvL}%@>M4QRK~&lhQ2Ho_~%aPxBKhUj9L`w|%8%g>(gL zI!ZnRN(uOCoD`7{#N_5OXI=(`)Y$){3&r9*4aZTA>@G_Vr|Wc{Ek9-UKP*$e!#r5XrW&n6 z=OAz(-Z9eoW@x!tuj^=3#plsrFfQZeNvNVq3I(~GM)nMWVZjz%6g52i|IY2y88 zNZ3?ehY{^v_UwhAMZxGe@7ug8(gbzXt?T#`nTq8_B9EuC$w8al^Lu!$W;XFMX3S^T z5Jg{0kQZN&ywG)WY|hS*eW2iPWD3@U%IC2!a$k(VxKiC6G3<&oy_~7LbtW2L;$W*W ziYh$v0w38;NZT9H+#oADd8;_r*o_Bh4k>h^qJv_@T^POuGA-40 zAdkZXudprki@lp#ck6FBoFiS%XgKf+)n)%Zv87R9xf3{M&-p2_+_SHUjLoKAus-oP z&f*DH;bY8;)sn7buY!sVN*&(FRVqzx@v|j+yUV4CttFFaUTeuD{-sC&t?;bkgceC} zH(!V&0FZCC46IzJezf}QtUVcx_M>$pUp>Jt_!Sb^!*0G6#wzcA1{_nE&ir0%nLl^sGa{JslfVA}Pxa;yb0e6iHy-w)i!f$R|t55>XF-(P05*$87sKpTcNrK$Wi zbTxMac~wIvWKpA4T$MS~YLC8zldBcc_{zUM`kK|FCrS@oCCRLO&s(fDw-9{IK&(5w z!0PFOpn-{!$0SU@jKwZs*Z?u&Q*o6z6(_Ze^u$7l^Kau`7P~2N(gKG2eT6h;5u3=< z#H15!Xcms`Vrk%0={{t!vgPBC#ObP(1y-$Ww(3aIY}J-6+u8-ZUd?aTK$D;Hz~et9 z+qkC~@3s7cX6P1Nj@|)7UkW~PfZms~QJjMiZ=sG&NzuIz<>H;m#Q5xfZOR9-&^tWu zG2oN_!OER5ot20WME;CLe*ZvBqTwYk`(s&BRHsAmOGDwCLG?ix3h#1eZ0qop-$V8D zzyY!A>E-h}&Hdn~boQy~jckWEL&2N^+Jz7j5EW3EDgtqO)b|i3*B=mPEv5d*TnU{C zUfPX!^8F2=@l!ev`2Dgw!=)R(#hb(R>=HzK^c6f0mNMh7%2TlG7g6KDi@&X&c82x` zFA>^+tnl_p#ITIrfHp7*FHixB%wcx|=kE8P6WpUN+Nkn3{ljCK^I|ak*QS9Crjzb zhNlq?nH{sNeP|r~E+@4?JUTaChbuGHo_%JaSw+gJOvHfhknlNzyFR5Vj4&jlL}ANSgZRJGC4Qg`&^J~i@>Ikwxq%<>R%?q^}L(9~Beoh)R>z6`T z^7(o27P<+%EcBw`^NZl6&ytR!6fmS^teenQdLy$$2~EVY{4{q+!^Eb_dkzFnbFfgm zXZO8S=>0D+^Js{QlQW{-b|X+F>p8h4ba1y(GR^e##>EoeNN_%=VsARa({c1~cRxz| zHB6jP0xuCnL@H@kql5h-y{lIkcRKc5vg7d?KY_zz%-% z(cEz03}RRCy3*bGp9CWi# z2f~iN!VfW40Ysf14MTJXOTIZe{X&lO7e^;=!6Ed4Ck0^mW1no^g$Dh0X3E;iU{{B&xt*QxpG#Cq3h_~|1w*z3k@u+tJ6todhXxNmxPr1t8xdG_yB=$+13 zV~x+Sh{Ej2@lu<$;QHdmqmMokW(|v<0G(?ia2PI>H*(A-1*iE+-Mm9hW+~7-)*ppRn{V{U{JGKtkxMiqF@RPZUvPp#{Gfkq`*W|h~B zMMirIR%)WV-RcpT-gLn}W+WcmXg0!Vp#qc`e4obYIu^n^Ru~hkiS-54-b&K8EHaO( zjb|nbeW|1!tW+aGriDuK+#!diuf&3>$SWe*ModI{%VgvJT}iSrR8kZdk4zh*jaPZ7 z-oI+~JjV2})q9DP@yae1b&Fj8{Ooh76P+nFf+>>zx%)l>a2^9t13FGj1%**U^cJZ3 z-L!*`GWXBUQ^b|P`&iod`(jGq8|=ztfCB0UD(zA>>zV%WXBHKAfAxy^xjVn`FLDP@ zW~?iaDr+k0a5N10j3o=QWNi5eXA>goObtc++a+1(*S1Z8#a&NFZ(A>saY&>6|3 z8m|>}=Vx%b+jr5MfonTIsr9MLXsSosSqiY&ec0j2L~`(M|5AmG9ywO&okA&XR*&U= z!tdQZ#6RLLCviqz-UmG?`LlY9o;3u_b^p7 zVqhfNA5q(T4k`H^7UcDvMew(;9p6#(Ko{KCUL=0_vj7K_w1bR5yPk;&=qEl!d3oNa zbP13th7Mj2el;dCI6aTEM3HA$9ISa}!=iqH@aTa`4;v!$Av3!$l}#NOfx(kwsVxz0 zXF0^O2?f)|Ay|$7QmgRbIV9B$Neo~B@q0JMw+a&}KHk~$5{?V5rK_hMHiv^cqmfLw zLw*!v%m7-OXaJottWvkIN_})UvnytO!?nG!DvRL+g4IwKns+x!mz5Bs{VN6Omt?8t zVNhHWlrtC<*?5WWHjZmmliX~cpKgYn=M>)jBtC_E2i*dw{u3K~S_K`3Y3b7@cn4!T z*ArwgY{VHc7FpNv2TVB~Wdi>(C^p!>Fdq}1yl^pH6ez-_1~LN;J`a&h@n0%Y=B(&H ztWM8ozn}tb?PZ(#_HwdKed9L$dEf?k+~OulL}1BqkKtHt^E}45+`&>ycd43U9sebp z|AV+WJ${HdFj-b9Oq`Xn+^6)i8J;gTW{YS8q8U(LzY*zj>|>ydf&A^lb!4%u?PKxS zFpG7JXo)J0x3J4SJH~ESkM(~D&)@EnrVR`vp}vkusH2jEvayliUO7u+1MFg>Kel%| zxRaWou7gfb#H&}kuE6%$j(~0*G;;5ANBap=?&h%;<$FcQNBt-|vV~?^cO=YP@xwdJA?Hd!vHQa4Sc!j*XR96w9UrvFtw+ z%c}?w#9_tpv*P@#J6@b?Sz)eC9N`l`;Lw}QlC{7VCcc+{kwylrO8YuAohs zz@#4rI)#gkl7s-xglzd2vb$NPG;{qDWGLkw&scGT+I`Utka>pi!PIzqtWs=el4i|@ zl*G@~=X8rYH1$WKf%-hANJG6_66*aDcPLF7pv9_QyN#;;jK3ugq^@Nq=-9TWGU8&8 z*zt(+j`rizvhqCdEL=V0`{J`ojLAP^wg2c}iOC1l6syXdlGM`kKlG!N-j79RtwQx|i20QRAwmlNwk9^)H<|xG)JQk~TMhN*Ppf3B z6H-TG>}A_;)llzjd4~TuCe4T?BE{pRi{8a{L6?B1u<@voYBUqKa`7)jelU*jafi+V zJ`CNUY@~BJ@z^sw$g_Cd(d~E;fdt$(q8enal$4+xnG%HEQYAl#CLV0T8JHsna2aq? z<$NsTU0jO99mXKWXtM>#>!d+pX5%;lPJ0EHoAW@+SSXoNiP_=)n9O0~Y#FPd%m0!* zIbdWvigSnj7f6Yw%@nu$i?z!Ag~ov<6jZ>dxLq3iR!SUe0!bU_gGcbz@SJK~Js19G z7671*mKTCwN1=$CJw@g`E^v;t{o(#U$LIG}1b5HFjSrWwjStlj)uIrdvrFa|8fmf- z$MR}vDF5&S1gMGtX=%ekrNfDP7SNEEzkDN7emYTTn5K!tA8n_kSWJibalJ9adh}7N zm94l(U(G&%-6&q17ov^JAP?A1QajroWA3UlUyQ!eHW{Wfr+BE&s@crY{ak$i!w%}z zHkwVG|0bzi7xB2q6h$0vv0xLb(x~0fin;blET$n`WIn$G=fuldWSd?1qY#Y_WR6@$ zb*I>@bnyh#prrjB9fx4ZKXC3a?kReJ7~$AXA}-`w8aH9DMiX|1_}Q{?S2{y<_fBcI zhJN@!hBri7aUg?ZchqLCr?e~NIQOYLTg6#?QCXTt3v0n68*v#VjT5{}fVm#0sl4Ej zGB8`5ba7aPy zL?7G}HYu#hJ^&tPg{>*Ldn{b4rtitPQ>@B71vk=_o2T+t4HEqp?%v@|NT)IQCL8MdQ*9KDdq;S8$-6PQdmvcD2XzOo7090{9A z(O0aV6Tc)(cK#n>A{*P#hBBNneGMBbUQ8!jox>56xH4z3Ta)G|G5#@(x^E{AKhTN} zmpQHscB>2WaiMMFAo@vYxIE7@9OnHWv(ylNPBy~oa4+lL%)PhjvZiU!Vb2*nI)&C0O2h$kWNq13^yVt73E zCsr%5?4^i*L4xJ5NVoq<-1_&?J4wh&u_G8;%VJ+E#qLgyjpGSyUsl1z@RN?tk`6pl zjJPkG^<_ng1Nz~7W`2;ef8%k=Uex<-r0X-q!{LOkN*huClUj9eTsanAEu)h@vW1&X zxDpnXt^R0~Xad!`onUWzT&|AL`G1Wn!80y?FiWiS(pP$NSfaAW#l8-gRxwGnQ>Z=@ z)lI?4I^E!h8sV;Sq$QcMqc*3|_HJw{8yCfOm7Wt1;tcW0Ke9PSnyC+!SVNo2Lz_xT zYUcLoI?u(HG5sl2tWZU#yJ%IyzB6Lz`Iqx0hDI*p)Kt^e05G6l3$3JquPAq__J%6T zBNZl_yKfPid4v`zg$a1{Xo-ahuSs8&q$~Vdx@)>oA(z+wE&ba#X`&Zsb{Fedpia73 zos=-V2X0PSAM#G7JE*OmEi9Jlk8IYU#DeCTd`0>f&$L4qLAPgf?a<=L#1dqKwec*W z5;zD7gEO5_igR#U;LzLPRbj9RiA_;f)A_pb=-yD}w@>KW7TFG_;-FjBCW>usg8Xt-_6qs4ws64p{gKQ2A`akNy>n z_LUfsCL%X#*aA`)%dv&!7@8B?%_-&yibQ%!U_MSwunBXAG5F5cc`0-R%Ve|?30;B~ zBHpw35~I`VDgQMd#bY9HdSWV2C=I#K=sKUm11>iiLG1ql-w5tFemo{dt1O(k$^J0+ z89#1`GX@VUI}WfbETlR-i}9g>GI)9i6LuBjY(m`;aYA0#@j5^bJI2|Cr2_fkyjqD- z*O8*8CYc^Qo)SoT5V3|gL@bcX&_`Yj9#TR@7D5Td^+N1Q)HYh~YgFN;mki{Y=xbP- z&vD0Tg^~I#w%li90dJ|~T@G&LHi05gVYE}XGY@Y*My5jfw-cN9bAX{Cw^!FO$Tq@e zMK+yjcM8pQ*eEigp7J#lVW4tp{tSF%842n4D>-Z#Mn`VmU9)EHqXIdvHdT+GRHBd}M8L@N50X7vwr;1}>L@a=hwSBsHwRW%3Mn{?j2* z4wKa`8qtMHmBNmcxOCNZOodj45?0qS9#;|XAadD6LEC@)q$HO_i&C23@R%5(|NR?A z=vz5y1TCRu5Jjx;5R&(AzmX&?G?{6lgq1eraX=XpMbI!|kSy$eJtoRRb7aEI!MJbLLqx}4JT{^T zg@zgxZXE>zqp-)!AS{pJksuIRr7&FhAz}XOBMH{Ygp1Q7Fuh?Sfzl6`t|G7@Bv3CS z(EH4;IJDB3*ta@8I~cItkH&zZu|NzK9&`BzrM^Gwb6~KU`1*XpZ|7E18rlS))o;jp zD5M9)wk+^@{^Q`ivEQ+CCp`a_d0v|SNhACT*^Y!JxN#` zsDpcy!EXKLl^DmZ()C_7E;+P_R3y5|F)7kzv^JO%JH+{VHIt*Q0?j& zQuZ8DvThn0lOf{K@^AB>qYlOvIhls7``y1(uZOgEtFd_LcVj8tq0DM50pDa!&wjJ# zu-ctF;11pTlnH|#`5Qg%?PiZ%@Cb#GT5VUbfv^X+UK{olqzrZysJpIB?NeV={YdpA ze2?nIr6En=FjT3oW@X5@B6KSf_xfI1e3m}wexvrUQhck0%__;(sOMev=3dN$?{)K5 ztvlB`&X@1tv$EghC*(c{Kvkh->d0b+JGXQKNFHq)TEb2c@P13-OgzE9BxO%YsvexUO`P(a@Y6L`Y=v_hjG{{yugWPF$Hc8mz)gl8Ol@m4W15ARy-#F6JflH zjcR+_H>p#+2G4p7`5Hs;&`$~x_R+c6;SzPvA$1C2U5a~~)uGD&u2epU@QieJ9TZNr=V8T4ziNk~cXJNbjP7n(0-95W&T)5?R0ZfsCVO_qaGAhx zsae?@UUV|D4yiNQa}Nd|$Ka0@Qn0XFK`OEq2a6gYK!+h{0m|6YvkFa}s5oKMsC znw5#`BM6$8ouW(MmLZVcKvqrfF#F)0^MIy*R?-MKR5}#Wgi7JRK2&N9m6}4O8KKgw zP-zYbjm3dOds1*ftVn=Rnf<229hyFiTFdkdcyvu)1{$)vFU1TW3NAF=ggNNp&(2Bk z=SdAp9Lz9u?Pu=LvQI;2cTIDLjPR-k39~TRt*i*VClq}ZjS4kTNuC`zET5hZsiKoT z9Bu)q0er{BQ3yaEcQ7B3;sTT0(ea28!HZ6A9TqMI_;D9y zl#s`8r|vxjvS#6@hwUM2QX;AG69#`QGBKjeNtjeX+-qFvzJ<p1*BLnqG-#q2&B8DTdGe zQdG!*?|NBq3I?aM;Kx`ne~h6lnm1|xG#pg}`2oH$#^8Ghk<#43n`iTTpqNeIzbM3t z%VO~_@qIFLx5c@;HonFxrDo+0MIYlSDteUSUq8$q9Ve`hpykx&xFD2Cg2G9O9kuI+rL!mIyTdb z%D=Jw%T)im_Ak@?-ffsq`!6%ikF~w^0 zybP4>e;m9p+5g3pF@4I42?d(E1Vlb#{VKf-uuGZDK^jZkViGvi?$^Aj57C__mGH&R5+1HSBl5?VaAZ}XEcU}s0hj~f)q`8 z?4DJOC4RPz%;Vjx2D7_C`Ow|ATuHDGVHSfTmt+!0bbjbhSy0XS&$764d%TC4gxkCu zs|*;oSj`7C*>9qefV;Dsf3@u#H$Tpudx!Zw2=`A|r!CyPi%F$}-uK~;t`nCJ-T5X? z*CAlXzHcU5nqHD>$?XZ;2t7OB({m_wHvCapFCK=yuCo)>#~wWQ4gkR)l|8uxpK$RKi1=q8 zz!LN%-aPniOThO+h@{zp=mUUzBZg;bHyHE@m$S-e^TTn%&VG)6onHbFHBW8=gf77v zx+e032F6H79}2whjuxx&ASx`f$an6LGR*k8b6;q&x@(~l1l8ljU!7n0Cq{14#Oi?X zXC0u(CZT{Pfo){%fAf*|R5-uLKW09G7n(ZV!Kci4L_eB08l)}by4#L(;_khzbnOEx zR@g9+|CE`3Mm9x*QQf-2>^H;z!@Z->N6q&OhZOp-;iB%ts(~E#Y=2fUaEbJ)95`Qk zRSis)UeyEIaQa2v@2c9LOX)INy7U&@Ik{;v|CCva(`9)-3Tvl!X)FtKU)}gQzaMAA zX1}!gOO!{q7!kn&7AqkFisvkzFpHbs{{ zJP|4F4lYpXw(iRQ!oA=|W!s{T1O6HO$vvEgse%?uc=-l(*Rp7M1$Xkft`*z>g`OcE z3-Bfer$jbF6r&}4F8nER=iaFFK1ma&J*kUvtx(tL7tiRL4Y=YG3hMu4DV4nsU|GTy ziY`rf3SbkiP+HoLtNrWSkEgVyv>(^BHS-R&GjbF0**xeYep>V{^4Z;)@aTR=HINB^ z+V?32%=A37Cln{eudi7r2%M`?0uaFYIHxu^M}G!6Et0V^eo7IcH<{( zeN&7sOtfX&w(+-ZyZf|lTc>T?wr$(~+O}=m)|@+Ub2F)(N-D*dO4i=B*D4yXeV4~H zjpo+%WJdTz!GT;~66q)k%ZrRS2!lZRG~YcX36Q>xnNrdUr9}5&XcCeJNeLZ8E| zhD;Cy{FTA|+E*kv(pd87&qCn4FgJ4cn|2JE$$b$)8s}+|+NiTt;DFM=F@o$b! z|J-_hTtTb>jNugUNI~lch-*PBwMdA9{=b+~CWOnZwlpQ@dZ56|; ziwWI;ZAZ?(%t310>yWWOk-Oj`P}?iEPpjK6%EIFK?MMM_r}hCn10|8MJ^^wQW0l>G zg|(<|Iv`vBBHGNAGmenGDvxOamhlKdn9X{Jc1wMOQ)%-|Dqrr!Fa-WXalJu30css& zvO4cry(vA|pxhg06+^~4AM>%Gvuy{jV(gg|Plr-?W~l9GH3mQox~D`?G6S-!?>~~E z;o-Yg6xhCge3B3WTnYpbDf;0r^q#)NwFKA%g3azc1h`2*eHg9p6Jzq^Xi;a*(5M0) zG>@}TeAfck9`wBJ4b7i3?uKQ zEP@=PX?+cI18WYx?Y-z;RC8&Aksw&WB|HwC(beLa`ggk`{YjdC3x`IqQ`F+l6&G+W zeT6|IuGWwV+rRrP+n^8Skl32ugm~p)Ub!ur9P@0V0_L>&@IVbeBnQYvxdX{^7-phX zs;<@c7n7_bF(tOvV<6k>kGN-vaDngu+8ZaNB_mn4OKHalMxyT*2EmBiq|tY>uB?x= z4&1@1b$>2@+`|4Q*Fn<`khd^O%BYwh9PqxFXtKv+`bPyJ8@C~wL-h2`bSOCOeBKi< zsJTOTRZQ({o;*3T&_3Q^w24b=kjJ?B{}}d_GjA>a%+Q^@SZ?7)M|m?UP1^^@9FT(J z@Z#pM!{$GnrKyC%`PO?0f(u8;m9Mn+RyhTgy5r$Wc(%9Efj7?tBvZ`)jg3t?R|MbX z>Q}F7AUg&e;ZhWB=#Qhpz#F~yklK6h%sA!4&lq=iI!oyMCIj z7R1%(MPCg+DR*XP{(K^xeGjcITLNXEU$H^BK@&erNJFbukh0?FYXbP@H9&-3V_=M za>sAu=c3RnKH;sDzZ`zsNo9Ba`^rfA2y?3l0eI${)o^PpM44|b?HjJrY*~b&sJvdp z@+T&*;)UJOyhkV?g}s0hqZAJ#6&Y3;9(HkLU}}zbcbSEF#%B`D_;vfgyohr6>gD zSvz^*PUDf;B`|O$4;d8Xf(um1 zsmw$YLGVOM5Knj`o>db7_@<_}=Zdc@;$a+}=1~q3XmCMADYM(_|AvEDIEi#N=e@^cVw2_x8t9tVN8&G$boLF1Q z$}I*oQi2QlX}*ZZ4I~B6LwTtShUU)mf?U$(-Cd0Ce-Y^J^VdEvaXTjLz`(*%03M2` zV!u`avMZ)vk9dgxzB(V>vSM0np{ZU|L>VH{Yc_2}fLk8bs$01=yfNG6YWXQph8MOu zLgj376f$|^Wvd847>t4Y zmNM={gd1#kVbi8S-fq-vpTge&+Tatx(XbV(L?bJ)X#Ac|!Y5mM)L6lm9ZyR#h&BL^ozuaL35iJOYMg=ojxIM7J zP(ll`1O|C%sMJeT5SlHI@k3`oe>%KHxy#j?-bFns0n=P7MzOF{8VZ%r**RUldVL0Q ztrj8LjII%>ke($p5c$DD@%;!x$o}AtVdx2_rDhr6GX?)y{x^(6X;gBW>JF_AcR#!l zulV0lasDNkxTG?WML7o$(D(lHr>h00)>x1t-EN!UsQ~CSTTp%rp@=NXElM!fthhOU zwZcUaOWWe^C|Wza?d0hb>)EP1eAegvH_F#y1(Dxw!n)V{b`H!BzTTkr(#p>1`+-oE z{pUAD(dx^MH~6sRFCOt%8SNKQ=rnA4wXI;#ptUbO<7TH!vySLN^{GH%Wtc<#d_ z1aBn>$_jSi1(+Y_dA~fRDnjUn-pCKac?o2UyXc^j1&>Zq$9wKcUf_(Hxhw$JeY@A zcdOrYM-1m@7<{*>*?ul_^ou;OT7Rbm7Z;5L2oGs9dfPxAU@+PLw{0Twz@mmbN2q=x zUTp)+?>lw~EEYdM*B4T9UdUyO#*Y{3AkQwS>;|>9xuPTEL{lTBk~?IGw7w1P3w5-Q zK8Rrazel0*z&3-s=~sl&R~QTc>YzGln21MNRPCPjxcxTZuUPG6eSEMtK<$Hj z{2*nyl}B*@7NG$#hit>y^0asJ{{(Nx-|Ot}fx6M(i}hC)&PDCZ=${5P2R;RA!_lE> zmlX@$93PjmMcPVsriA4rYcFsjva`Pp_yld&59mVNitEP@Y_ALS!q}p>?*)HFwQmcw zf@nk00dEi4I|=B*(&6R=ZFkt?w3i3Y#_Y%E4cqreZG6iH+pX9G0A&IoZ-7>S+eZ^l z_WS@?e*AOGaJ4$cb%YCtt|WZzO?@$t9N5`7TWI#~Pwdg8oA7&#bt?8rMAy*y{f73l zfnIpoh+o=$vgr5yd8QC$cHnKM5aOxiRa}n|f#ZHOUfs3EuiABdK9e=8r@nXd)zHH{ z2n2sU+;rpy0c^TqgzL|S?@92(HElJWMz3N&SH1j}fY(f(5rHqE`l|#g&D336?!$;M zOaZlReUD3@SAhjj=(5$`zAXd(vbH^5m~QQfbVA#Nc2k71Uf3;PE4;MNo1>@g*0(l5 z;-WeD!R~eok{@=T7Vu4{J3+F%vQa0#K(wFsicqH@?+wD+iQe(k=0;zQx$g=*(kljb zv}-8E0!4SoyyVBqF7|J2*sIyS_6KaRZQc8OcO9DK?!?hugyg>DZc-AUjMPV7_Ct-# zrz#1coCr`(0xTv1*d%w&NqsJp02Jgt@=_ls&yBdeWgOevQr5i|ir+I^QI^37tPAUli#0Cl>Y^ zU3}}5^q%MAxbXV%^Db=$_&gXY^J3k)a#Imgp3pTf(wx{~H3jjL6iDV+kq5F1hkVGx z#Us(Xq=*h%8ALVQAuk<#g_}M*Z;iOG$83y6uG0?gRflNviGB++xhEhXA$Yam-T7fU z$S}DN9SJvoXVoKE#4Z}uex{;{6Ngyk7W;aUKYXtDjdtJs(~jsjaj_rQ=*%-B(WWos zrXYivvQHMBFyqWhATMAG*NGRiNM;`GUKJbZ%!M<$$s+dU%H+GM82Wl^@@9=ovhAzc z-D5n2n>_sQh`B#a?!1Q?MWd66!%fl1v(!JyiBjIiO z81hB#9wZ#+h$ z*&WSvfd6mlSme0R!29<~v=ZObJmMX~%TgdjdKG}Ji=i|MN{%a5pga<8zTAI`{r-EHQ^<|~=S9aFAfZM9N8EUXz z5UY$~BO1z9+OF6t@ZAA&^_sS^S42eI6OdH%{ z3oA$0#aDd5Hvyp^m8q6* zRt-8)P*ULNkL9I^!Y{pF+O`TKJA`4cqv%pM`;rd5@>DwG+fHg*w`rVdAifkP_r9ho zj;ed=^g*Yg1O_~PER$bqIYme8f%=_Ob)a8gk#B8ZZl1XpPrNCt^2gQL+DUwABTHM) zFkM!%hRRX1E-_Z1_GsSgAVgqzEwaGs_ns7^?{jt*RaMyk<%8L)&+kz^I~WY3e1()jQ@EB{IJS=Hp8N3jbznaE z1tr)Iw2q3SNk_Xyly1wd@Q){3Iu0yo#_7L0wR4w&iAnyDcr*Lu2iU|Nd6YC+I<;!H z4OmqZpmCnDPE-Y6`J{NSg$tUSdtr?#fe1@STAiK922NHDw5sqf9B9JgkPW$MMs(1u z@3>ke?tP(<$upsz>IG#h+RMTLupDo?Th=Ap$5F=)8Ffl*T0S#%K3QM=9$Pd{&6 z83NF2pA~?y2fr{oS6Ep=Z>Zsrsc5K1z;)<9gad}hknHdvNn@l_K$3+Nh)63XE*s6< zq=Cz@`rA-8M1W5zTh&wPYKWfv;%SS3c5KensTRV$EhTCdj}x}2_o(yfIhsFUFBCGI zh{F`_+aXTu!pPMwlfF90PqZbk7R_qFBL;h>hc_u%D}kEp;6>^6bJ_})9pqflE?Cr#l)G^dGxuVwx;OrI+h8RWn)pR}47p*!-i zQxIEtUrY|jmB`)aw`s6&iJ#HrOK+Jy414@Jv#puXlaExFB{|L;t%TDI3gI_2V%9f> zV%FskZ=_Kmylou@DV8^Ywu7vQva;%+R{W?PRW$xH>*-mWu*M3L3IE_ z__5Ell%G_fW(@{6y8h6Wsc*^i$K_@Au6va;EkEg?VlO`Zmp8Vh-n^<}o2b?BS~O>r zUuUv5o6y8fN956SC(hcI=);#&;W*&$Q;hCl2QudkpbGRmHX#NVsGV1RxWm&BJPs)N zNnUs1t!nSPF1&-FONd|mG@&(}*iCjq0H(hmL2(yK?lF)#!cd5wBhrAI;FcOx+do}_ zJF8y&gP_e7@caIAKmV{L5uGi8aC#6?bF)Cgc9Ay(TUbumcAGtjem|t#s;U2S34wU+ zLj*^q>=6S$k#tfe$7?`ec{v|Fq;ACQdHO46)g7h#{vmP(drY1DqZNNIkS%C?Q8O|( zp7ztel35kUmOWShPnfL%O$CZQJy7#*Bxf!AxIkR6w5)=ofxTQvj_3d8`1<+4Y6-W{ zF@t>JZrt|x!PB_3$6fvheh16+L2l{p?SQ*IlS$p^+1mwm86fllze2Sa?L9DreDz;L zmQ5--uKIUDZt?7y>6aeag0vxK8`2kp{@*c8j-0cPJI9IebxTj zW9W{eI!x*VbO%yGVcJtQ5M04QvX%{OQ8W{lsqE?;9740!;{mrDts9x0sV(_&@4B*V zSnInB2d_)C$vXz!+HOHj)#di*iDYaoz`c+v;Aq(NT~;Yt18X{&&Yr$2>*b=SVKkQX|+r?K&>7f5VJP7Xek zRpD_E$kwIrmOF*NiI|;{d$@IeFG;nB6a*<1L+tCir7S5_GkK zk^-LJ!!&{!nkYwDmF;aPvoYxAs79V>fy$oUe^9;@N~JAVcs=tZkvd`PI!|i-kHRl} zO|iwzf7Zk<^yQsos>@|?g%jGFSK6C<0;X6+m46-qUZ0kklc_6m(8vi`Wec@T_pevn zStkcN{T2315Z4Q&-}tf|4@!Ol~pQ93nEdKp67DISsf=T3l(G>Ee;5Z zDEmZIVJt@|pSx=7*5Zm?Gs^?h)WMo7z#J4Ymy?+X?Xp-~yHeM0lhg-qfA1Q=KtH`2 z!9Yu7Qvp8j!~+#IH5{ZU!G_2j6${LRqHcFSfDmxMq$b1T(-S z4seynE+=ulf0Tt0p7L&4_z_u0Rr8oO2^PsJb@&Bj*MmN8AC}+tAGM>C#AIotUP6G| za5sk9aLN6643=PiX#D>&uRE@5w0vI^rM$yvckc*Za#YIiV&KttwP$Iq_yo1Tx$Xg$ zw+7rmRFit_ujoHFg{ry>3Z8p`!_27VkQGu!qokn^JeR1LL2>N-!|hNZtIHt%ShoR< zp4QpC82g=9^#;f`&EvA4BGXaI{r>+8r|q(J$PTkU)4@*ia(14R6L4)t)!~W#vkvOl zU|y?W1z{uQGi3iY&?>?VOf9k)>m@@Bya|1b?0Zo}a@xs)iK`D@8lC{VG;$u?r|Z2# zQ}~n#(xL9goFf%{-dcW_bp@Oft+$0zX6eQWTiOQb^iODuBkUin;u;%^T;NY3_w)7QI}7}x0EtInW=+! zZ6^j06D_s6(k76-mW&JQx1ptL4GY;)5E@|Qm}7b0UGS^H}Dnj~;`;HhrgfY~PEGxGS zDk*|wsVr>pGbu(N(Pd@CW%7cn{6wmPSHqoU7=QA8{y09^?;^oHIYoo3YZc=GpM(n; zd8J90uK`H24_w%~x;vu8|H7^U6NpB*(iWOn*xqLyI5j_KlSbJ)hL4kEYcLjvh-ztNuSVtw!fRjX7RWowBWldX^(aImfC^y)&X%4ZXF-I^4hN-@Q}C5c!zZ+ zkI%SYjAV84bB|a4jnQMabRp2Lhj*#MCi#hpZs4V?rA0ouwJ-y|4k?x*htJK2lUUMHOdwE5af=w9KnvY0Jn+{AQoJ zQg@5-wz#OCi?--4Fn$2>&$7DybW92daw5}zH?&~u$i@oRjA!PS;Ce{!MV(y4spT9B z0?SKt-a!_0#&mLtolNq`dR8@Q?gL>_GIvkStcp1thrUDxD=o~*^` zh?O9JSFcz)R$4zeOfs``AZs>2$T_vi)`zSqR056GLp$pDp zpsI{OEJ`rt|DdD_ue0N`!U>^SlB0+n0@%pATpI7VEZpN(Hk(;qrkA8<5AgqOi zELTGV@dOT4meVs}UNRt8V9icgP*=bky)sGRRc1FVI2mKnM99vaif+W9&t?glMnINK z$&f@i#j^U6d+jse?55MFuNzc~*r~-ub5D=C<^L1C11?3viVy#tJY4vIRF+t-kNT)RwN@S??C*qQkrAH&G zu9pV&RgT(h#>gaPH$4mLw*7B=!R$hPxTMz;C!UqHjcu7-BGS5aJcP-zUY*UfCQmZ5 zkFp|c7>|wc>WF;^JhO_Q1;T5IwcQ_ffc!DbASxIQoKN(pRU=xlRRd2=3PQaWc1`*& z#e#DeI28KAtEKH2LcK|*lVZN0d_|u}41L_=PjG;bku@%GZ0^A$=pXdIhW|O&@$_59 z{3A(6aW>jPzbVF<#UFYM%kGc@Gb>>Y7-xLw_zJw#@H=qe*Z<9mN>)rRUYqgRVPE+C z<68z{RY_YNzfVJhVe4=0$`)~$gFJw3TNrI@{OGv^>;PLIy}_?oKw1;uEQO3=70etT zah*_2e&o<#e?OK{iX}_tK~`kN7gHm?&NcaR&}cp)TIzx{Esm~_m@W8$z!YS`RAr?9T-{r|+S? zBK0*z)ZcEq!&VAXhbeYpWwq*5)Gz3_LNYu((2o3`F`^G}_pbBKlKU@jh#MqBU&bz~ z%)DEF0D=`vtd_R6#?;e_4tv2zq|=>_6smZr6<>r6qDsxS7_)3XJQW}VV4E(%l66XB zAJv)&KcEwuNu8ymt&ap9Pav{)^fPP3qX;gqBR$exfuqK+Po>?EkciIsuY-5@pA6zb z)C997k1?{*6q=5Vm@%@9L(yMyB2zH?;KoZrJJ~wz%NFP(wDEGJK+z zkw7k~#f15IS*vk(l?x8iY9pT$GW7_vJ)+^HBOhIBVJ71nQ5jcd&hWYPVynH-SJX!5 zM|vC{-cQ^ChNM%PNk1@;EHrY|TNL;qN}0sk_P^=0VGU-eCF5Ys`|f}MNegOH+3BQO zhGoS5p>QVu-@2Y#gt$tnLx7OVpC!t*br%%{h3K|dVI0y#GnC9ikwol7!9;8pRH#VP znl&{Q=k=C?!p2CL$VeI(YUuaRY!`Efm?+u%}Bb2ev)GWRK4Da9ThA67Ek0VcA7N~8{2B7U!v z%vBjfb=E(oFq3YV>pw-zWlU0KT{_k@P_B^J9sV>1u$&RcSZ0wty;8QOMB>qcQrx zp{IRHQzWY`qr#Ri7HT;K0xl|gl8SW>gJ?m%5u+k!$yQPX5h-i$5`ql*?G{M+0PThK zwKIcdA-EadyX544Y`l-`Ndh1EW$8|DOgR`JG*COtXnBnV>+e6nS z!w(cwlM7+T3i&{`U^atS zMxyK4GDOkrt-Qm zXCEnD?LZj2ju@N@z9G@SMOuR_Erh?>oxRvWlHc(5&6qf}Ol&tgXq+nvLO&&jlty_03QpcOa!*792k{DQRFOk7aIkrK* z5Kd4c%tn!DDgkHNLgv zl}`#4_2@cUS)0*cAohsFrf79)`r<=%7~IN=+H$N6>^2rBkj&Y6Y?by zbxV@rgNdrBOPa5vrefC8wc+{9YSeRQoqs~(Ey)`{&M0N#3o@o&dk4u_W<|zBaAWy z3eEFtxZGuQQXN);)5=7EpjEI8S6S<1l#^X9^b?dDBFQV9TiuMqB#!(e$`C?G5I+Cv z)B_3z8XD?=26w+>yAf2fBs64dWJj7lW}JRZL(3BRjXxK#E3~ z5v0{;W*O%*pxSy}=^Y~C$mRMhZ;mS56mp;kBh-#jDz#PnH zl+}5PpL_%+$r+QwP8d>Rxy7iV$0A^vtwi-Vg&&WBZ|0IpvY6WM++uOL0Ndh1!P0Y# zPC%g|BR!3;r2x%+Md@Ih?CWrRK~#m@w7yUEKVxcRE#F4i;)a%vRn}Y-sj&F5#wSCW zYtWvG6u2(&?c?Spz8TBrKeKC4Y$SJ9chr{`aiM$e$loqP66hZ(&XnGQ zh^y@zkzN$$WJ)}RQK_$#5SPP`^s=R_MF*GEPIr0ZC?pVL07D!)^fTS~wIrLpDD`Ym}^W6!x7<(0LsaTNsms)-$Z&i`f4_`czcI)`pV z;bv-$(YnJ_e;=vi_gF+2SXH%Q!W|T{u;1s=)wDsvKIa1{TTn@E3P+o3TU*zQ4xn*} zf1NSyyQn8~vZ33n1RDa+skM~Gdzz_^XD&?ApW`#uC;!Hgn(-%6Ff^5xWz~7Z*9J?_ z9-2!NZY~M2+jgLfdc&I_3ft8q1b+vJ32>bq+{&2!A(b}}vv6ys$8&wxa&Rf>DjJ4= zoxvjFZfzu#7hr#P6?L?yObmAdH=W>i_vGU{{72q%h4R?f#n-$P)>-L9O6#FdWI%y; z89Am-!c$*mWa0X+#HV;I`DIyUb>-8llRGOYg8462$3rD+D+LMFR!=kk+71775)Nip zGe4I#TqqA+Hk7MfISfgHg0huS&U93n;CTE%j6C)g-2LDG3GxTAFFKLJtl0tcIE^AbXk!kto-Sz7!h+MOa$qv*Q}W@P2Et?Uf@h3&IKa8 zsD_2i8VfYiRJKy~BI>wqxcqON`*sLuV4G%Qe_CV~|jL0tZmY5e`NPcW-HWOWSd<3F*J_F{X?WhozR8sep`btGF0n}>u`Lap(ub(va!(*v8w9rJKZ zjP;t-1V&EJx+?p{xYr@SnuehX0X(|SM-!5&9IUglZ(K&HC zX7kg-NS!#8k7R*VFEM*pQmhi{uku_`ra=NwD(vWty^QYIz?)RW+S zIMi)cEUJRUK2@---J=R-kTNX2k!xSH3qE4ucWv(8DA}1|cN0l_EfIC?=!Naam?s7U zf;0rUbpa_iGIf_0j)j;k`YtLfa6j@dl0W8l;SKB!1xa{k#6GN5!pXMQ3wn+?O$BtH zKLiV52NT?Wd_S$hX0lMhQG+&YN1PfpLyZVH8b3-ZjEQ-Kj)}w0S^48Rs7LY*66t&7ev>X&8M4Nbo z@i2*C5dYWEWX_Z!Q3SsPpBN#}T<-`#Fc=!3P~YN^0NPO+vMX zza6>P{15pD6Z@ z){ZOUDJokNwvBCy9F(xPYa``}iE~v{dvl|EPEb*uM2O-QUXelMubMb*XK_sjK{SPx zw`qM5%@2@;qj#!z#W^&)C+1vP$mr}#$)9%nGbjZYq`$YZ%=I+!O!NSO^Z_=l4O#S0 zCYykngH*HT_|Vm9YsawC&OshRnHBwT7-R_pAEWNYbyHg244Xi5p2FmK5S9ozd53Q5 zKl&^p;%5H{Z2z5L#Uu8Ej3+Dh%Nl&v_IR_R?2w41k`QY-MjM(y)3dvJiB8z(n0SkV!!) zMkW^C>90l1|KfaTi(s5fb8DNAVCRKB?MQ3M%m;7a_?g1@92V5(MEiwjW5wJ}ZmOyW4Fw-CM4A|&S6R3e8Ms^wawxM!^ zV_MtgpY}#we5;n+pmg+B);BJ}(&VV2y6^N!(V<_lvP zV-(Rxy*cc%6UVsA@Z9Zda8Q$agcpEE@|Qg09o1Ge_ogtwewmfxx862U=+*{_SE^f z2?bmgNii6^y{P|#E7y0bD;<#Ii-9OvHZz-sb*SEj$U4NL0PV^8~(gLH$_>lZ4(quGCgiYP9M5ziMeH~awg?P4ET~W zi%2&4m>RdPAG$$R^3Ns*unjf9N98)LDQi0qNc!?^^d+_PFJmI|6VGbWb{>t(3oM9C z;GR{(s;Q{hXWZztWu*qUJQYgr?hCc;x_41Cimu(ic-!==&PQRF2l-0t8d1+wd*iSQ^*C2`H<}-6M2hx>S zl-I=MZXjz){txMW81wfye|X&8KU^cvvc!#!(x*iuMNkB)NRVx%EVKr5sX}>^`w@r z{C2obhREu|hm!e}^<9^C3HeIuYFepn!~G4v)I^Y3`$5g=PDr$4zihTodg5Z@q8eC* znAjM#->w5w>TDjLzP$I6Pt3d~n8?38?;P@b4|VJLp7D#~07;iKK&8UUk#o{$UvV?z zy?5?;Ud7lT(mPj3P*r%9ep=Udbq7o%NtV_6>7MYhn2df^VfO7LminD?}V^%5uv z71Nbk##lnlc7{E5NAd#g8FG@(&UPrPdG(hG)p=C=Lb9=E9L2M5PZ&=gBbeW&d6%}x z_Op1t_$#G8{@1`fsXqV?)4>t{!wrB22tYB%#y2&?7Y)ID>s=kghq}}Q{YDH67OgkthjQA&`ZN>TcG``PdQuoFV zkKU7^H&jnMhekW-@+PMT&eBb65(2*-PtCaMF_fkkxAWDTK5k8JWuq*9PoKIQ>W4DW z9F1=$D@IX|Mwizl=-bCxZsw zJR*#RMWbT~!MSU{1J=mqK1PW*kLxRu)=g~LW*=$l0Re;b#!=3chSJ1;R%qkL|FV_$ zY=NHlQUHgD6;VWnC~OqV(s2VX1CtArk%Xr5C@>@_Z+wZ&zuV)u4oy!BFMqlg-`vgT z*e;&njyflseUj1n9uzgvVXsA%OzFaGpRfreY^@*MlT$F_r1`-z4FBqQQ`$naPmh6= zt8C$D!%S7uQ`I=fWtq|@j@Lgjmy8uZSdOg5PKUEZB3O zp^~tOTD0%TB7(e}88;g3G|8$Al82n%$a3C`#(;P#%dws@2Q4)N{+iR^=j$!FADgZX z=4R4+QTV@VnyYow?qr}Cg}y8IsdE4d_2OK(8xDlE1?wK1QbydTcOo?TO6^)WoCQs- zDTLNHQL;iLZR93+Q(k#|BOyuST~O#^=*zpuMqF9SO2Co}HB97Ilc-GOPND1Dk1iw^ zC5!V)qThzwBa{@ZNv-^nTt7V?$Uu1`G`DGJE5_uZytY@xO{8X5GwRc!NR?XBWS*n( z)#Yx!p~8f1VssZ1TjQU{Hb&Xa#2R&%vRW1h-d&kW67+<{RHa^PFQkDg>)x5Es(q%j zB=Ik;c4+^j{4_A7DyyTV*8b5gP;d3N(D)Zlo>Z}0l-ads+9P?*@K85f=mL0mt*_G3 zGJ5sgc%hllh&;fVs;gTOkrOnYmSA1PzS=&ube4_`qBGPjyWx?Pp^bkjTm@j&ty%R*^L-V%q3N9jT=Urt& zEf_S~F|CF89p#fNk;#xH1|Bh7b52GvNOg@fwC)BPwvud*MtvTys>W61X=rG3n;Kc= zb1w0h6eb!%0ihtCy0cGKul$u>00%x7$9ZmVzqz5KKkf;7B8lom)Guy=kBHZpku3U4 z$@R^jjc%-e^kQ`ew3Akq9sLmU&4Rn}w7;(iK<&;$9$}gOAzZ;8Q&3mJp!V7n#-9dP zSnK4@JfoHmCvd8!%|2qNuB&@iPgaY`Pe-wH`wBmny#Fd1YlRrd2XZJx6&*uv+$Zpc zMu_iVUNGbSgr*0X?(0epy!ulhd*M8LHTOg&%3mm4d?fyH)Ewbd?2MDXC6uTnV%ebA zIr4`qhN#9MD2vjeHC6mSl!Hqsv8@c~Cq^VVGx{L@t3=9tao&#R-i#@U;-&s)wNU}} zQ*=IUzLVrcHZL{R*cyY$3GC9(e&2WCH)eN?AI7(zyG_Egv|eamwlAYMkGt(V;5VGN z`8(P#h5zZgxlQW@_9goge(Sh1eDi!mamVnb`~rHrO?#T$h3Q4`1^@c*->j1R)vPlb z4Qq}nM$+om`U&|N?+!yp-s;LuKzDm`u;e}C-(5ZKgy4iMK7*E+`w7&iy#^)!>{;s zvB*PKdc&Qxx$@8iIFG_e_U_Kg8QHoHw=;G1%Sl+8FPEcKDMX1I9$jaZb5?OU;rmt!C60LEgKN29WuW0&E6E5& z<&9h@NbBwwiUA;kI>ZRZaar-v%DI+jzWBN3^L;RShqun_`;XflQ*BNFpt`g5i`CIi z8BXp9%E?j-Q_Uofs9>~a^5eKJL?5OX=m+Et$Q!&HN&pQY@RcU*CL5O(ZwCK`^7ek` zw5PpiwWsP%_(k-_x^=Rapn2z_1vd(%nX;<3(3c-ock^u{xleEBX7?lk1A&m7jB+3W zUGhgsM_Vf$L(YMSy>uKoGc0M`u#!V=+)xUyZK6tQA_~@6fdakLMh>0=eSy6ULOJ_! zBL^o)s>ih~lm=QyCgxviQZpahR*B@o&yqb;E3}ppjb5i4KI*Agz<93#Zc^`u z6S?0GvB$exA48ZQfiLRU=^fAhs{kv*F68WBTA#eXU4Q_t?^A@w`=w>h^%>=U%iP?1ed zu^`M0u@CxZs;PY_h8H~)g#Ub&d>GOJbcDrBEaz5_sES(9fT|3suSa54OwJp`j*Q%r(8NBkyg@0;C$SG#2)g8E0DmjlbMw5F z@)i8)5l4g>Gf6@lNWnBKriB}p{YCLDd)pkw^5Sd0j|_2$QPOM54@@&+Nwbo>OMZ*c z#_Ce*=iCFxhS9=_kJ3ercqc?NO*nhfgV~(oEwnsG^i$i0m2uVTE><`9$C4f4@Bxn2 zh|CdDJdLoWl9>O1J0Syq@GX5Z@-@0!IO=(O$%!Ok&r<_U;Tt~zmXgpU5mFq;47U^W z&vfB04D(a4fi#N}lDhCGbHG3iMG4asW2pfCu$&Yq@(@Sy-WC75G>d(B_GHKZW1oH} z2EBEodAzQ6u8flnY}V;H)48L1)AR;*#)PK&M!(ZH27czRM+kedCwMn-H+nb3H@G(n zKXKkHer&zrezCg)g!J_TGW%ltiu-i?;sqMj7}`Uy!`efmL*_%%2Wt0_4O*G>+YEeE zJw!d^Hpx3_{0V?$-$a%51nDE?BOH%FUeTMx*@RzGeR6%W*`(7+*rTlDjETII%M{TG z8mSgnK&zHlpZoUP^xkyURM_N6JT&XMU+AYBNvs z@CLO_S!)^pTKlm3z?wm~`9DUkRV*WT(^j@+YsP5?W|mtfVR~MsK-ObTuhy*A=sLy5 z@k@ql*LU?dpr_0!-l=r)D*Kf8y!*u3mEReQ`@Ip=4`#h-&1zkI&99NLzPAz5anylK z2c9FNE4&Ni@B!`>oFkp#fZ`tWZuMUJ&F+2o-8eWY1RE=7Gh}#xWB_+yR5;f?S%Xpz zEe}N>^-~g3vPG$=S?HsURghnf{dn=H-aEuQ?5j$r`2Uc0jzOM$OP_B{TQhCjcK5V3 zZQC|}ZQHi3Y1_7K+qS)Z_ipUnXP@}*n|)Cc74@njGb^*sC(p^Rq}(JpY?iXNEWDyh zaaAc^Dd&7Xi%5ETW}a zFcSjv*!bK8%!K2iQ{AxJ*6ZNyN`{tMwtrNMW4KRPBctuYZ0=;OiO$h1vA4Fkw}3Za&djS_xpO!$RJ}%< z&g=T?%IkD`#SE%V(oM2TRJO3L5D1BOMVd^q4Z;lqZt4&G3xYbkR1X4rK*4*^yGVp* zBBJ7?{H0=+ytY!Of`@s{YVo8pS}{Ut;41R{i~fcBg|t=4V;kw|(aF-u)M?c*-ZAIB ze*MER3Hl7%c?hUNrW(JQrT3%aqvWHL6N;%h-KA>8x(IgP zl7Yt}G(>pAE=f)@@T_Qwsv9)XZNhuyI1o~_66bueTgz)qt2&C0o{8y^`CWaNg^a1| zE4F8rSJx+V&IjkU6st7DBx5DRC9^iuCtSwd1mzv|9rT^ko!lMGojubO$5d;Nx_*bD zRU=Q`rvZ);+H#(jRkrn(ewVRzU00p+vIzUdWXq)ZkwS3lD1F(?rT;RKT9TE)Q7v1w zbL~?dZ?%839e|R}zb)!5W^DwgC;G_b#`|#VKq^6H(0us(+JeW0%fz(w0;>5~1KcWFce>f@z$?wG-3QJG%m?o)&)`Uq zRRVeumI``!q}1TjV8tQ4y${POwA#kv!eaO$#9|lCATB_rzN$96daDt^CM?rFBREq< z?2A@6rQw;V2IYL^-0_?SJ-ujU!Vd7Ag z9%!jeo}1rY)?M3OYVV%Wv(>BRGw1W~C&8;d$g8|nJtkA+S!BVs`^6#Lp}6j*lR`~t zdCB6^qTb_(QwjILWn*@u4v?btLzM<>wO6%xbvkuh{&(=(k4Nx3ij#+feql0um@TNZ{f_oWw#l|C z_TGEAN5as1{cbgKu%Ra5U&w4ZBs$@|;X#TZUT49~mhy#ywHNtWd6Npsr5_D5>O!0v z8YLeRXGIpTQf^tcIeM4}gWpoU-M32lGpF_N&cghoe==4kF^}Mmto%SFDAJfzfYhm) zmDbzV;Q>%x2|ANi+dBIgdb~YkHhu&d(B|!;?b>cyS$X3Mhg2{L>4|~G-Ziy99Gp4m zmF57m+KZhtUbBx2cMpOO3J;{*uYykS z^0$cuqk5w?qhett36u+?E(gp;L3aLjSbvW=N0p}^*<$d6OI6C~io+Jc#6H^}Wvt>C zOR_=FTjaX5zNEI+*q7M{*++_5htf?_<|ZU2s3wvpmL~KTp>nL}Ueg<Ru_OG( z%B+|qo0JCOBsjAfCyxr2S{|%*Wls zW36ODMQ_54#wv@jj>MVvfoF?m97MXEJVJwT25*(mGBn6s<$% z`2+Ml>)7@D=Og6(oMDkqeDDhS+Qg(Doo-V#*)2=&&lAa!Bm|Y;HkG8KZJ*^lRoYb> z`5RT-c@=_hUh`hS+J|R?_kH)dtulCp_N|rCf5NAF(X|Vwg3p}`2n^nP(DjZ@-yHTV z_ofD=20aJ!V=_sQjrqx*so0<8>p#Hmwhm)at-r^OYSdL&l(&_O z5D0oY`EOWG)gP@&TzD^ATu41CzhS+hx#KevFUI1)U<$@FA*IdgWUghBWuRriO|rrN zex8YgSV-ayT_CXK%$eEjnEBXjnr?t<77IBYca zKjEKv`AItl5KA;Fk~E0bbt@f7!2C@wfXMmiB<`U2AUqg(8xa{J8}%#af2v62%z4o! z)*;%$-vZ}y6Wk=Wj`xnaOXx`OOf;wWrTzD6JJg;{y^@uq8caD^IbAuC+&%o>0|2%@u`U4k)r8LFP0{=bZR%Xs!m_Roz-h`_>$dX4?Mi$@m+wB5 zcvg6xdm-&ijJ{45xJsGY8s+Wbo#^WA8t@*6@gtH%oJ6`r{3IyzDPy1`UgH>ZNYnjpG?+g9=FOlu2h0|p zc9dp65j;*d{+05kQR)a@{f>AheFkQ#|K%6)wYhuF7G}k%n5iQ8uJ69oWHLsu23ZWBrwFkx&nV{L5%QS zZh@8mI(9$aINk`_?Sh9-_T*P+S40iL&tYi9R7D2ZGeAq!~j6401+VpgE1vyVrIN0|p& zef!Y9$v)Zv+^z8o(hHSq@OvBA&!k0J(J&Cxwfw}I=?v1o)wJAk#Yv?@$|Xu~Ie^Ng zT$aibKj^#Ch6L6R+!DSe&!0A1IUQx5e=iEIs@Tp{PMc1=m+<^LZV0!(d~PVJpV{&^ zVN=lfwmNV<4z%q9U-DdiJgX;Gleh;ftBY1~9(99*!Ij`nY)CC5?e*vm8AyEchn4#p zpAnZiAmw#`utjNrV|xU?p;>NpJo`WY^oHq5wu#AsA`ytB|6_`{8VJ~7+;KZ@>p%UF zWfy9fS10KJ>G&WDjeUxR80$MgGStE)6WPDho1u-#PST0diDw%Prt;J011(X)B%u1t zYcJU^8(SD!NS>cKO+J3;T$POk15>e(s{Tzo512>wh3P7`ns4l>#4g5z3Ll#-yB8il z;yqzIb{5FiEbA)puDr5_WeD^2H^J~`tOVQIFl~qFY};5KTVLYp$2Jzvxu%>$@Hl6s zV>?QB?vC<;c3NqhcK2d_YJ{)#K!xzELw8ysd?PqE&Guir1OvDu6JJ10{t%tVr>~i7 z0j+gNy-T@ExU21}c2z`BTB$i_JD;oOzk6mpp1R|#d~ z^Qw&P^!fM_vEkR|Q3Ax##Z)DJ5%N}L6idsm&3E-Jy2@`9!!MZEW2_=huaT+4)W+lW7xJduv~?uAeb%PLO(JCKadT z(E5VbVb5HN2k)w?A#j5vKTsO${w@J0W8r^SHL$wX3_We|(B{#1WKRxg&0V`Qo->Lw zIE(a$GRL3vEu(WF_CPhd}UU5mL8IlM5a*T?2L7nDplWKMU~3ChRr8rB-n>Ywx~ zunVY6b%eUKy;Z$YP{%e0Yr3mQ_Xt%}rZDj^-1!h}b=Rgq2Do9{o;ZhXfM*SY95Gzh zD6boJ%6l4tVC;iDQ$341M!oPZaL+T&Bka>M!@I|n`SISO>OIYI8-U?`z-&0yU^n*F z9|4b0k5^iruy#&3Xy{0>o zdQsPGdSJ!3FuuPKP-TANnC@2Wx>gG(hfam34_xeK#mtZiqLJC{5ZY9}6`1^uoc%sZ z7d)J&c_!&p_*;@a8UuQh-iJGj#`xp>B?b`9U;5FH+novfM%k}5vH>b_3j+Y+g+(k$ z?F#t9y1#6CzIyQt*aK5wM`_&~=*8(Z=;hG;y6XLDGh?rtyiUhM{Ym+dEHeDZF5e^9 z1A%x(+ag;uUoK1<=V;+?<3=fFGAjqZLBVZmz^uVJpi*ec4Y!ijDFH5fDh zOAhT`ojYgBr^BY}Gvza(Q~N9Vv(C$hVSJj8!m66enkfmZPik^LS1H?w$NW%^l6R)I zoY5k00hsfSQ8jI>!lazd*J!O`?_6NnB-#HHFVKp0IG)!aLm@Mr?*V~5nv?GL6~{Q3 ztE6|gG2Wx@qiK=>)e75+)j9d3k78GlJErEH$Yet$%!_&_@Z!V9JL)HrsggS+DA+IM zRgCGUpVEOIn@IfCR^lu<8gPiBejecc;58N=-&B(P+yz8+Z4BnUy ziEBC8*o4?H81nesgxn;aG#3evi72kjuPAYJK{z$4+8`}0*q)jcRY^<37P)Yjxy9mC zmW|mc!W(GH^Rf++9q2B$;jcXR@t^Z?vJDI|XnVdm$>vKIY!=R@R6ayq7H?;L4>`EA zZ6_WJ#-1qz=mrr~dNS)!6ITTHpG$;h`&Q zWa>07q?ga5eXrUfy?%GEZ2kVByl5s(WysIwJJ8ETD4yE4qOd$N4SuDU+-I&m*4f($ zJ8@yJdMR>E2lsA$krp@EU;h16aO6J_RV01F1QN4F15|6YdjH*94D3E~zXE>p(yc1YL;gb$1;q{p_h_buPvR1KMUU|aaZ;|8TsmHmsDo>_(%;+w=s>sNha$7oOWSSE zE#&?J)+oX#(1W34yIZJR*DHN_=)~#J>CtKIvQlG&q<_aIqm37#U zZ??uX4htuTl6U%dxOXJ>`K|#hi0w!4XGp4A5glapi44<<#(j@kM&7!3@E;OBNp@v- zId$OJE=ZYOHhN4!nZvApyGb?Ke5{e%%m7BigMsyp^}1?6*PhoN{JzLFHQfydZ>06n z(e)DFkxmaD{3#XzxxWk5sOvA|XKRvp66-TWeRWUelHbWK za;A8qK%hFPZh)gH&CKU6<<7Ta>ST~+G_p@}O?e;zYR>D1(+lET6S*nh%o2q-W7xYxi#T4XUI?0h{u-e49gJy^uOY z$!}5P6t9RCghN8!0Nx0M{0KnA7ufs2yQcXEjZai(jLr`jdRB{O#0+D&F4T2n?k?Z0 zA0-_q?QU52Wf#*HPS>2dZ;xo;kp2N4dLcF`^vJ5rurB)o-9ljpYofu-Uw$bo}Ko^y9z_alTuZU0W>&_u zAjod?M}%kkv+SfWj(QzmHV$@ZXW!5QrmW>ng~uq-a9TkzZ3dzozFqc^q;?UXBN3C9-o zr=!#??-H?Yusm2xY?0)3#&iD?mT3m=mBD^Q@$c#uwk|y5-2{Q@mFyfuxI@72QAyhT z@$#GlNdcWgKf%Tns~8Nq1Wt&gkAXwYdjQYzv9Sq(sTo7DSxMcx+D^HHvOis=qOq@%Pt68rI(IWw|X!K6rZ#vxHmcWqk#2<_Y%wgaftKu4u zH<8>O_OV4>d-UIWm;b$+`Tz68$oUIGRs!?~G!PIFB#;8WFIV%n(m^#a5D+CO5D@wI zQv>VoDaZf^BTG7cOGhIIYikEnI)U#yL2D-?F)JHOVg_0ROFeu0NO?U8EdHOK=^5H~ z+6{#@>J_XD@q-DEmNPQq{DR>EvIGNH>5dF#$=oe#Ft1gV_4W6H-hAE(?CwIbKK=eH z>8YO9hZmEdT`zA4e>}QNgBjW>`+C}g!P=c_j`c?du!3yol+3CptJe{2=@eIo$h*i_4YJ6w5aOax27$o6bu3buiLwgg7<+~RJ!Em}l8h6w6;%zBF4@7qmWp=t zjwGQ4(>IqS2s(5g4X{r=Kz3 zbQFzW$PH)ywCxPU>?mhQn`c)W&_?aw*E~uwsaL1X zfF>Pzs*q`?C^gpUhEaqvqVgylzD&gAm3#KzjVADV0PbSmo{IUM;3_t}g3TLz($3RS zt4RU?{;yu|XYlz$@dF5``a2LP|H13}4)!)Sbb{6ZfRTZNnKj_weos`guwN5G=00nV z#j8b%i}`{0y_Zst6CqaC)KmaJx)6Q6nHgbKHm9~-tbaK!W+@Z?y@U~zA_yaB>YY5O zt#)^~kxPu%RHe;*s-?~3s^jg-+xs&Tczlo8SIlyN!S@Zi5rs<>Kdb`1GscsjRfqH% zB@C+8C8Zx;92%D-ch_QtOSw9||L3D&UDY;z=r51_Z81ax7s_-&uq{fL!fj5lEheFf zGzFt(?RPov+^%`^!kyK2edxJH=D9^ytFhf6>f^5^=P%N7|ona@kkr7Wr}{bZnGu;!E^l?QpA zK`&rJcGlSaVwez(biS{<J1wJ&q0nA;8Cnlb>a$B4$1-t>c_50MM;$(}O zck7UMe_s`=EPm@xejvQN8_C0;YGUnTmU5>|FI_)9UolmL!DVvCXPv{o#mW)-Ia!l) zaPQNk^N)WWY3OFFej3HzWf+-SE!IuyMrEAt+rmRxBEyb*@>M&Ljs z74bNmsmUkuFe4K{+gd}qd0FsA5fC-qu*|JK8%_s2287QwU0=sYg=LG!Sk-a)wO!MJ+D_%qc+lO_&b0jO;|;&h*U znLKDZI-k(M(-eVBr!UC^Yuhs^kLtqSu*SB&lPiUP%sw!_{ZE)6j#2972evLz4d zqr7#|9L0-G-T_CZ@3s9N4ZepiIA4{bt%BEAn6V@IS8@$axztc8@QU4wq~VHH>DqDc zo?y-fXX^I}0)0QskyRI=#~eNpr_|cLGt)f@no)s!0s+@?0+^t|Wc|R-sgPJRk=qEN zwEZN5gN35AR7;joP(d54?sRP<%{srt6BmERyguvYsyHyUeVG&gaitsu7oO zlXvB^=m3hFt1dNX5@$j7%+vxTE_d1l?0OFlDpC|3qk#F=3$uY+kiBs8k$vG2Oqf{? z=UDgmfm9e9ohQr4dyjzuMC(vkgIf^w?Ip z7dNs8OE7hZ;fAWsa4SIO55{lauFf(B++df*h*&2MH zQAzoOBF1Hh zy+jWi1&&nOj2$lAK)@d^*r&6&vuFB#s_|u(LQfQOlXH2e)N0D18tyAdQYc_ z1uq^ZkWH|SEm-PNvvf2Ephgnrr{~G7&>+e~UM?1@=cxJYK4zri@?$z`e`98gn^~si zNQ^Lb3C?cnY;{q@o~*4omSJj)W1a@9-#2i%Rm2-NPRzQ?B3NIQ1I-9Fc3-tI-A!Jj zR|1LT8r65hAa}pp zl;wC6<8(w6GFyj97r6#Z9y<`eVi4XseJHgHEJgp4xmy-7XFwiB>)Y{QKpa8KpYe#j z^WZ=|jShZYP)_`zGi2)5REkHaouEP78){nC`tm|G??d7(LFfbr2OVYA?mOsHV{7b* z5qT1HND>-UriytP9UmU45F%7aSA2e(ZB0tpZz_Imp^7SC;UWHtnsqn_Iad{EhYELD z*5m(%8Fo)iyNfu$8J~M($hw>iSywgP>(vka$f8_hU7h9`?(~SWSba6q0x@8to@yLi-UP|y-2<>H6dec!KM-B(LA*-08REvx?2YATzk$6Vx z495kE`?#P;guF8Heg?A-(!)|Xj7Op*uWlhp5f2ykrwx*Zs5De@FeG=b&uWm@Xw2Wn z_yx#=Q)pb$7V_DCxcEb$lXKXZhVWbRSYlfYZ14a3Pmd(c#QgjJJ{<%Ii1Z&4uabkA zrMbKh(0hciD?+^x+ zeIUNqi*TJEk*S9$O0Q>+S9ElrwfXt(E&NU1IKlmA+cabTy6fWrX+9b*9j(f)(C6pZxj3``Y_?3~ODjO-On?Tqvc z|LwH}6;}_%1(eUt^HeU7ABfnC)#M|@1Phb{KBI`!ruclS5yg&-uEhTFsn5owAPc25 z<`NYR4d(ndxs8X-&z`J-K`7a-KSDsH< z_LnVNYDXt@c7=T2* zcvxQNJytq!b(5wsn_$>_d0FjHL!#b7tx&0o)uaD;HN+drryBlIJ zf^iKF{(@2w=C3~3{`^Al3UzhuZ_B2MM!ABH?MC#5XN8T|pYwQ1bA>EN7 z7KjY9SY~wWWZYXE2rnxW-7{wviVK?YBuD)gd}x*{m=rsK3f8yfm+X7ysaMKXrC&8p zDKn1~I(@nE!N~4lG_4;LoCyhvQIUOkR(+rT`aCU0!5>uC5fh zzD-*XJ(?Q0z0_XEO+3rGislAhx;M%jZ5dC19K3ai7oSe8kTxD1c&`MAu_&zs&(JSx z_!+hL581iikPtYzpkvqKoz2}ZB6d@~jeYK1(YbO{0S^ORdQ2!%$@nNnBJ3z_Q92^7 zKNz?QQWa86GnAhRJ4vu+Go74&S;X%ODMH4Vb2MwFTWPTh|E4a}-3wW#_cUW9{aUXh z3PlxDPvV%&dC2M|CDKmDfL>I>91Sm%=nQMP=ok9~rZsGUS))wF2u?y+I794{Mlq7F z&rM8hV6BXg4UqjkE0Ks=aJ%G#&da!)ghpTbAWLn}6pXDjVyURO&Zc%hD$+t+C06t| zzmDEeLj1*daIkfA#a`1EZ<9FkPafeYRmuPJjSM+ zCgE>wq9FB!9CpeDz5{||vT zh*ya#k<*lDFpkMyMjVqd8~CJxVMfOKDEk{JoCS8RA&lY~1~hwzalwix64g=zg41;u zl_9(vGMw;g)u9r0sbHvG*_6hCzp8u0N*rVjKa^W+b32a|tB2$(9~EYrd5#SOy|QIXl)mf=D*Xt|TG2K?@te?ix`&(<|*0dv+F^?Y_9`R}RtM z^!sNz7E9!c8AZ#iAt|qWoAxXJBdOTqkRd-YmFrAyId?claccp~I4gfxxtozS-LXj* zzv=tO)pAPh>t85172_^Si?*9Cs~0=M85h$R%138RVdJ@yQBzUo1))@&jL2HUdc&LR zIWW{Mf)1I|LtC1`UDceClqnsvAdC{m-W?!8%ky6k#P-p6^mTd6e{<6aOl%vVv6DxN zntoZ*VI|kgpcvYxlW@yhY*23Y=&=6=o`Wri7SwI@@612}y=>lCv^)iFBbFc+>tP!JVIA+0da%o;W--6TlkY2vS!Lf-t z_9+9s%)GYY3|`xG+JC*cm^MPk7sQnTzcrNQ1b-V_jlH6?9{Twe;spEfhJ8VP{kDEV ze*cznfqqDL*TP||$my|`aF{1Wa?4KJO`joJVWLNPLq+5?gxF-(ZwM}zDkwRLPYHue zD)Dm5G$W*#L^YqV`3_K~11LY6o0AN$&5Ktzl_h?Y396p85@o+;i3*|4bVNZ_erf(g zAiJD9%P%L`sw#)82WS0$!)RXbecFiHT%>O`C}TTm-y-}YWy$5pyjNr&11MeJV93Mh zJ@Fp)P75~DdFNeIZ!@))sU7>veuhL^=*`H`2Oa^fb|ezUx8&FLH&&vi*|C+Q3&dq{ z&q@e-RmGoSj4!iG8f~D92JIXdd@sf>RNPLrR^I}(WbmD(hn0W3HGie76*Mmqh-kI` zncobpa{Tp!jg~KCD$*b^&3e#yJyJ|Hyuu}8Ypq&kB6`n^MMIbiCJ-BI7^feob%C5? z@kg2oD?tTW%CBD6U%i%Y>f{uDcm(1jXtGWjvr?A)5phV%fvgTUhbA?cbUPX@nNpeP zuD|=tfHL1a(iR0zV8|`t;pzgxEpxeSeLqI{;*}B(7w5&ttrVyjnzSnV*Wnuw?Y~8; z)a&IH&{#lZRC!(S*7gnQwf;Z}=on`UYdCH%w-~kAWCS^)_Y5qtaQQ*qjpF58eM=T# zO09WZXa3TdU5+57>~?->0Do!5Cb9*qX^D&a^b9&zf8gOgh!(1x?VWUvB%y^Wa8~2+ zd=8CdZ-hY8H9`Ub+2dQ!K$2 zY1woq{ZJV}&%cqcz0tos-|5x^M`$JQIEi1Kcd@)~hFjb}Mjr|jX8O49MjsQM53-Mo zbhI`@#k+3nDl$_j&ucmL(F#}0Uf}FWbQJFsSm;Q~JhItq^F6YsW<*w}d1f1xINV1| z914ECXpUZOWO!bBh1~vbYn*u<+9Q@E6P`gO zq!r{m`P7eG%!|Ie~lT(5#y{aEnLMj|uC7 za`=q;dc_FdCI=miow}LSASTJ4FG3cLsVNmb2QrzfUOCuz+h(#pnjtcjX&c+uRaR}v zCDfzr4Au<6(`fV-Qlq^rXEc3S5(zji^@+ueKBb_p=)#U{B{!;)M!C8R*ghN#4&z%Zm(7j4r9}QKsm7fFsI@6avFejS@*fI|J!V^kuScQz9IZwur2_Z( zOkii!G%3N{Kgy^CAE)cj$7XApP{z(GmOIPCJcC1v>FTPS8(kQw?l6t3I>!S$QnN=! zJ-~1l^|ScR#jJiCPSRX--(MPcm%(Qlkh*C@QPe}u3D{k84`xGZhvON}kTf;X(izYE zG1&g3UwP7;)DoNG*j?CPHA;Pn70;N=9u?NC6=`Xl6B7#zb4$qM@@PcDA5!jEr}WPITsd&}5bA zrh+Y5I)1HU8fxz`zaf?G)?f#-u0!qYiy%a~reT$~j{D^1`ScY2f+$abKtI5n<-%hi z^Bm{8Be)wZf}Nd0&wxND&ZdH#B7IaqA6H>wVpmO!GJwnOn{E$y_{JvX$wkH7H~TnZ z#nJk-twGLpsf8O};|gY_sPv$VacrYWFX|*yeQgQ^I%$?#5UVQ(_xd;XyT8Tx4=bww3Lc3i&GhZ`>|DhF#@2RL zdjDyCWXi8eBlG{{=4Lvt9y`|ldF=-s0-k)#g@MG9R{e_vaIFUi^*qm1Kh4gG#Q$b zg2mAG1atZB^Peb5l$Vo1 z;{W*>l%)MT8VD?m(42opKEVC9WDr6QNm4|CBtK3s{B#%LO# z$|fe+Y)N}nkK?ON6bfWkE1$8Q(LJxim?FQIB<#e}5Zu`#x?>7*t ze3`Oe>GxJn9@Gj)TEx^F;%4X@kk_zlz*&1>dQZGT#MDQL2~gI#D6z!y2vBraZhjQS z$59Yf>I(P)iH8oFSn0*L=GS-w93JZiIMpovuBdi%H!c0cW$WPW%8|4TcSH!KHz#%A zjdDAB$uFqLda6C<(qmI>xzFQghx%7dUU?1

|e}Ac79mJra7-#*X#_CMV}_+H59U)V(qVC!gR=PK_A0O;vk8vPr; zM8-%+_tF0h@=l)Ra}6;X05e660W}GHkofl$HL|`uNw3NwIL4xg_dQd zPj@{|e=#|HxOf4>VjuJh$b@Wzg;+eZH~*U>$?IyS0y}3*J1$7rK$Ms;8qYL15zlgJ z3OXj6egPDubI;eH}J5p#nNZ+ms?dC9h%+ZV6SNw{;*rS+fTOdw*i7|V_ zYb?zZh&1p(O_7o4mb5w0#9vIm3Ei3yh7P}^-1(?}CqE;$HuCe!)nMso);*1r60InE zQ2v%gmXq90bAFXO1dt#?#ltK0dnexQL`;L%Ps(47(~N60zB`=%G2y=e)>FBAY2UZ$ zetnyem?p=V{k2SZ6|PeCvbo;_~w4be1D!# z-n-v?UYxivxEx$|d4H|YM@E0U!^d`9-gvu%#RR=Dc;)u{Y~H?N(|CrWFu3n@+<1mQ zT~4d63U`d16F9Cg_{aXc=Erz@+&uQj-;CM$xcB!sSWn_a%Ace2G%PiL>&Y8ZVtw%h z1BRIB=o*H9lhrh%_oMJN5Aae@v9tul@@M(bSi-_az)Hg6cMtbM-c!TG4D@$HldhmQ z`!J))f)Rmof|6lD0R301?4q#ZqI?&iukQ{R`#)Iae-|N1MnQhrf8jkNyZ_dFSCmqj z<3sKc6r4+f3{&o>la-YK@>i16c=rK;R_5p98q!LOvZ|M&my-JmgFypmx<_rnY`o=j zZ9;`S3b;kl<1iLuFoWUd1-0M zRRXTqPA=e6nR(dXFzz7sM`=^cFK9dFbh282*KF8ghUPihHE`c()Z9wbNO8R!ZkT@P z;9?3?Y9g@FJK7zv)U&fy13zOVf6gMyoH(AG#k>Cj{#5|wq}9-2CuF6aLj-GCCFlGt zX8L57nqNSWX}ldohq@?$s|-!EUU-(vXCBU_R+O2x71M>Wu{vIAbeJe!V$_AfZnvn^ z=$o1TyKJAK8chZEey7lt$4CXKp|um)`KN|li&RpnCOFG(q7p%L=7$co14Xl`s9X;L3n)Ay{$n+>=S z_w@o(PjmPu?|_iVp$UgK_xjXBi2hAM35%-f%*Ao%X>B62LYCEW8Plb~y_07NN!U50 zFIes%wrV>!=USDofO#y~eZ336SaZI_3|2`2G5Wkc*kody*t?x1S9 z#L5QmpgJMwn+cc!cU#zdZQ-YmvdH;#@&^~n>6x+aLAiDPY(#Dl`TANKimikoc?AJE zu#|l#+5h>}{*}X3>;NwQ-=7&F!vA|e(|;Px|IRs?Di-c@tjIit)6a4!aHvh+2ifw~ zIg0lqd$YjPLQ{6!fyr>K5!wDS0p*xgvm%x!mP*Z$;~<|tl(sAsCz}iG27qIUAU^o( zi$O;QM2hDshZD;X2FDsUC^LaMVUBS0z{_LH_BELekg+zfq|DU4VU{z#GCH6~PUh!e z^MB@MSt(I>CEIgJZ)jqz*lisJw^YoiL?WFHz_B2tV`iMmz!=(1;|=oaxLM6~ z{_InPXKvP2kfz}=Lxz)$uHQ&eif!zx1gCO4_>B>hA<+(yCUv#vT@#9rIDvWdt``Vq(w=_e6M&|sAfmb$T z)JjJ|*-J*+ZaDFNaEk5_VTQ8V)Dd$niA!SL8-`0D;Qkibe)t7kFcO#sd!_r+_4HbB z0nu0w_zG>Wkn9!n_vWG$ON;G%Ul@{2n6q-LT78I#oO3yb$dl86aUTahOHm5ya@qgjnQKqpwVNiKuB}&K`c-RHE=c6 z2hkX35GRm0>x4#uWX3dQV1iA7Q@Yj$gjz%`3TN@JGaTUY!|Rx^;8!f=ch4P-y|5U^ zj&g{kwyjJCN4!S)ui@kCrLlz58_U>GtYxTIiIdaYJd-9h9NS;s zP9A3tcq4`lgF^|S1|GYW<28|jkN~06v7!1vgWsT4H>Z*3DAWx1Fj+MEB~J6Y0}FpZ z!im6Ak>D<|zmd{&@(m_tXut5rZ`@(~a)n!JR^)-Sg|P$A8GMPw0FW9YTGgRBx0VK@ z(Ku~!7!>e++x%EpTGvP9Hs8UDX)eYY$xy2{Js<9_)5D^s{SRj=v3uW@x9N#5nJ${< z7ehL=t2K$j7upSGJC25QK$J9@o8U!+ob2hy?y$f*wFH32lZ>c%G6d}&`}6N+cL^1N zA^(jLL2N`i8q0t$FInfl?|IB(68UGj%^tyCM0p|kp&9|(iUz=IUE_|0*YKHWJLFL{ z%VT97i3t(nV+~JP^wTuusxjMO9+S(Z3IapB|K3#k)P}<=oJ_g0Me1Zh=*1e zo}Vd3XKS1d#5&00w_uFmTlX%U3JU0ZQHhO+qP}nwr<(hR(~@)v)#MBlRqHy zAr&W1U;yF{Ggy)y3S%o9wN@={@XO2K2jChF@k4kkSNw8zfXHi(wx8pzjt6eiq5BUN zc|GNop(nlr0)o8*#L7_zY^ow69s!|DO`meRPNcO?EDIZa?$RrJN*4gzu?LjRq;ja0 z#C_u0NcP%^_NOd=)eC-V+@};_ZfP91SG>UWU|`Z0-9DB1jpZvT$p<{^@p$X4Sk3P6 z#mlYWgb09oWFif{0&9ev1i|Jld+=vj9WzQ1G+%KXB)2#|SJ>r%j>L&+SxH<5p<<{A zr1^j%$Qw!UXT{j1pd`PKB*AP_n@?yU@_i_wU|zNWHHnL6cqF9@rvz(<1PyF*8#ai0 zjnfX4ouU|A7xDoW^haX)DAt?8jwEQQUACwd=#R|6)_+k9#Y%*R)qwu_V*~r=55@lp zGyMW3N2mXZ9-~v=TsKD$Momd1ip)D&yoN=oxx$eoU8LWwve%p^fExA$h=Bx}mP>^B z?P&V*|A786=HhW+c8z_Mx}iEt|6U-z8FnA{d;@wHW%;80qd=A6JoN&8%f!U>AIG1c zhuv7-e0xrrpNR!t4;JZKWAiATT_Ml25A_XxzOeBO){h|jdyOPxe6)ha3~<0F>H3(SQ?i2830Jkz75h-XN$NPCW%@2Ht5 zb09|@0>5Dc`A%jqDj*aOofZW+hrtfUET>hk_A3@DFMg1tOej{*G3aXB?%p@P^Ot{k z@4Z*OhBC7we>J1QdD~hq!p4Dee!9qYLLC;AK^VLYejALygM%R3Y<7SR)+Rgt{ry>~ zm@6NOiEuggDA;JbdO0if2piU#G7)!PL0=;$ry%7*15_A6Hs|3vl!ojGHDqnSAO20->u-FjkSiU*Dp}@Y*{wf=pkZ9C>cNjBYCVd@vHe@>j}9~l z&jlkdZ(6olm2*dDFBEBf@{qxbykM9J()k3}b8E6)rO6h z%8fIK8qKc7@eb?FCK@uw=LDBNNTIH4U+tW|SvK7GLVtT37J8q9^qMvFlJ)9;vED8! zSvotFT*p&g=Qz>Q5k;z@KR4{%fI{nu&9{)h{Zx>>$&yB6>zw_mp``*YU&a=3t;wd{ z91!>Mwikl5L1m_Rk&&0(D);Q3Ye@B$F$Pz~FyHTt)dYwZd2;2&r6C8eDOIZ}WIq@> zZJ#yQVHmiLRRS^mz^a0cdAw<#d(H7(?WLy){@q8ONXsc#ul@S z1J~(hBZ9TF@!%?9a)Vrq+XuDA>*No3z32o__7-PmL3{)!@d^K0Hv|`m7ykN{Xa7dSWZRsPlxF&9iX?%)mawO}YV zu$S5%K`WsRx<;(Z@07R)I44yNL^tJ?N>BO##7_ADvyJu+DG9+FeS(>GfjIR?I4(m!clTM%*fJ6VdUuIsZ!|#SP>V`m9#+6Sdoh?{5!!hq-< z)thUfppX>yJYKLM8*g!Kp(oX5vF#bRI0om#kF=)h;{!X~v@AHD=Ci$?D7W*_{*ihB ziMR0)n^oykU%*qg3k`JNTP*Phw=FX&$kqn@%JZ?nEj2F{)Y20yKYZ31VM9iOsO806 z5qcfmfx+sxegJxtaP6DnO07ehYqxZ1N$Fg0gN20!L7S}5lC$G_lm)km3$y8T`yUU# zP+IA9TTUJgd-aE%KlfVro?iZgK0z@G2^#sOPRf7T$N!^D_J6Yja{3PX*8lVOmz*$Z^UD#0{FG<6iED3w z3beCWx3#21uvN7oZ^TKI3j_pZ3bQT`VZ@hbVH`!pyMg9}1P2cR)|*T};Lk)2B!IL$ z=5D@z=34!HeqC{KV;{)lurzVk>GD~q4c8>|P+3#CR&PPs@$~_PT&->|9zOUu%wxcU zZp%2tKkhh%oHjO&OJ`Kdl_Z%)XnvmcIK1l*>%aL&!P7OLDghnwCUgXmYqVtk z=seMgFk4)mD!n^JY#sGco-?X|5kHJ%z^sv}?sd;buGbYG+JX-IGnu8oNE^*mvokt4PBM+&^%aQl z{4a6o4{%#J=gME(qzaS{eQ$lb2AB9PZ7b?SWwi8Qr+9=1=LPEu-o+oe;+6UU?f;`jXp2NFt?!VUBTm#-HK5Hjow5)FJ}NN*=il`%P( z!Xa)>es2-BzG%!-*nO?yhbU7jn=`Pi=G$0q?s%`Ybbc$;zOvA6Y5DynWjmUZA~6Qd ziLOkzZ+E}EJ-a^doKAh@_Id-`Fdqo=5x#0*WNI2UDzfUPTDDHiTl>7)b;fWV9m)I# zY#iF~P1tv4Z51A3`D7hR^^_Z?!o9pRfV`Zw?Z%q7ZO7W~ZyvwG;?CXW;W6FC;lUju zusvUEQ1}SKWhuGqjPl~? z#9h!y;M1MCsgF_tE@Ks({nlrYc1)RZuB;lDv}!UiHP+KviyQ)qXfm3YtP&TbN2Md& z3VBW!(ZE~nqHg1EBb(zl(WgK86W)>>XEI@t17=uBqDIg3WD^m`$sGGDI*Mh%)7 z^4T_l;6sTdWffgaQJP(!yX1`=MYoA9ekW2{U_~m#C;Mjt``Tf~m_uJYiIRTc>>pCU zX}hts;-J5|(os-&)v&12ka}Jd<+OUxn;wfLS`fWiy0{MDp2uZy;%8l)khI#M9vLM= z*B$OhXE@SeK8Z_A^fezvv%ciE=VW=kY?#D3{hegZc`9MtU)OFmFtZwyiq&*Nw|8=) zXj_+Xmo@fY)L7V8vKYt0JJ-P!vZxj=`A|s9Wsx}?<#EVC&th6YmdZXH-)&I^RG2gp zQlO!VA~>91J35oNA5&~*Khs9ZJtdd95Q#KA(hqR%E?{jT-nuw%R8k#`w`gM0C!RE+ z1!@{0zZ$YJGBRKWTg?9>#>&JxTg3lnCWV@`F&v2omE;UVdd0igVnBp9lZYp_9<*3l zqZDs{rN(XG5YFsAte%+_h9y~iHqyw@?JVS;uC(KhI`NY$WOv0b%PI+8MU^Z)I@O#) z?c}cjpHajBqhJGr zH`FIz{wBEIMU`pDZnG!)T0gONfD>45BsU5HbhA$eno%FnYE>@Ba0}=|S!WgyEW4LA z|AFp?$H#OF;6n?aK`sgSAmh2(qS@u0pb)~wRw=G*cKJoNYB|zd?Y>$nEs?qDC_g)C z#A~^SLD$G}cmf(&zuL4~^y(8S&dciD@}L5feUhT{pi9>9*hFr94<{x&5>s+knE%dt znm(!s-JJc6kVvMojCEB~Cj1ql#{64l2Lc2&>JA*ezy^9>+qWDZ#7Rk;LZaB>Jea33 z-@<^^ZghO8p2wXcu^~^D-adfMeXQjut71OH6IXm0fv77vmg@1Ol3LI;d^!HyQtBbD ztp!V>YA9PZ1bg(8F}F-|-3_s{9&R_@S{@2qjDE9!hj4eP$W{*4(qUA1=Vm!@shY2o zFgcwznoG$GPA!6=)nEj8sqUaWt5N-)-0tpZGm}v1p<=h(nAP|)$vM*lsIR_a-kjX{ z_K86D^I1E%S*`s8+Er^uT9;Ct%2PJjO0aT#WLwx3`E`Fw@Na+c*0~W+WPNOIR-Yqu zgr1U}J9JQdaBkpfFs(~>Kfc8>uhBX<BWluRpz3VGx> z0-#4_K8ETo+D!{@E+E&BZKXFfVlZt%TiqR8F;=Bl=*@!NcR>RGrx)%xlp#8=A|?b* zufYX=F_Y!RLG~|~e+Z?EXpV?=8*iSndkS`d*)wPtnH<8c%B(vS(-wNiAklO7XR?y> zkLj;Tvyn^77u?@Ow$Bm1(X67XbKO%aqbduBH|(6}Hr(&!6<$@#lU^DUdnn7BjL&A} z;UbZO%@vBwsdRmmcQ5g}ZFi8-oVg7QCd-1O)5$?crbTKZ1t(eH;f3G!If8&g2R~U> zFX8guZW!M1hV7Nc=a&>h>+Lf=x=DTQKL7EPRsO+{na~0Lg)4Di0`j%*r1eVFr8$lp zvxPBNusO^4zDB!I@Gb?ot@qqFdPzIui(OFLZCI-ZxR3TZL$ngRlk47Y;4g-3z7>3f zZ;@_)z;5w(4rV`G@4$J73Wb_7$?=G0x`p1^c?Xb$UWj@76$gS%hmg6c0NrGO@4Cze zpbRK8-fE?FKzf0l?WGt=iC5c@O=- zv_W!Kw=a!R88YD2V>=f}njnZ`mG3JQN>3@W(V{ZdVQ7wx0~CA_zC7wtB{NT~DkjV_ zke!AtP+bk2oGCG53tic`4aH^Hxm>4A1jE=GAe??*#~A9r&LapvQ4h8*K2(*ys}|RRL>ZWQn4WJ=vbXo* zDQMq#qCdrbMiAHTK9Jw6T__SXhDgnDSU;G{iwC{>=Tjj~aw)8&Erf|0O=~a^>5xAN zZ=6Q?nMO0gpo?yXhyv*%hq5LHU=UQKU5YOvrlrN-6l*xI~RM_0HLDv$s;H5QuThJT`Sl+ z^c=@F1Kkdu<$i9Z4d>{fy)3+*(M&`$7K?+sP5p`Ou%(sHJ?sxvl_UJ$687QV4uo!oe(b z%K>jz(uOsifuM`zMtXasiw?trWM=V#M>}sI+sOrXY}%(R1P;t8lC~KE8l)|TO9T0o zE7f}7`*I@mcm!S=tsl_;Je0&|gJ4hp4kY=%YZZ?F6BDN(B4}%E{r|nb%vRF;l|~?c zhv>A>P$}1$ffSEbqfH7>fYT(H`6n%i6^#YjZeEG0ZsIg-7ks1q{Fx=joCouM5yhCL zZq~zJNGoA7ojK;(edAor?d|an1v9S-&NE;Xn^Xc{Op90P!h;}2DFSpuF33{Hm^U(# z>F)}N3IGB9sW4BU!4xFaVHHwjq6uYdvM8L!A;{`@zKm72cRIB0X-Zx*y+sv@W(t}t z8P09ZRJOS}TLyIpogA3M`slEpa2y@~hegplAL}%Yys$I(X3Q zd1Her)TqAyjL-@-(9kwdfmik|9IM}uN?>;0VY94dLlW|h%C^yR=C#J*G}b7rUp_v= zilf62)ZrCwHe?ot%6BSvx#xCBLLpT~xY5$jCViIK74lP+BsBb|fl`FNLQj4e5w|kz zASb{Wg$msiy+eTg;PO7qeiOANAS;4fMVUK(+0`ypf1mHsNbE&!+4I}@)6LdZiju=y z`GD3IGPL%AXmL+?hy93EaE{%w&k{P_@^-eJn+1Bu;@G$}bXCy+ovov|vldF>V{$QC z2c&7H@+z=_UGKJ?4^@!S=NT2V!#PhGd$S4l9*x`6S+gq(bF)I6K? z2ill4Ob1a=OkO$zo_SylegfP5^ei!df|`y@(E-@tb+9{-+eH)nadH=rjEpa?zcj z;q@okwm<0BEn{*`T(+Y)Oef8NHlThhP3K$yZE__29oBz-M=&Dka1_A*{DFr5@7Ios zLUQ6ZcFs;EyE6{}cUDUG6hpX_vcu3muDTCeP_#jwHab-UOh2K1jGSXqVj zcO8JCn+zJU8Vep=xZp>_WxT5kCjy+wH{)Kh zhIrL@4#5Ri4lP`sj_+^VwivCN>vI6`rspKa&oJ*G#D>_c1U><7*idl-N4G5CflgUP zj8V%x0Mb^eqFGv&mFAah;#%58hzLGrFK52&p%2{MSir$4gB7)^?Cq%Jvss@n+g9D) zXgl^G)nFGugY_7rl;anmT1j+DJCJ*&kI!PTB;T=B z6!orYvLe;0MUg~jQjy7Zj+4_r(?woemy1_3^d(==%$`dO_(vF>4Ks8TaidRIvd%p8 za#?TCG!>5y6KWMXg)I~(1KC=>i&;l#q<|~-7dxxzWF!tp0+T)jAvUyqrNG?e>S{VV z%k^0^UZ*ow60gA!hd^eM+cdvg6Jdm*8rf+b#&4Q{3%QZzo&7^h-FTdrdF+>Ey7rV^O_%NMdHlzD1o;ibFoxNPo+gkB9@H14Xd*Fu?UQ+equ-w zmpgiS>K}2JaJBUdtF4CV!3C~WAL96JTDU3qE2v2E4I7VIs3$kOe>+yk%_=PDF>l2N&x>Zi%8q)^R2jM&rLhn?MuHJPtl=1xpnWZ{I)$FI# z<*hrRdFgmNy=pWed|0Gz@Hop%O|OFV8lSHaIO;1|$zv97_XrAFMLT#c?b79QU|| zOrpy+N|Iz0oKG%_uealhP=DttLUR0PfzW(M;i%Ytns|C3Kg4K1jifUIY$%MIR zEHa2iW1laEv;jy&8P`%`JLsoB9kqzLZi2Ps0>rcNCY;B#6kU6dv$P}Arxy|`;N0u1 zg%ToEf-cgQa*qyRB>P4cwO`jBuuz=?w1ymB;5X2*+;q<$&<~JHG{Vq)6UMcxC1jE< zJFsiuq^2~cE@tC#M;Xvw#b^N4TNblJ`k9hK&g32m;d^4Mgm{ZJXp4LEaS2%w%#xXY zTl`X;S_UtXar3ErPwmivL%S&KYCP5M0!%rZK(p-lnIHfDvF5DZLYSmMI8MQn+n?$9sCVf6mhQwtzcBYeh@@2P7UMA9`XwD)5fGv&T z#Gww#H4xfgB*-qLsT`FvZXl7#15@NDl){uPv2WA~=Ud1j138LTVp`Rt!K#xda;^k& z1v7whG^!k(Av4E_^5VP@#YIkid9fz$Xbhz@@^V_2w;01Q_FGGi2qb9o6?31%F-j}S z2M#hle-a6x6R0Guo)^SlhpisgY(5-bArD+|GdaO*mAgkMJag+iN0b8GG2Mq@ahEek z=lA755$>bTay-wmA%tG$>jTnzLh7!EPe2 zrsiOG*gNOKKW^b&4#l1JHUITjt_9-d!`&Fr?F{~@A)w4!qdUZ?^7`GM? zDvX7Tz#0=_$WAIkPc5S-#2q<0jDd}IdK-j3xOjjQ6_L9aofi`UV8gnuvslnS*Iz4D!jY(%|X)m%F-Kaq~WA1t9ZOu1h$?8+a69%<`5M>^_ zU%(o%+I)H&@=Uq2G-9Xj31(}Fw>P>G`kHRD7m*X0d%<)kxgDx|=6Gw_jeT?Gc&Et| zwtFUd>*>w$U1r;#`>6fexD(p@Pj=t?3*%FnFB0wv>a~+M#`oOzpyHdAcfmIz_KE6M z=m)0e3~z6@VncRt@(C^v<3isq_`|LAf&YZl<|MiY0rrZdCpfc=sXeA}d|iG=Av4_- ztljq5mn6#r3GYGLt47)ZS7t4KKPCvry@lk8_7-O?&g~I~SQjMpo8nrzHbAs@L_5XS zvgez@`{;t<&D%`1H2<*oKjRWbo4P6_h(CYe5&ruv`Y$e#b$0rH0TU>@r2im|yMK5a z@=D^zh~NtH4te2kL0DU)xU$WM`y-l~%NwMk zn`0o!QR`@Anw8Tzo13d)r_?T&RLWBFajX{|f4qZ=0GhV9KW^Gjvp%vNXL(Myev*Cp ze1Q>B+E$~}&7Ac?Q>e~K*%Uv=h9RHK9P_rLlmFGhl=8BwWB3u&O4zfLES_TLo{h}3jL@6%umCpI)@yYR%6HB zR9jwY^NIpv#5M)9ZWRS&Xl`p#S9b~$H2G2)&NB({98a-n^f|*<6f|41z94H!bSQg0dm8S5r8`-P!8tE zFdN7l#0_4U`!t%N+uqPV@4v|%<_E+s4bd@}IXz(}>ub!63K8VNmX?2Q7fbj#fBm=5 zKMl;@iu9jKUck4Ut#W4ZS^w4ALBEO>!RttL0obNpD3~jyDkLoe1RQE%%r-{-95!@D z_qU#Q5nBy1WBNhAcH3s4h1X8tMO|N@XWe!n&cp=F9#MAE%=5|06z0IAYlksKzat)29 zWLn>Zvo*~0bU7!cY`xTSVknAg3)^zhV*}fJAzKL1*=LM~y|N-@3m2opRA z7``a}c1oXLB8upq76v<7&A>9W3(O+skE|(&sRg7Pm6aUZh?08sTT=o55!SGNM3h3U_Pn~!F?^@Ou3JhMQLuI$19VX|0X6rM8;_0s@{*C z%8wPkGEJ0fgZADjuJtB;hW{w?=E1CoTnf$*Y_k-dLfa=@j_$DopB@~H+ws(axtuVj zKlQchD|+le+{2Ud24xjlJQMtzL`+LdKc=o^PY^^8YCH(5{>?ZHTeX~b5$56wrB!n= z7q-?{a9;4Dk@bX4gn%Px6^rK`U^v1ZK*@&U2#j=~=LTQ(D+2Bk-l3w=AlAc+)0m&r zKdR;k`z%Zc-kdguT)NMv*%Pch6|^j%P?I206IrYeFfkyR76#LfRCdBqc>t)+C#@>P zs`IxIAhZ69W-S0GthaF07JMy2=M4d{5zf02OwTj*GE3AJogF?0Z}5oRGQZfCs57Ab zhMc_s)w$Ke$`b7-lOu=@vWdn&vJQKKQ5g2F;I#KS+b4i{z)y)nL5 z%kJ{ZQZ0d60P}>^xjT8wOOQlzwkJ`t4`NJqf{6rwHi{O2rFX4vp(7!5LA#%bUZf{` z^otw!*xqk+((s6kE}HH{OXRzIatuyagVt16q-Qg3D-7`fN6?i~-!2WZDUe($Oc%3* zYPw!M>l9`?``7<7<0CjLVb87}`RWR6LO7XT{u5S zR?N|{XfVz4IDWWynraH!Rzs}b_ZFhVUND|uP%LgLnIL?{^2kj>TOYNk8IofwO*8o@ z(XrKioZgXLOA?ozeo}TXh1xJXXIj?G-8;L1ZNgMOkwL<=h&UO;$VD|RUy@e0rD6E5 zn8H>PH()T^@1&v5OrAs4t9jaVk^nPkRK41K`573}i}hxSUuy1ZIYXLZtD{iEQEAhg zb=vgivb+W39Xq#0+yC9_@PfX?@#AA_ehNggQ=jn*=Gyl~5y8cN zcXOKOhQDH<)eQGp4hFY`^YXao1xF*|Mga>q9~Rm{_np_ZNVFX8gFFKGs?P_r@9 z+TPbAz&^LA`xSvFq|}Trrv&c+gEP$Z%pJSPkX@*DkHZ5c^bDr!Z|SX}2ioXAXq}^- z7o>MIA4<{#Q$n;+VFDdQrdvn(nABmdPXVpy)nULac$(K_wP;-^z8&Q5*XXc=)&tls z5|=&KgNxU|wcyraoh;-)b`sn{yx~K38l67R1M(fT(L2>UN?v#}JCUyN#slk5>8yd! z1D;Rqu2{zdpe(f0J2)S{w^FBlL-jCOBao0|?1Y98D+h*kV;~MACXQnVhjAB&$>yW@ z3-f?S#g;9hj;I7xpLEi3FbdV{eD3yG$fHCh^4wy=H$v%nI>magY>A^A^9*j`#p7J_ z5^l-HBT*$4zdTkd>>w zJ#89s@z_I^CVJyT?Um9;%mqthMH6e!kXFjUPNrzG)rU$g1&zQO;+)5aN?iq8-3>)f zBJLG!;wA4yA7Mj@Z3(oV0)$#QjP^^u|BS5cRBa>Wf2A4OBr0 z3gqj}5ww+;KJ;QunEx9E7^BoRXIiDl zezVFyDy1ydcK>O2LTPQZ7lUp)FekO$gB;IyHEEXbg#l;8tf+y`(c}Ge9JznO8Duf& zi3+t3Dj>Vn6P}dgWQB#i8Q~iP{^r9T>*Zc*_4Yo3c#10j7k6{z5|Q?2nIgZN<3=7L!8*j+p9t+T+`FV1xSJ$_aFg3}FA2f<^0uN5F+a!w@Hnyx zKwCw_x@B31@F{cdC`(0vU9EftxU)i!j-n^`Na?>?`WWy^@W_AflFx78CF6g?UkjN# z8vZ7nI=D-jJ31NL7(4JA>DxK|-wKN4gl!u{e&o>~AY^!XDvc&oN@b-o>-GgKsY-uz zbJmQc5Uko~L%>DqPIfMM_dj@JRMBX>esIRzOr6RK?+A1*&r|6SKiRSAy1l-iLYSRv z6!?*&?o}vqqlw%rj&2!)jo6sb>#BtC7P$o5X0Ygt*>i``t<(s&FN^hq$MsjQM-=M$ zmLEWxklnIb7%YeggE_|`hbiF5FPbrY$CS{^Wy>h>STk)|nuH46d-u_%vdF2{A8 zdy7hA?qt}qUNuh1=_0d7_ht8oZ$S?AxPlx93Q!+gDc5EMUd8iFcN`>F_~*{z6z=_XJbST`6JsubiscrwMm4X@so%aJxFvW5|3hZ?Zc zge`Yj`lr4%DJCTdG`p}N)o?Qqt|)^m3rVvT7?h_b`!h~v!GalurP7#ApJE0+y5b1X zo1xPH7HauuGLE2Q0oQ&mAPpLirW>7KFqc#q6k4S$mRZio<}@P!ZT^{$rLD2cLSBD$ zH9lq_U8Czz@kj-%w?)RYn6~=073iz-v-)%tog`LOB&@yOVjlTS`d@YBp6Fm&u}8m- zPwe4dr137?;^tt(Q&^j%j=48@=V4JRw2G|JGg>H(&L}I_x+;!c(VDy<4c){_FcJXfw3N6}I?DuaWE1$|1sj&PYzCk{YVt=`o0hk$N;0Ne;XZf zQXk^wRX%bbGipz#zEc)EOxY0GkQe*zko+1A{}Ay2krchC$=oc)oPl}BBuSm5f@;L+ zQOqEuQig7jlq=ae;l!NinmlE&PXxUpE6JqQm8of1i3w*JI`m>bDCaoFoU{DjpDWO5 zb>4)Te?f9MvlucFTp1Ew#D!^F6$n#;W?p zFdAG!bx{J~$;kFWax_$#_HGXUq9&MPOfa2-<2Px5gmslvpO)&%$vB$zc1Px`oa6uU zWDS^2aLsaN;NmbgnA=c*MVkCyqH+{Mq6Jsad;g=9&r{2Nirq~08*KcAIIktQut4@Qw(H?NQ8uh1z}*6<}o#)5(u=kp-?*T3SBdDmXebc8KV;#Di$q# z@QEp^)D}?8$q!_<8Jdqc<@}VQM3>Mu#q(KI6jW@L)L)kLTb=)-&L5~VD8*(V5DFS$ znR-N=yUceQ8E=>3o!L9&lyw{=C;^?!n@~qldjN>Gl&BY#j)c<|DQ9^7y*T1WWZLmf zh5=-!5F{C^k6;xKRQAPAr$bU!v$a>mdBRbPVS4+*nhO)ReRsXKq}eLEZ*hg=FeQ;9 zx9CH532ufur31dM!E_WZ2`7gTWla$sQ{I+Tx=B!p;zI?@;=IhsyE6{K`#1#Pu2%+iBenc1(5cu&S9sHdOWPdO}=J9Y0rnjBk>qDgCYOvHCH0D+4!JPqW7KednbZ z7n;Ir>7XF?SdS3emZ%WJhqbN4Y1_b^7{?l?&x18JaDZ(A6XB5kl70=j$1v@A=J#A$h#{cMVc>%agC$NA2?$mhZs+GpO{I z$^8Rlc2Bh{EYfCq@bLv-jOVi8hX_}|jBLqf<0&7kvu^Whd|g1+Z!?mIz$dCAp0-|^Roh$nlDEc+A?O7E9Ndr=cXYH`YbAI1pUXa|o zE!v1?oc#0W|M5lq4|Co#L6Aod{+~ZMivPX2{(t#k|8olL|5%p|b3?c(Eia$$sP7ov z`_U8o!-E4gNRdLJvqFTC5{May(TD5(9U7mKL{Fa@QU{c$y2dhVb_SxjR-jUn6AO^H zr)suX?r3gl&fI=ksd2gEJMCe!-J$k}*!}V4+fDVn>73*^&H38ldf)KPb;p&G>*uQ* zY`lb_>=7T%&$^aB<>1)p-zZ)HQTA9H?$+1CUEMN0YiB(0oPYKV z@g}UnUDEq^+Zyr}y^FFw8&>!lfPsCanS3vS_BJ-=*5@vc(wVK(kvvmjeXuxxkHE6k z?Mhs_vOarqWtG&t0-^Xe)$_@JnNsrRAN=A6)n_(~uj~llwKYD7p;Fdoy7zB3l%M>A zUc?V*OIR1RvGi<5n+AKPnPb%RmW?)}fNrjn&9-U4gWX!X6t@^03%8o=NiXPWOv}SV zGt@P=oaoqA`_OFJy*E}Jy~AKu-uV%-b+`Cv*_Jy4tXzRWMeDAik<#_H#gWp@S7<=T zjOf`SkCg1$6G!6fhCz|%o*~Jry6{f(BIwrPNfI4?ykwW#`}U;_(cv>CC3*iL+PGH% zE-L~|w7cOY_mH8~H3A`?WiJYp$uf4ugUKs+zaR%_3ia{_XyRUpLv$^J+eM08ZJ`k|;htA@nT^=jL~Xn~BE*zR zPU~)LPgW%Zvcn`o6R4Dc9BPkqRruZ^R$ZwggA zbasnPRcnpyh610(j1=dm>P!ul8lyhUCFl4uGIZ?=h#_PoN({re+SwXQbDNr4%i415 zic*G|yuWyw^K&Yz4J|z^yk-XUtOsx|U`e0=3zhU`X7?c;C+~ssB=oIF2ttDS|4!PQ z?^HCG4!0XNZeT(Q^K1SofF63FkZi#}ihkwz{V;;C4XiMYt)Iia3uqEKKZWtZ-+KUZ z24UvXRSDUJR>kv&v!TLL_5Xt`p1o04c_rGB%SF7ly%#NjbO`J>mriwi=iY=aDv}l; zBnA28`7S$%jCJP(lIZLW{lgCI*A5_C=UFphk(H~vxU^Rp&){urd3QX=%_sw z+J(D%1V?!u-~u?(*D)1arA2#EO>z+KY{{eFyB5zmioJa)>TtO&p(IwQ4`Se$jQPBd z3R9>Q&m79Pa2fvofjqE^eE%xO3yw*mgswsx{WciExpQ;_O@s=9@`))x#ruI3pq+0A zCj$6MEp%u6CTP%aVIQkBpqa2B za+ViAS5{D{RzVfc$K0AfyhityB*u(=PF5vih!MD@R*qj&w@@N9k9()N%wEry^h=#F zn`i-lz-&kZ8SH|z{Us}1K70sOf!a=}=ab6imyH#$vYaX-aOdRJMhEd&wUDJ>Ile=* zFPkSJW?v9>rr*x1j*oMNvKF`>>cqxqX2g(d#IHl=(oD{gQoEno%p_V;mi61Yc< zW?R%cD`1fNtE5OMezB2M$6En@!U_*J>Q-J@ESW8&6Yiy-XD(FA$bn&1p@%uvH^n0W z`}Q5Cf08k$Lb4Sgm9ymy2p&8hXgQFtLxL^5oqi>8YARB{;qk=6^cl~&JYHc_1~AQr z9rJWBbI$Gmx3sPaLVpRhccGMlZ((i`OV6&OlAv(7l~gt+P+ejZHx&>9;;)aDSYo35 zidY@XQe_9mIGXM${p)7)KOBLhGqMn-LtF~GXd%i#Lf;`VK~MIO{h?ButSHzQg*bc2 z39|Jx3&DK90|Khtl&(Bd)a@v*7f&9}qXVR=zs^tSJ<$(K!(nWJpYe0zMAd>m&jl8? z@^T1T`q=-N3WP#_tAba>1cg3CJJZsqA(igzsLQHh6{OBo{k8Td$m5IBtLyXZ?j&V- zm7#WEVAPF(j~I-d_V>$L()zJgRiNV2U1HH#ND4yCH2=y9kGv(Co5-<7z$Bz1=m?jJ zF`XnLDfxX`D{|}Km`wYcpKuH(+o+u8?$#NY8=iqmb<_%v%f;l?l!q5|IE@q-sk5$z zgorRtXiWSh{9#%PGbHlksfRJ8KphVZ3X>aUn=_?8c?q8lC(;w%-HZGO2Uj?s0W8b0m^p`e8UZv*;p7~~g8Xo@52MC? z)5%%aXi`2WMEqEQA?%>%yAM|T)x9&jO}y(t3o3EnOgsU91VddCy%16W6ob*E_b)k_ zyBFkmIJ3u(3^kt2t+c_4Mm^>!8;duQzJ#D4J8=Q!%OLVqQ@{xx3`VrpmdqZ) znfYh*jALT5EgdLKOcFuTG`C@b6upA8((L>t7vLaL_)CV%Qi)mVeP+bP;t}^ztxeM{ zQAg`%F7=6x52&SV!hdn5WN?isyS9j=F5y-8-WfO+X4H@VAX%Ef3%?(&Sk(=P8`xe* z{KqvGA!%tOZKl~tC!jG%SCV(kML{1eg1z|o6p@(C?<~@&X zOLkDjN#$ZZ+HpfzKaaApQjK0ibsj&+LbSIeZ&Y{NhnJHYq3af(sD~7^LWG`xL(aGf z`=(q&M(~74&}5S$hG@F%Z{tCsctlza$ena?Y*e`5+$AZUTrwpEg`BX#s26ppMu5G* zUn~o8KUCj3))nD-V1jtA1R*JSdr|H^rmQ7tM_Vk^ODFW_6SOWd3#E7g_=bP z(Ke$# ze*jlJE|6|^2t!ffA%P8(!GB@w{o|AXZU_J|zSJeLiSC!k)OShCEmK%?v_4nX`D$yG zRga3m8H@u15`;1)SnI-!USPaQ>jo|%(6;@XjFo!Hj9qYeW4APJq9MNhy~eMsUF3r= z`$QNzfvd)^q+Q`YR+W5W<;;X=OD-a8lb@VE-Ozjic$2r3UO-I#)Hgf~LB%?fd5f0? zf{y%>^m8}RASk7}o(6Uy9a)UO-BV#P3mEy<97OdyJ96lSMbN#(N4uwN;kAYOi14ML1`R0+SE*{MU#APm;(nfHYrw3|BSMJJu|sj!Y2?GU zOETySeg;frbeb*`kiFv>^DjGPVRLIC=P@9d$w`2+xk>6y+2SQMnJ32@ahK-d;}uux z1C>Y?v5}}pA|7>~n48NOuu%J1Nu(>&t4 zt3nro(sOz0&u<5@qBT~?JnkTu-xRtR<=uzz_aCn)(qHQbmxORRA&tA73DP=oI^Pi9 z2sGD~fwGAVYc}>;uQ4lZ2GO22f(yp-&3ebX++NFD7?mWc3z zS2!PGWBaFkI!zHxjKv*bI3MYQ_va*|Z4y3$>GDQusN zh(Sia0Wc%pvCz3GCLN6NPjU~9Z|G^U7mjc$!gM&I;7|2$tt}!lT@>+8_jJ5Ly+K|4 z((F_Z>ps143SGoG6`iCv$xq|--T;{l-{@QH(t`{1f3KBg=%308zj>g$;l%Ma|7hj~ zr3~T;HpVU`2Ash@QD)nSM8<{~hVTz<$1V*bAkY$$kIh#>WUc@K3J)x?0ebtX8GlIg z-4c6A9$Md8jlN-RqO_-L;@>)vW$uTpkwcVC(MIr@B^@qXCoVMruk*oPnFk&lQL>+v z^|4yGdCRPvNwsz1hhB_YlJRv0Rwkz+`9s{(Wlge|6x7gA%(RTtiNi|=THKUmBbMCR z50*l+mXZ9~tS&k@ALd)8Slg(1uE(V2}s(zu>Z9V|cZE4eGd_*m98 zGVa-Nb7S6)lcq*vXVhF3!AZ>S%55)#F;XH!@uO(uW&QlQ27{v5hMU5C^6D^=uo3o5 zOntH>w{~h30K1duW$1fMFG`J}HVB4Ox`>SqM94<*S`|PaMBG! z+NbupRlBu1_uiM)+Im>?WsW)e9DV)$`(*H5c~S)~f8p;oqH7wS4%7%#IpbNuhouha zcTx3+Cv?G1kKWx(#{bd_J;R zaO%h%A;4W?Z6D<0MOX>Zl)jLt?YZ%WNlTgg(b`n-e$6D`l2b~^*{})|;Q=c74Hog$ zM6O?iRlo(K+Q1^^Nb%9mJBaTc6CLnF?Z-roPDeDX!=zgi1VZpRWM_CTN0O`V$H1L9 zF!*L+@*b9p+Ki`d!^++WipJn5eLnO|pxGAVSksek)p4(CGYPMv|0qH{jhmb_RVb^VxBHROCt zYR&Nros ze1ME~=?^gpX&xZbs}h3`UJ6S}uB8L}WY}J3Aazy%Ci6qW0cEJD8mvR1N37K1OGl0| z5Q32Q%lE;mZ}c0K}VX3!1EqxHi)Yh2Xa(; z)Gun3YD_}EfOaGHY5&S@sI6D#p<$2xp6>2b%f<52By5jeUz8!3ehb{_v_Sgv)OY%W zDdXU z0Vvq^z}QQ&i)gq|sY5NCadiUfloyPB=6;3lo!4O{ID0s{CU0+!-r386D`|nkXQ<^SmMvuqE3P&rra{51LZxN zyw(U>HkFg}c8L`35E9wu-9S;3P{A{BoD}?yIAr-KMjQyi_t*AB*??}C9RZhn5h;EH z9y}6^=|dd#C}h6EOks)!daEwOK$_Acw^4>LnV6cQ9TZ~w2x&7N4a>x9xa4CGhys!! z`Ea;hiR$40E_1Pc!wGr?R~on@3h;tluf}L$R{*CXj8PU)+qX`)E6So3XL(c`JQFlX zbl~%+F-03V7mY%&p%x=Mi805fo)ykLV#JUmTY)u;k9%S(;%2~|Y% z)h7r)6=ooV*4lSwsrENtV5Y$@jg2k{9kK+Nvacs5D0(}FSD@S$3Gsm^+j#@Ac;&P( zT4hhNh@>FA;EKpWXt6_^QvY$rpkfs1B z^FFx3h{d#@xCgW;Nubi#~OlUScQEzF=dn70Y2 zUl8>JW@>1s1}MuL`0dQ}VIF%{$ZLkrEsvl%S1meU>`Dl?15)M$ZNn&FoXdsw+Snst z9BkZlA2D?78rp$%GAAIhQe6}dvy`T31HQ?yysOfOpDPujRz3i;Lrha}% z!t8xe$SD+Tg4AHp40$=@l*r-*Hqry#AmdMI(E&JXg|OLD)d=cR#fmU#iHPV ze9(;43P|b{lmTmodG0`wl4H8;C`fX(VxKmJM|$J%?C-oH2XxU5CwR_un9Idm*Lwl6 zh`i3B8Q$p`Tb1>vTNoYjbpbIi?~9MX=*HWpw!moUg(vpOA5t>%9fBJ9uTzB4jAl^ z!*bUEeNYiA#;`+hlTj(91_OO?aQ&jvXtbI7K#O^-CCKc*`{J5n}m16yI!Ud>L$WaW+7*Io`A?u)80FA<*)5Zr+IFx z+{tqi8Xc3HTLKMQq>75?&n`-goiUAufe~1W)Ts-Js`*E?qD;R1NbZ+n`Zyk{0$4#I z<|$OM=S4HZ(fSG3cCf<*4{*Yr3+ElEt787(MI?yT3ewQYC8Y?(_>9}%iL?GsO~@_! zpg*LYi)e0fMHLaarXi$j`)&7zsQ4ulFZ+`2HIPfAX;-@?3M7uCW6u)ot1>0NygF zvbUkx($Vt9v_r@X#<^w`t1yD5VSADmlZnOwto;D1%9_wLV*Zh<6CiG^GH~zcas{Yr zw}?|#CBSU2qNBeK!7LVO0@8ZDhwm-C1JW|_e*id0MK`FJYMmN-@_CBz$>CAa-_o<8 zWyCKR9hi@8z>XnAW-o4j&dbOlI|IMnDPT0=fdYE5uDRui9UeCT%Yk-!Io&x@smYuU zRqX=cd=-Sa7pY023n_oaw1?IMYQD2{6s} zMt8jBXANc{l(LzDgkG_lcH&2$1zZ|h3m(JKKQ6elm)>!!X|&b}mt&}fR;=g_tdu)l{jD1!xD@PuCyuu| zLMwT?ns`xAbG+ApCx;a>#XPe0fEP(I$^&&Sd44K;x|$iX8DkcFkS!H|DqynJ2b9kE zjYt|7L0sKB4%aX9;>MI+V;QoGri{&XIvow?7PqRw3c)2|61t;0Ph=I>TA=9}hVs%x zG;Z+nLCX%Uw$%k)jFMLCF#HI71IqAQ$zcxjU0*ZK1E8zry56na#+Dp!_Q}79(+uNE zl=>NmDqeRBymisFBI07$e7Dm*Xz^HLq5hox;14G+Z);C@=$XOFrU7=)d$fX3e#kw5 z<$^})nrnYn4J7=f@;f0!%HC`&9L$g}JladcOUa*@%wFU*s;l0HGg- z>77{a&*;VB$GH3;e(2x_l|9-vJk=|pdVe?6`AdR5Asi_*^iG(Q_3j4v;MK=f7& zykHQ1@c3)JJ(C~Y)z0vYqOP!%2jJB{T|saMP|SUGKj9Z8%#B?S!xv}A*ft896Jc8l zgotnWyLdbBBVUlJea;ejT!*uid(>l{ltPu!4u^yIq4{*EMyiPX8q+QVnh8TgiQ`Iy z!I#THlmdK{X>@hcuiK>VK-&9F#J%&T29mrSonnh+qjc9x!ppTlKRvBPFA>#YU{KXIiu5jZO1ea-ik1(74=;#sJiOmxW1A;i z_%wVlF|d7IfG>3(aYa3K*k$G{XHo5IXYL&%oFICu;G~Nj%!$>oql>OMb^G!PQ?;js zbfE4vZsGj&QVUu$RwDLv9_}k^(c5hLcb?e3c4C#QRrkfv;We*13n|xm#~*+wH~4+V zU&Qve_(GuH7-%;+eT-jD3u$`%*xxknuh)4I--t~&d_r{JRAX8iR5hKr?{+<3 zxGP<-?{>pqUNxN=-$Kh_pz?#XV%rjLJfS-N-YEnjeh1{0_U%jg=debM+vB|C9|w55 z3>;^p$HCdD_HJCK=m;UdCFjb?O;Op1#?Djr`vT?4^x|FnPrsbg%jsm7>kJ^2@`al(LehF1XJEDE^a zse>Nzp|(kK!l}aa<_SSeg^YfULj6^R34OSc`AtU);`OxIX^&Y#0>>~b5j$##hR zkf_L&PFp5=#*u?bEK7NpPBgBUee_v7I#{iAdFd%JFDJ0B0zH4*O$bh3F|J5*ZnSX6 zH=Yx2g4OrdJQrfjRo)t~`k-{Irm)!I8N@^f+y#;sebgQR|1w+|?y|1AOVAjZMXccV z-*uQAEJKU8M%SASlxNlU{AESU!$8?mZ3gT1{g?W*vtk!-#)s{8!xO0mKdQ&6e(Jsj zJ!QV5CCVp>C(OulNA3Eg;%ZNzrl>1C2^*M?>o5415X9_@{9EElb8X40!6&1dPjBpo z$$8B0#5Y+p5bD$4q#z$~bwqGi5ZEISQ|UY{@Gv`ItFcYzlbTlq?c-x5XsHqO9yNu$ zs43XCfF`)b6L7VlSfMd>X3X7u74M&BjVOYq)4l6MTKrkz$EyrBN@4iIICvIPYw$$M z51fC{S0XU^Q^kPyNS_=*2|RM7cN#LMA)*(}IkpuX zcw$>NqYBvJ@GVi~5Sa$K;N?CsWm3ZqhW=6WHR22VkgfzI{c?(JF`q!vcU z20d=6Z~vOgwhFGCb(jruusMK57JP+#sdK9kFCu-@1jj9brW$mL2GuP4U$kSDZU9dA z-HWeH?{K_u;FVbMe>O{$H=DbNSHAFQA3XRQL?N+>B6k z>`D{P_%@-i(<>68>yECJpj@xxfkuI9vaUj+&C~;`w$cjeuEtq=TI4HgL?tzvbhD{? zG@VU>HCy3zo9`e*2@X^vuPx$SF?leZANI<`p_Ww+G*g8zw{NaI>T_RBu#*uARrY(X zHbaSC3+!}aX!2d^Cvihro1%C@O3n7w37=PG5E?|9Uj;(bdI~&z1pT%mmz@>+M~Aja z^mJk4=y_11D-Tk#6Aj+#n`&3kFLUqSMdaO-<}5lVd@<}u?|MW%Pe2}U=MXg>igCga z$~O*4A9Mo%jUf^+h6NP%!)-B#G&bR?6VTa`1hxT{M0cn^aI`TjChe^lE4vf4F)QzJ zOB_s*arz(THPLwq4k26#7uu!57)tWrg(0*|Fqp0z6mG>MHDn^LR za9GXE@AwmhyS{8rz*jQby*tdt_ z!hl>sZJ@7^E|^j#T|+RFy?B^FY#u~$r#Mhfp8tG_%q%=3G`NgoZS$61!HND}aBvre zh^|i~YCy7CsJCQLcrC3&IC3!~`6djf^Co*}pX&QQ}AUwNnN40@ug$|=?Sfgm4v zVMbq4W^L1@)jX!6%-;Q`kZ`pyp^%y_`8VaYr-$FVPL$xT-82J9a|`(x z(H=@{3#m8aBojt0wJ@J&oQ?3kh_%haE9KRBMa?F=ZH3 zU;-7GiP{U|^G1N$p#p+1sT&WHZjpi~jeD=pZF(q4O=Ds;H-umnz2wq-nix#e^mBBB zG(nhzr2HU*a|zSr8jCSRU}KBg0i6l0N`q>krTT%CpyY)OnUS_?odXsyYn%O;XfyNW zNzE)>t*mouY7Il!FKjjjn*#V_Ot7Til&H=rfs2;44JWsZI*WjFddjBotM%fs zS%n|JNGxJ)Qj0yAlugh&of%jD3OO7DG{$#GSCZ6=TBUnWwC6tYSKp&TUgEZmU^{*S z7T+R;jocNwhN~Ms=Jo#Cb;~ zU)Qic&)zYi{avf4E8_55A+o{#lf z^pZ~VMq6&F_CKT1*c&|SH9z|!(9izJ`X6fJzgl*FL@Ule8|D9)n@Cc$vHDT%_!dhz zoq816SSv-@Ni=%eEF$;HA@ZrCCL$Eh^7Gl!uDf2EJhxng`Hj=jP`m(tDC}M6$TN%F z=)1a_=6D<(9=*rVZOiup2f1k9*9M*A*}hz~Y7EnqtY4kDuiV*Z)Nm%HA&ttLDw#aI zFVjIhgw%A{JuE=kgc6M&5{<<`G?qwGy+_JJx`hOtbzw^NNy=HQPLmU-bs`r8@kC{Z zrK!?$tTUM{{-~dK9q3pS#4V^2%m*HpFuaf+qi_!_EE%bW!CRXwiS&HKO)OihXbp%j zd=T(O5+QtWV6BTE9F|pT226%Zd>DSkPYL|+VGlH@^?s=d9P4S|wV7XKFn-p<} zwXqb1*5FO;x1HopLHB=S(!8_`aOztDj#D3S9y&$w$U$M>xMDj;2Tz0k?Jb$c+VFr~ zZ<%P$4Kl#R2BnE{6unJOnK7uo@D(|{!C4&I!?g6GHoKwSfvFA43aHl@n*6ctBm^&` zsYRqN$^CncoK~^F0R#sCnEC;H)BJ}u@b6(zIVE)xrhjr%)U51r1`)sBbiLNJv;^-U z(E=SY404PiIk*o907a9hZqw=yPK^EKacbMJrL1Jz4c+9_4+I3IAqeG0fHSydYF_jB zP=r@Lj z2{>;P!)-7s`&BoJ_go`OTY&fDJ=?>D+(QE(LER|n4;Bi4m^>Jws0S+6zhfs2R;5Qx zHLKE~qW_xrnWMOkb`fNxQBbe0Q<^$71Cc|i#p|MotWHaedgZg1>FW-5x|alOGIT&+ ztKQ&&KL2v3Bixh8usw(CYm%PIK4qklLun&}7TH~GV%u!=3Lf(my{gK)xaKl2EE*WML zi{#ih$K3A?JoVoSUo~Jb@-pNXKOI{HoS$5E>PwqWts-B^*lJ?-UzyZl!BCpxH23Q7 z8<82mDU3cEs4!bYdvB>na|>cJ(hMQLJB-g_5l_BXisNhIx_Vz$p|2>dx_kV6o(Zoo zeikA!<$8CTwi=*phJ*!|0lEt*b|59?%^NlrTODsYntSdE)3r7omy3~oYz!I!I5+2$1t(#u5<;zcy!raE&;eB&XglvGG)o!)2`0s7>n5o(XK9*3kypq(xQ8&mwQguJS}ZU4O$7PoNo z^`O5kZb?AM(e-y%%KcAnwZS?5njb+zymrv|vJ5FGISaQx9hJLc|F6uWi^^MD9mt03 zshI;rI2Q7Q;25hGbB&^RpLNagF}K^XS!C(4v$zVD)m00(MdouS47E?uJo?cm#4e<&ibIGPr1F1LD3 zS__ui+URJWXC~@CZrQp5Yf8{?(J74IjStwWLMR9`apcBv(~DuH)m1j*o*p?c2cLKt#k`N)Svy{d(Jm4##y$!N#qSqAEuz zV}2&DI&DxOeVOg{hjrt-MK$7Ew&8w$TOEkM98{jx7Cr1JYQqO?x&4I-lKte-))K|v zh29;7D{U1Y63$j1>+i?74VIn0()CCGy&mEuk2J^~L07Pl%MlBfM^eZ* zPYm)NU1JCIk-cv>*!=*cZ>&#aU}%be|FF8;sCQ;YT^#c)O!Rs(bwLwJwfR>PpfkcJqWSfk6IMylmb%lz;g zPX%5IPv?`e3W}&9mzp3FAw5s%_8m?5(--=Tep=+%#QG@SY3f>P*eyH;_W?-o0hf6` zCU4%YHmxfZ?Tr`d0oXbZKR?MgsPX~Xc}{LtQS>O?OwcliX&GYbqj_ZDC_kAEfW0S0xEdA%^$D^e-bx$}VN8FU*U5Hb0aX$w8VY)ze*e zyrdDnn37^MQGc9mG4oS>7las*zW~f_Hl}4CU~-hBGLSpAk_(3EA>mSnNffc~9?n3c zZ@#_8!#wQ2BKrO@Sm6{$sxI&kMBmTh;{TN!{_leoBn?=Wt_5j?z;E-}r2u(K=Rc9nu z=B6$p&9*wSaNozPV{&4JkuP!TTH-~()SOyE;*pkFCd}-KLm6!?)o0{q*?cK-_7!Ysiv@K};c$Fd+)lD0!*=z)sMivD%UkvpEKa!)UHTik}e$!vGVZQcW{eX zkN5OB@I><55~#*zurDP|wz>Z;S}Kybc6+pw))pxA+w~kxh#c>?$AF*Fj#GKF;`_1) zn+wtr)^&)F(gP-$r{%bOHJ;R!`1b9ap9(^?a)i0BLVgUj)P8D#iu|(l8}&j$E=w5q zs#1d%nU;s+BfS3OkQd2QeyS76JPNRPk+<+GO7MNEKh`~TDlTzH(Mh3TS+@`ohp?gr ztMJ(=_C!Xovk}B)DpmK_u=+pZnz-z~VW+B2t#EkCUiZ!*)I1HwRa5u8^U)q&)gF<+0o;i z2sCty@$J(%SygI_uWM%R#>RIihUg^hdbx2P7uLwPawVKF4R7trmM zv(3DkOsRG#&kv5Qyb9s$b*oBm!0`^SR~-r~-u~~|n`7l>+4xPi&htuqC0O(&PmPdT zw_8-mRQR&xJCtpJp!CDx$>y`^!UFeI%aL}+&8U?WJxc*D=K~kD`)O}UGs*Tk%7#gUbzfJY z;Tj5i6eFNe21jFohp1eZlr)^Y)BWJ78X&d}8*B0zwXWGUta>Z7 zO7wT-={K|w7Z23E=bIAX7EX6es6KlH&F|8Dnuo%c<3S8d9gbSm^GkTUmmC4`S>X;{ zSoPlTq%YH&2Mp!GkZAVaRAi5nf9zg9wS3$9-y2AkM&|IvQNp#v(ImC#bq5iKjog3< zy6hlc!jUlYNn~q2#c_!G0p*5z(%7{F{JVv!puf2S&)40%Zm@=|9#kS??7C*BhtS?4 z*6H11*F@jgV9-JhY=k<3YE?bok(NXX9$Y70-cf<231W!A2|taH9)|8&l&&fWj2_z5zFa0b`VXx4Tawk;@Fa*s#FxSC|+&P@S5&C-e~_ZRDOm~ z9MzN&g?UN95RmK51CNxa_Et!4AE{ud%iHVq<_Cbo1k%h;u5}!$cl73_L{B7JFbD5r zacv;^%Ik}(Zh7s+LJu2?{}C#Q)6q|*((v81=kC=hIAd+S@o_M(_^hMsYuM^?tmv_O z0T19uqKZELqY~1%5ll3V&fM9Lp!IAs6-&v1w{5vp&b`7~PMZSaJ?`u_(G&MRWgv|< z2>@m@fA3y%l^zvRXr*14ctJFaVJY?4XXp9UcG{+Lr;jm-%C`O!Pf=r{B(m?&G|*Em zYXZ(*ckSs3Cvkr#sPLC%oz`xe;N&~!r-KV~v*rYB9`(s#2kE$i?m`4(kPZU8_B^9| z_Ab$H++zc#T#ZwV{0`pe0GW*)5`s;Mo1=$_Qf#Ek;Er`h<(|92kVD~KtO+s!1%;(@ z7p=D^M8%xb39l{}TTlr}^F=U`1-elUl`JTCVee&70@aL8M+qyAc~eaK;wiq7jO>T~kE9D(hw;sHRNE~EC zvVsj$uOnU4Nk2$QN|GuIWwF`gp2`}SkqTioIm7g8-=Z^kJ<&7uWlJF0khlf=D7BA8 zQzaY+!r=z_-|NzNQ~G$*PhGP9={)>@Q?UwJTbS57|39*oe=c;DZ6#zilrP#<gJxz6 zg7^=ee##}sv?%ry1jb}+$Ju(%T-&Y3M>&4qzQGV=4t}x85fYg}ak+>0AhdY|DdQ5- zyU-R{$sts8hf=?Mk_KSH=jhA#&e^NT9AKA=>PRNploM4Z7zRv(i37@E+?-U#FERQc zTWpvw@!+-D%(2KGnH5N-j9znt^sX$BWHeKMac)yM}TTH({q@%b-H(9yw*M zSSE^P(w!F@rM)H}f;O%xF@2a8@h4>F5vmkQH$PVQbkgd@(*l}qFpJ?r6=)Kr#!a;B z$ydaLXN4x&!VTE{663=PY}H`{9VYHDjc!ruY@r==N+K2Xt;bUH?Kuh*}UjZ?AwQgmAZTb zh{hZ#q^2-i^M?VpnV~qpY!@z>d7*~72oZK$U!n&hd)TwPI1XwJwCB(K z!ox%zicq%i%H+(e6zga1!m#2i3+tSFdIIN*vv45UJzd^zcZY2!p2dQd+D0!G|L@`vL;2RTA{cFxeX zHh-aX398QN;@tg>MPGqWBL#Iw`Qm1npiUoXU?}Hjr61fTLT=Y*h}@x!$dd8KhMHnM z!)Gy7*6P78*Q7Hq9O}##m#1@cqpxpxwuo1xY9MoCLfwVEuw`5Ddwyvy|3#R&D7Me$ zrqc(?*=2q0TFLA_g?5Hen&jVNA_7w@*P6;5?fbA zAlpS*_wq;Fvx91oRO1DsM2InGB#&IM$T?XY528qpLD0`eF<&j%Qeq#ykL{;T0CI`B z2q>7oZUK}R8T9qb@ERoU?rSwR$;`_HF8Ig_#WU;YBw@$SP2C7iO1jM{+35#D%xN6* z;rH)*!3YJhY&He}fHVDn{)hITLLEgDBRfZ92^)LsfA$|WAib3j8^3d|r;jR^%w4T;3X)dlPIkz7$jjeqx&Ae#xGIh3|gS#H+S%Cl%H%t{6r_7)AcEvi~I z@>-QQRxi@J&ad&VcQ|!yzWkL> ze$8Z_6-g-M(1_;T0ssTcR6ZC|_Wspj&MRj>7e-6zYQ%}kX%QYFxslq7^7qHCqI^|c zsvIXlKHC73F01D>KgukmndF-K9i8wqw3EGQ2?Nt&UK}CoqL36(w&{#D89!{zmL=2rhZ%c+x@BCcME%& zR~4@B#yq1Dms+06Wv;@~JBzr2VGWNEZMCwqeX^Zc*F-vl8V+{$&{3g%eSLLukks&J z=Si$!cPCw)8G-QNtP-`>yr$kTkFSpROmF@dR~>Rh@`LkBfj`_Ch&>Uw$Xl)Q4qYBTB&eOsXe4`EUx9oc4NFdAtQD#Okf6`fkETYSgVHXK0gv@pVj zIWQQ@~4gm>!|<>pqxUodn^!Z_h0FCZTWI5iq&($3cxDRPn_}v64jG!C_auM3w>0E&i;c~5sWTz&P03&zF$hwXiQ+hE z#d>2PZCeHnn8j$xwU)n*uXvcX@VSCJ+Y*jQ4Y+$rfs@c8B8FYd*@f((0$WJW(n z-`Ql!(2E+`Fi~w|Yi;Zs7*34#o8vDegF+TG4rU^7tiw7A(^d4MDR_R8Kq# zTVA(OO6y__qoi$}mm@g0wS{?hpAn-)pwEf;%aF|BcWcll%Jk>!_w$JYY)Tn z-JhrViy#u^QA$NgtGQc>9;$No2tfkyZ&#InU z%C4i}mjX#I%58Kg5z3={B&+9%_u4_;WJ7SJkvhV|jA}ftvwvvQY%t!%;6BbkG*&W1 zLJT1qc}XwInf%!is%+bo5Z8%k zmpMsCoXdinE;Yi|h1Sndw{dBL?afTogADoRL0-lw8u{i~-ug{)g6;DRZo|Bg+a3+P z544@bggUYgI+Xp9u^w{N!_9gt*&0XZ<}^(~S$>~{o5zXm+FqX5i7xr&-Hh#9Q|OgZ z$EmO9Z{#kc$S~`&%dacs0&lAjEwfk_T-;rLlD#}#&sd+bA#)xxB0O&YYtB=`Cpi_o zH#nY)LLNL%Vd(=#&qN-tMm{v1={ks}d&v5wH!foTGk!NOcPF`p3kNhNcNu0J?54sS z3aP^W-s(0fG2?PBqOC@V#6~!zLb?XBvt#Yn{$^I3v%6Oh^*S=CGdxe}hwnmX*TsQT z^NNyCr%C={dD6QX-Py}>`$llJ->4rBZA(IOGj6NFb}sk(g)&6H+(LfelL!qNHB1V< zA2e*V=DF1VkrNYEb;+@i!89O4U2*f`7^Nk zORNH>jy;++qz`a>U-UsWtb5a6X4bd?7v&q7qaec0kQC)<&lC4_^D8=ffOT6nI1;15)mt`IqKn|cWXZ?X5pLp$r5e5E5-MUP zo1fAn(^-pIsz_ssn+gAdR)-Y3PafbA9-b5=5vSCT6jS*i&`6+=$Ps{o95>8-hF$1q`6Om379B z7XATTjTZRDA_1W49cS|K9qSXXzuU?IS827k@{*ol+aiYU6g(;MDv&Tk_TzRdR>PwgDXPVbY$dw-?ZNK0dVG|@fhNKx3KJhTLbP;B?6AhR@D+X1%6 z(_t%LiRK`qBCQllI06%Z7<#b>a`v6QxMz3*BatVGPkXi%(( zw&LVt&I2gB_hutR#6HE_q3s_Y`eoOk7S7(YF7x0vPdtK3=Wfc-2Z6~o2m9wY2HEaRC)nmIPGT3pjx84%t z))6MX5d-cnR=xD2LH_VXfY;EZ4?E>@H$Dc8)N=rMrILJS$ioNqVXvyKfDc|J-wX@` z-`Q^sgSjir9Q9$>C3}-!2t|H#*dx3`<%{?wbC?{TsbG659s(g~ZoCmFQOYct8j>x6 zBym-nGNOE%r0a!0<_Z2pQfa`sjc{TB%?^)@Ac~rw8i6tHKsV%pyPh@kZT&KftM7M8{U2?62~rSCi^-N~ltEP08W zLI$TnrEWwCIe|0BQV($6@}4)CZbqdFripkPF=;~=0gPJ=DV>^Cl^6Q{r)gu3Hg`-s z3C@(4AIxIuk5tRHp3Tcm*dN?~M@N?O>jFwmKszqB4q7=%?siPx6^fR>GTZA^V{Q&t zw)uiB0|_JgSEIarzanva*D-?KR*k=*gI`d&&f!;neMS?0q$b@UyTWxFH9xSqiusu} z-(xQAIjMg5)i`|zBt7Q9Jansj=F}U#z&s=GGAO#I!*I*FcJzJb#3Fa+!q60>xxOl` zVx|SO^f`*Sy6PpZp{}m{IXcx)ct1n%wnXVEgU;^NgESKw9vpK?9a$!+mxazDpG6f zw6!|)w$Pwr>P)M1+~Bc)fP0WAX&Ji*k-hhPqd$i;UZu=>6ZWDr8HC)4C#PT6tYHXV zg1Ck#e#C9PxBQa$i&L2;ao5Z_N$29*6idNlV!S2(Jn2S6XLo>+>3gq(5yy5nw#u3S zuN}8zw2u6@_64Hkc>jX<#=$jR&y#mZpVo;{6U${HZ2e$h>piC&YN3+|d0a%T)iKLW zzi>H;DaYrrP8a2nbK(oAJ}1M9?HziO*X~fZ(^*=|b}dFk1vCHU{nn-0iVy2;hGKpz zvLEAmawVo%_dwZ1YPqO=>q4lLy^E6Atk!v2-;svw(z-f=SkwxC?ZH=V3dsW+7!~xr zc3~mLBqOm;YkOIfhJPe9Fskbu}*?cKQ31z0>;@=_-^TJhiQKy{}EazG6Ou5Dt z!Fzki$>GKZfaQ5X?}Rf4E}A~#h2JGFL39?sFdHI8=b^Bqs4TcE^MN#Fm`-rY2>EPE z2y}$7PiQ$)TouSS#SqVmFfQ|=9w>D9KO3U5^Po>f+WzPkMV#8S1#K1B&DePy4?A;w z2LF&4Pb}Zqbjq!rv&M?gRcJSJpBzP(syx`Z0Q2NN%>4sA{WmM4F>XPYspgK6CW#k8Jm`{XqDJ$g>@{9Q7Tvuc12R-+p!*JPCqLysDPSv3noH$js zzJw|16-xWhlf>BpXLSho^CV^Inw4?6gmbx&s=6kIx79amCe;l-EEb13C}upUIVt)= z&wVH!A49~=QJFo$El7(Gjidc4Jwec#bfS(sj+3I(r|#@SyQh>qVNsqtPZi=DBJu>b zc_5q0%P|D*9GvsTR`3K@n`v(e+v?|fK=hT!*%5l{T*_>WJe1Lf;4U!ng)528$Ciz* zJ+|DmcL3=UIS&aeI1tigQ`h`J+l*~ED-d@6_>*wktS$+K?`WKYao*>pIR_Tg73EeD zbb)vkajZc!byt)0lu2VD=R0)`UaKAKQx9P0G^imvd%~x-pNKX7v zZc_eh+BIZoT&n7>g8jefI;ZGLfNopIwzH#-ZQHhO+qP}nww-jaW7{@5?6}jn&pG$y z+≶svhgLs@9rweUqZboJwU{xk1CUhX*=+Dv_dNbhSp*5NOGg-4(MxRbBqOK;fP^ z5Tk{`J>R|h>af$O;wge@mLYJ4DIm2fF*8oXy~XrGBms_C@wZXTk&n2zs#dK+lSaN# z{gz4miJ~Ev?O^)=J_I@2dEK34)6moo-ZY(To+g&!R<4XIhtv-mbL@XuJLOK-x%T0f z+MPOy8oTlo7xzcC%mgFwPg&QV-#P??P?&l)=!RzSkEz-GO?@FkYY5y$b8IB#?l{-ZHvOu8+)z>PK6};{_OZ`)if*4!8thIL@;Xgo6cnw9=~NU5q$+2rvqELJ|N2biu|R7 z(KOu$67)CCS}hT?Tcc^I4|?vZBDzxjk=RoaloescWsu4FD<6Rp7pl>MK~v3nJ?ugU zg;4Az6A9qc_iHFjM&1nW2JeExhOT{>fs*e`5UGr9`G)8rGxaewU{U!jc4-Fr7Wt3= z>Q_i(mf^?WJjN8p$Pk3T|Gtqm&6+z_CRJTT=T8euZ%TqYJNicMoWD(3JuNHdGLRMr zzA$cSmx&rWo{1|x4@O%0Mb$0{=DzpJov*-YG>BBHKeB38DcN$L*2S+9SE>ZcF|X#` zDn9V)H3KVWuUNMl1S$!xh}=p)GlFvVDal@)y@~ccbwb=K?vK;d z+GcD8<91S%A^NAz+popVCt;dW`~?ug=|;jIB%ovvIBDYKW|$>Rf|;S{B?#wO#!9wv z#*uvZ7&soCOPN7?D= z678gr9Ke4qqur?)&|khJba_27;?Wp-L{fyD!U}Ie(>s+dhL`=A4UU6#rsftygz%3n za>R=pu&4S+*Yg>w66#N~|9P)3caxWkF>qj6VdVFH8s>EVeK-8y zG6xG0&z9al>h83{f0jA^Kcn^k$Q(eP|KaWK{1!9tN+hVsT8Irc7=a>; z!gzhy>?|BX!QzN6scXB&T~c=&uKkycdRteLShGm^(VB*C??z2~?(P1!>?fms`$wVc zelDkDhEUV~-#@|KcLTk7zAvu7`tMc~3;YS~m=yc2BP#E=A=UgMWA9uZcsl!sfUj@A zKOMXP`)c>l4pax{$h%5WjxO_wU2o0s`z|B8Z|KQ_IF5-`pq)nZ!BKTeIwlWEaKC{-Of`mp5SO;*FEX4?+x;wH=x$`?)2WaG}xaWZkH=baf256`_AD4dkdLVF$bM%zso zD0)W8#JzSGXk^~}V|3*(mob?04P|y07%ZIZDX=Y_lq;gN9X3Ml&}U6Lz)uV(Ekv|u zl*PDRPvnnUvt;G4Fk`CRM1v;K)J^_=G0gR@vtsuY;0_nHzsWUFTf$m6Aq+NjF1Jk*ggh6??nD7%Cx)qp7!XbQl{_jD$W^_mwFOgpTs$$? zbe75wifF9h`eTc=5Nm1piPu_>1R(D=->A5{h5r3By#6*flT@zi`od~^Z*61o%yvgh zbAP9+zubY9{n965GFB!s#9>L|GoSDJ}E}U7g&lVC1wiY z_`-C&-L_{%R}AUiV(pP^?vX0Emw)dW!4AemQ32Vu;9&2oNYdRuz8~o%!3DUFL<}JJ zb?3TWY#1dBl-ri73M)Ykiyo~Xt(gJxitvvj=*1qi4^JF$562mQsH7~JP}Ca-nw|UU z%Y@lj`#(jDC9JI_RNUUy*Ya|#wzE6zZ)~jnveobGxA+XXg^!B7mO;&<6-ibyArGnd z`y~P4E6OHi6>m+kaGk=RuTvLleJ+lZ9RIBqwI46xTf#d!g9KcEM<2y5*unn|-Ch(X zNu!Lv%penClC!sue-(!cLEjKHja%k-`zqd3(o6{WSyw|}*lP~~r;@>&8Rc=eg4VL# z8Pitj*AUKp8;x^G9PdnC;*S#hm77HMi87{K3%ZMO5LT4&gMMl>*e%x^ z`!P}!+jgK}kBKk4$y+J38yx7$<-62~1G^4z%g>HYUBp)}1lgyNvK4l?& zR1zTpn9^U?g!t{$rK-XfAFWuMC+(!qgtL4^cRd4o{Z$9tsT!RA?Pd@+k5BE3Qh}#( z*&4OR62#6~z|6Qz;rj4@)1+U}!#K7rTl&3cduv;|yuzZTq`RWn!C!Vf0xQt4igHslfx0!& zOOl1u*2qE-4}AD!hME3bs%4tU$ZSFr!`ve$D3*15eY~V!hfWy4(aWdl{Isp!$ZeT+ zNRch(v7s%K?h;(r-NQ$TEEvRdOnKS%Dz%qb8lj{)C{PlgmfM6wv<$-;e=E}C?q3~# zI?(s4oZi)GiX@}8Abv7LtV67(onA6=yRE=#7)K1>S;E)7umVE$iDK-LF_h`9t*N94 zHAXk{I*Ob+15)*@Ib)GwiZ{$meisXNO;Wo5&y4_P;M7#5r9!~}p!GyQ+Q*ZG+<`#O~ zWF-Ih>PSHH-ubk9<>vdW3z99(sbO;%b9PJ9BdR>v8F8|XP4O}s=SbTc?+dfEMav6RI|rX8u0vOi9~@JDZt}1 z%1d;XAliA^9F`@p3TMd0f`TtORiwW;!3*u5%N9YiB(0Gg)V@|SYZdQSK4P*sYr-bj ziq0w_6AzH0qaJ|AVR4y?^YUoVBCOojv?dx5!4jm`th~2g<%yp1GUwEmYOe11OF-q_ z&nE zR(*c270U0~rjl)xgt2x#zwxo2wWb<~lxC%p!S>8i4U}t}I0%zJdY&mAcIMSQy?-zu zq^`r|ZcO!Othdlo2g=!OUEVuB>bskbuQe!~MQotz*Myo#PF$th$FqZQ_z4nnY)p|z z-y~-i-515GXv=^IXK_lxIK1RVrD07s=nN8erjDfc5eL9j7A7YhEApf-j__;LBVaQZ zyRWDtlYJF6dKG|~t{WRrE}79Im4sUxRXY)-a(`W?Z%>^@?=w6(wB<*W&f7*uc*CwV z5&H6BMhTpBz@-A<)E_-NZ8>G{MTXEK-oLLo)SfGsUn<|W^{$a%jjzoK8~AVl=0hv< z&74fhs8)M~6Zk@DDcx21rcf`C!mYQ&rctF$$u>n{yOUv}=D4t>hjlp9621)tF0G2% z-Cjqap)q&G>+x10bpCh(Bfm(Cj9bx4%iL#Fli_K*0new!UWN2rjJjvkJ?4uMp4 zk{t+Exf9G*5_*-tllVI7SvS+6B;r-6cG%2*9xqt`DukzwhGnj9<2I4{AoKJY7ZWvW zyM`q{**NZ!~1uQ=$N@JxsX%i>#;)`i$C2 z7I%wj(v>i$Ow*$tCM>?y+S8W}xAfLCioS!(QiPqc;RsFdUs&6LIHp0+F-;#rV-**? zW$pd`y&z2=+_;(-!QPMF35r}lQNm|+t|3)}P)BrzIEHCG%tF*c^2UD(VbwiHU+J(c z-v#(vGTeU9Id%Mm1{Q4xhKnk%MG5J)<{D*h&k3%+E!mDCAl|B+_;{&|ZA-l-rWVK^ z=4YK(%@AKX2czzlx#*>@C+in8R_l2!=@avoN7EoW6u^jEeU`7x&dn9*o*1xZXV_Kb z6HU{A&6)H;uU{8~2b70-()kKrT6aXcaA5YIaLD32q9QLKF6C`DemolGH z@OK5$^~hruVjC)r-qyU4*bcj)o3*2!wHviNYiaHt->Dwn#nskZz;049kY<-tj)tzX zC}>Xm7A^TD#ihnvaoO8&pGP|j@Uibt82nY3#nEs!N1ubWN5 ze;|J_hts$W<_~Z&YQE~?JF9Rjn!XhlReqFBn4Lh`GuV#EGe3 zQxp&KMBt(8=g)Ap!W5W;_~E_<0YcO)5h%qIgv3JU*23|nZj(vcjav6M}HhxC^^(EsQgHC44V3R*3Xlu!*QdPIR~o25>g*DHkz zt@gnF&_qLsnpku6gISMnOs~=MDc4$<1AooqW5m5VUwRKQ3x@W{S=~<`Uj>MMB(2UT z9(DwN(JMH+EACTfK#7@aysNAu!+Ltv?a6*nbamFk1UFH_6g|pL zYn|gGR32@u;R2giNyA+Otz2e_#V)A3+*G9g1jrk0So#`GP}nhhr7TBjkJK?ekK`~LN3PYs z*j7hv>yG|-HPZ~t+Wkekp6~=-!=OJBES8gGlABc>AwKY{`xV0VK`@qYBztOB#Bkz% zBjdO=9LwL`<7CsS^&v270+AtS-A$X9*@0WEk8Zv?FMZ36R6i{IFdMzpi#J?{3q1 zV`@IF1>>$KkM_YUCGp0Frlm44jMV<38 z8tVb>E#NY_~Pl>^;~s z*%d^iup4B)=gsU;DS%PnsWTqy$C$z6Lc>vXK8ma;WKd~lFzrZ~TyXXdV{}b@TC5{T zdw?hDBC6~`PN|3#!J9+YIp+C8?7*qBe$SW`MI3=}8I@htWI$;OS#r-{t27^QD}0Ok zu033qMz*cN+1AmP^+?vWdTQ$$p3N~$mtnsm$^ow{IBc2E{vtj~{632mC~;nrQ%sk= zzmqMXUXF^#qfs~s0eq4)mxkF^*7psaw?x2SzD?{DGo@A>A3sN}XEd()jYH_TciE7# z?>D<^;Wv_5KT%%Y#odRRb^>2-QNzm7uD`3mWp@{^D#OYQw0)P(OkX{TmYBKf#w*4s z2&okQX^ayjazD&^Pxk{Kw5a3!=d7iyS|NhuVbinl()jxU$xFeY3 z&?(D3I0X`F0E}QtA;Mpr0Gpx~p@4JvgXcKhkmkr4%)A!&R>&CDNRi*2hXkfCe5M_< ztPH+a?-|t`u2;QhEAL}!l0Xoz7RtLOIghN=K&U(1R9$PfSNVD`z*wTLrVpbWPAv*6 zR9PRq%nv(IfmO5Fc~~yNK;puX`K^&bf!-j3`cG-bZLWBzCF;a8MlQIRS_VF9Bx>(B>!@Rkxy%7+Em6AI#b6I zt0{=ZFL2--Rl{?hGCPR5?5*l+aOK1RvIMi#JY9jd@aT*H!ZE*V*060vQ6Avz7iWap z1hJy9vJRioFiHr@aP8`v1T!HlV7x7xoM+=sbbHNHHf>-$ik;X zbgP?=!N#1%Uy&=k==wJA;O$L$e3V7Yo`X)F;r~GA0d~c#9jzjHW2vWj zq}re}$4)Zv%OVAhv_2v0K2?TWPvVs$|~n*YRkS_T(fOZVT&;$`snt5Yl0del~@=l)#+JPQ>!X z5qjar(xq^l$(*6gTDGG5f!JLv*o@>+BoW5-q{93N^T#K+V4of@#>U7)Fm;L%7o;qE zPM!BDZ_A^&Nsl0}hH#~Sdgu%7u*+hFJ;Oa1)9&U`Y{EE-c}^UK*MFq(9zIL){b@WO z&W^07CEtXlRi!C^rGB)*T$_(Z1gG+y*{0Dci#+5g-97An16MeqW6o^c2QhZY0zXD* zn%;(t;>SjBt>m0Glo(r`*uNx4O4W%Uyhe|y9@-S3FAmEcqL@6OhA5n?ZWy!aegs!? zV|RaGLp8*%6eG~>5soxl=0tG`s(KMJS%x?c8v;Fcq_qTxcX&MXfK~`wM!+NB4v}k$ zjk-NhZu0TN4PiKf&NA$peg@y1fjwqk9X9L0)E(Ai>E4L*47B$F!>GT^x}vTrEI_qN zJX4)M_#841!A~_KQDP9XWjX9-g}9P<37`u5dxpJ2S+;#(zOhOJj?pp>&34jOA$Y0=e%+QBvBrtadYz)ls5mf&fA2yn+%d+GU{j^!as%bSeB4pi2uddQP9o|+;s)Qh6P+$n&woyYqd^}=E-+=c+t zK+=4bkMWegcgeN~S6~3f;V|X8e#J8T8q<`XAybcP4D-Y^tge34wM+q1*6s#E9O#;i zxIGo_6Qem34)wUigH2fSo_9r0g&P8|Tce<4(QUp9Pj+`7fFqe$AfJ~hcJq`#l;`;c z(q&tH)=oqo+mwu*1?pNRNSiv(twdeOL(nSC^Ftz3G%gs78A~GCnMv5|C+*k>8#Aay zj7b$%DqTj~&oXDwQ$#vzXf+ekcO~Jj#vzL6UgUKEt{1y=1Z$zb`n)RGJqQM2FqO6C zo$|I!%DK2GimpW`y*n0nZNVV2h9)L=Z6*yS(Bmo=n>sY9%H3O^a-)-y+I7Dlcnt{S z4_)8{`O^-WE*{fq1j5kKSjJYq=H8Bu?DsXJwstSm6~sZ7iKEs~hKL?7un+3lu2C4TWV+g4khR0g2lS@`*UtFzC6@w2sH`>xt z7`Nkqr)5c@#F?Q(r5-IKSyxbkhaYk6sIqE|r+NBhoxyIzqZ+-pDYPy0c*0`m$MO@J zRl31Q!67NfQ3c&#CvGQB&c~1X5uQb*cQ(BqWC^0+=?*TwOyprqN!qGQnKr~Bb$azO z%E$D8!s2~PZ?-=TgkiR41c5V37+~C?FVM6wJ8&+3v~s_*X2_y=l*IU%?J?yrd`RDu+^xd?E z-2%qXcHnGg)Zg9L-LfCO4QdNik6e=R2vF#TYMi#z`vnV*mA{$ zfzQqMX>Yq3{bEGkK>@Lk7+JFawQyve=q+}cO!F`}f+y*K8}=3mw9DPIAbtYAx6{#m zv=NhzJgzQP{2P|m(W4Xx@qEkR4+}<7-Zvgee+luC+Z|aSVt|{p z;mAO$e}Us}rDLe=zM*f~%mQmK{vd6{7ZTr<92jqe6s8AfsBxOJn8;1(ReP`-j95sv z+eVx8);TA6ppY|s$;6~dntwnnO}slsgu$h0Nza3tLl<3ul-G=!17!#Pog*8Vt}_b)Kpz&fb=q2u zfE>XbzTu0nIsWu=PV@WCEF(PtD}Th5N2&0W=Ygf1M3VT2L3ona?DJylft+-$NJAO9 zV@a}$MX$;Za|$x=EbIYdnjaS(pK#xzn~5yK2UC0vq1&M4gT56*IQIbjLq(m_6g{V9 z`%X$L@~$i|5Z+sl#$CHmraEB?Siqjy}JA9g!)E<}W5hq4W0K8??zBY+LcC;gIz~+WndNMtJYV~h{okCzs z<3T>uv;q0~9ICHB5JRO^QZWOKMY3~+$E9_cTJ?9|ebKsbH1XxPb7Ly&2%HwUyvmc# ziE5<@ppo($LgB%3i|s3%>n|r2dSE0R9Gm=+==A%uPioC?36BZ(3dM;n0u@4YC34m= zId4C9T2qX#2epi_Uz5t^z7GPSj6}))PiLmk=Qb3MkCt{H3iA`IT;!<;-gYR2h7#1d zt{?*gE9y6W4%VRA9>U4A>0O9Fi%rf=DGX1T8{?msI0$z-V43D5a_zUpvdnWK&NnDV z0NWT=9rB^@|J*o|=hJ#Fk&~qa78UIyCyPj-l6uSaURZRQo0;Hq#q>Pa9jRp}>DjsP z|Ez6yl{&&unuHU%llEu|y39v>mqH39-|b(Q zXQ`Xlb;a&E3Y@!SQ-pInElSg*+2{Hzk5q&+Hr@zC^EU5337LFp%a3A6*oAz*UnV?O zDfbD3;R}Z=<1v>y{S`w~{LNL(`)^CBW+PX@U5K%fj*`50Dv9>FPWz<;a3ZqYaavyD z`Yxn|eX$ZzS`g~Dx$=~0X=8urP!V$)~Y;I z6>uxv;>=BRB}f}T$omZyS$8`l$--{`s|&w3q@z^iATUU-FyWQQA9TID?4}1=cyKcf zN7227qLx7)(EdS(I~KV_HO&e_-n(n?WRR3wUh+=LPqk+CPB5PmoNEdwPyu84Bsv*d zLR)V&E0gO+Qdf0cit5Re)I5D=pO zK!f{lJm&ux6Y{lTh4j|l`5m*e1rZFb!aztl;?3v~M}ClzwZX$DnIRG;kqE(gTh9eOf*~odX1F4_yN;ye1>(r(fV7pTq@ePO=Ao8h$)zx_H3_(nlIT_Fa8V90wkc z>`%Siot#ex_(29TdVYsS1U?_u2C&KE{tXLUyJvJ6Uq3mx1`HgIaFS0rPR=sgzI8;T z5$z8R+IRsIVGL@1dOkQlKHa&z5ea-%@_qBazYjzZO}s=tJ{bypb?!U}65fwXlphDK zMhU_Sej^Jm-PceYj2jbw4UzQ;)X}U!w!WVGX$zqFoB_ZA*qJ-2^`#O7e7$ z(bL1I*U*|^CiZyb)vQhWg@8^jQ!@yP7ILJ-MUudn3JtrC*|toCjQr!14tqoBbFU3@EOofSGMmwDMX$&#)a>A7~eQe&(c z*-~dI8a?wRAzpJ+Fm<$OrEDrP?+fp44ofrS$6$M*lWr{Q^h#JZ{PYLETG7-7I5OmN zL*J{JLpa7%;1V!7RVw4 z#iyLcEqhMd|9*MTHn~|bo_3nvT~YRl6^gfmH;SOwO^0x|bd(;M8hbnjb6=i2rqSBfoTlSQ~s@S@mzI`(|1}CtHt=nY4(!b)DA(8q;jnOCWV7Uyyk=zhHsD zvn@q)cVd}x$qkNF(gK3h#)7ASo00P!EAifq#TJ~9rCUig#+UGSB^_z=gm`T$wY9t0 z^71?Wxx8u3bH8sYx;3pR2)nGM0)BpU?($MIc_1~byjO)7Nw|4>llfz;yauABs2SQ(nV z3tUqrChm(9Lz|2C$aKhdeo=qrk6l1R?XRPVRybqJIhSGIzzdx>Ppn{mW)DtE-1_yo zks!j-r-Qb+&Ecuel=F7DQgX7=LmrA)!eG!m7s>3i35y0Q1&eAP3ljLF-wtquiv#2#x?pzWOCl)|BdKn;v{tkFSEm zI8@Hl5n@EFjrN|afGGl=EtgyB_aF?eQeUrIY^8&Y>prsB#C%(e$e(BF@Sz&NveFe9 zdy&>>JoYAsyr#TS|A^AKC6b>)zGKeVtHe?K8-tFW?mNDg#TubUax?|NWIt5YU@&d%fFzt<^XRSb6|mtch-7*b)MrAzh{FH>Eft}YgEXT#de<-({p;hekPAI1=Za-OD$%kBvOEbWu-x- zfWb$+(Cj;kBH`*NtIIxnBuxg-?F%o)F#5KOqN>Djry(}$xgM0ciZqxtp`3La?!5Ez z2x711xJ{32U8^@tSM97?obYDzk+RV96 z>syLcfb6#=Pv+ofG^AoKU8$6pv~{pq2&9va=3KJ2oYCZot=^%3X)x3S>7twU4x2yA zL4RXMKB`bl8r<#|@U?iASjE$8^V?^tqscf|uczwst@ZE}u4BXkVbA#XSqK?9%{Gm& zRSp;0%SGEp(?rx&TWCtr6#$!{8C{a96>_24;^}nL%V%m8!cKg|ELGSCzGcnv?@3sfic7Z?ia8sY71 zBovw}c5)sv;Mk;BFQGaC%xxU)xti>ewuYeAOYb$_Ek?`{U8xG`rRqxPsue~UWUhyG zZj@7OZ9Kf_pK|kUyM}Rl=@FPpF|?Do1J)v(^}ke55lq zXZJP4YLTtA?53IHee<90N;s?^1;z((5aA315OlYP<9XXTA=U=0LD|_}^TdABm}jZB6Z2juiwZ3vhrgtdd?nxz}p72_M-xdz=L4}#PK z+7+e1&y}!kYqyvpKSbmEvMMAt9lK(=0EED;juwf?&oRoAXv{X`Wmbu*V}!+iEY3ys z5x0fim5!){E&LcTJ>KbjIfgFWa|{zA3#UC{&!85v^6O!EtCEID1|e6&u-+R}+BeRa zH$%;XzldI?q!;oD+4Sa-SBysbBam-=kqjkkvx)fi-C<{oHStd{2G)8h{npB+ znR^G7@Qvk#YN-o6A7d6*+AKAYf{~wUave(h{wp^}37otV{g96IIOO=H4J9dVoP2#T z%A4jA`R*Zwn3eQWZOhu^$Nqi1iCOxTKSrWE+b$Q#?Fdi#XOGW>ZLGRs<^w!G?c@+P zNMDW2JO(YDfxSbn;UPIVi1c0IQ@JQ6+Yv|~{rta5a!@SIdLyyiTnA$N8^BIf%^>?k zI2-3>_uN~Q#j$c=ywHDDo^+bRZ=-ZulhfMg-5qqLKJjjPBp34M@%{|pJV$CxKO>@S zp|`smpI7Zjkl<;Ko1>w~HdNaA<)$%Br8y3M16$B>ZdUbtNbn{uzRQan`9km|U_J@a z!PuAO)WNj3brZ%KSq~3`DArKIfOgNy?as*z_bjEI$}2oi6g7hsrR`3u|9rh>KKH1= zrZg$hms_+iO1eMY<(JgEr+6$-gs=tF-42oYg+qA)_3e%9xCV5`9vWPa-ZV7X5&FGX zc~qLGvUeAxs2t+f<@32WQYiHHI23X22Y%Qhr9A?+MMB#OBxTF+#!pNx+BaGG!?FAN zK(by>8IktbE>n{B&LdxN>*-AQ0Le%!vbJStmDp^%rusrk)ts@u)Kq7!?>ptGL`|+4TsWmrIM&u-pZGkEfofQdRX{3m zK{gW!uejEqaCi-CilpDlJT~WWUW?V|wrsK5pk4gU-N2`4oZ0OX{uNMCv^Vaq>tBAg zd9{vB@+WyUYvW0k#W|gpap6kQnM5pwGbh-Yym z`mCq>r#`_){;a!SJi#K9%kb=>5raER!gH_)OuBSgumS9Hr0W9alXQt@g!GIoIQY!- z{*b_~VQe6haIE7@=sw=XWRSOIh`!Jiiw3cmpS>XHjv0a^_|}!n=_~-b@IsU1)`h?2 zrWgqw{hodJFVE};6smvfSOC24155Nf2kY*1owR}R?ftHZiIpW*I&xA-~^4;^cxAsfev$!hB@|!>M2E9>}(Y(XQ{^hA2i)2-7qJuuvoqd z=%*=DzB(dor)Uhm@nkyD59)L8h-O5$1yCLFB9REAO)CB+e&m62k^FlqO?{s^Qb>A( z6#wvOA*!u!CGKwh+0TpA*v@XrNlOfY@L+7K%L6clIDz=!*n1ZXBuec2oJwas08K`< z^I>B8L*Ouv9F5ZhHy^NPCekt-o+$Ee{C|7vyCsdiME^loP2oU5=>9|5YT{?TBK$fkdeU_6$Y}upIgK5BK#6%!ZOVYnB&YppFrrua^aLN%F z`maj<+qgtmaVn*(3G?5|3Fi(ONoLrhL@zsyt^wzH`~2s>1pj_NVEZ_ME24D;eLClj zM*=d~{nCUmUQOS$;=Rc=(6oR$A#7`(53qz*8~^hDb2R*S;;(2%~63DIB@YMK@A1<3y^* z%8w_&OMl3!W@uY`R^GaH--vtivJ%>4@D}86&}(5eYE1HIpStY2&9Y?fkdL3U8pKFU zw!Ow9Uc&hXI(Uyym+Bm5#PB#NQ0Ed7g6mcUl~K7?QdqZ-Bz3*69ATce)(n|RwR7j0 zWWm0AVO99nr>K%IrHBoIJ2*Q}XmWJ&9Z@G>+&c7B=+nbr+Q0Vf&;^_ls2b&LHx>Pv zaZtd0hU3-THjTPDQ|sAb_^_n;ETN|UD3fU;!M-`t3ExIoXBiJJSjaEb(bIB_eZm)S z8TvPE>;^KB z^{#h8h_Pjj_%PNz4ubVN*)EWW{J2-`j1o6cXrF)H=Th*0 zUq&`DBm4RYARv$bm}cbv;WGN~9-54?hq0>o|Lvq{{nv;O=C`8-3u|^Cot%^u2=NaQ zmS9+8RWu>u5HbW=SPIN`o|!%}WD8hUM>MO|4jWtj9_?)zHMK1n>@5mm6O8gL9lLrB z`}VbRo%Yq5`ZbN-4dC}{Kd0=lQIj9h>+bKozj;rEu6HLxfA`!WIA+jgceEn=8Fp^Q z=(|><{Tcjb;~S6h7&Gylb14ev7S9FL-M{{^S~WW{y%0{+?KB84m{D5Fz;_T4 z(%uqV}iR zNNC+eIT&_3UUjxvDiKRV6fdZ#2hi6zNJ(^5KhOu;8_#)_NeR(QQ?`OS5VB{_euM zJ<6cguQ{C9`L2|Z_+eO3njdm8-5O?hnK1rQrks{KD2f)+JgLLUMPjTZ8G&bOJ3}v> zqqDE@Wb#n4<$UZ;H%;Yrrez+to}-I zUYqOqqHc-j_^MD;MIo*d>C*30_R`YvRSIb%(pH_!7E?mpSxnnfA#pz3)%K_!77Uwf zg{xvMLpOW6j$z$x z0A%E3PfYFR_7f`!om?D1mK=YE*K)FWb+K}c)Y8gEkxa1M{h1KUPtIS333h`g>Cei8Q)x0_JA$1^wEP^Vgm~r!_pj>O9UjDaXAm-s*ko| z@5;hd(TQxt%lL@0?=V`Gw>FdADz~RD9WHW>EgNhvTWp&EwZf1$SD`S)kbfQ5Kvu*1 zOi5}S9-qe%BiwgPr?$ghrBO566wmo6FWh&;;4-62D`T>LwqL)6waPuRo#y?&A->T; zj4!;u%J+tL*i_TToguBw(nA`XZW9%Vx)3#pT`WZYmwwOY*&Q3vuNV}0N@4{~uq%N- zX~l;kofCeRwW8a!L#Xc_=;~?iTGw;XNR_Np-^5IeuflCLPd+9nhP)D_F0j?FrnOWx zZ1rKUD3Q+MG(ym9gy+j8HD9*UY;IED$pDpd9&4RoD6e%?-F=9UVgazKR=2ScCeGqr z3$!5O7%-ix7&IcuV;IyWT4`F?5sIkgCSajCQWE}P@B&`%s$tN(F;t?BBotEy-8bqJ zdt?%ZY9_I&YSbnzSw|SEn9eC#XBf+v%JddgCKL?nqmx}CsI8;a3e38wu43^dHsaAF zeI*L0u0THN$S2H0^xtp|m`|9CK}o7~N>2S+RZ-$5&0z9NbWuqmuI6DCiKdXPq{rv+ z+a0Vjr4=(GmIl$;E}XoQ-P7K<=?VGAzbnK=uNva>O>3NFV*G@{SFJMlW)+%vQ4FPp zUUD+FEUwcn95Tr(Wm|?eX{U=ZG>7EBO+6-hinQ-I4VX^)8cIcWa<4n~)+)>m& zb>cLQl?Z&{a|!KIkX!Hr1XXu4ZXU-k!oHGjmWG8Ckzr|=Uc>loDuURg6U)D}M<>jx zCcbK_3GPbr9|fl6NVR{mVtZX~aKf~=YF&ZS=is1=PWyPL_QYcwmWZZ0&)`})(7;%% zNU_eG*Km7Cwm_x$w`Am!YFhTtDw-QK^I^^b%#s~rf6GxxnGs^YWMcmdKIV zJf6#$%j`5WMz_p-Z3&g=axyyWCVn})>LhfXMwv0#@UG-f3T4$0Pz*4i9{fqbqG+j| zu%>*mno`${2{C3znU9*9YAzcFf{(soXdT7>sWWMY~;6H?-=>}w0+jG+>a4w-!W^ zZ_-^qxXA*FKd3I}pb-3xS^%+cOgAj39jk_SvKH9z4)v>s@1ul~ZYL4a;BC+=6@?f7 z`-s!YE<&Zh;7td31Ozl3)$)q6u=fu#XhiBFZ3jU4LK%E~J0Eyxj6#8{5lhd4z111N zh4nYidihK$ze0634}AZK6ZZ>oAxu@D5yUTJ3_>l*Q#2FYn*T%DIR#l3ZEL!!(zb2e zwr$(C?X0wI+qP}nwvEo)_cYGwK8=SRdq1t%5o^XA|Iq)H>f#q+=pYOjf`fb>sMh3GW;GD78+;2;T*UWuH-ia+&m1Dz9;~w88&)Zc zj7-*=XIMzThr>S}xPqHVlCVx)a?q2qZ;x?J7_okH)Gniw(B%>CkveZ{@)PBLKxEfw zz_TTkgr_$?y8tQqZlf3yqD*hUEudw8pgj;X7Fo2ITHsHc9z=F(5)}t!2n*&=gToc> zhdI11Dg!5jk%Rq{ZW0^n5E;NZXFW)Sfdd_lRG$b?US#Gz?Fr_3hp(UZYF z=QOADQ%^09MaPBvdu`v!qA3p~&fp@;k;>vfU52jGIk$+ee(-!lHwtZ zW){g)w+oO#+}NrTsnI(T;vRd#{&>pY>YS(p&8Txb;I~?2mYTqgkvdz1dRH1QPX;b` zhitv-yL7!T@U)iL+0Dt6)z+RG!d=jo&5ydP4`Bm z(mz8_@)YvNY84braeaqG9}1%`-#K=9F;^8u_2T+vLB49wPJ+{q7o$%xvpA)6=f?YNBnw zw3EW#TlT%pxzmJYd#_C>0TaytRf?=Sd-!FISJX|qZC2AOkWT`1&=GQw|AKn{uy6$&cJdn-8&^v;$r#lCF~#`dK># zq&an!45rptBrk_8vt&D*2v`GH$3<%FK@T(Z&N~sx?{J%;;H7^{8&$2@u_uDe30oH7 z_zjy4AUy2GZ#*LY$iGOpU~Km!rc*ZK$9v9qe3@=v;toMDntZhCo@kZPx@A|lPU%z| z`7;c|Lk%-vZgAsJ(k(v7}C#nqd}9i5C>NY|(~gdKmgf z{wo@j!gTfx-1L~_X2LCE#9 z-#qI~0N(j8{&*uK)F8J=QA3nrYEu%V)sR6Sv1C5lMYQ8#PMLl(dezhVN_3A87!_@J zUh$1;DaR2z6#=A&l}ZEON|awj1gajegTRea;8=p=x@(yC=vMme88gzwH;Im$=5;%i z{vER=ax8jW-PrrkWn$BPNfOlw7|ZbUb`kP!LF;&};_qR6u9M z5$!bQ3VL-a?o8*khHkeP<|aSlIf^OGRDX}yV=6P#<2a+fU8h^ilMl{9wR#u+N?ER- zE7&Ob9g+eP22~x>Dmce~5gZ%bRjnu*=!m`ePBW_ii&kL?l>-z8=Gi$L{Dr`S759bQ!PnZont!(j5=VV6b2|Bb=7stG(`j+ZB zmpUHDB}u{%tyFVu8EkjwoYA3uX~R8P5@jeKg|#oW%M?Pn*hS)17Uk|`axV%6v}jU| z%N|3s0&O#HtHW%BbIY}1&LvOHekUAm>h~7^wrJpf#(v1Ex0J)OzimDF-*>{-PsBJnqIJH*N%5M}YU zK)D3~2QhN5<&+RL&{i+q9ld@=u|-`oUhauc{{ z9PG21b@oto4A3`~ntfSsk1AAHrAd83L);HRYAFW*(DIsn{ctP|i=p zIoKU@{PU@j{1dHz@k6XogZlN0>EE0x69Z!!2O9$mBS#vA|N8YmPS<~)r$ps<1w|*s zZ_Ouah;bpHL6HhF(T#pix{JZh_Ji^SMym9pq9RYjLz>2T z0jVj%iGc{|ZpQd;c?PMUG}lO{q9630>)B)aIpdyf`g*hY`|}kQ+p@3NyF#EDM&yIE zcm1$LB>KYLi}g%|tnKg+i|5T&(s?-O0Rj!yo`0mBe+$80euNB1`d#kQG&l$n{4XdP zd>#ZEGW?_7fQ(>&w0Z{IR0#~-Zp3RXupN#h&X5;tc@CqQu&|Q^pVD#ajUX%Ha;0qb z4MTx|-yf&6xM zOBmsa0wUM@C^u$nV%H)^(i zv!~K(Y~U0Qi1sq1otDseIs~%6E9L#@Zo-LN~Gu80|2-f9=bvWdsnBJPy6R;(AYZ|)aLA=2h@*YP6F2~L>9S6ZwT$P+s7v?Y?Zt0$ z6yY>crk}(W8fA+$CLJo48g~>H=Oe1bii~hcea{50t^o-~5m%I9op(yX>YhG*G4i~e zC1BT4SLp9|&s%Qcbxu4vxy{woHlp9ILdT3@D-%6RdjtC1&Vb`8L&(Y;dCYOTNg?q*Xngi~#+E>_}UuOk4#A6{c zB~0YNMpPkdi{+Sv>!bL9?`5751f#Rf(1gie)X%X)Ci=txV7TG*Pit%%N%~oH7FL|i zQq?>+ZACUh=`+SCMAxWEOj~bJ86|7H)po+NKK}c1)O^c~+`B4RNt`gBwL|Grz`*Lw z0R{hHVd`vfvab-c%<}d7(MEC10DX(2Bt^*V8`4t-Q+kzg%!h_|eJr#|56Q~tzF|vf zJW}`FA^$Zz=aO)ZIC<_f?_wtd-f}a{ugz{fJa)%TFcqPLj~H;p7;%C!Wvzp3P(EZ~bQQMA)tenG3F?m6!%V6HtJD-O z8~b+%+#o1q#2)3)3lJScz-<4~rUA@vfr*AI!tt(TvzUa0yNWgGF$~BN=`j2BH0>-d zFJWfyaWP@6Wo;Hdl@@EDtGtQ%IO7_syskHD&n!m8HMOLnpdPN;LqW=6zt;U8M)Nt; z9go&xHK}|>D`lY^;YoDWtf8o$XCUCBTKvd2{ENg>N(zoOyRSPydCYCFA+M zKklzCt`QzD5Ij3L8_g7Uu-wkgA&Hyf?pfuL9Eq+hT3bfSOS^REsq9=%=Y;KCspXU! zbl$6*%+}5}+w{fy<=`|s*(bfzYyxu1hNRFdD*6FlNQY`3cph#EYacquH4nrDS@+`x z5@z)!mo^!|HV=zIOWu>UMM$+nI+%l>?zJ;>{Xie=5mT?;m2lllQ#n;LYxzJQ?&C?< zZ#e%PKE!ZUE&_j`M;t#P)_Nk{(98fzC(Loy{d=~@ z)MfQHk9Qt~!^+Z3ctTi1Fe*LRNy=i(Uyjk1@6BSwOe$rFfhS7-N9}?lgCeB`oCduKNAjEy+L-n)GBmz(D zyb^15z6H+k?ph-?V)ktp?K&sO9khPY;oy;eJ}j|^a@G0TsAP6#+R}ZvBGd>UrB*4K zVPb8ugQTcpdB@l8wSgHQrN_=aI5o7o=7m$_K3P%RkPYqn$%Pr|N%K>s{Nnv&tM1iB z?z;r($r;!De8Ls<1<%X=QjDPo?xK_HGoaa%@Xb!hItaRP!;ap>#BaX5rR7j6yyBS+=XS!hNAA@BE zEQz>=;zJvxlM}Q@As#RpP5-ht%ro!EL(s1N7LBI+Q>7_$Ii(-qs8%bXl{P#fBx71Y1r# z+>gq7M7OaRwoI*xu4Kbz(xHu7WV0gN=f-%`HOM+jsk%L%4&rz5)&uP;ze$n%9))P_ zLWmW63#^87N1VTI!(y<`+)hR*jD}4=Tb0K1>__zHgRS~ryNO8{eX76h_hWq040t%o zMDZrmb`}0$bc{d`(ha97DC`yOME%w2b-w&GY(DvZ(iDePm?6+1^8tD z7d5M-VTt&&PiD;JaZAsvTLbX>A`)Sw4j5B17m?)0l6++q6&*o7Cpp4o_^HP|cxnn> z(t+r?p;a^&MzNLDMM!)OHwd;^KA$*|T*-XySlKFH)a}yZ9`W&gI?80(B7kp=%jAgX z_`CbMdrGJK`ytx2N4O(Km?MfwAIh72eA@8U4Zd4+cZ+e47DW#+i4sW7Qf(*>RYngV zD&PL1z*ciXdPIV5vUn76gOM{MAz5c^Z#*bY6I7mb+*_RRnaGa)ZzTY4Oy zxOkJ&Q>N}&&nR!e?s~ko?scsU8?w^c{qUs1(JA`9%VNg7>lhgnVrQIIPHp}`+oD~j zZgH^Xllcf#B~Jw(&JB2=dWMUpM++yL`FqHO-0phZGiAN&$^(`gOprV6ZUUoaTivVY zH1Brr?`bD13R})(!Q_Z_z90{s+?{ozHPewQ6TvwT8I32gRw23gHlx)kG7X?m71TUq zahSy+s;hNlJ#no0(*m8@98Ql49mKt;bsg+^SdJx`A)k(}=k-pjl*-xj*nkZeBMd(ww>I;o0ZjnFDNA^hdVxp)k zzMa6y_%WP=Kcm4oa6GJ9kI?=>p@;J=+WZX@i86^s%F z=7F<%tDznYdU~*L&x~h3p|Tcd)O@slP2`o`jwB!7bofy&S*+MnWeyLOv%Bj)uoj}T zpD}QXnC&Ccm9e~2N-XMI6q=LM68KHymWZEfwh*cY4raBD;!3d=KwD>X!5sL0b_!xm zpo59gO&=Cu zA|ux{Zlv{alARINyO#Wp^JlEd+6^hhqI1Lz0CXg?_C@M_JF1cpEB!QX940(8H#v2% z*&PM;MrHGTWgd$znDTPFf^X1V78hEw0?S9uZkDAfy78V^w_l2V2Yvh56a0NkK=oHb)LWP@;yc)^ z0R6@raI<3KnjgNsHldLwMtD#Vv{i|1Jm$7LvY-mPr1tmq;_pqq98SMrlwWJ!QoN_F zyw9*FB!KK~zh(=){_u9TFah3?h1+d2f|Q)o+!~<*>RKYiy`Zn%A`&u*7;tb4@*`IJiN# z>5Nix4bb`|E*{W0cwnaZ+$5DRuR(9FFAutZV#{#4ATgn$RFM*Dip_1g!a8|{5EnCn z-NSPYN9VeB_~a_Yp=HDo<|VrdK$T~Y#ETh%Ya(FWp46J!gMTu=Buco6Pa7E`IOM>$ zZtu%rl5-opMkOq=6k^g!9C}4y^O7d;siIp#L>p(IL^3eYi)}hK9+Rz*HYkKvN18tT zdHi-5lGE0AWL-7sCp^XN^T>PR#x-Q8O*CzY9WG_4%4rFrppBJ*CJzIIAwOe9>QEVA z(`hBAPS+79^5I^X^x*1JT8dMd?sve|SG>|IP1kq&cGUNc#Vr%bGt0z%bC{|$+*Krd zAqq&p_=!D0(-$t_P2jQu$>Ua{N?#UF&e}EKOjftg#~P^ ztp1l^r@Zcfp@Q~}<#w2u_$XD2)oy1w=malhw%6jvxPVuAsfoTnz)1bOm^W6%!UMr< zIZ;_mllpKC!ip@&UQ9QbZ03Ui7O@tg8(Z?^o8rKQ_mKg>*84<_A#DB_Fbh?@_{BCLgNiw=T_44m!g zkC7`We{0IF$Tv*L_dY2bCzZ-(D${~1Z#`D*FBz>9j`^L2r;ewV<9#0UKkrS;t=D!M zfR`>9|DkPs?(k?0%!qlju% zw8eS{qR^0AxT4mOCS?F$m-qPeja<1Jc}uWD+S*5>sgLsU2<^U#qsPKWkj~+^5zV1) z)Ix$dCwe=VTo4ob#GPFRS|2?)!5a7dzDmPjSY(ZS_0wB*JYoov*e9|XwdY))aD}gH z5*km3QbABtld&6qBv!i*@5|SSQd5l`H#I-=H=Scxwd^IQ2Y^e~Tbcy709j0wusIuj}sj`s_BE}47M@0^)h=rkhy&SYegTRv(xvs8%0&UTUjnrAnYD1_W-l!gHX z2Z+||>(MTNy67hW7QQX%{p-prErWsD%LfpjB6||=xH_dD=WaZeA-05g>e}D)d{g9S z;OhUlgzEziV*@L(HfTsZtUppk_$faEo^nlr=~`1tC~pI&^GarBj7iMRW! zXqr(#R2~EQ_Xn7r(zIEK1)0$!Mt27g4TNogOGMXI~`4dWK4`A8ys{tADci9#eO%YHe5ZC=Oo|CJ&wer4ob&6z`sB-NGzS@3dJ&3zDsP^?OdTA8g#5mgjY$bx_A}!* zlj||^nQ>f)L{S4_H;glZKbI(92yrCjPRj%RbEsoocYX9{=H;YTJh=adDz+v<0cS9Q z>;1#48COa<2OnxO~>bEU7p5-zu;(WIz>BxU1QR>Rhd2rK?$<9H}M^Q)p86 z)Vyu}iQ)}@38*btea&eG((J=iwTIpNj~(}@qi(@p#Qm|4x#&g$zZcLki4#;r|?+Lh%2%u;kA$w)oC9^Q@pQal~Q2M-I05hA|m7TEj|WtO0u~Z-@hzd8`r@v~+d!bajMC zv;}CihiNA-4=HwFw+IWG`Te*Se;tr*KV5sH%^5S! z4869XB|p}UuMZqb&bO7p`GFM!uoseN%kCU@(1TYJU(I64dqv z2iG^qVS~sxMBCcruKBs-NNqm^F_K$CNfLgz-O5yb6F=%O-e;SSik}$YnCTP|(H0!+ zwDnebSL%&EU#KS`qUh`r%&Js6_A4qoZ=Z(DjC(g z63aI6BJ7>;rmf-6E#^Hk$Dx-faV8(Tc)eO9_p)CrfwU?8=`2I=GPhWK=f27Y>%b{l z*%ad0A{x!JajI)2dq(p%=wa{5S2*){n$WYm;jn4IRupPjfIp zZ$$uU#s7^N+q$p%jNUG0Mi}f;mJ}fX3j71&ML*ySwdx$fsX@<)a~MnqnOoRe%(T8^ zAlSkP4yBCUuY_GqD&eGJAb-_|Dr^^0Cm6#|@XRm63UuJ1weI_WYSH}%0(=4H%s=I) z6884fO!@ysfHVA~HK+XUfS`o-zkfRJ-LKoOz)yg=^U z(_~uN=ww<_%V0qV$st-{L&hB=8tvHJ9VN8tT_>6?*iLfeK_XLlczD);Ve!+}Bj;dU zNd^YI%^FvBM497Oqcml5M_u)^W<{%qm@1>m47VSn>4irbbmcIOHsSD#MX1fS;Tdez z1#+qY$SP?DK5xp%Q(&Hq=>a!q-pFFHc~k}_Caw}=r(13Lw!n5sUD>?g-ug^4rsVws zFe>ByqfEq}I?Jt-z5TYK{Gri~tV}~z_03N4~N}hcvdS`gl4n z6T3UAId~$LdQJoNjuycF;4m|<`k~SCw?L{@JGzSM4I|@}3akxXRU?d`yQC~=CyZCf z>9QnibjAy*7#Vrj}b`So2gTC^N zz0vS<$XH$|iYMeNq<_$?J%WE@Z)9z)YKm}lZd*!&N2){tmI&x##{3=`9=Wp8Aupvz)#?*3y%A!H}; zQ`jlO1JMt_WlH@+|ALEg4B=W#OApwHRSmU{33hQy-kE$WxT{3A?T&mekp7!Jag7Ra zG<+(hMnvJrw5u_c=?*Lt$D#YoOU2b{%DMZr+v;A&HuWWSY7<% z&LW}A1d8BFzp>h~qjY4!(5Uf%<5)c%qs|P6Le2-^S_xyYJFP!=T_S#-y=OXGep7N^ za8t8?I!Z_XRxUbcMlSGWVI!cjm85L13PJH;!}e<@4dS?gU#}dxF4ZIhpjMT5!kZ{@u;TFd7zvw{HiC z+XbO9Bd*-=heOJl{fV!L1c1^QHN_K9|P6wT@9pGTEa6w;?&iF2+1W=_5mC^?J) zXHnB(T>gbNG7*y-LgyYLSgKsAg3JUmV+onrlKv$28%DS8bVHQL%UqHOQL^gq8Fik!goH3v-p#3jYEKOW$LpB9S-my9_U?A&x#%JS24oieDKvSqLi4-xL z5GjRt{JmV0@?hs2R%Be6aE%E_B!1(;F8k^+Q!DPwADhBioe5lj$)HW}Q+A#*WAGc2waNJG>7O`jD zr5_hSrcZI^c=9hZ#Xx^A6GYUjD$#{RBWWtpR_`HD zmNaCl*r5iY2FoeZ1zPC8C_*lK)P}~PT9dv|26Iz_m8Z*jR?TT5GdCl8=I)G>cFEKE zdeS`YTL5i`=KK5GAe}(Ib6!=Y0qYzD?<;rsZ|R~=Y%i%iO3t%XPAF}bzrNKC)LH0T`srSphI#c zORhf@qxOw1zzYx_E3yjsY&E#ms_7hELBXZtWw}6Zs?TXDRII1NbsM`w?z`zH#759# z38(4`BXXaO*<8`DjPfp@PF80atZ&>%4O6pswd&iuV4NZK?-4O>gv8x&TM5BgYJFctWh}X(60kunyXcJ_#U^(Ad z6ko;lf&%AVPo9v5^?*>>S=Q5y8EK{u#j+YClwY=k+3ynQ;jjJ)9Sl)0UL{gkik z=Ro!bB|o?EJ*CaIJ!P?krfsDn!F8rx@$JAYZ8-+g)5uNh&b7EUr)ODX6Yg0KDtk!bX_fr0M7s8WHS52U0j#dzgP@Ur8eum_t zVF7$~#p_7cjDPnAujY}jFRn5duBh5nsjE545nmjC3Fn9$KzEC%VXYCO-^4)zW6N5Z zx2f1_a$DHV?k)8@hUYFHS$KOmn1Hd{^(zvGWpyN~hh^mO6o&i`%n8Hb(~-+Hic!Y( zMr6-D=Ra3ya1SvSzR#+Kde}&|CSWXM4DSb>GDzrZNP?5zhny69lWP23bV}1zqlCjN z7R|-~a3r1Z4A&0=f5vJT{udY5{Jj}(vV zzd$(E$k#yw zN59yRp^*>`ho$Q$eUI3{I}oNAYB93MPE@<1^omI>&%&z=b|#u;YGQ_z`wEYgm{rYu zso!3FTRW`VeUOc>Db2%g2;h-58YdzOmh1e0-C95McTT|S6&7c7lNHHc9T`eKxHalR zTFf)&nJjn=gY^M6?1bUmAF(qdR&46)UyNuvV(O^ue=fx2pU?kY0sq%-@V{21I38`5 zxq*#=wSb+Sft8(snT3I?c0T6v4iuXwG8Bb@*@`pf7UDiW;v#ky^6D1wk3Tv(77pSj zJ~%ro2I>Tbfj196G(RUg;ubJJ2~*^~GSX1d0D0FQ9N_Qg9zWyjeDioQ(9lv)aed)V z5P@-{fqwmSOFQE@>T2(2#tsDZ|J*lrIr{m#8yv6N&cn z`-3!?AU;$o!*z&)>v*%?#zmU23f*Pay6l;BxNi=Y2Z^@TK~R5M;t(IJC;v_`W{}uf(5WBG7-|p- zpz;(+Thb;iX1c%d&J~atgL?ZrBD*Kkc+vsN$AVdpRaub{f+|g4n_)Rfm<4&#Zc1IB zNrt%AsI|h3TVWO37>3Fc;rQP29HiQutqe$6MT>br&(UGrf~hW-q!xu^;l62{Rf>$$r3P)txL$F`sw6a`-6j?c~; zRf~2Urpm*oEy4)tZ@xSgizoUVsbyRCNLtM3ui=KHW#YR?zuy*cfb?Rx34XArun5P8 zrahn=bN(@>t1Z*|>*vw5b%sJ}7xl(5{l-`vI#JR$7}&u5)|gVN8Nifq_ZE0Hp1005 z>+dOh24SJySl=QSGxxu5X+z@?X=*`3w9$76j7J;jvtzqI@ZSh%#Af>NIdw_=rtgfk zJ7MF20W?8Ks*(O+m=MrJ?$sMHy9z}N`;7+k#SPi4%XL*#99kn5FYkK2`1TO+pfCH= z8s)2Vb42DnlsG3U9c$9R4Nu6pB?DJv=UP!51Dq`4j>&I@fA8g+ws=g0$ZV#&p2FFj z1x?<^;RNAX^GgQMr7x{y#n#apXZa+!1Y*>ic{ipY2J#s3eJEoZ(k(^tZ`CtU86z}| zKf>Ge>1ZyP@PzL(?oV?>B6+Nm?+uG}G!sb2)p86?VVM}PuyY=;q(c&$Dr`AXLwuUX zbi4k=0W|XWd1ARqZiQBA0c-wM{mTs6ng9ZGo3Cs97W|HU*kQy1GdX6NElZ@z{sVfh z9g_yv##U2!>!8KIV~|d$Yxoxb&I6MMZ~NF40}TUyyZi)4vA+bNmJH1!=f=-hcb^ zUoO2YWI3hCpE-f#pE&`df1?J)_@%_zM2#$eE{gw@fI)InG8?q8Ud8~qdSv6zB4&ON z>M=bbS+Jo1po+4;O2eP72$3ypEfbtfU)3_g+;>23@?rOVb#oJI45wdSCp{SMKKr*h z7HWbEK|fO>X+vnfQebYG23UgqsEiWUjZ2tR)*ySUCJFmRDQsq>NUP9@({Ec_ z;58u}hBT^Vk1XfcL)3|c4-&U|0E11hUC3!N>xwY+{c`c@Di+DKjD1qIsM;3B9jouA z=TNuJ3b7n3I(1WCwmHO_E!7I_bzWQ1xjL&o+_3;a1t^#3BBq@p4E*(W19HWV7EcM; zl1mLxt8tB9dq>A9A@dUz;~dTryT{z#LBl~$`ajBMiCt(R<%h`V!#>M>daOxL`-{VN zdW{4fm$E@o^B_&%lKviscXuOh=Uq3l=7Cnk?4M!y!7-9X%|U~r5rCn8v_@-}u6dL) zk*oR;F#RP9d*DKHID-4<2vCg^P-Oj6#_9YSA)xp-?^EB=#K!1@3n-S6N{bhKF)1q7 z@V<#p!Z1hsx>cOi+6|tIiSf196~puvN4(GX`@M~z9pW}g4b1bt=&k_}1(gEK6SIK^GRuKwT<&>=S?V6A z03(-sIKRmSr->+a3UaqP)nSW+!ZebZ(XqeP$)HA?!B}fIDuRV^(C&!8UNYl6d`HP) zm=d+6Mui!hT#Z{RorXnoFK!=9$Ejp& zBAEA!G|Lb>`$^Z3<|OGlTp$t5c*-;P&)0~mj$7jo_3axT>4U0T5!PO=oTba zav|3BM41dtUD-~ReWfKJ1ui>D%?jDfD81BxMJ70r01H(%{>1POuU(kBwRZBdZMv#b z&G*D7f~zKJt4XT4t+fx*uK!9qoHDrD*oiLdz^6V{?i$G)oiewWyf;Q&MUK%kdauwh zT?fndeoKR2W_*FNUV$!UgGZb*?qz9_UEyuaAjwR_H!w3d1JaStHM%S__(>hIutz5& z5PqBq_%P+|ei10{OiHn9X=x?ik#5!63lFNe7VTMh=I>}AZSNL@$r++Xb;%o$yH@QX zLd#_@fH5mDid9o~l87J`-)4o?vlj1lU~0u2c}bS03`K;6+cSoFrB?15Lw&oX;r zqa2k{O(?~4kXP*oGfF_tW7%(pTFor3`-W+>RPI4v(PLhnpc=Ejio;7CKGwy|;n?-t z6Gg6=3hxw7wsgv6>-K!QD=OTF_qt8cZZ)}s8wtYZoEs-=W#q8Ab;ub^OUi zzd&wk?yI4|dLoFPRetZ5UxxnDJ|IJ?-{j`0(VEr`yn6Bq)#K5c4{*erM-iN~ zS~uDyR$t#Rb&@*L0XSZ>4fmR842Ma)F7l07AOd*|TdeO9Zd`U8Ngz5OKZ;Lc^Vcv= zCnBqKLML>~>+i}G7R?Nka5su1qk<#xdcmO@T0T1!2rWsTs2NnWEi6GU967t zb7BRF@2d%$(2sy0`X9B6SFLpA6)%;!RrZA$4>#Vv#fhG260roNb<<3T_q`+Hi|hPD zf}9sNj#EYO7HFE^{>C7@?@l&MY4=Do(O zMDS^)qvUm;^2n#2VZMPOyVyEGH?lCbV}#_e1Fl(t*jy$g56f>JOS03!$`h!-(^ahb ze2)HN78KzvB(O!3AXTOH93Ni^>%|!)L|x&{c|!mPAE;^(ft2&W*8-@c5LH{cQ{j80 zmVFk_Z{X=&MW}WIJgBUtM^7K$m1_%Jk?@66I2T7M$DWzb74=)bIU^a>TNA4nlhSlG zguA$C&p{QERzFVdevDbzpEdF~-(z%M5-(G>xIPi|xEZgFw%8E!6%6YG9Cc-^&13HQ zqBYbtjegq}X77TP?6niyOvJ4Py;Se#jg#nqU63i|0vo^j5$=~i9r1tXCL(C0?_?rr zW5Q_8XKQO@ZTR1!aio%!0)h&nw>5m-s522dtYAqYx+Of}EOR3bZW!K5105+Yvc|eK zbFyKoQSz!K4CtNC;j&|-#j!LpMDHi10-wT`u|DmxdcYBkLn$Di`cvX(*yM_=eNqXy(DxZQ{Z z^ec9VXR?5vg`P>sy3;6I)p%zCb0+okus46*l4B+g(9F*)zV5BbhQ6*5uu*!mx_bcX zKxY+P|7%Y>WZEizM;uj@6MiPONtW!6_Y-Q-+$SadZ#9U^t(=VR(h~NqxcR2@Lal&n z*CGRn@pH&pw*IpMWi6+*s@`PDUi$_f8n#`9-mqY$161N~2>;!=TCv4g;c(A+7JIE> zrJAB$xFx2J@ZmkDzj~qO3Gqy0kLCqC7El?p?@sjOYWNu^rntBOC+PToi_-ScMO zjnr40S}E@POJxvj2$Rsw=IzSgn0KLo9-x(~dOP1YwK1ek{EZ(yWxr+r2yfH3E;Jl8 zwr7J~bTz|#igu4>hx-lAZHhdjQUhutBRjfO$S5puZP{*cq5DWg9PIyM{`|sjDcVol z+8Wh+lyDh)Nm5o$Qb7ftOsdeg!8~mjm@knP|KOL*Pb(K80&by`UI?$-&;qv|tFC$s$;d&xnmPcz_#y z0;c;8t$`TXCAOZ$iPDXIjAf@BxFY9{5xo~x_`qu&kI_mgm~UCyT`5pHnZt@w_>EZ& zDjb5k5q%Nz>|q%v?~=YkDLWz5Mi-~<20-}5kMH&bdd#ei ze~T#>hl&3Re+GeeEEWN4q&%R~BcQId%BRE`I`j?n&vFkBxs7Wc?$<8`l3%~@|Bc-H zZ}-MO%D3tet_g>U-ZJ!~lEgl^V0bBjqrRZ6B$|K+NolaScz~iYpswkJK5=02sjLis zy62TE$mc*bq<_j)m#LT5$p2#S+cmClnp?E5U#)F6{`_3KT)Jx7yjt2^vR>@kX8HbL z5Hrr;}Zdf8g>?dlR#5!1*RktuGC7KaqNv9dN zpM*v~Pt_V%ymU+67O}Jb>F0#RRPoB(JvMZcyInu`?8sBE= zI7;laT|qrbZ6-I~+)|)axgma6C>3exFy`FXvo5{5o8Zi+ZBbJ_4XMS%Xb9{+Av-TB zsLKfQ$GBwn8Y*P6MtA6d$bSR7-lCGS8!iY@R5LkC>_;6K{k zog=k&A_nQW-A+C2+ZyN3z;EUp_;@-wHjzE69ttiw{Shnk{czdc&dIA-V8N`Jr9(-S z2on!7^nZn^Pn3_SFQB2RALR0V^iZrq0Rv*cf-n#v?Q=%L&KDkJjg^Occ?-59UfRff zD(Q7QaXTwKQDT{aJtWC39)TvBc6+HA8WdJ@dVtzHzqGbuWI8nhqC~r+d5;?51uBPR zEeuK`^>X-KG6?OZ1(IL}v=m%=HzA7I((eNGjY&|O>Uj`3b8yM_gMWPF3D5LVvNaN! zg#&3i^y2nSX#jMMS0W^_T@o(k1Px7P}i%Z>(bI_nY-a!rR;*dt4N4)t4gH(p8 zW-;(lkh&`^d~@?uib2|ei9u4C$Xf1T`cg2R*1ih;`w0K2GY%lz=l)n^!zFz3x#wZ@ zj~1Fg9TTRmtmgnU3}f8FFKhwx$;~NEPO5iA2RcGMgHxwAmFTrJFDr&naIK63oq99G z@E0N{HZ`*aRUMU7sr|MYXx?71TR3@qZ|~TAk8_yK@Yjz=Ym0oRUy!3UOm;+XK^R^*L;!}?55*);YeU0l zdc$QqL>F)##|9uUcYZopO|vZ^Va24gtxuy&p+AjIiWPF?i*)9Ty!1~?QMxTN9?@=9 zmc8F4Pgkg7IB;+E3uLr)BWUy}Sw^7u@WdmwuOCJLb7zDv-Y^YSQF~YF&=*avNthP5 z?}FNpVlEJo6mY+-@dLSy@w3?j1E{7*`}#w3`{9ui7EdB3@K&&`OMmG&=8N}EYZ$5n z?AA+?0WZtIhy6=tGgN`qDIPGhPfG7^NoGGVcJJ{jgWI2e@9yGr-GL1cEQ5ji94FmaHCvx;WLzFvHcd`yeQ#tN8$Nlya#crG#cuPt{vhaorF zcp*1&crM_lUj?3Fn5LSXP-ad}(rlI^T6d=@gY3(eH*@-}8dq}0+ZH2U_5(5Rhra=I zmNhIOJproGS|SVfk%Mmd+(Hczy8T#gw0=Xfg+-&?(VC_tps|*3Vf&p~k3((vMME5E zlj=ix!q}kOOJ-(9ljF52Xv~!OCJ+ud6EXVJ-qcVSVc6D9m?!=&lVM;FgU;Ir4kyKiVy(5Z25FGE7KbO%`;m^wMoQ!j%E%cex_qE(YJ6;4M&PM!v?i{YgWqmFwlb`+};rDew_?F{`dl)ZCsWnr}K+hNB}I<{@wwr$%^$KJ7R z+wR!5ZQIGqx#zum>Yl1ow_ep=Rjc-&tM**;+jEZb8)h0;K01LkYH)9!sX}IOBGFMC z8C~icin_`ca^hfBy??Jdwc|@SYIO~%mT|J1rDS0c;Ol$1!R@VkQ$0r!-_*!O>jIKm< z%sgZSn&Km=Mq7J~W!t#UL2}k_V{MJGmX0R(%`+g?>4tM*YH;GUuI{fQHzZ&Pd^zT4 ztp_j1#eSS-VYu9*56hYE5_=)NwRB$X%7@Lly@5|w@u~*Yew|n;$S&yN%lf{TNo0@J zFO6DoyzwlSbdN0}S_3Gv79wTdRpoqX>DG=-PIV{7oB~Y?`Bsd&UM}tI4U0TkE>dHF zEQWmOd`u zHjB<64zU$`06UChhJl06a(6Zu*VIBIrR(Pt8m@b6ubazo*n1R5F#HKQC~p1 zx|SpM;wuv={(kDK$$>47h_3G!yQzvyZtj=^T*G`Ws{-z`4Uf>^`D`FBil#mrVa#$x zT)2+?9wuW47TAgqZ}qVE20xbFfTep|1r`mxg(98WlS5;U8hHsX|IQi#?(gVNA?oLP74x zEy1sDDDYZZT_`oIDQjAzD3G0n?${!O3TP6l8yxrMB9H)C=i#D1 zdkQ#il5Y-DZ!(G1f+d<#bTuP6Y8K&qF>{+{yJhIZA0Hl_%6E3y(D4*qDU#O(8e*|h za~0zE20SHTT9S+Nki6lleshX`D~dhZ6*Wp{!wwoKz2s=w{IVnkKlAY%)oey|)l9vE z($dTzLqwB+uhGH-Z6vnH^oY`Z#t+D`TXYt_(OgeTphZWlMaOCm!#vLkL6?7mP0|JB z(fOL0=_!L{WgIf{a>xtE5N8p~k=GTr(wR-gytqX5(nzsUs4kv($lPUsRA-OodbU5LaNfUaTc;}kQ=$nb- z1IVhcXRd{B0I4%L=>_rZ*2wwBht0Qd@1C_{S8mnkBMRjsQ{~`~@l#5A=3}CwY;jJJ z9TWMbtv8U~0;0zp=|!PPs;4L5eC}cXo)Z%#+>CZF169fAp6cx=E3q4+$(zaawHRQT zXa}&|-r!qgqblfL<=te1E_n;_Elc}HxlXbDUchy@Ec}Kw_d=U>r^R{b<~-)*JofH9 z_Pg|t0jD?oWjugq?;mWuzt3J@t+9ddhP!waXi4I_Y}>r+m_kNb0h-bo#Zh8Gvy$$= z94%Rotn0Ip%To8?X#TIHeRUsf4OEPM^#+pLf$He&6)JOduX>k~y4+|L=48Nt5Gv!ojX=g`#pxVn+ejSuM7&06oFR1_Fm;lkbsS;iD7JM9lFgZ8 z!1~lXJ9K%VTWDeECR41&;Mz zcc?y$@M(&Y+PHg~u?T;`sBsi@z%&D){@uH>HT9nrADP28+|`uV0{5p?X2p+}86zf9 zi&iJ*$x|Y&m2tRoxolMng|LAIAq~U8S4U5!O2~Q$Lpnx?;PgOu0IZ1L;K@4%W8KC70 zz?J!MZ>J3@_GpQ_T1=8r!EZAOVQ9%SsdKJYbdv#8!ur{839-CTSeYSQc+hl)4^ zEhHJlXnj!Y;&h*@X#|vpd}hWYiuNG#%ANN_c$ITLW*BbDvCZilk>V2*B|N?s9I3f_ z?zsQl4XjqbfRvDrgRPr%psH%7pq#b471X1`^oHbPi^AvSNCMYMnh+%YnGO1Ol#lBO z>6K!heMH=_Tr3l^xm5*kj7bTo7)4qXQk~ zdFH^&gZ1jT&HeB3u0Z36P^&J0kT_;17rUS4j{GVSnVp)d)0M$FogEbymIHBE?hBEIscat@ zrKOm|B&e&M!4G&LrebTWl&h(&ng+n&Oqt;1UaTrhF(uaM5Q#IZ z)$R^Ux}#Rw{*wxx-7wD&#E013Z;PoeBBbn~+U*Cj-NXl(Pp~523m^4iWrV1D3tSz^ z0hnH{IL6AKW*f?!Fr(uFd{iHV>Z8D66le`0=hyW1?J0f}_boyRWc*0s6M#IrAGzn; zm=Lhd;%@7=3g(p4NjQ{ZD(kDp3pcJCg3+?F{Bm)SKOrZB{pxfaLX)S#*?eGZzc?1* zwF*vrQJL<&NcFF9h1mGkI2Zw23=dgid>l8?yO^{WjoX-~oeB>c6cR|jA?lK`<7JLu zyOn*0m8NPTci&Bg)@y$;jUj%hy2v z=Sb*zbD(wh$3(0R|LYgS|1c8z-zH)uX9FWEH3?xMIT;yZhX0%pWvTtAj9WItIAJnb zkYEScG8ou`t7!1IWjQ%YtiFf171hfI>9VU-I~HrkT6t~&op%5os0f&{cP@hM5PU<>Cf)#?2gaJ9J?Mdl5~6NL6ugbAWdtf zS%2BrRwa>NI#BH<$FyMUCVpb*Zu_{et!lkKlmV@JytwlEQH+Y$pmIckN?`@~%^02J>Y1#-obzXT$+lI_=g z2q(tD#@bEGJ+hK;5CFUB&4c{{Vn3F4R0+tR=b0kj+N@p4d1=qil_3FJ)6#&}Ari5{ zik`-+=14?Df)O;e%Y2>aey@VD9P7ZgUj2%{ucgP@3A!jwEKHg(FG`;@oLJimv*Yp9 zo);uO{#iGHN2s0LZ#AJpydI@o9*Qbp9-WNnVAL5F0=LXiwY7w!*qH>GaVzh%t45ZP zNnk^b&WZ(+|I6}Lo0ra_-sUXqA~&DT&C>im4u~3duXN>MFA3yJ#U5p%i%cXn~)G8ccoqfSh1VrkQRqT zd9T?r@Oy%TyXzet!A%sY10|lI=TY^WD0llAK$UGP$w`8;$X?q(&3uJSyE0 zR4|H$wR}Y<5~CF9YWt`&P0iMJKlZFS?ne!rbped(`O0)7jha}EnzW^0$G9=&RjSma zqS>c#<>*Or)@U;OCh31IN-$1Iiv^E=X!7FXL9{vFqb5k#5ziG3`PFTQ3S!~CSCE8k zx5QJCY0`x04YaBaG`Xo1DIGM})%SwwNwU=G1VXCE^;-jk97quzQ4kCT*IutcJEQ?u^ax$3FN%xbo!cA1raT$E3nx*M`1@AXUb%$Xc6 zh#fi8Ud=2W?^|R6(+4}eRkNk>yFx;{tr6YQ{Llq{t%>)Os*8G8u+@o#`hqWoH4}i1 zHj{Tq_d+c_Hv4sFG%W(s!m=6?Axa(k0c@L2^?NAp?!sEh-|k-&d@lT>T*8 zEk;jCQ*gr){qLIyn4#y2FBF-hAf5@_2xyZpKwf$_$u1WO&Zx#Z7?Mvg672CWF1Em; z0jTWPyI3`o(DV2oxoSXgcmKqtr#WcDR6c1j>#2awCwK!@oR%>houUhe1N^wzCatq88Nz|Bgy$AA=3bzN- z6_9h{@gYdJ%hvok)y%i*nhkezJS8yKN^>er6ea6h{crK3B{H(AHKYikPq(tyMSWDb zrq5S91}pdG{+F$A)L|_IUM?z|N6>e0#_BLx_;jRTvu$rxwmF(UON^>}6^r@)XN}2k zyqK!}ZO@J51iY*rbpzbjHq-1Yyg?HWZY-WH?-G+1)n_r_f*B)8+=Zb|#{kb8?DAB{ zK_&623`p~dahk%=DT5~5`2B26Wt~s3`@&r=WxJS{DZ?)aH0PWk+*_QXOe7E*MZNmz zy)hc*0@FNiovF4Z?YxSD)_MiCyL>D@4xO-@qpc7@F~mGK`V>GOfX$1hD~9#$m(?jz z@q>|di5&ik(!)H(Mc#C64DYbj0~p+_1$GHt+FZ>Is!z1tDa^cQGk@03JsG5uL#D*) z4&o3#0I`<_lGCG#oz;`cnTV@MI9-u9|U2;>x%IvD`r)a?@&1l?NU<=Ns)daO`jn&qQJH(TLA`!n*k%_ zemMb~sFl9U?g^(ZWZ2_ReWgKFo_&q#{F$49jyv zEs-WnvBY{(#%oL)Gm`GH$AWICcyM5s7sMJ47~>lds3n%f(h8{p-Xqc2(1aRzf;Hd8 zZr+U;{}7tY_PVZC;=AZNU^1AH(9gOgY{C0RqS6=U-Aa z2es_^Zz9@S3bt${;$OegRet@V`~P!*`p;j-px6Jx>ff|IPaSlnb@HQ&>q8J2OyjyT z$gAUgkG1sjj!X z9`hY{v)OG)lOlce{OG6{o;Tf6oTh!Jx}IdE?~rQ%0e31gFbn z$q(mI0Ig~#Oj2d!N*)|MRHdaT_UB0r%DRUKi{9;HW~JW6V|512W5=c5)nmtHAM8nZ za-S@eIW>1+lzak*&=ybOlzidYKl6+Nv#v2LbA2Mz$Wr#Sh(XHdQt$ADoW2ZYRXL)R z^2)gE$%XCwdT>vT;(Cz>ZWWWJ2kWAInZrxj?#!CplqBU!LfvZBS4=X!aXF%p?CKjk zj^62Mdq=wK+$&kklY;adOC2b^>mdB)6B7_rpx~U-Al&r&xZhNzkpDeD?Y##1F$UGa9n4;0rJZ-P(7=VZgJpWGmu=bG|C(0H|r?A9muW;t{a2b zxgKtc4nJFE)mK@?4m?D7HwtTHo@<2{TVOXj1sA-T9n#pv^(<#UhtD6K)VO} zH+=GfTf+u2@O~Hbm-G-IT*BDhi8Zr=b z@DJ<&Zf-9`m&A&S@%ANbt$kRKGaa+$kv0&y2wCT!3~l8lKqQ)qmKyamXaXWbEQ{*u zHB9IjcSFD#A1=52Gc6<6(St;VkgdFsI06_pHecwpT>8`$*7$4G8IY^Rwaa3XfP00> zd!ny~J^wJhYda`sVFV*Ts$UBz`vISIt^ZsA^F#jXSJYC5t1T+?sBCAk+i-g|+ zf|z3XccQ~kjnt5SiPLyO8IoB5p-%$CJb-Cn4-vq7lnMjCf`u5_Y%cY-$U&;4ClpQC zI+VnVdy_|?kQBEbPSyL%oEm8>;^G=AC~D|7hy+rJO%S<3GY1|_;6esx=Hl|{Jo>F; zKw8h%_)L7YKX+v2FAdt01~`7fkciSz(<_lF9b~WS9znZPVSS79X&`!(OjeRTZ3yKa zc4AMJ)>%yhGAcQWRymauK4qKi_zTgvSM2)>jI+(+ZsS`Q??EgV0uIW{%A;PxU1?(Y zcwfe6TyktRjLRhztO&k{L97+y>_QB8gGCt|%JrRV{F#`1oKlK58szf}5yOC!v%uLX&Hg z*d99fOy9j!vN~iHbZDS2-KvhjS_hB*46m}<;A^(OEE&&dsvOcXeOcH*R2xij5{v~Q)WYed zunpi0Q4tnXCzTS`fY&2Wxer|Gl+g)@;PVq&()K+)JetN>X#mb6jCyoo^1 zzT)auEQR{kow0nZ6}QK4e+Suy;B`c3x8=1fZVEQUk1b#*YGO_f$8yBkW;1@SNebl) z#$GVoy!A$MLzUBMhM53`P5V{ zX&DTvkbZ;;77X-)*Motm^wdn?$}r)UeBvDwVl*MFiBO8a?S`lk%^mR!Vhq8M1_>^T zY?gD6s9i-56ZUOUh?v(X(y3_4Ly*^=fO8%xi(@UMyy+|XQbg}Ue?71Qr(YG!%T%o2 zy`tSOmP=~zU=We>Xb-HwFWZNF<3RLL!`&(S8S}odOmhLGDNC5aj<}{|9@r*)0#V;+I$3Zla}{S+U$vAs?O@kzJ-Sy`AP1<%28bzg{)zWM`$xqi~ z3hO}4#ZXYyjX_l6!V7X8`&h_<4ebo}fhcq!r0gZAzs05vyvqNj$%*QWWa>k@rbuQf zGa^^bIEecPt36S!*~XnKXL|1jn?&l2$HwYhJRhLX-so#Oth$Mq4>JO}!ge}t;)0nJ z0NS7Y{1Tr{XYhrZ$^jRR?1+^rbSfrS$$Buqsuw$e?4!1UCwV&sMiSV{5MH)h4!mnA z7ul9atS0hTgdI?>WDHj(L}^8Yc)gVDUP%Vv@_~WgM7c!pN5kYKVZwkNpCd&nvR`UH zzkeZrkn}3ot8i+i=WwULT7*}L8v)%{Wy!q{X_~VmA}+ZSS!;R1-&W^w1@mr%1!y8# z&mcA;LtJDg$68mZkXMNoEQ*K$RFzB!L4|)D+i< z_vb(c?N=8p<9c{YH_JgK?TZ~S_j1#*sXnpNiNVvTHA#b%$r&%=L}5!DDC*G6(szef z7-X_}eK-U0aDqQ6#8$rf*uuQWoheP_{crP~N1$hdG?XV~<9P$cYq-$nq<(WK$?<1O zARyBgBiVlV7m&;1r5+zlIo@9$xG$>a+K^Umv~x}n6hZ^vgS z7|rE0ug(DBJrHXF|0bmW4*n+S8bDL@js6betLgoTtB$ff1vez&J!-+v%&8^`?_{YV zLD|rZg0yw`*V;h|=Z0$a0ro{`sEtiRiYB(t^Trbk{w)x-LO&EYFA;0LUdP|!(q$NU zJ6N_y4i{`Rs53wYZiM;JZ>y~i&W8*X4I4@~<3P%f9=hk7)2BE0A{SRiodS;HJ(<@u zB-;BO`)UnisYbdfnAc2FDk-LCglx~4A+C&;4vKQV6A7Xq0cLTp8Xaw>Z8XSSKLV<| zn8vfM;V?5oKgJry!`ZUt_;;HaqISsrxV%SAKHDA2mgP zp|gcA(sDbB*qfHMm0fPET9A;LGjmxUw)_V|&1No!k%cvlxd*?hW!>?rx{iXG7?S_Y z3h5v5ON&6!#Ufn^8piPv3#MOmPxUR^3mx+psbuDNd{6KX?4S3nAQE}_Vh~1jlI}@# zY4}u{Kr?ftm*PVW(=Vf^z<^S-q)yb8+u>*#)9N3l*1(a)1#$TzB75l$l-{nTPB`|rMFHVhWNjsG_xyZm5-_NX=OJ( z<{w61;X~hJ-^I5*$WS>*RNlsG$O+wp$S`j|XN)HBZ5bk!7cW7oZdcqae5xxi_j>JN#meuLpB$I-6mP2Bpx_X-&H$XGHLQ=xM({^YgYNX2t zl|zJ*W)f;4V|JE@VavcEmk+7dDn@S(*)Ff(9Qa_*4p0DbDl=#!w;2Wv;hM?iioLGc z5C=*Kt#A?c2T36ly~cq$lyRvo)H#2pdOUkB&}HRF_)&|7bITk=&ZeUiZJ>K1k)~UW zvsv6s8SeAP?q#4?gaa@5GRUIjo0xGDEUg$->LKq-j9wXeF*pCLTf+$zD#Ia__5aQc z5FfCtPviC>WT~g-$}O$jTNCIg{rnMD?pDucMX|adc~Xl0%)2Kpz4OT8l1~7d(FLB(S%!e8`M{CU-JwnfLY@amy#Cljz8wv5-5Kj1@IcHM`#pAse7a;?xHqI%+(ppBw7rxeS71Nug?>;sG$nA?=3RX zwgW~x`A)-X?4W9fYftC-=tg9I|D}4HjxdszDNy;->>Emj=#m~G0Qe+ww}m+>9Nf0j{VLNxD^*SLUxlE0I_f zv|_AQOteTkJV_{!vbWbFY7g(V>#+dYyH8t&!gy^H%6HLq4_l~yw508> zL>L!2iQoN&3pN&i0A4*D0)ZR*pFLgwCggP2PtVClDu}gsL*Dsl^c{-sFsV#^au^Hy z85&&%$Q(v!B}Y&$N!~QBQ{xXjoEg>T;29x*DOd2&BGw*gJ%bJC6qh8T#&-GCk5FKXa$?(uikhdq|5FlS7{` zlRJ~7v0Evbk5kB9_3-AyxsHXq3Yx8pPwBU;UkTt4GbRl+hE8I`XC3knNwD92^`c$f z*kKSqHyC1)+#WQuG<#ZREYVn5*yxGTGja*P?oOlzQEUE*8)qazB2jBG&Sj5ZNP+7PxNgUTtfk}c8o6@qdJFDZ}UX4PwcfM1u6Gu@BlZ^%e zBW~_28lj1Wh0re(DSyyniV|>oKfc!N853F>ZhF*EDAVshzWxWtEUMt2m3K_hyo|Tb z#kQgIA7e>eX<;Yij(HdJkaN#`=ifO9M)MPIYbL4``PZ2BC{k+t44n{kK%qH()B2$7 zr>T+Mw?!b#uimh_Dbs8_f9_t3y#c{`eOmu^)aoy7y#0pnzO2weuKVmJp11ejuc@zl zhM%9QudnyteJGt$Ix8o?7Zv!+=HNg!R73|o84i( zkbm)p(%pPYRf6&B!{&BY!Z$MBLL4MM_SY`@(0?Ezs80@_g^B&ku3W=S)bELp8tJPC zvzCX2O9d*>M?>kwCJ!{ZfzRFS0fqfev^H_>HmBC2;9CYqpk3xg)=svzY>-AhTKG;? zs)#Oos@MHlV|f&r)a&F-u;W-r;)~ssfoKFYu=DDOKb3-MfVBjqS6l&SwCcw|&Qgdu z<7di3vgqX)DQ;R2x7gF{~Z|cI=sz7a|1J*?kKo5XdBS7n-?}m?nGf=vfiJgZ> zR_!2t>May9VMV$XqUWR-yv^13;5BpvO6(H}dmoesN%`Eo+1u3nkLCBn_1Q3f za(|fX&?$n7VTM)tk_P0Wp!K*brnq#nI5!LjmpDXdVoBbM^7Z{f4U!2mMEWo(d6 zCj9Z_O2ID*rb^zW(F!))A^?5z%zQZ1d6! zVxiiEqFx8ijU*{qllcdd*VQmM%-@l%rYX;T*qSz1yvv=!pRGRC`^b;!KGmEr9xL(S8edLy=6M#``&R;kqN-s~CP3lVJt_j49*NZu zR67dsS~<$2;wMK~LBa>349kTe1nHY~C|*i_PR)qDHJhOowrSVaG_;Ev8ZIBi4-MxQ z`Xq=?@cEr$ULCEyRht!ChBZY-pGcj%m@6*Y5Z4*phB_w;(4}Jyb1tfMVX$Ac zL?gV<1M#i_NhKng9sI72ff>(VIVFT%bW%~jBh6_mLL>w$m5Li#OL;-kP%S#)yja7i zyzTm{J88k?6kA>`fzy@=XTq7a-&s+b6K-lw8=0!571cJK*Nh3ag)wrn`5yv?figUB z;0YnRQ^+r)B?bKnlY1C8r9gxOzZgm?K^n>90buA%YGm1DxM647XZ=rh*G{0>0m(w4 zig(V+_?a2Ih1yq;ouAhmn;}-4c2Q+%J^WG;UH!tI52_R5Abyr5v^<9Jm?K$ju*G;* z7|oj_bQKII5zSehioRJz=n%2?F|jdH+n}Z~7|(gMS>WuJIrpDD_Y)6BE$iq^_2*g= zaNQP6>(c%ix|t$(9h|*i&R6_qU-T~YM;c$sivM#2_-eWIHm`qj<_UT2~jz^6+ zQChJmx2#T}A$mENW7z_CtOTlq%>l!EA=R%crDE_V5Eu=lYp2Y9^BG@KY=E~zCsZ`= zDjlyzL&SaUpIK`*{h8VT0@Ua0uC&(R1&m}}9WgFfj_E=mBA0aysfN_-CfQ~z`iu!j zbV12JaURsO#r5eK9{55_uGZwHcfm5Pc96D6GOX3$F9*$GQ8|$4q}%NAaRnw<3Rlf( z)!Pp;lJ6jAI zq^dTzzgj4dugJtk#=J-hyChWIrST+9UjUoIE^Ramoe+Q?|m?cPrr3*h@G--205NfHZU6$kfyr|x$s?yil{$~RVP1MyR%09eH}zad1tNSbZO$@ zy0Bm6WA7@H%ymw0eG=+KPs8rk#8m;`z4`n2vG0{dGFzt&=WJ7wPWy&fTfLxtQEZnG zoGUlo@(+_cQu8AF20*u!*zL_`=PJ~u!inMhT{e3Dvd|)>J&Q%sBRlIXWfkoT*h^-K z6>HsvShw}}Y)%-bFO#+{y&dcr)(fTltL4a{Rqvo&pu>lA>d3MHDj$fc10MAekol2W zA7wWpr#pgRCsy+fg7!qeJ=nE>g$H)^amJ3QFVM!sbg&k}kj@9;=uHEIxNg)FhN$0e z5CTd=L+#N&Vgp+6P4cx-L-irUm16yWJPCss7S}W*E0fmHOQd}q)>IKA0E&^t3+u|& zLRu2g)`YD7sU*(!1Rt!Xq=G{`v*X?hi?4TYSAld0I^#bWPxaW#q?@$DV4eAu9|o;R zermhd9WNc2e%t4P*Vi&ESiU4HKh~~LCG&jc5n9vrIp&jipxu40wEkfhi`_swv9500 z*c%6nbR+!>MpqBbaa45jIjw4Gt2Rm-n3DA)X78TiZo8fJX!clw4x5+?7S9JBF$>!&pxdbJ6ayP4#xpa^cS?7fVNqq6Etx4?jX z6`x#3(d-DL``Xi}wy|oW8j{=Wa82kBT$Eeek)vnAEw9|a*CG|Ic#^Lm^jX(|tKNJI zccC+!xFJgJHH8(Zk8LOsE3SnC!N93g)%}>44;j*$|M6L25zmWl!b4Br9H>rNvke@) z0IxJDn(-?rV|My=Ae}6%Ny_%Y5Lr#{q>x-qrM}&3%lJ1dh^CR9PFgDI1sSczVsaRX z*xr>XoC@p;ew7A%gJeaJz=S`07+z~ZU;imhU0_<(j=ODJY#;wqje(BoS z4MW{K1lWGBAz=cm>a`u@CeYMdw+Do&OJ`>Vo=qPb%&{f5hZ^x>WsmI#BD>ea zAMJsh{-R|M?zg^xDLic~M8+B0L4w6udpMkO-y&sW$LXjq`lI38z^Eu0ru zfH6a#x#Rcx0?N^a>9b~P1D1v--nxgQYWx>wV zJzYmJ&vtf2Hq&&s3`hO>$b0HVYS369^_Lg(?K6E?XAIB*2=Nm^5xl-*lKqnFsSiEPPok8opILkV2m0*GK)x=V z6GLcOGu)^effand=c;0BLk^EI^^%!!VAH4lAMnSHl&AiwMO2@gf+I&F@|a3$InYDh zm8SC%v5tQ#M(3fM6&3}T7lB^z2DVPyyr4Y5h~>hYjfG(!*I^eW^Z|ZwMz4S5hrYwp z#?<5|zk#4%dWaDl5dAHsZP^+^NjREFIhrmIVRB)1v8O#X@cMB4;f{Zi?n!uUMDO`U zJ(h%jJ3Ix+=6*6uZqFoeORQX#)pcBk_U<<0bwXOhx7(~VrzoNlEshY>Yd<5)ERfD4 z53aE2XXm3+mz8K*W-}hKlIM?xGsXV)G{AnmNI1rWkS%I~_T24F>Hu(`sWRMlqXH79 z$@KlAg(h5%I5y#=i=Z~(D$6{kblp!R+|glMY%-9YGM>jGpf&-#?!pr;2Z&&9cXAs~ z++wJcopN^-l8*e}R4H2uerpe836~x0b22l}OU4}yh|gX{M(s1HZb(ZFkI%in*2G_u zw{C=A$>%+ZU-)0NecRD59e94z#l7rTf3uO}Hh^;mZ+utJmSRVUI>7V}qt!Fpo{hDTp9R$HWe zVww0Q*AbtcBG%9RiFA2LQbunYIVMUP#3*) zyP%C`a1jVQNUZ1-DC7u~(ui=SXsh;}Gr6({{0Zpb6$ADs2yOP+_PvLO#M&gHy)K0C zwy3YQT2Uds-n=9mH=X1`%Y*LjS||)E(x$71m{=r|?!n~yWD$nC)DPbNTq7K+S8Vfh?gWg}c?Ec^C)Cbey2`}sU$vsqOuO<2ZegtTcCF<0U z14s-4%;BT?8p`2l3__U^O{~-@&^_uDtYM3L+;ytjmls-HlVau zImKttld>GVS}Aw`F7u%L!7v~X$~Gx?N}7{!+uF!j5;d$^saO__2kILRpKOS5E{Tjx zjxzlq*p|9|3#<(JjuM4SC?v{f>9@-O{(KP_(g+(gP|`FAX+u6H*}tT9DTh_yCGdpv z5I#v=rU;l~0tk6Z2e#JQ26!Lt|FW&M^SY_LTT?q4+|G)=DXuY@$8@vFRMhps~ZCsawrFGu?>L$r!hDHnEzE^zCU zQP%vD82F$~N2Uknb0f^UJ$yqd{k;BCbTR!)^yT@NxHV}lNmsc4%$h#OHEb;z^?7u% zPI3EHXIm26ybZVV@7tDt{Cf4)g66vJd0vxO-%s4?)rbNc#OJE|=;&9Urg2Y#&jfFra1av8eUFn35Z560ns`=M=F|7f&1|8Mf5{{jpO7#W#3ISCjW*gOA!;E$|C9i@4B zgph3|;9zEND&IQ=L~49t6hyFIO&99^5eT?H8%3uWnBobtjuAIG&Z2hCH+^_JF^(HD zQZzQhaJt5FQ>N1m?^ml&%hz~(v;H21E)RQoa3C>AC;dnn!`8{G+y)JOM-&-m)~c(O zgSXs(M|M`w_9g6Tg>zt>vNRqbn*HM<{_o`dQMW@wS#Z3{OsVWVn(gKd9x8ixJr~RJ zogmQi8hlmZ#~qBlw&)L?fb$i>}{#_W|)5GElLWEN~i(&!Z9?d>VJlo zM~(=bJp3hY#??}4p)-*a(N}|sV*INO6M=*BV4;kGjVrUt1yt4)XJX!$j?*`=7TO?68W$Mj34U1N9THZwr(FabqyiM{@#4 z(}$w|oED#zwpW~Q>I8A(auX*2zE2^9gb{-nW@}h);+Ttnz&Z!pWc&+SRTy!Be<`gA zR+ZJTP0&5}LuoSZAUq}x8O2QcrQNH-Ki`Vg_-6wl!gK_w3cFz1SLgx;2RH{y{N9DQ zOR!JIllg8VKlDwL#=J~ZKB)-O+d`kFMIW*|aVbdFUk)}XIvKQmwmds2GKki{Cu`OM zY%BlwDrmMJs*ghDaDm6(by()$u9$LZOp;r(Ej)H!x^Xa-WIR~g3OCl3XuAI7w3RMjxrV4Q$Eynl|-4kZm*D6`Jb&Aw2c$5kT=;L=Mb%|F z@wuCcc#PEG8IPp)LfvY^L|)B0qeCiLw@e(|iKdN?L(AL5XkIcqNC?|YN}C#2$&i_4 zD;uqjY#n?XrPxRfWy35Cssvwqo)*!r??$=KxubBgt6q=|Mz@T(Aq}QKV}Zk>MS`wY zMurpW+D751k2$?Vj=`JT?%6fHWs=@&#F8^XfnSzBs;QSIBSC2KX9<8*Cf55C3+!h( zHhX3RCpV^~h$xm5QGu>F8*CfWjZCU30`G}RUF!Y|^UQV~5t3u4*ftICB|XA`7~OQ5 zgpx-sbpEchbqZF1QheDJ`V-U+2Csi)m5`ozN-`ga^)h0{CQw*1`wroQZiGO9E=~3q z&|AEHES_R`r64X+5?n*h74F=7#HhL_UfzRRklrPcVqpFGB3x|rENUr1&@_5slIHZV zi1yEhoHdc4E~E>>g`M9S9)~LynTUW;cL%FF4tDm9^YcX78!G0Ma{u;$4AhSZDduuy z5tsIYS=<>>X6JX@w*-wJ3u5@YaDJ;lVoul*Q3%Ntfq0f^RT+C!hOWchKF%Ob)Efea zCHZqzA(`&7ra#P*k~cydCQ+FN2(8E*C{HVaUiu6W@UTl6%c){bVn_N-_(THV&ZP;S z^)m{lfnL~KwJn=D=*hSEnuPY#Uy#OU3~fS;;q$Jq|EAO~oeT?=`%!5>|I`Y{|E*L0 zzY$T^7ACgN|J61B^97NmY@;;KkKhXk5nWS90j;uA7N($)7f`Tn$`{cUY!Z)y$H5?l z{mmntAe)~5h5G$BCu$_isB4%bgmXfKsdgoF;e%X&3(ni|njVow+3u#qy>7{o-0Tk1Z7;Eiv+Yl4xy z=P_Sa9CYbGrP7SK;e=fi?|G+1=^66M>GY8PA0+UHAfsulYK1B@@MQGF%!VRuZ=I(){M#P6NH88@V%#Qb!*5Q4{;i&16L7J9KpNtis+KX;2JnzC8fX%pyA z&CjMSX4%Lht=ly3k6PHLwT!irr)QfB9!x)9zC`CDNjI0o2+upc41 z0n|LEDLoa5&R}K;ceaH);2b6^6y-0$#W41M^?55L6z0*bV1Gbkd(b#c%Xa}Sj1XDf zT1)ryOFqNEMDbvsX5P?c;5z`V&MYPoIIKKQvBU#)pas>oj>gz0LH`8mQ*@U1ck-G>d{sr6q4V3_Q+ znEn-}#d5>Me0`Eo?=!`jhgC**yX}4XDTUxT=LO^^iXe4eLf5wPILifUgU=Qw{6$u+ z7RHN5Xifvmv=8kPvY}>XgN$1>ix^JI5#u?pz_SnC_G1r<{?|dI> zZO(U)&J(qO!Z$-YJW@^xhlYnYaZ1de-!+4f^6jeUF7GG}(+{~f1U6!Ukz(1q;C6!j zvRYW;0>~1xJR(<6uCH)nqhoY3(>56<+4pwHfnh{b$;iv~zT|bn;ZOa56PC`IlH;UDpOz9qr@t!-M@y^4un)DRW@5=`yy{?K~kN z!DcpP$gON_Rkl4QQ2CW*6K^fC(wx1%J_c{K0Yr{?y0KR`&~C-?D#hRX=$Y zHYcVylra-7@=FmX#;~cIM#%8qac`>V4K!8`>$M6l`OyB3B^E6fxyi_w0;54>=qP6~ zBi&HUF#(fe1$_`ptIWIpOJ(=&5YCQ=@;RXr1K>P0K(p<@A-elN@Soah|@Ex-Bp z3#Q!YeFYP*)wVUvjFZ7ZEcJTImlv*249@akSGdt20xv__<(i*q3QAQc3|-8x%H8L? zSXG^+49ZoQ4S0CSb4?0+#443ypY=aS7f!8PG}9{ZR09!mT(!Du>c=DaK(ne=F9tcT ztBKVQ@1|lAL>$ao0=UV83#Dz3YM~`Ivj;`UM^#m9oYiIe>+^m%^4fQ-;l}&EVlA`Q z@}cd@i|;Vd7acVgt;#;JGPuAykj}K;27B$`_&?)81D%_VM*%Z5(l9%d^yKJehsz1B zI_>3LS`d|%xqIBbJ}~v!*1doIe!E-1e{+kLRMOj|j?wHQF>9HeL-Ax0-=W;T_pfZI!}Ru^7O&LL+Nhoi^u=+IQ1;8mYzJ?we&zmVpt0 z8}<70jb&?(`+C`X@~Gq*$IUk}R67fU&i;X=n}G0Nj=AG{tT*u9%J=%rH(clJK*)A9 zE%mzmiMzsNTSp5XuX3{d@@9?*8W zHB++_1yHTgB@G@(f0xUAMiPVjyF7rEWtwAcLsO-;Q1XI#j@uIao6h5fV^nC zYcRW^iFK_M*-+W^T)M9AXQ%EGtt!<|1iK5|*PsoJZB_M=%t`BqQef+hp>y z&cWM$l_~hTPE~EgNrdmTzr+Z&b}AOB2h>&6(|rzG4is#x$E(8ss4N=i%>>9mdjyUk zM7GaAXvqqcF|#UDQ`>ZSbs|3NjXnmx41I(EbhlKRtogi6yNP)g=NCzftJ#{_gTbOZ z*{vF^tpa5Xv(F$V_y2;49_Dn|9RM27vw(;xRa9@k(XQ1JvIh%99qeA_okvzz>CT_R zfK{K)Vk7)!xpv=d`*X@xdd#+8ByOUMA$z#HD1l&(=n3QivbVSt8&Rz~b&FBG;)9$F zledB>={10jkQO%~>gCZ~mA7nS_j66&5Q+RJ_9<^JDt`?d+A!aJ&!y^|KEOB0iSQj? zXb9P-_%M^9&nErnA@<_hBcd5(%+3JwW z;ShIW*NqX%v(pD#j=Dl+_f9TtdFZ!8WJs|z`wmU^b!{-GLt)=F_$oj z)e>;g4PUpUsIoFI_uLp(ilalrDgO%M^$1#wo%Kz^$0s4?(jovXVj>ve%I`83pA_lu zEf2g?eyO0$$Loi1)1if=roi*#a-f9_bIfMe2n+ubtCP&PWvhJc77xi9 zst!k$aYM1n77-?9z^u!as)oAm+buMOctou;`o(-vFo1jkJ||(*B7_7VgjGPvM^(&1lw&@}3M_B-~{$3H5nFdVg^j;>2~2JrZ#Ta+=AJ7N+&$Y<-bqUPH@os%;$ zLQr&F61%EHDfvXs`1aL2kEd9DY_gcDH7MX^gD_2*)$F(0`uJB|PVg4nB9oUz!QFvv z#Qhe=s`lolF?-;-^4oxvI^XZv9yk~`{JC4hR}D!IV;Q0-S~*NWZNscg-v3s0$r4eEsDjU^n}LWDYn7F8BtHkjDXk;*j$@$7wj}WefRhBE8f&Ebx(i$-2Mn%|D^Cn z6Vn|0QHrjj0$Ojy<5vh>IA=0P#F{ws#Q0iovM$_#NVKC~g&3rYbJZ(XCx4SNuOU%G zv;o15yrC2j=0aYk@+g(x7Hr$UF~&zL0)+z%X8gUCl%kr~bS!-j$1qd}P@-}8KS>ssoR_DlUrlDgSMmIx++_cmg=OrG4Qdruf(Q8|boF#^Fm2OoB;+ z973NUo29=|^J&+-G4$UI1 z3d_ZgHC}($AR(c3-obT`A)Q6zleiZu)ttn$!Ert;WVc4`-5)Q0wXr8q7>!_rw#PrI zP$HNMYtD318^^1*{(D}d{8jL&?W9c}eieGZzLseJGeFAF$=Kpw7%68ZS35gHBb$G% z&ju?<%YiY$`Op`E1w&MFeItN&`n{45VhMPIDv@Z9;obT=K>>cb^%aCJ8Kb&%3*_G|YY(6BpQbIe1L?R|8!u< z#9L-?kNUd~XBfpgXV6cI5RtRmQm)F~FdTWKfoRo&k>HxKX8TePsk{p{rt;m=h!V8@ z5R$elWwv~S>1)xy`34$44f_YZYV?qzpTW>@9vsv~>=7|lVd~bv6iJX_MBB7XV*|+G zyA<4m1u&UF(ZcP~&W0r&_03Z8&!I43l4N1bg5c|yu2|S{y5d&y4J@Vbsz!w#Huyjk z_h5tizBf~@p_v53>(AedyRkiqv?$dO3aq0=y9Bv`55Lqkm~dmJ+A43CLc9JjmJ1ZH zU=?j&gLjU6t|F`<+MfekbD3kfdMq#^^|%eCKFvIHdyT>eO6En#_m(GS;`J}1Mm#gz z;v9PM(c+e1{e%#e1Sy3TYll~ERyBV~$R3kUSQ}c1lSFF1isD4sw}}=wj;&O6=xy-u z=+4u2QU2OHJC1aDfu^b-)>3juS{z zpLw86`!+?%lx@ JN{k#B=RT|o-hpqK-Xjtb=@tyF<%JT?PSGpkACh`fJ;WC>Biu>keYFuF|oVL3I1| zg?#AnH=Lx7iW%G|V<9twR{KG(8*G5gGi(f%*YmCJ|CP^oy+Cm}jisC|kt+C^TPoHLGmAf##~- z+Wqd=Ss`B~Ja$*?5nAQnZwoa$#0`ldsItKo#%SB&6b%ss79JoBR;5E;@C3bLXbhGf zSOO}w22s_;7KGEt$c$zQeW01<@(Ne%ydSj`5=@S#Xb>fGG*-laN#I?V^LAAKYV=z_ zhlgO#Q>T$M9wEAUk^iC&leh4|`wC;_e)$^~czeUdh+OM00H(!rFt2a8zUB4LQ_Is9 znlz4;m=;tXM%FJ=WW^h8`0oBIw!a`(lp5>IR9j@7rpg>|0h3R<*dLSyu-X)=z2HCr z$pKj9CL0K6d8H-lkIEf}=Zc7K%V(ZV1&20O?VKv@GwWfjo9Dos`8c+}U|)F+E@#;E zO7qKrEs990ws?=`ne7sCv60Atd~|B1KlusG=5! zx(a>mU0?xPC+kmDRTAuQOje%ZL+AWjY7uv>bKAXx@d)cF@}pn*uc@!x^SU^Hj z=}}RDvUP(v4~|f_$UKoU#HIDv!&oMLx|^tA7p(U%GXrEH|e<&}HNhZ@qK}7FLs_j)J4ZTt(&HR}_^P!m^BWz)Qkj8oY#0+pVnF4|DHd`_IUHDq2xQ6nM6l2IzEp?{qh#aL(vHODw)lO#Cn!L${hGkFQ6=(X(b*-M#&a%$^ z!LuLf)`{a|+!yEot)qpt7SeKQoIeYDT{ew&DtI?T{9TLb`rxY)^bc~zMuC#3mjNp2 z4J$E4GdtJU!w1-a9bt_~nU;e;;5|g@$T5vh1ht!DF%_R45Q^`mF7&B3-QIX#lhegEQ|Nr6OY^=ax5eMPU?we2zNFG{ZT)@8 z%!p+R?=PQT0Nt__-2I%HC3)vo$lZt#wA!9=R*_;|^y_R8hK@8Jv0s}z=E~;m&wYq!xl0!Z9Ts%Xf?DI@FtimA z>)LKcyZR~V2&#S^UIPd}F5B=7>VwSZQY4K_-_n6y{5`t0T|nyj#deo&3LYJ~ z{hH*Wm!eLE(j=SYfsY;}iRgl}PV!LFuzKWYR_7Jd4vrTZWnSQ9aJnlj z)623c2h}aZO-E?IiV)76m0ws!7@GMBerG1mzBj3)OBB_(IoQ7_(wZkRpSv~anyCqt zmyXj;HgKqqjVGu?s%qEim^A_Fm#Gr!5%Z1-)ka{evNs`9jT;LI(%-K()sMs0_=Rm^ zi_Y26*&PHT4?!khHFpsWsqoDP@X4NH>&4+~Dey>fnohGw59IbU+;VZzEodV@=6$Oas_}l24gjTdlso9-ne^yA3eew{7w3YAyW}Ln*H31I)QRasn~H z>#jTo7Jh;DyPbpy7Sm=#^#F!Rno_ggWbhRPM5KFBK;UCb_g{0cS;{AjLC^FEC-Ly9 z(7Aon7|DXHcz&teAn+Ifo#Nx^uxmXcdn_m|>XAd*U6t#98W1<)wkJE;x?@;V!Ey5r zRD^NM4C#n0m-^J{a<7mx)~xuTGmdv~Mo zFIF4Dr}o(74)YgI*ai5zyt8x@G8(Dteyum&5O61j>Q1D*N^n%~BvmQsh;1N8_v)Dv znL6cbu&5sA(G4C20(Rei@~Tv1{MNx=^41%#uH z!!3(flWAZ!U}v_~IF9&>_As~aSGXbQMfY2K1d?}Z_#YdzymzmO8Jv18XZQ_)24CoB zdNpXjyUWGC;nPzlf)9DD-;tYNfM~JjL6JOHo#=ynaw6vWdN}=n-W_>$C)~Pb1o!kd ziv~g&KjU6;6K)DN7=V(`ZJYMzxf>os!ubuNoP_I%Zk2&_rGs=?4+Lbku?<+JF>%5= ze?Qtu=?$jQVfDaCf!mb48ml#`P21IN32jwp`fAttweWj{`z!rzYr)UH6BwqpdRcmz|Rn!d> zq3YfeM35!kS{>W=aRntn)h*%H-K|`Qb-03=f4T&;YG8)e-1ba(uDRfp#v$53& zu}-a5`@J;NwHp1M&Xas^=k-&q|HWQoXxL$=g$I*xGeo$OCC`m#$52?>v_kh$Z09!(Jylx=3-uyJe=i#lrksj zF{WWmNBcnmIi?kqYBXPL434NuIuo&B*7K+xt=mpBm1j7$vL9;lbmy4``^HG4YmI+k zF6lDmhz!yA3@Pf|L_K2mF37Vgm*oKou<{&-i=;SXsAqjH>sfk~D{z;T+&PWL(CWPd zgAodhZe}YJFpJ|u?ExtyX!nP)*g2I9G?)>m+Ca1D6W765v@x{S21c6dgLjbw7l<99 zqI0sr2*pQ}{6FZf6sMKLEjEKFue=YiV#aH{Ywq*$Oq75C36d1h-@Kfj^x6~}9LG}(UbJPa$<_Ap4a#e){SP3hw z!n20^Wcj-e^o6M+DkdH>vx~nYJQ3JtG1OzL$Kxwvt+d`imlfrON}PrUWk*?{#i%77 zm-RNeNf%?ak@BD#=Gqqx%@cEL=Z&%2fHR6f@aabgnvNawIdz?3ng_ZV!uR3reQ;75 z9-g}14D*!zZFw?eL#XrG17*W~)A5IX%#9||&06yfZ_&lI5uuNY7z`%j(Kgz6<6w!8 z_KtguF1xI${`0bPSUFbbY@1#nBZRFY)%~+*H92IC@UfrR;$K8GrhDVj3MZi7FQ*?$ zs1~*SyA*aR@_3f)sm`M5+4y1Xd>$2zuoGD#m9w+^suleqQA(1in%5rptbb3U7SzTN z(~jmVux!xNe+G4fgXQ6Xd^omzt5*Npm^h`{A%69?{x0(iXDRarjPeF3@I&F6XH}1c zQhyb#L+lvCrFsC(&ev2S&X7RJbQuyZk%#c-8Q%R4y-)6}8)9MF0Q~weR3{QSrYO%v zVU!WIRyD}SB{x5DF{#TQtq`6#v}=>tF-Vm%DXZ)joGoJdE0Qv=FGYT4i>M3)0f`pL z{vuTLu%GZTfz<6OUBd*J%R}hab^@!@$yN1bpw4FAQF2Z5{@ledecS?ZvcAwuO?yGO_ejL-nT@(j}Ar&Q7r7)SdlJJHhQ2x$H z%=~={4=RDFL&ZZrY?pOKRdt@5NfV@yB-6y1>sU6Idn~U64g~wo-O=+woGT|2oib7g-)V~PY3yb4WwQ0<{b@=uL_@7gmR)alI5cM?9s;p%u%PXjL&%pBEi^m$!VZJAa8FEu`jR$`;IohDU(z5f zbp4v-$aT*uG}&7b=cej(oDAbIpE)cC_b6&%-jX%bg<2iEa?$!B-8DCNmG+UR1ytL) zNBpT0X8TkuZs~QO{FAE|ZN^RI-;!j_6&IFoRx8tZnf6%KhT7$Z6_#stE%a_<;k00L zSVQ!o$Uh%gd*{)h>IxkER;rK?9fMikxNE`^%Y)wFkQ7H~^s3?lVLeNCeaSMfK`V;Q zlIH`?FxA43O-mre^I_a3W?nLg1|k})m}vM@kbWlpd@1n))!bg7K1i4?*BNrt*K~MV(4HC{!oN1+N&6VgZPsCYs*vwqR)*(HK-V~dk zchhLD{ zfpl^nVP@VZ4@hiaW=CIJxOS5CI7*CRk`q?HN4?vFL`Qzj@vAp3?=hEt4zgW9-|urt zM79Tve?J@#a3D6OUr8E>_Mgok|4*X+N0v5qlK*-d`LctwxBFL)R=4y(HOKputsAvr z7mgtlv;fuBj;VzPhiOQfBMqu!{XvKcQ|emBLkgCeZR*~azgXDlv1Y{wV@tP4jc@Q% z8fqF;3*y4CO6$z_?1A@{_kA0(JEHq@+=NAwUGUcA^QzO;*Iw zm?J)hkVZfxwQuRJIJKU_jWLAP;)t0nO_71G`1+|myK+;!&7~v)W|QfP&xBemu)DRs z@jZv0q<(3{rF9wj;o_7Y@Fxn1W4u$$s4AZ#N=B`BKSuXe&!=1ZFvksxU2&{l%nH2f zWVOyIC?_i~-BwyllO$hor8;kXyy;#8OZySUJ%fs`RWbI8{d^*a9i|})Xx=ljdQlc+ zLxGtdm5kMzV^U1ny(RNdy=c23ZU(=60@6MdtmmbL7lp#*|6gVM;`9bg$AlY6FTtc6{GS{i2nyZ zNxkTm1nkcM`3G^P>3t$9G2(Ivk}XthYTMukxkk^C4&B z+#I%bgS(~{LxlSLj7tf)Egp5a=dLKrM9NHZ9K~WHa&$(zb(AG!vf@1QY~Zeo)Oaou zjGYx_*2r40tY-jcs}4PTWp+}W!*PUL12yFg84uoj7~Un`=s2#TZGRS!x@fld=}eM; z-sKdNIvlRiKFyJ^FUdA~=&c^KUI*IsC*t{XY>w-V@g}W`lh`hD5cmelp z9KwHjP%`i$|Ict~zteK5N&SIf1^|VwxX^?CaO$?r@WdqDUGg-;Fk@0tR6SQbNnMA` z(Gnb{IIU2aU1=cMtjWivRXqZrm?8V6p{Y{UT=GxaFkd#yB8T0uxUljG^2`WstMr#y z*D#iPTtb()^b{&JWO-$6Fpdss2d_l?fl@2ivjNHuwM=S&wpo@BQHAXrfJaSl*%Fm& zWzla1FVG)}t=Bh(y%~+?qO*vE0Sq}1WftT1B-~|{K&!EM=F&qO9mw9b!2wo< zEsf~zORQ3nz<2jp--GfrU+8k;vbh))M(A5Tqxnvx1PZR zqbf@MQN82KOX%^rO^Yudh+m{ovZtz6SHtkaXuh!=Wn55O(F|96szl3kR9Pi2&rIW` zDG9%%IF)W*)i#H+zKni-!JBf?@-=mLJS9ySO4GV%nQXwDuqdQ6+>LvBPAm!NRHQ&+&`(wwVRck zIIDSeyV$sieYfbk>DAoqX3$x0cm0^9I@vb5vUF|9(njeH>z?|;r7`ZRe9xL>aYKa) zO^N>FhXQe)%5Q2y$~@Xt514$5IjSTMcp;vk(HSBc&ftjSdMGv|6}W<1(scA4-5?r8 z$z>s+v*OTIBMfbi2(1WR_gL``!nzR0c=3%a>o1V#u57cKyqSu!OEK&<+0(EJ(xzSf z9#3R*s!3&7rpVd}rg-P~WacxQN-g4xH@|#-bk>Q^z1Y?#MyD)9lS#~Ir8If0# ze;nb#_t667eYviBfAMimDa2f#z=WRRf8;)_fe zj>E}g7rd3usO2Q%cipB4Q(576-g|>5H7` zSbg~xR->M{4rSaH{%}>pK7ILti+$tv;$_(^#saDSRVsR63NFX4R>c=sCfX8~`P^-I zX*$oYHYkRtD)EpZ?Bv?*K6$77YScnNX$&>;vh&|`T0&Si|Q&y7CTo-d;O zRe0K@X2f@3q-Y$G@Fxj8_)H|#u`r&D2rv?1S=Lxt102?!ShnzyFa{1-w+_$wU0fH; z={u}g1XPj`v|3zB3Zmg-IIkR}PgVc~=Y?2Zo*FzvgV!;)R%8Cw-a}YwRRuPKaUa+C z3cA??hn@v)fQtPL5f>n?l~^R<8JXI2=e?s!ToK>4Bh2jZUSiq|SnDrNb^4?K3A4`w zSNR6qZZHvU1S#cSnRc+m2dkADBTp61;;b}E1#^=%zjSqJO2O?NDd2t6>m^I_VDDGS1M!wE}a8_JFw-k}X&JXB~A#Lgmd^ zM4buy@auNvXS#`_r$g6gpJ{b%Q3SOz*2sc*aHsa`ZiN89H;-iW?S)Gh!<~imBC+uO zb0BZ><|B}5lIRfRaBD0l*kBU<6(G!nnhWlhmESC5o$MJ(k@3Bv#)-`r~ zH&rv3~tnTYiXTm;*f3GHN95R4u#6CzjY=L+<@5W;k?Jer_d~u9eZMRZUg*WXAqA=o%Xj(4n!&5+wU1hb3T8p z3Lw`BEFKGF-=knu73KcbT93tS(u3Zo*KD&VoCAdeBYgLxFq))ecz4t zS`*gtNm8QkI{OLZ|LHvQId^69!lvn~E77@a(ifze0cr_TR82xCH5Lc&FHM*gCbd#&HT2N&0DY^k~Da1Sxui+u*RAN%MS4GE%bz<|=bK0YAV8xql#iX28f{a~hyL_7){ z0q+!af2e0AiDo&F6W-{T8?*|IL5Am_K#NvKUS1F#Ov|=!_SEt4_V}vO=+#LWjp6s= zbX;f%6&lrNBwY;0w&Xn`sh zTw^aSqBJDutc0D?kce?|Gk zJ5i^6i9q2K$f+S&-4cv!O@wR>5k}~cUbgzRRCK1R-e85RUcWVx{37(ZQc_ zZTx(Yx*e`PH_>rN@D|`s&9`1ok!dw|j^bMjuYzcPEz42$?Inz8fikr4d7V;8cV73r zWdJd^`z?EP&8#QSo?Ur14xz5vqV;%~MM#nQ_OYnlanM5bp*3J7oc2W2dqfE%8_C-3 zY`wpen@@tkPz%JfqfCS{1ui&QqPBnoHMn_5E{%Ws1apvevuI8qI?Sx-1%PXdev-JU zvR=WguvlBA8Se6$bl$C>0SVxuZqm(p@OSh^4wG8#04?TzM|uZh!7LWQP*?hCU^0wh zn@p*&a${orAh$7d(_UG@k;2@>Y&!1H&YGqDQ_T0Z7S1lOOa7Ux@7==Vlo&JVb1xw` zl149l&k$$9ig0=l&PRnQm{Xxo*=XUNEvKKy@Tbc+E;ID7R@I`3zSu}GrT)Nv?KXo3 z)~>jTX3atuuhgR2#xGX$Tb2QgjwM-s^<1&{uU}C!Wj7z39SW@E!a8JKFH14FPr50| zs-Lc9tNHYm)Z@Hq8lm2urN~XBmVj|Kk#+{oZY9;C*tV@XvOiun+9v*o$VnwrJl=Fl zEXjYg4!N(cUGYv~=#`$yljMvQjmyR(QRMzj$zVR=^#sfSA(wfhwQMnfhAQ5i2jX(Z08ZC+e;&cw$DTEXO>yDnIMAXJ& zLp^-3XaSMlxBD!u(P#OCE8g*()UdL0s{~lERE=@vu&7ZBFN+gOjCeTCe^Y#h(vgXt z4q(qbr4Qd*Wly^UQ(sPHNF)NBK#tmFCe0@F&UxmGPVZs{yO-i$=8BphoEq1@5n`+R zO&Vy~W}Ik{W`*GxBjqPjQMT^^(~#KjoH`lofmFLyqw;;I!*Yeasoj@0D_7UEMARgZ zc*V`LYsX^c0I#-ip#fGY5eU>F4%9?U9zc!?pA^nQVS~#1gc?Dk*F08vthV!fc)7gB z9bloP()Z7)Vi$GJa1~d%^1bx+FP=`Yv#WvQHx2i^?q0u~Wqpqr7ywn$5Rq&=>!2^c zct%v#M-LbE4M#Rfs*H5e%sWP@4fybsB3B3+3E=_1c=AUR)@_z5@_I~DbJbUHO;)k~s%m5n&bJ%z~~nSj&>ZHjijksJ|ilafW_1HW}>s>AM#O<+H5k34#|# zJa#yrX7oS-gp~`03j^SZvJ=ZC`(CdNmSmF32z+ zA!B}PO{4| z9zlTgMlW8@sb={N&-Sxs`GpHBXG+tgLUwnrzq2NmyF#!~{C8X~pb`kx8KEu;t3EGtGG`-m3f0LqY)V@2rA3a^;~Yxxo9MXcWw^%G}U$WB!5dC-@d~5YYnQ zncOzmJb>dyR$s`+k}d#3H% zy|^P3DYuP%v(cR7GC@7NVi}0B+QTo$QrPA|L+CHA4jkKvM+o*)1Dc%;O->P6HiD+5 z!!;Zmo`u8s^emldjwu`C=WRwoyV)3^?&z8GI1%O+$!UEj_LL!)bEqllFgFXnTuq0dRd_eglgeYF&N1lO zTdV~(nZ=LesX{Ni3X##y(3+5VYngJwx-Xov$=TRua%|Sq^f{_b*VJGjIs+N^DHwA7 zhy~Ulda4H=@(a89`-41Gzs;2(bIjD|Sa;uv1_sUJmL|8y`+F8i1jh@n7mTmxG@p;1 zIp00cy>aU`xntc2l+UeL{1Jk4`G?!74jMw(@ePIZjMp(K`be zYKS9z#kT@YrW~nWsl9%Bb|F5u;3@f_TF{Dp5_9GR>37`g!sg@M)5bZ)=4DpQ9S4_dri#`c~jXtgGu+BY!iueMHM&31zKLdpjT76eI30CSr_-?nb^N!O+Z+iDBU-se5Q(D)|C4DW~I@#BQ?RvCv%&eBJKv9Eef02ad}UX zrIQ{(%e)s7$A(+46N@YHFp}?5>88p|Y^Kl$MPwlCNPqA=I4heo(~D*yypE9eim0yO z68)mBrm1^Qfj`UJoqd-KxSPO;O)UxIQmnyDSNbSl^Q1# z{}B1n)dNm}^oEGwlzgTTb9TLpS-T<4{!6MOP&_sbe0LTs$j>EotGa2U^vw|~Sf?y= zMt8=}lve@5?um(SHc1d1f5*fMjQ8zlzjq?#NLzg9pHY!hb^lZ%t&?_ZBzXI3X!tF`pih1U*;R~$ZykH zA=S$VJK^3p;!Y@GCmz%VYk9cw`zU+=;K^)Ok}b#=wYi(JaTU2gn&*a=8U*S64oh|R zsp2>5_GR5ZmRBV~IWRy`G^8E6EK#M`T{z$ubBOaE#rk=z={)ukEr)$0X#QVN_}J%M zL1Gc;I=|`@ek>PyFTa?P*>w$e>MlA$t@0&N+KQdv=skf+m~Vm4G)k7F`F=yhUQI;eRGCD?JN9vo8?4OI z%)2lz);pCoL!z41BoU{~Jygq5O1xn6L(FYO9My_zr`o^JTqVnGgbu^67{`%!OH5u; zik;8D{(T?-d#h)gh5YT?A^Ep&tp6{$#Xnzhl)ubVzTR;DTWe9I3G1D-ko=iz!pwrj zFTqS?!5IIWw~v&l1CU{n1P&S>qz;N5FhYtovTZ^>DI@el)LXToVAgIUc!RoPt$0I; zMhZV7AXvA(O}nvewc2NSwYq(+yuHefpdtBV>d7Zv#sIZ`>?-xDYm)CN=acKnZwgQE z@9~MTgn0V-&35h$1HJcfa4Ik5&=|g3cS88Zb2VhAhpKhW$&tRU#|9YU=Je1LGuNX} z)qCdR=KVJ0b3VJ@eqXGv$5^0F$Ig&^!{4&dcYEs#^VgSFNWH)9f4cU1{k8=fU-VyJ zf~jAM=wGWRJ*J|c_@3?m#yek52GMLAt$E*LfTq4eCuUU&}v0Qr5?4Vux1$wTU^t#e%3bQJg`0&^U^Agz|FVu)Pp8j@9a5}LQ z(?z1F-Aj}-{SBcByxwUFOtVVc0duoX^;?D07#g=jkv4ieV3mxGUUN602vj{(U>zSu z1VZ_&`Q_K&&V%?xL3>YQ!c~;8YWVdp&cR@+HgR&mxP&_4X)Gj(VQp9tZ)8O7H8eIC!n)?P+SkoY)szBuCgkc zcbpJp#SUK-X>*MZwk7hTWzTMs;jm55sWoj|W%e0J84{!wlRo8c7YfJ%G+L#vGug#^msFAc&vyo8dxg$F%dL)tZth_miIbnF%gC;!1ZaHHm0#` zBE>*2enQmnVp7>hDXW{ylH!uX!5njKB-7TmWa7X&n}2u&k>nn?#3T#UBid^u`VgG!= zoH(*eeQbhgYlxh?!}6PHv7Nk~L6TrVskpb`s6qx!G8cumEz?e(R!l!8h?yU88%%u1 zvR(X1DTQ6LCssIfNspgyg64L;#?O&@=$MhD;c!yEYT{@PsF;ZAbkq(o^s``#Rrp;G zP>owun&@9ai*A@9U-PmnYAMo+mW*W1h(5k9v$fDNXKxqcNtxRhObSc#WzI{{F($No z^9`t?WfB-e2x;`!z#uv#ho#+1z?GsA3mJ`DXwm z#(|0&$We{(U`)O(3_oB7hPyb4?w7IE+?BHvTkIq*b&Gu&&xdvwC0O});jJ_;V%;6o zXz&&{2BmPmhCw?G9@313oKzYfCKe_K=cwmNi#+m-7vuiP@g8*H4k{K!50iMZ#Z7Ad zZ*@&^vMM=467CIj3OFjnX<4^fQ;P8PWo#x`a?GVujSbsA6EcI{eE)iT`(|6N-iI6kujjvWU;Z_sU*9Lz8Ho!*ksq^OeF0n(0u z&GDI1o_p@^=_Q@^{dcZUTJ0(-(~!y(w(pO-{8d$KfSFaBM1P(e&D2U3lTIDm5w`UN z)-&_K2FyAneWq(u?_lYiqE^ZucCoGdTEgsQ6S2EQKkZjH9}ECo)|=Z$4@6RuQcCirNO(jfc+B+>dH46k z`Nr&Gfek-6%Lrd+E}B%hU?QuSA1t3MB_(m9RlyFowYPapgIzQ*NQBVL4o0>#w9@0L zq5x-rVk64D5^Hd+dTGBfT@4dEA|!@HLtKmy-?;ZSM46OSa45>!`$I$kV`Lnd$jNE` zB*z@2^c(aiOePUFOD6O-SCc&;e;cK};8%z^uSf-3=QHOY3dKq ztMQ;IP|TVJlO*eu%FkM<%$$!!lnh^1jM^V4d4o$N+fXHjD!pl2$&XH3+ZW=3op9`# zE5z+6Kt}MKC>j%;Kc`l?mf~Qvfs&h=Z&q+{E*ZF|M)*mlQua&zv%J$v7A?>;}~pY?0b^^H;WRn=S1OQRfV zE+ON_BIyx%C5DLQ8ynR^f1~g4+SxI>Kbbh~phUjSoaH9qut^@(v5!=_mE>FY9tm0kMiey_jrZIzZzF3X<Ol?%1}$vqt)^jxY1hp zOqEQDH*snvUg*mcA>_(`GWVhe&L*Mn28zBQkBX ziG%>iAd1E_9Y|Bq)~QCAbk+rtCQ#AJ5iPcyiJr-Xj>c0YGyao0+&c;zAO ze>U8vZBT(BAQQ@u3LTWJr8%6G9J|P?G<~zgrUxd$1O=B|?zN~wY4K)#RJE0# zS{m5Zm*x~gr0Qj;c&&pM<+c#={>`!PZL2BvtO}{Y$B8zaB$P_!&yw*yKH zvEKrkCiwOFlk909cpFKZAt+$5gtEh*6Voi?%y6nt+t!BDEhYpkQL|yEMRYH6PMTtJ-A@+oe2RsO|=t60GIKO6pOzKbg z{5A?q^W3?A+p-X93wt>AxnA%xOMx|5+AZqQan&Q(dyvzAY>hu8?I4|!Gjt`$I=8Up zxB-=1j4v)Gf7{X3@N78eNTpau7~~FBns|$|P&Fkj&rX)tQr{K-%TC4A#eB!ik#NP~ zo2HtYmlZbChjuSWJK_9lz#4%h49nZp5Sm|k7zlWfdUPjPuf!76Y6EYXAT^R1G8%x=i;RK@XK)t*%tioOQ`%HV>6YQ;4-w*Dr`CM=K6I^>nMYGI= zSZjF?+`6E*b{}bVa>wrQ^+!!(^4r>Qw#y%Wfp@&)`}!}&NB;g#-$#UoFU+%T!O?qb zwC>j5eh@dU_a_a)HgGk@7f4I^lJ_?}Y2Sv+DBDHGuJ56#@U*JJh(<=*cbx~v=2 zBt)L34fz~rd;)*bu}Q&PSsLHr?DBPDwzJDqg^YzcO}kG2&FA-05S3F!>>uJ`ZZ66N zPmn{gC{0&(qJeX%J}Rv(8y);f7_ElY<*(x@JM6^x0moC zn6|4UVkx|DYZV*;mrwT<7Z|6J(2EP4@1&z2?Z4D{+jT@txvv=bu=k=bH11!n{`yo{ zn_#&BS$iopdo%qkC+B)8bzTMZYQ40^`?an*e)|cztvQymhWLD&d3D9=H&p!fA^m`)A68V9nJE_`L^88BFKH0ze2X?)jTJ3s$eDJqhQF};KM1s&pBo^r{ol851<9KJ%C#?hB=(I1Uh!|s`$MaFy z;Z*_{8K=J^>F~~7J--o9B|=|fpdBN!X?^w;W?u$wm*NlaFB8R@Gw4}JT@I~Tfs0FGEyH#>b`9lZe}7;RXo&Z!fuUnu zn0KPt#H|+s^b4=3af}g9&OVqg@SS~v+8zH~?aZCEZ|39!F!8fU&d${}pa+2R%2c?A zR`5v`?;DM+S2}&AbcVwbbu}Akx2N&`ThlkpZyEgKlGWh`<{8e7009I zaW*h^w(vCTlu1L*u1P7J`!VTaRuebh_u*Y&Yh)=Za}+PuDJPKouK^8S3EIq_BhMJt zw8GORl4$BsqDodN`RYEkLK4IuZwd$Ss-lBz(6196o-PCgqx);Dcvg-{{z-(nsrGiZ zRSx)@6~59DHXq^cWs(!UKa+ZM*H7+f-MP;F$0a}8@^}A`rjhmM4|n!=2x!6gIkW`{ z)JqOplKOOw=7T4v!08(iI8re=Uat{_K52FvP9!spdwamcFO{KzDeGm0`9n+ZJS_`f zf!H1i4for%WpD5CyvHPzQoJFVeD$q76LWsaP3p)7&X6ldl3X$pm{mL_p;;l9Ev{@$ zn1mF6N)%2j&YPVs@J!qn8YPX%-E3%)A;^n1)85+_jIlKIt0`LI#|0k!nElqi;;*8? zXJ{U7W?jik!ARNQIAN`dK;cYz%i)g3!5Sy%GysCN$At5v#Nyo2w^6QB@|>azdS1*=S6}q8NZ*LR;;EU|7=&4tyZ-BueGzDSs>dJ&GilR>{8Kj|9Y%=EuuGaK zO(cy-iBYN~U)>ZLpwT8A;ZXi8PfA*r%2XBaXq^CdJ)zw+#^XHdEo@BaIy%%QL)X9Q zNO_qEeQxvtbQUXaLe#g0{G%lV)C3HESGw&$fqS8;1S7EH;K#g7q0X)K0O^@^>iL82 z*QvJPwGjGqwpkznKA7*p7l<$EHZC>fC(+UO<*+|{lGv53Z~K>RfHKni_piyIy%{_7 zgwIk?zO?t5Mli+x@TIdvd=w zYm8@wlaaq>@tCfr_&e^Zr~_~ZH*YyvHR^}H=~0Kcl)xRJ~Z)B_Zv?l=1Q+Z zTY3U4{{YOCL&@!__q?Su=@*B>&=rg+p!?bEAG=)zRW5Sa-(r5QZ{0G-zv_1Vm+(c- z#o6A)S;_gEwPy35+eKP-C}OCeOS)coUQVR&a1!R`FfMEuDA4&(ZlRfk;r_q+pniI5 zki+2E8P`&JR8T!sBdF+6p;fd9CcD!r4i*c93m1w0jkSE6TB*k~CzVf1U*&Y_xtnsE z#`=1ABCxtPL}U*<>0^W&3B2A>2N~cX3`sQPAPq^w91g^l4Ydb1W6gru@kS&BuxdjV zNVx047J!Wer1cp?Dv5{fr?O}-*^3ASHX5TV)*K$7o#&2nL@H2UWw^4~q)IP4Yy_7j zvJnWQ)HAaqYmv)kwzzE5&=4r>$fY`RHssEbv19pbCmGa&ovk@+ygvR)d?fK8#OZe>x? zmP`#SDzCAL*pnwVm??rud8@Ihxb;&pEpdxVCT$caa9^NLE)bP_VQeDPU(irq`zX|D z|G*4~L60c@>3$?Itc`3Nl_zp!=wM-)2b!V-UkgRQT=Z8m!(NtdWEOq9CrgJ)k=IW6 znZ85@ItzH~$A>2eN$;Nq&662s_l!NiXeGNSi26efWg-$~ zWvm#5L7xoZ8k<{l!Bg)+Irf9z(}TLHSpHoaQu#)C6?Y=sGXbS1hdt zm(bNRLUYF|6_TH^E8P-%pe~yq1Q5ZRux9&h*yMQnSTZvTz1dMtnGo&Yzgju4~jt^{AG8(2kuzZq;*pPh4aP(v*+^&f!lPI=I4(7r9yA_SV(Y?R#WwBTQ1 zegg=^U8~mAr7b3o$65IHh`1yoHJ_rh-L{T$D|ZfdoWGU7=GGrJRcc>h;hN(F zEVgFc?9~U{l48|%GqE)L5FD!=;U%8)nYwP_c0rn~v3m!3NBH8|cj#8Mo(G zJ3tzXz4IFAv7P%xf!AZ+Jh_GXxCQB?4Sr&nGbcE@geHXeWQloycba_#LiJD32irflsH^2Eal#6Dya`)*EWT~ai*GdOeq4v8$!S{zJ#V<&Xhk=d=1+} zi#<;`qMA7bY>_*pb1x$af$!HjV1sG)n3DAjd3eWi;O_(b4vJLiBh#PUkRvO;?qAOz zLl>ZK$R&A{6lVe}ZCP@$rI+Y1t!HxlsuZi?+aK?w6@eIQ)c!$kECLiQ7?oQV`h>M+ z^@H4K$Df#%$42GE_M(~B3oQ-h-yJA;{CgCV^$NQR zitkr_pwZtx(Ne1BC3W#ZP%N_bUG|P0@DY;Jsasno634_~_sELv8dm`nIcQb@m}n(* z^sV$&O8}ZzDAkllBqQJ@JK+&vC1j%Xn5e4X;AfO4SOHbdGdKQdRh?i-j2TzJD&xa+ zo@kw|%1ynCmNJ-ft*0U=BEruTq(D$#qXP_%)8NA$Og8W^7K0z>)J=DXi{UL78?#lhPYva#_uaclo&%Vq!eA7d3q3yKpTdZ z%>Rj6v*~H^A}x+FfnwkoS5xkO#e-sM+Q^;3&CbRJb+*PwW1u@G(}}oxHs^*bvZo?7 zCikI+QX*8_4ToVfo>7?w5(GL(afT2N7oso&`tsix+yBOF8oLC^82kPn{%>Xz^Zz)9 zD4H0VSh)TNc_=z&$`V)rF{pBpp zKg4yu;2J^D1`n#T%bm-^%hPcXmFNjY6Y3gtZIEk!%BDX#8Ro#TzU_x>CyjkYV$;En z&x(2OwSt)5yh@UjLBQQA&BO#^Xuy;$k2bRAeBt4H!zy)`M2wGy`ll-;is#p#q3UZR zEBHAM&zdWEq%Hb1S(%n4g$5HG$d6-L#16G358g=ptEC@;BFe#S*!dwC5=`h~@&zH! z&>4RJm|aDnyFA*y@uhf3KtQbj>Yw?ijUX`-=YK!;X0bWmhN#_v)=pSr~e z<|a-rzZ%Lm(80PLuoAcO19_d=qF)M7)1_%3j>2wZSsI?mQoT+Fu)v=h^k8KykLH}> zwDB89_{j9k@NMjbB&A@y&-%>U?0%Zgelb1DY*+hwo!S13adh5M#mvU6*)tNxFBITG z7X^x)*omsjPOfzlFefA#EEAOc_7ZgVhz(}I2Y9@&R519H50nXsh9nxm%V231%pj|z zOqvL_A%;Y2W5VAOagpj_41zM#4yGgK!0wy5OBUs%Or;7wx6|+wlldYI(2LA8Hk_$7 z>^efK1-R3N=|S9hBhpipb!{`i9p?o&&3-1aVzEn$%>WY9yDrsJocL@>A5NctUG0j6 zI(tdBhTdyW*G&S9+2%h!ZpB<^X>Vhwx#v731$N?+m(Ug-aY}r7_|q3ILYs|4nBhKD zB`31xtc8X@jr%z54p7fEpsM_fF#I~J=N$JvuRdUWk)e(yMpCxsga>t!L+%^{ZrD^W-t_q zUREJ%3~?(Pe_cYfyN4#JR>Y(l6Hgs0*>uL4iN8R9@Q~FA8A2V@IQ(b|18-~3D(gju zwvjJNTApX!l*&@yK*{bQ836x^^miUtMqpVdOlef6-U_%*dam=zZ>1`atlA8+Pxro( ziHm8Cnu|K|rJiww8-iKxgB zp{BweiI+-O5Miv{^15Kp1g*Cp3axghmCBdga|wNpUp_A))kjVMFlDXDrl)k{wK``W zHYYy4h&{`caFHH%Eiy!KEe0l&G7+PQ4E(1D({Eo;Ey{Cd!o39r)S>cYiNma8C zhZg#$bWhG*sh^jV-94W4djH#l!-^=u9pS2ygVd7` z5rTN)9`h(Eg>eokw@2U`1x?7Oc*Dr2a6|c7pnujN(~>haDXf@sifO8==75P%@hlC? zf;W!YaVji5aHoQOyxzs4LbvcX zoHO02i~U5|9M^(yG)+yC0F06>TRJ?0MGTw4S&a3=%g%D`oY6Yx*r5-9^GaOksbc5* z)3JB=Ue@V-3ff#~Lu&TJ9NIPH^X}QL*)8F-zth{;w3)Pz-B;Xg@}4aZoznx@n=Q0n z;mzwk7z@NP@%a~`Be&|TeZc~}sfTF4Qmy1=+fvPSrunvXH`*?8$kZh3oL(jw+4*zk z@!zNm3%lv&D?e^=40HE+iHCN$Jj2V}MAfkNE3z*22;9AXW~TgtBO$*}+IK7&zm`?! zjfT7`%BB#)?fensuCy80jeE6!!WjeXeHGE%yzM{76q%vE!!~}Pfd7W!h)J#p3UMypk|a~>AVZ^`)x=GHsZ|%Xmf!? z@2N0U?LF`v-o84bmtdcquM4Us%-ic6T@dg{S`mUX;3ofpAX^rR!g>jcRGC%XrO~${ z?3{P;^I~a!k8Ev2)T+~5=DIw`mOzg&0OHRXu{#J_&4NB9s8!D`xg`ct5~Hchpms%X zFnEaVg-unw01BNpWW$V|@OxdHM{ zA8N7->^Y6#SgWYT6Vd9BH5SfLqfdF-h&bOS<4rYB6jC46>Kb!t5B7MPY3w*6%2vme z4xExw-KUyGU%=2TN8*o|L#?|BSW`4&GibwXJE_K^2U z{0=|uxcz2cuWDbohw%v6o0L~n+kYQ{{Kzo3fThu&I8`_LkY@%b=+dV)#JHyxHsPC$lvCBXxWGB~RE7g&t# zYxvL}$>Z}dbAVJDOYdnAZGe>|O=XMHAvyhmJcQQ0 z1N4f3h>ku`t&M1LR^-{FmUvQ4STb=;3HWY>aoN5$s1CILsQ&I=(Xe%v%RXJAJ0P0o zQN|sg*4@9^GkI!9WY2eOsHeYCwQPZ|;rj&93b`egJWf7koCVXGM(%VP&0R0hLv$5{ ziz(3mcxGXC0=tNHQn4k1yM)(7#5|x~+=W41*UE1b+OenmS}fEeIEM*s-xsIefYdG< zbdB5IVPj*xTvW~IbiKCh%e>y9A8r{`_fEjy;)lQRbwB_1c#m`b3~PT`d3eYR?cT9k zn+n?Vg=3U6Sy&m=*}QMaUL!I3VYwYE_N=0Sn#k17_{PY&?^c1Qd#rt)Z=)Nth5p$t zV3C@K>b-xn1s`rmqfizxuCk!|spd{S?fvn`; z_e}mTSxK@6l)JVH+NYhVN8)LrMn;lsW|IX}nskaky8K`P$)=*9rg&Kk*p0~%D^}WM zP&$;2h?R%}0BxvP1xcX~E-0nM9~ex*0Rv3o2b$Xun480o_Zc6%t;r&Zb&`+E&Z{k_ znb%yW8L8gS0p6#bg3pO{k zdENNwk-9JB{843(?i|4g7{WM>#lAIelXy@7} z=JzB%>~7@ktvsY&!V^7AH8IkSFlK3FdF=ieVom}vKihR8!}Ne091q?w z^|g}5d%Aya=yfDR2i}`6rL^DAm}eEpUi66VFa$qp>R#q+X-uCsxsYv~=Rkjc?B_&5 z6Vu6Q%@<>`>OZR(Gf~3{r(M|*aK*zH-eidc;U*#H7xfRDmAadWl53~$ufQKz(4ULP zPxsUdk2;n*21AOfo*Zm(Gi39F8_X@b_;Ls<9(GwKC4Hu} zb*m^VG{BjWz!2x!F?*h3BZ|;h&;^cvPUzjD;ourts|m| zH`c?lBqE3EOvKP@OXhN9*(Fql!wON4knHLjRxEC!XQFGHi4rT&Dn4UPoBVuS#%2)J z`AM`TrhBTEg~>AGot-B$u_R8=KIK;9iA3^TQLB>O9ql6&63jemym3#P&CbZ0Q<6C)S6549_EQ`v+8G-hVCb&bbxx}#6J zuf$fz!zZ}w`}4lW1YX!}^>7hoTgiv3jlL&}k{D0q37j+GDxBPUu<=n;n;{mD}n;`~4(V;H0xxb=~U$~nbD9Gv5N{Q=q40=r`7{0`{Fg%4aY zO(xrV9!i#!dir%|=-=k0b@rxIdsI2&2i7<7HO|oFEx5YmTBYS?XzOwc>TE8B{E2$m zSaRfDT?e|HTa%Y99 zFRI}c*fPhkpDV+Acdy7=b_kfXjSY!)O?Gn0K7)^?-*GfhzT$U*Vbh-J6UgR9)1C=( z)Y3}Z8`B@H8@ zwJx3>gO80x79qVUr$51?r{r4ujUwZcpec>PF={1w)P+fgHSL_ZY?tQFU1Rc*BQsM! zJk3n=m$Z?m#UN{BD^!{@ZA7UY4$B~(wqAM}Z z|G3G+bZ>CQrb1OBO5l2~EN2ZgovLCDx2N$0dIb*m=C{TcuKRh+k0+o);A8ee)`FrIzh0Ef(g3&P1TP!mZ-b0-obPkI!C*-nA z3k5`~EQ0{J*^Ui;Q+<-eVkZBT%S+WqrAYISNhX|;K7QT&C!kJ%!B~=IW>J8Ii z5y{t{k%zRKS{;Xgelx;CcuSk-p7N0BV zT#i#!!t^gitB==yz{ztE_E+E!VQ#T0>l^Zx8XVF4 z-jrDK1?ul+AVZ3HeJoTAu~)tr$>MI;^ItZP5s0DYtO*ETEbGUf9MPl^q^H}JO&o-& z4K6le)rWK#PsGCEbX*w&lNn*4e|&jr!QN6WwD!Ib@QOsj+oHK zna*2)=8HDZyaI~J^n4fe@$M1YD>wZatZ-?!D4ou1+`gMx zD4LU7vG*r62)h9bZ*V)|Mth#H(Gn1K^-gnOIHX>?ArfrP%sxY;A`!ZH4FG{A(v2EK z`?j-Z9-n+5hTTAdBDj=C6(57Y$>pl&>{(DI=ICpmZTo^ZUND(t<4PQQ2^ z_;y;KR7X_U4VtnD@i2&a`mZxz;lct>5)S{C5ZGN8fmu0@X+p%a(Tv13=|q}sAMb5TLdOsb_T~M22}(DSUn;1Sfbcc2e6!eHlE0f_meh7uxro7-`SQ} zTV-5zQrRKwm1+(9I>D`$Jla8$ms7-{3S^MPI={fp;F*kFIos8K78s5ygv4ThKc*Xsod2LSI0<9@taQl+--Q1OIB2raF(YOy6<)2uErAbR}Bt=#G1$jhMK3KlI{rj7l z*bzFMiX1IPcFhDgoJtTuN0=AkQj{X?&zlw*E59;QwgE>ffqjP>u^YWoOg)$hi7VzF z#gecDe05@@Rla5Hfnhw~#m|D2Y8<8EyXE+(-PTFdOD`j)6I?FP*D$Q=e| zr?eg@m(YI~WvSxQuO?Bh>D1)e798AN6~WsH}Gu zsH+Y;CRAM;QmmR7a4~BXTHqlu#m*U17P3K|@WR_uo|36-G>1S*6;dQL>p)mg7Vzw! z6ATn$(b@4sXAB03>Pt~#6fdkxlcXzhZ3LtWgdJ_3QLO_)^xyQ1guRoXUTtv$+Lfd` zZsO1=IbgZx_udWjcVn{4|9@tm(KfL2^r{~7Ba|W(Vi8uv1(-sD* zXJOU^vYI8{c7dkJWI=z4%;Vo1g3oKzwus^CFV2@U`4o!&`=PY7W_ z0cxt2oW!eJL(Ro9@D4xlK25qnhXSE5Wg_`ogryI7HjE$n4-m|=$XHl!*|7xnxm+XP zC+y-gXJ(pS9o1)o&0sConjO1BTmB4bciw%O5&gqu&x)TsJg2?)#(c(hEGtCJ9e5>E#=6x%2?vh8w z!Y)YFwjwIO@;AGgWwF8HGUDV%RS()OpGON`htm91;q=@z?cB^<$0L2rjKXKH#2rt} z2uzWC&QpIRsf*33feS5(-Llz`Jrr_CThOVf9knT_15^xeRrbCzcFS1-=3?A zt&@wry`7`8iLr$3KaVpNWTXavA^K#N$V4w%T77hZ%2nq@?o{uIph62EEC!5_==_!J zz?qA_xAUN)IN2m1l{KUk>1t!RbKUOpX`Jx(?d~ZIGCJ=p%RAMtj7WijS%-JUJ!ev$ zE>1WK$X~dG#XOhdMTK?IqjE@$7K+~jGmw@ZTvk9t2v9yc=CsHZ<22xSAm%+%#6r4b zm=2m<<8j1`pzKvkq>*s81k{x#Oy0{-1vsSEAj3!2@Pa>CVuu67t4F6U&S;_m&6C`? z?>6?gs5}s?9A!)_cf6??Pqr9ruor?Clr~+#{^ZFRCKgmlH_k+JKU0tBykOsR_0%sr zCtKEh`$zn-9f*ptUARHqDdvH0O%(og_SXq=%Z@@$h%wit7Mv^ApdJvaQZD;~23ZBc zo|Pq1^?HjIPFY>zRE3IKfWPgh3VDt7XLDQ2uK?6hGlP3>;Qp}`=69B_EdB;s{)YS? z04@J(2J(NOk;D8B%eLb>FJ%L<8<26h7@ zP18!c>oCN_kXZT;AA4LgcL&^b?D}G%W)8k*F%7>bTkJneSl%mMmpQxyy?5NlTOW6| zq3hQLcvr#K$g*Ha{TA(Aq^bCD-Gt9N4_NJ4$rGIISzat5gh;?K5wCDcl#Yn=6 zhfWZ7MGL@PnY*j~G(Vo~+EsT|%`>4enHj07GBPzBn=Ck8X<^1`Ogy?+5%2nX9c7-- z^=~-Xn~X}wxRxFQYwEHn61xEV!8jTxN@r%e>83XFw49RL$b|Md>zDI(nI?H!?TlnO3%nNV?dR5-}>D6fY3+lcR<#p z6Gu;hrQScfDK*X>kHQq9<4=Vh(a)w;x{)YfY&fcRI5W}&YmdY@MU(K1$MlR|k9CBk9ZmR7IK~CLfqQ ztSULJU~+c46?3ia%(%sU?hY^aO(evek`hy%)RiQrkR#?Uz z1ueE5lDF@NzlyTM)&BkmxbMurxBTn2duaiHft=r*~}{6S$Qw%nDX4{68zV;T^*0|s@F2ZA0|yPz^PsUnv< z2uSHl*?gHO!o<0WzuBn^{(ReS+`YCzm{K6}#@1$Fw!^E2!(^M}5P3J-GL`V%&$ z;%pvhJ#fLs&tv&20YnY@_XytTo4P~f2?-~UP1f6wZsNkNQn)g2W}QCGd=H0OXk(4E zXtBV&zKb^4tk2z~Z+h~D?9VWlm~B)ZWCy2Vo{{jpc>vqeJzDMq*kzM^ zAh!ULcayw%wZ0}GdSf9^EkWDd4zTS=7y#pNv37+--W&kK?r2~-y}@i2lKwQ4s)ku+ z#2ZUf0e-S?gRP`4J0%HU$ytRYNgjP5xe}p#H*-vL5d{OFRJDo!a1Y0gt1Z)TpS`}}y5F+dg zq}yXEEck#DX_X4U_?9a`cb$UhkSJ10G%}6ghhDThWqAZn#PjgQtJ`}h+?F-E{x>QJ zo!&e{Aw&=DMbABi7zZqd@`C@dIK0%ErUkwbIU<}qE!HSoqeY~L zv2OZ!Wf#9Q&B)kK%>W<9XljVj>lEf6v(+JTubLSw5YQJo5D>+`n&GNATUh_cK~<|m zxhpSX@wzokPBDPGGtd|?0xu%={WfnZSdh3C6eUaNNY4|nNh6^j8#N}AB|}{3&|23# z3y^YvP;M&VYeg&$h=?fI=~)DOYPMapY}WL=%p5Z&6RqA}_SV~Kzv_MZ{CY|4>{|WI z?PMp0X&hpK(5xHwH?3+m$_{K`^=JcM=Ca3Is$6=2-}v3T;!uc(gKMuJ4UmDhQ;pRk zkq*~VxnqO4wfBNY_M?U0@aMibQJG_v91`VzCAoCe2ewr^x>QYMTfI>W_rgsJm~ypN zxb?bdn~8bDORG7O=~sPl|MkFAW{gn2#J1?E?!r@`+iLcsGhZ`Sl83Bb$gmW!k1Qw7 zLwS<~m`9!w=b^sI0^A|fi+54nu!pCT=%%=T3k||`kZUEn=x#y)naFk$U9>kbfKKEq zi7xsZe?Ta*U+S~?o>90Q319NF^d13nu9P?7ja)cAX-~p)DqtCTTl`&XPb>Ti_Zh); z9qe2X@&F$C-CAc%%odw&DKAa7Um$ZlJWAxRXVuMxhC%q}C7FFlqZZdEV z(N%r_VSj>r69DD(JZ5=lb(QgJ1T9&N7^#pGKSI50lmF zTG&4!*FxeK%j}$j2{3$j>FSBHkB+MWiu%2u1lK6b{vbC7I~G|zF8a54Mm+2Ot`o&zB?=`l>kD- zLz1oUY=w+J(95e>k}T;)gRXsg7E`MB=NdLsoAH8h(eMGo!}O2%^zF|(DG!c}IPPkD zumYEh`@jzo6BFh%#BYpK#0{#+huv0LUywUX|M1A(HI7a;4UG`3kjkQnkQr&`s%8lt z6K2J_0>(uQD^4;YTK4+__J$ao%fPQn6ayNJv=m)4T2Tbvr{)xqPGVY}^0IZ26eZ(G z+|E%K=*~FV_)wIKfn5NUVOn33|C$_H#Yk$#)B&sxEpQ@gtza`b>aY-=XcISIuHBTV zdHby5392lkHt#Lg%D|F&Rbd>duKB&Q<02-lETdpl5xHTKj=3zOX4I+KZD8aurM4l> zS#NIbWu>%{24Hyr?E*G!D2xS$)-${R$V3#JQ9DWswcY`k7^0Kxrv_!C22}?UyRQCU zx#eDz(mfWsar`GreEAi!I&)P0h<{OOK&!^KD=DEG>clS8~9t zH>eS$`SMpX>$>H`QyB@Yo5TdCn~*jZl#MCdxktkjH)kd@da`JR9dy$!G)bUch6#!&3$}0h|ktMs<>0} zj^{S*KETRXZ@U=_fhRM$fk_bP)-HoFEi5dP_~;cZpccK&%gfYOOW=R~#7XA!OD`=D ztR0J^l1%P-&4_@lO**v9W~0F8r#M&T+c4RhyjDN2&N3F}*ePG~sfd_k8sAX%=S@26I4Gi1=^;;ocy3`=ZCE*SX=8IzqeNwOA{%qCJcRizcQ2~ z%cx=luH^TMoLYbQk`Z&LJDDJn4RpHxd7kU?u{)g31G0iD#nif#tm9A^D9i3PVz|Kp zf~$@P9lBT@o2shob3WF7sts;yxI~fD+ulDdyOjZI3g@Epyel;Y$cJB5u07}P#yT$` zL@-*GKSDQa!!%b5g=gQYsWWh{$Q&|QGT|X?#?VL=iY-w5Bvu}F*!WZ8=<&lkvbAw` z13#*LKfDu$UX+vCF#od>b_6a`Olc$nSu>Sl>`m_WFEiC$n2pj1$FVXNFO<=0@cUnj zdcO9o_hS(dU>oaXL@>rucVa-b^~#@Vvl>zw!O;wTxW0OI(WI_CXZxg#^Wvm!WqZ__ ztYlUzCjx5_Y+PY|bpA6_Elp??VkCiug56)_F^w$Th(Z`*Beb1t&Uf>28X7ruM7AYp z5O1y>4fG>*GNYC&Vdu0O#hf*`YLA*5tatDSRia)5j;js1SUf-3E0xio1XCnayHG>x zjjS(&)eLiGMy*yrAxaVEv$`=a$4^Ci*aVv!RIEs}x-pxP)>0TTHzAfiVfiWKrq;q7 zw6q-`F5!k6$vPcVIvR91X}dA?GS0@kwNJC-=CrPjJjrbd4>yX7InUhGwj{Sx8G#+5 zWJIl@wEDC?JLyA=_@e-yn4yZk-T1$;IO6Jg!g%jqTp8ep2(x@Bj#HHaGwZ1aCH^>Y zp&O!AT${Pqp+(kZbFTSYQiD`S?Kz6Nf_bJTV>PuRk1+2w+JnmWg`aDPZ1x&ZtBG(Y zmuHttUr3uuHp}j{(NwxHX{{P}VwKhO<5^0G`i1q z?MbXk9X}Y%fpw>O1F+cEUpKENjVC9Sd8310r}9#;5lU(KA4x8we^s>Lrb%DPNvm#R z9h6(Ta7_d3#&jIU$z%)9t56GV#}}R*G8u~V)z^)Pp=InG2ujFuRZBqz&82rKWaY@` z`*KLN@x>aCG0n}T;~g6OzGqV&H`$BOX7_;-9J-Hp0%m}-W%nAGv}4}EeJ zL@b$y)MGSO0Zq&DRmW(rR5KhYs+eMOuR7r-yVR4%crTgzVVY1yy;vCFW|O4K2C4l$ z2x%d3(dv}!7x#FlIOjWkhYNIVMwxSEg`g`^8lR0+#6BWpUE%E9d7GD$&9s%1Ic^nm z^u!9M4!x7e6I(wn3XcHH^=rzuHbu!q9XRUP&^CK(kE7e2y+gP0l-ubh$m;qlE`%aG z#Z@%UK_2cxOC>AXn+OUlWd#AR2L#|G!>#M4#7aT{G>K5?YFb_0o0q9df6|fX2x^P) zB)c=-uwCVh zvG6M?KCxn{dzL%S4dvbiz$|=$R`=(Ygm<{O&YsGi4`4a`>D#4FvDH2G8R!ONFAxwL z)z(#Y8s9Rs47dQ;g~uYhp^Occ%ryq48C^Knl?RL1wip1&!(IU7;e}xb zmN-J*85}Xsu=T&iFI&a{%VEL7j?FTGuawA!&1@qJM;U89C2TVbkIc;9xs%Dlylq%Vqhe}+7%JD2L;YwNn3o%U1g)$eIN^i~OtQl*H zjb9Wnw<}a9LP~r0*kv8rG!i@34usQ4sXN*Zl+ze$`pIqB7~w8$!rGyWd*Iq+Y&*~n zFg3`n2GMOOXTk(EXqk1o*28dnd>a(_eKLkPwn*y^l`H=1Lnv)ZJkim6oExON0J0mV zOQg;^kuLx5k=_c`)?nbCkTnXyKGF>qKAN6>=reR|q}_GVGrSzL%FJ5Bbr&rL{o3ty z!c@4LHF4cH(bpvt#%^tR-)3F7%PKSA$;N9>Xx-V{cpWDfwhDh8xCXyD3#_K0tNXS0 zAB&Ylb)Nd?@8WU~{9iOb|IL@-pJ=A?F8?7oO-{Cv`*vy=`AW5MwieO<{rjgZ*yga1 zN7^@q80Y8UQ2Zp~O|1J*(zh8eKRuRa_2(baaTYR{9*eeoDUnC{}zz=C7(Wn{dLP+N0k**-HT{>6781f&^ z`{nN13D?pCP9f81Q-97`LlEMfw`eFc44ibvPE~9(OMJ@GIDM;(k+rT8I)>r6C#cb; zSQLvJdN#OxLo2~-P1-L2qEA>|5{-RWo^u)f+saa$w%saDT+u;urn-wyDpDvj4+6D5 zWh$6Qc7n;2PEyU`R<)M&%;L$|q=VX>R)&zOZ3<=miSN$bk;ahLc*hk`Y(fKZ+OODw`f)=JeJJ1fIN(c0}$jd*G! zAbMjOBavaMlcYDC+jMZM!7wuY0kl$I^~FC>6!jlD@PFcUi|w*BMYEI3UXj}{(AZ$v&khQcaGa_cG3y@_l>|jdAt_s57!TyIO_n!#GvL= zV9gG2^MP{ae^#|m#Oav+_||SueAoWm|Elg6aB(&_v30gE`rl>_Btqr}*48GrX8-A{ ztGelgvW)hnV^ORFgN2KfzBU>zZb2mFfSR#$Z4$=+Gpxha$Os~nzP5Nsm*|SC5^b1; z@Rvkliv+aIDa)ku>%)!&`MiW#zzyo~g%ZK-TyMUe&$(XQqnm0Au;^6NL)0{{*A-{) zolhGG}SINFGYzO2?8X^baXp}!O3r2f)x+P7noQx`lF5T}BJ6MG|Z13+I_l^x_wkTUEuctwG; z00{=H_JV`Nh#MMFj!DWfDstfQ6pU$)H5c=X!ggbJ`Ufmxz?qvA&jyn@_maGe?b>Zj z=Ddj%O@~M$kF95mcdd=(XO+xo$)`r6c1sqP?GQ|ik;jKgqhh`L{ha=6_QZOOUGm-h zVZ~u*4S%LvX?5hwZqFdOXXR(r;j`=Pz0LBf#)tun=GeVV@XBtah?TBv_)>}o%jMWu z#&JB@%;Qk0bg3|UgDWME4od6hdzw=D^h{@tT{1kkNUQJ^7eh29)o{SZqi0TgSzS4Y zm1kj!o>VB2zI%tK?Cuzs;dX%?*ubEQU(erpoQW*rq{|wwN(V7Z`8+4!k?K0T={P3Q z%k=}M?5a3MqZi`l0lu75Yvun%**P|60!3Row(U;Rv2C+sTOHfBZR3q?+qP}n>KK!% zxivHQ*3{tJ`2nZSUUl|b>send)%q8)jI34PeKj}9OU`A_6U%`GxKl0Inm^JUUbJ&uC|pl#l;-=x*i48d?-v6?#z4n$+QN+dpiS{b|iJouY-^{fc*#9 zz)wJoDFGqE^3|MdSd!VszU5j0kAJAc;LH@}s@buRW~1nFfKSSd%ZBput0&|r4=S`| zMoX0clm`1mS`Z^^K?ka}qVn+}|Bte%oW5Sxp?9yy8Gp7YF=DQ)9*xjgN*+FD;I^y$0X~6Y@7Ed~4 zGhA_FSoZKM)JG^IRtLf_Bu@L+p^!r$n59~+&^5ARR?kUY0Gb5}ZWc5%4J^P%9`beD=V`p8Hw7TIX&CE%Tng_dXoATy;d8zuZ(VGnN4- z(B7|8(Ky;@`#jo;u=ytM~t`~_izl3L0?)2@H8#pky_zB;);MtyoK!6(Mx1K9(xb7^Q|UgBFJqy3 z)?FuunY#XH2k4gUHA)KY8BVbRbO+Sbxu@RhGkM^SUGg@{G@gY&b*vIt(UTO=%Jd8{ zTS7j^8TdMrWUCJ+j-4{iPpsC_akcuqEWYXQUmQ}@1!P&i>D!CX_8^xwR#ouG^u^%d z1uIEdmz$nN@_TU#t+>GhHB{zK-Eq!Pb;saWe#=hQWz$hJ$EvMCqL%gs$c@4BX#7>v zK8)-bZP)Fmza{etY`JBmGsLzvOcws&tlqa3`R4v+eSxg5;P^%!y?y2LdtM^q>o;u8 zBePe^I)0$qV(BlRQBdR}7HXVXOS2oJS7We3OW#- zrTt?hZ@CNDn;NaI(P3~PR`Z+8e3IZrp8NZtx+~pDRtr(;Cd{H3W2O96ns<*>a;b21 zTY{V9yC%Rnh>ZS5r3-T{Glc6IFKqmQ`=3QB(w37y6(|r8{m*p$KW^y%HzM_aq@t3O z-+zFdNFzN`uxjJ_d81ND)PyPb9J+k&&_x1uij5&*J*Q1uz3~@1S6j$0s2`{w^en)P z38yz-3d3ub=8;73*7IF$>1*jTm($muukR0-JZZg_{9MQw17^(d$k2v-QSW<0KOhMo zX(8lcO8rcXfhfd=ea@4C-_WtaFNN50cayO|*^w*m(6A^N*clis!VRfdd_kz#%q3eb%S=t$x+vVn2EPX-g3jcJPa>Jh!<}H7jVGKOVlqR_A%3JTR?>_Ma8lh8S7oS&! z=MC+PHABgrja*PB^!?(VzU?H;YXfGUiEfQ|y-d>CwTQ{%=E>ktj#U!fb2N6+ml$T!9aZn65*Fw5u8$g@t$rRHkIk zy^Z#4A#R191ya>+YihZo;NLaBAlP8BL1%uXC^r}Zk5rA_+L%&7mq2dHt!$mCPlwk- zG>fy+^jnw19#fdDCbOmucevHz38~+@oo{GH_?ynD0GOA=dd`}LrF&F;;e~URJpp%C zsvsx3mw|+*7e7Hrl>aerC;9*t9{yPJd34?Hoy1e(_g5eml`%)5dp|YaYfQ)}C6C^$ z2k?zPvAV__>Ybaot!dy@})(Eled|59hB0Gz@XTt79?R#vQEjLX;XG!bO|rd z_?y-m36?W=>LDrxMw<#&Pe>?wQM8{@L70&;3J&6FWWg=!d5G7?>@=$-4sH`S4uL_r zgwjWgx(P#6X#i%4RiI@WPL~Dq_YtQTnSFWSzu04{>3%hg{)GKCQGtLM|Nms|e~%+p zsX;p_t6_g#Tir|@1_#y3vO)ZjVv>N;T4w?#CX#?Q%7dPTn0;e<_(LGQ4QFdY_@_#> zPH{!G0^Lfqj*YI-SjLaANYlIu)lx%t><4z(nx0i|i#ktgrgzPSD*8fxovG$-^@~kgC3INbqiO#dvm&h@^Xb(+Jl8Kh4SmSD0=hlG{DHfGRmdk=2Vp0uVQJ02+YFBfn zFrYtmT1+apxaeA8Z{5|b*4x}9OGvJN+JUkz)|F~h+NA(oC)?XpT;;ALMU71DBph3V zQk$A$jbT?A9`r|Aw!y}%Dtw!6YO~ZO_)JFEk)-s;?N~fLQ_hp028B<|d&Sw&&3ymNces2^H8VzmH3k z5vDe)(l2q3Y^sX*hUAmOF80c&G~-&5;wOkH;Jv znvv{lTB}E+hK*#3?-2}8;|joLc##to4Q}97V3XwNdWyQaC~sVpqQ%CMhtYCa zOXk9Q@{tZCW6}BHamfn!;TM6+-{2veaP{JC!tPPmc~+A%n~g-thxV-1X__pZ>{(@% zMq@2vQH0OYiWQAIX#A|w6^due?N!bgQO<9ybAY(u&>?dR==6oEA$Ft27Udt^V1;Jm zsb;{PXDiB(X5;5XtR=wRo3OyRiQ>X3!gAM4@lNYtUP`kNqwx$d3ZQ_K0h#cTD2nWIx*u z$vt?LmypQql9AETR{E4Mu>mej`!!azo`9SE`~a0wgP%jZ7y0Uz=@0Ytu>Wy~Uj zc_9=!>K9;flVhxn)#4xtn~%7G@82;pw6H$F{HnDvJFE}4s2|GxGiaToj}TSmo%#22ukHc>Su>AcrYjO+B7} z6b#<#CLtFj(}Jwhr*&oLEhk`rrhL@xVaGc z$B?8oj5$XP!r~XmT`sVaPYPtk-aY5cU>Z9lTZSWyRw%?z$V}nUbG#rFJ9i!36QKHs zVmFswZm8H5{J6Kh^Pc+vH4lt6;k4~^ zc0(lQ94gad4O7Mqh!ob&^o^F-3p*sO|8sdiLvo$&9?}P8Qv*#NFbKKUCcAyHX6@ z)M5Gd(!Tt@>lB0jU}oE+m%mfH?7vw2{0`y!z<<9*d^7M2I2#$5aj+f{OaiaB7} znbk}O5%M)A3&Df4sxd@jhsZ?#X}jS`x|ess@PP!W)=!eq9lIde%oIZamXQRR+UEDgP^J;D?qooY^UPY`~M`Sp-ajC!q43JoUS2U3OY< z(vQR>;j@8J$xVUyUV#*5mLg)7EMkuGn2^G2mGYRF==i`!ApmqAVw2uxkf;tQ7KT3? z=?DuAor9dJ3e2VeDS5WV8!>p>p9-%QW?rJH2bRl4etq368kJ(thNdNfRB8TKi=xrV zEka3HX_g3d^lJ~AsDVbi?bzbmD%-V|ldrV-{FqR4U2k_i1N$>n@jGm43ML)zq>OQo%%k3G z;=w5vdP`iyQ5qFUnpmS+Wux-TpQva%f}&cxRBA%76?IumLNPQQ+ZTsq#f@Z#+C#7u z?EsO3y1MEFNAkKLwfVOP%2lL_Jrw8LFptAgR|+!>!iKp{1wXr5SvLL zm1-7Gxaz}jYsA8il8Nj4>kf>qTa! zkv8QB%c?m|AjKp&h{amMTsWhVNG79jR_M!d2OxUCy6Z(N_Pp(y+VFL<>3FiX(&L7g ztWMYhUI#m)vM0uKGx7}b;uE((fBKBr`08oxqaN(r`>@Tv`R#Q6tLc^8TDNjI_I8HL zqYURez;|gbHqc7<>3|&gLko$2XeQvrwG(g9clXGG#OdfnkY$f^>nS3}C$Hdpv7iTT zS51&*7d-2Wp5F(5kcS7e*S7JyitQV}w_?5Lc;p*wu39!=w)zn?wC6NXR6J z!(N|RBvXd&6!ei1G*7|EN*5J1b`dy!A-zm>1Yt@&PIebGPj(Dcw{1*#0Ab2`lN5Pv z0WZ|Sb^z5NptLeIyfi)G!6m6}NJ9)wc4b(&{uBfD3g|kNHODI*bUu5r%;@(RnbLa?fYYuS*Ppiqibu*RNR;H z>N^b<7l)uE%IrANSM?1nQgrEC2{ESDeT(yL(Jo2F9X4KIJuimmIo3Y^z8KuvbGV| z(yLVZR2VW=F~tXOSF#bjeZCiJSJ7())sDPBX$IT(^x)GLX6);ma1*QSyRwLj8VoSl zq(A+*QiV*1%Ge6fq-1Hx1;rX#(AuH}>t{aP8{AA8NSVLPxtRx`-^Uy@u@wW-Nt6Q8 z`(Y3#H}Pc#A>E9EIXUDVsL&{V{|r4L0%kypC*-TQ3v$=~BK=m!I^)HaNeYd97xxIS zn{H?j6ox*ay}P_U7jX&;(8W62nsaPsl1>M*4Y`XU5LBt;P*ABi`-c*6h8}K4W|+7) zWNM;{(gr4G=^qmiea}2=niMowZe%kkE3U(`%yrD3Q59uUAc8t`zw7t#({VFC5?WdohyWZ?= zFueS3BsqNP)B-i_u0$1}aa2eLuC-1eb4g9X={#y8Mj$bV2nuRmOqBT7Ep`zDLv_95 zfH4~mvtCePV;11@K6Qg3%6GED<`%PdbNNdGihUsPxZad~eT?AYyG zFj@|OX93*ahA7qan*y>#9UM@Fr4jk=rz^d z+H4x@BR(neqYj6gIh0n=r~a|}Q#N_lpDg5;+VL=OC(SW-RY;Pmg(WyI1XF;q9j^7^ z5FCu>qScD-NxK=+<)dLE5nEXsC%8;cO{+m#LAx2$7|h?Vv)D4(G>T_?U0<6eTQcv{ zHlI*YxI%CF(Jxi=StXtv9J?D!yBQs;^#b=b*pE+m7su$lTE^L5hW8CIP{tCgQLnmu zcTR~DLK#i8lZcDA_`+o?%EHNyJB^gL7q7gIV5tdbimkBc#?)!Ez?!8mHfNmjIObu^ z#<1ZWqG4x$epMge=Q=!TF41FEe~7bYHHNV!$y};AZbOK-m%M$PYK>tzil3rQy`rFw z*La9;G1Na?Y4g}zhLxgC&#sO#WQbui(t$Oe7)dVWA~{J9nzFh{63BFzs^7Q2bK#-D zBY)kxIXa=IptarG5p*P8h0Ja}a`|EdXfIP-0vi#^8IQ>nL%hs`_*(v#)!t0 zVswYL1}Dx;>Jx^5(!JLRod#|i)kj>MI$}U(IZ4~znfeANiaN0%+=-pIhN8^&TvWej z)+#`zU0FSla%j||_oQC0#->@17#n{oqNTucVl#_`6VA+#D2zcctPlHc*N|&1G=;wm zOOajd4)KbdB`}r%Q2CCLc!WI?CgYKQC#SrU-H^r6j*IVHNYG+=iyg1R=+12|qt+z0 z60+&-XXG*1Q^0Gn6UuvN&2|$4kl!T*)9)1qo8DFi*X&(Hk+Sy%6+p9obazUyxQlOF zNB}~M8Nc7M*zb946YrNi&BJF;4 z$TU$%9s_hv9^}L^?UIj!xxh5hJk$ador z`atYb2pr`!5Ih!R38+Uy4Um0Qf2JYa@N5=t?U8aUEhuI8;9bG(3pk^0{9xX3 z#cC&l(gVKP`|t#oC_wR<_No1ZD(spL94I~Y!cmIJbI|HKf$Ah*r$!uD*|x{}dYT@9 zYIOY(dNvle0=En_I$8NLGDr1KF$JaQifQEqT=+|#DO2r`I#-5iE zv-4L+{Vb+^=TG*1Bf)XcgThIVTq2AD(W-v|b$vD#Zqz;E=FlT#H--Q)*p2AT9=xSf zaauNoj;XY0+O*KBu-iu=tC68qe<^!fR~_+)6+?WR-53fr!^}EP9I_U{FWmgA&@m#h z7&do=#0$bJ_Mm6SkI={Y_c42Hugrf3pf8~J-COvtixHa-g1u3To(5v)sW1-RD6aFM z$uDtt5X`^6Utk<~{PpUdYk&Qiu)dnE@*#Y&{*fzGY+;$4D)Wvg$r0!O9M2aQL7}P~ zi!G%}xaFKOMZ#jBpb`FB{OT#stN|Y$7M$!SzSjzhl>Q|`Zw>in&DdplKp<@l2ughe zGr!}?wJ6lBv`^8=PYFpNw#R{l>axW9gsn z1|bA#4K+bwegos1+7eyT`saRbSK2z%3XzaYe{#7ZV703Hi!Z=Yw$T&8Fvd1K6c!`! z=KAxtYvtgIC;V?g$-@i06wmyXjvb0K>@Z`?#>OeMyK}w5vl@>d0;v<+gW2@*o8yR` zZh!^LmBGl-axS(8;OPb?)Kc0ASPtIe&sE7;czT=PxY`*N7q(&vDDxF#Y!{Odg5poCc6XCAeeM2Wsg6&gZv|~KCrv<13N*pM(MJ!!uH8V3 z!VYYrqvFx3)B=tda{FglANi|@UZCdv?19U}ii;OL-&ON0=e0G~?wf{gFvozAFI4Il zh;Af@u@dnw=vTn@CpFpf45|ZUcp#+2QH}dKk{ZE2^Np>2(v>0BfD}i78bi#^Eh!u7 zh!FunybBLiq`i>p-Ciqn?8HAep^&@6%l$~HIhHWO6I?rbV<@|(2nR0&mHH&;YvA!+ zwZX%>;rK|_n6FH7s>weJYGW@qC7qt(^+OJf#vQR7J*f2i^pst;AY}Yxf{4 znS2ELlj_dOp=S*@ZiJ?nYjG8+PZh+!E|e~w?%hRDD=Fe2-uTI|RNOJKhBCSl;P@k2 zTrr4IxM2*g)m@lM7b|Usp!ve!sWpPU8}ti7GqXo}c@sSmWPG+W11sj6JqKNP@EPBL z$kg-z2dA6o)1aFJ+glKVK18>-&|#IUm@;ismbq8N`B5PpHsHEcZT_*S ziV*rPXsSoiYm+j4W=NVjz%B{h?6v*lR^aPMZTH_$_!yZ_L$`M0hLtq5 zN8+Y8WZ-v22@5U7KT@F-If?6!Ci9hhDJ444%{b7~ zlQXk6a2xmi)+|ZF>ofDXQD?E2v+3v|ITb4X` zRG;5CwsR}?s8hE#dt2nm;DaW_y3}QO zg$6Lw5B{sZ_=wHBp|C+39s~m$b8<6+C{IViEh+;mbH|o^<&8M7DYUY?c_=34ufe0b z4TnLH*=LUR(i}U{mX3cV^~%uZ%jfrOTdZ*|n{lS}L}-t1%|W-x9+B!jz z@;h@!E*=wwnn+;63IA$7Uawj?Vkzj&ZSEx`OGBG?0JjZ1N~5Ee9G#{xEG37bESfQ9 zV74tyB*lY}kogavFqp~*i}{&(%A2g_+dbvbE3@13l0EL3 zg*PVEIz1xr@}e+$2^NF!vPS(hWA#&#a&I2U1=3Ae4bFmhH2aiR|HEyWTX&Y%wkV(L zY|;&-q2w*Z1b2Cb{AYbN)%rNv_$y4TBrF`{pSom-P<{2*{M}-Ub~*v!iQpU2@);AMten@vIk?N}{(zT+*+@ zjz?IU0EFb1LbD38hvF3I=X+PUWC%FF-jpOSMHYEFTCA5Tc0c+yGTI5m?xI3oXrH3*&*m{H1?(8v}l}4CQXKD zZMT)}gooHNF$ZM8Z7JQf`nciHn-9`4rLUPTe`4}_%jAZX3wHR~EW8VKhQ+9no^&fp zTQSy-!krh0vQ7+(9KXGodYDT)JgBCSE|@cwCmVTfhQuo2p7BO-Bcaz;d;PPOh9Lha zoX*x=`-IdMA~iU9D)(kQQCv}ClEHCLcWt^1GgqxLnA?Gcx(v)OoQVlpC51(E4vP7& zQXn1hWYPWI2H><{sbcy$!{QfKGWje$4Y!)&z#U~3TYJ1?iDjf*q#LjA@JJJ!x+G-g zwa+xV`;xKtZxMM9?)RIG%vR}du?{)jG95;zAD(VWfztkETPuB%#_`hbEkW;`s1;%# zbWF{{!#ZITmRr^?BcI-y*yNoiXX3fSU%o07ePX5GkLxrhwlVBx8AutSGU9l4TNLuI zh6^4m<~SpU%?^|MQ^E}QFS0_vRPvqff!XNfV3YdK@B{fD!E}92a~OH^L@27?uGKh4 z*>NoJKAE^N01{soW9XBnX;dOnOQr*ftpibVVVRO5T??igg^;(hncAwexqfq9!Y(N? zS4I{zTX`Qm2PPM$R7^z&a@J7U0T>H`Xm0G4-B9UxZ(K}?YPLM}zIPnHUi*;I13N6X zBhfc}N~buz+hFaLJd@|Vkl5S05En1v5MB6=TCKhk9KL}Q9L?Esg#+t_+Fx6TEM+ku zJKXX>^-Q@q@pTf@;#2C&xxa-jF)~XL6xj`mf3rz2G}6+eqInTfcvEut7VTL+QoV=` z=sz+w(#=bI;m6pAd%kuWuQrj~%RldSq9N~sJZgo2!s7G9>F};M9iN@$XU7#IEX290 z)ENJiOq@H2GgFqQgSc9=JB$~O;L+!cJN${iL@(HbdSk&8?FlixrCGvcv`U2AaDdwg zGPjN-NeeOLsNPE%4a1@kRzuf=!s#A(?mjmDH&jVwe%3oGswh@vpevr?8sb1gPw&Wz zxe9LKu_*0XP4}UcW+Zw^kZzVmwrx5tbHNmoYlok@mif3t5*nddaZ?iacl(ZkeI6ab7V?Oy)a=a`Aff zVO7LTAaj_ga+m?z2?cP5+JSExwxKabe|~WE;tcUIcuwf?M~T~>D=2krmB*BgU0 z;1~rPlz0)-`0y*G=hPR%5<9}sE?W$LKXgbEMi<`AKe3*XVt^__;ev;paW2vv&5u9< z8SELRm%r{>Jjk?8_w4|&5+Jr^?OX6gzE=+)emiW=!+K)7GV>R8;EGt4(!i)7#;4wD z2uzfhR>Pc6vNs|;l90ijB+P37MF7{Nwym)DtJdj}Rj6IoWhb|Gho-iR2-6QjGSnYr z1CsLS3buLQ_)|7joc{SIMU(= z3GK;F_YbtLBaBDH*=+)ph2)y(K9Zt#6s>t%_<*LFw7Bk*AgN=&#vVp)C!TH`w>{M7 z*m*X##amhE-Tb7`X|T)}_&*OQ=o+M*V@x0*upc)F!~bnS{V~=zGImfhcKV;A>8F(P zZ_?6T&Z`UiyKzG=Nk@5-+*WDj(6*NGtuWOfcwo9@58Zm_UmE1 zuu%b%&x#8$a@*(-vrc2;r!1X)eAZ`rZ_>Ct*#Hgpcoxsbn4?qnMLtdS?5k1M$r+Cx z0=?b65T-FKGI!4Yp(q!<%RNd~D%Y7U7ro=pb)$E6D4JHGquRHCY@Jv5SZEs_Yog=w z|KzHPyGdqR9795~s4(J?3Gu+jsc(%37^&03$+IbGUQwRPuWe^@BBPm1ol~d>G==BPO9oe__g^cfCXRDjK~vCifK` zd@TpkLv8R?IjI0^)qL{N39)qQRxQ;jdHBcWD~w@_^diQ1%?`eKbhstk9d7QWq;iFg zdts5muFBrT+RS9{XRhsBXiJE38CeDWgb?yqkPF1fz|_!KxQcKs!pd5&Do#Zj6=n2o zeK@(wIlza<*tVBY-tdTiv@O6pfRfz5s?55~2BFdho`rQhV?eU2sove#x*}Iiy=FT)WHT z;C%de973baG$T{n+_GvzT}MrWK1H63o#Cj6j(w%M(#FC{p(0v!3sA1=ukY+_EEQSF z%IKaj&$6Q0%*G1)0!_pvps82ijEicj|D*f(>hsiD^tph5pJ;Hwx+y=dU*x^&v}AQ&QPgeJS-qX zvp9-$uiMTFJF&{`7>BHbXej8-POsG7&QhFWoeD2lu#kDRgA5BE){6M5E}LOAW!Y7% zIVJSnAaDB~VH7`7#DMoGK4$jGL7_v|d=VuAy!q)_h{p3L`zy1CaS87VZkTs&24$#b zfScH&Ue>Uc8?UZTGm;tN-^)h-NmhzoVnqo0N4ATc(K)z7$h+?L*p31w*TvJclpiAm zd#~4Dev$)Ze+YP>u&b~8`o1`(L0@?&r)4kDX}q3;O5gXwWcEUKej<4O>?um>vJ4S% zaFBy}<+ndJ3%Qn;<_3E!D;j)6t^-B2j4=z&W?y01Z~Yhe#SEo=Xq%yo5^@ft)47Dl>5Z{NcUaR+&f)1+pmVat z`LgI-$xx2=<|XxV#Jl=^29aZ01_~5CZd+V;`Jj-VEyZtBn?RPqkn0eCx2un5F(C%# zb#_axwpN)_`SfQcAnM^M?SpXKVnz1X zyB#wc8qjD+xsU!5Uan6A*K%U*oA&2ZX9LZLG$HQ2(hXJXsG~>XKw4z~% z#*Im0haY}}G_2L5Xmz&#n`~wi2{*h?$z=k2>a2dY6#B*&oL!F5th>g{XJ1%f#O2pZ z$Ge_`!5WpNczVVWCZ=lTQ#XLr6d3 z(9{EQ9m3GArh=3S>k6(4YJxSDT`XC{VNoV_eu0T61c79V^{N=uX;vn7HrVD37~f$* zpKI{&dk21)g%*1VSVYOSwuNauy7DHH^qMxzl`qgKv zkB|=E0r4HUh1VXR9-5a>_gc65AiL`}51KeyxV#g<834#GC=pyF##BB-5Z(Hq?FJVg zUPnvM`b%EXVC1aou*A%zq;R5$IJ#c>vK}<333+e&34s<&0xUt9^vN<3jXtsb7A7y% zqN2Ll8T#D+6>hAZxK&{7q&l?81g5lY23`)qZma6*qqWof*VmVX3QVZgr=#}N@u9^% z2X4pyq3T12eP>wM=8Irw|9Iofn%y_&>+Fzw(~G?8;<)3*h8=Tu;|@xA6fy&)+x3Ch zs|MgBSkrcP@>mYgEzB8)w=f6K^2!0+oIq}V5b_@$>l1bAwMMnR>c3H2wbP<)?Oni& zZGKIXu>WYJbHZ4h+rws08F3FuUm%^uBPY=8l#Wrrq8GSa$7 zl+wewQJb1HS3PBhoA z;ryeID~V9xm!3ij-J}+lFxLr~`{tO))K9bGyVV(JY!f$~FvOHJ@5@#sEM_1%qe9l^ z0n!pX#1pKSLVrT)}*2$ zG}+}0`H{b_-e7%4rwQgBz{@J zWe4tF1M!8urNwYV-0i}6+3n2ezIvCv&PsZ za*@9*f4-@7F){gedbK%ZDSV>tUyzgsK*lYg*(}nWmZ7Ko;Mp0x zlDFhfin3<~NgV)P1)*c?do}FSv5vD^AvuN9a3`Y^eBud}h=#iv`W}XZ26Z3x6usjk zMC=zUhUuIf9>gG5_J5Qj-Qg6gGPr2@vm$6iT^uSzG4gW^_-f8x$N$(BmhU(ZJH9Ze zR4x{bbW9*m!3H-TFHu9yLs0C~WO0fO(7`aKq(aS)*9%{{<5Yu;oCvX* zX-n^#NgYw7DW*vXs2lG30Fy@bn8e|~Qei*!sn%o=x>quPIW29Z;5^I^*N2ux6+Nb) z>E<)$YQO=E5S82)X6N)$Nsbuj&p}83K^D&ZBAUthdy1&P&cDF)X4y}|cj=YoQ)b}R zMrlo;x}B>h*iWe}ZCgCpI{Jy>#Bx~8Y?%_orszd)jGwy(6~MV~f06}lK1}`g?HBkh zfqJ%+QaH`*PIiXcC47_7WE|a(oIHGWU8WS0)4`oClkMlfE-L$uv}P?)jeUMej$upr6A=1Q#~k!Vs`^W(7a^`{DfiaK&`I@jyrVOs%g$PR|6S?rNF~u;7q6-xyjVuak=p+tjpls2OfQs0X zc4?-$a~?v`4*OEih;mQ;VE!skk$RhGU4D>3Vy;Sf+3Enxj+kWA2~8UVJX~1GF7Q>6 zM5dflE06{HymU59Q>PQvJBo#L-hm7&lYT-gPVysnQOG1;FI+TcM4uUJOv%pg_UJ$1 zz~tD6!s3H|xVT*he_q_A?$mnUa&_afuRiKiTNvPQwmpKix* zr{8h>l_tJI5at$7rju4LU$72iaeuqqUorf0vWfla(h^uErFuKjCQTLiQnkj#1OwcG zy+wSLCcm@)L@eCWV%6l854e;_hnU}8Gh*l7$D9PnfE(ZQNRhdr(tP=6vOvwSLSI01 zkxImtOYbYuoctSn^({h|j)g7ujrc1?w8{k4%v1IETb4R4TdX#NCE)B{DiZqu6I+dO zYP7OZLV){OA#bMOru6YOz7{|=%YNC(qV67!@Bfi~Lnmntk0lxdnlw}~I#4pFJXzu> zOstGII>4?1B(>}fXB(g4oj=|sws1yalbLjxxYHy(b`1g`Cz(foa)%=EH;fjIMhGPXmm_nig~bWtvNfm*ES6YJVlPN?N8Cy<-mHm~X- zO>}4?Y7`;WG$C1HJsit6du&R3>j~uA1hij!%}(nG=g$PW3%i>h7hR)~hi|)y2P@)J zx?Frd=mdG2q6pf*vL)op2QRSlLWqXRmVk3OJW^K}rK1NHlY}c;V&or?x;!8}#FntzoAo%wbQQfOxf!o<`05k|}Zyb0I<2{irD%z2!o%W*Q7$ z3N3|i)sGsh0v~9ENF&lr5>nJOA$@{gW{LY+jblxRbqMvjXR*4xX$S*JTs5jEMi4E_gTzhWx1%&Jsgh z-$xj5aZzcs<{e~01Tih_axLPd?bq){l(0uUxIUyjnJUkz7eUhn=X~IxIix0!t0#f~ zVH|O%W=8HCU42w>2HhQ^du%yZtS5K#zw!N?x+ zY>TJgSM5$_zjfst6vo@Txf}B0)*IM40lXq?kGO((V&;0j2zICD9KXMycjxRJL%y{1 ze)#{|=if7?b+@CVizFRQxHGH8a|?COOm7v%R5=0!C1a5QqUL z1*F0&lQp~JUw`%xM(h*tO>mF*p50I~*g~AQu{J{N=}yv(bJs5k$o_Pc`2gKwM$Hb- zv2PJcrT#$J(p#p$9-1XcdDlp~)@kh4gmBb!zGUU;DW!!!8Kp=kipAX`^0TX6YWuyJ z&KY+T_|wvg^nXRf!Ge{nrJ$$at(Um>RutA6oOpFucmGb$`~ZpeZnR-lOl-j_8^cUR z+t;O|bh0YP%9G)^9$k%0p<2nt7h&cdY&qe2q|;8vCJn|0bYipF4(B1C_qJm$H7HrP zSgujaS6*L`jA`fZu9l9nlFo(}Y!qBtNN~FR2BK323b-U5YLV_t#`U*2 zHVY8+N)C~TPGLs8LQy($b=LIxgVDS7a&C|Yp|ZMq%~N!IpHh&|@$;&30q%Zp>kpX} zt$Uwn*u_3X>18p~N{?K$1K3^^LhFpl_u6iMs%mw|kp!|@o5vT_&tdC@NqRvjF> z?6Pi9FN|uJeL~w5TV}eQzKh@&38%kuM8!G9;UB-p_e|y0vx_i%V%A^D7lXsjk1)+4 zzmw?pQcoR7j^IBW+k^FrxL+`x_;-``| z%t=@w^<85z=3e;tEJEs%^A4x|B}5S}d71WvyHLnd&bvIM-v83qj9c0{+p`Lwj6rd?6(WI)G8#AwAk7{dl ziDK$26%LU<)nUQA(k`Lo4<=01vJ9|^_=+EH2>VVk>cgl0Q+mf< z+WbvCY4*ccmtq|cP3|G)QiWao`roytZmP##od!ROj^j@{rZnfZC1i@kj{TF z*1xB?|IZ=Pe-pfg?Tk(S1xGcRT~+$ahzh<LN|*31-HR&95i2`xzkzQ z@3IG^A-BZ`s4j)BpReROYOy%nLa7rqYgKXrd^oVU`3(_QQkJ1t$hdl=ID@ApTi z{8Xg(-;?}p-_s-i=QRI+WSssRIn|_Q<%V*E7F>d=%2Lv_xOVMJ3@6N|^f0$V6EzF0Q18ERiCF}}@0B3z5nma{C4!TZ?m)Z%rb zy`HuX*me2@!eVQ@gJpUG!18w4{dxDWr4TE({%8av*5N)E#|-#6I67Z{8yzj@Y4D7A z*B{j~fx?&0C-Tl2qL>l)qVM6L8ERG;KhQ$pBJrXhRof^tR~Y3d2{;oL18wl-9C=|1 zXkgAs?xe!vrTC_#%!cGWUn}!Z?U)%JgUvoT5$K|3+|_?1rnhbPk2~IDIG&=ddi{Ky z=pzznOWFn~bCOw18a3E3J;`q;= z*ll{kZ{u9Odrl)&)&A6y9&Cv$tbU?8VJ@>UaJ!|DiUO-vIV9bo=&YsS40~R};MfEA z%7WMA6z0UR=x40?*?c&w>#LmTEQ^1How}~ch$^3Cvm6`C7-{!s>T7*j81+GFxwe=G zRi28t5+0#KaiBqATq(2>=QcJ(YkMdZ>P#;V7~HL9XSf{p+K1U&GGAKu3euGpSd$8| zubi}uC7_oOya?Q5#TFDC0liZe=dXbDDw1oQe-gl3sV6WdfyQTq>0#mGM}$v}sb4No zu?R;)1=2hhFiaHsWS6qIX18wOHLw6K2pXL-T3&+5&Na0%0a;{?+|4^`#+&s-_9Ys~q(C%E*z`%sQj~#+f-tU* z-PJ%DcIrdXwG{J{i$iOqo$}K~xm~v%7&hl`_~4-n5zI-d`u6)^!<&Ge@#OXMVi9h< z;1CW5(ciI~a{Mbp1T@JMhSAP%cS-OF_D~pVPoGi!W|(4hxIe?EozDmIoV{bMxaIWo zLVJi~R4w}?G$RCZdvv`E_N29!Z_rGg-?98=>kMWKqBG>=z;<27ek*Y)55wJ`uEdqc zW+9)Y@=A`&a0Q^w9zJMR%=#-x4%6D6r1$H&c+=He!3e@&3Q@Blg)25G=QjxBUC3V#8g}TO5x@ zQfo5y0@=?W=WZuaOG9;xWUaYHz&%4r`zn)EUK({~Hw7fpvNp*!Kowk^xDvCfVK7$h zsQn_}GS_OiIKe1&d--sic~vEa?amFSG$2FEpA(VCW(Y4Ok9xclBOMCVon^Dn>R#0u z@$E$)&}w&iJaEcuO*H@?c^P)qSjCCkj=LxSOYMf#hfFRhEAnjoG@&nT|}J73~A(z zr2a&h`$f{|j!NSYEg`25657HM?Fxus%%v7uXo5@-zeJ%Yw()O(zMKd@YcM~xW4Njv z<~VX~UfK(BO51*r=~v!tkL|TGpQ5NLd2kYqQT!Z3W8OCS)Sck}j>sc@XjGdrxNyCx z=*qxv)-4qWbjhKg-pJdapOxKUn&D*fIzi$huz3X+&ASKl@w3J}NVORlo#Eo!b~1)t zwLp9kK`iUg1n)DdMhK<`_Qow>j-r?uB9lf*)<^Fm%CRt-J-=k^e{q)T?*Zmo!eKYJ zA&#_0Zce>Y)fObR4=!B*zxw{f1YntlBg8)_p|HFNyk2AZhWm!r!xQX?b4uWz-MB_% zV&>a$+#I!%7@U^E(50bmU@7^v548Z8=da7h!MUHv39^p!ihY&M(R=q`TDK(Td!);I z!P?%Lv2UO?UZ`Q7iMv1aj5<4N{eQX2qDi&j@SDarw&%ko^3yl^p=2`h>?C$yAZw;< z^exaO#-onnt|1^B#g*Cm$q#DQ7tyaN&#tP^GDX1y`9eJ8+^Vdq;44TLl_}%4{Y`@m zf(YH1mJiqL=uf?+Z@t4$dgM!b1k!jTLa`6|^q%PP?Za*xv-g!+n0L>7y5dYC?0Rfl zf$1Vw!DeOS9wSXr+>=|9VCX#GhLTJRTl=%aDUK$}M3rRa%||YNODDrrH$ORnHu+%K z04=WG=OEA0DdwX$^NS%P=S&o>rAtH}Q_1W*A>_Z85ect*N!;J$%9DS9f&MoeimV8m zh=rMnle3zmfxW$n<3Fh+F-lh7I3QGBVS>N(Rms47J=9&NwlK5^Z%{_Sg;0{c1BuxE zWf!jXc=d6nJXOz8@6-{2vm)JZMbU1}vXV2DS?5#V>8IIFSL-h?XJ>B4blJ ziw+1+QRxF9a0qNFE`Y!a5(H@z%Twj$x?+P2L6|l;q)ZHoF)3XWTs&roTKq+YHIJHwBgaz^T_ zXDcU99@Wq?uR7w1ic^4fRkA~o6?xMBfgN^}cB-64S?NJf8Y#oHZp6xt)+k4sN)-@g zO2zKvg*wBYp~?W7mNA7+Z3@^ss#!OoY2TD!B~b6|g*sDxJe;wE-vKx+7Tf65uuCOb zrj$8n-RHOtX|Gz(!cN|(4|!gUPF;KX7~)rN z1IFoWHT*6o$zO*{L&O^@AV1)wa_B!yj!TLtj59xlA}P!}b$CFkQYg9z@32-8DA~G+ zzDj+eFJMCmCZx-T7?YRhgJXbIhaE+5qfjgSLsZgBxf8X@eiDI^xj}#Isng}{ z;#4Fu?MEkLqLr$<`GWlSWq8vRiP-zS{7}BT8`l4A8UBM!_3zF`#KhXd)x^=`Uu!XT z(h^t@F}P}x^K*dE{SHV3!C})N0!SVQQRJSLhn?GWU4y+SUF~igWWPX26NKwvyCA>v ztR(> z*vm7*d)sOl&&*G_T9Dw#a%cxOAvlD@ecIT35x5&PR=*$r{gJf%l;O(x-j$f&E@pxM z>yi8i2=kviRmsH3-p=;FhQ)JK&g@YCk=vBBI_11FS736}R8n=ja;X4LMLZXFnaaLu zJP$6Vpv0E5q5GGpoyFxbR)HT=_TBKkd`l8r7AFP)l}bU$8x$B6P7LKC4`?bUClxtH zjAGTv*Xh#ZeTvKNacN_`N?|4n355L7{Fp7i2cPP(xe%{e(`NczC-|x|+4Nqo z{iFpeXAVMgmG6ctZ?BbW3A*FXo8i(U&3iPjF0Mx_Vx-0;)Spwxi(n8*BYoh|w)7+pwUGhYCzQ$ac+klQJ0X<}~a@w&01Ybm5zXg~_& zVvG0)S(=47C+yHj26bN2U_>?3PMBayTw8sw_~)42uj(uz?7x_8p9#Xyf0@$z(48e% zlZDDev`XB8HehqCW=n2dfMMT^N3ES8SDUDeJrJJ-mmcaDMA>z1uAKKtTRX}N;)Rg< zVcWlWePwEO`;kKXzxW zoaVF=@hf4NO}5DfbFBb}dZT$}CAGU! z5794lNg5P{UE(!##fh??7E8oV>weCOf71=_LSa4kD>+z<=S~;4cRQEytxqv)&|0K? ze8i)^@a4B5GRNXLgRSlrb;Y4L>`^&xsBI0P|1d@6*<PDA`Ae~#`=@rH8XZ z=A%VBoJ-H)tqoIVN-7Tt-vVrAs6Anm$LYzEv_GQF&BnD<&qUZctt}zjoCD5*obNa1`3&Rw2%Ss0$T0Au6Gd&u_?`TQK?zYY$tU20J>QF zoW-nE5@(WM(-@#86C<5?!>*WXRbE-H#4HXM%EG7zhMJ|xW1&P+jb!bEh|HD|HKM?K zhm%Uvgu?HO`lZ?%E&Qg~u{!lm^~FOKKgTCwmRTuB!RDDaq+#V6YiYeIuxpYMyRg9Z z)^rJp;mu^FqtnukLRfT4$g`W^IvI<2N^zI7`7{{&3p6WF01mA^`KIQ_#W0=~q?7<9 zc|2Z*ePUbe?0QjV>RF~W7FLrqJYj7PGJhioW2|^%M(1-!<^yhLu?k0e3S2boP|Qrd z73$hua#K|A;$5SOv0gf~KMvw@T~)iRh18zcrIET+y2FZS!}i*PP#wK9bZ5-xXiN%c zVF9=<)RXJh9#44CHaJDyuKiFXFS^DD zV`=g+qWXx7_%nSnDiXSQYpFe)Nq=+e&jg%o`kZiaa31H7Z2T^oouHY6&}lz4;6&cw zi8F1y3QK$4+ZXJab7svrFbpVgQEVBInbOX7J}HR zA7so4v`HN-MpGD!Xi`luX-O}j(&eYUMAS2l`BGolN0xa-{zFC@K&~Dm#@IIm@(Y>b z*^G0LUp$##B-<~B+{1cl7%S#< zPd~Bv?vY6K>Miy01L3!rC)}0?cO2QYo{0;tjj?as-aAs;3rhAOzk&Z(bi+G__F*@2 zQCz|y|2FvG5GA|p@4u)hsN+e~l1OW58OK^vw~{5DZ92~o<=!9y<#G=uwQb=w0uXu23=t1GD@a*m0kq1Da_Hu+G! zU~3y3wd;-r8O#YzI~98my921#-kLi8Le|`-5tsf=&2A)&RV(ws%RStw*lTC`dyJvF zEK7}LZIs+!X4SWJ7`fNCdIB> zsG9FHo8x~uuZ8VgO=Rqh46H>=TrG@D6ddio8!2at|5E2elD3rR1rUdy1WqCX{ryub z2_ZiPG!I6x^5$4`MlrMG=r5w>GtM4*^d-{w*Z8L(zJ7dB4$DgarAdBGY@fb#dvd*E z_xt>Og^RKWrT|-^>%k8o8D@i{DA%z0+Zb4S#7;N;g|Cv6YSLyyW3GkYumK(bcNF;K zLAHD25mLb#J>89{&XmNd3{bVfe;^G}1C?q(VcufwR$8I3XB21Tj_vEs>1#82rkjS& zR-QLka+lrS^CoKO2VMk)|+@q?YXqRVEfAkeFceHCej}Q7CY$;eFb$c)5=?9+MXoM+vPDd^EGMS zcp934ajEz$pr1k3sWRe;DS6%)DQ`vYb3z&@&bEpWVqH3#BJ-27!I2LQlrLhx9(hPg zECqh-XJR=)N^1b<5;@3$D}Av7s5w3@V{p%@xz-R63O|&!JkFR;hN%JaSuD%wPll9( zW0h+f+3Z!>7wH^R4GDcGYYa(TBNlb+ zvE|`I1EKa%dDdppmqBfU6fgsh`7B8f4jFQtR9jAZk9D3sVg@1|VgY@iANYbuepg-+ zPYLMyP_6k)qQ3bz%(ucZch6`sY6%2Z9ibhyH{iD@F&qhhSU1IdD{ol#3x{|l$YS#L z(t4tLKM(l-dyR08oT@*MuJCXi#*$G=4I63|ElYj2X!3;ld zmBo~vtJb^C@ks%>Gn_KI`h*z~EGS4dsM~4(K9+GMEU9O z%Zh!DjA%u7OpfqGzhjVGG2h~od`*tzVS3~x@Uz?kkq|Hw!ukW5Y#Zh?Dqxwzj$tx_ zAHY&$sxX%uGDh~2!HThzn=14Rm?@0w!v;xXMVm0j_PT?kV9FRXMhM~sjlz~PrjPYZ z>SG6uW6GE@2KCB-H(*ZG65=UL>%#}N!oq^zVX`u|;C4bF1ijD$gW_2^BaQL@vNuS6 zZtW4p{L(%qUVL{-h-!f{HDwDMq^}S2qwh`bnPYCLht2d?8Jtwt>M?T-?YMamApBvR z%#byTk(eQ*RbRH{n1C?7XN^X5)h01vdq8YlSpyXe!M5*1*kncgJDy{9)pTe#K%&Li z5hw!@HW(Oce(MBbzz4~CW>zB`6Q{+YF*AJ>t+adAK>dPMdx!B{P}qhQ8G+P3SHS(k zA1WN59pxfn<&{VZm*kwoNZ5tXj&+t>g@b;sW9pua8->Y^vuh|CPE*W7>mwk%$gK}H zb2e3?#YjO72QmuudIh3saKK>Ql<^oYD`AOK9$L&kg7Jm8z}%`Yy0ryfqGaZ_*P|Tu z=b}(ZCr>9|9@Y^^3wYLASAi6kHTIx+5uND-j!0+ZtD+DAq{p)1Ncn<71&oQ+3da4= zUH}`=Jc99@KYxy4K$zyRlxjDYUS7C}hX{1MG+9-rBY?5G-C&52-v3x5q#`YvZnLg? z5cajT6}y2lqi9nxFcr-$p~wY^=8om&eN!#8~F}`X%Dki z84tn32udpeo)hjO08`b2a+gE61yfF%@DjmjET_`c4)e>v+1n(9dKQUI8mA0CiQODo zT8}wbJPkZXm;{HTdii~7iSti1fvJVIVb*i}Wx_cOdh&Udcs)a=UcDY~qR-9tvzJ&s z10L>IZo>I^YRY+;_}Fmfl0M>F1RS>#vt>>x`utg37SzNBBAqHuEGmoaC?fQ;VM2h5 zD|TRlsvp48b2*F2gEqVOGJuU`)*@WY5K1@Qu-lMQu4ozuX9ghy!slW@XKodDwTFdK zI2YE4_QFpI!MJgL?Xcl#6F|jl1JsSxizV#NXaDwY&=u^y8Wq!yh;X%&BkX=oPV5>~ zB47${=YQnQdVFDj7{Q?nZ@eVV@hIBoewt}OfUl^OZ`DcUt3pAH=ber&bFqy?VTVVk z9E!D^g*S<0H=$?E=%F5DPKwx!kPuggP*VZbe||=ccO%mCCpV9?9xmtGZ*|V@l1^nB zN(_}Go*OP2Na7NkwbPOlw}bQsVs!()J|bObn?5^S6l1{TcsH=yt9MF?OdpuTxIhVA zWS+!5~4V^(eNcZE)qCSiLb7=u4i zn#gN2s-5YiSb^GHa_2tzT4Oa&HNKoQadc6Jyzmo@8H>iOigtjkSEYG5X$rL(e;VCe zm&&*y#3uI;Nb)|D$r{)Dem2p^N3|4Y=rH`my-ib8j!gheast-ZZQd!Er} zeuxW)sgUkt~Z{%hq)CHoju)R~VUTmk|B^DExk7E+cp?uSs zJnC+y7FG3p_;J|WNtHUQ-<)Q5^;3IHGwIL+pM>nxkxv5c1&d2d^b;=ij-SS!A{N&i ztGYVyXI&=0PVpU86@-@hs;@Tc;rQd@14gwrn!8PV8C%kBY;pTM`fJZj>wBzFGlE10 zh3!FYlcP2?`J1&)YZ+O_$(redzVaf9?Bl(oPJ7Bk#Hl{#daR7A8TjO^&1&@EBwu!S zH$_H+Np$1zSP?}^uDczx+A&H^CE(&Dd+`9?fbQ}3_h1QN1EoKIy*2JFD5Ae=_(Hbi z+#$p4Q^w6N7ee{O!rEM$S>R{xPzf9iI_z#>2wc=5!fxSE=wR$nR2n<23#)Ehoxy57 zQ1vzI6vKl`=ZDS-ZC=Zulh}|GJ$c78uW*VaQj#US)Wj6YRj%6mYT3uzWQzKB`^@qb=_i|h zDldC^kJF=T@Q1S+9j*FN?Pc6caUa(4Ctvsi*BMqj1+7bsw2c&oVr3rpOMB-khKLi~ ziwKR*)xg0chW&cpb<97^9>3@C{XDJO;=4BMS%RQW9fukH*x_IId*7O?F(EEdZ>85w zK(MHz$`aqRg{U$ce0pnzIRrH-!Yj(Upfg{@DxgZe=E15JaM@D^Z2~mPqfPIQVNI7G z>8#OQO`UkGDdTp4Oe1b-pLQ-!Fm8`WQZH01x8?Q|GrT$S+5rX+>fRqO{sA&>?8{mE zMyd&EJ!;_Y9CWYzIYrO$Jno#~8V)gMKK%&Qb32@N&kj6&FRGS&Cq`3j+V?f8M9J&9 zlW?=UDJYa{&q!PYszI8*`>^KEp_t12yFff2ehJ9TG0yQZ&oanFC?gajumci{%f{3ETQ{!`x~9Z@Zuzr z`E{n`iywdMq%towDhKt$kn-9NJBdJVOo1n&#_q6ons`i=+T zhw+jeL?Hf2L6ujA_s+ZTm%7GJ)b!Prd_^Gf;-xgUg+=AZpL}{IuEdv@c>7{Rl_xKK zk(Y4$f-<_52Y-{+9oR=9`u^s$;C}u`Ex6oC9@%}y_Lf1U!;DxRcl!1TPzdA^`wq-c z^PHk_-hric$KcxJ0wFQDe(FI1X_IG_O<3!CU~WN~(|r*9Ls1{EBABouAfC5c%bDzG z1m=AZTdJFwVNH24(U0Qjw;Pv7#CuqJ<-3kyH{Bw=Zx|&WMFe)XSD-n<3SJZWXK7@3 z9^vn>9;euDV=~5|mH8gg&q6qtt)qnecg8rR1B_=Y#bg|~&S;)bwuit17Wy5~1HC`P z-i@4(?(dTr9@|f15l@mGdb>f$1gX#I1!|D|&DfqL@$5LBDe=3Zd{PoX!rdYgRj@vd z@#t8dP4Te8zmVowg_m&Z8XC zGdfNRZd{)^3w91EkVjYQERaW87_N0+-`iu9igYCLPPE8k&{M$Nf8;m%L?^*`ljo7fuwgLo5a=7UiDOqmHx(%s^u(q;G}v7qoeq z3wH>4{hCgxL;Pgp`CM$9x{pwfU4Z5!n7tm1J)YH?^vD3k1C2dtxghBssFvKW7yXuE zeT%>!jN19zn8b)Zm){Sc{)1Nm0xKO}BOPp60AydE?>v~S4koq_&K{Q!j6$CyJ5avg zVg<%*o7^4RHnhPW1_1N6jq44r8?3d1)&i#+G~EZ*g0~sWv(3ALaMh1d4s%%u+a?#c6gvmXe4-{cu zeCO|dyL}=bP}~f~4$~_vK+X?*t7y6(MGEa*pdy4K<@dF)3G=&zLw{V#>UASChHoKj zpL|M)y{biE9u3Wo#$fPKGP=8NL=QtU=DX5~ztb4`b4p?$Mv5)xulqh}DS~&+RVW6U z<$k;5&g)7?mUq=wI9)Z{uq`ULzN?h>?LbFJdg`aXtTCkLB1hCs)!2TXF(`L6F0d=A zvK^2EShBJCWa=wrQ5VIZi{=^Jk<3k*s^xp;CEN+IN@cUy5A>Q<_=QFbUMK1gka%VI zB`6Df&V`H+JIE#Od zfgkYNBtBSlswmen*O=Bya*8+B z_MEF8NoB33XD-&98pXW=9xWN>`7Yox8}d#JgB3%k|8x&g$W;R1T!fUi`mS1qJj1G+ z@-CmhOms;ZlGL7asyj{j!2*|Jr%@jp@|vN#O+LWAuD@vf7B@kDB^*Kdy@SpHjgNFE z-gf_ovQuz&AB>Oo<3~F8j~~qci?Z|ol=y%2+{$*=CKlHJY_6L$JiKupe&;0^OQtSI z6b+E~MHH>adLIx|xk3)O3hi^t)#U^afT~MdX%R|Csxm_zgrbfqn!}(f#ipjBOXcs> z;{ij>phGv7lwhDz`uy_oc`CZfFS$~DHT7-RtWkBOy$j&4-uS?~%X*n|JLKrj)BC)x zFwzeLf3JZE{at}t*s>l&1Gv{d8TyIeg01GXM@6r_*VlwkIY`do8<|(u_B$hw4&Q!{ zJJ%r-XW8r88PFetqrGxE#EvjA*S5CNlF-h6Gn_%cJ~5pSQTe++B=1omhP`?o{%O5# zEJh2k5~8)yG8tpm`ulGTukE?Zo-4~5Q@WjN%>Qy;9>$Y$DU z?*%{kcb=aRfbl%^$irta2!vBTR2XyT5C-5*B=%yq62uhkWEaTu*v5DgpsJ#izMIW%FyS7zaEF-v}Lw_4L{xyY^HNMG>#cF{;~(1>Q45{@h6pT%<}a#5Qgtk%(7>G znsf2hnfvz9x;wAmdJh3d+s*gy{dV-UqT20P{MiQjd;$LQPT=Vp;Q!Nh!>;@6is8E& z1=lpm+=IE2y5d|`JTY=<3+qIFE)W`NyQ(_id7U5{ZXl_jl@MPz zK9H%th>p6dQYe#knf{Chcun-BP+}0vICS&3uw>_{P|(5paZiArX28luZa zUPUwFR0Br@C5{b14RJQj?3Xn45-X7~9482a=2aeuxGhN3pp81qX!Rqu)impGj$)Ox zR+p47Qpt?{jJeXeQ8D&URad=-9&oP;)vTU|KN1PcV5MskEnh^Mc#4*=!DmdLL6!w3Lg#bR4NuP(22hhVxFGNoo1yGxdK4 za#ZheDff%1HH(|e5i3b@mEO|pNWLGB{uU=0+3aJT!mDhkhGcow{`l~NH%Hn)Fe!?wR>?B0MI&fzQ^8QPj?;?gRWofi_UO;!A5p5J;I z3vBdr%GJYbaV?-blJ9U%f}AYFi&+m#r_pqOQFdtCnVrka>Wewa24mHynuLj)h|rhf zH8PR9de=8=I5Ic-MqE*E^*?8BqZMZ36x14Ht9NnNApXiknQQcM3aJD;z8d%SOhzMs zuio%kU4$blj7mhVNm=p?1Q3!KhMBCCnrq@AX9JQd9Yf^)BrJT^L?rVi zsXEiVA+u&yh0X2v45?GL=CxBn^SC;_uVE%s9*^|_wRlznNpL4(0Fu*Dxi@W2Hsp{9 zAE$RDq`Y%bb+`oeC1+C(^C5i}@*%;?5YZPiL}BXP97;LDd|#r+Fn{`6VL@>(Qy0?I zX`6V3A^@7Sw_l>FP(Dz4hdGf7Fq4O! zcx~mL2kI42xn8nlGu9y>#Uyt>AZaB;h6?_StJunhzHt>djOr)SjeR=|@s8|^*DaX( z_EUA?S1C#aXC4S?3obp0=#4LwZ7|K~o{gim#aLb^?X_8r;|>SeJNjl^9pm5Q>A@a? zsIqqu?TDEdt|}w9%vhCvQxMZXR%(ci3y^fE>miKOm>cCssATKqi+z@Rbsf_o2vW~B-r?}& zR-*)~vz9H21FQ&zQ)rE87|3X|Q$c5_=tDh(h*#e3NY3!f$8B$K-a-{d*T!C z&pclaC^0hLK2(y1!z<_kw7p2)Dt*J8e7QkJ=S#yn&%wd+yX7#$q`1Q*$Q`h1ZP!## zal7-#d?3M`F@V@uAqkqA;jhE>d$p20LXuZ^;V(m2v;t(O%VvwJvANvI6sA|7sc%^f*yQ2ULTruj@5K+(bBj6YXi$3{+ft9fN z?MCdKZ?sA*S zb#VQ49{uX^Nt(O6H(0t`2PnXG7*!dS!nAzE{z9*=EKwFJKvnul7&w6BwPRdH%{CYo z;PEf@_+# zk`6Js)h(2^+(2sBk9!~shJWoec>>CbTQ3Vyy8cfZPSkj3Qd=L7`j7JhdC+r{7ulo~ z5fmNenE*<1`e+z1>JY#)5p=(P80G+xpgaOWK2Xolk`ET!-y*~F!F!&V;vcO3AgO{>tbJz3(sN?{WJ2t>qdI8|0`iv)UKe3-NOH4{ zeXNVNGM($`YsK<(P|<i+o4%kYy zA!h@3POo>KErI~Mg_121&eh=iEGV#C9B)`{hMvTt?M)X{DYuw_VJ&uOWEwdHJFbuD zzDA~W-|S3k_`qczBis(aI*)QAH{@>5-u75u$B*?sI=N%Ae7ATap3&om9p@Feiy4Tl z9o(c_LA>tid4j5aF&sSvNEbV%^|mzo!&#SN+ihP;e&_~Q51QfpQ}=DCx(z6nkqrtc zH!rieAOsjn(jb^u1Mpx2c1lJFaD6`5KICwLAM}h=DrGeL{tTGoznHo1_p9|0cmpI( z2@}yBPcb5p-ro~HJ5n};jBJDcy7XE(w-*;FbVdbFV+FOUs_9uL(qUP@F|QYla|Ri& zuwt>%_A`Os#cCOA(;2H+>^Wn-yHenymimBQ&PDtV?Q&0^bQmGt^Gt%xBI*ZsgTd1H z0$LZI^M7||;IFu-GX7I~cH-%t3L!Pr<42L;^-1LAN<=4QN8+~uZ(^*!bnV!G{R=6L z&49+)pjKeeIni|S$#&j3?Gj}h2Jz;-?ejhKGU*Kt@65&Q@40G3m<+N_sL)oh-3g0c zv8q_vbbG!nDtf&~6ucLP*=8ERvWh1z^$wKbBjs;TSoB_`F}-ir2QOS%A4@V?UQo<6AY_xq9{nBBwYQ4g z>=A3~JP2Z2(BShATr!ReC+=R|I`qgHxd1LWAp(*@x-@xX;%g1m$bFsMi1;=SIo4w! zvoB9Tbbm19xO+7uR(GDr&|YvQothXv-RDU#GjqT!O)+nUG*3_$E?CJ&R{Y`e(pb`v zUC};?SL`|yCddBTpo|na&AoBmTqf*h79rODnO87p@hDy)d#aZ3i|Zmxw!a00I-RTk zD}}*NLIoXu_%dUg8|bsoIN&Rgu~vdPOFx#?pGMW1AmSmzFBcYT(>ALjLVnXdOg`z%EYMVg?u3;y)}dq=pL)k#7!Zxagy)%k+P|@<;+?E5M|C0^}&g|0s|X zCTE*bvLM9vHwa~T2+?J^8#SGmzK41jSWLO!KLNbe%GOAdzdYJCEHHzFk@+KOg*lkhZ;O<_470N`odnH6tP_&u>z5mc9ei=!tBevEn7|36p zsXF?t(N;21EUG*#wKpH10@B$hp98mHzVe3Fh&x0+`0}oo@mJB%rS3%kxc(UVo z^nbVsAy1>{Ys*-~sjv$u!YQcm;@xP4B2vHO4JHV8eDJ=@#Y-NXc_d`2JVVS4h$2Jm zAY8{aGN~yqj>mhLH}HitN2G--9repRn>}Ovw)mtWdpmbkuy^WpB42_3%u$_b4*Eiz zVj&KKe58M$MW*?J`YQQ#Pu}z!?52$(|BcZ7c-D#H=x$SI^TMcZ&)r|sHMW0M>r`(c z%Pr#2vq8&z!gi8rZ{~@%(T&X*Jg+~f(+hj0h&Do3jv&a1pt*$-c3y$V7GB8`CvXrm zfc!hXgAsaz6ZS|S_m#;&YR;kmp7WjK9U+62pbfN`-E#_qG3!x8%Ia!1H=L{P9qQBC z!h_(`5a`s;VtUU16|XfB48%NeiS`IZ*nj^a>_tG-j&qSTAjxt|3 zfwrEJYw3TZsPP~SJ{2)pr$U8S8wxnl#bUK$m)%K{w`J=P?bx~O5(-X;3t%ESmXb9( z!?RPEOI8JoNh2P$hx7X>9hT0>Vp$mNQ0eQkhptsMzu1+5U9qir9-3rHdy$rvuDqU3&;DK(X&&9go*PD`4`)rf{mERq|D=lWv0@MT{| ze8cfgGnBNGLC%hF43Y)gl0?zsQK1jC`e%VTtySrMky}(MPaH9O|Nf}QV;7a`?Sbig z!Z>|5Qjlo1e*dT{C1T87jIasP$_hZ#sNn~OoZwwXl4X~~IpHB1y0TAh%&jEx0J~Wr z<#cVGN_Bih{CZ1yNwy|HDk@6MVl{c69i5JYF-4-jhECHqC!rn7>4?;EI{n98KlmPt zhW6O_u5C3(E#N3}R^S_&krr8s6I?Rz2Cj>Vv-9J6DaxL0U>lqAf2d}`|YLspWKDYCI*g1=KmOI{&vtgiMkt^*gIR;+5S^(O^NT717<=D{Yn6vfDR-q z9|)olg}m$~35Br?Ts;Ol&|LzzOs!d^8(6*-+3kh6E{L8Fai4LolQdg9;ossv89w^X z6Fbh|=@Z-t?F2mDaS|q@V9_AO8fR1D@xszWISW%hx+G&FWh6izF-I*D3tb9{j@?6M z9G--4-#-+QCVQie{(Z5g-Sc9CZ&kW+=~3^s@A?%Ln^74&a|6PAr($e;9D`-o$gXTh zDT*r-#;jW|K(59R;LQ$DN>i|Ul{X~nP!K_}GdDz&ZClDlKD#@M*oJ=q!0$KJmxlTI zPg@%S(KlPK5H)@=p%rAlQeVJbc2#li+PR*K7X;8cX5V@L?IE|TSH*?V<~oweZm1zU zW=lckYRe8V63f=lk`GCNBuiGNjB5qISGQ}zO(saZzLzt#hMvvfGWAdDgeAlg~ z$xGLUv!`b9{A8!Gr%%P)O^&2sLe%o3`~8Wmx6Ae`w`I4j{i}Ar&k#r49tQm9n{=Ev zrgL)3V(cQ!y#)^r{9zRQXrsVid?)0mfjIIz#02yn_E^kmS^Gbr%Myvz(Mkc=#Df|0 z*%gjGG~O-L#23Bn#v-kHMGvX^XXz?;-j?zocmcAt! zff)6AN4AbG8IfhyQuWGOxYJbb66XJpvvZ0LrCru_k{R2!ZQHhO+qP}n_Ka;CGq!DK zCMRp}eX!OT|INARzUaQ|F{-P+s<)okNSyUB8Y5PeYX-_*grN=isHfmuDRn_2d!wZ&B6PVl64sMrow_l^ujm!r8GEDdx=s#61Z~O_R)JIx7iW z3xG02{kLj-h#5ojht zi>*VBTe#aH71~E+NXyNitz%ZR?m$N7sL|Hl^>f;qQP*?1g7BATN|WfY;e7yMi_uB0Ptq z5IGT&?O_=Z=p@`R>crWDkO*~CZZUPy?m~mv?oxvR(7do55N^cX(HtOd?#4e5dHce= z^N-@}l?Fz`q0H5Zyqtp}-+e02l-!>aH^b$Ky(4Fdu}2Uf@(!RN^!8KzYhz}Wdtf8K z9GdEYx$AvBAj}&<78+9_W7I<{OFSKwl%{q!>>yVan4L6PeUhRrJd6f;A@mNg5OySA zVOvSOXT$JriBMJ;4ViOHDLA%liXAa3zYv=@_Bj^sEjo^r%GH&o%w(8$=D>#=(R>hn z2WEj_cjU+r>`(bx0&p|%a{gjrUzmK(`0+qeEEl&-mq>AUzxuIS`s!=4g_flzUprC` zof%Dliq<$WS>Lm}$}etoCcrKh;%?}Ry)Vq!8!{tE4AI8Kh|J3C)Sk0v%awKcD7{y} z6sMyUtS_L;WU8@oW7P)Hs@7R6?8zNdvzoTjpL2*^Q?VnPaEQ57Yg7ud0|}Q>jKFN4 zXRQEX|6XFYsbrO+3xWI|0&cC8rLc@ZpJJ%mv~zPi0akQ#%ckV%aur}c)ViDCJ-^?$ zYVMW?-zs6-=-wJ^mn09_c3#nFxnHlmg%fTM36Mc~_J5#JpfHnw$(V0Xov%`tMS?`@ zDC=hAv^ibLwu8ytU}uuy5J{@}TK=#wODW-E)}a8&dss1^zn}ac-^#vGQ{T}#0)oY4UsYgxF4W@!X3=NMm-U}xpfM;DewlQ zjgl@R;xFebc7!e5vwfN=f?}33JAiZA^$U(?*^fU{L`EN0%lG#(kN5#^n+0@2B7Wr^ zyz2qHf>=0bsMzUB9K9jCtkax{F;*aLVt~y2lkkY+Ir(_n+R|WC?`CP67VQ8)jIzKZ zx1@QjmKy;g+E`*rbF2Js@EdoZE$;I)pjr-QcsD8@6ex4*Q48J;A)#rYOl|h|aGL`V z)#Yms>u(lR?MM!OnkaKzy`k7UkIU*EmawgU4sQNBj?0X&A8T>p_pDRSn-V(vuWPc- zY;k9S!aL}-_7n0>pSJznKpjs%YB8AZ#5BICOBi#?b0RzH;o3WS+ZP z(i1hmN(AdmZk-blhxbf?PVQ-fwOh0qT0LI1MlW7wifkz0v&B9d2Ryl?(kKWST?GpU zWKzj(DJX3THa;X`qPlR#yqKgD_O{)j)}XI7`+6c(uFZ{GY>VEp-v}$y{6f|o9u%*J zBsz9i@p&My%uezCufSR9rx;i+#S+s-1pttz0sx@+hnyp8;QX@yDs5pXZTBxg{(q;K z5={ti<)dakvlcI=c3?(=zOns!a003*QShvIf6zw!s!Q3#EPDEX>6pQhYm_%DT^%f- zEK6)13L^301q3RA6j5rdnl-hwo}PHBW>@|`@oay4zs&qh5EgcbdN)64PPlg7X5ReF z+V@_+uldAfDfi{NFHPe{GDkYnj_pI!vM-+&;Mkdht__7wbaiL;w>e+#99ciQvIl)! zW>Vbvay~A&`OSJ~emME^2Lih1lNp?FsW0#z**73*{`HvWC0y?5BZExl@NsizVvJ4! zXgLXtOp>7whYXr0-WgPL?eZstIZ-aO^B&PNMlQHz5AHd1OK*fZQX=6|F1h&+!a0-9 zxy28M(76LjCU49+bn_k^b5rrY?c9`y3`)4a8SSg3TzaM^Q@FKGI2^kubE;fw$9FYz zs~(OV?>#tYSKI?;pj>o`nWJ2OL=hyqx)Tq~x~T$D9_?wzcaR>{$)l7pb&rOtRB`#% zs$?~u9?WBdOYI8kEaRY6F0c`$e@?qpqY?hJYdoUNb5L4oIrmIVGQ>_26*yH@YnMHE zW>_bUg66P!zF~Dq98`t;W#RNw3a?%E_}$f8^5DX0H~;1tV|Tki+M`fzm-uJ;ezo|a zHRKv~?O8R)Zt;za(@*W>=IqnQpiS^(Lu81n*r|;BI&l>4@J`6%Q~acc({AzAmcgWS z0ah*8P?|T29y^*jW$8~1!v#`4rVbq$jsl(yE>|UD}T?nNA%rsO#lvhvHD^=u-tQgyp}%J10lK?wGNKCnQ(1lmW?v8(%+XyrNd#B zT3e<=g!@UIY6+JS8(<8w<0?+47Bq;MG_kM@^b!)d8fw5%t7Ao0HddcQ7pE9@owd{7 zS3A{a%5|9oG0xT4D)l$C;F|jh()B?83>Wj%6q1 zc+mQCB-lqYBjn|M*e8~HKL(amUV<|T=hewD^TQ_AGi;trr3jH@!c(xOI{uK(%d`s; z^c}mIs5MiW{4scH#E9px7QMAbHuKg+ z>sbFI{H`nNWM9+XXKmY1yHLN_87n(v4_;e@U_*b?UHwr_HosZ;+1|PAD0lr%&W%S( ztpk}K(P(H;e&+*f zSN3fJnH|Ho7%!WcSx#6y!A#nDSH2FjBy7eq&%i{Pd0@$nDNHD6iBA^rpZl zl`+Wv4%B6iiCu~fFvC$6#Sz24o{)snc93#DwW^H(JG3-#8m0sdDA@){QcYs8xl%?~ zRv6V}>k+a)ijtl+ZuQ$MUR~0xWpVh6?CqE*f zffS#mRS?`g0l%p1T5B;2E>*wvSqO;)f+Vx=_U<5XZO@_eNpU|PQj5klPa~R($fO6}mS{W37;0MJS z1@ac^L2b>#_==qBqHxwBmMYlRmLC8H=_M(_(87s|Y6yZ_r+{D@%^&-p${2hCU-oS7 zuDrptU4=L><=CdUGd^`W3qcm%I|wuyB)XHn=+XCKjmzQpwi%{?xb$Ez>N{Btyc_S;x| zM|a&U)E0bogi`x&Dk^GQR51~1{vx(rNf_*6!MlO{dTD^pPJ~T$jk53$+vInurwIP^ z6v`(+hHGg`?@tG?=sOEcM!)k3;@j23_$2TP7D{<>FZCY-g=-4(g#;kIRNz7$f$VE@I|@|3b883lC9K(-G?B{;i9MGCy)h{6<#xH?{8%A0R`@Ve zk%(Evd;~m{LHgMDf$cUK8gDunSZ<$#J3qi=o zTWOWc)4;Lh|1l3nf-WduB56yL!Zoc<&0~`TMdDJL$iV|WC{42fMHJ;&#r&GR=xI(q zm(<5JM>%RzZEXuE-Q;3QU7Oe>?Z8ptId3CrT1xF$I?Wlyx>hF!Qh=YqbH~WENr+aP zCj6spkfKMG2LI5l3c9mA6&o&VqkKsSH4~m{3C2`R;chfQr=~Q7;j^kCb~L|Te~_k- z^!nwuc(FfkZ#6)xuA|zl>5eMy8sv=nT0D$S>bFgS;Z~VHe&qmU)mLm4!NQZv{BX*I z3afLGg?-DBA|wkpq{tmy1jJL+51j?^o0ai5O)@)GXd+|)?e9(tZJ)OYildH))M-6peCMEE%Mw3KF5({rWzsguG^G;bT(2PHj8F(yvo)>>iCCZ=^2l#J@x z@+%a&3WnBhhbOsTB)0h5l8yIT&lLs=__28&+?l>rruD{g%Tb8RRh7VUSB;6VG=b3! z5*Bth$uS6r+A{1C%0pfWb&79DV&-yrdxDuvjq^!%`)tEbIA4<1uast1%ILgpwo+$DWl??F3}Bw zliwlvAYWOrqk9@n{rj>2paqIRHYeGUTnp?HUz^YQxwL3$nGa*U(7Yt9MJ~*?fVpZwLyfKgc@gHLx`@9n2bN#X z+t>HoJmNgJD5&Ln)L(Szd|a%3_a=F|NYuz8@@0;|>*>LHRTrlTh0hr+CoBloI~O#< zwhKgVakuF34rYyl2HVdpvH|XySW_&c2^XkkuO3TjATXg@g7lrQ2(3N_{G+gYi`bEp zlBTzBS>VJi?K#ULnmH?>Nmp?UNmPtl^covHLE><8j>1i5USWcVKPdH<7jkLLeO?!{ zqwUlJvn9p3EA)oE@v0*X^dznQvzD<{P$OfMO;9&ek4v!o6VqOSRR0!+Vv+MSa1>w; z>7GYBAkDn#@s11m>hEhef(@B(-T*GeVRTc%0ai%Z4p9v^l(;)BFBi(L>fyT3U}UzJ zc^l%k?tvS`vU$`5r?BG)4HK*OGQqj%-{$r1;%JR`ja7ew@-6PQ(-Xs3a~)jY zz6T}INGd#;*}rPW;Vs_ z?$FM)CXH%j5=6Jm=Wj;WEa}~i(cX7LQKKeZ#k9=RQ`_5=1w<0Ij=?3%O6-i4DlT$} z_@=Qip)g$;=kEwCDk>X++MrBGEx=h-_;~)Hxx9~h9LKfcSHaB7dz zEM?V-@wWr&?vhRvWmSaR7C<;tUH`RVhPk#v{Tp9-CT5?ewTE~U%Js=$+Db(D8O+OH z|Bl{&{sOM(mmjtVx4tG4ckA&;4p%zr!F{zWnQXmWo_k?I##Z>aDc$J-b+u>H6z8T0 z)+;@mujv!pTPpO4=DD396Nck+1|kO0eTpt7hCO*!ZiIy6WL=tu!#3wIO7mEG;OaSj zC&anemZs}=neT=px8N1q{U|j`_1JR&>~s1G<8%0$=zHP3KsKZOzQhsE>jYagn{#jq zHzV;Vb^`srz!BBsnEBYuB>P{vOPmQ$sWTP3vH>a(g{trBGi*IQtvJy$si2J%ltmoP* zb&^M>2d?r3Hmuo5*G%=C%_2&VgvuHlNUrkIKD8|DoG7r*V1K&?r!cFq^%1FV^H`cG z`XK;Au=ZWM?rJ4E0OF{vI{lJxc(KYyb7GNcXw!58u^cwx$YYVj4Ug(LnB-gsK9g}3tfk5WS|RB{nU4LxhA z&KBC3ha{hd_nlI>f> zx#NYJL)R;FzPHrhOii)H(BUlp(9cS+wn=$l3*flG37|?8a0L+H#!2q!h<22$&x>!5 zQX#_#;-=f9-O2fEB73pQ7x9u}#UvBX0B}ZUYL5iT*C}xp&kSD>u#JvI;#qq2ajD}3 zsdhzsXSJY0RKo34NxCj6PGQk5b16M*szn3MLb2905So9=f7QG;WD0`h5vR4cJTwvj zON=Z)Q_5wOt6vkx1$&4pu%0MD#FaK^gX16r@(%;ZLrfnsGzE?-V#O(Ow!@dDTLeik z=Ecknfk`4^DP^wytkXtmeKVMfAoUjPtY^BT`n01^T?vshFW;zOl)ISsT{k%a9E_dY zj@}3=ro)aY5@+cEas$dw*(v$&{C*f%7qnV3w>P+cv092GUX zAi5Km2`VA2*k?dR7_u6hlRLdhqr-YU&{`%3cUJ_d(yhtFTpjj@7n+l?^__D{`gjw} z?I+e$Sdi82ge+EzRFy9dRoG+6R_3?Qp*4URs2qBLoJdCb6q?YY+-tVX_X+N(SavPJ z3=PHar+BoHu5=Hc=cpZ0&Q@EbGSBN<&2sMzYIvc4=B+D$TPxNx`b3KMi@cj< z_yTL{-KF=LR(NM(I{;?j9CyezLNc=tWNJ_G>57f=;E_9Kt=)yup54(;s#A^sg5|cR z*zOGr-F(e}>Glq->I9&OaEXW$!pd9h?O*FQYu$9$q{;b;Y!*BjVZn$|KKylWPfE$b zLb|I4n5jGoduFZy+ZXWg$@Lekb{y&UKu^C03hgxRu|(&TH=36geru?0AuF|yN>?Z6 z>hn{hTeLF8DmA&|y0m(L(2Vx>cKSIVVWVuzUCf;tS8XBtz2DP$#&}{{Rxnoq1M=y;FK?DdQqxgz633OiP)Y9&bB|GQ;lKf^{5KzyF9O)hiv z!aWf%zLI02=vM*r`_P7gI{Em;`02$4EMocZMg<+@MH52vmTkw3o0lb=wU6QUEf4p!RcFYz8FtKxT`Q(y?q~hb+1zv z-_-5hzxJwNd+D(K7(8-%cTo1CVyAYWgnxtL1~70Ad_Nh9y+Xq7tKx51*o#{|sC#D) z-e7VEdUvH>Wpev(Zc9FC^=5AFfPD1?+@KOiw2cYzsOGK)K;EeUs`^v1U_0}1mp5Ra*e<}%;q*P_bS7i~z}@%9FGj{tD1sL7;P4K=>xI%LN8Rs@2i)J$ zK7m-lZ?``(nerZ4=Dr)DOTlxH0X^{ z(ND9P%7DqwLb%yJh&9sY!p0BsV!WAl=P$5eGiexJ>db}4LNhuhy7F6Ou))TR36rbk z7|DSvElR1PfUDF-p~!EuN!l#XK)74~rVp`y$sA~dYRc35R4J0P>M#l6CF)r6|-YM?Xe4yf#XPy zSv{s_QTHNp@LW|sU<@)*O5CJ-xjs-5Wa+KAsI&lf9EPW` zpXzVcLJ2AxYot|eQd6`V=K}7yG+C z&4=BP;(mFpT1|WAzcfNOYi_iaZJ2BunW4&NH2Aus-;MR>{=7OZZH48&WzzxWE4V?r_xDZ;-QS_uS?M z&8fP&`A~=*XFgZ`B=?$|mf9mI{OaD6Ht;p(Mc8>61+coyc-tW-WPxC}wak)Uw>Wow zw4c{Pwi{w8!AL)p_+O&+hPbZJ@;-bT+jq_T696?;JIBP6LKeh$#; zX6zu}T@cG|o)ebh8n`4K@eF4u>+M%V;i12#ZQv#^em)~Ss>WLd#Qj0xY*OKDLSw!r zQSL$z;+mtN_-Y?Sb zl^=q@w$CAN_ryZd1Pr{EH912fzByrx*CUQXxeO}lkACj28u(98X6oan2lJ0=Waa0g z`KLjV-G5mpo7kBAs1}Sx93AccH^5e&NA3q2>hlXsOcq{Pp-&VG5UG0t(kLiXpO*O) z#TCk0e|oF7UF%a%l@#?0z%SVWHd<4?ZP>fZgURk;n@@KqeiY(aYV~PXe^z8sBuZY& zq)-@nf>=d#2ZruPFH#O2En73kiaf7~TJQVA!$VCHpGkMk(-RtYDoN?aKkV#|--Vu% zMyw22aBPYuV{D&h1%K+3){v;jebLJ|LZc*k46KOoDXEG6grL$ix*Wj6;EKj0!jQt9 zs!bds_6cNToiwJbQ)$`x403wM&jtSW7X#}xHBp`;b^fXt0&C>*C4Sue7R21z1;g49 zKJ(~B+mG*dS&hbCC(j3Ou~`1mVTHxq^h}|6Majgfh|ZuB&0IU==*D~LCRk$g%=97T zo$E(c-Die!wlK{${5E9e{SPDS5sMW5`XBJs2m}Ct)IWTFB@=5CBj^7S?T8!L8e5w< z63ZJn8dzJKSpU1C=l=y4)~IeMVVNL*+axx^qZNo(AQ#st!ay)*PZUWSL(Y?+pc@^BoA*eBEcbYgiMpeUJy?mPT$C*e z7qy#O_BZ?Bh*>vy!EBTh_-_Zk3s80F#_O(Vvo(Ej(cqLpMp5HvNpi_GQ^g??aWvv& zQW_>wMG6Ewcqi5~!H|yd=gjzBi82<(I!L*y-{;!&m1Q9|nXZKFjELtJWMQs?Qp;>o zw_!%d((+8!1!(Fb!L)|1!s@>@rL$FH+GwdcRS?^aS0N0n81Cl^Ffz9&3N~83&^87w z@}YUQOtbCNLRf^Li_HoLFjb2EoZAzD=!4&z?UOQ9Qzdq zA*9NayAc_o4O}iL?*#vtxyJnVCF>muY8-J*tNkgqG0Uk*F4r0tBsS*dWo@Z!fp!=#LvD#4!skG6m2>G^WKy!V#K#Hh)+1nN$7dHfArP)?^ z-p&er8@Z?diJQA*)UmV0-1x*3#MBF|8t4X|g?y$dFo(EjjQkrQlKi?Ab=%k$7P4=r zEqvC6G$7Up%Q!9vJ_nOoCtq(>{2hKhon<~uiD}*%X-xtBSscP-WM9n{s}C!URzrdb z_l`zB2PCO#e}g!&9eO$5ci`(sqn}{pI_Xet9CwH<^|?OYo<(9cGkx+x|6bjDcRS58 zdlaw?9r^LADrV*Hp}ZXWm2nRx|@Q&i|_ARM;nEVfX!Ldiw$Kgva*0a z%S9K{hN95f-l#5_X~as~U41^fGrje;zz@3u@}NpKVhX1h*bR!@DCN_st$q*5Hn>4& z7;JpaTz`Rx?Bc9|Q3y|!2lHJNvnj-7F*vMSmgfU3P6x2KJuS{VoU>jsKE8x9Jo-?) zv&Y%FTPVd>l)3{p?fx5gD8F4CO|x4v)Y~+n>bx;5BFGKyi z{`KoqLI1`9w{FydEGc0{jn~vfj0d%dN@*eovFt~t6p(B%WXoEtuU{+4fS(M^u&ns;+`nA$zi*Z#*FvnBc>#0 zWea;kb_7#!B2_8VERK#fUqx02Q{NoMT{|D=G(39aLUsXfL6$dno{WQ+qzneJg|vF6 zrF2yb?MT&tfBqN%sL2v@JCAXBJ2sib(oVuvw{S=QOxB>c#>#8C2TR=s74!*}(ssS2 z<@T{9CvT>@eA=>AN!4SvDUFjCNx=!WZ1w)ULTE>J(K@VLoK~!_$&oKKRZbs%Rpy8j z$1F>9GDwWdGBlV^wj8Ett%djaJPi{W!E`;{6>d{Ya#@)2pm>53`aS|4<|y}Xqfkpz zLy6Hp)6(9mLvqi^aHWewF)<96x4^c>k&6eGe_$*!U?sCiRLFRnJW>lSAF7Y+XQ`lT zOr}VsjxC(#j-^s>9Thyb=VMlxSFokp3N(M4SC(w{xx@}=NKn~XeMZwNTH9$XU?X&* zGzC(v#+gE>Asf@v38>Zki$H`1QcHuNrXp*H)Zl}O3E)m5>MGmAP(kVj6789Q)a|N( z)CC|G8ZhaBtlV)9e$k9UqT10nZP8`gP!0z$iVb8zZVzlAZY$XTx?ybEag*v${tMGZ zw&(MMG8Q`j#cO3bjmlP!Q~}Z$dhfI0oHvzKs`dvbONN$bXm41%)L&G1L4{bgAelUf zaTB9)iptY;@X>x-H43t#2llP8Nj?3ln`epC?(NEHL+vY*%9~opO33#^Ucx+)ig=ds za^b#ZTE z!4HpsIMcI8RKVr+F!Y-3V6^a6y=0_IXQ#Tf5&lc6tkt#gm0wJBxXObn=8#)aotX8M zg&>qC!Mr4ON1J0@=}mfIf_|wOq?j@;*^V}??XUht3dtYr)fV$|L)KPFw)U3C(^S0l zQ|9$kTC`HF$)HCoWIP1VR{l?w#X1zY`L>uj2IYA^e7Egi7nkoCDsJY=A-^80L)u=w zqr)JmfP_W_utVEmT<`^}fIZ`DFl`nQ)UkZV27` z2MGr5LrVLuzA*7F23Y*ssIlh6W_h#icW@_F#f48vF;~l0XL*IdKCpd)!@%X>Q7^d= z;GxylppZ#0oD|S-9b9JTd0xRi$VA!sop>I-kh^p9R%w^wpZfMGhif}m?;wEOhU#gw z7nQaA7wBpnOUFC-8h-Pk!+wQy*wa(bpJz3#2R-!`>=`QU;<`SCVPb_Cy8(J(W(^bo zJ-ddK*q{EKoMN8%9}_?Nd-`O54)T{$P4#ti(>)^+&oHtLb_`RtNfkSLgdezRYjEoN zd>y8Gg5vVDncb(EW7^J3Fx~v4MXkTM?47=Q_Wy(LC`tK{Ta-s0?RBfOZSFFF?2-4dMxu}wNl5dDH-k5v!;t?j}R=3@bmXezT2!#){x4+3(N7E?LP6o_F(zAd$@2La)6p-T$fLt zk1Y(|V9Y^ba&{EEyoO{T8R8+hhGL)@`bA($JSCByR^Nwz^H6EER#+7FvK7C$#J;OBQ^u{P;xVC-_jbqg@zH-qF*_vmC5(H&dRf%CT{U_uak91RK z%V4bMaD4;RVUU`wyF6JsX=5_0=hFJg}zVBEMbTVJT>xm`Rbr+Z!B+ zC}@53$!7IB3A&rr4~S6jNm}TP>0gUmN42^o6SkTzofB#<^M5Y!o(~9FK(Jb+gy#b4@hi(p>h5^vBy5*WH+sDTd( zUwCh7gOm9{+f&emnwjO-zL8@B;Hf-1fr7 z0$Xm&&gqD#@FlH z6IS49-(U3o(@26qT8I;)!;8qoGOYm+18rofICW2|`LHiZ?Ew>rUkqbygquNz?Ubnm z5G%yd^p|=26Q9Jh8lfDeQ6C5;^jwwH#Sc)JLD_#?Y+)@W3;Lj-BM7?FPf86dLV4+n zsMR-(hP_j>kR(-! z2r7w7r>3AS zxMy9W4CES>8%j^%l#JFmCe9I_Kw>Vl$xSDPLL;*av?43fzT$oI&X0!5)_CNn1COp% zvaIip?i2y;Fj)yN0X;=!3{*&Gv7$ChLLkqHY~z@w;pup==a^4C1O{9{>6^$}IhvGQ zcLGXeLsM}t2@l=Posx}b)6q`tm=rGM4dpHvm!aPGW?vu}BhE-`xH4h{cb#m`V;02N0hMfrD%_K z@nHq9=LVaUBGO9R0CWy&@(^sb#Dd)eP{fsb0~ok=F-rJa4O~iq!AP%T_tE#zV~ghd zpB19RBiC0^l)dd85IR%QaFv%tMCK3kW%Jhrp4M68;mc8kSKy7*g-8ZR8IPsp>L6NI zh&8bldzm`dUB(u5*C{I}H0rpkHPe>QS=kSn(cLgNpKugUc?A3KMfJXoOr6JY4lT;& zBNZ){kBZrH6DcCY@muFAk3 zBWnj%(6<*Bc@vINOWx)!01pOA;Fk`c@U)2fv2;9!Dd3XT`xCr9(V{YQ zQ(`LkIijJ(ZrP#)MnaE2<@iA%wOF5;VcXu&vNoY-eW+~z)Uoq>&A$275?qe0i<~92 zs$JD(nuVafSgJ;vfUgnfBsTr?0J`9N1$|rV1tK^$3CzFa#~`e&;@7t(2(FG_4f9_0u zKK$L8`kvi>Uzw~E9I@0^-4*IZs)9d?OBaj-jK$fbxeMP&kl*F+4J20Va!KZkr9dBo z$Ftvz1;cR<4}zl_>xTf7UBB}Hd3y!A@e6M4IqjooljXQA$I(-i4_@5#jc&zt+lAmg zg?@P}{-t+3qV{?~F>_S?ORxDL8|MV0T1Qi?GAsZ`e{35iiZpT0ypd%yZNYdBFNg*~ zYM6@!)a_RO)x3=wkqSx}OmY0!SR3lau1F)LKwinK+(u5uE1y6(7YNz|gSx4%!AH&L zFYa|L!_@d=Qxk9{2c?Wa6(&{?b_#|gqq&Kak_lEA4e*NEwVhq<+J^2Tyd~rkvlDw> z|F8iAk^17?Hu_;t1WdM=2lI5o0dkOy7cr*9wK4hQG^UILRgj5VbyVmvFp)wH!SYVQ zu+UyCui$-P!;HP26+7-;3!r9VcLMO>AAPgxUTQ=cOCJ-QCT&JkspnJ`nU>6?y_vxe zpk-oVAE&3>3Lwb@@*qW~)e0D5qNZPm$(|kP#(E4EXS<^Gs3kIuuRz0{6s6!SNS^!- zGzsTYh@$S#hhvsLax^-7#_9btd;H0u93EAcKs)`F zhB`St_DyBdqY-2m_>wpkwu*M5ZYq_XT2YJn*|;?0Y%Q`_%&3`lQat7hA#kgts;$L} z2$4AF8D!i%Cr6tm6akQU$m_Ylpt;+tq7kWZeN4WlsbGirhgU z4w{NL6qw4T2+rW1&fY+KRwz!SuJ8XBG=v zQF{hX@zj!M6MIgLaW!pHsO`k;TH_olE;_y?bV*Of7L!>q(qcliOvlX2^!XZ-Ry57H zI9|>HcC97(h*Ae5E*#u^?d%9$ccvGsV@=`tS@IG* z6M|+ah0x}oMePgeXU|5q^vf7yJI1vmV>{M0t+8#(Myj!G)5g}tI7xqfhzswAyedA?drSus`zVvQ%)(6URU|W# z?VI~8$T5bwD||ogwzNT;GaN`YSgqC7Ex0Z^StuhSjjVVPNYB&m^yDhWz~6?v*JO~W z*Q_{mh`=GSh%q%{zq+S`F&Be#@da5u>&DMgY#WsMm1w2N9zN?DVRrdAj`+YZ4oc1}B z9gMFITt_fd!;iQ~4&<4HpK8D%UT8J@q}Ccj*RkeF$2=_vLdcyOKj-X9zT(--FY5C~ z()e)>bLX@)#XpO-x8JP#Rn#{m!$p z+08D|22bGsY-y~_H)=d$a1RAm=d#%6eTM7$@3*ww(;3{s95!J99k+|)wVGhJ6VCwO z`x2&UZK<}JC~wmquMI8EO|@ z@rg~Iy`cIS@JYB6{AKO9O7qy^Ab=ANz6b%zzb~9!qe}*ZU7Qu^O=64RId*)dac&~p zt+kJB=mc_nufaHN@kdSo0DX-0Z~UYk1%@Q0k2C6pPd|5SXIxcrQV&@iL=4Vjz0)zf z?VjEJ@b71{z4cM1-b3`3%i}SLhk#^OljrrZMWjJ9&&_Q~+C>DMLFwWFO{J;#X0r1( zJm&Gkv{NlW*Tl=uv$of@wBOdZujvUWWEC0#L770e1ks-b$O6Vs?T!t(2S#;po{&)I zwy_Xso-0CU&T6}IbIO}}NFuWW(%mi_y+P?d^ow9HiTo(p?4E8SibYt8@USAQuNJ%` z$30SVeCUXm@F886jrtx!;pr7e{X; zqZTgNZ9St zoXK?2_=LNaaJ>dS%6%%N-sV~l<{eUZ(VgthIuh{4r|r|-J9?9&9kghN#vMMj5!nsv z9eLfld7$y8THV35gXN8h(f@q4vce{uFv;v~)F%ak*{t~hSxW!qdrM~pgcgI=E=bJg z%T+oraVox&Rhu(pPxEY~tRpXxhL-yUGi33It`#M^Eow)|?xjTiB&2Y8sZh$7gZMVR z>5#|z)$Sg@|L}^825M<@!2$p{5dCM%(toeulcAgm710e&Rcsx!;!7 z#fK)Q$A^b!CMGaIGA=X+$Cp@>79^BUlek9&C1Y|(1^=>IMs?Vsfvj29q|%uyR6&d^ zY(dfLY-|40?Yc-?yS%Q6_I0xPVtQ|S9D;GS5=ZxN-8so|lKa4QlIw&Q=l4GNYu7(x z9~lKncQsT3PCNQ9WbOq>*uSw}8l(2F7bO zhdMMc`}mZG*(koDzucbyy}V<5V3GLIaCftVkh}v@zQwz7D4!8%ns*9x)x$v|ujpUN zV!k6#xN3JN)rETX`n`u5U@D&}Xqk5qD0znoW$A;9pAXT2z0ZNMy$ZJ)bdS4sDBiJo z#Ab9o`MXh&JwwxJZzuTQbFwpoI~1>!bl=^9%etSxC<0qP#7v*auD_VRyGnO2xL@c# z@72EEve3R`?dt3894}}f)=7IzF<~%&n zfNI6iS4v*OIG;!g+|8Qw;%qb!BFP@ZaifS{RjnbP!K{)Z_F$`AQ{`n|u2<8>mm-ex;ddQfT(#pb0Ygwk#ZFrnY zc`8d7iUA*nnHT3qh$dbS+$)ZyZ}hMjTo_@^obO0ALlDgIr>_)~qqeoNE2;@DOc)V& zOD0c!S*w|U9g!D{S5J;-9yyi{fX7B*GG{9} z3rOh~Z{%9d5FdF&5BvaTT_)tHf$5i8Bpx3j0kqfDa;83%BVM&Hot8(SenMMT=?R=_9o{KoJE7PnRaO0xl%!H?))Ipu z_+(_ehyKjs>{zxtE+cVBM8}gGAYuIp{ zSI|g^9{W0;F(&$~*gofo0g$t~Fkz`*(59ulP~#?sbV{Ph%B^Wu-o%337RNG%1meXw zqcM_{iV#h#$be_;T`^Echk-{nx*ozn@c91S*pO%(>l|8=aM6(YkKGkX?p48%=mq8g z&7Gyv?GAX-DtffF5xI^3JM!#&22$|=0%_K^(N?_)kc5viw~QkRgAvn#pnap@&&UFX)S)I=gtD-5<8KG8xSdRDUK8P!f zWHEE#{ug8K6r4%?w(G{WZQGb=V%wb9<{R6#C$??8v6G28v2AB|zP-P_YW-K$SG5lM zq>s9O)qT*r zBDRtss!Tx^s}nO+P$B6|ch>mhXo%mQ))nkpYcjE$Bk6*YKdV7IHnWUbyO~*nzGxf( zh~}TOs*mPc?<|QAVNTOo>e3KLFR)+VhzYt(OE%XsvC$U?ov^c>f~?{PCCF7ynzuWO;MG3@VOm3R%jfsnp(geV}a7iihOd+tj zm+e+C$}Zz9tSRf9K$zwpBedMO`#K5WoNro6EVr|Ajs6YRVJpolwOp$=x{X0}Eq!?_ z^c`mr&waAIuoW;@QlZz$;+g}tX4KSBpP?6@#+e2MdrUjZQM{V>u;ZN@leyvJMS@#F zKe`gp)T9Y!!Xo{R@VlBYq?s?wGlAbWBx~oWepWH8PR@^^D$M;;za}1+b{2^a3dJri zD!^%ZD4iYm+veyu*$}OR)YTLjduTWq_edEVZLt%qm8fk#%l_FanL4@FFLB^ln)wXc z8?N0<90_$~Sl>!mVN0}?wJ!r!ad$bhbOix!QM&4E9K@`y)=%T5zwO0Fj}xge5eR5S zG-sw+c)Lln0Wgi4aiGh!c6urvFIwt`H10#mgvC$t%}ZCN86+Co?WUyzX2w+%$puVn zcziMK2j}|c8E&pJy2jzF|zsL~a<_lspD=x=k%n_$nL zf7S4xBWW8Jjui1mYGa^O4t>xmt%X9QX+-wZFKxQSoTX4c)~I>x8hxsr>FY4qa@jcp^l>(!$2GVkQTI8TQ}WJ_IU5Nw{EJU$k; zOcQx1g=BMAw%?$wivQEa+t+ux`rsUQaRXMk6E?4vG-;7PO5rUGf$rk)G^&z;fAp`* zk*~%qse3Utb0}kOTvlq0&FM*^Q$BY}f`iGROV}+8BmXGe!3;U1v&p_iz+DK2s;-p0 zVyrm`*~&aN8)a6EG8j%0WZ@;JGGZPiOg_-=1`&}d zoIXPF2{Q*ub3omdWOcL7%8^sA2-xC?NQ?+2k7ysB4O4DQDX7Wuf$UcdBx+C2VST@7 zkV&0ec*V;Fsj1RU<7TR5o=xfEN0U$SaLN5iwm*uu3BOGeE-lYhr}e-DDfH(?^+O9N zngwDmz&qVs%C26sj8o>(UCQ0Ajam*%N^npKKjs-`KH6nXvFeG2I778|Ar%^<*Gr{v zOtrl_{8H#xxHZ*l7;mqT?T90z21IDf3Q`O6$!T27cow(C!cs?9*d@b2mcKxpza^@Q z%)^(tQNB7u3d8M54l@rqc7=Mk4*S?#b=ICp;%qR~q|sS$SUkqt1pCF^W{7*)vPo<0 zNUw-XhGKz_gt|KO6E~eGcI>^)?C4PPC%S!sr3faGJYe@civ|r3)RSh(UO@t_z<}O* zqLH5KuF<}>bd*!#EqGT+vjbSf?>4AX8)?i6W+bQY$+Db$;3{bF`$qxi3)N;=(gxeO?~7^J!5fyX~ubG!=)=OJo_!H8Wnj03lD`dLC^jL~NSwGR{& zPq8kPi&+}t+0`5ZAbychS>Din7@$i=MrLJDP}vj`TrCb^u%<>3GPNuW{fXID<~`)o zK4m%Vq$*8xrv>A$j5y8Wkszpwgxj4PLSSV*e)27kVIr>d9A6SEp{f+)P39dK2uq)p8Sa>RQ$}wZCXk;pLr+;Z zuwJbIlou}!@k8BMI^|FuMML7s%|nt0;wz($+8C2=7Don@FU&z9k+Mh{@_D8 z{^14=dFjJRHLEd7!kg&I@K@ecYbAVV2loupSBPa9i_MOHZTLIS#2s~$E1h{)B-Pa~ zhdR)x_|tPLUGdiOfmI@QL=3T5_!eae?K#3T+&494bMokFE<%h?l(@EC^Fg7uXtqu; zW>eI+`-3mEn)+3-gPL%ot5%Elk~2+@jHZJAXM;7KE8pD zW!vq{Hj^{ZnAp)L*L3|NUaAb!)FPW%?%bvC(ag7U$3dVY59xl)=9WkkGWFL3fo5Va zMT>#$of2v=XASzsbv!QjFkPf6USmXG)k6O5Y2oIP%ywgvXKG3992@gA44V6|_(rVw zhOW2$0shXkLcMCzu?_)$wV3m}syKa^1XfpVBR@~A1&#(W%+SA$c!7^0xmyO) zU~1Eb^$9nsMM$LJ*HGsLDV%o_;-PyEcG&`Hzk=rG#I&w_4z?&i?V+AF=4SgrE zAu11LWx=N!)GH53#cEZj(mgnjBVfcdv#D51bZoJFDD;*Lm9Gnl#q*x+R39 zIh)cGCmm?pQIIym_L(hanJnIU!bBd3u>Deo$MndWu-}`V?V38?y7Bdb>pd;VtXBL| zRHj^XVa5%6{S5dma;IyBXUTwTd7wb^7n$^+#2yB|5y9OUc!V&M5kY#xpK@d4biDy%x>(|(GV#P>APfb8i zO+rV!rIn@s^y}a)H8821;)O9=v+kQ|T+TG;!iJh^xj&@^$j5Q}iq|r*ODv3GvC!nA z8xeoZi3}RanvAk=JPm>;jRZr^wNoO;g5M-qP3%(?TKPYlCbln#fGtqWQ6#dh4Tj`M z7UOHhzL38-akaXLb#G9?kbFQ8acUA#zuQ6J6G+qtm&OsxdLQ0Q5!ai2EpYspr_Wtm z1q`_#&h9vwl&p%#D3zZRY_C@Ku-HSt7W>CL_*4oQ#b1}JdG8TzQ^;je3$h&Uuf<3MCg@>xKH7nm8TG@ON7f1E_qk_us@4TBk^dd ztD~*Lx6CwIx-J`J^fc=9GH21)2NyjL=D58ZF+r|-_U=Cod|1ETGv?>@IDUXI_>`}+ zCZ<8;EcsE_xc^qSo5Km|2TQMu?CAc7{?%#=L5AD#J}+74lj4GE;;yL>fYft%|o9w z>I0+mNE>X^HA=dN)q%j9FR}g&Xk3WD5$*^6V0q;xWZUcJaRs97Ea@)pJ-pvwp$M ze{w)FT@WGhHdTZ9$|u*I|J<_LK3a(ErQSj$=wJo91%R%FarBBu64 zWXy+GRFblz$7|D*kaIk&$g!GZE_Z*le0cCuoVwxqW$B+>b^hA8++(=6x?V~s+ zePiQ-Hy!R?&)*WCBA>b(B>@=vu#m(|@LCW|%>f!cNL5F~sS#C1 zC7lc`ds4{2bIKH~fjnBA2!vY$>cA4f3+yB2!kBley5uxLKa`v8ZVU*c)$_t$+XrIn)=DhC?^WW0+KImr00hc?#1w)A1aM*Ux30ka~ zp#>w<-=OjUs^&fIxi~^cDE9%Xi=gT9!Ss6Q+JRU{MhPS6C*UQ<{nd!PBl6S0=b}fz z8&OfOMfoRO%davn{Dye60jiUrJ|$a?$al1;P5&|%BX*;E#HbyE49W3RU5r7@ADFEw z1btB`KLY8>JSrxf|4fbU5}Ufm@m`k{+z@?w{}S01fQ2K~MSzopqWOX)#`ztC=Y3@4d;p##09%C64>xUJLn{({@W-Zvc{hYH zfHo&O9asW@)C<%caPNk*2UZzj8;F{BV?o`%HFqp4GY(7KC83rM^c5#cIawWECr3%F zy>W-alj=HTNUTE>f3w!(%l_p7?t>IM<42n12VFXNS|x*D1XhN~p;_@$#%CrkLkPN6 z5mc&=nHoB6=z4KmDJ*VC;&G@5Zr!+132Yc2m6SQJ^GR8*T6e9ytX zamK11{h^@Geka<;9*F%T0p8f{U{NN$DwS%)?SunMB{I`KQG(t^s{N{!bZx@m;h9au zVJzS?22!x18jQVN1K z-Hdky!b`mhIQ&L+6oP2*B#z(DD%Hg+|}Dg#goGf@hU^JaO#%HH%9f z!V)pAL3>gNXoosrI2lSYPF?p{f^@_k;ik$`uIvW(zzPjSe2IF~3NVYxIiuTOVFKw0 z5Pf;FbgDluttRb8S+(d`y9g&8tDDc=3Bvs%gYX^sFVhucCmq3v#7`Il?RZeBS@9g% z((p4-(@{T-6?W)&5vjNl5q|mz;>sh^P+o1ZBd4VB!@&Zv)MS@3O@T{(C2EYco5Q&EEt{3|1t*Tyn)v-waNu@Be)8mKgXeOOKP}c6NTK%2|hUUaj+JBI{y8E zwo#YnWdptQPsg&;Ruj1&8%$hIQFej;2MlFux1~Z$pC!nQL%Pc5u}31a-=FI>XzaN^ zRMhCU1oOC(sJ3t40plIgO8&gU7*^APV{10p9UIs6kJz}EKBe|I`jlOK(^YQR9}Yl0 zAAE&=4@2Bu`14z0*S&60Dj)Q>ThVqHq0pKaRNQ@&_9UdIs&RYnq}fXhuwE)X$8e>c zcac!yXfl9IN`IX=D?hzNzpODuH<<*GI28GB0WWa`n`?yA3F&OrE6n|GU`RplJjp(^OuT= ze3-w3Ruaqc3y3?)=Q#WtVRdBH`TZv;_dIGHQptHc2$h)Rh1TRxxtP`8hg}KvXE2kr6r$(C`e|}q3Dgn z1H1?PSTmVGSEf{Yz>BlET$3VO1xE5S1b|?M+l7mGd@w!CZVB2)^*W&N(-HMB=9gD_ z63X*oa~0#dICWjJLQv#lk2+a;PzIKxx&j5m5BK-n`0?PvC^(~_OP`{=d8$3OB(e<* zutV1j`7Xsk7uHM2Ap|8c${36m7U`)_T4OE(#-n~$C;llc>H&V#fY(B#vmsc=LLOMG z=wzcvEx4*7+Bq`3L!xZ615`8&h4~0FT_#VRvZt-IIAJ?;ge-_rSra~~(o-}Eg&*%~ zdO!bsn`TpP0D2ir$1zRHfUAl5r!1pp!v4-FXC%cj?`Mkji#kC0(^w^<6YB32eSC!} zsDU5v>vP2;HOXeVb|t!soKeDUkzSjvAm<6L^oX_YoMi`wdUKoyG;Xj=^0G`Z+PpGb z95Dx=dgjiCMNtTyWjoHvSJI6u5;q>Ucyo=rXc67TW~TOQQD(6DV!_T>IsspvqI*rJPLS zk$3p8TWuUUa7CQC3DoBumVSJ=Uu%1%B3bOgnv!3u_YeM<-ap{$527J;8|nLg|DxBL z_4@kOiK2$wUxCd`KgaKEUX1(S(+e_cCF8TEFq(03hG%I`$j@ijxXz9^68+@$@dRDU zMnba~BQY{V87HPAM2FK5Z3eMkfG=H6C%%YV530yb7E*R*_+Un(3}js+4!@pXkoDaT zlilIldHvr!-~XldlnF~TX#8fcPQS1J$@Bf68@z8Y&CK5Ae|f&$;+5foexig~Of^@B z=M(Y$L~ZeiK)4WhRIIlbt*OB8h_W~@0Cz37L_Dhr+|6@%@z3z=y+S?#;*AI*_`;x= zbEA!hz}ZZZO~odp*K?|A zEO(BJk)vp+V9TY3Ij8x>UMNBs&4+3+O`u0F#1so>_-V*A(R}6Zl9KSuVRl;na$}Ak@)uNm zE=PB{_upZl*U#f)<`C9!c|^P<)}e$X(N1Vw#HNe|miX#0NQQ~s$fz>9-xYwFIo)IT z0SvcE6!kE`Zpw;h>yfVelM+tv`5}(+uwtA)na`x5(g%7~mX=`#Esi~<4R3FK6J-~b z&&s1>qi(v!pW~76&plLND&}Ov2WMESX?jLBg-SR=qTLDx!YAY;s&|WwG{C`g94o2W z#_>JDJ57(9n>>jI9OprQ6!mZGbd`FhaU~yGq}mKfbzQBCjH z1q4Z0B*;xe?5pqwZ(vKI?tMffr8rJU;&OM$InEF~;U~^qK~a1V2akMDdSoS_VjnY2 zjp2OENPM_5jP2@5y z&OkRg9f@g3% zTscFwo!$ugBAP9T5NrBEudG|6NiK&jU**G$!gexP)>_clP-q}EVYA?rP zm{OyZ1fau`Q}T9Xs*;j=B7HtEk@sA7>b^$3COR|q+Ft`I?1Sg@MmlI-yCaPD1>g@7#Ij<1oid5R|CeP1YnLj?~=q}v;tWQ8Fr8*H^0W5+v-#) zr9n`KFx@Z_5BXV0R{<_Awh})R26KTwX;iMQH2KsZBoB3-y*!L8hR*5r_K?~nHyH)p zm_%fFntPWCojpQepI*9^0j3DGIqDiJvgi%5BO!W?)ke~uZldDa(xSXUh3q#SpLU^- zi3uy)Ba5Dj^7`WFcJ*nR=}Vl;TqIhRGH3V`=TgIGNpw2WHT2B%by^00^_J>mPQJ_j z)K)arIZg(r?ott_OHwB%Cao>QN4h#%d!x#y?%#S6Az?(Wnh(XQ80KWWO4YqSt=%jn zqw%Z_F}3RhMlW@*kUTwY<+8{x4d&VU=Fv}R9^S|+>*_=0@L?gyE<@D~6lwBXy~zIt z&IR_j`;a#5s|?4~cJypNmPMM{bf0)J59fcjyJ1fktr zxLHtcM{^Ouu2#UUWQjAGuvwSbkm_(#F8sR){cki0>snMCiS}&{MKOI=R+#t}8V8uV zwMTf1i7>TDcG0t!Z;UBVw3k!a26kK}E)`cXfTA9Wl)2(QJ&|^>lLax*t#Z3d+H70) zuVW9MP8}K-7iy?s2F@DpG`dzDR~0_l^g0IGHmsBNX+b*=%9*32ahl<|tK}}8csHSS zKD!85X{T>*KczC&(G$q~)`&%WX>HTOhD@iWR|AvLrCR#CC!1}~4F@4jthLDPS?up6 z42SlD>ekX`A4*7Nxs|tw4N>=uoJFJ(*e;$oZL-)yDSwhZ{e5-OKc-Gk6|@LEwLd@; zBi02PT4)*ucG03y8@$%HIHXZI>E;UUak@=tlDgXx?26M66)Qv|Ud?;ER|` zNZ)i+U)n7U5v2z;tPGo;lTkrT{60F&Hjn<45|a+W$wS*nBip$2D0JRXndu8ILBg%o z2O?&2niLOC$}T05mJXR6Xlhhx3*}z+;qIMPEFdUHy80z1rf=B7?1NB{djI|f4F1l0 zqDSybh{tncPTq9)_@h0W_?ac0`WE>ha5s(YN3o0cToKz>BH}Cc2j;z}av1fFbVwvP zSM|;7B3D}-#iGP#h=2Zz5*5Df$@~nbO@^zNjm6yYqf(T!m3F^dU<~u_Wbq(fx`wwN zHp)MBwy(_3)T2imTsy;S`s#@nwl;t3p(R`meWRL;4k+ht8*P2cVHE0qHo9!K91<^< zcN=x&AJv`F`v|So#;Ewm%m@f;5~{&z?iLpem|MZ>&kgpbkGSkR%sT z_Iv0Cvu`S6Vn4J%>&P$=%oD|`c_tM&c)40}S4>}WPWo9_6{&>e`-G{uty7{mHQL&%ODiWhS=c}SsX5lXbjCRB zWZTxap)?jYPP1(C4_aE8e&BykhP3;O3Bs!T)Zk6TJXKT3AT9U!)$wsvGl3PN5gbUa zt~mr!)dL$a7D&)*$CU9135JW`TQsCDrz6^yD$T)Np5L2qYI!z4u|Q>m-Tu;fvL|NW8G?lAF*r_ZVkh#8VX$db%3odoj`C)9a3w zGu61RQCWQD5pJ&T9MH?vyFWjnhb;r6+s*~Ja)((;B&;iR^cnH>WzWw`XEP6@AoQSq zN2Bixp<-buC8_HF36W5#xouqvD<=vkGvMSeYOO78?XE3o$fV(z%^c=lIjW30i>fqJ zpXQ9lRwd-4p1-obm57iVI(+PMjkIf?9czb4)?1tiwF+;WR-Acg|3poSbas`bo^CC# z{b@sgeFl?bo!t4`!9`n51WaspTf#Qhe7@w@BE-srIj+!%q7+S$yJOtk+eCs59sLJw zZhr-X8CfYW+I;OVo0CHEYvo8c(n_eAvN+C8u^Ka5QhGl&REr0c+^iTl^ZNaN;wPdl zMr`JLmVX~`&DM=tROFsq=vBPFz}`?x5$foT1^*@PD!-Iq_NCm?7Z-Bbt!`tYy%Bv@ z{cP?s0=3yoYWK|TOiU_b_gGKJgC~&2ra4{s<}OfFCVlC+!Hq7fVBJ0{{5m`Ek`FpI zt;PkFVeEWrOAmf`r}=m%s6OUUY=ldbaH5qX=oN-dZ0hhFQhfpvbEgKP7t>~1CqVRp zLmE&OkqYzB)O{A(JzpAbqSINV_Qse#mshs1_?rBkh#C~B^r;huLzj=?v&V{pai$XF zU0q=^%{k%^b>vB!??=a^=yFu(IY@z8WyyJHb(a?{1cLn9)~NK3NrkbTu%ao)0n4K*R(rYmHeJ=@%Uxwi2OFnXH&_X~FjmCJ=bc#duH zQe}3YdNM6%W$u?vhUS7}rVrsB_9wIc&(RpI>W^PM!qn4cPOnNv0z)F`$K?&M`D|qyjVI18;wg;FVBE9aCGhq(( zW@O@@rKPIE*794~)p~+$etR7IkrZA?FUq>k^*{c>e?*MvJM9xMyihys=LN+I(W2Py zXZJnzjspH|0z7Q4Ssj@PVs;txZ<+T-C^>qW?Yk33!uLi>IIbe`XA7JhHdht*d)u87 zMxIAw>807x{c8&{p{=Kub&%|~!Qrq;kMfQv;X8S!x+G(V3s@=?#rG7R>9LS^{M|7@kvL4G(b#)~ zky3}0{K;@Ka)o0dp8P~Le`3xy%*gS##L4Zn{U!xygu!2vDNjYzM>+;UdxP+i_IJt# zOW7z|$`cE?`AyF}Fs^^}@>EIRFzkYV#QDWM5@B%~^Lt2#@4j+Z-u(BJp zE}%Oauq7~b?@|&45;RQRwB)^oub{ojUui!bfA5e$rW&7;nDUem;j}=^EVs-VO zHDgDQT(J6TIMF@53b54B3?>?_BkL=OJDS!P7v)5eiPS_gY!lip+S2$rH{nS}rS2OC6qp zwv9QjFj5M)G{tN>%ov0tdmId{@ZzTj=qWDE`4bLmGs~E2M+up6LAj)d1p4aGk}+Fa z^Z6=SPu`Ry+u|uumsC!B}_hn3RqEp<8H0mTLI8{h|aT5+C-}0eeB{+R@dPh$@ha!Cz^({)iQvlzkT5ZKn!`#SqZ`^e* z`xMjyN)$X#h!w4l)6he2%++$x$@@A2N!wAzDZDi1*heiHT@IcH>5|MjH==Pk_%IL2 zzz5|WWjk@314qY%x`4wL+3n3-KgQ8}^4*^Y@xm^9=9US``NP{{7xb3?BL5xXfhe1Y zw}G|MHzA->eCss9wIeDzeh>{06SIDMC;3@N(&M#jJb+}C5v)0|6_(UxM47DBZy#~e zI~~#HcPzbZfxE)}W8Ql=2>{ETpbBs{ksFZ5dmWbZd%79NFYel>ad+{GH?}oLpe2

0z z$(JzZ>To3GM3AizhEYP?_=)+CuJTE@0?(nyt2_DZ(x5U?sPGIBake+8wn0=h@x-Ct z(x;^EoqM+K^djH`;~z4+L-~ScAc1Nij88DAe1oSDu;PT*9cVG23*aIcb=kGkL+~HP z13;$(yH*jdcXa^7gEye|0mx4DJ|Wydp&O$Y9O7`r8`|$xcj)Ym%gZJQR4>b6zrUPC ze|o9*O{x`YkQF3cDf}PXyF$xO9KzD+469DO+)^9IYAgJsjMjag1qA|!PDuSyKF7jS zYM$}M;AHtvK-j5Mj`bVj5ggVOwkZQjqf;jfqyE7Rr{>|PvD;K^9a7T&Pt1L-xjV$$UaUCVhbn)hn4YSfGUc@)lK z>4(P5+82O7#k?nRpWVLpfofp>1;&gGT8F|2DB;1X!?M`pG-frR{~f&&84Kva86n&= z0|d82dPHs9m^<JB`M+yz=4uw0WzYttu{fqG)G67TpzNJ&!z>T5j8+Tc_s}|E8 z!AU@OG#_3!QfX2h=G_gbRPb}T#e9KcAxf69%@Sre`c<&aHKiQZt zQLoN<72Ehf=Kg31S`0`<<*AEsgl3~KVKa=<{>f(Rvej4Q4_t#lR{)MK&ALG-YAM=Y zsqg^T8Rfr;_5t&;FcUdN9;rDSjO3{H!2q_Q=R%ZcJqe4EIeZ=V*|}`7*Hm+Zl|ywQd4B#*^NvVz_6ciJSQY_MMn?HU<&(xD!f>Olc7e1LRERm0#H9_>^0 zvzJ;l!DU++XWBrwUTIMS7iiU5$ZyF1Ux$AAxG@R9kWH zJGO_;1<18Hi#K9zbei+QPmlfT6KMdokVy|}mA)T|UO#ehT)um+){GsI<)XIRIAz{+ z!Lw6sM)d5{xi0k*$f2ga!&m(;`@aIa#8B6eZ$KVrp8GM*9-_x2>@OghpMV+{;pex) ztC7gS9smwezvPaxPfFt-lZGxRZP_L!%Q6wJ^(Xbhw1LGlsTz6rp5#2h8{Vfv$n9la32%fWTBA z%JNCe9|`vB-uVG=4`9>S#xsFA8$jV3L8<7g##IZVlkak=+cO_-<>;4^?6CPoF$kiq8}daRhGW$}nN%BaB!_#?>@anwK!L(%W%Vi>>IS#M)f)HzrDVEyu~b z*Kih$P^)gE%m0Qr9d{w2WSvHZnjV%YN147b<&Yfmyf@84IECen`w=(95$uJ!`>kTe z-`kxHSHPc_{1Ee6zpp6W}Rr9>x6)8$>;>@HOSDkhXd;xxh7lrn;}fc>om);B90RFJ(F?E{R> zcrFBogB7a7cbMOnMQ4SNy}3Y!kT$go1CG8okasGmg@t$-h;}0^&~YgOBZ9AoKngQxeiCA1D8RXcZ-{Ig(q)L= za-BWisX3r*{U@(1`ID|i?OLhoi}?kM#JYE|;UDCGj^3#WnGn6cr7uz6vV;G-McaSN z4*r*hPSeI!O%wC$Dbw_7>cAWfyr2ieS_N#1f+8?QlRD~%b!@1AP8z1Pxs;oodwgzO z&g&QnrFz*K&e%6UO~bMV^3O}T1`VQ>m6a^9RLfc2SHhvrUJ|jJ_OGRu2gP$i540&0 zFktnj%hQ_0weQnfUDNUObDj`9bmc8RvWBpS31#P21nE`K?rz6utigk4Lcap?m9Pra zyMPoaqX#s`=6TSmFjN}6He?rn2Dm=Z9@%G=JY1OfB6YCr&@s>SJ*N1rI_OXqN zCjRQ3gdj-_ei=s{-$=P(84-0GhOJ-OQrZ%Yt$dlB)voJjRdxj7>kID-c<1gj)it-zHX;b00h z4>rr(H7`Zyds(I|b#mYWTIdURQJRI%Kuae{q-~a!?MV+FS(5Uw;YKU*dOtTn#UY}GSOwv11+}gv&`H(|iE`M7h1^!YrHG^BDc$Shson9W>y0h3Iiby#^MqQc$BgZANT~CNAFJm8;X@$*$;NR_$`yOz zHwg&L+fgPTq`sIJDB9$;`CNnrYc2sZK3=+9{MtRW^`l~`bJyqhEc@l`msMgp_ z*bo=wvXk~XA?vCD;K%A81lTa#3Jnll);2Z~vEo`jOSY=FRDK0}>FxPDjF^1`b!FLp zvc>dx)=^^F8|{m~Bs&P6Lwu{Go)w-TsW)2oNwefjoXxyn)wZaAo8qD~9NtVylCs!b z!nClyLaDJxhE6Lxg%%k@#dV;c6@CVcLCi|;!rZqhAjZ7?BnqR{RBwoETH8D0sB5XM zFtS-$wk#Hy$FRCgIt&qYC}k@;MDL764-ik4%6f9$&o|@9C>0zV2Il=z_^C1W`r7*P zTTjQ0w$^n|z(t`3c@yaKCw5*&Rox&>u_>~|AvuvCVQv4EvpNj0$-(9$_3Da9ojM7! zVjoYmuQje#Z7@zamb)wu zu_?~gG>FgD)j9aKhY=xD#`=+)O`{0-u$Bq37#6>X(AOqPpvy8re{0=t)ZO(peuVFy zzm+Yp4hQj%uB93Lwjl32OVunpkdnDhTbiPJn&orjBMdGAccVGBkkzMmV3 znTM?IVJsoNr6&U&SZO^>-fo1!y`CMMrCZC1r9}Z*3lK%CPT0X^FqL<>W5fgQsklLK zzY7k{!A#h4N+=8F?xeATaRHNz%7yD3Dvk(;8!J&6gr-{Cjk8Eo)#+ANr@jWuA0csO zqs9)S%L&AnCbfY7gw^Rym#yV}kvNesq!ftrF4QS77CORj-zqUqeQv817P}GhCFeWw4eA zX+w(F5E~vE=sI)S0_bj8aA6V=rusv>martGuEyg0f-z+-TGdHVd+J}Ts?$O($v*7! z)5i8`g+f$?VK|P$Kq2fa6MU`$T>B4PKm6koa3vhYKLZgj`*UfA^rzJNAM%VRm^M^B_Q~COcb+Gh=wAL0hJf3q`2iX6 zn;{?u0g?V67y=bDI|o-YF*A276Ei6@TgPw3`2T)O)5_KI|HX(*%}k~3%^m*R2JjuU zz*r*uGH_4cvZW%x2ZJ!yBQ;#5fB=IF6BU(`nFp~(fnes!Ce>cO7}?T>Szjh1QukhI zHAb#zfue6!f|V8%7Z<+NuURfy7p;0c*|Kht>EmYSX}W%MM1S+qiqm(#H0SkEL~0u|YC~?@dxzv9 z6uL2v_qlr94R4p9dGh?jjQZrwvLnh0b-0&++_oR!LrB+8*shA?;ptcpQqsN=?A_h2 z2}Y3QeVvSU^}JJ$yueBmPVNl&iG(a8fh_$(?0IWKJW(&(`%w%cG(3B7aqRpA&-PByxuTG^^7oNwJUm;L($dHN(~0NJ$+=wM&N0e042ehhx;k5}R3upT^ zUNGuf_>)ZI~?@X&i(?iO28SqKujzDC|5pDxEeXU0#@;`9D{cpOC+{Itt|^CGr!l-E-S7i zuy^{dOQ^!yZqVdT3_6%6d#pu#iz%UtQ!EbR+!ZAI)Ks6^#H*zpRR#>5&Ybsfmq!?%1B*}jgNXkp54isA~iuc+>C zHn}b>Of>b?0UP#Q)Z%IAk!*_j7dOf+WyPzK+5i<33rL)%ncTZA$4lCSBO8|x4cZ)3 zwLz<(IF`6l?ltfBz6k<>`0>|99@p+{b}5*(%p;EAXre#^=^i4eC_F!Vy>+x)u*JeL zTn{xa*`-}NcsjDAYRTPFb|_UBK=@;5-#gc zVLqxnoL~qhoJP@fuqMU_uD|k)W)8DbQiVz&ARe!3e)K0puRL%&;cn*|?kn(HC4v3L z$go=I!vC>;=J_)k z+EfUo{#^=)xq5_3Bn}Yo4T@JLu@Dr;fDuOxO?qsWL*S4svbLbn$vZh9#96SFQ8QIT zQW9gRg%kmuB;vx0!Xalg$m$WokS{NYyDasOGyBWM*^qjfQA3?^O!B)4$EZ{LC?|7= zu2VGza~}eXe73A+$!JwNMp6b?GBEp2iPg5zLYJUE4=xLqE%K+BPV~l193v8zNVz&9 zQe~NfRXBgwS4s|VuH7vM72>FS11Xh>z>e^^guAl_LHCJ1?ecu#(#T0X+T?k6m9+lv z6izBzqqh-;Ri%E#>xIi-(WWaC@C_VwvxFu^sWUtA3iKK07J;QTJPXOx4bn0&bix$N zL>&ygtyswORgC+$yUGzHyh@6#5?VuF#l8fvOfWro^Lf0@lI>`ybX;7!9!u`jQ>KNZtB z?VhY#P-`$rP}raObQFa6=}Uia#?uIqQzYY242?~D4Guy%zql6fNUQlh@w)p|4GZ-yJj2agj}iX;%q~lK#s;2H4;dz67jpKt@@$r zr&yaKpn+f{i|}r8=nK^)!GJsD*}kB0T>C?HkH0MgWFs?B3M?;_`qkw}dU5`YH%eve zVpf!Ie1*#sHdSBN%>qqX)1)g(^-=t=sx3JB4;>9Y2@Sp)eO87(@v219PCAt|Mn!b1 z(3fzWtL{HdAE{@IIQ{Fhj*Lko#VCzl{v1bV3L$3Lym&K*o&@j#z#ev`>cqc=d5(x} zO*prWIk!zAub^=+MCqT#G*98LMnliXu7ILf5Dks1;|`H1py7<2ZNfDV{ZoJb#2G*f z!p|HTR}Jb^>ZtOD8ijrk0=T>-FghWU%z8YG(^aB^!Sx=@Gqx`>W%Oi9ZS5GOecBoW z)s%-{o|q@Vd|JIO%yvQVbK4gm7D*8e`fC3En~`ACbP|AJ1C^_Y@El&_imIhqVN{{7$*J7nUC6# zT$6+-QsJLAg?P5dfjTDp{jhKFUi?gcI3sS89hzx9{$f}0`uT&Exq7<(?ULu!w@hiD zHV%ie`VeFhxhB53+dk9hs>tWcY^p7x^U5L{-#i;%h@PO(hTs7HCef^vW+XugTH3P9 zm0Z(YY?l1F%_`ew3d*{s3$n}`Y^nBX2Dk4$B<+AZG=wuM6hkwNr4pqU_yRSi zGr#fakVe~8Wd^1%#hCbrFUBF^pCnV?!J+3(YA%0>?*Q>P1rSCH?2xZnWYt z+qcXtdeGdu6{nnOvd6?e!|c#~EhSBP-Qt3~)`lk@haJfSS$?4a-qs11&MxFeY5jDu z1@Fa}f-wt57PC>2K3J28=9i?Z2_RF>&W27xBWJB$vw5;6)S(&WlSZb(WeSXDipw?2 z^#r+P>@BfV=c#IVm{CXIS0aW0xWAG_8s@rl@!}BSV1UN?GHA}!Ojed7f*mC&wSXoz zl@lTnql!)3x?RxHpkoSp#mjToALHZ3CpPU1U;S!1Z_MnO$;U}vr?{S#n7W8O%6XwqMm}&LmW=`AK&j1 zFNp!dPq``J7NeQwkzAeNgtOX)^>566c> z1o{ZgeCbC{`a^s?2^$+7^v$>bk+3C!_(p!gRbOvoG9wws>amDO6}9 zY*x554>s{E)Pw^56A{_AC|HWDT()zju4peybv_sMF0WRh9>SXjN=<==S$h~YX``GG z%1t5SC)$5SY?&Q7OF4Ecj@GJ*i(ZAI$1R&*#W!J(#7GVWGnNnLOjan;!Cn8M%gJyfZ`v{3?__itjyFj$NlQ{0iEQ-Kt-w6UXH||X8N@!hsbpwrqp7p1 zEJ^wVYhg9NNB!5u{I(yGIBegBk@N5WV7mWM4ObIK2V*l&#{bdK|KBpish?}$sv&)C zl9@?qLJ60Zkz**X-y|-o+kFd?D+0T~w5iqCr;dcvDLRcBg?=WyK34@qAD?hb$K~(e zHU^}QwsTG%{enIaIpTLe;&ch{Ft`8wxSr`n9>RU*55{sI!0MxfArP~4sK76XzGWpQ zkhlTU4&|@-QAk=7=ursTDSQE)ggk&`Y!F!?Y#KHOZ3JUPJ?2q}2r0Y@1A~7OK`N@$ zUlcrpj>jAttII#h)YVmoZ!Hm(TeOa$fE#a=1wAPJTeE!J?Uyu5lN?U@?uHrEhy+36 zX>8gN+??6qLG`e1^tz5VjSLUpWO}U`p=As4@|F46I2L&LbA$aMO8DuGElC=^^Jqh^ z?7-Z;dNkou$2py&gK<%2QtOvTGjZ zSS~#aReaLE`drZxf{5vrT*rMc z9D|(>HZO17kZ(!FmoESLonuHrG`Qc`oj+hld+WMj2cs);jH}yfYwR*6Q!1UcT$!ll zz+6C)e?}+bL?aD8Lp8@yQ(SZJCBhbHIlLbVq|O{_gs#CP39WBnzA(J0C#2B1j(t`6 zjA8(I#@VLwtliVuP(>b%48B(F3Nw;^r-3kUfIzO7GE} z{p6%DoSG?TB0kK^ulOqzks8+KIi0CG-Q)siL;Y7YJ23}VIqqY_X^Pfi7i9~(sN8r@ zsWGY!%~eRlv$ai4Qf;;Hing^u`YpRv&II|Gn(&h=Dl1D$b(~KbvsvF>_R1I5NY2({ zzLMjFnL*iB`5}Plq+t}dX$*N={pCl>9)Hap!r)7rK?0jNPEx&cTGy49r~PLKET@%a>d$QgG1E>cS zc@&dXk34Pj&$#L~aZ*%lsWp&sqHd(PUvs@kzRw^<`7WcDxFy@nsX?oRmUX}h-|Ls7 zz#A!jC1xg=n!m-FDZWLg@?V4?&KyBt;BI+G#IJuTKJ0hOar^u@18+`N1urtg4bF0> z1p95%8taegF1TTRrU&42l{VX_?H8(kuRB1cA{kW*tbq{IaqRrWNjO^^&M8;Ybc5~+ zm}OQE#t}ROvqLe_+Ivi6?>^~tlo?TplO4X^x}oQsm&a@ml|KU2uY+k?=-fE4+I4#w zT({=#8ed2(@jtjsPXbJ_OI-aW6|lz6@~)7uDvY1c!1AvJ^`B3i2P_Pn-$rEEbMsoC z*n8glA8Z9O3b3Lr`J+B){T}~W^wd8HH(~D>>{S+eFGOe_&oo7m39AYZl9G>`5oFhD z*r~9G7nyeBJT}@dq&DU56S>I%Y1|^4hLhNcZZI{!zm$2)zjqj1aBH0MymG6AzyCne zF-FV4GlzO`i^2fmH#cV!h2kf$5c zv&+~(0vMBVo^o*NM^cNr^o{2(#xdHE-$rCnJLiZVDmczM-nJTP1!peOsGDBm1vlIaOyP6Ej%{6QlokV%8}? z$b`ms71BgJtGq?W#3V=_8M-P+hb}3mhOOMe1F+J=(~;KwjDd~{Lfk1qTCoC`go`}P z-}gzF_Iv)=e}p&7HJqVbeW<@QiYUsb%0KqYhY44Am?-e9Y$J$BnkpqQV0s4Bqq1hx zS|ch)aX+Rl77NIjBr(@B49=G=&g(O$Cd5a;rNv_>{hWJChWGp#%|NkhJ;r*v6=OOq zZz|tBc6Z>Ecq_`4mL|>$rdK1j?BoJ7pZkQ860WRMG@v;Z%041L;6tnCFS9SP645KS zL6DSX7S)zit9KvqzDSSXH`)-P7vA{QnX>(~d$k9Uq#OJsb=T$V_~+H?%s z0D9kQ4~WMivN&;y;w*A0LW{gS**3lXGf(pnbm?#9!P`Q>OY92}lqiq3jo?X6VRB zVMt`j;8H*#YIw=O;^El2S@l}y;o2Dt+MJeldNS2b!irGEBn*l+%{5EQ4AwC%Zl}hW zogZtjZ~1RqU0KkmW82#X{9f0aZ&!Rz7wfpaZ`-25^a78E4sX;6gh`w}zFiv2?ysl7x}JmrGz$qYp1lQ#ju~A%ma~x&UuXNHABzQu zFVD~d==Ul9{?Uk&hgJfFyB4zk%L*R%E))U|cS61@~cc9$65&ZtcqXKs-+#cEQRT~DZFQd+1Q3Vsv$U+}(?eB}D0{6Ewe($g;+en2D z6Nfdvg*THR*(1Gow@&T7c{6hF@w4|fUaxVw{^!RYFMKK6oG+kW?|I|B84F)TAp+U& zMdJY|4_~%-2C|>kK%bKOA5#atIq!(rUn+)QlcQhz73M}61z+^JuLEgXGW^i+|% zSwMe}1W-&wvuG(@RS;Ig6jZUPr4`ho)~uFSnK>sL$f>KmTUTY1P|ByYpEew_d1WgV z%4@J5Izuc9O(nCMzb)daSj_N9uQzjrW?U)839!Z_bSMMaT~bsS(h+d9t{ZgO4*EaNd) za!3`|l;TW=d0aI|u3608{t;kDl*DttWOlY78+7D` zKmK?1=%iTF)^D=IlWKL^bV;nF$Wx9iQ!*4qR^*7hMSOjE*kn#qf~1+h*}d;wQi2LQ zhJ1ycGQ{p2bC~3^h)d=6{nf0QUQUiaMtw?0xz*b1a{j2JTs&7JK*~|YQJD-&j|aew zjVQ4)ZGNVL`kheHZ|UrX)R!5ZeYBEa&|NoEuE>iVFNPbOF|?AVbBsvhj z&|+2T;aght8~%dpnMT8CIWkQt^rHG14{H@mAj(c+U2h1xB0FHuQ)K- ze-uj%$*$r@;j=YdL1i*8RK;W>U81yMCl}q4#8PQBfQvf=-b~-jPG604W}VK#&Pi`; zgp=K6*9?k^jnT!{#E~l*zE=#WSZW>SkcBaEFr7b3O_E1(sfn_K zS+ZNj!uBb?1uev09$AGD!Sj*(#noR%Zd6+&WI@H;!sEIW zCdPl9=ZK6p?+khA>QrpNX1+&jdK?qSA1!~3Vkp}g;3gnz;K^}axFq1a5c<}M!cD1E z08Ck9$cEFr&B+gVE`f=JnX7vc^?Om2BWOaSIrZ!SCKQ)c5gA~bY!eX#B<`WnHHwZY z&XHtT6a2ZqYxH(SamDl`7WC^QI}o-f6$SX{YuVhCGte3aAE(@oY}CJLXT~ec6xT!J z%w%l+sBpH*r~0l*0zbs&X3cX%YMCvP>{J#T?aMA*+&RWMcvr=hBZk?=wPHw;X4ec& z^Zy!W#k|{LJCAvQ54zejn$6St#^}m-{JvzgFr)c)i=iLBkhhXg905P>u!|~_P}>3i+w?Ov$z=H`%woV$M6`Z<41}^ zlfBtt zyk8{hMANh5-+EH5?N29*&L}qGrGu)v{?3rB!NP$g45nV}G|_`ujW>RB9V#S(<4&+d>ViRIMUHS`4q(XoLEgtnUO;R&|$nr079L zj&*|K7EG=m)6o2$Dq1qM#2XRdz4xoEAtjKvpZY631}rRpYxEOwH#3MkUW;1XxOqL- zL;YA=gK|zH*z8{Yz!-OaT!hb=6*=G!cstTjoTCc&Hd?C??%rlm&`=zM4n)&1hdrN@ zm{ZFfov80sWCU15N3QIofl1x$57UVI)F=)yjnI-=V8OgB6^JjyY2o#r8oEujsa~Qc zW&&$iYswpdZuSDM!!nQQZ`DLFnxe`!nf17{?>cZfl~I+UT%%exUh-9s<%NM4aBWUC z{;{#~@?b!-Xxk&dy(wqf127G(V}weWIEQ99rg|xRPj$6i1#!+ZUK(+OGu_pZ$MM0Ep1J53E3_iU>ZWDnRYF3mE z1%|ZyhTJ5|ZFfninnxo|YDPbqRV<=})(%#jl1yfhAu@5e;ubDu=Ey7k701sM z;IkN4$=*pml-{ASX>sdJUi8|fbt zp(bQ&>K6xR{V%rTh$x3zjRKnENtSFbn3Oa5>;Mh`he5seMr!;@`$m^VrycX=BlG6T zDeH`!=Gu|PJ7F2Vfu$@+n?q?}Ykq1XdJOEEcUQ(0`poU5dQapPE$f7i5%C8!V+U*g z?LAy9ciwOb;)F>z<*FRRTlvq1VFOj4qMTZ)4lDhNS)FwMYS3a@#tIqj4&q$F$GH}H z+8cf>J*%;AMfQ47oCW|NNaT{_>jOjK&`NTO18luCETdZ)O0tF@ zS$+UO1q3PnOth?(KnsB!D{K@61UCA4NO5V+AYSJ2<20%6W-| zgnPNly^}>NY<^H#AsWY}tSsNyu_rV_^1M=mo?ZqYqeS2m)eHjzaj$<*qo8FGnVXwx z+VvqSoX{Yqi!b{((+9BphZ2swWjP5fB51+{92{~08UA(s{l}tks}=;uy&_&+zS2xE z%p;y>D!-Q%DTD`KEpwf}N`#}GQIu}|*Ni9T20CCo)O4rszX^@oM zq0ns)D5xqh!#C4Nng_(ls12z2o*k#ZhG9(=vSq>xox*ESazq$;$d=4Ipjeu>)3HE66hl_mp}+?4F@%W7LJ7Sz3gRnLWA{wCp%Dp|WDk~&1~$|cJfFc%wC z888zMUz#tM1@hMMwIOQ*;UAQtNur6#z@6nk;=7ipfgd9O?D zdMoj2o#8*)$b5)@EGu8%JrWT(&(vAl=eCx5DXGK^hoR8D9#cj8p7F_a&uE<2QTO?} zq5L&39~hSMeUsAh(~`*)n`b zK{uO{U!Ii|nNW{Jx-a})44IaFG%o?mF0Z7+Ol^#$@1%zc2zmWw=Hpx1)0@y$~&e_9N6U{U^mz)=aQJ*aqL|BNLR~c z0@z=dtZtwU3HGPpmk_{-_buz2Rl0F=r~=PGg84Pvd=Evx`eIPCvsrr^+#IwkX0^U~ zD4oq`5l3eX9om6?S*Z?Spcgyy-LX?kN_?$3%&T$o&oP=3^B=a@@lli+82EH%gBPhL z)A`{?cBx8a+4lHyDa&(x7xGpeyBCNptt;Zf$+Y`@&399uWCg18%u+hhNr{hukn%Ah z%)iDi)9FTxxElK|QtT@lvBfQ@JuyCRB`;*%cps`J$I3|TKiRq{@Sl*;dkt}&bWgP<)mu9;-z-R}$$=p5PiSX2Zw`lPHM95f(cyN7&UteNA8`FjUOQYb-p3ptR$2FUoQOC%V*PulMr%sF|ybBtV@#snDqSei2X`p{-hlFI^*~(u-^~x!2P0x-70Bgc5-vno(UcA~ixNd>|2% z^aNs}+Lo9fLCJvL0pPm082zxT;Pn!`pMVA^v1gTPM?4X6haxdzvNDjiGI0{XsG$^4 z3lT$Mlx|5B_;?WzK~Pc!fQ$u!VoMM}a95TyAW zR=ymnCxY6IE~Z|eM6IYhJdI@%plyexla%kILR*+B9m@P&8c_{Go_9)1U$ zEz!n`j1eqg8u)KaW%RivM1hROjdAwOV^bn-WfZOzHRl|7S17|?88({!g(8*0LNf#H z3s7*i;xpt8c31Iz|Il2V+US_hAJ52fb$DKnM$lv5un#Fj8~(5|@Mc(Br{sRm&?4N+jnz#Gqvc;!NrLJi+0 z>z7@AY4!6b3J&$Q|A{={9o*bhk%m%x5fX#uDabWjwL^2R+tUMAZ#p8D;gpR3+*Js@E|tJuQ)#Xoz!a@0cYbp4MWn**hurNDLJ zY1Vr_BFDN-*eUx}Wei3sc%rs$PV?&AFoSlR-fe9{>*dnWW7#Jg&*V{yP&GqHMH@&% zJD$4-Is9R@C7prD{=Ih{ie{kPbsgGxSuBWaL-c9`^lI#2;zIGqSA{)?LBm0>po@yVG4|)hBN0to^X^fU z&!}}w7y&iY263^IpmIUvOd(qNcPNOqMFdw@UC|+e5jY;my!xzc734nd=G<@=S)#-E zs#lS~Iuq0oGK#Fwb^-qD)s zvG^Yb`oxM;fqAXUbjv*S>3E16&+B<2H@EuEjIW#Z7S-)dTmsiD4$ysK?)gDgT#$9u zFCGm^1eicV#D?|j2;lk+-G8lAKn^lhGW^BJ@@B&;QI3s%pbAwYs;3AW#OVi~W~j$l zYpCslVdkJi*ygY48j2Yzq+x;~S(QTlahi-~b}pnqDHd7Xe>|GB!wby*Lzeah3hM?g>{%=N#szJ^q$w+5?i=#dk!?_D z^Wx)*+AG?6Gs)DhapLp|%{N%L0Q;`uT@WB1aL9Q=_>O`4l`Qv(j<~Zg*|v3b`;O3% zXmHQ=2|u&9J@D8&d3@uu(RY2%@)^juv+acYl|T3{5q}ra754QzGtxLyD0y@g_!f@VJGhKK(Q z(%Y%$j4SGlRkWBZVS%9K3`ilQ_GAk)UXR0@^C0zL(De}HtlVf@+DxNkk%{QjJ`&R=nK8)_2r?#$^t~DJN*$Z4Li+BGeoU` zU;+9fjf>?nYT<*_*c;QMio$}U8`#<-p6#wzmGG@o$1B2=8l$PHjD?dZdh^Ux-q4r3seE{K!Y!q1gd0cp;Q3S6aFI{|5Q=kwy6i}fjI9?1d| zl!lwG0{#S+nwXw?61fP3?X!r&ee~H|niEg>pC8Qds&ygx1@lyoE}9dJhSUzTaE}yu zfUV-Nvkce#SM(Z1hfdpTiQ_hPRF~6d%oC)J{XRnhKPTq-1Rb(JJdlX3ELNZEV5*iN zG_az-N}iJv$lmeHy1$>_PR>*w-@ObY`Oi3#TQ ztfLjc(vv?DJly*|had{>UVk4#yM%(f5jWrg<=T&!+M#b=XQb9j0VQc?*RDygkTvRG zrEX^iXlh^OGD`s)##T_t);jt8)`H6Z)JON+)6fx!op_Jcv@6kiV@d zfx$`NH*2mrGSr1-O=H0_zSZ}0s;03;#wK)WSo@Z_%s~@y7o0Sf(MkxlYIATU*+*C@ zmCKp3$2cmM0Om9XCixNs69_wY`HGxa))NjBgiVv*Zr>s1JAW{?V05jO)ErDM;ZFG% zAqFlpmb5RSKAXE#bKWSr*y!)< z9;q7`dbm_$KdZagDCzI4x4nWS>{vtmWn-Kk6Mk1l!JV+&?Q zcC{bNv2q7W^?JrWC3bVL{`f-HOYT11J86X^i+BOgTaG--DVq1Iued*xrwc_Bt`?8K z86@BbA*wB$;k`W$?j{t|a^j38>{eY#AaZ%oH|c6XQ$ejwfwdT?#5tE8>#)Mm6sUI> zhqNf5L#IMvg&8V}!62f6P3>V_mqy&$CGjsSyjZaV1i^;bR$q|)VXu>wctYhWxK8Zr zUr%-Gii4+2`MEDG$`4TG`tzfAV%=fM!?=z)!?7Pt_EUMLcSoH zWA06Wl+zwcn=i``!}y#r2iu^PO=*!hJGQkpxUDB=s6$rQY$tHvv9y~$jRo!z_C-_M zio=m+*B&Q6@VFV})wUoG98TqpXS_{o-z0aO*4gfn8rNPY9zNR*p}dj2hss|ImnQIO zwV0w6Cu~oEaX*+&g`Ec4w2Ehn?`?>AO+5lr4zo;$@H);WkX-oFG5P8)kStft4ExQ) zPs8vH`X{i-EBNx=yW@v<%agy3xx zH+NM{vHS`qL?sRbMtq`vaS>LLzj7$BwuRYzLd|h}EPH-s;PmYuj__M3%QwVW2GDtK>|D<2292BG%`;yRlsJmb|d z@n-o3_%W%~?l4Mwh+r1w2^xqn|LJ}s}J z%u`z&IT#LB>O<*nw*#_7NW@+7OI1%NAxv?6l2(yH-#r#Yq{)8mI`PApr3Ruy${sHQ zrwd+mI|%0;M`^E>ZOao=vNs~~1$c4yNijk|5TD;wt^?{YIj_+dpVwSi@hSJDr zD&$`b&rAq!H26m>w(0#MDFRgWbOjeaaMk_OeTcR{v#F=?71eHB27--E5KK!z&K?RC z2au@<#H~D`zxhQOCnAcjp~DpxWb_^yny$)Ho!dce>i}(y6^Jd z%^?4XOBjJ1-aVFnA{}y9W^y19P-Sy2NG;gair(*J_YSZ=+6G>y!%cliKC69Zy9_W@ zknRS>NVO8%YBpcJ`aJ7fe3(|SOwne{SZ)e~xtC7f@b>8N+jcNr?Z4$2lIkICI-=Kb zVM8$rnlg`q{|(I9@!M%abLaA3T^Fm1{Q5v<$j6(hTT2Qc6mwoCc(a<|_nxv!zAQ0` zI2rYP9p~>D^<&v+N1#gUSoj)HtfN-6-I2S25cIF|D@e#NbZL*tZNu_R8 z;+sf4d?3<`UAsYfr69NB)I)%D;`7U~AO2ui+h^H>p_#+Z>+@1H=#>{(7}*KKcs;F1 zlnU4gh=1eQ2mr2F5MA(umL9}pA3O>8Hx>FqZtVEix9-{eTldWK|0A(+b#QRCR2CO; zu(SK8BJEqAZe?y|=KSB9v^@1w4O9)ZFL*G>0U}^@@YX;oVxeEf&GhPFk=a;K4VpsL z_!Nvrt}H3jvWlJ8)teeR)gP#91VPHv)Z1^Ak0J`+^c8X7l!cTOPKWjP+JqyMTCgljw$dx(UCIU?65sQ7d%)V00j2m5i_>6O=Fe`rD+dZ26W3m;lYd3zM zpvG}u4pL!&*gy;glYj03B{l!=XvOZ;cw7?u=-Dnykq(R>UpV@vHzWmF`c1)6_0~o{ zb63Wu+;6#&IwbZnZKQ?$vNYm9@blB$@~l8YBLn3qRrQ(`VA?Pu=ZxyA)@9H0<{Ex; z!1=UzFbUwcnjM;d?OP2%0MoWupOA*vP^g*5Pn74jymm4|--O12q0VBdxN#)Q%`mwL z=g(PIaGO&#xJz-U^-SA&UuZ3%IKJP4j82EQ3)u|)g+0rsl=<(VD}!iOBpBUND-8pQ!QUVcJY+Ea?YjJQfa;(V&xbw^y>{7V%>4;~{$sv@q-JCy%ltbuFkVo8vN%Fri7TnD@pn7#;1#U`88>`a zQO`mH32ltKlp7VlX@bSr;>t|z`ee-(Qdh`P5D~wH0d=@721S#p#{NF(FXNHVH}%`j zKOGS&*IwMdX%$$anggJ`XpR>FY3a@kx|7UQ_c8&M4ePq!3%|Q!Qh;>3iQJAMbo|3= zTyz-LQ-~FM7U!(&UZc3`8wxj-o-10){sw@wy<3R8pDP_dGUBMo3MD0}1y#wiDr}De zr)z*1%q+S*bLZ@}_6i0qWNprCp+XC_nMDIfj_ZU%v97=E0j_gHZW-I6of zdGfr>Ig;%-`tB0?BB~>djfVbTL8}=Yna@`Hw!C=fJ`0MOUrQgA6i9K7u${Et?nv}2 z+S7@6^CcF1H7mC5OBDhJEO{wWS_^H5Jxrd~aIBNbDov|6nv)8-%`Lmr;1|Df`P%a> zylLD8ypa68Io*W>13%TeG=M6LxSJ8Q2}_qiJx}tWbD_h%F^IvckCem~c1Tqj`&Ht+ z7QtTjIBm59#}KWQ_!8C(XGj<4w%>Tpj)}oBXK!eCRdXBk2ThB)gLa@KPj zL622|^_AvOPnw}6a^5f!8xKR5tf0zj6fN3$HF=RGV`y<+Dj^9o0n4>6 z1CUASkAynL>$BNf@{2kx)EzQ#7PVxl9+0X8foQxzU$j+ADGI&9fZzStpP2tD-5kq; z_`Cb9q&)%!0@D5uedYhF=>F#&1^a(oOB%UY${9KSL)%FvX76Ta=KNnGTOm^;N7w&t zJIyLOHvdR$nWmU($ysXp6}RLK;8-FPdm849QIrk|YVxZWy|GJ1Fh9GpUCnzG{z^uK zi9Y#<8;YE-5n4T)D0r;iV)~IMgZpj&xb>Q92UwdxT2rU*n;qeV+Dg}cX}md%kLdw@ zKQShn$wf@(p)h2FY$_fmWKrxVOJzq}^BZ+wX@oAqJV9|IE`hvgUQL_8RLOusqL{Fu zd@T-=iznvYGEU|1EZ-D~y!NPS>;0S~8H-A`*CDG1oy+%&$em4Ajz&bS{fMvLP zX-mjXfKZ2)_$nbC*c<)c9Xz?fw6=YwVrn7X&6&if5$>VQu1|S`T-S zD@M*wYl~~bKVcU00zIvP26Y`^l2H_Te==(QzhsjChL!vek3<{RSM@OMs~|_} z8@MJcOcY8i8IC0~HW*4&2^~xvOcqK6CRAJ_pDe?|lofRkRrsi;gjUnc-y!VL+=HWI z1j{d+2t!5R)XaZ&*3(hjx$fRtv+mxxUi)TQcD&KcjA`d%fwnW zBeWT(Wpy!CWhiku6bq9+J~Sa$t779UsItt*y%hc6EMh(iv5Y!azbc zun>=qHhq{;C&&Xo-Chl;stn2z-+Uh9K2Q4YE|vIJE1sIcIU}INk}B&wY~JlkmoTws z-=K!^b$kbVUNsj9D-Fh7lnfLE9Viay|3ZGuk%#71dEr9EFDn+vQ=QyEK2EP1CJ^W| z!e&`YRIXsI?!dks{>gO}g?x{#s4C%P)4WC$e-!jnAS#y-DLN7C#y^neV=9fv+AQr+ z)tt(DVvvdLIG~!k9|0CPaBEhu|ZSd#AkzmS)1J&BKF330>r=2cmhA4e~eI4)) zHIush8C~;=kksaM63Dn}&|7X1vxR#Y25vP5J=rKmv)Gall1!~&HZihhR-`#wyp@9f z*tn3N=%!yVZueJ|HpY9fgRyGe0$Rh25;%vev)Cx0zPH`S*c5rYe#;$O$9tBuvf^xr zY#=7w_p=_0)vfXBneJz*!Wct&y>fclA5Swi^J<>Ki74O#FX6X_${t^zI)1drh~Ta* zJHC2+jBvZLHHZihux@J-z5td8hF^_WHxk9?BJ{iU33|ptY4k|8h6zw%Imdc@Nhs)i zW1@CE8IUF+-rsOc9d?oAGCdx*`0gVcRN+6N7h^L4b{ADe#C)qbdt;k66R9F}Gb)TZ zDr%i@us-{BsNWdxa&ZXbxt`gU#XOfr*c80J3I~KRNI$6(D=Dz_i7Hk*4}A)ka!FpS zT&d!=D!zRL&bk)*iN1)CHN16K-o~FyiEH%r^~Z4eE)*;s?oyuSC)QCcz4@A|V5eVT zBr93S&%d#ey|3yMpoiqffA@c26T$n^Bp#VfpfXH0K*gcf%V}%NFs>U8aV2-IWRouj z$b!(&qmJH6*iuD)<>Ga}ExWljn-yv3?_V{F5l&&oAe{79_GS#KW4v|NI3~r>p@vU% zE)p{|#=`N+fy~u!C7aqxng}n`^#J@K{MrfhkpH?^!d{%P&5wekUf5nwpBOM080I)g zl#(~FOL4J-GsqwjJUoSqco!HXF29L9N-fFehT|903%?AN%3__nidQ0@tKVoRr3JOh z;WeO|?VIebrsn zU4LKfamF}zF~?j_#EytPSIF21$s`P1|Ni9_7C4=VWlpN}k{8Hm78905rUqZxyL)yE z=MvTi9SV{9!)L)V)o)ZEi{LUU-CANc6&>3JRtPE7zCv+CdOb@GK%_v<@W^Cy6N~nb z%ZmzW%C*wUD=`I4Tf-49Eo)OqZRy@0=JQ4IO-0Em*(D3cY~@=c>?VOY+1fl-`J+s~ zyXZ~cL2KFqEtV?q19jlE20h^#^$JBPm?l!sG0S^md#dlAy_m-1)WBU+5x1(jyNBba9tFfaPiSWOI7UJwn5rCO;6zS6HdDXs3o4h7qPnsm~1 zk>9AIv_~&ZNt0ru)}_jyEF77(2*TTy3TAfat`(<`yE48|YLw16U_KWK?bdilZ3GE1 zRjj%)a{BPbGn>sxfuzmP=JwPq9gMps+~~m#u|Ea-WWpC*dAoPX!;OzYMiqt z@d_y0a0gL8N%yz$G}Y4ys~S81bVZZvvf-j~kZef2TPhF_xheZdV35*s< z>tgAcxPAPX9zGYdM`8Azf?6?X2t&JmbG-&SjvHxPI;HeYmy`70$E5r*7jh+H)Di9C z;}nxK%8Q0ELa%Sa=qV>-yyMo>(%N^)isNfN+E%VaGjU*omZ=sHgy&;Sf6aWCEFBrj z^$(jCSA+EUT;yh2?J(_-adjR5#!Cug2uXPy8|mAoZzoyUL^@$PQN?Aha*~{sUdN)p z*UzygQq%u!Yf9KrCpMQ}&AUZ-{D8qNL)V!dJ(Y0Il3&XbEBN5>;ul>+LrPY=L)mV} z_dLG)YmYx6!fnV=bE7^@j7bE!yhGVPxqhj*N|0|gd{PmE|!V%3~t1M4nK1u3|D^n7+z$68KLc@YW+uZP=Qnz&=`jBP`pE;WJ8iExhGdHGry)rkVWlhdG!Jy`c#B;1D)(jA>O-$-(|_RR zL_OSgMDA+^%(ZG&e*Q|e|51Uj#hN2#5WAeWnpZx?!ZXsJNHkVkovpJr=?7TktUaee zZbO5-EYJLL8NOYH7qekT*rkrA-NM5}i?svbkaKY>B|g*re)R*o%|x)*L=Dl3dz2)y z_qq~Oaf?#IFJ@(tjYw^1(M8gp?7>Pr6lJzxiO@yN-7Z^T<>jb*WB5S{QS!2Kq_pNJ z9s2D!!Z#Ie`NlSpW|=-cQDT*psyf3sn7npL2UJ5adg0jkBaS*K)^~oJ^&ks@eJ_)J zZ6@=o=v!zV1t;=eA(%T!$DtzN8_u4OFQV4EJ4AgC?3r@G8@!OvIGH%dx4{Dbq4Ph-DKdK&Wo+6qnGzEz+ubwQ?17wB8SnIO51)Wo8YI6sXqzOCd!LN^=B5}1R8!c=^7 z#E8pvLWg9)SCOGUtv)SJ%xVFOnz4o^%^7&?mhEDDs`>jG68iMX1wsA#PFF)Nk}9kAy7Y6J6}Dr!xFQ!c$EI_OCs1tIB{V&et;wBDR#5A6KG@I{w455v$A z%bnddSQ000s6-q3qSq?{&z8(jY)-k6vZmykHYqye=3tS;d~~a|F~^m*NrNNozzHj+ zYE2`|#j+-w5P@`GcJRv*@dVVz)>ia`^|2dVPcIs=5AM`}@tQs6(Yh)^>q16O;;VFb z?dvX8$7eR0+%|&4@3`r!Do*IA{#>LL$@Oyhp6pT9*!vm;gJWV5#0lUGF{M>d{@CB_pb2fMX! zPIKm}@8m)mBZNiCP`@r@#@Z{AdFM0GeOiZQ+|Q|N3BN{}!b=#TJQVliCi;i!(g@MQl+2G|x*x+fKZYqNW0X{)NTz;~R3}L;_tCF@ zAJrA3gpsIby#~!-l;JVY(UeX{vWbSfZi}7;ELGz&f=UNqZfN$ZmQ`m>#QphIiJ$1% zC9QR6e+y22OvN~ZKouNI*Gu0FR)D;><1S_=wQYjDqhQ!`Thp!Ngv|?A*u0X%KH%~} zdLlI4l^ZBCCN;@_N&D$!adKPp;)tOxdd-9jm58LMmL^6}8Lc46963NoDU1Mnx%$m- zmJu}3{hIEPXQY7Obx{G$RAQy4nIt`%tuE&Kx_HM^pQGHYPiqm#b+ zVw(COcFA((4oYHQ_6I8 z4EwGPn^uhHA*7K<$jI46x&ukGb}>$GJ_Kp8D!~{jsDO@~qAjh!aKCte$Z{wQs%Qr) zAh{->Vunx2Bu9=_7MhsMNV6-{q~FPCD^ch5 zuOw<1DTR~a707fN7-$u)ue!x7%*7-c$P2cKcDtytyBo)PHLPCt+zUKigy0gDDz*1< z#bc*!%Jx>j;_ybhI|z(731fq*Lz6TItLx-w_$qAiq2t1~6jIF34pSfEN1u=O>*QLk zQ3l2FA`IEiQSfq=)5G@zSII5NEU^lcMUR_Aj=#%!QfK$!=QE_wIWRki%={9pM6d3X zyi-V{4WSkdXe2J*QmQb5^C$6svTz^Fd&oQ17VEcqOc59>X?py@!Zxuy3YNEv0x{y; zujYuZwD&9Rijd>mqzkq>y(_lJD~oNYErnkbTx{GboyKwq{XTqJ3|A7Naws#V zxER7NIasNgigvxwqwO~~X}4eWdPc{!wiif#Zf`~~+SaMV+n%x2caSa5oJuTg&IPh7 zzziW1(K4K2%=<1kf;Qv0(*fb!47M*qxDbi<;J^rp*O^?})3Lybt`f~`VK=ZbB|;MN z-_>sq&&LRotH?VttwH{9h7lFfCMHN{Yy&+yJlq<|l$_}iT^<5GO30H#s5sN)NMiJh z8o-*xB~~du|7eL%tQKGk)!9e4RE*q(-&a`6PwRRgak}!hg^nWK?A04Fb5?i3*_7Vs z^4ynbEBo4Kk8ixLxQWaTA2;9aRafokyGR`ju#1nrv|}?)#2`RjU*m3@=r8cAJ>sM0 zc%Dnk#k>Ybqnwd%vjSUxye6I$k$JOd>pw-Avw2EX#Se;qq+vl@FHnjacum2;1qF~jm^kO ztrAmz6$8M~|AYq-6qH#ydV%G;@p5>#{zUrM-6LhT_?Nt|?a0%whx$KkOa9N@qklGs z{%6tz6LCRRZ9QW3bUy=WPJ9;05~ZKW(wS%tlrs|y!d7;lf*984l@4xi+u*IEkT+Ni zqE2uUVy3wq*~UQ%)Gk5d!gb)P`gP=eK&b(~nn%&B{~0y$w={#ldSOfGm{{6>J%5k;l{2vYEA^M(T*uDN zz)s%S)<8%9@B3-x^6OvCveCI_EmTw!J4H{WkSI`08u`LPhzGuf6jkRP2|&@UNi-t2 zw45=oQbj{t;qQUD=7ST+%0&0UAnyjCar;Z*d)6js>*g@o#3rX-u3n~HrY$eO-+5R8 zpbM;<(Rz`7TjPh*4xm(3LeOI?MTcsCL)&L8{#pLBcWQTjOptt%R)s$8KF!3fXGGzv zMI-iL>Aod)`3Nox?gqtX=L90P)rzKsa{=#_uSx0#wqM4@_e>QXNNQGvZdz%23!BDf zO{5F@O69na1Z+PwiZv#KH4*Uq-+|Rcl4p#Tp>VT^2HPX6zWrEm)5;aizDgK%ITkRD zvHHqqlJX~)b9-twsm$Xh$9VFnKQ{HX1u*mIR9w4QoF{f3R4atf)f-hFf8Q?<@XvA0 zRzp=VpDIYQeJi8?Jt8^F)Mp{b9{yQitU6j+QE^)$Yj~^n7oAICD0v*ykgj|+C>~m(HqewCS1VZ|z_+pnzod=y zP{+quwEi`~{bcI^3N-R{%1%GFLV#>S4fOrLEQLuARR3tUTvj<1y}oT;Li{ECFksz2 zUt`jQFTTN@ozE7gr)l%m0Dwn7$wdKS6V!97II25{U~_2`ioY{L^Ir>B38PCm^y}*n}_Hl<*)!n+1} zVhd(yy;!;P`>v9a-fVY}!SI-|&hzQ{gf4?p9oI)23I&^;#|P-@ChWb1!tPnMWlihh za8`mBis@@B+<7OIB^?=>CIlXo$5y)b@z!mLB*flMoa%tuSGn z#7J#Wck&Bu)M*5R{{ZBa*p=^=yQU^g=ZyGY7wfS2QBJR^E8w|2w3ukb@+HaOm*L|z zaj3TPm07mBI6g*oSb7!8+DyGQC>{s*tl_BK4*<^Oj6lFW0I$%kY3TKe$9Un60)nu zrSogBTXyH@R_Hh-*`u82{@@qON%<4dc7A{J@kpBR!A5bxPHwlcDyaWrF6`uIMrQhvZx1yyfAbjq z23$R)s1s!Jpq+A@s{!RE0-v_$9Lj-uk=6}cuCAYMPZ@}sw0&q!^YFZLkV#=#LvcZ~ zz%gLtu|phK!xEh`a2tMf78NYe_(9c98|~q3kF6#YFa6Q<^ZxWk z0Omfi2<9mq=QFLOBddqz`DH!pqcZp{Wys1o%&I#4@`|qG@zO5o<%f!~3qXJz&P~lo zsql?sVfo#pbI4&qKgIpMF}>S->A6b+qqtS^2}f0PN;cpX{cPEEjAlp*+pD15Q)km^ zny>R=nPN5`aaVJqQ7H=k#%+e_5{Wy%&0hMq!ZVy`ol#L!r%UUk@Uf*XZ>q?gj~CFt z*7i|22GaUhO=nqd~VhuiYjL(v?F!c}C6EDK+ z6y=h+3hCK?!5@%|UYJzosD6@TRxA?VvVBk@!uO&u@a|D0k`L*}^BM?OMSLbm{#C-h z4%mK-FZuoo&t(1&68_g=^8X7A`>%ig4##@Qx zVBLPw-K)$v4yT4_F%rC9DG*-XJfdlNs{OuALC;D1?JNvdmo$|{JLs>tj$C(O?rf=W zOho!=zi8UhMgzj@7$2wS?Io)@u*5-4lU<2@Oj*%k>SRUFd_S1ip&50}(&UMeAur@p zn&We^;1{UOv+}*+Ahbf)$Z+5!GNj4VYXS|@_uuTwgDAMH2FzX-nWgkF$;L+?tc1BG zS(gh4ROSj}e@^#ibeWjP3S$Vdr<|mv)nDMN&H_9?tsf?d(XsfC0}@mOIosb~(S35g zB#K}l<)t|*2b8kFX<4Lcjrr>{q2Vnt(0Z(%^AYj0<5O(ShMHm4sxtfw#84R%usnYx4pZwfD!bDm1q&?1T$O*f(qD6 z9x=kpC3D)X!QyIS`fG0fe%L&2Nrj%PwvCIhDBnT8%v~9X<_{i-z-FwiT*=HA-6h=8 zR+Fb+`Zf9G;%+~G7S!h?(5ni0Vg3}<{S|vofA*$Vw(W1W6s#7^#E;Oc>p>qy&nF~4 z{YrP)*IYNS1oQDwc^{sHnG$xm5au9%bUEz}{9-va9~bX+eflzw(wBM2|D$=#>GgE}-98cj z-9Egbq|l^j)o9w^Gs4jUcqxp4D5}-1?=9 z79=rz`B!CNYpE>eS}9FR@7j$A_mZtt$adtSO|7ERd|IbK0?QNXpaA-Tqmg?nHyfHc z&a3@yvUkrmrs?s_8%Ctd9rT06lIR&qYFyVcSIS9to;$J@6OXAz^=mG}$W(Hr>?7*c?;lw)pz2{uIp>)2p_;+;Awhz{j0X#OtB#?AIQN8~_ql+jsw%T%EqTlWUkyUk%m*p%HA z9D~qFOYF+8pvEjI-l&ck@reBhTJ> zj;-1he6hs0^W98WjFWXHV0u?b8VCMhJUoXW>V0-KZnVLt~20e}j+MCSUGf@R9%W57~e8kCBzZ|FnrT3jDoMuxgTQ=v1&gf$5ph;XU04*ovaxSXQJf zN8lc7x9glpbGv+ddcNlnUHa-a0lwhDS*8nqippv0+8Z*cV7?O)MfETAK~JZ54k{qP zI8YNEb#hrrSazG19I9QSuNIaRC`jXSbbU~V!)Q>g7I~&!n5Z!3tB7k^f zWmxDVUN$O9@|hb<7RAU2D(`qAb^d7|mANE-yy1CENuGwrsbFKMFQj5n*UQ1EI=ZCd zzhe^p!@mHCG~vgcN-SFtn+*|=FgIDl5*2Wh>fwN_Bof{p%b?@5AqHhfxS!($tla zG78-tRSHwGT$j5-BGp{ ziOrAtEIK*<*y}alY9DA19!$DlJdw>NF=+&0v4(j@r%KwHVOLZ!`#l)C8Tz!MUEeHY z3z%{RRVtLH79WHw-FwG^DB^y!i;XcKspqt{Jb--^LUjoOD+5p?fWNx9JB2<$C)gyC zubtzjf4`Vr&s_pxF9lm!`M1_aKNTX-{xACczgXvgoxJ{?J|hAsf6*uNf2GfCW}gn3l7+sZ=wyzDL(T^QnxDtxm(q=hi`rPD`}T3 zlcvpfL;pK{zWq=7aK)8e;)COt=w~ib#-BtyMEuP@bOdX^`~GGhhgS0Y|DsPiVk^>v zw9eAY7kwzz{r*9poST;aANoxEMIYOUl)vb+r=wi*mwo;Ref0i8ALRc|AECeKGr3UN z^+g}GztP7fW||Zjrb*(z)8__`0Z<{W3`RR72FQmR|Dj~3CRcGaR@k>bOrDvQFH``2~NRk{`{Hv{I4)jZ$%rCUida&+2V-A>8W2aBg6sCZ67GNdh#;kA81k868hsWS{a}Sp56c=4=e#1Tz3TG%iY^^ z9KE#Nsy)5VE?%FMKU!*5yKp-0^jb(Y0?Jr?>&jLaFN(>QWbu0YMNq0O@n>gUo&A)S zXUN-S)7hws^*?`8*k5fN8T+A;w}?>z`gep{e#Sj!U)D9(^YgvG+F#>k8U(;1_q=WT z_^aH!7^g{Bu+aH8J@*Ea3AQ~+_l@hJ+Zq0}(YAeocHJI@1k=mt(>tS8)B-=t5#M}_ zDP8%u{a8y|3bDWZB>kn-Klh*iH>LhIq5W?{{dYqJS5g1XP*sIH0?TgS{jf|JWaU0b zW4F2yu5$ZKP`I3Jz%_3)H8*H40hLxsJ1DRD*sWj>&~yH8JrDpIsM+V?ls{C@3rHse z5Kc^AhGO~4P>kjdtqbjdzYG=OMM#M`ntoFthuvO-?OQu-Cr!Lj?It}6*iVzzyq!{O zywUshC6i-irhNb`L(f~Mi~p`Z+;sg&onP3P&Fx|kzqtNswXka7-wkDc{mnID^lyeD zFo*h*$vjtl(Bev#c5`v*b$9P**9(<9ORzOZTO#`^JQ#p`8=-jAff!%I7Kcy~7GUju z3S)88bT+hRv16`N3`{f@P zm^v{j=q(|xHhjpAFg6kw8#?OoITt;vC`_(qep( z*evHT3p^-UBIaLD(|lv9CZp&38>!^=b2$;dq0m3#8x~;BKeix!=Zlo5WpCfz4G+#T z)i|T9A8g|PnM)`*) z?2c$W2c3)V7HK$&do+MWpTnq4XLEIqjEp*#{n*VFgBO~?`r$jh8xOsW8ykwfN1ljR z&`G?J_g~yzoR<0Smh+QY?i0ltO~DRCQAD&F!Jdnd*L!6+N~ z3DA}cVfN@Q!cIjBZ<)EixUAzuKV+FgSQzHkHVLPpcPnS?@_E0rTN9p~(#sS~dU}gy z)^aPFbZ1JVKKR{yGtqOqx3%>oL@vfx2o4d|>IE#i<%lsVbE%Af!J$?$@ynhugPK!l zC)tvMvlVRGjG^6mxyLw(G%pF5kCdHZS*J)HZjRI(oNzI1fa-w?rWN9YGi^;AJ zz=J}lNYMDVa%dH%4or`uzXl|@_V6=Ghh>P^Ko|Qc6PWevIbFIn@Umz6X6uHQ5r#Ly zt^i2dEzryNK3pVmgO;d!Fv1Q20A}`9df*MUmv!2y`F+NY6=0OzV`%b0;{#*?c+7h%Ccd8s+G61UDY{8^Rr$r^;r#g2CDczgCeo3#8~4R00mz>pXC-?Kx-NBik$swo?}y zuOG=eVn8ZJ8bHY6```8Y?zidUy9?Ddcz5n$NFRkgl~!p2nz&u@uhz`W>ja+^{aFK} zoex4AAO~K0Aj@o`kYG3Oz-)XiP;;m%L)rw@g3q#af)s?hUOi)KA6QKA@p?8i*?}#(|1ly#d@84(J$#{@JKB7-v+k6Lq>v382Lsz zr#oLMYyqzVd>%qRc|dUDHk&o=GsKc1HiiAnS5_fcC|04W(j%QYJbO^iLEWY%T-PNB zmtdqJ22jW8*a^x?kM*jcY}VWK^)2@v6&z8&+xQ@9HdFoQT&Y#9AgSYiSN~7U43%ul(Xh8>=SludT=8~N{YtO1 zYZ_XQ@M=!~cUb!>9L72g zUi!(c<+xYh(;yI@F}G4>ng>ciCJdihR5zvs#|GKMP9KVkvv871>9Pp2QnR^g{k98f zmT-RZ1bI-6d9X>`0Br^IIqVJMI+-bZH*jBcXTaxu%63@g=HL@QT!dI0x^_KUi!*3Y z^H;Ey;j=6v@da+!nY%IqxyrvCn*GcZX=S`j1m>1zd)c>6k!#rb2k?k%nJD)^>RU_@&SwA9G)Y;9iBOV=dx&P!i$X&4Z{8v|(>1JpR&K z^4dBTmY6)V-$Y6fS{-nmfq&NUXQyIu?sA_?1n#ioI;eV@M5j4g^FCk^ncPpR8juX6 zEtv9C96$;m-bACuo6LWGGmcc{@F+4vGl@GO;liI$jqU)sa!#^`vqR9D?3U zocB2w{c)M{PFgm41W;fe6rZY{)@Xz_Hx?QOW$L(&YTZ7PvOys zc}wVp1E`H8tpvCb3{!H#Mp!x9JbF5nnU*#9UCaY3gp)uDVL%_VnI+ruCVP?n1ow)^ z#(ed-dzWK+5Cjq<3cA;C%T0b*ZSoV05x36l*Q}(SZ6T8f`6JrUp!ahIl&Iv3QS;+H zkfL3#3p&L9uSDb6oAdBd4uXC((A+4ADg)K4k7BNcaW;1Z!OTxFBmbIy^1ANp)*G3F z^ob# z<*>V!?(*X*`?;nY=4?=}fW3zW0x^<5kMO>eW{I3yBQ9HoLD4}qx;N6T2|+9Q?&SNV zB0p6`e8nQRGoM5$l>>LHqX(oVhE zzcNrlNm6yos@!!0`fm=Uf^TPSEf@z3;-<~9?qIB=Ef5In(?eN>!o4U4-VL&il^%J| zMJyCIJhej6kYkK?{WfFF@(k|R^38@*>V|&F?+QELW!OHB1BTJJ1zU}U`3htTrED9o zhuVJ;@$BCEyUiuM&YvK{3z27$*#m&x(T~^f>#ZE5!d>b`mS60MQr+nXEa1&4gL!-28~BDe`FG#jf-E} zt}Pb=pZy=JZgul2aym5Bq%f|2)35fy;{gyZ!*Z>B-9>YBh|JmWX5_|Tx6HbeoK<_X=>)v8s{I&0lGJk1;z!kfT9`_Z)eE)jSNj^ZO7^Zk(9&MRn z{P6Em+V>g!nSMgz&X-DcqaeFM?jn72l8f{H5o)vag4Xpun%%3I{aMAtX1$am@3KU0 z%xV6til8P{!G*nXzuUXbITZs!JP7KE+Ex_OJj{?FROp>K)cxj6$D@)2$gPB4qV zrPIzEMdv@Cv~A9JsbI zx6C`tJ`V~`#m@AqU7JncMZR=Wi{E-Aj!@!cI0u?vf&YbR_uZO1uxd9kRBP$xv75I7 z>O^md1jPqI)jnfKpy{$k0$6q4%O~f$kBWmkYgDG9U@ghuZpbC%ep#|q{x0ZvHMwFD z-DMG_f=2Fe_epF)G^O7r!hS5do#mZp`XEW_!^omw%ViJXHwbpa@Ilih!#(-(x@9w5 zYOKmi`rDr~BwY|ww{ZE@7;^#tp$tvDypm071?OPOGdjcf(74zug}?xaB}1$GWz2g_ zPaB8J-@zX8$ysz3P~ZV!B7}YE6wL#^an9e79(kwsrvt=94abB9FXGNMmcRmaMlfsL zZt6prv)JioOXPiq%{h|at3<}ohnfMVNj;GD=-TG%G#TAAO2=c9--CEYJ+jV=h-+&9 zom5Kwh7;TqxBC~V5G_(DVjH9jB)31GKM)@nA5o8YgOUil8rgH@mBIIl+uUb&T>ycl zb>{L()iGJ>`u(&y)a@zLSY=d3ShYnzddpO!{8Vj(YQ~+hOUy%sL)T($RVIxXT^GSq=yC8mD~-Gw;$TR@Mx=jbF1{g$3VSW zgv}y8rGWB#(#oW4)#qq^=o<&O?CS!TCjPc)svPtJfvSmPFu0?1w!!A?Z-=VAB0NTM!*(!`Ng4(|z2xToq z&39*oP1Rww*~lPQ*?`XRouteMa*rhx3zmCr+>IW0D}f^+)+gnhw#36K)L5lu#-b*?8d!L`MM_Y@uERCn|XyQ7MxTLu*QHwL5gPxLF!%RkdGK-OrhG#QLj2R6HwCUXJJJPk#P{(a5Eq~1iNU_Dj zgN?;PL)c0gm-B_dAKU8&D68+xf}8VQ+2e`<1NaYg@lW$kUcZf>hB>$Fh|%f=SR>me zhfYzE%T$gk(>vsv!Zje>5H&$yUjtMjzB?w#sTsN5@24r?eL&31Ix!{cacNk#1$iRz24;irKMO z-a5~tzo8om&`I&*@zn{M0ALpK@?Eaiq&3hD-gqSeXkR|xD-U6iyq$*z6d@MG^)4&N zE)Qf7?Rm$!__^;IINgivrZcF%#6B6laQX+`o-;c^>m%@%A|t* zWM7)}qO6Z6peL>Fpr@@>``3+rf@QP&+qmQ> zG6UhnHdpRP*^5lRP4q3Sr;l5A3tNkV)?XmQ1VEpj4v{^8E9KqR=uJPHRtgy-f<5Lq z-j3k8++1vfFv=;K;!45i%%d7*t>vxO8ja^}8-!$vJdL)C+-|6{)1X7hVZSHZNY3)y zw~%JO8)TU33WlmnYx69KU2nZ&zn@GyU+EdJ&YJ-?_ed9z8Cn#o&FZI$YUWGgCvmQt zSdu1~5Ff%V(KC7xU)EPWhzru}{&t>du z59Nfq=R6vm1YDOx*;Ue4NpbDCrF_Um!PvEreR@|?{cc$|I)k@LsZ+eks7qvB6_2lZ z6Eq{u;(JxMsbpdD>aE!Vlj8KLmt-|(6*^yK#{Qwb!Kd8#(DsboVGt4M zTMA)a9@kVY*ubyi=SFeG8I!_~dy=1vc0i4gh%)e~bb=o9nwW30i!w%Y-HG8bJaw0g z^v=3-6vVZec~AK96mtaR;H(1ZKL#>Lg1X_#vmWs&t@O$}ntDnHLmYCQUV z(LAUm*dR3j`uyUd7S~{LvV$8e{{8mo_U5Ye4;2Toga1mXQefLwr7i50`~aX^>wQ|3 z?$dZ*SIZ8yVLFJy9{TAw5BA9=no$_CQu;cs$UMC?)dpO3w`jXA(G@BBI&ji5<`Wo7HZRv+xEL4$+me19KuPVOQ4I8J0@$_CI=; zp{svda!ub{bcXndw&DRht|tk0!t18%tocgrKiceZop}>A)s#L3j)mkZjU&u6u^XYp zr=LGxQ4X_KN7BQec~wuY6<4NmCp9Yci_T#HRn*-19={HO(hZk#@%1dB%Dj_6yUK;`|6v0n!w5@Ra9e|o{RvpU|vGN^yV>(1TN~mgZ z9BesXYx6a@nQ_%1Oe=d&9v7FZ{xF|(DKl}iZBVQXFU+92 z`@mR0Gjoss`7}FYsfr{qu0-qehw}sSX|x#qHIrwqikAZd0%G>ju*8vraqJ*j5CD(!1qMjkoH*A(2H|dV~?#3EU6VSs7sY#r}luM4gR;8X|rWyJC>K}wRU7^W1)a4y}GN$9VPTMI9g`1{Z9R9Gu+D!BTs>bVf~WDg84 zs90-{z;+NF-i3KwD=!Tofdq9?r@2Wq53Q_fCs#X9zE%$CVaHtFHs)!ae*|>sL+!f{mM0v=(Qz6{>vmE-DaLMTl z9Ti_uFX31MWOOAUMAc;tGDJuME?MF(Y9n8Chiyk@T~HW?Xe z0&{1c67yE{A= z2vl&pS=tM9mupzWCOEYdi!S7(OJKB|Td}TCLxd;%wCBM+EYGI`yQQ`O?uw>Lp<#eM z*>x*(|N0nk1U;L3<$Wgc$8GDKLezJF2!msUoPD}Ym)Hwe1YXn+=a-}YeT!|3c^lmF zs$bI!9tR*uQr|0iSM-0uKjKZA47ZlmtAApLe{eh^PMaV>T)eL0JuKs%wooE9_ScoX zn->4y>b1>uiYWNVntdr>Ccjvhl=iG6^<1Q<3^GnRXblK&B@k?geNpG!I{v zJF{xw>ffJr1zbsyj4Q+-pk;Gyl|CqwIT!rg%cAL7I;tWmkG^L+2c5f?z%G181MIjU zwRgZ-ur$7h)?a?Jx%zd&K4i}&ZH zXh6E2TaJ*G5qNKFVT69JH|=SPJn){1Fo(;)x1-9o=zoXgz~TPeBE|63rpV64tZYWB z%4*%{Xq8RRcbZ=h`Sso^H}G;1d*u@-HsW*i<81!@dfCYOEwmt>L;Gxj`HALJ;`Ue- zzDj4qpUc1Qk7v3b>!y$7X^dP6&!tFe4UcZ3iNle2+WEM+Y1GZRi;=O_1nqfxz(dTc zwBs@N3w|Cl4MP!2{wKu|s0YKjx#a+PWJseHQpa!e92?J&oO3>N%N}QE5l~NgE8A7&s>b5tvd8TggPgAb_6n# znb~H!UCS-oKTq;)#HWcJl!K@nMLqPjoh!#e-PIUzbJXo`m-WzoG=}v|Y_n_~nLXDT z7_0QbyGrSk?DG{o%i(4_UC6sV7&QylTd9r8-$wHEpQv?69g|^hw2V-@1Mmg%;sbfonEOuDytC{z) z_mvN@JvPE>6JWIiVJp_qAv}Y4p2l+vo;gqAJD#Oa#%WWN(#MP+4LqQabRFKgM{o`F zd=m4iO7|3W#q@o)pVyR=aX&BCN!(jOxizGC+ND|^agXh^Qi?hwJ14ywE}YXtKL~lA zGt(YIx=)ri>VS>H91V{@m^R^HCRM8R2{B=wK)%;z9a{;OVLJjq|l#ma|^YO-dc$z3>m={Ixxn?aMR* zb7RooJ|OL^kvuI|NIPp6{nhp!mA-4Ooz_gu8*Ktc0P+caIDrGBG%r7Bj)>3?l6#gD z7cl>jWrLZc%wQ(!&HU5*gA?2-J=Q0{rxkxuYh}TcYTk(l%bwK!>a#C>)1HqVlMaV% z*ngLBZtV*fYPeEfOz;bWjB!EAozW2~!8JU0b_v=MU47xLkX=VoE}8v==g03u4ht&1 zeU1>XkLpu$1?!?t$F6V3XUH6*4Yj7veRuFPWeQjDzQ_o1gS3T`z8D3YG+qWXM;Ky) zv1XN(Rkg~Z{vr6Ji1}zJex}#*8A9uol+3|#*>OzBbgMAC z*IEqxFd<*w%f5ns7r4Z6@0WY6y;;51iOYl0ooKTZFrJA#UY-LY9VsHO^Yqb)S#4pz zd#GK7G$S*~wqnEIqkRN_#jzRd6X5T(hYk&sTb7xr3H(4TkFpYHeco&a2+f2`Ci zJlrPNr9AsV-NM6a&vNQ>rLHp$O7J}}n|C>ph%?Ml1X z_0-i$J#QDv*g6dMg?hFkv{R^c^1A`6d$r!z)_Dw|9%q@i96FCBXDgjYs?>pQjOje? zL>-65_FDgi=YdJIPf_RRfLExGe%a}L_|`R6={mCQy#sjnMf8LE(H)_~;W2)x6B)10 z$HaMx1DX!}0P{TwIFI^%v;g(_b$#dC_4zxkaj1`VO~H2)-=|#`KXa5p{6OD}H!Hbq z4|U1dr_Vy0KR)~W(XsY9ef0Mg$_15Lj;Z9m0OWI5N?aly?OE8S@S}BuHOaS1>d$gP zdsy#Y!mm}GQOMAGYo^iHowk}y17==X59q4@9*#|YU++uwj?!LO#We?0fR z7wsM!6YuA?q<#wj&_3o)#NJS_DAYD-Wk~qfT9e2#`P$?>(HAy`Z;k4V6!rhqJ<+H3 zh?GYNH}0Kwg_ z{MYHT-lui;xkxMOPt@5v<&7<;$tNi}7k-V}C7aoTjT=&P_hPe}L~fcz++y?b;6F@|9q0 zE39vv-5&Yi?ZFfDGkpE;gC|yf2D}!14tUviX2vr>&$4{d-|IO0!+4gMVEy**L-hm9 z|BbWTA}_xk|JDV#`iLudE_e#-_$dWr!y)VCP15IKeVvwfQd|$zEM-=}VUjwVR7<%J z?{5{T_ZqzCX}I1>xdkw|S=$wFrjK(*Hu=_c>Ib@9y)s{pJijE;w_7gUJVeT+A}**>YcFnE}l6A@HP)x=bI+r1+%XE6O>S`Wwi@ zKLxDmo904$w7U~;Ap0M8i|pv%!AID5$8%n`p5$z4Bg~fm!ECD)Z8f5;dvsgt(H7fb z{i&RDwB^&Z@hiYV`hl}tDauVjxfQzHy(pJ^UAslQAHUNtl|1=3_4n`nm3Z1?J&!sJ zt*blzv@q&`6Wb9EB6#rbLs)>Y6gaaA&z(=l&xG0ZKl#3ttq%PmWl8EeR{Mx2H;2i) z@m`0e`aR2mH<=o54tz8i^O?3`cDAI$Dvo&>Z{M{-_^$=rxh4q{p7nV*L&1c;h#ri& z6X_)wZ=)WgcX#3#)V)T1VcM8SX}<^ievAAh9UpCB8AeBB^2c$11<-e zDZTohl)2F&yc@ia!mo52d1&7>SJ3w_%KDx10A(}xh3X84)bHqeZ%4hyGJCD>X@7Xi z@`Hvak}OY<7axV^&WXKgkZDtC!`wDe>w!?`t5_31AZ*Qz(qD!A8|Xwj&%fnq*iEEw zosNG&uGjckHJ?~7<%QY|B`=K7@}3`Uq+>1vT4wo;lv$+w`g$|+dVKznoAzlT?vrh! z-3aph6X`k1qOZ}X>0=JwV6&Egz9enjbEI#U-8c5d&^B8>bI_mIc>;ZQk3LwVP)Cj| zgZ&LSxcio1xMWb-gqti4Lf>mMb>Myh}6=Oes=822s&(wRjF`}PRKzMIYV z@BhOorSD7EXO3N3mq+?)>yRZ6CR9IZPy6K5prl_mP0Y|d)K-VDq+S1$+Fp6Cq>)`V z{RWPzIM3KD8pcmj!J#wqTk2Ca&q065FLHg*U)WG*m2-UbUPfit7_+bxxVMi z_UI$eIhbvJU-oev+eI7qOw~3rz&Hi{xM{SaN7}b8o%}m>DfznZuaX{_8)RP&OWG8Q z^_@8RUDW#m{X2A?zkzPr{R1B%`}gi!s;+nNjqksGN1qKt9iC@|VLqeQblx*+ZTj(C z@Qm`aqJKJZh-=fHlYBiVyffhtWh3lQoSSWvdoB86a&8(hH})RI`FZuP@%bUGUy8hb zo%h>1?+b)uAQXKLxWsGi{pZ!apCoJg$t9U?I|F2GG!;Yzk?2Q???aXzsb5- z&ks=FJ*dljA#tWh()b78R(<%T#G4;VoOoH{4dA8UId=Bvg}c2fWw( zu%|Kj6z_>hHSP;BU*H|Z!<;95nY*p6ScA2ft378~rrKNFfZ+|2FIR1hAq{Knv9?Ly zBRx;rULfzMFys4wK-cl&U)9`RrSB8d`OpcUk4{J-3R{twG-;R8fm*<(~ca{^S(rSe!kQT_Jw;<|I9|xjSW^1 zIK3M9y+rTh#3j;aYg> zX12;Tut4u;o*;N0!0S7Jl}%5wG(CBCl%gkJlD3$D)OSxguINclrlKd*v#_2|%vI5E zp^kLlRiRSs-Kne8eMqA~1M*gJ&tIqR95j}PGJKs8-bX?>?P}Z~!%5Dk^0^V?cli#> z`%eJl`?i{KxTOZ~3oX&GBfMSG)^!8#P5HS2UjA`OFZBFrdLeBZPI`eg^Bv?X)x6f; zx0GFm`A6yX!tzcT!^Rn#Kl{yFaXca~QvR%3FWc~}22WD`tlATo;aQ3IK0N!MRX!-8 zXV0v&qu;YUM`$WuXhA{i5nC50{aKRqNe_G&*Y)sRqW3w~hVQvEx54^ZZ=Sc0S9tf9bih_tgw7Lz91_4`{LseZ(VTJSgR7w|%z0 zRq^y0B?)K8$DhJlzVWTW7;pIRpp~}#e9$B0nT&ToPj5M?#Wv-R;tmy21$SiNm z^MV_sJ=N~(R;=@`3wzbQ7r=9#Nu44(BHLN7&g(YgehS;9eSAaAU&BsUcY}0DnE(1s zw!0z0?&r)){E~V%)WI_I&+bUzpE>4}de1ulEp-lpXCn?_?K$(hK$lXwG|hOZ!^&FI zk(~v(vBLEXWZqEpf|TZHYD#d8M+BF5dh}URR|j>A<5#2pH{`i<%8v8peUX%fd1oYb z3%ob75KrD6sqCB^Vs{)k$7~d+Gh~L*7WvLF;~tqb?p)AE%yl$pO^38235+S{+a1|C z6W2=};|kx3uC`X$=WwO&vlo4Sh5p^3gMGgKu$0rKU7$Srh_PF~6E2T6s`$>}?r_D# z-&>47ZpyT5(4TR;%-xxca~w|^yEF6Amt}_1Q~F4^rS4*l!aH-tILeh%jE)4o#Z04D z-XXjR{W1LOE&B{`3ijmtuqW@iMah*HorvS!WrND5E$?#F^0C~5v9>7pQs({n&wu_U z+SeEG4C-@A{@sKp<>+J|KIi`U?GM!cJ67v%13q;hL`sJ8wSExvpKEjQxLSv{jA-jv zxmL3rG9vvvmwYfd!S?NAyHXx~&Y`PE`JzDl9IvDam<#IFY#%W4-x+3mgnnQfrO)d6 zm<)Q;2XPscavXKjvAcS^6b;yh^}#(nMe{&H-%+$5$r+@iS%Eb)V}0n z)p-Nz2w7(UbshsAS7iRt`ksS_PddKw{%sv8CfGg?+x0ppzFbP#*j#U=F&X)`-yqCTkT4v<^Fd^jm zK2t!WXq|# z9*-!L!j%sf}R7iC`IIW5GWLHu{@7veACx$`-tv)cEZ+RsDJsePVn(AX;sFG3kY z1=i;>t(zi0P`y|AFWT$!{*(53t6*w{>p-^cqnNyYYfh^5>y_i}mii?*K8$y_=5G!3 zk?TtO`XsHb{trl7#Bp2yCZoy?qa2ZRugw$_q zIAP%pW8M&g7&>=p_0k_*+n9MKde#W_J1p|f zKF%uw`;qa2NPtD39{U$GEVk(P@fsE*G%R>e*0NBqMck|woR0^s*@pa`55WHci(_vi zY>L_=yE0!5&orHO>9w{U)rMO()@zy#yDucc?rNRhpkbGfKIfzVm3S5cKW!K$+XPoT zY=RTCO|V7V0LN;ZV5NQ^qgC{%^jr(|d9X8b+e;qur=h0rv z_B$aTH#?1d+-B?0d&(zwl#q8lkKc5WvSpn-rgZwxl4lBSvX)I&{)D~q>_Mkhc#QT{ z|yKeH)-%Q9mnMPYQ6L^*F+b`+MId~G!GSPNsC2$DuhPmI$szfk* ztgR`%Rwn3tCS>JI$jX_a{nl9jerwgVUTa(cd3`^;jj@0l5E7G z%(#u%F6X=hcGpB@gJT;jk14;Aa*QE}^a}JpbrIpe*7_$rU1h5xBe1XUs@fAKj?hj^ zIr7Qt_Q-li>Ut|D_NGCGNPQE0=m^f2xmo{)%N*X*oxZ@&dvba}CpS54! z@@`xgM|x3tp`yDRj>dH&`+!@2r3?mm6oF2vL zsmHVLzHk+FM4r5OcX(I!?yyrYm#mXJc;vHnay&CmTNTTsXnJ^kl5UPN@Un@@SAb=! zbf2C_pJ;1N$dCS*TGwc|Lw#f6#G(4eu2iLOG>6eQ@*W%m>o%*n!`jSzkd=*z9rUY< z$>8I3KYpfldL!g{#uZwpw?gamR%o5x3M&V7txApS*WOCfudOoGSRV23j`5I8uah)p zesqV}4SwOU9NU@nW;QHrdXBZ423nrV{`OISrv2l0H()OZJg(AuvJtkPZ21$%NIOV3 z49XKcZv}arG-MIh0_lfMe_Hnq)s=DG6*>HJoq8&HN4xfwNL(v%J=LQF4n5Uu?L!$< zyqGP&=e?`!Q_H3PX+uo^w0EqcOaB2}{#W`3YFsll54nVA>@#md-hY@b!2696-<0=P@P1g{f81-{ANzfcN6;ts#n3)q zOn>DKHGfY@d%5!O`UB#}v@c818;Z9iUK@Ik+^fG`fNzg#9T?AP+hZ9g{aQD~{2uMG zjFP^z>lKXjxmwzey{HGUKF)iAvk`v~@e18W4&Hx6o%$K2Q!?Rc?oIotON#5oocgev2W)*pV~E-l$*XohB}=JO6{$ zo%^ga>)%2HpI`sh`%a?%jj%1Fk|jrOtkpW2{cNA9*LPhjbOSj@{*Y zH8Xa1xX$z6NqPEGR34{)*s5Xt!}jZP+=uAD^+7mTLU01uW^W>>J`Y z))|?6JkeilbBc)BO>93fk3Mf}`y@O4jQ&mgos5(IDjkvEMkSvTX8iG}JZHiCN_RK5 zKC#zcdmc$s)b9z<*6;=GSMezLg$%v77FlXdH)=mL&Rg|od-a*I`!5g1?#9`S`fdBaTl!0^jI2W+`CGG~`(OSS$nH#=r|HeIvAx*^ls!;} z>GU_t1)ZP|e;dkG%uzfA?_(r=q2F1`7VOR2sh`~t^FdBmIzaw?rw%@4!Mt>8Ga3y({Tue1GLQuF~T;J~;R~-%FyhKCF{@VP9tN zFD;&<@+sdrey6|Q_l_z&_&V)7;P>3V=^^TSzAEqeniG9po^{-4`83~_d@fq1w67M%!%YYk|nQC2q*Wr74 zC`#OqpD*Qn(ns^wBiaYHP2E|TJLESPbXsftEF9tQD!Mn)H|f=|SQHFX55Rl%QY(YY z`MVlC*TK6QWZI(OQ#?0_JWt8{p6HjNadk)6{si5Fye~`ph!C!n7jlz)M7p$Z$N`@F z6o~a zNw>%NcZ9m@nl>P*vkj{=QfuBGdPXYw9+3ad87Z&hj1=R%E9K6&&unK|6;8BGOmWyJ zoc5`||2=M>njwZi+xVZ3b826AzzRwZg>xj2H z;>#TIrH*)uBi`tU*E!;g9Pw&LywVY0;D}c^;^mHbz!5KV#7iA8KQbd2_Ghp^Ps#q$mv2iYdAki#XGA}ORoYj??e{|- zWjpGwLCQ0VCUATk@Vztw7>55gIQS*rO*|@1(G+>#l5eH-eWe``^!5bh7!&dR^8D=l zsA2Y|ftI_bfrmw%u9ShGi*Pyhp%`$dxC{@%Y0f8}Mcm5}rtmjM9JbJBdG>{K+z_aRjG2|+kh4>9_RV6@uL z-+#36V{T@uFO*6C??PeQ4T3J=3x)aHSZ+y&SIB#a_NB(}^E`>Zl=P#|XcO&61}|8B z>{Ne`<>y?B1>sXjGx}GjxI;NEFOYy#4k9j74UuuxQGZPGhp*V3; z_nm#V&uRasTWH+uly<0};r%Q5q3HX*3nTRL{Ls8mo*yGGB|_w9ISsh{l_K`}BH8B-<^i4oUfCif@1`Fo zsKes<>rf}sI@i&-asYv6YxVeP%^*iZiLlfl@2!ryaP`l{pi-oAP1ntstqwf@Tv3ZrFty}~*cpd)MqfIaPd(tCYSA|6D{qjC3`r+`7mOORW-HCyJ zoA4$B_e=Ia4|}Qf74&UR%QYvYxsAcP3Ul`vpECNAnT11b_;5Zys}VtZylf zz6FQr8*$hbi1#hIFKLxCLZb5in9sc3mjU~CFNC_cPsR0bU>IHUw=VyYD&&3t{JyYx zafp4`G0eOfTDP9jc)vxvxrZ=m<(ZfJ)x8mDe?zLechKh_ZB0eo4E0&^_hCY<*4OaP z-w-4(OB>Kv@NW3KEaojtRkV`+nj?YR@?L4t!h2-XJ)k%31#Ka>wtbT(+x}X!Q}y~r z+aB=-RX3G=UY`I&(k5z6)yAv!~ck#NT>_bS-ox&%3 zzQ%A2aXrB6>GHi#pQmrNY+VHN=VQ+EeG}wwdyyZ^17DYicl)4({- z&PN&gPx_ttXfOP|e&_F?dVTAp{{a2&ey7u^TguVtn3wU-JK8-@>!c}L@7C$G5mJZo zTm5d=OBnEumtX62yI!VKFZ-y1P52jlnqAT-gx>^lLCe`TU3pF8XDWYNTmSZqeU?%7 zA$~Vxx)=B!=R3slV!~ao3lHbn_urN}=K>n4?twZI^9}JUJJM?O$s6hdk2H^U{>bH< z4qE)6l@WRnxG*=uv-57TGSuksG5a3MWJx%S<8BQX@(hMd>kEIxdwm@Fn;rSZXXK~7 zAp`4|K2a{8(zWr9Ag*bbx`X<0w~mkE84RpJb(X!A^z#ajuSeUosVm_<@$K>sR1s>o z_?w>|?1#4Rn4w|*)-W`IziB3azaXH0zd*}j2G&d8sU??;}Z*3s5EoL8hz!TUJGOHsy)GKS7i*;+foPfd4N zH+_7*h_rI7`wH}zJP6mS%brK=*X%Q~t~D-Wp6>g|WzTcD{2lZU@Xp`RWnU>1GS1(k zVmZcnUnA?{y;kL*5jK6QK)b|Y6gm-*bf(n;1A3y2asOuN3(x!Lk7%DDo@bN4)eBrd zNBaxy(ciF#r0>vi;@nmp&(L>P*!uj6zyxd1NR$36zyBnrKTWsO&eOl~#C*R+UuLo| z;;eTX|_g$x?d{2)VNym)EU0+G~i+y_0&># z4S1a5n!{SXFm2s=6A?@Vd;by#6|UO*r~JK|N~Py?hsfLC%yW+Ep3t9Vyh6rR`aG#0 z-yrW?KmCc)bjl!{>d2MnxCck*8NQQ+JdQKd64|`Wcs6Uz94rQ`VK~q z*=KnxH(I18BSI@ea$k~lbp2$6u44@A2rUn?Ph+%wWF-1@fxPEqY}8}!urLmZlVik+ zP==)8c0EJ;qGgPj&WgS?8Twql+vxtuu>DWUPn-aOJz?`B_8oh)OXidB!o1`)c4F;z zN$|myK@}) zP8${HBwgKYkUm=e_80xl<|gC#_)J%PzubsCXW>1AX~0h~B`0Y2CLhl}wdpkgz9!of z=*o6gmW)N)+1%@;4%z-**_B;h*^?IF9ew=GDwNOibw+GILCOTHke5DC#L*>k4XEcLnkHt56ruTK)U3|Qs0_CSU;4swz z2e*a;*SpYp`8%rImkIj}{(eH=I?G*&eL&n8^`l;Q7k@uxgKX!E5}*Gh;gn1NA>Ssn z@l8ofJVsl@BfcM5=!*Y_m#i0gc)l=2`+IOr@!k|+u9a)aPIn=Flsv~5Pje&9E$3{k z@{30r>!N<1_dt#oH-z1g53&FgwsnyF9LLexV-ZHgA4BfN>uoS*n}aQl$AZwugw#{ zerm3WWHsI!;qO^yLH;AIcF6lhgVB6#uWS50%z41*fh^QxJuH-OhR`-R;@q!3QFq1K?V6f~UZ`oPeLq3M zZxfMz`ZrjoLcLZV#xn+VS>Bc4UvGs%z49F}y}}G}{=Oi83zPTI-3FM_U)98uv=Y4Q z2@iM`_JjIsq4(Ly>A@59VeuP3v|Mi~yD!gv@{FUrr_QJLUj81;p?^TW7T=e2#6H_^ z&+A9h1`>+e^|S65Pb<4!hR(w?9QlBc{rg1p)3nce(bn*qUbk-`pWD%f4Ie}67u+HF z8wpYVt}S^%+6Vq?P}u?OvjZ*EANdKB7HJ>1^)){cirKe|Og z=JqQa`j3Uu4Uo3vq7Fam_>oRa(J~S9trhCtH}cBI^qsF9v&88GZM+j8Z0oH!_sSfgnJh2RQGg7xvyqO z9)GRAZ*Z;6S6$&UmPf`wzV%?;os#S9y6EzPRs(b-8*}5O4#aTiz4tnFr28E41CIDA zN4(t;Z*|0%IpQ-N@lr?J?}!&U;z5VbcB>=4%@N=3i1#_-I~?(yj`%J|yx$RTcf?mY z;;S9;E=RoE5#Qv9Z*jy=aV-D;-~TIr->SN^YU$;-)-9=NX=rF!botzxraNmF*37B7 zy|%ffsj8*6p?><(g*A3r zrKWn;Y)4J8@3WK2)K%5re)*gw^)0oF9o30zi_2$SKm7_*{$1RhKI-D;yo+luNoSwR z=ggbV=ZxaAxr|&Z8iXloL=*mNKrqE(yfx#$DsekvrnpU~FT}H2rd%xQ1o$a2zj#*p zEydG{uPvQ@?ex-HCJ8&OeAYG7XU{8-z0W9~RW`j;%&WhnzTvL=z1ZHe=8MJj7kKb#-RTqNaws z%o;~}-o?$Ai0O0Y%${?Fxlk5Wd75h$HlT_jS;b`w7B(zi+)#hn!p24k)2dq3+h8ti zs=@r4^)+{y3HV@tzrCi#M3um?B@0^`n#|h}oEh_GmBpubZc9^b{q0}7YshZ|K&%!_Mv`s`bq8|rER&-jN}nUV$@ z01c`?@?-KhXF>I?w5G1=ZnL^Z)~kzFEnHaB+#GMWv<4H@aQCp~llt0ncca~}VdtQ_ zhID0C{kNCYHr?Y|&EP7_mZytw%$JSR=M zOwuGgB~AOXPA8Em(D8Ve<13e$fiq&V&Qpl67&ujRdyV~+UmWp#opneW{;A~$%y)Cc z!aM4#7T1_qk)RYeUR-?>SCbI8lCmWwGBZ#lIV;9Za#43{%OW*u=U${Iuo{bDA&6qjx;UiMw_*?Io-d4wp9rHGp%G!#SB3G~6k(ja zQq^%l_krb4I{LsqKsq+2${Wh%0W-iJSN${uN3G&JGYa2`r3_TAE z8>(wmdcwN`{ldD2X1QcU&1H76X)RzWZmYdr&dY5LOX`!p7uVG_+%>ypQB6~Gd4s)B z6EYWLkFEoay-UmnyJKV*Iy2 zOvBd_NwIIkm)nst1J637s(P_Ei2`vMF#a;RN`PP3GO?0lh)86fSD%myc(j;vmozpu zG)W3xZ_cl+F9B0BzpA!nMnltFC?(%kB)Ju3mclM?JQNdqHa0wW^)s_p-;=#RMWhq z4%k(#H!KAcyRk&PwP_P^zN;j@X7YZMxNaBxX6TwROH^8JiC(w*y;8p~)9_eJ`>PQT|K5Ju6wIG=m!2P(a5 zrpmW%rfQ#bai61ozI&b+N@H_%IsZ&WQ~Oc>KExaGtaP+f_zl%g`>go*3ZF=%Vw$aQW{Zo5C38fwU`%OTx%|5GV?Vn?7c;9df+c>Z?6Y^P}oR52rnSIRn^tS zEnpXJT>>6XBfMORvYLc^fu@F*hJ_7v{hK$bDb*Ul>|({wYj zQ`n27#9%r(A&y7VzxiqnESMi(n~VD6YlmxPYyZ%-^VaohP3GwGzWHhmmFag$A1YLQ zb%n~iw<6AC?deaXKc1(CwvnaFdn*(#HB;9U(CL*Gnr7?wy)O&HYz7Uw5wr(s%gAFP zbRz^2JoxTyj?<0)TZB<_S<`KD+0U+*d=fCC2F!i66n<;#@2sn;wS~BRvxYftA(v$O zmR>9w%rlf8lJku1kU6?r3EuS*pYvmNpRvsBJ1GR$=YLk+nh0oSM`r%Kz4(-|#qy|8 z#=84I$xp88)~1F#YU=IJS{ISXug{sms4WjU##vg`QuQfQ<)m}Eew3ecTM1;W0N6Te zAL6<(2_39)U3=4QC6f4;IAP(Sr_^dSENLMy0=G5Q)Hr6PSrhPPz}S>jT-T*G6-Skc`%4KwJM(g&@yz*V48Ar$ z=YVmw)W<1)`x=np+D4n>22)Q?SdIzLyi3fxkgZuFK{c>~^Q;iVymiTKw_$(bR&rY% zD~!WI6}9WQ@uo}k9%D|QJtLl0-(XicBp;#5v>R_SA#vB%Nha2TL-8sS7gh52CL4)a zmfABl8hgi+x&htJka5N;0X8f6Cf0xJ-7Pgl!$iK}E+ATskpB+Tm@Y3r$1C6vfT&Br z&o?zJwsBk4B*ecIUTqdPHC5e>&2_0bQypqg*!itEkM`QL@jZa=8P5&f1Garj^Rb}a zOPh!CeBL`8{Qq-_Jl}$0>T}DWrip8G_%+5d7fXqf<7qiU*d&`4r>%cw1=*WzP?7>or}+p%&HF5&eEz_ua4S-T4amh6jYP9el!0 z@(p(iV-KFo@I7#sFb*Jo3Qr&Momw5o!;Cx0L)1-@P^+6XyFNzMhTWFLa5;zWdu5YK ziUV@ni{+Oy;=m>?dndF#s~#*W$bci;aGm(n5^|q)n2gwyc=9V62Gu8W}wNNBxPy6M`H_) z?Ua(II&-2e|6V zk*M8X4z{_*o*!8!GsG$+ey#3Q_}15{=;~XY@japMrNlkqGHK5CvcPiRnr|W6a z>Fu2gkAwPs4tU~5X#ocREvmpPQ|l`vzf4`R(m%xY5P?^PvAR3n5B}w*xQxc%C9cg@ zysy$}{BD0^+kE;FoMre|ihMhNm$)YP;{71PfKF!~*D!UlT;&KLebCuOz~$PuDAw{+#`=|AI&hy^=WI0ld3k9Xj6N8T!WZ2Zrez|IAkt+hhNx zB&D&e|5Zg>jLG2V5c~**lU3Rg(1@({!Z6pzVc3dzAHpt2TE+&HL71YSTnnf0EZ-=M zO$dI3V|cH|vu{>*qZA>4F!P71&0{|j#+J?CCAY-$E$adQ`JgcNBJ?BV{~^&wOvd;`IU(2xEuL)e9J9z-~Xa2g@&kANw{0)({)eF!fh zyoZpB{CbQ$*`qh-1=PGZ8L9D0Pe00i?Z)upi-f2+twRN4MU= z^KFE4k!L^heiLa&5dMVt%OgeW45VZJTd%?sINb_aq%{k1;BV_xgyRS^@%|lzGK3ou zZbi5RA!~$aJqJ$@>cZr=PDD5xAs69%gon{z6W^Z3^HMx-Mi`6majIzLn0^EpbRn!l z_*aBFgc}gbG`@@w^XC?q)YVkgFKHBF4BxJ*X(_8}Zjl-&afQ>8FD?~Qa8<^7kuNRz z^u^K%;zE{}DrVL;f9|Bqs_W`R$?Q4POUue+{GY_ssRboU%`@vZzyG@8Vt>UAbcSX6 zv=*k#(`hM4^XW7@-&mP8wEUo$I=jAjNp)>QOlRaioxh1o&pFZcC z=-}LWW#!JktL+N$CNXse&@5(k@(&BinOC9I+|s};Z1|Sq z^78UIw_IObCacJ{;jb+oajdz-p10T+8~0|2sZLXuKe;%^$mX2j_g^)ARzQOI8d=(D zzWaO?%)}sCm>QTfyL@)Z?6O;?mrcJ$!66{)beQ};UzG~vVz#ri!yx$i`xT#(sjjKR zncMYBc-_Uv>Wiv*(m2AwJ8T&$W9^Lv_vKxsXeSk;_9r(`Ay>h<%sr#7;jZcRRL=gN_O3rBvg5vg+1pFjF-g`jv58HRbxa(5;e7Ac zzW0`WyYC&x*_?y#wmy6&3KdI$JIJlM6)ZNEXhKqKBZV}?ArWp!x^1bnRZxXgRPhIC z_YYJd<aIR!>iJj={xpvp> z!@@3~$_G_C8F@1BJ#?ccfiQMCiLIuEmXLg-k0%)IOBuvGUK zj77T{geAImz59J+*Q`&vISStIWH`*q_Gfo3=j5R_c1S`h<&++?M2EY3Y3D25Z5ddA zd%g4kfIxr0*E)Lnv&oK@52R#M`Ose73I^aWlfC!p$k`X|@*hR~;Ue#(I0p-KKQ+3YyDca_1wNDMJDBDv=5PZ(jwt=^SbrgB3pd8x^uO_d#ON6we4{DJ-4aan*)4x zw=dqta;MW#ZRT?O^>gP{$(_0Ff4*~J<`ay6^$%hN@oOICuwGdI0p{d*-+UT#Y>8+J zI1S2ytTR}<0SAEnpdlS|e@uc$Ow8evn9%lMJu7JlD!7~|-TO1>2lTt3AAlr;qDQc@d6X*YqgcOu472^m z=@fk&>z~u~1f3y?WKu{ajl!gpK_*48Zi7Le}m#=j6^zw)KBeU4u zsNcFbLKVTKSJZ*`gWpB*_nPxAMsP(?|w`(w|uR}cSP z`WOuNrr&$~jw>WDp3d%U3OO#LmX@b~1uR~eUfwY%?XYg?wT zr=zE6CP(!91^J5`I0_l;eO%j3Q@mCSxbbJ0A~?L+VT@z4YUt{|UW^Yuz~gc(2WaBM9XD z*lAKk#$$|bDdjTUW-+Tz3shi%a>y)798-(uzQrujTST*%}-4J?QF8rIBw*&I{tS;>y`Zy-5 zw_JlCi4E4_$K`bSde*=y?j3DBIs?A)0{-~Lw_57GDFd$)p5tq3 zTDvp7hi-2AKmNSEH|zh$-YkClU%!3tWZ^S6O~D*!7?cD_AObac`y`*R&tBm}c{~<~ z19FbT?+fD#PnK|OVVt+8gVMA6c^2l`n?TjJ_IBKv|G_EOPL6$L7H&zo1Fyng-Vc^} z?m*;Q^YAtRIB%Y|;Fr?b@sP z!4vNyr^>^Ghy5OAfpmhLDWLCt@ewdu}eR%&4a)yDvkCIdIK7^kj=N7P}jGW5* zfu-a$GCoAkoQIWVz;~0=1f=(pGscMYtBii|=lCbdDSZI=0h9wgf%4XY5af0&%) zgFxh;0Ma|j;WI3BFZett(yc!z(lwO>L+JjD7s&}e1iTM&JtXRt1o}Qg&e}twKJ+jJ z{RTP9K;JpMuR!_W@BbhW{3Q>YJskFM#={k${{__R!zibkoVpPB)RNQi2*MANlY2zy zA@~s>(p!ulBxjn@Bxm$dAs64_#`?Pn^fi%F{ZXOU0Y;0Q)MJ9*0?_{$>hUpzPmvR- z67>%PPc)M=_&DCb2l{zjlv905VD^+qmpdiOoAJVP9DkCWMGsdQpCiYth8$-h?`ebs zsQ+n^uk*CvpFQpIV=RHacsT8)n*;ii$bUw(TmKmmKX69m8v^>OU>}lrUj_8tPfkV> z{HGZ2fn1VEzvQJ`_He~}zb1+Dwt**A%JbbzKIG%OmweDS-@U|GrwIPzK>vFv&-Wpf z!2Z@a`~c;7pEkEo3h0y3?i#}A4^5h|-w_YGQyorzp?& zP;floL*av*d=G_>>&f^P*#D!O{;IQ(7k?*_sjIyZ!##(=&* z2LB$>uLprX_!GX{g6mb+E9|G=3r_<5Rg~v*xm-^^m&@(K=W@B8a~Yv0K10j#e1?|$ z8=q}0sYE-yh%o#)pLs1&5dV_!TYTQN1mnkazwiTzmqk5uKwn9TGxHmwo_yAk>s9_) zQBOXr$YDOa=tF(xKP&1R`kbiO`sal{tuG+_J*0a@*w54};{7(z_c8c^S4DX3RZ-8< z*91zh33(P@6XQr?7~wyI9eoja9sc%9Xm{8@pGo8T@|iSlcRrKm`kUVpd@K(eMu8YF zS4M?>2frfFVGNT~_PQ7cO`wnU{<^T!`PW7Nss5_KQAVV19~1V>=gpY^Eb!z*=(k@( zJdfwVlMhpV&I_*t{rAI;zmD|qlXYJg`O?6XHs$&J2+PgqN?4!kz>=pR=NrfugudSp z?VWl<=rQ+(kblX;z;BE3We9lk)0F3PCMS?z`X=xy{PDL$xwnA6AA!&B0qY_E?+f{6 zfF+Nh{*%HUn=72=(qZ=K*2 zmnlO%)J5HN&AXAW1Dw0vJA1Jfa?{9=U7`p`qffiH^R?4scz@2j-LC`bGwzKGwccGQ z=e)a6Lhe0)-G~!+yM~Z2w3~`=4dn8;)DY72QF`~JDAug>{@pUt)Cw*yqsFand30!5 zmynKS3Avp6z^BbiJA}z~$!`7X+*?}O+UQ7yY!uK=oouDPi{y6eBAoiM@i|dny z{(9WI7du^f8r?e`Lv+^FZkrc6c#~rYT)JF6a;-aD9qgAq1j%>qY^)yQ_2lXu8aeXg&GIn|O-O*R~UDZ3}T7AOh@gj0?x>}UPJlb6y-{ZyeP1Jp; zSLTj3#gFE;+x|QUTkl}o)zSx$=Q&tTgUf?8&UY5q&>8&qlKbBix7{4{glj9;kb<8& zw=P#)z1`k3i7Lg3QCGvh##pVn6Wwso*-V=4W~aGe z-ZU4@p~%fhBQ(<-OUBw`ov~Cb9m~Y}V*{~4XlpID9@~g*##ZBN@%8vdywYysO}#V% z8B3+0R3?>6GxDrFC+FpPc|pD@FUq%MtWH(G8c?(9q&lumXxkcvli~L8c9`@{eM@gL znvFSQ-PnNM^5#4w*)q3HicCcO(Lj`SWLlQxSanvt)nFy8Mytu1vZS~cH{({^i968M ztUYHF9}RQ$wW6(RYudWDp>1kgZh8LjPOFuNE4-Gg4ohJzY=&7QGy1GPr{~dn!^Vg) zYRp2SRddZ;H#f{pljSIl2BT%s@@Pdg6s?R_MYX6IU5l!p_>0 zcFvx%r|lUbWs+zNGUlWyXtZAxgu1VIk*L2pTYSJ~Cn*N%_np-tXHOn;;<{(q0Ql(TYdp1_5)GG~2LTOZ*lxC$= z4XS181llpHO=>x9N}JYZU}dRrI-Eg2*m7I6Umws1^&x#n$~t4!SVPN>n-gZ%oHCtA zU8FwJ5XnX+?_g=evC-IAY#e=7%z)=##65J`FI7l`5@6U;C8!P zl9%Nbc~xGMO@-Up3OnJtaDBKToCr6Do5Ibm6?TSG;T&Wi(MR<$eN~?~7L1!lomp=- znEPA2Ix4xXZbhAFU9>*B<4M-6b!)@gv?%5;kTDY$)0V3wP=%JrF644AczPu)m?K7~eE4iQ4yv zhu|e9poN)mK72F0gghH)%Ya@6pHZ!wdL4R5GkjYHEjyx*>yv!p`ZUojU`NyKM#{(- zgXlYx#uWVRoG}kQ?syrt0q)^jhTkkRt4zr>&1&efKH3~@kEWuT=s=v4*WtYuw6OIcwUQwdSn6HE%6gi}3ENXo)~9 z7%Pue#6q#knDDP=tS;6FD@(^HPqYoWQ&L76lt!gV^urnS!3AkiT9Q`bWdm|hE|)`c zl`P47e!oFZ$c=K7+$<+$9&MKOHTbU5g5FsTi?4?-Yd5lH&YU*q;89oLLpI>gC=!U2 zMJggy5firG7-^2QM^f&{Fc2Ax3`K?`BazX_SY#Ytk9$TgG8LJJ7FM8vZRkLZA7vOh zBv%VFu&Md@B5Z0iz73lywaZ{tjj*RqJLP(zVb~MgG*X<3P7KzqT_W-P^ zLgLY_4))X_HA*RIz}3c>G%ig*Cv(zG=wk)?SeN{A8T3&lS3@5fG~&2g$Y8V`mPh5B zJcT~THn1kI7uaJNJPG@d9q*A;I+a0XNSRQkFhcXlyre8E>&k|*scb3RieIfzL#hey z*Q_Qno~6{Zno$STL3KzSRmaqEj2=04N}X0`)j2h<&Z`URO?6RSR#((jbxqw+H`OiG zuLZPHEy&9@%-$H*W$qh1FQ`yLN+o<+QpqU&%A|4&WtXcON*jVtTU2>IQ9>p!-J}3U zvvQ2ORnU@&@xNY5NKH~w>clwQ4^0h2SL0Gv%E5=vN_o$ER-`p)1EVy_`)$a9{Uo5Z zB3?1YhjH4=12S)?pg54`TEm zRmPR9l7lX1(dQR1%UQx)U=4NJ!gw2iuP%o^t5gX(bug+VFru(t(`r9-It-nTqt-cB zpLytVQC)&2S&v&PL5o4H95ae4P0~!w(dsd)Xo6qq)Y4kNHVFSRs*P(|i~`db0rJ{{ zwx}&>D;RY*FyazM+aN~T5Jp)Ep4WlbO~B(O;ce6KH-q6}c%1QY7CvV>JPWV05MG4e zS%I(GfG;LJpa=DGc%Ld=g8y;!dU&8F%&P`K@ z3IG5A2mn?ffjkpGH1x1B0001V000jF003!jbY*N}bZB2=WiDiFZ0&sySd`b9@0nqc z5l8c(m=Gk%XMznTsNcW{!=LCVXdxkS0{AbI3c@Hf2oo5LcHLbPFw(9xR87J*5@#E? z>yz^I(q5A5?loPqYrAe5ciAT0b$eqo!|?4A^fv4*N!Zqw`+LthAM=4Et7e~PpXc6A zdveZq&U@bTp7(vv`@ZLo`tW02EQT>=Lz54(<^g|P*9{lx;-Klj4YGnSGI zOUrBPnpJ;OJ#59Cj)f+1O5ua|_TtE>U(d7NmZyj8(>%2n?d#{C&MYKV##c(Y!L? z+aEyQn=c7k6Q$eusUT%#Q%zN%im}1Fm>?9DZ2fdN5B|SWfUy&E#n{9fw(Ai@w2{&<_aPIZf;TSuqFF<+xJ9jd_ zXT=A$!H0*e-eA~L84NQIau$pnozE_-%1Pa(1;eo_>MJ|-uc40G{s?(Hl5Mba$lvXTYq#HN9c%3y?P!3f8r1S6Jse0w@|J8(V?JXiz~8w-Y^ zX36>LNj(;0T9yPOPth2tcgS%L(D<5Xs7-4R^{MZK<5_70<}!Xh^6|;ZuE4chPPMc|ug*ue}+LL)|~3&JJEv-Rr2cXkQQ6wRdz2^A6dyH+75h^w7U! z&P10jv_gMJ;;^g4>o@hE&^Pjbps|rNtxJzV{!@J0koO~xMgC97=OBL_c^u)zI2W~d z!WOl3+Bmkco?$aT87qU#+85q7pDnTGv=1?io2s_yX-Fw*yRIS;Z7CSn13j{^vhX~} zSH*WaWNgKE9KNkNtwX8WG2V`{HBCDfi#7}K96D+teIs49{?EUfXL*vSrw4krXbuY|jJ3UyMD=dvnC?=KVXQ~Pv3#tcGfwx13Zqyn7{n(q_jgUUQ6uJ z?P})`@%DApFNCa^_M&cAI)@0B?8AxwgSnxO_(65VL!(|Brv4aPLDED!3w7!?*u3X~ z&tdD)Kf<`{e%?7W27By=tx30r%|28};8d)qh9IJ66h{=uaZMSJ}tEp`-EC z&Uqo{=cabl%`x?5;o;JU|*21>UF^W zk%UdZ4%k)+n`(kJ^jk~q)Ge@cT~3pZd;7xWqz}+%*9?9Bvw5&1;PqPQ#@z%@6_Wc1_8WH z+Ny8=M$#bHE9`36pv5&t_K}T}&xtkZ9Kp{q!Bt2&V=iXhTwq$8LFnTE5-VlOh}6-v zCxxDNNnIV2>ox}K)=Ke{pW>xp*o*ly^{DPh6})>5bi1hzW09@oG zu~0Dlz@)Ghqw^#^SS$8YF{YLJf*&?o|H?P?ONe_?W~u)t)RSImJQe|6pm9C$C6ay7 z1W!o^x!v`=G4f-HhvsChlymV4xe<>J%D9N^d8_1cGUy~fP4toMYasgyDSNYQxct#K zUpW~&HaQuOn1Q#^eDi)YITcTlOcQ~d{ORo`++(2ctG}5XO(Gs3)g#p+b(Kz^p9Q`H zeq$ITT(-_Fk63epf1Ttxgjo2{56Q1sZ$C6dF^CKCmm4V^Nkd8m-Kpx+h+hurY4}#P zL%QLQjQE3MEs9wT-wGXycT3*^I%5zgfqaaQc**dWnrvs@Pz>-{fX{CBdw(Afc-%pII<&2j^QXG= zWz+pmBKC2dubR{&>?0RoyhM^Q!+2_6I05A%c1bS`_2?c?kDl-C(G~azlDh-;41Pwp zc_|+2)E@yIRR7JZ#u^v&Bn}E2tI%4f_(jrW)DvA46EW=XNVX{$^PnlNTLL^xdx6Wi zT*`s5L*z#wix>1t$YL90ac-TE#he+kumhH297`w|NvE|>ya^rB*TUx!tRMDf7wnCl z;!E;_*xOLNLh%~e{xQ(!DrbrvX>8Mq4=Ue0sbjAiqBxxO1;ZuMXIGNX)?VT`Vx``M z;NQ~V>u8Mzh%cd+bZ(0&?k#wk$4v7~^kyrU^epgub?B1r@?6q0y_fWi%1gS_e@WL` zFX=xxdMSMNTbIIVT8}=c(p(TXz_+N7Nt*I>#0`Iw0=XnXE{Twfg1xr`vaz>9PFTmvluDbwt+y`DpGNUgGpJHQGk=qq*5opN6qF zlTOn7JTK||EWk8B_RHgXCH$NgFJc$VkAsn#fg=&(<=As?jC6p%2a$@(h3`A@>&Z!4 z3s%0*2}bf+Tjc4vV*gF{n8y4HbZOu~8$pi@S9O!lL_BgOBDN)MOI6wO9mrHI?9 zzL)Cd+M*cZ6_S@K;b{H^N4c+}dBvGzX4tI%j4?ZYdt+l-k$>s8lcNmqRPIBW^3JQ1 zquhs~{19+XGB!lM%BWj-HCkuv_hYgCu%~)UrFDh!?X+f)lMS#UCp&~aDUZc$$g{C7 z9f&;@te>@5Kkq>wC#2n>y4z7VZ2De|?=#T5w*hy?RR0^$+K;+Zrn(8#k)7@~)qMf| z=V07hF@7BKTaeq4$05HJ`6AF$gFY3q&%a`hB`CuVj~e#c3cWV)-2r?m>MW+ZB(ejt z|Ig8%bm;{2F^F^uX#}YsX%MLw=`7MYr1MC_NLP@?%SBw}Fzjn3_sijxoUdCW>6F8N zk#3NGIb}Mx6X$YUB8xfCw@99EiQI;{ox&WtKwAv#*o!i*x68Pm&e@!xcRqaee!$fN z?ga^Bv@b_HZ1QM1+KbTsysH9`KxP3M+ad$rPD zyRhd#dxYe#l8+?(6j!pA$O7^?^bL8u`K!sx8v3XSC&gODKJ^>YcM$L1!Mt3oNB@<8 zkK}^KX|y*6UI%PqJ=Nno9sN|IA7$(hhlqz~wF}`7n^^rJIS;E7?LHl5~-D3i<7EzfRiA%|AT-i=g_RJ%EP=0Uvghm7r0 zaVbmgo)obH);XPVSyo(~oM-4jlGK|J(eCAOP%_1k78x63jU@l0Y{On426_=ou{r3l z7xMEGHtME0P{yg>;W`f9Lw{1e?L00eno|*@I%I6}t*at7;pY{g{WQ`5(tAjxW29e( zo>46D&G)1GL5BErc#+tT)hz7PkKf&+cMbLEZ)YOrL_M9=|AO=aYjz{}oCMuiLvob+ zGm2-aZoS+i(Z0FH+N0Ni$8pfBzsG#?rCyP*rMcI)oz(L&Cxvv1bqu9J?)ey}pZKD6 zb3W2p5w-QA&J8-|VxFY4{|Y%9V^+yAtz^>y`zKPb?4Zjk$9q)j6V^t2j?^cDeIZWh zz$gDcdHLOplX`GrRJRtb3`XWk-I|Lr-vUnR^Hub*#s?$cB|O2tFy4&qg`t8p4gfA*}P=>S5mRJ@j*H--KO6@>1+sN<511(|*Fw zPN8GT?=FR30p9bJry!;QuUdesA2#DSa9K)%k!H1B@S(3${~O>Wn6;elKjyrmwi&SZ;iPqRRO;zB--pja zyh(PdXbV%4kkXMR$X+2ojdTR59qAm>d8A<^+g7HeA=SVR6m1oD&Di_^dl&~hH1rRg4zZUZ+ev#7H{dl1{|exVu60~TpVyz9qWcip+X&%!V~(Jm_Wne7 zt)%0~R@0tt=ZX)WAbZp&_R6F)N}{kwrxTz9F6j0mG3NI$<}yCscJ3co=taJtrWmu= z6puKB9s1d6OOL*u+uC4c7&0Lov_?-u*ZN5|p!YQ00k)z(NOIjCDFt5C4UsRR*w?^6 z75B2o!Ug=?VOwMlx9uX`N{eCe~gTX|NeKGspdNxM$%3dVUw(nc}F*HOL?w(6?Mev!^UG$HKO zptM)#6hZR_NiWe_K{gFKzf|505q?8nZ_9mgGQ}C%3p(xFct6CJ_aqoFN9Er6#i_ls z(fw%wXz;1NhEzY!$K=%9L6a5PXZ?=Fp zw}B_?ZV5*I5@QdL?`h>{NIZ_VsU14m+XBUYvq=6h!S4y+JU?L}Y6mt)2RFppEo}VxfE)a}x~tU5b$oqy4NleH|!h z^P{c*UoM2};WPgrmi!Q{0n$CO&QhQ!+kn$fcREtvXxvJ)&6PT5XXMXW{FC_p(8exn za^Jvh6Kw7g$nQgftqexiL3j4Vidg80SP{$8T3`f&zP~iB1(NUf*qLkL5Z1yWtc625 zlWRf5lY%x{b0PVL0X8=N$0(mrqV)U=={M-Oo$K)PQ5}XZinE`ipJ^v~ACvwnGxV1g zh=4@&3_3(?am&fN;7 zo%uQR@=03Hhy!UnyV=ip1uYiPelL6}-8E5cdJD$9*We@V(}{M-m3Zf1hev3x1}@cm zSSQ>w&%DUS(;fa#h{sCzHS@Nc=1qIFe3PzmT}6yGY>V1%x&x&%J)vJw*do9NY*Bl= z9c9|%&^sD_e+C~X?-L2ICUe~h#CriLXX3{=_+j6UI2Ne{sb;%~VO_MYJc2JBQq~%1p|d1Ea7R{& zw_M%8OL|Oegzj(&Khb+7_{R4-GvUBXrk}Sm##gF5Ugz z&tvVak>!ZzM_@PR%Da-^pAdWhbincZeDLMNRq{*-`^P1cR-%FE*(S#wo}5g+3u}PJ zzC-Q<`F*iGXQlq<(DzmeQ{rudewLGOOeUUR{%G%bi@8edI6UXzAYg?OL~6zjgbM!SeT45{ASIb}ZSI7i`4=&QX40v4N$Uv{ zjW!dFwD0vuTSdN(XnPH`#mhDRvDJ8A$>M*4vSJ$Ve}hLhIZm$}=iFo0uBmR*nj)U; zm*eSjyg&YU_I33$Yt&BCcy#YazUlT)#G2|Cx=1`3O#@z4;{7+^ZU0!ne1~A?@xa#n~F88&{@v?mtZu#|4ME!vTzOd6?FavUf7`*7Wf2u zQ)u^h4sBQ~{FefLdFalQ?&M(4lODzX>>J|V^q7_2+xjE-@N;giJ8$(t-;K9d&wnD; z=jF-C_`CQ%M8q;SdDh!1`_ntiGL-$M`8LS;K1=%ox&s&ZlMQ{M`P?JVAC`Vhu>-BS zOS%ES7WfiP_#Wf1@73|=Y}8xb$Pf|m|Y=g>yU%S6e`B)_=hOnDOg{D#t6(b&Gtk}#f85m`67QRfLb1wMLljRfmE+wd$D_M* z=6#<2ctSkghs8@9n<~deV4pkye)9J}scfydDDI2=#z?^@X9ZBka${^7^8cMV}4FYvgO&$FP5pL5eZqIZdG z^oN$HjiUCD>`VG}Se}<1hg=Vu#suz5HHtN`Eit zhVA^Rh4?7!*S9Rw?bjQi#V&2aMLGV+4&itCm|arGFs=q4X!x)%uEZG75!ThIfB7SE zzm+EMWR3eRE^o2MBjg)zgS^w}zN7V7E^C|m#gI+u2+=uXuVpHJ_!;xGL;n06;ni{} zXTtgF$3o5@Lcd5Rjh5+g#@9X;XMAar4g37qCO^PhK$OkjOgAZUD8~LyaI{toatSTBgUJE2NKEXq`R&bXc#AKmBqJtrby!>@d-3Q+cdTdqtgM656jV zGR5roS%h7%hk6!cPK&X27ssXt7unQj_#18bsl`7WpIpNCH?n_%seiK3U+q~On-W}9 z2psTni{sR%7r6)*aJ+{86#GL?LknTA%>DU$PuNB~@Hph0O61+#3CyWi%Eh?T1#OY# z;BjzV`bWrzU6?7=-@Y&QiDOcJYG$XtVXcUnNIq#&KKIj` zKU!a~acT5ED4*WmxA8wWvT;@C(7L;Vk>seJC95$#`YDT$+uyz~{Ip>UiRO(Tb`Cu$ z{TI#I5BljGe&a3hjWh5Z#dq5+Q9LdQ_iHvCt^;rh3!-pTM{CLAh}QL%GG(w-@N=Ma zdThe|2j=~KHnskenY8P3`I`!U_Ze?Rj=g+xj42+mn#vYa+3bV=@T2K5%%EIH{QZ=d z|2dTi^mGxyew|IlLdhDBp^st@UPkw&i_)}b7BhZt`b?}Q-;5b+hTe$!KAIdIsSx*` zOx}4e;O94@JTs^H`$!MiqY)#f?sCF6^Ep4t-!NG7#hpLm{h^vD-{Y5|?Dg;%AA9e1 z-9m4B@lAVTyVkCY`=NHMm3F-iuw9lO{Z7cl&W`IoDHDowsXoaf{``_rPxmAwAN>>Y zCMJoU)L)QeGx?VDIVSq>H!_c7z5}3T?1X;BA1#lV%EP8|$W(sMRK92`ziTQFn#ymR z%I8hxbEfiuseIN{K4U8Po63Era<8d;+EhMeDhEyF6Q**vsmx4eo2guBD%Y6GwWe~t zsq8nED@^5psl4A*K4>bpn#%2_a)+sW#8mDwmA$5NiK$#l@E zmA9G7X?}6`MCXuG$-f!rjxq8LB>KegKST8N8zbEZgzcw&5v>K-hRfo; zC}_sIr}y&Xp!+J#1M9|S+;a-sLVNsCieb2I3&EF-1ru!EL-56$!xNK}x%_>yF=tK8 zncjQFIS_+7h@Ll%_Z`V6Drx`!0=<9cF>i;L?x>&FZ643i96rwRsry`hk4EzWyv%iAZ)N2fhCUua46_E4?o=&Wd3tenfA|NX7#vbO-Z>)$@H8`g3f=SBewT zWSe~e_D_~=C@1oAr+ym~ewn`?$2czfvj%;P5ufwHgL&8s)p*D+8v0R|5Tk_>$Vc5h zWjBKsriH@v7S_gX`!hQ6-X;H>5z#UZS_%e0GseXDLz8zM8JQU9(LE$rx&f09AL^mFZ{U`2A-;P}XS%tQ^u8<@UV`z*CGAAB5tn)yle*c-|7=q+zO&Oq zkzZ!&cMdlL{(Jn=NYuSwCw`&ZhNWB;h%F5eo_I-$5Si;4Rd;96v7 zoeN2qW1-90`9$+QoaXyDugk;W*J8xRi=bnR;3F4NAH-dYDUQ37u_d$*OHq1a5l6;C zw)1H34*epX=KE#%`O8G|LN{xg4HuG&|%f7Pz~7GI#TF;Kgz%-6K9uG&}X+f&yZXsQa-H8yP6U+wc#VK(^n zMya5&p}|*u{qSXhs(>#FN^q;{8dnuJ1bj_RE&hP7rg)PH(^UJW8GY)j8uqLzZD|P9 z?KPoekE|;%-m)QA<-cXk@pG3or!A{n&i|5zM_40MnU6K$e~m~g+l#Me{I81bK}lu1 zWqmdB8eX%E)w34#EvRa^H=ypWYp7ADMgxBKR9$_&8mMh*d`k71>eH4rFJ~J{OE;C~ z(%*-Ht^%gnSKSB{*MPE>71fP<_ck`HtoGC2qQEv*)d6p#THWLWztjfbQ|dJS8tr?0 z0Tn1AvzF>WW0SfY$qblQToPqhS)i$|VNc%jEsW*YHPi*xFt)5YPu;PszU6UsSsCF4 znZBwTwJs_Sn&tHI9`*%l8*7RS)w4sk z-?Zz?&?vQ_zN(pqW?o36nmqw|1W+#E`s*!OSH5vm>BHsQy&H)1GRU$DvI`*Cs|9=m zpl9-FitZX8>3VU)lPz^k2cVEm(?|i$TiAa9@>zHb>zb<@_xYNp<1CrEA`GwtC0KF3 z247R&gR{u$u_;<+Mav4!bQ%pR{rxK>;JT{%y07@?ui0q8lHTVl^zCZdGX=Hj5reL2 zLw<_J%!-5k-m(@oU0v29lKIP2ZTk5A--ox^3|>7T^vclta$j@6(0%wemW|}zv8?%V zNsnBAqwjIlAt}{y?=&e+S8eafQ3Yt*UD0L-0Y9=;SSJV3Be;bRb-M7Ck&>Yn< zwZ5_Oi5CBishHr4A9-|haq0G*;C8J;ktM zRSng?M~JsOmX$p|gC5MIZufyHG{TRW+H0$tVJG(oREf{rwzX_s2`68+JwksA&dkd7 zaDELl=C=-`)`I3bfk~~ZClhvn{%WHJtPF;H+7e7xYg&Z+d|+7}=&Pm~)yu|f$k@~1Xw=5uL;g(uUZv=jo8(KA)ajUar&b$yEs)dA+Uxd#&t$ZGn>}0iH9Lzd$SZJ zGinUkMqyhTu7$?@8fNw|*5Zz3aCVJ;s8G$cF=<8l8mgNP2*=zgY{>NXsum~%LXPUH z*Slnta^xUE5Y&TZL$=ej44?A^1V(+>`|-y{(56ZO+JXInY{k=siv!t(#+}a7BuW|YML|iadjo(mDH5_0tZxD z0P@>B7o*CoCuBJdc9~(R!2~DP{&fCwIMEOtpUA7KCi?~{o8Uy<3|&LKgB4I$U$v{= zXXXuXRM$5)&(ITsPlNGZK3mLEv{V$0=^xOFaNaqDU>sD zsS+X`15<**G1K%^Q(eGk?$hjRkc8tWTG=)2v!FEV8nI(aP|dY1fttprW}2O8vZf9+ zp5NzdiaO1ix=pPny$2!Cx81w3q)CS`Sswxqa~0VT?hxfNVxQ&<%Rb9bB3gt8Lu6UN zHn2>@6D#pm&uD#>B7XGq-9UhCL}b~5T9QFEuk%T`D7^biZ0h%;os4zErw1R8*8Sa1 z#{Yh_UQ^xAQ0MToS$`JBTCL)5N@FXmto5&AS*wbC%)(k#t&1>uo4sK;3q<4?#kl`)-1U$nzK_Et5-v&oj@MH6QJ6P7Uoxh(}w?GFH~q*R%EIMVrfuOL)0pQ|X4n z5>cN1Gybka*DkJKJkF++RLR&F()lXJJj)pCqrV$5m$55|0?yA6N>DXc7p*;p*rPaLzexh$T| zV-7YSE9e%cumrY{ErNb8hVI|SlGyDmnJr-{><)G(y9?UA6gqVeOGPyP1$Hl3znt9% z{Y}UETFF+yCOWZ?%EaDjH8XZBJF9(MyB>U`c;}{ul16wsQQX{6&p+TzcVb(&lXuuT z6<2gSAfs++-L4##e`KlfcX(>WT}-Ar%u4(ew6 z8@sFTW*4ix@NJk3a}u^xcY9wD%CZc?cq9;ovgVz<2W5*c~eXC=Rma; zmbUS!=7J43-dRRiH{6fnu60wJyqoI2bLWFM-En8;`r_i7={@}n<0cU7ZQN&;KlE~I z9W3tW_Lfapsdc`65=Zk*BAIb|cGFms1p&V~f|K?&?}Td${0EW8r}irq=Lzfial&;N zh3i99@Y#{vbt2&hh@TfradSbVykYzNs5U__ch}R#^mC#r^;Ok;rVYIzG+1n(7gO02 zb^gzbV=F&LyKyAtbR8VMs=9FmbVy&&*sxCqi#PiF|M7f@e&r8-_Ir}EUZ$Kz>OiVQ z(vX-}yl;AG6a7mW|Bw6>ro_ZEPnyiVGT$%rApJ`hG0fA8+`5o?#wlOMJRJ#4u_Q9j zMamt_V_%3onR)y&zexFf=5Z`Sf525Bw`^pdKqB(n(N6gi<|$l^_Bm)rZp&sK_pQKR zfco1oejM{uQa+D)j>!Cs%!g&JB#As9xot1=jNOj@cQ8*)vcP*#=Esu-o#!Y|2OUcU zo$pbO{`M5)=y#BEH|V)T%)1u3C7*e=-HH4*=IKXn`vUWnY<*LdrQMQkrES}`ZQHhO zyVAC8+pM&0+jdqu^XA{(w@-JE^RmZ&U2D$J{32p)2H(8*!W}Z8pxaS&qtVZV7X!vR zwvKMZGf|!PXzgC4>K4R68UL)dnNi1Nb@)zlluZi}2w2{ek~z zP#q^nb+lW#6X;FyXoqv^-vt$~)we>GWc1 zuWHt=fe7_&V-Oelp_z~P{w);v^LuIHeb^V(7CEtqkA7u=qn=gjQyVMWkV$oID9voR z2TzDEHdePn#{)$CI@h9Ha)RbQqm zhNX_DS9Rn(9WD*)1&emLyWb!yPsfNuoVF#h2d&&dkKYGC|L^^Z9!#&Go9x9a7agA6 z+K8U7%~4zC(FPI9=ORTJTzxdO@N(YWa;p2Bc(paZw$4&yVWWq8$j&2 z0>??3UL_iXjWx+##$&b7ol2Dlk9P)D9KWAEEYo2Al}Xk5wkdt{d@J6}rfhR{!996a ztkE(r*^CIWPHW!1XinRR)IJ3P98>l6?@Avy=u1g?ax5oSOkYymX|kP=<7$o(;m7R@!!%&pD1JcX z+sQlxI~9|Mjb(+ewh7G3W3QMWmTfg2mD(47ut#_w@!Ouz!|fOCac7dR9vSOF9w5C- zWanmvj#&T9NS{q5ZF#zKy;+AGC)r~UI(RCjPN?qr$=!Wd1AiJeS#qpP)=+u<66g`+ zO{K}QTd9#AR($3AB4(FvC_j0KK3~u-wnL4)@7(b_mqYljT25O&w|2ACsG+9WNWPk$ zp80F+X8ddx+JIx*`hJzwm*wU}d)$?ZG>$QiG1i`-6t9)u$=6EdhTqCqOIpiX%R7^s z+B4i(VlOk7k-)Oea%A9X;%>9Sdl+n*~;=RX&m^_*>Qi{}fK?+tH_)5h6Tn4_GjD)Bn$ zI*B@&Jn=p(ne8^$*I7s$eOXEzrB0qsZ;o$Hl8%4ckJ>jJ-<@U-b6D;S>1Y1_{sb5S z8V3r8Bj%xRG4-Ar%&4@owz{$cvU;xNX-gptgg>oVv~1F>)|GNBVOKG$SUB*W!El7- z63gGHIGT3Y&BHAu}u#WRtul6Evz zFpISBm1jSv20)~pqxr_- zvZ-6M%Ng^j)6vuM(`j(itm)H0Y*5B&GiX!oAZAgKgrLNRbq61xf6h0UTw=0BU2IV=Mwpzs0*!b=JZM?&$yA$`53D9CI zTdz*)Qw7=x5+vj!`s#(m&-eM91n{o}X={PSBlw>|`B5sVdkc%RspLsV##LQCL&$3J zi3@gD0(vlILmRu3f%3XV=9gmi%8W#*2(RAoMwl@?fJU)uX4boXsXRr|-#fA< z$%U*~z>hbpU%nEed+;Dt=r7g{k4Z2$(Du+m*viQb5 z7A7Cck@U*mxS@4@^~ZS^E+Y(PK7r0fRNu?3f*GN9ljT4 zpzMSvh!uoBLP`CNN>$CO!iN zon=)=jVW^lX1#XoPTrpW=WMr)46#har7H;epI@&wJC(P zMv@D3v@4CK+4|BBcsvqdaruYe3b22F((MK}ht?)zXOt!B0u4bCIJOJ~XYwNB2KjPx z<(o(#B#RLK&I!@VUI!LOUs!0D+-}#rdz08-tLD&LJTL+7GR80DLG4sa8`9716>hEw zOEMhp%CJyFGR00@wW#-W$qOyxO^E*PDw?lF%}v;Be^hQBFK*PQvj_ulf}1xwAvSC( zg$lw%5GwQ#*dAw|7$4Hc5g4|J_L%`DhAe)McMK1aJ?{I8eyh<7NHqN5=S~0-kD1Imk`+Yj z2^TQeqnQq}t}+jKjQ%k$SvzM7Q;Yu( zF4vRY3NNTBs17KvD=4iisI4m~t|;jC;Njt70OCj&@^`=@wh#lwWj4{j?_P}&v9I9mMDv}}L0QMhS38cA7~iAf0)<2V7O zn^e7o^pteXA~43(c!BKScl1Y5(17^KZyezsXK!B;8vGifpdew#o0EqHAB#!Sah{)( z-abLLqM!zKw0U`@e4EMEQP5G)()^Q?y}iAo{iD78y^x3X03Ou*88~4azpY6@Wqr;fPejB{5N#}Z|C!`yZJvJC|PO8ZeAXp2MsbR`qSR&ba2Y%3vjdS zjnfEFCv~yjHUIY-5{3H!r<9c>gVf?_rC&&RYKy4jQb3wIgZzgxX_=$+7)00UL1 zFQ21#g(U|t?tlY$Mrjsl?j(EL$y@ zEHbSiXkoIYwS#quxQ+=Q|2 zbbF|{{W>MK+&qlMWSQ{~+`IMZr8oNUFK>C&nwsv|E)r%Z@IyDCGkcm~W)5^ls6w{{ zV&CW5xC5oqkdEBYTfWE$ae9>9fR^e=)z4G=X->Y8F|nA{DLjRg4mpFF$vE;P(0)y4YCCVuUSoi`mfJN zrwcI|@~nocnTWrZZZN86&e(P3i&BdoB;Tsxl81e*i1_L|LoSMX?Sa_DrYkOkx-<5{ z$Zv*0B_z620@4lo#N!C)Dk1s)4{iTUmFG$Pm@>%^b^jf0l}sF6EsRVQP0W70w4=d4 zCjEbD`+ou_n{AjRQhWGbK!$!8X~AY{2ZfcS)q3!)W{x=b%P-y}hZcCajDH1AKHi<} z_+g53R_aCR)tNo~P$5Bzlz7B1bz)@e_QZiU-UsuU{C6g_DTIu1Ol&oz+$f; z=Ld7?y0^VVV&qWDxYma?VNp24eWy}xXq{omkOz;2rbp$Wpue{o)PwWs^qQghIh;fo zG)Yu9#ifQg5L1=fG&-+_5w!X1(xljWz&T9w@sM3L4stVwGwPom#H)q&xb63v7(2sy zA1&$A1H&y4ok5A;)?#JE*ObnnZaX^6FMntr49kcDsZX$T6<7CjqtHgU-8i$tol2Sk z|BxmCie)m{4~N0JwvE?{kQXHJd(6P(jYt+wwZy22e-dXsNV5?vE?2EKlvw_S)Q@JHUa(hs|WViFT#K0PZUjT?3_)6P5wdWKO<+c>ZcmA3c4?-swqZD zuL#9mAOe!Vip0C}BA_q`fDF9Ohvn*@YuM@ODyBx?C!4j>l4KwAVv}Oi<#H!P_Bo07 zq3N@o)9=&A?KKmO5DAV_yf&|!>}Q|r2i_a6oe90~k2kJ}dO$u&=1YWnwkRLOh&sJ~ z0B$lt6b52}!5sSi4>knQgB~!FBz-@03ENaiAt)pDeu7iPd3s3&FeO3I&{us2EG}p< zVb#HS`WVTwJu>V82V38OOuiX2y4yVw1iEl{jef+g{!q2oV+r1_;n0;=`v^F@+dUcH zE|Ps4fP@Tj^~siZY$^UCFLj;*){BaG>k^nL@fL9M2`%SLQN`c0BzeZ!rsmV208UsX zT+FcG;LVv3qa zHF66%s}9t&Ot7bz!{kRLELwhxENHvdHJ#N(UxuNY8Iv7{BOy#(w>Gp4AhyQ>Mqpur zS@4Zz$)pTN1^ITV$uQy0=^Mp?7gzWy^VqhohlbI4NP-Bqgt-ALBPjYiTnx55VFLC^ zuI^P;Z18@zz`!)NE%bY!WC{%^HO7CF<7X*eDa-0c0 z058t;8pU-Yr-x*&sm|;{5GHOo%#@m>o4Ot5y-J=lHL7OW%)4(*{SE0#z@s!`*)AT> zSp36Qd9figWuK-p%ATE3OD)of5=h;)Q%EQ~!5&ymyk6v2TGLom(W*ISogwZ?U-20{ zm%`&7H%C%+uJ9CCl57e=;y0-&GVH}prLP-lSUOpiBOj91VA+f)SDu1NX4?|wbecD> zO>p4j&5utbsm+qYu{nzm8si#7Si`)kFoe|{24|8rB1XuYatFbiT#qQjB?I%mi$s^t7u2VBbn|G05x%;?_%QmEgH(XX`3ASQ%_iFhMD5@nx5&XqQrvmj4}Be zggWlBSlNwn6!05>7!H4uwHQl|zqHW@AT3566j1x79qB7|*K@{1SmUIfGW}`EyGoLJ zzrF1JYT*DMBf5gmFmxxDy5g38Ppk74hEXiPerbD3#wtoo*^P_Z3_MOBGvN2G<6m>( z$h3Bj*2dB*P}Fw0CR^(8SEiczjWfpHvsIGVH!|3#Itmj*`GXyYZ7)*NWY2MZ&MfYS zcs*O>=&U$3eiL|I^5*FD-DsEPN0PY%I-L(uoOD(vPW}1hHJhw@N_AL_3IE%3=Vt_q zDtz|X1CyNCiF6|*Vq1ADs?YGL*9@5FcM{>wQ=netj-043;^ zza_Tqby~e9b>+(UGy>!v0FSJ=k8OG&!7Vac1hK47vpcORF65b32YcZ(ezekCRl-2d zrsL0%j_Ag81USwS$Q|_?#yz8|?E#cS3^UMot zO6YMz*7?jMQ#8Ej2`C4mNO;C@yPZ!?B7A$O{}ivR^Y{5F&LRTe^xcO@SiTiF%Dd2? zLxKwAFv`^c*;Lp+;;%@{ZAtzS4%FceKkwCY2Ne7EUf>p>c=Ret+Q{j0)!sgRk>ALM zH>6Sm;MN0IL_7h|Pkdm1!NN~KJy0jB!kSil4UNXGm<7U#mEDCYDZ-Zyl8{OZTowW! z!gG~Dza}GR7C;Tpo`!O3m#HvP@JD!v^KM9xC^Cb162kR7}Gl@?TVZrk8DGtKYU>Kmo`k)O_-^>UC z1u(7zu!BiZH85JDvZ4quVnH0BM@+bBO_hd`hI*^D7;}>Dl4gB0MO)imqSUkE>>0y` z*hxanNU~DwL-uN7rnA8`4a1M8ua|2|rtVZhQH|2JvKSg$OxL$E;tznK=wDg}Gcqh9 zxRmnRf1YJ(4i?y+Tk5DTbaD%oH-avf=rA;6boJ|BRun@=9a2j7_uOh~SI}dx+~Jn3 zjQ@oAYN7CmJm+M8&|JG zvL|LbyUauyD2UK>ndZSq+ zegLvUAX{MGdPCAav&HjFe*EaMsWFQS1`O11o-`7A$!$D7ffVpgP=Dfqz>!CW-Bw9P zp@jlE!N$UrRWzBGYXT;xL5C&e^iZ5r*wD)|E6`Jj>HQo@S=ba0;|T%|owCG;&dh_- z?2Pq@oIVeM&2U(lgP4(nYG}h*;q>SL$}_!Ju@2J;nLA7cF-PqdP`3y^3gL7VV>l*? z+`UpB6FNE35q`PRAki6QQ-ks^Lr|K*E$@_h!E7{~4x29t4@DcJcb*HD=l4dx*f?>^dn zs@6!f7>L|ySd^^jrK03aY?Byv5;=uxss=N z+SR#HNNNkOHqo6O3*n$Kb&xW(Hli>OpfUBy8Qb4P_+ZQf12?77wx`^KCA3~83A-pg zLl<(#T}gX{G@_+nuTeMGXhJ-cD4K7LYv^(a%>6XOj14PVrE2a9Ii^NsZ+UVBOH);) z_wH2@l7d^$hF|4WW!SDuzY&`sU10JMUBc#D-6^Uge%kJza$F#)Q@xfMtJS1u?QW~o z=3_fR#~39Rg-?xXs#WJF&Ht{%{PsC2t0`mP`sBk9~9ch0|c2)CZoArc~(;J5sS66Zugd5F{%W zcS)4>2C8zbJqv#-=DalED<%|!_?*FR2^*mu= zd~fBWO=Ho{Zp4^|=EP~vN`l)EznhyueU=e)Y~Pf6_1B+wI3z7`sKFx=pVt%=j1CBp zK<~m~eiOs`6=Hw8_bcht>0PO#?B#=|!oj`!zeq7p1m8}gv=prDpiOA-ob&WQ?Js@B z@p*n485a`x4aiUVLunGF^^ey?z^J{BT(TWK9hZrdTA-j$V zcE{aeKNU8rTp}=KCf0Ni8W73y{K~o z%<2T|KK(|J6LF8M*@*@dZ5^t2|N1S*M!*Dh$jz$iM}Ny6UBb5sj;v|NDZ+I@)nGX; zpfXvkf`~8$5|MHXPK+=H#uS!B_A0@7NRim7Z9EZ4ozfy2l6ZBJmmSTV*+g}5wJlBg zd4C0yTHPqcex-Y_7T>g%8HG6YRXJ9(JR2phOD>Af+NN1^rgeA)RcFW$&*OdS;#48D zC~23{UwM?JULPxCCkf&O=-3-}arr2natSN^G$ z|4pR(KeE?Py2(ZGP$S4<4PJXt z?eOX2Y2oDh^jLB$Qv`v@RoA`{AZg*deOjo`;tp_k+;<{sA;jfRHS5(}o_fR|P5nbb zbnF8b9n@C{JZeMrp7l{Id)6iyl6>JJ_)6I{MqXPgQ`*4UUpu9c zi^S&4&KVc<`t#lVICK1;gTw0{NF@Sz{PCl#2!YFp@%MZUfs!$ohIC>TWz|TS?;6R0 zc>lWce=1-T{e=vhA6dfoM^PjAH&_0jwXe`W;{AVKw~x|>ERq7UPU$nOlD}f5A~O79 z3nbBQ<}ff6=@1|U3(FvRx~$x~MG2F!X9V|NVtCIk-%DONXhC@QJBlwj!ZWrc7vMd; z(_dY)+Ge`Ola*XMKKMasTypeYXXsYs&EafzWaB`wUj?HSVfvh5g*(8<4r~!#3X}9@ zM@P|;^>tm%9qPWry%Esi0YNW1V913?A%3d%VPGU@DA;JZ7htq z=`9qvOhFAp+QBgaN<`6p2^J5{vX$doC!R}$#2Sv!TNS4@XRkW+#F(a;d!FUxH>aJN z$@fqr2rxF`H)%gljC*!|#u>Cti==n*gdvfoO(|RvIX70Y;jDgcJ*5DK-iD~R_ET+-2yObnl$5`E#mZ+V^$yqELRfrp;yfwXMLhR@uXGFZG zDKP{94@~(c6qwv~*wS=7$wqD%daUej^gCaYAFE*A0}34n5Xgi0ls{P}VhP6lCgn9{ zr=%6oKLgX)>%I2a`Ex&jtN4~_u7 znj^Uf42$PGeFz=J`}->4Y3^wp3L&+}_-Eme#rz1!S@!U`FTsDZ6A1Vry%yXgVebzd z`b*5{F>e7MpHwo{BW|(ZFLwbHYef<|iUq2Ey@j?``()es5zjW!__*b;s=#iL;SP-x zijX;s2|odHjE(nIrC9MUisZ$Ev>HSk=h&XvqY<93TlQ&iXK%o}oZjef@ZH;}-VG;^ z;quJi$g{>`%u^o#`?<35JMW`=v>uAEfh}sovY-D$t@$Sr-o~Lx&;$SVs~_>-b5+{T z$iVu4iZ#({P+kkiD84u!Dgq)gY>;)}H zl8(P^sdR3rHdc!}X9YD{uXAktQ?xUxXSddyb=-FBR&%b{F4ta(MN(|y&Z`+Zb}&FnGwa!laiq17Yh zqTL3G!!3O5N%%e^qj_rfGJSZb=;c%nPMlotqTNp50_cJ7dLUG@kLdX^{H6Ao9YK#-0FM4n6c^wcR>@FFhZv+Ma-vKKYpzkz(adS`>u4>6rkRd&D zY)(??k@>dr!W>WogUL9Og$dd~M!2&s1IttvCfm{A05ne_1Pzi(V@X0x$4!A(WLulI zA`9YrQ$a3&QC zXKT12SrlT)A!Otjp@VV27%c@?l8VLyF;tpQ<5H$5A*h;;cw?wI-R42}N{m^QvXxOP z&T5wK$`~HniB0U*!fI|QG2P==Fy9^<_(v!|0DT2SuVjm|RSV4F1K4Yho`M?mjsPql zm3MxLCDy@lKzQ9UghW%VK$~sR8NhpiOiH!|wEeC`)CKZ~Hc;=qK&&y4?dL`%_C|gd zS0BWJzM^st3nKYY>_>-{ctII1|Fo;WC+P}r3%YQR1Joc-ROhTNI(*E_88;g>PR%yZ zq2{6~T{0#=D^G)`6T4o4fw0>nz)Y#x2jD1$h0he22lS=cV|$^A4z&S#lyg`lO@XO`4HFCxtJ(7_P5lN(L)Z@q&Ra$D0Hn7)NrD*{a$ z&GasKez#92OHk#PqlO}Or_y}riPB<&PVU$$Cfg)rA^rf6fVkPmfw&PcHK!WXHdg zh^^5m%#tu=OhFT{qVvqt{J55M*Sb(q&r=Pa=B=TOcrQUlf27SEiJjPR<|zD=7VobX zuzDqC4tl2-yE?X)7aJ=IQnt+MWoxtfaSMjX=8#lHy>d{uZ<5%(V+XSRn(KOI0GFvS z;~=DZl&Q2+y~_I)=m|Z;&e0lwC6kspSs>6vQixEZ2_8rA(x&n+PR?ShQfs<4oM%OX zF^Vso!_=MkGMA`8Vy^C3ztdS+%!CI}2RP4cX9BlZ#CPv<?XGAL{*Y(tJ9ce3LQRKIgEs| zyhb`kIMlPAkcd%4%7ge71%}uPtFoBe4Ut89YW}v6UKFVFUpiXyGAjmvtD%~J)+D|3 zf5J6xsO7N-!S%PI6BwYMHAxkViTc%Qje=x*%-Q{n0h*oQ#cB#@8Ntp#&&A$%L>~~( z4~(}n6l8C5g$6!98*5N(%JMJ3f#>0gKT!Lx@DJ&E_cRIfHs;~>&4|7t2qWlf}1 zkwJb}YVs4U^ikumpgsx5Pa;Gu;G~AnjqR|lF4OI^hNQ=jV??Thg|FHut;A*a4hTyq zwJ@f5AUZ59ycf33D7ryEbJZz;wPYa5>)fui94V-!p=XgZc_TWAy~v8GH#M#d%17Kb zfeAPx;PwW7fm=-==-!I3$AoUqH~egB;#u{^*t+UVnOL3m1-Ll9MpLTg%h;7Iru2t))- zAk^ZSk}#;Q@pm&Dka!X6^4`l+#FpXmI#>a)6+>^Tmmvsi75YvbW&cy~+@hY4tYaY!tQ0Io| z)j>}BUcuEdPKLn_`u?9f>}i*M1337JaDde)BiJG3X^#W7&!YtdZB13%5Xjb+Hh-+b zR2Q`|t(ghwde3l-<`H50mvqAVqwto-0A z1l>)Ut-a!=L78s%x?dSa5h3t1GU+2T=>tsQuU>2bshR*13D*I|J2l{JoKx3jOI!Kx zlsYEfSe@GZYsoS80}uB>#mevhkxBoPo!|ubECu`&E(Jf?G||7wr2qRPpOKxT@qgvg zivQ7u!9yjE0-^w4OWvIfb_Mn#oHr~3jn0qs)JN?S$WknID)_>R_wkEwoLwg@05j8? z)Xa1`og=;5udAEDUnz+ui5i>Xk~L!~bGmrr^j5R^fR{DHws5(l^O~N1I;`fu!hHi7s3Q;;V5Wj&ayUePnPNt$C#ZvJjJZ zf3<6j`Rl<%psPd!s1axmMf~Ud$Nf#2i-@R=4`0qT2;o(y^&-5#=IgS=W)sav^svqR z!tu;X9!DurVm;Bhs~>thrsXY|FgzZ6V8W{z;c{$zk?qjMxrk6Q#s^+orq98X^oKIz zYOr>`9V?%L^<#AtW*xnmioms;+=Fk=v1JD&8LJF%^3nvB2VoASHwRH&j?0-$ zk;xmQ3(7C`R|a`5Gjq>-%W!-F|93IuUwe~J`cnvzg8ll1`EMXpQIQb-PvnA?x0J9{ zkiT^j;$+nEtAgO9^sDivz?g&Niv-JyXi$YUNrVBkwt89DrW+zNWypLC-twOCPNiH# z#Y#2t+-EUJqOuWu<}khiTt3jv&e^{pV&L}MGnx6vqTEQ?p0m8BZ?bmUPcEOoeP2RNxacqUqw67(9pey3R*H09t*~2>#_{Zu~(p{a`f#( z%?L5xxQuG%buOw*%bbRqt1OF?t7I`PmbDcgqYN#yYbdu|b*bo`Cv{b7D2m-v>}?jB z9`1sJ&l-)OtwU%Brfsy;R>H>-K7pc z7mGmoJ)k0qQmd^%L&&MFL&)f^F-WCue7YY2{3)7UIoF4zM5Z*hSDqAh5EiN4-w>wz z$S@lC-6-4@A@wN#q!~zXYk!8(p*GpfURrX~+QRacCDY=eOT**-f&XOrX9aHAf@Ry{ zF)kg50Poi;Y}@aOMnmjOcqy-=+!kQctvfk3_xw{ba&a*rOdlKA3J!;P9LktlE z2f>whUj%yBK1`Y+@b58Tw=|Mpj2W(mTJU6^wnp5CU%$HL`P%|Xal50Avrl=NX7g1b zgIZ==K*FO)&JfmHX1k+z(N5bU_bLjtXX>4Dji$_E7vP20{qi<_gMR0R9n1_~p<(yc z4j!{vp6$dB`*ely#SP@TL-}!J6{4`ROtXbM1-0EPAu|Zx1W6pQ@T-`5(^t5lJDvlA z&&|x$N7u+%r89HB_24+y8!CyIp$iwBf3xo0xk(Ln2lM@f>DcifX+GmzLIU>=g9p2k z815Erb#l+$`Lou0eZB2ww+#3+?}jVQkMxkA9uD4Mifu#_Hp?+hOa_o1&@|604E%CH zYAK8)Zn*lhiJEAsNY_mqkciutUmCPSa=s8NW;P2NSaLo-8Y^Zo0UDg7yp*z;bfd1* z!RSFBLj9&2F=|orw#kU)?f(P_zhp#Pc<5ihfPY-ezm-}HoDD>*O>F-ABTlh8guC(* z%GZpS#IXswAbNiaFuFYcgt*-> z!g(7BIcn3Arp?l_s)&_Ze#?4C)4FDJ$w}9<=`jh0V9$*ACfiNV$)?k{({=mF_Q=Ez zw+}MqbV0mp)nL8y%WW0R%v$?R8Vp~<-iT|_Zd%C6(K86wgkQm)2moI*5eD5@SgMjj zRPNZp$r$}thwuRkOl<~^jt-`-6zlfkC)$|K@Q%tH0v7Yf{ACxU=?UnvH_zH>z+Afk z-WL^2&+=^ujNSU)uoh;_#%)W8oApa{h?~vn;;j};&%&)2)>qzMtgG~Z)c#_wwY%H^ z1Q#TXw<4}z%E-In86D=AyZ$QU*o~ei+B*8)r;^zF=hZJ?ZRwDzRUn7j1^1O zihVHYW$kjE!T>4Eibb2o01PIp)r<1}EgZ}@vQnybTO)WTzMTO6p9lCik4I`%RG#C2Z^cYXFq)->nVR#eG;6cg!y? zQhlPae(_|7NY<{T!D=s>5JZm}>rj}h*6irewdCY?K|IC2c9CrONTf&9b2e7w8@S-fO(S6&$OZhCo3Sdf_s8r-hVJ4P-ei9Y_M zc3ibijcnRiS|iit9PJ4l1a?yP&ClP*ebY}yNb_dG>d>mdKvNw8t}D}RVL*FNz>l=J zc@8UtMtzKqjz~1=M3XI+0ZV&va?~)#Lk(pZTZpH1yv3+77Ot&mO2l}rpaF_{gT$EY zDM%qt^Hi2v-J4j5HZ2^B@U6iQm4e%%a;qDId7P`LmX9f~ z#60sf@f=zqTy??7V73ES)KME+gR-DPK@1L{N4`C+YX`X~mbQs=#aGeWDvWrgQid7a zF4WaJu!WLI{x~rCe~=J6RYGk`lBRIef}eNLAR2wyRa`fNrJ3k7WeYu z6TgMM@GgUEsP0gBb#=bOUJ}%duHEGi z`N~;Y)t4@1u-2T$T;{+gfQkyT*TrJPp2vb=v-4ZPV*USF;I>mlgk&_P z$4`w8dFV8DsgUsdvn84iJKj$KW^#al!5qNCp>zr?)fc{4EWV<=l;WsO zr2K#>V6t{={v;#M+K9Mxn-=@o-xt|+b?2Fjj~l#oUzfGUB87pSWiQB!s^+eF0wOe* z7`65U<-Rdc4{c8dIZ+O7$h@PgHqHV%;6U-=ooQ)Mgx||<-dBmPXWB1 ziBVg>>pE;jH?h?vJwiR%199}LnZu!Bf^4>nWjg5Pr4VD)umEfx>Q-nrnrzN?BX{%@J= zA+2wW5ao_XC}DWWoeE{WW|bVatJSwsPY&dx7jWPg7x zw*`4AbR8V@!^yBvx)OHx3tR6+B?oiBA%m(HLAfF6NJG#D=_Q1!j>gjSGTRDTB^T&Q zP_K%dH5r$xa?TtTDbI@IVHK}KnH&7bvgrhq%N(I(L_5uyN_P&)Q%U7H z(56|@s#2@^XxqWhCWsMpCf!1wJz8#;*%n-FDei-Zt9834 z+p3dqs2<$VTRGmUhFdZzdah68>yXq=OGv{guG89(eE%3FtTA|i&2P;ZGJbPq)LaP^ z(`F}#XLN%hIiD%V=TIJ=s0&_S<6IDmcXyA}^Y-DDlD!_>`6$nVm6gENC-I6R`2_s( z39&kL+7#3?r1J?5Tntu2?!Sl#Xhmkh)x(axsymo_xz9wV48Os>WN~}KsiNU(VAhMh zYT`V3l+E&@zJVw@Yo-)CF-t0wZWK0YQ1(EjJelq_u%ZAdW+*6r!R?WtSPgxb_I#%2aVWh+esp{qQvX3oO zp(?QtESh|}Iq54sg_TX9aoh|urh|+ABJSEuAwaxm`s@YvnCeC|Y-uQrCrXI49)z?$ zUXYr{jBXzKVhD$vp+G&O_f1S(g;zA>zI^CyH0=p*7h&PesN~62>b{D3D`mU|UeqLU z2l_#cQVS$%T-BiFj?pPPHJzXgJ^>-HJgH)UJaX{f&Qv-K@{#Jz^w*LZW~od1UVwd`04T2sR=*89+cv&86F~GC0p3J(CHx&o z`1CPredtHm!fLK7=Ii9bC>?ur*9-GK#q@oclk6Y|+kRCT`-w%KO!18odDT@3pL;oN}{1RjQWe%Xl;QGjh|gQhfwB?XL%nNo?SEYV{7 zq2kFL#<@3UDQ%HL6f5iuP2B0kO$>}p9F~90SW722oJ_kE1r*+ITdL7lmbeowi$YN5duMS{^qR8aPCa zJNaN$e1C897|1cijbei{oqYSdF8xd|iGIs^Rb8P{}W}*EzQp7i1Fe zwueE~yOVh2W`hFH3LQ?jfLVCyn-XJfUz7c z_Ypu`MNW=v$`Wt}zSPEg#3zP9bq4e|jIRmm9*WR3-y~%p|+eCcMbJLKv>6S8C##u#E2A^;a%{-lk>tZ>}V1>k%r{(tT0pD358YY z*V#E0LRE1F8jFLkFDTz%VZWH38Iwpa2H7VsPIpO6j69iSd zJplchBqqf}A8RTZkGu3@iJCz)Z+PdzFa;duh^@@s0^GF@neGBcOFcz*jCT>km4j?7 z-6CBjcbpDl2Qd3G(RN677T%$!HN($&3Z;7kK)*Cw_XtdI6+~6INsl17|CDeCo~T?w z(LX}_m>#{{!~Jhooa#>#w){v}fIrN@{cj2DKUg8);%xp?TUr4BW_k$ z|5<*GXw)@2t>0HR>?!b@355>;|NF!gw(U8RKc}tw(Ov(~iG{2!eh#c;;^g$N2}Ff| zxjG|Rn0O9EkaULFtDzN=U9AXZF57q{1Y@hG;ISYvk1R=pqQoxOc@Hu|1j z!O!8uuy#HfnurF!x^Dtt@AyHq3X1+v$F$jJ8v^^6adQNq5>6xAh?-tW+bBj}(_q{x z!zinYzH|b*mTB8A|Nj59?!?qG5#;}PqPrjI^k1zz|G~R|gl`i^MH2@X6DMbJ16yP3 z|39ggt*m8-C4&4ly!Av=Vlz){V_v?1wMsgLXf9|_i8y@nF3R1o->w<{?&S6O8v8Yf>b>^#5!X(;yYKh=iJm=hYJL0= zz3u6@upa0LL*|f7S7jhCiKGE-u$G3gJyG=YB5!R(rqW61@3|0DHE zIW=RQO30ziM12=W2vM+Mw1Ad9R>0nB#!;9{j}F>BkZ!94W5aRAW{rbIxfk(bSIUwJ zd+XmYyE~hK>PVYH%EOenn@BnDxhK`Og}UG@5@99C>u{7lEJ4-a5&H`HsP`x4@iwZi zU?An@{)&RsI?N)QzgFQ~#R(4C;*hs8rAt7>cIoewZ{m5iy?_$#X8K)itkt zMoWMt&RrvaPzNUc?zcCUwG&-zeJ|b00yCWd$(yjRT{I=I}IV-xDeAks?&oKe*FtJ_hR%U>N8>dWf+Cg#5Zk0%Kmp2_%)zQl^ zTvJ41WH84rQJKURWk?wSmo2jA3Ps5>V6R0EnaVCvsJEFr{M%*yW&_#XWD^ksDVOvd zU6Iq2WxD3~A}=0NAJI5uQ^|mldq0Lvsjf1SjlFEI7OZ17%4cSX5pxr|R>lX3$z#)D zGvLT=faS7*mUH1*UFLXH9E)ll8Kx@IS_#<7#X1mP$0CV^^+9~&93<jp9m{Ghuxf zM=l+!>6q~aB)3w+!&yrP$W|EeJXqkHsnjMl?ejI0sqICH)L6JMWp)ly`2aPSV50UQ8|ICB1919_oN;Mp$LBo-F$g@%GFUWsLt$ ze_Scj4PCoyefUoCh`+qyv0wK9QgWZ3O~)YIdN{4d{tkThE*IC{6M8v1OY8Xh|2n%8 zcqqH?KlZ)sTUsok6j{nv$r`d{uaLo5!Vp6xDNCDFmZT6RDkXX4l}ZUMyppX&tE5CJ zr4ma1=P_o+GoBg!{?Gdv6QB2f&%I~6=bn4-dE6_@4xHYuGZ?sF=dJL zW#e%hw}bOxTVP*n(i}r|xx3d|hd}tTBk+3Un~E}a-m=}PTG17!JomHBvzHZev{}2) zaXrsFpX(QVRPJqf8d%rF%Hzl`ER!;{cHcVf{0wuq?ygVwv$QW)jYa=r5t-R}{hZg! zYBP>3RsI*G&3qf2978u`?TJ4VAH2sh*BrJEBdQV8{_v%8-J@(5qy59 zLc4|MuvmQW#|sySZyY$wmcF0#uw^J}ky7mABkXJKL+2MrbM3WMAe9y9q%61?(DtcU z)W7wt6U&H&al=CSOWzeG3vZf4?kUqc7J@gQUfI+e~Usb3kp`>a;C)Q7D$u3XRCYY9;S*$%=n9Ln;GW7AW_@pjQ-ftoyr>pxzx z{G}Nr{bTdWd#YbYQ`__}9p9|swxPX$QBS{GUzLaR%OO6rYHZ_>_Z@<8;{d1!ZRc!U zHEcr(O)voq-mNOwy-;~xXtPp@3~BBy`4)4pRukd==bsW5RlhvrZjswa zzW=`_E@A7j`}ad`4*wkeHoTjA%dz>AN)?t%gnG`uaPpXE`96eo^q!eR@4?FvafP>h ztpB8I9iJ`Ml+Sy9Q|w35pVGDZkIXY1RcC3qv35kW^TrpSk56PZHbF4TL8e4chs`xzBG5yzKdJEk4dh zT1nzTRB6r$!n)_ngR`!d-=ER(lbu~JNNAUi_`a5RMG_i=JZYNQxydUzmEN*u+)D_q z+st)(Bbr}qD=r`G1%90Ye$7LNX%pcJ`cC&jTXh>Yb-`@wLz1kq=5}k>8nMKzI?v6) z!ShbxGfUmq#jkrx;+rI1K3Cp~J8aZ0WMmCvO@oy!cb3|)&)_)3&Y2L~ znwfzQYKX2sy5wrK>$&tz1zF)Le1j^3hkw5coqguNqhh~W9$k9V=-*$VRjs3PFzw2N z^^bWDa*tYMMa!S#IK*RneTOzjmttk9fZ2uDf3jRF?grk}6cc&CTl}%E$!$r~o>6O! zdD$T^OA6-kx7j)Wce5_~=DwQ=2i&hFwEb{a=>Jxgv7OyW$ys8RlDtp*fpZdT#jm?+ z{>ri{iqAJ4<3h8ERr$EZHSjjG;nW{pY-djh4-FxP6O2QA2opzBBhrV%pPPu@>rgzk zK-T*CcdLd@Tx@=G<}ZIE!=q2i_vJgiOP9_tZa;LUqDx*x#p;jD=Um;hnxFW8uKWCP z%g}1cSH&XVk9J8|$yntGOHyrszisuLt&zex&-t2ct0fiEzSJmaNm(5b z-neFyJ?DN`!YvujUwwuA>iP>Rm21WO-QlzK;O`Tu?lRj(k5%(zM%UJQ z^?tI^DIL14b49Ku)j>6UqeZTCDsP3H+{XTq`^vGr^<7(wAFuQa{XIAMp>?@svFay@ zyB;SBh-IxewKC_=K77FZ>~OmJ()J&TAKTXtXI5JkJMO+T^Xdan)r}EXH>NL@?+=lb zIlVUY`*Fub_h#33Nbj!A(=AOgmlb}(dtoG@pP#Ge*^w%38Izb5ysSc&OBWtowc)qt z!}@C789N%Rw@UJ^P&1HTa86Ip<8|1h>a|G*qk*dDhf>{3zBm64+NUF-4zHw-+sOY! z|GNLxol8dqzmr+{4iwFOYq-VIt|^@Q)~$>urVmo1* zIi@R3hL#Kn)vQiAEVS~_^3_A^trj)f@*PG)&TpS{OC-PN={OY4)v2E%!QHVtTD#Nq z?fjav$^Ej?Y6Af^e#r+C`i*bqeqpPdDICK+jITL7&%km>{p~%TTvHFl%DCU`o#A!1 z!ZEy0<=l+Qc`{OTJ9)#>Lj|77{?-~;h?jUO-zU#k!!od~Mt0@F!u|KQC#a|lt?}EM zs~f@5zEm>s{-KSr`)B?eoaFK&o-0yZv0cM$RnDAswbEK&9=y&gkM5pS{Q^0Y9vio> z`#*4sF5nzhsLnAsz&k92;1ht{j#mo^QL`Y1Mv!QA9w@VmKJR#e8TFP&L+l)Uvt}9c zHL@()v1^{|*0`mrrG{IKlioaCw0zfI;VllgmBnk9j2Uz+&$;xAZN^=H^@oxl_yvp{ zRvTS(Bw3VOEE?M1Jp0gN*{ZOOn+*J{cwW5`->00i{)AL!LOJ36^3ILXYWK#DMc#GZ z_-56jcWVXp3borT_uo2n!u8OSlHTrIAHl$XG9K3-8rBk7-M0sVY;}eY9AU z>s&&Iu7R4`QYnQC8R@P^>*`M8@)mv%*GxMw;NYNPs4;SUc!WCwsrNCTR_|jiQrbh% z?gW(f&|7B4X~wC@Dd_3La&1p6N1Y$Xz$&d-f|uEzTJg(FDvy8+uDm_7kOZoJ0W-^F1GON z^XM;Zzm>a=JF7f4*RUGY+unrN>7RQk#4a?^TVT8N;8K|-M>5NwS9p7h8^4pY4(n9P z`*@G7c-Ndgr60?R`wlrK;k%!ehe#K<{X73yUfBD*z?UAD1<3>J8`TOl9K%&BwYI*^ z8&$~DIz`;`?%{R*Yoo$nWE+;sY|@bn*9mYIxbQiNmnc27`Sg>9tvQ-Sk`X_vcMdkT z+ZwfrtUHqModG&=KJoM^VW2Ek6<0Bqs5Ocq*8eExnRx`Wq z)1AK6hDQfH6jXeVWTp}K?9ROu&|x4rYM`R=`R9SBwYfzi_m<~x_w78{B%=OjHGhM# z$h#AR$BqX0AImE^nIP>L)rNcPcrqnNwMVKo%CIRlN2Q0icQ~#%&#G&~ExDBWas;mi zSK0E!e+`0W&)R5J;GQbIOsVei+@`^hnHNvs`(N79R1?WV>WxP9Rf5z6L4veeHT2dB zstNUnrid^2u=NZUL&4n}8&8hjGm?q@=j2S!1&d6))K#0!{K}Gu$F({)iO+a#m#3I= zKhE?~hRe=vKcWnBxYZ3^PR?%@?-4XPKROumI3Y&MW9}oTdaI|7cUNjJJ0Y}wc}dCs z=a&_JsK-$)+KgI>iU|To`U+JyPltmo;=npvZ>r0xjtJViTB0ZdWEZP+Z{;x zn+N=|n^jf>MXoLu-ZPf*G|%~L*cG#R>@u>uN{r5(S;yUuThB<7xlZ&EriWJ!ooJW6gQIh^w`}?j$G5QE_w0I)SlQ@C3*umqXnGNf^TviGQu9w-J$|tc=v%{(?q&u?8EyZ-^ z(%95h>rNV-TX?Z?rPMV-h4!K5;4QwhBJBOHUe+7*4G{TwqRhk0BIqIU?Fmi269U`? zUv+msm0>^MC%-f4-{b8UWwokeuiEzgmsye9Eiy88V%yq;DBik@VS!Sr%PQxW#rQ@0 z8+BQH4VAuG)hNO(#HxA0=?Ipuk;xymBWXgc}ss+J;Vm-$#8Q{;Ls zvPVDnmc$p1%10{t9!Qa!t{g#Q=}ir$P>3;dr{9*#SsgoL{uuG|DW7ZpqO)IVq4-zF zJDQ6u{#kS+Ld6&3~2pPI{equMcU^Z|ANZKi!Jc9DCUZ z_MJAzH9O^q5WNx~usn4hNZutj_vE3$e+3)L1;@ls1v$L1*_ZcbnQxC(i-^*iXI+gW zl}>sDM>+jRMq|1vop+??_zm2zeP4G)-(&x$+q$`~`HJTDg~&XShowesh!X5}rn_)XL|MtS;6>3Kd> z?hbU}KkeB&)-x%1Mf}3cGqRk>c7!SzgEm9IK$`);BbbFm5Pj$iKG|8XF)|cgp`9zO zX5Cg6=Jc>;(e{KjwFl=*dhs=ke$#Eg9j^Fl_0W~|Jc~zIM$h#;a9A(OE^vQTC;YQ+ z#_&+|_SL-B4})CKWtL>zi4o^Y@KR>&9q|@Qu)nbP&(c^T&v3Cb{_T1HzL9^-y(9J| zUrn_%n{9MHMo-bzeT7&;&8mg!N$*93UR)Q+O=(@VebL8Kou7ftiE{|%{sK8KB(`+k zFOcw8PZ!eHx7Y70Oz^vQ>QI!Pb6eJKr5u4~MaK{I$GWa>>Q2gAb$;FRqU6lInq5CX zrg$DE$!yJ2Iyl@pcR<2dhildb#XdpRu^Y0dvV(3F{duXKDF0_`L-g!T=JK_=4KF#D z4X3KVJ?5Q%=eW+$01TPE*;VK)?9VPXlK9Ej#_V zyIxu}>~*r|xx7=_%k%OpLchYb)%RjU2Ogy?`u46#a|i3G3_Dy;dV=uwfDdO2t%_1h z565>{*38?!d5DJ=+c|4M4~LG4X?k`img$lOghp zwW*`wVhbBHFe^$kZrlcF_BK*xnoB_B|iv)FpMARE15D4!HX0g8p^aMG8CBc5m++B3DWS!Ge?p{Atf+C z^7Hm(+Ml^7lxs{-!pGNsOu=TMz_ZQv+-7z9#tiO>mw4T(l3-Bv>mC4Ki1u0F&?Y@cHhBi?!Yt4sh zJxXmo#Yxf6j!2Y1eh?la7w9k+#LOs*Q`(RB+XWi{<$Snt&M-w6-DJx*9Dv4xtT>u} zBVoY-z!;w-y-5D5K0!e=>g1OGw@F^10j#*}JT4qml%PKOv4g`nTu^`)CE8KlL=1pm z>D%wWnr&fQ56#+HpwF}?KlZ3M8N+8Zz zh(gti#6~4sDQzV)6&FzwA-;h1%3zyAZ~14`}HCa>I258qX;>sU=xD1s6#|(Xh;}|;A3G+w<4tbLJh?QB1#xpkK-f0>2qF>h6*N&+cQQC4)SpG$&({K|5P&a5fu|k82A?EU zg$dc35%8plFv{*QJ&8AB%jSrI48}k?bxIT zRDmL>4#bio5m*ch!b%%0Q2Cn-QORj{X0V|yAqS95hduBG?Q3@2V*rcxV}!8a03y7{ zgFZb)&wTZ{XXYvckrYQg7zK!VZ9~MFki3oS_k0AMkY#}o9(Sx!HQ91MA+=&Cd>-?vg zF*%G$3tQS3YeOzw2C>wD`$0CiDNlZE&R1-B7Xm)e84MvL%nXnG+=dNIs7n0t9{{sW z0nYq}4Lt5P6&wSC31N&Fg6QY+1Ko|)Am7Iz1GM2@gy4HTTpmw^cv0qVwQ*q3%>bgG zV@M!@7!buswzFQWc#gy~tkCIY6js1@e(bd&Z0yPN6wD(e=slCk3h957Q|K2KhzB2l z!$dYIDNlav%@J%GROc}6hHV{O6*Q;v9P!2BDf3+o5x)bhK|4)eR!&UTprL624ui-n zaa7yi9eDEr96s8yWwSFTK-GPUzMF@H1TqpaG7ek|$s!HLA%z5M6#l?>eyklgV=@>z zub?rNQHTs0$}=0vVH`mq2lRxi#WxKBa^c7E)BMaPT!c!Uvb;?W zlZ!oMHp6_75E;As8guoYxy{4j8f@r+m6Wl8(Q*bA!Uq2O@bp*|=;e7>AJdkP2;=XY zV*`)d7B<+`)%dN(po!iv%PvAmG2R6m%!@=`Ay3EHO^LM~?yyoB0Orm|Aq%=;BTov+ zusbV1_#$r6kis6LQEkHvKJ^d!cwNc3U! z_5{4QKN5mZ<2&E~v3!yZzGofiD0*&x5`j&SDkaQB3YsLpdh?ql;tX0dYrRnWE|;Ex`K(eRxgTiG!UI88wey}jY)Aj4$|;#pXJ zpL?4FxcA|MmOS%0-nh6<4-zxqsh7Vx?1aSIjhcCm;gb2kRY=Ibd?|<;K1QDR;|A^81IbA*` zzz86DcBQ-DL?7LB9@*Ja4f;MHN00wmbQ*l}_2p^s`35|KvxRZEZbkArL>l+U6sEx^ z_kZHP5o6Zp6-C%e1Kah0OXzjmC+%q{Q2Wk2RfYJ5Qe~CAMCkkp_@E8geZ}8W!Ip6S zXSU3GKs5jZM#oR;EB_W57Ka3w+^`9l@>XuE0Jk<9W_R@JVhzN#SZJ&4bu>zIaFqA z$#=q4E`I#5ZvZ)LbOLy$`!ocYtlQIEm;W;aU52oMj{TJZ)1cD13A>1ivLEz1)R64% zi{!u>p!4Wxf-86$66kBa3da5rwh)MZ4D3PhB`Fr!oKyp1XjQ_KrXfT(7KZjvtUC8{ z9r&a5BJ_dRt1Z)zK#v96qIYE}-4p<8u7TwWdb<1(I}QAVJ7qi-t2v66TZ5FNVd;WS zciN==9X4gUXKc(omjpYyA);W1pcEam^dFyw2DNq!V|1-~4Qw|MR{=6cN4@f;)1XuB zc+#~^dOiJMut4EEsLr)1?o_R88hAQ)%Fq;2M!M4Uz}k8dEv5KU_|A`wtYkvM+GMFo zfFFcJOasQR|0W7n1DFV~2<@v!Z!!T#xj7R;5KK3W()<-pR=Ovk>yn^Gt5Dq+yfqC4 zwDv2IheNqbJJlGFnRyYsd1M8+ZC!BN1}JKLx3Q^FLsYu-$%KPt7RL|%CXCzzB9g#7 zv~CsDVH2aQzZGB&?nek?z6ihAy?Ask2>v3B2R#K{ug8X`M39qSF2XF|fiSF3JY|sp zgnWkc=pC)vea1w_S5v?t*qv1%FMGz{xL#cC(MDk^%$&i(QEYd=hF}x zmkcsChmasb07l9i8A#IG>#LEo>@vVHv@qD9&I?vxgI@YflUUR$2E9tp z9>9jDDi&R0k>U}t+4ShltkrHXTie0HVF5~k1&6We(4{i4VgD2!JE;j)7(8XlzC4o~ zlRMPzlNZg*gJML$N58+=hFma0&WoTI%(^1jB!Cl$;~uXf47;{rVU)Wz^j`LEK>Df@ zu!6fVi>^U2r9u=N8fzLd=k-X!|cp?;17&O`s8sH0_aW#tG2D$$a zJ%qM7KHT3LAIg}he9hyI`#{VLbOJrSSSVr>W#A!Aw=xJ64W6%&^aHgx4ioSS)Uf=N zuqmJ=G?7{Sn{y9ItmPFEvv9aBGx~{mf%@N&atsOg5Aecc8>r=;6pvEqe=mH{?(3t~ z-+%*y2t-=xFnSA`sdgk9dD+7}P-e6u_gVi9Jfg@9wtVlV^B1W?{Kf{|M#m>l?XaQ8 zcabM<$4^YNj4WSiwyHoBXlx>g7tIz&e{66}@iH<(?ZC3{Gr^;?!Cs~XN_%E+#)hB# zmUVK{Ut#i}Tmne`ARcWGiI08|SKDg>q(LldI{Yog5sH@*mkga8VWSSr|9(r$H*sS zn0bTSH~H^K0Y$_KqjMY0E!b3PicRrkw7+26E$4HV%Rd2sE$~knHL?|LWE#lTsL8jD zCa#l&g^)tLLok*)h^TKxEwmg0R2M*9h(e8e#0YibW(iZ=H62E$k={B2?gA9FGMY&9VQ-3(SsR>R^aX zVK*~yI|2 zv>PZ>8zYN*kHzb9je%X_;9Sw7KCp*p;`WXg^*ATh|A12^F*`AYK!>NC*^~;<-vC;P zIwT~$Cbe%W^pump*!q+1vtm^vfXxSBbbr6>p9=avB?wM#*|WtD`YI1|3_6d(ePAjy zl@&DEPLt@k(O7sAiNfXs4K#k$!KwIEZ|fHjP9o3iOz;tYKW+;8On|AR3R22)D1N&h zo{B$tR>x-bZkITbbAT5v0OiF|c%$i4@u>1M^n(gN*ogFR_NIX5$G*>=ibyBCsgTH^ z>EB#UgIu386>?HWZ7Lix0noo(m{>+27S7P5j1(fe>!&1ml2~OZ);_Qj9pZ0a-R`* zMqh@DhMd;M2${amlx5CTQI0!Iy2@5G3V9D1QJCNdBL_uaBZvlh;mI_RkRpNZVpR;H z=L~(N8yXSIr;Lb@o!In>h*cYgfoXo|YNdty$UbTYAR^qc2b?|tvBd#i3&opsJy z`?FT>{at^Y?%L-l%0NKEfBWyF8mr0oKNtVozC3nFZrF;jPlbGX|&UU zY;inAKYJ?JGx+tYFgzHdA-U3fD9@ z>?Gwyb$D$h>7R7=D+?17I_jlvEFu((je}`E6ci#l!O>HZ8#T{-vnMn2?+@&j@CT z3r$0qD0a<4fTn7i0X`GRino9xX`=K!epKq+yl9i;Ko}4C#7z?9??P1!S2&|bng?r% zMqcHAh1D_rW06-fvOXvNmZakcreG&bqE6*mzl;hzEaESyV+`B-ycN5spv8x`Ncn7HQlN4|~oWa@YOULU~9fdN66%K_3>?ek@2 zL=Q0Y?&K-Asn$sEzRRxIw)4J|evTq@WUu>+WKc7Z z%g#B(?@f(@Yer|HG;KzI(a1gRoTCZZ_k7dm#MYq4Wi}xBgz^3A_ea)-!hMDVeeWLd z(|vsOId5e%Q-B1Z*Ps;VYtn4(KxboHNc35s1-*A*z;isAHgdK*J^%Wuw{bR^XIIAP zw>1Z}zInYBV)klZSLD}nDqigk8`eQ9=7WBnWxjs17Xg9TlCRj4LBEgfyM>7EknZ`= zsu+ovqznKBU^5(ZZ@~eeD5TqSOaC_f#4Fp8|NeDiSco5p{D`tYwolZt?(0U{2Z>mHNiJltyv{O6Bd zUOt}`=tMq#>wM5i?dvOut-lLt?@R>3_XW;NGnTHtuU<)C@ajK-fhlqb#=qCyu+WPxbLeQ`W1ER@h z1GebLOFvL~=gLV5WH&dqX>QbueNg9ObiUuiWCz6ycAR?;KQ#-kkGS_@2%Yza+DmXh z-!6Lwvc#E9`r(1Y_}qi^+C`c+I}7^+&b#>fi(Rna?bx3DzD>A)E8x?B;^lkDYn|}N zc%cu}ag|J}Itagf)s^O%84L(>>xHxbP<{-8jt42j;{C`Z^?;juyAq2=LVb7PCBD}$ zItIOAAtdK@`8O1S17ZBH*kRGWyY63;DFVFjW3`|~qK@Wyw z>!zf!NZ6tn*Q=UUdkHtN{n`}x&5Q?dPZwyjMaZ7{A6I1qIDTjsFhYJjcEOIMJMR9u zMJUDhnD>U=%>&H^H$h5OPm9`7NOS+JnfMlmHqaAv=G5 zVVqyrCJJP2Hvq9}Z+ud6NN_+J21Ek#jRjzp8Byz@j{RW4`<=j$ zLo~g3AuICWe98o8ts7ar76LxEI4t(wpl}#rNS-IrUVBjuiKF}IAm6$6x#|L9ML*zv z%%WL#cSC-RrQAH@@2(8=9m?z-LHJ)0K|Yed62soc1^K`K0&|D>WJo(r>-RNJQ<|n@4$t+i(91a(@+h5Jm{#+;3q64r0llg@-+Ei?|Kz2mI^LV+()e z6XK5%e8-OTh3L!D5AoFOpEtaEyI``1YsY)Ocx$Hwv6c&bdzT_s`XrjWbImmaq8Drj z1AO!XulaZU*yx4d19SO)%zk1`_j>L2C*B)CT+d_o1H@jK|19?Fhr&J^C^mrmM?Vq( zz)zpbckhHX-1y({j;F!QwlN?4z`VwWNL`bKiLVWyhGQ@;n*3``6+e5a$6Qt1Q*!Ut z(EYEnN_=Ac50K`7bcvt*V4fFHpnC28DXSdbk+X(Z2zG;hE7N6g1tEW}JCY#MH&%T8 z^-U;b&J5Rm)ichceQ>}26B+l7cR*QQ2g2>`rr3=C3cf?ha}Qzw%qWlVCwQHC@&!>{ zTuifEi`K<9jX&p(i_YKm<*bydbN^`oqp-U+!h4ZzKw!m;OWjb$K?_%QY->y2IpS~3 z{TG{FV<8BM6?Ss@xSz8Z`#)K-J;jnThPYb#FUfQ58NPFVaBa&f2yPM{Iy^gdYw6Ga zJ`Bwxun+ah!i4sLxE$!RiFA(asZU2``ew(H=S-`3OmKL&7MZbi21Xs9m6Z|jd}0=h zEo72lun8?5p_x-oXlGxrI0Vj+_XNmj@L&8jeMyffC|175mn&2E#O z^%aBa{WnDuVprOgWar#L0~OF@F@1re*SdHmA%@MJ!;j}+OGUO}$#{zi89C;k z)2!vfk0WI<^tP1NVHb0NiQREROW|px10DO>ERus$!1Xosru;`4I2--wK9H z)j;u*W3PVjrY(7Mqm3h9oc_V_H={rs6=&q>haW$geSgQJ4~}CH_8nf{5~$keP>vj6 zt#*T~+4fl&(%P9`ju3?V&h%cye;F2V-n`!7-Hf$*uHIG?lUlLh*9qWc^ee^h;!Yhs zXyb;D}h|1ZWXf7Dx2$LehxjJG%HNUqGn{E2oOeLG9Oy?vtWG4&D4AG>PytcISRxulc zfbqK3*)7e6<=vWIc&Hf-Gb2P*Q8rlG3fNsNP|0Eh7idLCUn~f3SYX-tc-IrGW#T{7D(u)@27G1|u6CgC?^|sl+U$hgw}VRF4H^!p~*nvNf#9tY$4eP(5Do zmWu^uwHk)h68G+5-j~0ETzk0Q}QoDiD+tRw3wB=)Ooz+IK&4i+dE?p*}Uv?f+4CdkIQ|l0P-f zwvvUBk`j;qG8?Wk$OZOnR7S zjjNFl$#BlXUixrkM&7@Vh8hA`Ojb;Kvm02a@=WO=?yPa}172F9O^pB$CML{%2@PE& zS2!c-5O;2Z9EZ%&9nAK#nk0vWI0%N@2@RI%5Cx0OSHr9HQ=oxWf+-#r^~e{<(L>|d zx2NL%8UgA>OQp zhje$-YP35YoT@<|eiI#LWad`FJG*E#lS>mDj>9A7R^&TbMTo~r^(GNYNa|XM4j?wR;1oP7O0!Zhq$D)Mt(m_xz;V*jm3RB)pss1mdqiD>1 zDGitDAk6#d7nywXsVgu(6Cy}H69C*X?wy3tZ2HrebNP+WBp1?a^j&$5<&fnoXaN1? zIDI)#UnxgSsX?B$pOA9qT6kqCUSUn6Cga?CTgW=6&4Dk1z7z zzhKZOb05-I0Oc#N67WU9f7Rjt&-ogGd8->BIPb%{%fgxb$&*QF6AibAlEdWf+}DPK z@bkH)q@?7xdA@HuLbU&N*7G7Pcc;l<>-10iJ(ZMH(}{$HR8z<3JPebEmbq$ETz)-Q zBS&AhfoF$5AslCPaF?-6pG$S5I0{4Ui75KgO!}SICpNxN10JMvf01{!AWaewh$;SJ zqeUw;=vu-8<(Sl6cZ*tI8zA>i#IcErsuaj@vN|sX+ldEO$b2{kr69>@v45%N2|7Rz zhQP7}qP8FqKm6tRh-J!McAh5vgd45ZEg2RV*vF&`_X}*WUNQccXXsOTsxAGF9$nn7 zjsk+*tKeOs{fd%Lx5PeE;V2w-&_?(LCaA8c|I6F?Hu(1|Te8!d_(tKsl7G=akYseV zOg9SG1i@KfB@@^*SZ+Z0gU(W*=kWH_9ry)-!M~7<F`&%8(Ul1tk~( z?lOppf1$Q7%a9dw1vYpLEj#jBGk6hJe9>_$z(F9ePU6`vI0;r<#i;{D{s$+-u5d8! zfQ5FgB`n8>@E-B5*4KP3tZJ3NCQK0gU(4q2b)&x8aV6|Q^EKJbLTjl18u98_^VM7N zMVA_~PdK+PslU2edbQ@&@;@1z|Hqbmi2>?k{geV- z#QXV=H2dF8JfC0p?OHt^Lew#1*~q3pY`8^m=$(yf7&wy8{5EuGEe=v*#wdkAk4wHJk& z>RP7X6>KoTn?b-2`(SP#3zbYFV_b2d`i?hQ(HOnI8czY%m>y5jN>9n<1LlBUEuAZP zv7=xAiyMFxWuT(fYPpvH*@-%0Z&Mv}(F|wjP_Dw(((cO}eny5MH$kk0=jjHo@W6%$ zuQgb(IokNs)O#-tM9_7EbMHf&jBv4+9~A={=rjeouWPc?>Mn0qbWSbcWINH)a_(W! zea3S@fyp&0a}11LN-}P?3=56K(I3NWiqyp)tSH*G+elDz6tFU6wnZ9f5q8~RSL;Gk z)AxxBl^8m|Rdlsh6b_u&J|5Z|2pMNVPA3O=Fj-KC^$Lm}q*7wcH<~Htme3@7OJiaf zN+AgdYU%@^pb)qIqS?BlmRoUEs)V0@7l!gsrh@Gi^q3x=Y$1_x=1H`xCekGf@# zq9Ca4Tnnw&E7+843s27cQj9ak7rkH+AZuAdlt5yQ+M5n0Jkg$PltNS}1c=a;C;hC3 zc~6at8Hh#4NyBCxnP+`BZ|)n0%iPkJmm4!)G{hN0qN|8z96*0M7y$4XA!-gD46t@u zKn5S*gBjt#^*;7_JYlRW&L4OnztSPcj&x>@Xasy;PWWU0T?>!GjktJO4%~|vE^B@m zoN#5gU^(>hOfjbbN>W*?Ss3rAGtft}{^ru*vrh6oFiq*^40T!tB!){V%;Bip-k_PU z*6ep7j7jo#l8!U=qzxHMrf~oMxin{ z1w)4B3`^BNUxDj!C`x%==XnWFU~(Rs3%@|X3@OvvKonamf zJb3wVz-I2=LWPWl20pi>qTg6&^?Ts&t=K>vYre0a-WnpcB9T+2no>{+GCIN|;}oQ( z5$tt`#`)D15)^f)*VdY#o(e-*re>k?m*Kjy{l;BMDZ#@uU8}JeFJd++ED^@3IdhQH z1aYYROc?XNz>t&QbXE;>a;JOkcp=Ah_{jb>KYJ$^34l$wqC)?8e}f4LHZ`tyO_QWP z(l6nNj|U}`l=1}uMJ^H=4Nd8%D{+p5T6|eQI7VOzinT1NEFZ)gQ!JSTv>&G{5Oql` zxbMjpmQ2%POQSF{@j4@{tPAj(d2#x{LcO3n-F7#s%tDCY;4teSJze6)cS1yp&?dxd z;A5oe@msiAE4|msF$UgA01MJJ|noh#!Dze?8v?_Pi?_^@8bSCx}MkH`3|iW;D<^KtG4lnLa@rveF&F* z_Q>ISYpLKrakjpzk2BGGqXil=|LI(uW1Iyf$Q9h@=9Tl=je|F8_X`YssH! zNyWn{jwb|n|E5ds)Wb`6La`;w_>`+SDgw^IT!}{!ydvamkIVtL{FJAvDe(TYq4%LU z_rdj*DA!I|>*_Wr_JP*WXgRv1y8NyhcT(#;+lHVum6oVV{kFd`QANE(ahV~p(M*hn zqas<0)075!;`Bbb#ivXeYYu-N7}0n@KgamH0^TkpJ|BKrsEbW&+lX>9caH8B{aCcd zI3H8Df6xqiCNMj1k$K^cXW-A$6{dJ82O8PT)k8G-)v_zErpbQGm232B;gq-t+e_1x z1*_`QF#aj0ChCMK%wgFk2eacTZ2;f@wwxzvB2EgAK2@MDSF2enVH!9tjJF zN#~{gMU%shDAkLB{me6e$+_M!HGPPQ{}P+%lkZg#ghr%qRG%X``CV6!#Ou72_qlm# zguaQPGEN1%oIM-sdU+WAH%VKtbFT^{;K&ipXRWAB#U(;Vr)p>T!z7*o#~!-hk!$5kcA(6{co%59-i$`!y<3fCkeOK(ie zF!+fF?QR|d-he{whh`Ktiik>D&LSQt{kF4)k7}nqNRcgLuBlV+1Uh@MdK~8v#v(9P zxOu{G7hzFp||=)W8_!s@?)Mv9)b@0#P zUa!wx2|ruOx-@_^C9N)_6QS|fI;4mmtTD-^aG;oVNh2+}UxrSUJaNMXpY+-4PP905 zQT=B-ssB}M;+ww01qi&}RM zM7%X1*69GLf<)`T>#!vx&#)Age4E69mSXb8OhRZelG~pUmO*FscvdIOO(K65APRKb zm8#Obibx+eVlC-fgpB-pNFV-jCwl4k=%2FO?<2mKrr1`CqdQs`<+LK?^2QEsbW1XJ zJK;q-o|=X5RxxmkyKTaWPfMk93;>;|5@|08N>P_-Z2P^ELR-cm>GBLt&rmO*pqmqz z<;gDW2}N`eO{6^S$Y%J922sd|X@BKCBgwIm4Kf>vZRYe*I)eOfWd*H~EULC{cZ_?M zfC9A3>YxHBb?jp-G8*caU0C@T%gzes5XroHCgaatRC|-?Um}Hamv%bm++=rMZ#9O`R!u@J1ZVe4Ts!+42VL|e6RuTU zrO6TdcpNtzV3`OT5m6KBPDmRzP<6@i3XOYvLE6DL_5^CwfU;C-z-4*vzhOS^$R2|| z97+OL3D@DPLNR08>O(;`tXAWXt)*sSly^r5aoV3~DlKCF)OW0Texk_*Z3TF4^+Bh?)Uq5K?a&16K2IFFEkJgYjxSOz(#YZ|DRnQzrxkvNE&_UPBO`5M!xy9`w0 z(rGFUep$LxAktrVj_NJj3u#>UkNHN8!KM4*k={*=X5C(E_^8v!^-OPAB8_O zg`Hf_#^e&you`I6Lv(&Gtj)P%N~}IJ}BioTz`t?gUBjB`}SW23a@^-)#-z@(;g)5U&|Oy&1~b; zrufCr?(>dKvveXG2T!cRGP;MrLccHG6SgjLXP2JU?-KQr)I}ejwPQ358u*snU&|pq zD1M~$hFN~yPXwwT9Rhm8G`r;x#wt(Hhld1+Mu&Z4V(-^I%~?DC67hfRFW;wVO6V0R z1K7&m!66Rl?vwqTCD)kG|Fi|tJxm4xjK)xl?{1u&o(ndEf5F-q3Z;2hE-hH-9@(u` zWqg>JnZ+SHBAsm(4jJd1)v8H85t1)ZEuF4(xS~Bev7E;ds;+e0Nu}JFdIXzciMj?% zIb=un;g5m(hP>XH-&o({vUWi{&DJ;=+di5?%@^NDyw2+NN5K;o=$}pZ7dj?2sQ(r? zhdfqEy>*ebC`3(@85BOAl@B|?x2VN3`?|iAbFaaEDi?{S{Jf!f4vD@N6V2uF2?Y> z3>ZFe$&|~nEZ#PhgvEAa-8E9TrIm`(%$mXSQJc>^bAHkrt17hn4=-gfg3Y)kgIQ>u zU>uZ~>z5Yk(3Xhht~P)RSKaRIAdcx>j{hlthLWu`ei;T7Wv?Lv*6q?|Do<`}u{;XD zH*$BnPVzQtu=V`Q8jKB^SnV`Nj;T2hdTmfEZyT%hjkEwJPH~ym;VBkzp|>FuureR% z!z3R9e#PP$%@iYNr&`^+$)%h53c2ObQTA;7xlta6a=-v6JzN&CO7+m{nwxHccd(0qhz7zDOWHT)-Xf9#WI!5`QBn!N2*dex%<3-+d z{VWzFrb$}jWHYD&*L!c5@HJ-piNJF`q=7Tz=F=8n-yNhAVvp;4mUL5ys_)bP)H{=QVNke~9a)C7jeH;@7l6WGc5F`yKh@J8SlO9NFap+C#ta4nk8d zal98`r1}VV=}z}UPIqyVuS{CPhp0GKV@ip~ZuKYOfslJVMsLpPR0f$qbxIt2^{ZjS+Co8KYw_KV$}(C1FhdqYVpg7w9Vcby(-^Y&**VSUcu;`*mv z&YHp3b7kQ(MDF@_WPo=A)+jssSgQ6TI^@piVX*Qf*n?^qmbj$3TQ878B7Ut2Uny=k z?kV2~kc)IngA4m1Dh69v%tLeu4k_baKo2YGn5>J4jVy_ z^=?X)Bg#nyKx)Yn;knp&kiFU}@o?hJ{>}!|yaN_IVQ7nStZTytrD`Xm?1|lQFdVRy zVXhJ7BYB+Mn38m@X7@X>s05Se4JpH)LX5)y$f!@N&b1m&@HCehZut zm|Dp3D=)o6?mBrNQs)NM_pr8AVweLQKS^Hv4?VpSk2+5L0X;8V0-*fr#iHVh&!btk z)?b4oT}yY!c?nV-Zn!f7$IJ#@B5nHo6vmM=+=D)@wMziuE!&c~D!WGZUX^U)<0K7mV=WW73NHgeS+vt98~HKGxLGK&Pr}nrkXtXPPh?iI zrgtv@kBsgf`i6~#1vauQ?=Ac57j@jXrOMHIw&X57=1~5;1yp}!nf7cVT^u>%4=RiV z^AHY=sxzR%^K09B{jRfO-{*&HNn3|DM+B03+1(_v)xr!*(&Jg)9~rR^^nw^3haY+A zfY-2VOJ!_^CI-6?a${#>pt-U0zq?t?+`i{@kL~LYz@1@Y@P|IjIS^0{9YH04jl3JB zR*mdfT|4`bm|dE--;yVONv^6!b_W#jSXRL6gws#+p``4r6HqCy1d6L(yie7uRhC(; zJqmn;3q6br_{MJP);gGY;OJFcJ?AQ2nz<5#|@e)r(OrWq*8-$(4GiUrq^SJNZE@5;7fs`}zkWTf(!cgdy2u!*W()g%BF;LcTkCeUV44 zoz))F%>ItvvrIH+eKBZTxjff3k(k>XBjALY%&yC6J?hSc1iEuCsO8f03+htBER9RG zo|wwrU%}(MVcT$g=DxI_Y{*KtH3yuRzOkzXvB1cT*)gcLlsRlbRoCybpWw(r15>4_ z2EN0Adgb^)_atzS8@65p3`=_(*Qjt~`;c;d*YyhV*0ZX7D?ff-`z?@sGkq)LeKH@B zie3#wW-9~_8YD`|6~vrpnHQYJJcUR3f+=pB3jl)7D zGASzcrB!T1KOmI5Ce3TG!x^km=S9S4o34jxYx>A>+Ez1@V zdg@qgaHATBQaiGf(Ew^|N?g$eK29PG$$BizEGY{0KSI$g~i4Q>aj)lxU@Rjw- z3?2w7N!-*6Zyqs88 z*H9=be;%jN)cY`vA{~_BNQC9FpO3mu)(?i^I14V2L=CtQi-N|S*={Y`2?oa(IBmGfWnueV53}d z{#-ELbf?yAR{53xSCWCDyV7!3O^>MAuR<>VeeEU4>wc2IKV-!UN(zxgtIl8Qp0!51 z?>i4+76J!6J3c#|4WKVzmA8Hk<>~aq!?tL`O!+S^FHc#f_gqoM>`YmO-psz9JiCjQ z>0ICPK_5rne3Nsf^+q)>&sDjb2gB8MncVAlzrXI!N+s*N4_P{%Zt^948j9K z(JQdLY_p{7y#=}1{K%SKV3#4yNcd9D<i2qC`g*`^8)P?p5>ityU6?~t}=Xr ztFR))3)g;S@;Mc0l*!!2<48Q&DvIZJtz%q#RR;ffjVpzEb|y}OpGTm(SIpb(lXr%~ z0FYn3-1v|nb_yL?w1;H>tNHf%Jy1GQWK_E4CeAU$9FPxdJmV*cqQcK4EAJ(=`P^$~ zgNUv$_ZCTY{61Yhl!>O#p&~rsw=b96uyFTyz83S$hO9hxK0SGf$#^hbc;fl}(l=GM zs5Ws@x^xjrT+yUVqT8v5HQfHCAD-u|o*y9oI*+_85HUL&$RI@Lp$32|@~uz>iok0T z4euG|cn(E0vl2J(M$U#XmVF>h$xttN)iwv)TWZVAxYWv<(^w_ zi`^BNm?OytIJ50m|6|2hv=38+6zD<+eCQPuo0IC>cLm@7>7wqp0+>T><3_O?YN0l( z3JI#QEh%&P3UwSvS&bj`T5to$%liNAx--|8?}VF&I2}<#L0#SEnD-hFJ~C?}b3bPf zcl-*cIyJ26grAN5>ob!wt~11)oBiy#EQb?;DJR zAHlj^=>)Z?PuC9avI_C2qr)E6mE9pHJ-j*YV=m8Yg+CnQU(eY)Wtg({O!R?6Kuk)1 zpssWL>3@p&0Pvom;81Q0s{9PJ|AaY`ewSz2b6?}BKi+2)Lx2=M=qgD?PH&<22ouPO zgZ=wfGZ3iYG0>@a=~c2b$aWk48XQOM)h!SN%_+dRL=65=*W7EK_3&|FWg5jCMT}p# z$JpXw9%WkR(^=eB7?Gd5Vfuqe9B9@x?-N*c;#8>1)wW8&+`dj;PIY7N1l$dQo~?yI zN&MGal@Z4Y@4Hmhisec+tNR8EB)0HGxs3F3ttfRJ5p@}451@C}w(Tc_Cgx7mx3wT}psvcr{;2gIgeu!Nl;tMRW{ZfT=^wfLLjDCbm*~NJWM^^3oXDiy= z!fGZsr;JabR$xAS(@b1eC4AIvwlp%UE2eX;(u$m)tvHX}Y;zpk;doZ*9d{qjj8b@_FYc zjthi*G`#zH6W8m(V6sCk?A*ygXlWU-zM`x{#EV7)F-YS2!j>+q6@hOD4IDGT5;*cZ zqD>^$DZk8D!el{|#8y`IyVVs^)|Ry#|G3iAxyh!+%O@56t5Gj{L@RJSHAOjm7 z45JLuG{rDZfx!o*=jYgqqby;Rp|BPzVmC&N!-ZgYdy!nAU;yyOXmk-UYB4di%~B3# zxX9L_B^KPeWbxy$DJr>haMe~EDt|npVWgxU%M|?)mUisU*jf)x#(z-y(sL_!%U-t zLu$O`sh1gRiktcp1+}(zYS()-_3O=ppqgbC9touy_LNU`|YTt&r!M^k+f!J_FjCCfb@820Ta= z&sY4sK!Z#)H6LB8ME>^~rZ}1lX_ZaW9|m1ql13fw3DPQ6uSg!2gk6JRdSpr|QhYng z#w&FTQW+J|)PiuEVA4iZ&cQ85{c}jScx1mSh}%d`7`un%R(Wn`qUK z@>2BjZ*tS*rpe8LC7|~%Av9|sqHw^T(R#o+?>1lTG=H@^NWlQo*llim2ltP~R3t2J z$ojarR#AAtTSmmL+vy82T1ttTs{T!3=`>4Ju7M9%;6kT`@BQXgv?M(;cPw>J3V~%w zo3-SrE0SIBy1Jc4_i7=5IJ_}LoA3K zqP3NA4^NpEueQ?SSZ{u=s&Kb4GBg(xiH{bKq0*u~zi_uZGBh|c)R_*CTZ7f5+9JHd zBD@l|S7CBqu+p)Hu0hRmblERg!<;wh`jfOMk_OpMOm&VFQTiWzx?Tvv1>8D9pp5<~ z#Z#+e<(4Ramp@pJV%hwC1FoE(H<8#@mptmjA8r!*Ef1ZRYBAmeC>>L!(=6YAzQw~R zwHMD>f-#0r9zroE$KLUHi_otIlt*ULvb&!Kq{ijf2^tV38v8E~8Nf0b&@HwacJ zeCn7`IZDuPd<&n^5GwWOY1|3&MYG83$x82leaC-dUiArktkFSe7k-L=rabgZTdr=Q10PY7M;9B~KU&;s4eU?1Pn zUsnDYR9k;WEOiHI-Idk996pu~6UXDZ|FZU>Vh0rWbW36)lc^Fspv7{s5Mcj^&DyY* zunL@3PO3GN>(vLB`*%Q@6Kf^Mz-rwHpS3hBDfdar_EM#lguA+*f}=8ipMYmzwakfx z-!+YIE*XN|}emxgCxwCpk2)UL2P)9e_q^n7I&Gg*Jba~M-56H~`-ogETW zmcgM<&UR_O%t?fg%x2#$Y{ffQeKTX8e{(fo8nYr31Czz39~{FWE>o)XldWU9T8fB0 z1G^@=L$hd-lai!;8*!i{+%Q?#p}N+wY3Z4=Y1CCgWDhc9XJ)LKk|T@F6FtiZmxAqt zgsmZ+E#svb&GcUf{)5Q4YAf9Qbke-u&w@!-k(DRbB`3+@CKL;j$6O=3w3Dn9yO<(0yh><-V-3S&~t2fRvR> zomSCi8DvufMT(e4D$I&B60aFjVu8?*@8GRbjsr*TKB-awlOdRk9+~l;VY- zvUg{7nyrGe5PGP=yVe=YyXk?VZsRi%wjYV-BwF$Ua@&r`K2x!m?zW-&TF!O1Zosl&}MRfVj>9BEprQI9IWYhZ2G>=m~cy%My6}y!Kf9 zNoabryfRaE;GX<4-|if7eP(C*VWC@Q<|S?VVD zES<95o4tJr?RB$ZkJf_?)`LVgM3twW$;Mc0X24e?utk~a_@tn4P`gAXtw|oJ`_ZM< zlUH)*H-t2nfH)a@Es;7(Obw3s^^ns{w>Hws2+;e_+|z+(F#$Qw{Q8Nn2+V2Q<=sR2 zXRqeKeb*{Ne;Zcjg!7q&1{H^m14SSGLbQqDpL4_>kLJ3wyr=r$2}iKR@>)Wo#9{71 z+3G8Xeu>Yyjr{B5k;qsltoT?vO&bpb5#ar3$m#k`oK!LTspak137rFZhQB z_TfUpCW%7EKmQhItLXawD;hVdKrhpxTFg%h<-shD`Im%pY9O}Tjt@e4;xlXaMuBkc zL@q53f%z#ua8PoFY`zdsP~&1~(e;VBPn9P+VfC`{7v5?E-1SA5Jg=#^t&tvv6Zy8Q zDnuck4ATHq#@IjWk@)8={6+-s-w?MEKMReuQ7pZ9HWQcp)`Fd^p<=sPg0Z6n?Vo@A zTE9874C<1`9>*$%P|%Sjv-&gOwAmRfltBOFGcW0_!^#wOA?*2c+7pj0C4UKIkw(}J zk`^p&qhb1a3vcm;=cx$aa%0idu@?wR9k| zKsmiv8wp*wJ)2kvdbFzY28DSK4^0E!m6QGbe}5QD>i6^mPmjM}o>zw=^aT+#5k%xvgA zWS*HK2nH*;LqSEESiHC6hpMA#-G$!=8@NWpIob(L<@(w~(`(d!)+i%PU|07m zOz(}=VV&=2B*wIyQzI-KeH^zH|B9dC0S*>U1WDkt#@tiIyszgkN~+?1z!A*{S}F(^ zulz9Q*oNAbZs&94+2PJE?^2mUkBVzU+?>(M51n-+4HubR#dn94Sq8;1hEpcf1RA7O z@*83J#YUX|AzepHB&Iqm+C_2f{Z4cUj5KxHnMA0x%FV;3&TzJ9Y5|NOJtDv?Nl9FZ zI`Y;~xM&UrG4~ZhR!lUAI~Mu0AZGL+U?7;Cw=m}}`n@X@qgt10BJ2-q_Cg#(r9;}T z+YoF@>;?t*?esBD^*r;SAPmm^Ic;*q{Y~9~vr^}ywc^`58GRY~_$l$V&uw@$kDcJlwv&!+bZpzUZ6{yYv8@g|>W*#OUu^4(r~mn9F6Lrt=H~3Pt4`IqIkl?R+3R`U zp>$qhJGON~u>%Kn(+O$(^gh#9vc>$^KN+wL_>YFayVE|BjWjIv1j57^Y#i@h&Yq!> z0`7|ZldaQi39E4I25Z^Al^{D3jl-k|vcJq`dYp`043t?@I3Wp4rMh^)+GHd~JLATO zch`v4Bc#C+XpnJNiTx}v`q!UbWu4A$XP539J9i%@BYgT+ z>f?Sbq&~I&=1*e31(Lw@k*z`dK9`S^sQxWVtQPq0@lfCLOr@-MW5 zph;0Y;dw2eD_9d3tG}@fRfC_N=WlQ3t@ArFCVlVnvijEcx!(S!(SK$}T`|g7V$36i zk>+=L6#B5o9-zQsWS;*`+p4}38WDarT8Ns*(E-pLDsqLi*@6^Um`uG zf>10_KZl*XJP5~GBE-@N5z(6Pi3-s8bub0BtiM1zPG3(Z2j`{-45PXy_sAh}<2%C> zcS}LyNPQS=OiM*5AcH8i^<@tv2Y1EHu0Kz8o2YY2-CN&q4C9N`+Eu@8~RlK`HG|;QDSvjz{LKQ5@opm#qKDq4Dq%+h z)7ks_netGr0KE+z&9Pos^+NZ>9Fir3ylz>$VqpZ0hjPH|G#mL&EX?lW{1DbNoU$FyYxIa8b84YQEUkUwaSa0W=0glI_ENgD9L#r?SM}!Q1V*0|pgojdn z=@(=N2Ojd8A_)@fKqik|&LhSz_GaDtPkEJh(IAwHoht@fB=3M9FOD1LJ%94aUvInx zwT?raI@@~Ld5epdrwxFpJbfwP9gdkNlEo{He!*DpN`s(1>>0ldX~dp|v%(l$_Tuij z@6Enk9a}n;4R&5Q!HZN)7B446e`Aa~b+Qx`S4hTXs>ixIDT(T6!<4|f5UednpRs)i zRq56aNfuRPuajh5enS4y3)m(nec{7U8=*^Tqf`S7Y5{5dTdR80{?WFSx!YnDBM6($ zX%zG9>F`L1;rY5F5kGYq#~4<^qW>Vn`a>&b`kIJP&OPKFjAUg^em*>o?uWj{Nm_uo z9lc*ORZ5zxW>8uWUH(#32pirq9tpcio8hL0B4Jce%YLrHHYe_Jq-Nv?3|vqld;yND zmQNEitp&CzqnL~rkP-wC5m;Sc&r&J3?s!$ie1Nf(2NOKS*@Tr9vzdu)%dZlBqpW@Oec5TX2PkgCuaO4^2{#N|mSTg;y+;e06z(ZG8 zk=-Zn7hplbu-q*pFfG?osKR>75ld0xS81WO1^(N=MrScmuVC~+!<#>hVU|g2_+Sf? zCuM$%OZaw&f8r`{zO5I-`R`jbVrBQ5V$RH!SlPb+&wa5EWFp?XasC*s_6)Ml#)ahn zK*9E&@8s?Eqa{w6yk)a_>gwviQBRmAL}F*DX{9whGbaX!3dQcV>);4fCj?&drhYz} zvD5ny;-V_vz@7!bL}{sEMDE7&$+yfA-b=#*vvA6M&9en0xwvdGCzE6XDXG?Y6K$~a zN`Xwzk&R%CZ3&Md5qT0;UvVXeq5Us49{YR-^_;nhWtgQOO#%nU5SCr4sug`RNj4Y6 zH}(sZcB4~MlVIX~8v$EfGY8#3Z4(f3*ZuhI#p^%X8z?nQqzS|09k&tlDO9!7Y?z!` zicsrC&2gQ;<7<@|Zo~?0=Xi9I+gIf*eipBHpI6OI zr(%>?pGyBDrRHa|uFlGr2jMOs!} z_Y4+(Kr{(OTp(DyGlS$YhmFxH)5G2Jr|0nzn;9jXgHtr|g|Id%Dq&&Y>w4sPvIlI% znF@GrN(%Wir*X79%^nOA_&@UvkKNVDMdMHRTtfHfD2Yu`SERNi%0p}vDz$LgzNAsT z@3M#a@fgyDp-RPsSEh2VB4n!-LLm$S}=<2$XF?s(kvzW+vy`uqsGRtfMKXGOLnL22GIokYzRz0;v32N6h z%75@QFTl7ZF6~On2SL7OYe{c+9OnJ}Nkc{yk!Cwjtsxt*9m~iP?8hS7uSD5L*grzV z{2+B~X~FiWhydU&CE)3{_NiSQy3NRP$xCW!l9ol3RZjSxkTU`haQt3}jizKxz^`4P zR2U2yDyAJbdxpRA(Q3o9E;V;23@?VOZI;4b{)aUJi!avN;;ipaC+X=KL1U{JyL|Pm zIO&gp`sA?tS~q;$OhIF4%J}+=iq)%-Z!q{Og?qt3ZV?vA$maf`uB- zaj&G}+K~IjdPRN5x$$hjX42qnQ2$oWhNul3jO_) zqk62!_g2h!)1Ad*XDNLLhVz+oNSc&t#?c#VCnmgE`%K;tX*$CR1ngIQXiG5qLf0Qa z1QE1E$_jjw$GhjN!=98aBcNv-J(|Voq7aGJGJ1v=P zk;rpMMZkSvYJaqawv)CN7HA>PUkFYIWGbiH(b}7W7Viq9ZzydkHIK)Er2IoQM3XX$ z!l`^<$|+=lYLAucxg&2{?Ecf|5Yw;(3%{?eDAyVPo3>t+C4MRcL6A;!rPpg@B8Lk0 zFA5NG+3EaZ=YS@`gJz?J?-c|64c0*A-A5y{;!e25=umZEiL@v?L&Kjw3m)9BmHGZ2 zr^*A+OiRIT2KK5#(#;I-lRyER0Of2Kx7o4ji|laVd)H805ZZ6SQlZ=UU8|(q4L)!G z8@@`w&RG97)vlMX8w#ucVczZzQZEa^ZpI4p;GN<7dio@8ARO|J@&Ibm?p(N$u5KsM z+SiBhbKs>f`pt0&2gbaB%#5fn(L9VyfhZr;DOBkWna7`$Mmf?lk-up3)-tK2KBQCO z9H{edNrq9);PX~VD58Aer(QA!pD34P|Idehg+3*zl5WA-aFqT?5=gQX%Z5GWm8lnB z2Rmh#i6YGle&8=<4k#2X#gyR|!$M;wn zi`2K9_|2c|osvQo1lI~j2dfG;k1n%8)~GkXP%n2DFmbZUkgBSts`g5Se6n)A9vJqD ztav7fQoe}R3f2?kah8sj{&qjUf`nUIzxj0r{uOli)pM7nCDgT428yeIviC`X^%wA> z(*h>t(WMGX()mb2JB}1!F5PU+Gm$iHZDAiSW2PZ~Jz0=-Z>-N`7s z*ylr?aNDYldQ2hDgG%>RERpCm;)(v~yxrFvdipl>a?DjlJgt^#3LVg>+Qkp;nET}% zIJh_yzN25Y9lb3;SEkI2fzIR0Q{*N1F_bny+ru(D%X?KH*NE)cKr=Y5&|dSD7qG$ z6JD093~45^A1*bdTCm6dGU>9I!>>*Au*kmL>uD1d$q~K)6>q)!hA+ zR$}1NPB2p6f2@+|*}p3>?UVo^mly{`baw@q?6eL3c#s0`!jb#WwTsHPBzRji#lKio zs4e!hxbofq&MbyA)=02mcW1;p<&5A>I_Ho08OaWk+5sN)U9Qs!$(M|EPda`#H!_F| z9~cG$@`LnuOe5|_2L_sfIzvIQ1mn_pKtCjB*4XnBhPj;4BM5;Tv@$80C!Ss!dJYg> zaEAN>kP1v#rM7PdGWRtYX5Yx+Lp#(6(t8^Td03e5Zde{U5Ej@$ya@aP^H&cQ25a~J z3$su6vP0!f&?`+mZ~TtPIYGP(Gyq$fTm}Y!aO^2xZwW-}VK{MnWS%bxkw0O8_hnBB zU_I*PeKg?Rdu+(VI2QWo@BF>>GOXP>?+P+u{E+^)`pCmGghZ)lMqoEssvpE)$8t9o zU@WP|?~_Ng@J0x|zkKlH>!Ab~`c}a8Df(={j5v(KZk-xn$2oZrf!tKyguOJBxWcIJ z>ETZ3cNAk2;Lbn8zlckvLlMD+nETYgyEU6ePQfx{Zw5fm;8cNf;DJV=wjZYpWKKTb{*C+8LKuT|!D z+TvkAj#yXy)XfV=VU;IPM-ZUcZr!)2b(>F;4Hk&@JrY)}wt+5GAnILnw*ZVN$Vt^X z?6(|A@V*qgrw%4d(5UifG}ONReOi%!47j0VWzV?sCv)#L2-lAx`#H*JEeGn;qcd0< zvU3N8i{>PN5IFVipqmm{zkYuEwP*2u5yK>` z5@aVPs6&5o2iDn&6nm#q6a)b$x|eTRE1I@L1>G@PPXu(s0V68*=k5K<99?yS_yh-* zu&{cT1oxS*j`@jhhkluWjfC_xMBnlA+kjF@v1C~9-r#z>zJ|2BDtmB&xG@FX;J>0G z{>@hShbe-8ms0?m%|>f|;?vy~2c&cR+L}#|nYx-wT*=spLa8KpzMy zr1|lm-zq@2_e6}0Xn%6`<`v#8dZPqcSN0GA$0Yr`Vh;JiiP_kag$rO;1291Db34SrZ!%B*;850$DV=Kj4gm619@HQ3qP5vQB3rDbr zE7$>L_ztQY3ykGa1c_`|39{EOq+ki*qwu-A;iN-iktF2Cb&5Fe*7rREtcQHTxb z)&<5b=PcNZDmbqFr*a3vxhcI7HN2;zC@23DDY&EN$xn#DiM9t3SkbrkMS0Ri0?b_z z8HNZf%4yC25&ZJx5iGp}?n(RlwG>>x<>UML=}YX`93ref996W5aMMQ>zsJmI6mdB3 zy@B9N0ZL_o5+pJ%^#7gK7=!@YlnD6R0wcabF#2uwvJ~_B>BzO%v!r|l)=mleK(;RI zL>ok-q6hGVWVt2o<^5*V$#C|C3Y?(wJ4KM|t-t4Z*#^IXx~U(4&V{|XB4~cux3C$D ze&|BJDc3SlARh-n`g1cvXuaCgUWhgG~n@@&4WBw znlRXn=#QXtuzaW|;J3T#j58Y1S7cydo89NBrVRk%sbdn0hko;gNbuF!*RxVfz01qmp6&4QSBKNF9(R=l{jE;ey-27wfmX#(RA8${yTZ>4+DHzb=L6i%P_(dR zgeY$(T;33KV7~yX#8&S-Lkv`i>VbyaGf`H$)T;d)-wEdhhcL zYZxN6XM@v2>c{@??TN0KLJ#EIoKw(i88a+O>5lpZePJTVtNy8#}1^~Yw&ggPsV*c(F93`aQW=%kBSn|`Ypad!WLJ&qA#j#^ROVp%{rum#2#_) zBWJuJJnoSTsl)qEDS~@g!tG+PJl%botXg+$6eGmE@w9<`o(BX_6|}(P5FoBCCX-#T zWt*$EP<~7r^iOJK=+d@-&If$|{)Gf>n_z+xHFJ7QSafp}9-rO=KW!xa?1vB#EZlS1 zb*r^Ja$gd%DKYp1>w;q>=kQV9k$u@k0^iD1-_w&C&GC~9X231_ZzFzR5l@>8+zIe# z4eyF+x_9+LMIx5RIm#;7i8=BI>4=>4%SQN5ehd+M#a(mOH=CK(Jm@=j^PeS7dTvHS zR(Mg?8&M&i{%Sln=BSPGE{csf*ljM#q^RLh(`&7H_&(~%BJrO|b90@)F`LQh`sD|C zXR*sDzSck%Pyiyq?ttv6Y$ITin}&IUe<5wYVk$x0L;KS*iuztos8Ekv=8P4CrCNI% zWul^;g4#dh!dtAsUvaa+MuJH1L~e1S2m5N#;>caG(pa*A9bUWh;Db+5@0L-o0PVo; zf2uH3A4t+PKK_6+%PN-_wEMJyDZv<(4WyoE7f*vw2ASjQR}0HZ6jY^JJ%@;h=p|Vi z-gQR$oRS3bU%fNPEL-Q!mOc(B72-`ozs>%>GYJ>LZevR^w%OhdQ!+GrQlq43-x{dY z%xp`Ih*^ywD<0P7^*J{sb8&i|pvw1Gde*pA-^KEYW40eP-~+aE;=N6yvrD#S{g<&r z+iU57Wi4=CSPsoenr0Helm?fd)}}I0k8&@YaYPB#1j<=O;8ae7geaR(I(dI5m?WPf zraL6c&QqB_5Jz_ge=4xLhSa^-_pk>i&LDxHO8@bW^`*)>{ z9^bDOC34{{)A*X27x9jz0AuW&05qyhqCg6v4>OCASJ?8 zj)|%5?#Y9Q-VdwJ24yEM2-WQaWjKW1zifMT7fVgn5`m zjpod)s338G3aSR6UI;Yrwpg5B;uLTLXxd&=AWZ@rJ35%o<7f8@d^Wq9?D_h5;TGTl zD82K<;1Jw$7~YvdXhCOT9%PfMh3exRSO}M+VQj{e)`QSSYCIjTo?SuMZ2 zMl$GfU>m7$rA^K2_-eLrc~g_D{N|$3pL34yt4Q`1>XB;4^8i>lP?@Hd zk1ByQq#sLp8Sls}sYad|sC64&j>g3`FnfTI%X*1Klcqt_ZNWzyw~U#0GrNZw!84%6 zl+!_M!ebC=|I0iV+fO}CGoPN@7$?kGYJS{8JWzmpKoH_dOJKyckc+&jjo7Q+Q zk(6dqdJa57FLOo{oybHicrOcF?R1m=l*UL8csx9v)$gvW#wR>bNvp>Ok-x&o=gX2< z=ME^V?A$Bn4VOX z);BB4yO}AdPY25ew!LiTqr3ga7nsYEUAnH^Yd-fz&@GNETsqO15B#Hf`R2dcWF)1P zXq(kqoTEOtA$I$bUX-Mh&1G?;;kXVfkKPtQOPxJEkUQjT8neM~O|uCxI*X5>_4hj; z14*O1Bb_4?+oD})*(*A|kv_8v{oF3QTrIDkx%Ft)+XTlz`W?TgQWK$XNCeKTB%nX_ zpCG0pNJL*{(Nn~q_|0GrRhT0}1DbKejB{i_BI_Fj18xWePFi48C-n6|%4cKGtbfha8{Ei< ze+V|2k1at+Z%m;RLEVQa-N_rI1M!7ay|n#IwL7b?g8-%6Sfqq>=FDGuYi)zJQ6gEar_;cr@V`AGXy>s|JfQox4nAhpHLD$ z`Im$m8iQu<3)J5yhCe63of^K%uYz)nKLxKhR)g#>#9{fz`o^;o++Zj7sV9Cs&J0hX zIPT(cIePShwW*j?^zQ<*^qX$+P-yqr(TEEocy1UOX3DWEAj$n(6OLECew5M~87XKeql|B(+^#?VCohkL@t(@hlU^0uku=Yn9i>eO$6=;E7h$As8U^M|3P2y{D?v z>No{Td!+O!mDE&;`bE?2mS=a=b=jU6J#+D%DgD!2uv}&P;@GU@u3IHT~S$StZVD2Dp^?A9uD@wJy`Vc@Obd# z@bK`?{(F9=m+h-}J}t^WXgKO{>+Z?f^0>UhnY%RK-PmR(F79W?;2DZXgU_c&PjJS? zKKd|L@)^k6MD@>={cfrfWGvaXNrD`K)}tTd?_{RdR#7yzu-fsb#3t;R5QfX5x*}Qh zr>a95#fQlkoZ`SEL{Xqqp-S_L*V2o>2`{=RV-DUbMR&3y?;a{N-X#1)*r$v-%0#y! zFQc*z+)${B`GgD)2YFOUAn*Jc5!o4fyThGSWbt-)aQunI+k5ioY$f6Lf>?0qcjj)H z_^qyDR6Km-h+=UD{DiOvc8h{gn!St~bgWIh`>1CQ@30ToV4i_ij34PA+sWGvn=EhA zhs(d1x(2qlkiJjfz<$hmAjwlrbl_zYhzX_b)nW%JJH{bDkL@z|r)A0!o<2o>JpAIy zE)fsZ_w+2~i40&$dd1Sr5#RB+7J4i7?BdwyB zswD|03hrD&=&;DaSu(h9Lw%zoYxNdQsP3zRO+|d>lEm||9UR2cIz@B?8^C0v!5j7$ zt~`uBw$eq#7p>TqBRh%@13GM7Fj)6W4vEdn<6qE<@tX3={90+z_BS|5b3xxqBh3QB zm`HIyWg2++FJo5B;q6$=bgj!Oaa?Wf1_LvEn;t?+EcMK7+UFrnyB|gH0VFBzR5z2^EaZ`OC0o((;=Zr{*LsHkAw)R!pTrf@wm`83LMR`*n zy8ya!v{(k~*P@xqAdC*e0q&$?enl&Gja2dh7&>GU2#I4)85h~472Gk$OPgBAdpp7T(LdkHW>ZZ)eZkDViqIsBTtCnPw6u64P1a~Y)gx^}mPM(3#^7(!jHKIIHK) z80(CsQ5O^Qc7BX5N2kcILg?DEPZY#+h0WW{Mu#e;0%<3+=juBLT{QCMq)T+|XUmW) zaYc=cQU6FoyYJFT6*3pz@L4#u2hrw3(Ep}ikYn+wq)$D{&-YcAXXr`jo0OS{gE>xr z@K)7uo4{5wyR5?Uj1_D3EtzYG_F2}RyvAtZO=XPc0;(|ueM;-Z$;yZ=TKqe6R$P8T zE2~qPaKo7M9dgfP(9fqs7yY}bRuCy$YyK)b{*&!MGAq@Jx|wegtkWLd+xAKN#C-W6b@`ecyK4B2zge4_-g-kifh><>SE2G+nK`#5Y zeuQ0eGn!uxX_msKuLO=}zXQ!00B6fi{)#dw!U}@nC*ZEp*O(m&|D!Y3gDyCTI!>Hm z#zZwmUN#Zu)Hw*&82P<7w)uGxqc?Xo8UXhlsR7N+844nc08tS}O0}Wt8Mf;{UbaH^ z=`P3cwkGRYyA_RMnKx8qR1@!4-e2CL4^6rAm zuk%?oI6BL-mygEq*G?Uav3gEqpa& zj(m_7`@n(gA&H4`RyeCxCHJnES}x`K9(iPQ;$-6gge?h3B@$apGlBnIAZjxt)69IL z#?!@!(y6$!jW(iH!I1{ytXQaDEK==J{-aRcGc&Jr+B+KDn}p6HL~fdzKwMT~_~YR| z!R%bB>oXYrqvZd?!!6i;jU5_@&U3Inp? zD2Yy3l)Q!u3Q>I)xRAHyF?_-UkKButLT#7ahgNel^%UIvJ~NJ-s{?3{4g}LW*Qa}x zD>qSi_{1Ao9Rofv$B)W&%0i>lwfQ#~``m6Q;0;47sJy`q(|{KLw1Q_kVNf&u80haw zu|~ZtR3NscKolk8S@OXr)Ak=h2(*3IK#iE7yq)RbCFMgD_(0Tp@>q^!3F=$^7j8;# z#BHe>ig^466~PiW=(JSt3}3Ko{3q$iuDMS#9Q31DnkZ(59=Sc(m#s`K+($7bXZ2-8 zQWrh0rLrXR&|IRCHuAtP^TVAqP@6XK_khYBmRmm%Sqw>J8&x37MAMy<+&f$kDz8~) zrLR>?P}B}f-wx0KK0ma=WhD=2EJw=|J<+s;9u!P6BvZvNE-`NPw-bC*{o3Uv>=!O{ z8s1+y7NwHG5l}nS^*`wAHyi&I|NN%$j~fgS-4DA14Ao90D(*zeRTP}(>^=1mJ zz2z7Uxp&+kWhyy5{9BD^MoGL~Sy*vF!RlzBWtOPQUowhqQJqT`0cbe&y)jF(pPAv9 z4x0>%kmAKzH>n_TMnp(&Q(!{|mpN9l!6&W5<}r=$V3(dGIf2@d(oGbVH!*TV#46n1 z(9_KznH#d)G!VsmWx6o^?f%W*bYbe-k>naijBV+0C6^$PRxef4-*8_L3RU4Jej0d> zuK|_XJBQL#TsenHe*}x}XSd6OTZYXK+0kL8#!=&8Xt`i^8>S>3{MIN7eVs z(S-}84JNBRdEPHB1Gj)3uRn63#8|mV(p2MD~=DXS}n8 z!|>wg>SXNEP9IG<*jvMyEN0s!4-S01rMQxj}t7EpQQ&$N^n%U|IHp!;?=} z*WjD$K3&-w`WIbL2zHRl9!oNMK9EJuJ_-3>659JQ`WN(9*PhwAhBo(&tK>LpqX_O>>rCg#P@7(Wg=!o-~Dy?#+{5sluJ!UlvItY%J*%04t z$m!6*g|zcT&Ek?rsXWK##e!YSH|Z zj`@no-YMR5K#0+5s-b+6)MU67zVDHFuMg&WM|u2A=wWE=x)6&o7?Gm%WLx^zsJK2H zUT8+DIGc!-2!;d;oFFe&J(Vm}`}f#7$E59W%F_5$R_&PYq^z2F)(`Gb2=okGWvoJm zPrSWfqx(fKcL8vl?PE<9zc)Q~->a;An*ihs#9Yy!+O8*zWx6uAKbdWSYl?M+ixsBUN0rl%l zC=mbVd14ZpUM4jYNnzf@V%`j++KFOk%Yc*(Z3|rLC@Aw_ew52NDm`bT%Qh^`{IoS% zZS6~C0IT`_{@O+6NM&7dEr%+zL9!6!5}(EM3KoVGAT1xAa}y{H6=uHg+e%h>GH$Vp zZuY4SSUJ~R1+ls1C1hIjn}4-%78DuZiYl{Si_6d{R1pg9k8pS4hm{2WraavK zJ3OEEaYf`#r79bBs?9Hm;@d8j58lIRD~+JP)F! zID@M>dnZKm8d?&N`$n&@J|zgYzPctY&M6ICei~1j!x^u*N{)M}RNro#|wCxSN zVG9b8+W4r|CG(Ittd?!mldrKbpDj}mhF7|hx3OQI6&}5=0r{s0z>%u03Ek`lzmr+> z9rFE$flFDeeI)xc?g8E{@>!v|weogo8+4lRekvj@&fYp;bVdKt}t4>(xgK^^TM+|bvjnXV^d$_)jQ%&C$KLsbt+M|YY8Yq9w$8% z%z7_o9vH+8@AND!opGh!V%OthHf?_}R|$(TTt-2diE2jJK0`&U-@lh+)0bANiH}z%4dh>)u9+{E_HUdQD9=bBh>~0Dm<1PGoDz*khuu z^ckvuyJ1z0e3~hrV$*Y=)Br*?7VGvKj%b~qp=u>*HKdEyeRLD1e0&p#_-pbwr`Os3 zCAU--RMphG<(DrB7uD3SES|bgi{uQF&%;eth!3t(HGzZ)8 zEY(iz7|IW{1aWObp!TiIwr$1cUvNEqHSo2j*>DXQVKw$uYcJ}BY7>+rur3TDGwHeiEj&dTtbGGRX>I1v|{UT%z5 zbHMW$AwLN=YNPuUZk+6YlM$~B1T|PHsdl4=eA*%F<{WihNz0h;DU6mSJlUc45?0rG zZ28A^S0P7 zg5abDqU{551I8(oBdvoV#KkE1v`wQB(X!#QqN&)5qA#Me!VNfwx}e$F<47qX0{~(& z5w_V!X0xWvQ&#S+Hi>>RmI`Le5yMq1rR;Wm07Wj-wCkGcjcV1cI!x{)vsqjBke+$b zboFp|*J5$?km5nhN?J#)Jd+TF7GxsRHwR-AX=>y9)_xZr{>Dg*U9df~5mHt}yfkE| z6MqANzpG?9Qf(s6KkQl%ija6Z-< zHXcE%&~nJ6!GHZ$MZu}5OHN|&3jl1SIOzU{@xq476H4eUMM?2Ne>^SS2#()Pq!37r z??;^N1C9?eb56bjp(kH^2`A8gsc0Df0U=Dm72NSITkirye zg@%)fa+>BzMn|R>Qr?O#ct@YKYCCFXR|xh2lGTJxzu*V~5Uh-cz1aUT2K!Zw))Dzf zQqd#?s}|EvV9YJ82!z?cQp3fpAYx2#XtK}hzbWF^HJw7`03DMahlN`sBEKIP4KL6> zHrk`WhpQjf7mSZ5@nS0$zgU^;4^<>RQxL&0CtjKM9B(i_vXb5<~=o+nhdLBX>T z@1{I^!ie@FDs5jcCSDZHhfc)W`Y*_egJl~HNM7^wMi4feween6Wdeia$9o-f{ z1XLvR9~U6_qA#+qX3q=Te8&!mUHIt_+}=YZjEs+T`X`81PtMJCZ=;CkP^{RWq={ESe+c zbb@$7-(jh3Y`0xSI4_ux zJe&|?xsrW%i3Jr^1o;60s>-8a4Z*o;)p$@DOXHNV@|cPh8p$^uH{p04)thE^EeBqFY>O4Bg-~eR!t{El z*-3Nsih?&h=6Y6>`2Cz;z7fo^0GRmaj;Y!tv=?X5^%;SzzI&6kvzC3%fPYKZz)+sjM8n-BR!804ItO zUYOn11~FKa&xndMrDqR9=n(LLIdcG~SGD__=A9&;pk7%~i>%~CjAoPgNmsrcj*WE- znNI&WXS2+R`ri-2nIZ$aFp9 z4xU&y!+NzkJ`20^?=f|kr<|7ixsp|G)lB210*F)N+$23pz+6Ov#?5G4$HhuJDIqdN z83SI-dxV1v1lmIe6J#UkihEh@5iM~FBS?bA9*nm(vmllyRFj}@ZxpLNIBzUR8rgqy ze>q0-LaDf9X3JkM@U+g1vMv6LUBpc_8!Nj|t1g|^q|%`D7d?e^hWtbUUQ4}ih5rNX zc7KM$$KLd>oQ7+ZG8qgq4^-BmvcwCavo>Fhgwx?=F|1mto8xQj|5Mlj`c{xmF?K4| z#*iGAkcy)B-jf0}OE-L13(N|%Ot{SuBg)cB)18)m+8=(LqwKC!K0$-Bm_?GKI#LWQ z;Hr$|i*DpDCg`!hBs|r=-4Cq=Fnl@=?5x~+@qb?RF78hIs-+Kg854G^q^nrYO!Xdh z+<1Kp@&fd6Z&~c$FuA2$h_-O9xKcPKU>k!vXl8udhkyCaw2_Q(;`G9tK=9#QVJmI@ zK-z)1_d#U@9*e?%Q7+yYYR`CyKtA`wY@=Gakht&uj(Te@Gz{(Ntw|mklr9*iBN_j| z@1rYF7D`-Og?Ym2`wczY`%7VW&Etn-7SDr*XV-Yq)~Xb}0g#y_O8m;SxycWuU%pvE zWeI6IlwXA}bsAl%i-ADOh#*v62!j1KYsTyBpsQZe1#3p0C)t`^7{rr=xw-oH)#BVHbWxflW9KnPx(v<{2+>@}Hc^^A(+rs2uxJRPx9YkBx26EtTqIpf?ZN%Drq9&$tzA7;6}TLDrE!4B>>bqC|GYzc%^jidyGXl{Tvd0uQ3>i zQ|zid@=k@1FQ*PG-{Lp82C;-f#V=_-7XVZ4^13(PI}EFuyQ;!fKD=c**-m*8Ls?RA zHV%a>Jz`S3Zd%&@xNF++d1L;D|%cl}mbfyXTD2TB$c4%apANN^_~5 z;jPbiU*oBSa<`PI<@=RnroE|T2P=Rgvd7qG5p z;n@}c;O)19g~#pDn5Z>`Fh1daV$NnlD*&D@vC^%`j)IL3dDh749i=79*d}OO`k1g> zgGBhaS8xsfDZm4|SnY!6XGs;%$e?vI(S(|zpeTYcx=?lb3n40^S8>9z3H*AhoG%$5#_a6Y){pe~*K z^7{Rb%0iB+X`*2|Tsp6>qan5&1Hc6=`K@!C6@`2LW7P?wvYBR$KlZFYN~_QIs6SGd zb*(3keiClVjW}bhcvqVg%{qs6-V|@b0g5*Q2Ug_?=2KV3ts|P`!dG(Zaw|z}7XN5h zw!6J5Gvi;0q@10PR47}SPe+AhbGI7S8kRs?X7IL_y6*%G24w&4k#>?*+@U+?vi>O- ztmuQ28QM2iW4u=H>|Y-VmQJFm^ZW$ zw)7n&udiETlW{>eEt=kMDE~9?!rhf;fe`A;mqgevU)cWN1204!9bDa9|4+bL@}>#~ z3+Aw*U4BH_fhc{{FVZMtB}_F;@s?Fg()A)U&$FG$DHYEmoi$u7KltrlPtX`HliwHO zv1>DExt9CB2h!*4&%o(Xa?1vxK>tq&T&-Uh!UST-X2=y^Z$x~8CiQ7;<+Lfn(MYm- zyw@BEhm7g|g-sSxLp_ltZ0=xB_M}dab9=@eeJ4INSwFI&%Bxp#PaC#_B%@-9FGs+^ zhH+03l=ClOE-squB?t;0SBq7}Zk12>0~>@g*2t=%KFQZBdC z#IOHqp$d~pQPd*A676v6Kf4s5SC)`+WzPz9jyjm_|EkWX9^doS9a@JBWY22p=Qf+P z60#W#0uhGyl;Pe$F?Q?(G4ju-`jizn2oz&6AU*umXmUf=Tr6BNtwsVyW~`mi-Ux)6 zA@zg5pveS6i$175q%>oTUcLuK6Vj>1A$QAMq+Z?bAAc+Nk{%ln%B9`$iHb(5o+!dx zztL;1PA+yBbm6bALQgAFfs+tm9LzmL@T;TP$467!Lo@#$3uE}R z%gTw!du0c0UpZtrfeDvC&Tn-G@`DPoE7*@iJ&-l|Q-}6bZA{1>gm~i~;z%-$=ZE1v zwWB-If|MiKWeU>Y_l4P(G+_2Z16YC3Z=gbmNty6Fg5O4VhDQ_;4a5U%Ky3RQA-QDT z%wB}g<~H31#Sh~$*^)HwMC|Tc9>dS51a;ER8$H@+l7uJiuSg@y1NG(In9@$ztzC+r z-*-6dC~}ploYe!M{^x3gra^U=gZT0V74pj$?*I4IreN%5?P0EF{(qNT;bC`d&Jq7y%m-F6%Q;9P++tvfXG37jIR& za52j1D~}(>t@h6e|L@T&fHe5SzES)HO?nq2Q+f*!s?7IFAtHUbAxmkL@CY-eyp zgdSW8;D8VWh(F?jP>IAuT*8a&lmwB(L8wIk1`@K!MZXWh4VP`)z)8w-5Dl6Vm=e&$ z4fEveaQ9u4i_T1*DyZ^_vgd1Kuxz@8p~>R&0CiF_WA7PVq%{}g##gntMAco^+#328 zIaq6Dx!gTb`j@0uu?q?jKLqK>zT2R;(ZIN3SR12MT8C(yqNkML6;@P_dmGO(ZGyvi z(YfS}A8{-8;B>4R9%o9BUHp=>+5U($HQA}GsJ2lubf~Od72EV{>z1Wos_`dtmnf7| zMPW)x?7nY~YlIJk9z+HF@MKDTIE%B8hxg^p=lhrE)mG>XQ!-DYvo}*ND$;O1A-Jwl zip$9$)V!l@5G%6RJj}xyq{5Zr>Q2T<%f4JMO)z$FH&G_DF5RChbI+=_)|Wn^88mxL zLx%M11;gMeRi>knV(|$tFW1&)K8KrqK(4Za(N^9@s@l;|9g{uyA~@`ft24$#a3JZf z&qrgWD<0)CVJ_HlvKB}~Bh0rK2F}ZPcu=f{7sktK$5^#rWqThs{@O%qj9H4j> z4#qCA5u3Ka*@|8HJ-Gd27}0-RE`=i<$gyoVWH`zhUh_COpLc=x1ruFn<&vFK=>G_0 z*3XsVNo0^3!KJcth#&3*?)m9`jDa=njJgocT zBQo336zlnoA|sfp7}U(PIz5`RF0@hq9Xg0(0;J8|6liA8RjNH3Bya1&fRE=#KB|w! zQSU2cw9CoDYfMe+#B1WjWI0aO@RyGVkB+IrEa`Gk0#-ESskWwPl*W1k5~pIRs+@oS zl&D9vz2O<#<33qySc&Q)5k;kWr7A zrDTv&Y?aFzI?O8D6| zzmAww+=0^~ufg$eTDVg+`ofctHbO(RFIN=^utnT@_kyQ>)aUR|M?9+;R|rcmCun(S zS*2EQ+@Y?mP$6EMg_g{FvkhMTg(`yKi#d8KG^uK16v;Q=${zQVWB^4fjMjo7)?-2| zlAs1frAa|?fmg&>vCP$@V`D=Sa5yo^D?bJ}R?ZVosoZ<_qzY2b-Xp1FIrf?>ieA6l` zh$xnoi3TT*4*rE14Q-FOSdpi$m&^E%6fVSG_Z8=@(F_oNCc9a|0(}NPSyv)|D(*Q!>Ab$q{RI z=@c;b{VLPo-|@VY0#$(R^uX1IBsIDR@onAv2tCoZ>-+?HY1gb0vB4 ze68q^XwpgG#b25qzXiwkXwW1`7~nNUh~g11RLqFj{f$D2+}$gLDFEjdj|@MeY&NIo zhX=)&a>M7qAFJM>@Q;GzlKhx)b1=Oe!j3q-N_t#j`Bi~{Kh`DAJ~;g4AUR9!*m*bN zZi^mM;FUIL;ujTcPC946I$XqJBO~Y{iMy8@TuP8riW>lva{%I}8}(AS{;b-+6ZbOseZ=9V z(R+KC*x!7}F*?k+#ZpE7QYkK*v;8u5;EQbMvzNZyu)F7>FJQVhRJGrp(#+D4_BIed z{itPj#qBzsl|`Z7aMKsij4fox>EF5vm{i?7&0cPE_j&G#G^mtx@48t~pMU9U2Timt zZ=8sKjzy2A;imp!GjVX=XDcNwsb=E7HJ)vjkH3s*XES%pI_Vij2^eqxsAIuZw5)D? zb2?9L(-4izj%;t&7grTOQ6$WK$UZ$jzPHE?9*RL(4&4g$QOdnGo!1pGdbjJ!U+(oS z(Yx8Gh;F+d4`?}#-o}8*@_yK=$WW=3LVy? z3_s!v1dPavl5VvhCGQ`kx_>BMb8R0kdRub-S*ER7Ou=c?0O35|X*@HFe8($@Sd;CC>8B{<)?-xSWsht|FqTPk>-?sdUn z+4VNW)7r@6y^+x#n7(k-cule*G<6@Xo-^d|+$e-WFL4Z_oKT~@(aX1xord5i;5Es|6Fp;{+Ggb(kSfc$2GA;az*%gr^f?vD~AOneFdI z`i=-Hm$1Tjn!$g4y-|fe=O~yzXepf94TuJWYTOX$kK#$5-i2TK35CxmqYz?H;0sFm zv;>lf*Qj4hzIjpXeJ*P3eDew}L?*5NnX4efWxg0+fa(6>RiB+F#3I_W&HRx%1^M|Q z3mNd|sM8SdYuCCTgwVw83gZvR?GBlq?)ogTAw@!p9bim%@_qUJ?9nB)@aG#O#G_G1 zc}S0t2^NTc$&z@y##ggPGA#geyyhk`Fy#dN%nK4uxut%+^?$HbEXmyx-%&M0b3&i* z-csJd;r>c6`Ba_{`I(CX-H~;DQ2jOFh5_<$H+h^F{;k~e?nQ`@1~k3-V~76XmZ8cL z@yy!tMbK{fBN6gYY}81g+p@1X=4$Fg`)n^4jh-s%?95`Q#)bjpxLuNZtKZs_>z93P zcO{?~PwXPlZ22zf{C3`@*#qD4MW;8Q%s=NuOX1An`=^liskY+1smTj@&f5}e09)#7 zKL(`1l1>o{t3Ou`N%!!Lr#RdjmNcZnqz`soPG>6-0GC>p8~Jk#qjrr-Y}WJhc?CMu zu~KfeZ1@rAa}pT;tFliFZ_F7TV9*1zsx5uTda8nUpZ?1YD6n`kJO~O$HbU==MmIT=hOkoAc9bj1r@Y{Z@Vttq3oM4x*>9F<=W`AFRMHDK(?pXWBj!+UY;Nj6$` zo1eXd=vszbX&^OTbGaX;Wji7?UT<*##JcYlzc6^FB-uW)AHVwH4+AYX;x|X2i7a?j z0bA|QccwM*x_Aez)N|t=Ph#bvd@cwQ0#xR))F-@R>bRPOO^|hxLA-6_+1pA%a*;RW+a~8-7v4hc4HA_)K0;rUZ_A=7?5eEINpk% z&!^&wFjTtgYN5M(!^#lpZJnMnal4mmTt{_Sv_5C&stx<&@-0-W%K8L=-HYoe?Kz>u z%Fy7-N^f?X2Jn#W-S7BXnO#?xp58p_9qGMWpcE3e?17*3gK`nxEmMX4SjTili5#eCtJI6vl7%K(0>-9C`Is#zO-6SW!EWj#RLegbanirz`jzom6dMV0WE6NY#f3G;5uA7S#OnOpVBDz6rxtHF@ma|$=s`({VAVF zzz4rn#ZT*u?M1^R`Zw{scFom7+8GK$&!~=$#~arpaMR+O^k*{X=pRaoV||;34c7p4 zS6IbgPx0f>ifel}RT{D|6$&EaUw`T<3|x-e)X_kD<9db&mzQH_PG+Pcq?9J+Lwn#G z<#7}rX|Z9|;=;Xb83=ggq!vA13d*5-K#>|xkNZMTyZhR|^98Z;?{@%*rns|QzQ=Xn5NkSI*8yK`DefA7a^ z(8krUvISt)e#&8%u{o=t!|xrxQ%S&UV>XkY64wn|7%8ILPKw=X6>z=GQ{%J~Mf6Am zuw_4<<6mcf0sb)kg1G5esb*gaY4LiBC{=)iRXu;|+|>86u)&Kvi^zje8;5~bvG+!P z_2$*YjA2Bh_{4CiNDJ)y=b0hVJGt{#xi%clo#d?_{%-4V`W&7cuaptuU2H*;mXRuc z4?@{jm;?OGCfK=)A8Wxlv>RHaY=<@;im95# zQjA;F!Tr89Tt7HE;Bzs~A8G3qqn}Q}wQX5u=Rk@G?W#w&PEe%%x=*Qs?~hec zj55_cq0E}s(4ectQ`beoEI65CG1fE@j4V-SF_(c4V1tNFtU#3^%`gKD8wZJ}8UFrx ze9z4!xsxYE6R=Be1!L19{f$(f{4#LGsvLx(X{^R4C=SOI!2mmgZcsRhNkFYKi<82m zWcOQuLulSP$9Y(nQ;i%qU!7cYhn`yWDf2f~)12DSE!|XNZe-$)VVXfJ37_KZ61JT& zzyt|DkN-@FRZ?x#Og5;KWDz-#%9P%V&Y*j7_X77r+v*9Mk~8-MAHMB3DphmR2oIZ) z&3I1luQ8DBmE}k~BJNy)Qh2I*f@eCb&YiSGbnNKqrk5(0lUyTNYWW0X?csV4l6I}k zbm(exk~kZ?xd(P(!wumBA_ZOaQ2*+~mt?GgB(-l395OaGyc1N`OqfbDpEnMM_az6VF7_X0<65!YR>OYSj`0$hTVUfZ{) zmxj!_C|eU=#nL<14wh-V?_x4f&**|OefZ>lp76Qkz*uxa;l9UY5FN$aPx!$0P-05p z9=TskXrOpsCdC^9ypVDq${&y_`I{5GkbYl$3TPGmLjvBg&x?NvDH&vrE~wX+D(m&U zbu9zWwB4>x0o0X!YC;!O>C=>Y;zaL~>1#;_HKBhX!y8fo*QK9)-~&rT9TPwo6dk&K zo(Z5*3cs#U#}p7DMTg5=bm~>Agv?Vox!>Q=<-zLE)T_Gh6mMGa+nRmTe?U+aepK*6 za(#*^AQp6kt`^f2ki~!8OO<}2K@W%w&1D3(OFh}a8v9uqFwFh5lg!5B6Uly-TA{ zhyi#;{`LjlkO`P7^8^D=%mCa(|KNlV)af%M17=cmh=SeqxrU-}D+(nh2NsgQ8NqMs z_n{<$B;W(9L$Bz72bF426mRb60coLuVtvC>PiGVz+I>{APm$;!Fz`a+eensPd5SkF z_*@2{J-VP_9~iPLc?bU|O%jNu{$r4eY*Vu@X0Q|M^RHlN*+t?yzi9VcPnp*XL2&o) z92O9gaU1)>%1)4CZYSKHeb^9huqSDZYS|ENa0|Fy7;5^e32w`WlD~FGGb`ldjl%^% z8E5fwV57Z}_LVu93ieKu#HbbzoqQFFV^&DSqe6dU?&IdLiTUva5$b$8&z-R24Y#*Y zGAmV!WSlj}E`i36VVqUZPW!c#EJihcXxE5 zM~JRaaBCULMDYs$K?Dp03lodCQmuXxhjxptfTcTdfCgY`KD0}DFo6Xe2TRkTb!CC2 z^h004hP#76SYQSwQa=i?eKxp9u%-Y4U;wxeg=`}i%m)!#L;4Dz6AoGg_i={8f`z8V zxHHbFxCw!_BOh#PpKvJTukZ>IUZ`LV+@Y|4z}SSn;J}1aXbo5$Q4B~44Ce#RP!bFW zA9ywz5bR6B9|MNN*2e`_*COu4y{hO$-A4xY?$ZxtClPE(h>Sl9Y~43h60DC{{7Itz zlc^#w)D+C}NJ=0JMuP!l0rTmi#gVA_ z|3dl?fg-^j26kVluO$h5xg?%A!E8iuia%cAFJnL#V5RnGT_Ip~n80!{5!m$&lnrjd zkYfJ}=?Xldf>BPitDoV+Wbrr_nghCy_*l2Qw7zAfalfNk@BgT<%LD~uHQcVRjQ$}w zIowtD57MY>;YyA3xnLlRVI$ep!vh9iMHc%Xikf)1^L+`Uc(7%5v_@u2Rk%)be5&uU zI>wDZut#FyYxn>1T$l6jHRulM3E{cfv63t&wC0DZ>D8N;Zc2V>8b#^Ppyh4~%-Y8< z@|jC;@_ZuC0zdXl6`|rRi9^O{ewun?M^d1`H#G1)jT*xadHaJlde`CJs5XTJ^#0Rl(BxY>sd;nats1m83R(HeKV=d zFZ)w=gBHM$8{S1ZOLi|y{Rsj|NI^?l3qhn?`c#@eje{$|Sf3lNhP9=fgHOIR+A zrM7WlK`&C2Ia7BYQ62s?mv5L=09J{Qa5%l|gwjm`z%#KA6ZkicAMaR($KcI>M4e{x zFsAdc7IWlM5B-3ZkjW!l@4#I8`mY#PW=3z^-p<*TZ_4lROKT!yo36lQYI}5QZp5f6 z*zg5mhNWQAdkdUULvO67?-ljPEXh$N|1620uufB@dgF5o;dKM4FcR2i)k8A{)Nub< z54`8^2qONiTj2aHzu19M9EQ4}*yIAQZe7kpK&XN%?zd=hWO@0v-9$|*$dkbCA?~Ja z9~$|&OWVI&yuTjt@hzcu;frAnnjs51K4(}$9^RvzRnxCfCptR~f>dSy!nI=2!ibLF z4h!vpL3sI&@)pLhFl@LlZKzH%pxy$Rl@oG%W7y5K8Z>Oo>5U1R0%e zF^a`zj?oT~8MJkSa~!O>e}dv@y`7AVGZD^}o*xy(%xRq=bF#6rZLJj!TAF@vhnr6N zYLnK8@KsxPcyn{v*lcs~VT7va3=NF|9xHHwn0500=N>C=b_oKUvJQE>obn-JSx6DO zrc9WvjwcSypPe_FUTyFR20x;T$;ZVtw>-X$oO%Q;<3`?uJ<6BS4Mlr5J_~jS633#y zt#a!>C`BtKiZ47PoL0;)TPDxHZij~lOR{9xD0k9*$`k#2^)1=0;QXnjhy@oj8<;17 zv{-V5$vhZ)_uD=03jK$Sei#yIlIn|$psRtecap1YRYQ9AWB=8D8mFBE27A`Uj8k(w zvpq9Cu7m?uG6~R`deppvm1!f6gGU`FWubvv6&WBGZbB0}VxHUzlSlpa0cx`B823B{ zQMPiyqZPDYi;58a(twH09pu5dF8`BeDkq<^H)`-sePKV{5Usr`h_#fX6`Rc6PFx!2 zZ$oLlb|Wu|-xUu1wV5+e+T6i0L0J4RGNE@a=52X*IZI%%Owi`fQRZ`)R@5QYlNt(r=t_-<-O-aV<|TzXcQ{IQ+7h&*OgiHKUV1b?KeNtK8kd8~fye z&uMas#7VP}MD_9eB|&n@N8sk2Nlg}Mk)>LMdAaF(^tM|Mfk6=h(QCtSL#xdt3At#> zxAI4I_g3{K^ha}zq1(4Q zp|bk23g@bt(=~#idH#nT9f{pCuc}67wltkM$H6a*21p=mOfMeB!$hSa!2JI;rP2+ zcO5^w(yYRFI>Ec&P(-rqm&DeWr zy-^{`dphUqrt^)xle7+ny(^v2(0gXC2SrfN0tml)Z<=`@<}PyXz?(|8q!Q}CHaNK{ zx-{l7rz#*W$McMq*0JP;Yz{CIWW8djKWIHNb=S%Seo(9NzC;@ob6qB@z3fn(2WI_E2EqeAo(BF@wOfcc^cZQ~d&qvKc+ zECD;J(f`5=Jcb4)iL%hQF@CKsDeT2l<&kvep>BkH z!Uz>HP7)ytum~f1O2=~fAi-=qvg{P88UHovK7rP!6MIV z?8oTQ=Mir`w+|<`roNf#IVkk`pwZ|&q|$hw|08nmE_9+E zpQ7%WqoV%!R#Xu{C?73ndmnVpBOcVzOm*N4cjPPjq^z_lUX4+3s1Lf;@n?SIk3?7- zZmUtkBIrTzxK#%EuaaF7t3zMSVd_aJpFcD|SOyi&QNE?yq_+BIkvq7;AmY%_iK8`^ zNWCT=vSx=KGpoDJQ%8W3NoNf2knW_l#`KiOh@n+zuDBvq#*B}tHH*-?pUe#1$DnLs z(;|T(iQ&7963*fx8~F9yvVXMb?GUikU$2PEZH8MFb4;e+Z#qF6nx!kQBsY0VH`Hl{ z+Vn*VDaCkNw6&gC7Y-4=09ueZ_ERmTlGHr$Vb^LO3$lbx+#j(YL%fn36gr(fexk?Mn}?yg?|_JMwnsZ zAIaZ%!%+Vlcr@AKIa;e5lr=STVMejO$eZ2Ym#FQX-VAPP4`*8HbrKtLMmA(hk7lR( ztoPy>xGikfaERHaqeUf|d1CRVp?q(W4|44iz;wfa8Q()=Z8P^jwDsz^#e)CR3lt1{ zI4Ye!AlXuqw{XX+>#JlY(-7ghZ00Rx3KL(H7W378!ULFsZLs1o_GfIsWQJ(Jf)8O- z1Hfi9zpUSsQ#yRROVj;{GL%4P5?Q_cXmp_o@1D=V=FS?@ig*rFk&*Bs;E24vahDG` zmrS)N4}NeiX83hVE}JmC}3E3&VyFbe_SOW(9n{>jiSl6}1EUW^k@G}=<>wM5EGeo^)UNtqdmx0lJem95D-PoZkX1e6 zvJ45XvPj$eWQI^f+G!U4oGo6oN+Ho?v1;AMnNoeQ9}h1}y_lQv;PB3-i@caYO?=N# zgy+3kPCd^a*Fd$rpk%CoGo(1y)?B$_yi%+mgE8Ej^e(P;Uw>xIe2s(z=%JObXq&LH zb@DHTQRZC)#H= zf4(R6oeEe@Ro=F{*DWy)!rUy^*P1CrHT|S&OGgO$oLtQ%o%&9OxEd0bMMO zMEaqM9Esb<&K2(pjJ5gn%z70XaTX_S!e|jR*6KZd)rl*mjXA{Q6}OA(3pVD!h!g(^ zh>>7$t?lhgZ_M@-C7BxB!c;T2o^w{BpCPyw$v2OAW#qE8=AmqqQ)#NAU^oj)VKZa! z%~EBLLm-NX-iE@8T!jTCR4&dBTY*qt-asAf8w^WP8H)KbWNCfGofre2DR<% z^bfrk;F)43Hr8T;;_mE~M=>4bcrTl?+h=SPHO`Jm`P;Yij98WDv6N;QT)^7dx+~2y zi>k3Z+vwoKRgC)a0>0B_-t2%jPPIGuRe!tOX3hF~4?CK;#o>DXN|*eK4qFJy`kD=N zg(Fni$n)a^+w{N+;V2(QJ3d*`=|7ygdl1+{nelc0IAss|V-Mm_E1o2pNxFe@O^zLS zvazzx*Q%{z&U#8}S|!{CQ3$EDan0gk6wK7Ir9j`1h${pGNaMowFDj6skF}24)vw*= zO+>|F9OtC6)_0pB`4boTsWO6zIdX94}0H-tM#iG4o z^*=B34j|{*j6SIjk^o@q+Nv*s>87)d@Lp?PuOM{i4;;*VEVo>Z8SEJKdFi920!6YP zj;gI{OG}E^TE8?3*VtETosNJpulqZs^)cE)+Ss8^M}XWjj5vX9G0g%@krBz*2Z>T!0$D987L_bQ3pGY>@_Q zzXwJvfeV|cZ){AlWKroh@iXrSi2gw$LT_NURHaPic!y)y8N?Nt=l0ZxT7MYS>}#Gx zdTEtPw!OOUw<(fHPNa=aa>kf-OA6NbhH43{F=B9FZ`G&ic6erkoJMaUK;j5r02Jtz z7)Im!1c-%WhiB_PWIN?tsvk967R+k9y&A8rw4bB4?Y!@TH|hW#5v}M2R&4)>H#f^| zdQ1nyu%h;CQcwJAX$pnu8+u}R0S4>-g%3DX12C@Q8nNhMu7e0h8;zQ4+*6-PeWTQe z&m5QE-B92i7xNIjgNC9uO{!KDo1zxj6Is=JBNT}GRS#$h`t(aSEl#7I(dzalf0^)Rt-11 zJ@Kc+qDPd)4O4yEjStJka7p{vCp&hFN9WuwhqXP2bb_aPBk}YT|AL% za$K_I+O7s;a2YeTx)U#Eu8whp{-Un-N7S^x59tdH6^g_f>hb~;vXJjlG`g{@mSYH( zD&7V2Um-e0($^vE7*#JF)%CRgO;|HL;0%~`4m4JmIpND85ryU5#!d<$o7g!pF>b`& z_Pur;O5FeKv{G9U8if*eNx_UY45U$%662;KD02D-ZEr)9)e_QJY-kH4ApQ2;TMCPr zMs1>>Co3_x0y>`BRycyOG1XrVJjjQTRQwQ z11(qCmOFG)E4ExXYIBHIeDk2M)(X|Q?u==nul5)h51<*tOz7z*L8|<$FrPn!HBs_g z6wseXW~KAfz1gTDH0*vz_`=CVp{lL=6j`-&^s;8*eYXGJ4Z90lA2q5Zjyd@`#R-0h za=@IBK~+sW4xfmSL_u*R&>y+{!xj=a7#98)aPnQ%mC?PpYRAWyN%dycnHq2+5yehI zW0}OkI*LsW_-a!V1vwKnZ#e*-CbWB+{IT!Ix~s>QM)X#5ggHqQm(A z3;X+TBh;s<5T$>s)63UmX3whjagwR=k0t$6O!^c7Am zB);FOaBB*qv9yXa8$n-7OK{+xpo(fI8q$ye_zS6$(;izlyA4Bi`lzv@8lhkPVu?t~ z8NrwHJGGU&fz8@Pc_bQ>IAiH*I!ii0%rh^e=AfrrKX)-x^0a571?31 z3z6qeTHL8=c{tQpga1gHQ#d6oRq2p!6EPGl@o%?W+`F;xLg@VV;-% z+4K1AJ^<_5A-JWBqivnE`7Ws0ZrY)Ra+l5TWum9PfeMK=#n!)iIA<=AVJ{e+5xpyj zIS5qPcz}Ya@w`j?R>7P1JJ67NkXnYNN_Q!`>tfS|y?#<-qaLa-r{1`R-~{-Xnyrwyr>J7_+J1@O_YDzo<~cpT3nG@xaD#Ae zaq-KIaoICnHT#lUP8PwnG;{m5^TJWioSF&;M?3M%?!s-LK{nNph_<15^P zOWd0Je4X2TNPy)&e3yi`Ckbx+4Yu+G*tQf zOipc4SbKz&tghP(aOji$c0zu>3hH3hZv_oo-}v0BULnxGZp0}GiD<8iEJfE>ZRMV7 z9$j4m7oX33S2LP&;cUkqUlvq zR~DErluq8J#&^xVt2w-3)((r+E%yE?WpoTvbK};8OP9MUb~EhsA;R5a9meRm$pZlF z{9iZBkqd2GEA^zq2fPvi(GD`Z+KIi9-9Z=4i{-wUP~HqZgnd(dKQzX~tG<_xy>^on zq6I20`xD+;@WHUozmD9+7}>OmnzZ@i{Np%1*;;}&3VNNMZnY5gh|I8mliPku*`%p+ zdF9Jf8@qBq6 zq+&N}(fn4gB0LhH3rB<-7_NKK9YsejSUQL=$WuDM3zciNmjy)g3)J9c(a?Wld1`a{ zQ){t!k;LKe>7(DOIGat}qIpeB)AnaqBhO9h4-(7oN%yUsQ)Bu)Q)P(`y`hJAVLJ>sXY-QhB{^+ylA^E z27bX;u@GDi(ORP)5xmkx-}K0xXNWxB+!B4qFVaO9@Dg?jBQWbE3CN_B(j*#+V2ISZ z*>%5E$SvD5WQY&UJ#MeJ||Lt3C@$>*Moda?m zinCB#CWlwOgjKCki$RDE&sT@la$P)Vf%e~1wIYE5?=zUv6Wr$%K9Qa6w?f@SG|@M| zBw};tcZ5x)_AnM60s1spD%&kVFM=%_k3bmvYBvXe+iK4Yo&^C*oc4nc8(<1<`<;Wg zq=pH1b4;bURE6c?rKVs>_1Zt?)^N~?cbKtsh9uJAt>8h5L4~!oqYf8Z)N|THiTJ>) zgADO&n#5eX3Q~U+$($r@8wz!~6rkTA-^=G;(HMT~FsOMqKnWiOB`ifvk&9FL@ zJ+_bOw>x!bzL^QR8t>#kvL+rahuCI9<8C!nx?&7bkghalKbh~;KO-*meJg#_KFw?X zwSOVoKQDY$-dyA&P0dFeu_&YuC}?E;H3_#b5}1Y${U(sdwiyZ74@~_XkGj-dX4E-O zSNxiMcr-L=9GA)(=53BKig7F2PQQ2c`!X%@ab@dGHXPR2EZ)}G`+cZaE+0Z@XIfS+ zR@XBUpT#R^&di?3@bda=>juR*8bhO72|ncFY0w#{pIKSf?jgC=vq6gJaM5h;`1vXa@_ zCw8mI1pxZNr}oF7W|la+?LA(h!Dhd3UaE-%3g^zZsVh$nke9u_7;It#2_ANrEDhAC zlq{vI1Y|8YN4OB((;VRevfQe(UTofH%QHCx4L7DFOW`Y4BI!NS;#a7(?fB%+`)p2* z7cN?0UNWZ`Ontv)>uPW?VQj7Swsjg(xaro3ZUd@w=uc8wCVk!7kPVahwhQNBg>{Nm zLk}CJllBMIUk0^XE;_hvYiL)(u- zNBFNAo{LjA%SGsC(nnTr%So0#ma!hz#+>};$=pXf^@r{>@K{YVgvoBvhWU8*WLbS~ zmL~h3Uz5CkO3V!pFJYs4SE1DJ(bCe+mhsY3kH@|Bm5x#__*-m;`EUuQ)s9i!1tY?# z(ozhko_zIyYLKN+UX32v8_zqocenYUPafNIvyHea(oIeUG{<*&Ovm^1!FJ-OGsMWL z!G3BQLaA`9=*XnzKbfOl<`@(mo~nSal=2k2;*mlkEy7@CFI?7A|+OU z^5pav%|hDQ5v@lmW*KA0MMJY1%)AM8Luv}i+NQL-ZpGhuG=3n(xY+(pz{7Zl#mm0j zO#;>%f3)$*V=;T17CD{C%@p1E0GCWwqlEEU0**5j=LPEDZtQpsH;p`!PoriI|2Ab_ zKT>SaarrDPBLIVp6)4@V2K87fRUPd&r4mhOnKd1F+v$n`3u9jA>`E(P- z`1(HOIP5Ex%MV$B`Uwnr-yvE0$G`| zxkU_2%e|;dFGKU(fItK6DAabtdpM!mJFF3nEJX{)djSdBNi?cB5x#`Nzjm zrTjMan+F=b@?hm1)+w~i?8=$ojg;f)gC(pVii9R32J(nh62T072`hEe3GFOkmbIb% zcq+6*CjO!R_%&IKKxD1G?LDC~Y&Vx!nOY-KsjA?;_WllGj|(;WyAOX6&$sEF8cMUD zaAJN)`7zyXJA~&^iVB$FiAeBM7mFqO%*^MUbB*qv&gyV+v6rY-`b>J}d6v<91pI^! zmo0=|?%&H4W=Ij@hcbLuBr&-RO%xd%x<+c#xO&^7G%Yfd$}n9eI%f>ea5plSuirg2 zRWwPe;ANi3(FMhf8)RoWs}xnNG|{)p zSN4%-XJ@^0AeKV{+y+bj{9qnrruSN;U|dZbuk061rp#ICplnN2Zv(##UqPyT{U^cV zoTt5k_QaBC(%+!jA@svx=jR(c#oVt?%>vGyRJ9T3A-+A)iBpc8B$zOR!tKGUX|A$9 z6aSY@fyk-7LzQvsw1?wYx`u5UdND!DyH_H2KfTd@p=0&ua=0t;y&@3NTacvhs~(4% zz@gmT8m)r0?XlM%DpDP3R4!8_6eQ-KP?fBy9>v>}Av>|X+;AvZiTqzP)vUeBU?==I z$MzT+8b!-M8!4F_)3Jt%RDGL?RbHl^*Aj=2P|0Ialx@RyB$mB6)@m7lNtE)!%#76jQyW3d(=y6_a9=nH9j7QwgML1B zcOy8tU*MLn8HYM?505vX=u_o?M#{tacoQqCnSLmHK}x(UOubX?HV(SOC%bzU5T19O zg@w3VU-?lR(62LBBd_$HbDVbqdrLuOgM%T}o(le~cdli73H|cu46(wQPx7!2v3b0D zXj|jJ=gbd2{E6@z9-3|okTJvj0(-R9PRye#oeVZ zgx`Z|dyin|N>XrkFl}pbwqD^=1>Q8Tf8#n|N~5n;Rf+!cqmJ9k-;}!(0<~OW1AiwO z?1HMsbsRE8^pcS?9ly%V|_Q*U+VI!s72^xDGGXjY%gz%HbeW7#~z%kuja!sGDBt0H9 zJ-~S*$OhBU6tV_gqKeRKww5NUlh*+UL=m%qMC1MYx)BY%pdKBMbpra5R zvBsd3U}M+Ge6zFqe&PEIOVRrROUA=x3#3(Gwu0}~M5|tApVgnegS7iX(uPdKW*tn~xJi!y91*&`Fdc~Xk{W0`> z*M4g0BT0?tCBNj{2Yd(ei>r3!c|q2MhjL?|3tcU7M8xJO5M8^@-_0Ec-%)%urlwf8 zDB*9iG_@OsH8)<3YPIbN9XXz59B;nd$1T^{>CCtNW|?ANq@w2W~b>cDP|vq}E4ewp@>q%35-mJ+#AyB4puB|6z)bDzg}dHE%SQYdp$ zTgL7nts5%twHcD#a2l4=aOy~4so!boQCP2p(Ktsnonoo8xpV^}59g$h5_}Z{)Ab5fwPY>@) zyOYYO`cU;b5U?!uQiJYHL2F!FsFt6KHI-&E^&1a0E)n0sJEGK*aUH0pNv{$!e`2vw zrJlscd_u6(2YcG#tY=Ug1lH)hG zH#xeW)*| z#jr@QyT4}Z<;*D^VXe2C!Rb|Z$-&K%f(B*UG3~mU+>S9y3C5YAiwM~19Z&PZZBaoi zC^J0bacf`oV9s>%g(~Lh4)$ z;h~80;oaV}cAKrnNS+Uj3nXk=jI+g>&I!xPAv^ogC6u~M!VwL}WSPDt%CEWOkKD#YLtDf5;@T6mRs;Xwk|Fe}?eGKqvNwfGGfuWGXW1)(5vg+X ziZm^ub>g_{GlWxo&QtJVU{e!6fhmCt%e=?y+a5!vxt{1-~1oU!R_#_N_*RaMa~fky@3e>)hfPJ44Yn5sjQ;GS>N_0dY? znfconyNIS&R(vUv@TZi)bW6+ecN4P&I?iUAUO6V~v<(MuPHzgjoiCZ^H>r*&6OKQ; z@iQu4N?t`efgu|eQFl^FZkws?Rr;>l#L)Dxt0*x|ig1X)dH7`y50p`T$RjHzGn+?5 zJI5ydOd|HIEbI9C_SE8e5}%tO{^95Zmg3F)yDLO_#@i%KEJGK|p!j4ag%cdjdADTl zL6!N1cMNi}CoBq;`V@-u2=6M?u2Q)1>DJ%S{=iD66(Q1`Ki}7Z_$RVT%W1TNE#+u< z=8kp5 zxVn&knX)iuv!wTQ%b0x;8SqHHD%OGu4=qG+?zQSWbuzfFfzgjQ-s{UnRgq~s;XI9+ z;G^GIgm(ANa_gH1W=Ls}%rL!q!dS4fVJtAy8yC@P_DOd&O~w3bPpQQhxZ%?# zsIS(Ul;U#Xm>%VG#BE%``-9;}smSH;5bM0M)kex(xJzyrU-;ajOS0fYe&Nj>1X0zo zMJmFFjfQI%>(-Z_4Zen_FD_Vy%d0Qd;Pxe9uTIg+#)m1R_PUR|qLI`EJ>3*rf_a{& zCT-ayVOTWohd<(x@96>sVFB5Aa%L`nqLvGbfIt?#b?v2sxRG=M;<@Y*wFc zsyBah&V-rKE7h1CF?i`vXw@q7_-&TGCOkX3HJXFO>eoEDX!*q)&$87VgYt1oCDESy zf9onb7x19_iL=_+wt4%!QC`a}zw4+pCf%#_cTCl$n#k%j0Arv%-*tl?cb!%5UbOHB zy^A0VE<;!cg&?+x}c!>=~IkAaE@63TKay@d>HP4 znxs)giH;P5#-6&7A)=`l6SybInHJwTU+-96j|E<(Dy?<{A@PNHv@)AvkFkF3YU1Y@ zSPZ66ACZ23m}4WL90!!fUTvUf(Jhry2_8p%xx(PM)XeB&3-_mutX{6IIQP|~`h;C@ zS>^QDadG;|HmNlEQ)g_E$DYP&+~i7FYf;`oJW0Fe*ToW*(>j?Cqe~=hHiWF}gWl=h z`R8vI*F*`6%Z_THbN`lt2tU$QX2G_0Gg~J~<5#sL<{Fji#}j%XZ8j->_h-OwjXdY! znQbaXJSmc+KFLjEy#X^1U_U7Bf3}{-?Vm2#e=apoJX9Y@y@m+`d(V5E`6`!!UKmU> zeTH_y!=ss}7(&q}Po!MCD0Lj>Yp!`_=8+VH!xmyCd{!mGa_ukB!(I~>=Hsxx;osvB z5>e<$Tp(m8ryf#bCZ--%sdcvtJMyM|>4?FWOxkye5*KK4M9joQkyHCUu8PjzK8RSQ}S#*0ThWpo7Hs-t@@ zP@Y<3C$Ak7_>(Fl(L9*$mv-!%{qZsE`W&h*hPS$Tx2+9`xyMIDZd9>GUuYA9>x#o^YbUS zyuJLT9e285Y#IEVi?Eo41}wITvwq%IZSPh15o)PO0i-XHob%9ayI9Mgtum1=u#|~V zy-2a*p}pUaa+T_Qw2}??%ZNl0qc2N3{+S=v$?2;^ign7lTNsbsiC}ZNobz^Rkj_l5lOEqpVA>LsFDyQywE%{vo5fhhxjB7Z*3THtg5z6ee_$p40p~7 zeS=4fK#Q25hmC|1vNO#nos&G)(~5i5J{JC&%`B+L=q?})g`25>JYIni2dAb3O!VGw zdT6dbbUHjkLNOHEoDy#HB94dghdlC44np_1c%lF5s57T^#3O(T2RGa(L7Ae_*6(wq zr(`kPQjDv)2$+li5b2TfHhba=M9wjEi@ZeY3X*?$lH3yL^@pZeelBt3xb4^_m+aXiL=~z#l$`are6jcArJPg zx|kIsvf{D{D@Jn?Ci$z<>;QJ8)<}z%Mho3(^EJs9nRgQ}Dd8MWNLdfG2hzfElf<6F zt+jab7Qn{|Gp!0~JiueRy;VgghlesZma3bwK>*6(Ni!?v>F@bvDrdiMzZ6pTgm-+r z?gG5Fzqo-He+rqGU7Y~7#}H8$um-c>c0iccw!B*K>vTcS=?fBmp3^0wy!ZGIS%~U> zQjsJ?SA0=(-*?DgO zxbr+y4sRZ2ZAALWIGS1mQb?-ADA)&eomLcs)qkz47HanitFnpfNkrgR`*kXc(iv-D zA(>chZ+t9ds+hHc75uKG;fF6{uV2utE1Y_l)OdDOWFO(l#2VlK6U4k0+e8O4AW*W( zcEd(Xq4&Rt6wH=#PGVPs7Yp(6@oU|!Yt8O=%0t`s$NK7n`PGNy>&qGTdCU7&`uD9P z60K~zr@k_%59e=sW7?hgP6iAECd?L{*jVsK)+G|ZFfuomM)Wyi&Dk<$(&!$h*6c3f zPPW6uJT10yTWxdyXfFqt+3eaZmS6k?8tlBM+#o* zm5YM#k=hX7w;-+(fE;<9j_;u7&4&WfxuZ}FSf3NmmM3{Jj@({0iR3dY{8=~K#`NpuQ?r5p z!aj?RTQ#A6F_(;@St>CcGHE^yUjLig9$r^KQ>#GW=DN5Lrw?&GbOv-3FYrAqs(mcKzY)zr-2t-<|-=$PiQ)v|@v`gl$NH0>t zAJS~=q*h&M5ofxkHvkzt5~;VJ5*UvqloGuID~uj>0kC@)nBEsy2#{apA7k>^GNaWq zE?6~HY&KN!+|d;DvF&mzxDu^Jc}~nWm)R&s6U)jIv)+0QMQTy36S&*$_|-BZHm<## zKCWKeAb{+}*ZOgLiadyW)T73SM#ud$i$NZobuNWJb`L(v*E~~J!RaueoiU?L&3_He zy0aErg$NOjpzPQw7T=1BVYn5mEDN!9UqXOSMWT(_N*7?o_xm}vvTZ5Zo&qa}# zHYf?)-~Jd9QtH6Xd5oG;qr084B~dLe_9?D@!LL6@L(^J6wE1OiS>9oq6HJ$YMSVsQ zccImRdb$Xx*>5z))Fm2SHga%rkW+sj`&4N)&iQH?yWI8kth7|y#?n95HAnZFD>O{;+%u>q^G`z;Hj~Uw>N;#lAm zq8~7$1*2egaIj7Aqq%%`P05;faf!JXeltDVpvOXdpDkR)F_M{5c1hnVEY8C;buubH z@lEJ6!LM>r0qw)-ag`kV@Av^^_{>hl3h!!WVWW5!kPiZX`jDl<3Z?Ox0zEa>EVOc} zVxABhqWw5iIJS~oJ68x4FJzU-$Owfv1mTX+&t`Fp*zoO@|f%_<<8>y{s8*WCu(cbE%V6F)Ox9lLk@Wp}F!7pE4L{GXxMaALw#} zK8J~LT^LnyM2+8m*HNeCtLyC{>3rhy{rz32QxlhkAPYO50ipQyVT@A3@vc!_0Q~9i z#WcT2z$9%tb3h?PVQ3 zRi9x}N`RCR%P=gKi9?7Ovt?aCLT7{b*V7z{!7X_KX43_0iVEVPEcBbX)?8NmrBm;a z4FLZ8IycpD^95{OLL-6$adQ)CSsErS?~{Yw3~}c>J{VuL1#1-KUEBE-(uL2Lq<*Cw zMzq)TKZ`i_D;iQrOHD8x(^i@uoeCt0*L-mQ=1+x;oo2qM_Ri_+35ZTDYEJw*nUBc` zoy^b0Mrv%_Rfns@Aac2Ii_y7FL3E2o?$W~?HQ+Pw}uCR9Ra`<8tjlgH3uvtsHEoq!@C zp0L#8@~}{+^ohYsxo!pr3H3yepOXQe4SFu1FlF&_fgRvWQ7?I-ijSo`tXojFs{=^N ziGu~**IWBB+Be&4!+h;2#|9&hruxkL?u5(9?BkYy+KF+)+xRdbqG69S_o&H> z7)9Ny55*=pq~(UTH1@sx4yL_!YIy{RovGutw!LWl8^`+7o0CX3((wu78gD^+?z)P8SAIfwU4@om6IS?LLUrxn)w%}yOwiF8w` z2{C;E=G%Lps~2!~hwnOqeW!dJ&jMm=RJ8nOz0Mp){-Mq@^373R7h(`Lbv`S89T znq45(Hq{V6Jy*s?PwGEbOc(r6Or#rJHMLO)Gksa&{wDR!W}Ww)D-SnfUgEU2vN#O! zqkxBi?GjTH|NILd#^_jwnJsm8^=(A=7fc{A?}rSOt}QYKMs@YqJJcrFeo79R?!!E@ zD3S|g&L4X8QxXK0$X;xu-9BBhQ>DAG@QV^5O&{;F$-Pm1ehcGcoIJ;8N(KyZl2wu; z5_@X5dqs`^w$S6N6o<_v`!lPblALm}TfObLMd16KhE^P>GzI?2Y>W1xUzmEcIA}@} zlbSp-OFsw4pbKRXBXtKKt@E-RafYqrm!e*CNhA6zx_&E(G(_#QNs!|Rwt46}y&_wE z4Rr1~yh`r8xVi=P?zYwU?|%0ypQ%Fxo}CKkifwy&c8xT&spmmfWG;&OUHo?uA)Gj6 zqDh-}x;^Guu)B+gwTuwo!3q_ffNSXSSG$y_9NQO+>idg)1PG*(WZWJ?ybq!XIwM!# zlgu?n=xMz<%-<@;Q$_cgdOOX!dwY(WuvM4cQ{R_$o$GbI3n(fo+OJ2%N@Dj%wn42( zdP`qc8lA^IhZhDHhAB3Q6@2oTuS$m>qQsd0p2s|0OrD@($0FnBYb~$Dg8*selW=bI zYtuT~xuf49!;^)b;iemP!L>L3l$_~3=1k`r*u~^bY4&%X?fzsyFU)JKz6JBFkzmNp z`gg-TG2+WdrWNZqT=Cktj%o7a%e{LpnvtYeGx|;7C&wS&d2qi#H%0lttZgrB3L*umj)9?_$K*jN=>e%Iukf$E_tFaX zDFnZaC4f%%P3iZYu1>Ucbt!3i$8Ktwi_@fTXTW|$DC}!=e_UqqmN^m6Df#!AQx4l z@$Q~nbx$#U35G_=h|{$2b6Hz(p@l%T+0a56jQhaG=iIc;faAWjZ@I(Lot0rzoN$K& z%>j|`jKqYlxt!mjOVG{f>ZkInUd7I?{tTrl;1-As$jMNsOQ3r@(Y1yUEKdZw}(&{A^uO{c!VMgzJf#fVS1gC~-4|n<6ZBL&eJvecza;gLYVs zV~JN2-@r`sn|8u7rRvVEaV0}LAg%)sMwyqE%k|g2ZQ)-{*1xXLLmXZ)(k$4_SsD1D zKHoDOm91qZWlhlfdpQs0g)liJC70zzc&8lb*3Af_MIspUbJ}#F#Vu3w9n%+noalPR z2}=FsXS$xEfqnRG#RQdxz+AoQl+dI;o;FHEh>eSS!xMAz%Q(k@XG3v3-eem&L3eEM7WBQ`P$9T)8SfE#yr4UPm}c;;rDU06+$TCPC~n=QJ} zy|BTYw?B&MbS|9tejZ4i)*qh~BY5@c9O1Gh+4RMUpobbL>#@2~^KW9b@qZp1Qw5(l6-!q>BTxei-Qv@rpbfxm%Ta@<||HPfdlhKa^lT*$DfZ7N>eNO zzkZ}X1ENFOG8R{{0|cNur>I+Dcz|sB`kKPUPN)ZpzD>TM+c50_%6TRea&6dSBb|$y zphnW_r%%*=a7zl0fT!jG5{CMmLVgpYpM>*jk9EaVA{aNVpJkDHv%ka7Q?nx(AlQCL z-~A!sjSS5{i**JMzRzD~-3nU_hv4AP*Rsc2Nw!x`?=l46Zc)TpvlOeG2e+{l--9S- zY-Ketdx77A3k@FHM!2x&(RwaD-%6~a+lm$=okFifU>KAZX%C{mEG{OrrS#M>C*|+_ zx?lOrR*^u@5Pt~hDY79nZ1ej%sqj(aKq|ywt=ru~H@wiGFx>jskOB*AQTzHA2jh9) zEM`qQ#f?n=jVjvH&(H&L@D|n6&9*M=6HV~mu2_aK!V@3T*a)Dh9_u;`X-o`$28$&b zfJmW&_LLStDOlnyykv4O>Cd>w7Js7=HNgEs4WQY>!mtwCy9fbd^!*M40*@(X`mh-Q zwc23B-iP3BD>rs%CFVWHl$$dnFjxF0^3$p1)5-==;gYgJ+&G2swT>vbP>KB3w4=WS zsJabPPkDWjb$sPZlLn~M2K$auV)|uiOy`|V8NYgB69*5uJP9O%;vojLBMpL@<2?&m z0OU(h!Ax}0Q<(yk+UwgAKEx^jbg3*gfOfBg3W6^nW>^V$BtY=H#S{?ZmbsbneN=z- zGYaCgi3HO6$H8qdlG&<-B8AN-b?!i7_=5tG&;Iq4G zfW6K$zyM`cLqwn#W77xY*71)YLMgtd+CBae$#)-#Lgj%9^g_puKb1N*} zlpW>kBdh#4owjP7{?-}2B zg?I_9#sS$|3>YV{YM5hnUK^3TJ-*_cmF~-SRmB!*k@T-4r`G!a;V>eq)O1Bb5fpO$7+-#Z_YDQer(>>yOTS1x`^S%^1T!NecxZ_Mks~XAkRE zTArz0xNeaIlcnpE1`Vz_kLJB{J#TjLPvsLMJ2+|SH2{{t+)3R_g8fH(#HZ7MP%N?c z;A^TgZrtmJ2XEoJF`zmbOAt`Q$M1x`P6y-Fv*#l&`bV+-7#Vphc?A@1ES!zxp5-wG%%JGK8CxyD^5*1QE9Rtl(Af&Y09hx&iI2S4*#1LXoAqmxIIUkBpW^3ln}v1AZo*!XVN~a!r4Ca8c>Sjg(Bzj1=QD)|Z>J;_Dwz37Jczo%^Bk zz>`k8P|GUdiLZjvkEfJpl)2zY-NYD5_wM4-6W=jyKoih{5(-gLdLqRX?dA7$VUe@= zR3O-+sga@#dVGfPQi87wp1CVia*g)mcDUEW0B6X4?Vk#A#pJOVS45$}I!Z#%vo9x( zmi|8gE2Pl0kLn^_j=;(L?K+5hUM~8Ng_qQx(XgI-JHKZaA?T^6IQAZ1<3lfN|Dpgt z(EdcvWLQu5Q`B?^h)iENp30=uEz;*X32>_T}6lf_%B7pyGrObEp`R7o*CfNI+ z&KevDO^hk#9tp^!z3JJ*?dfjJDX!n2@e_-<&BxkEGmiCpS^!~z`$6>QE8EFGTOgls zi-G6l(sBxHi@R_uB)@SH7cE~A^}pYZ40vR>Uz^<>Xu5hI7dQLtCDNVJ0$JMDw*%Ev zP*&Wvc>9vpQ2yBc^$Ao&v8jCeaQk?#2Phr!n0;mt=`LErI=(`z0nF_dHTp}&T@>FT zdHWs)oSw3mM74lUE)AQ$RE&5mtY%RF0+(WMAJITgZ~Q@^=(9HlPh*Zfhp%_89#jDR zFE7?a+aQqnj?1aGB)2=E3Tv=!5$ z9BqvA)!z^scuw^QM_uTj<#+P%VVJ4x*7LWUqy*slvAKx%E8jah(ML4oi%kkPbAj$N zG{}Rz_2r?ue-CGdkS*b^@t!B?^*L3<=@TKm>}3mS;ufN;G*_EW^} z6bR2AgZd6Z5$TvByc`fN?;3eLTmjfcg^YT=)|{hbkqsQ=zve^3>wq*)P&C!;15%%m?)0yg z?_|S($w$WzXgcH@Bt(>=O1(4!wcgGByg!sGZXzIRHSnO9g^bv%8{$m}#VhUa+494A zo@%{$<&n*pzYmvc5d7vFU~4TqGp^{ZkRM5h#fCgjNnTM}0jr{oscJtk&HbKnB!&#* z!p53EHw5q@&X!49n20^Z;kjgLqdaO4?`BXv*Nl%iGAKfjMo_{k5-Es(VhJb$PRL(T znszcFgE&j;4&ma0KVJ|==Z)`Ig1%*4T~rfX%9J`<0nuZV5EM5{l(t-a8gXt_F0)kX z*ulKR7k{MwToXTpPe_`%opB8mAri~Fs$Qg75VPV8iAU(_W(j-sMpBq44m`!!aM@uSouiyNIOc=D<5(=)Rkea__}= zAOH#a+#`R9AvDkv;p`@F8L1=6>woNdOmoo8P#}gVR|g0%CkLOwruhUN+vO2nzJuy` zeeL#n>3tME3(3~RET?S}v+(Vb>+SHQe&*d3vyl9C)A}vqN~j*8Q=BDV(nRco8}@CS z6I{;F{##D}hb~ytf^h+$99WynL4}#~4K*R5F|sx+@G$ZFTObzh_vO ztuNqTjer0(hDtWH(s-$K%ta<>G$4evTe#uQ(_Reqg8Y)J66a6xQkF892k zgWjU^NUpOQNgUfCURqU6{63%6Q%e{vxAUDR{!&yfUiHI5j|O=Sg=0l#rgoiC*Tavh zTz_Nr&Prm)7V7Sg4~yrnz}SzY(+`Ya?!ACNUN!aXf>qieF*D^|V>cUybEgpeI7lie z4Dc3Dta@=vKPLNyXP3>uV(s9D!;jMRrO+RU@!Qxpmr8f~>{lnnIV9la#aLA+riiT# z;3{!u+y-Gg2c+Eu-gY~IU*7>*Kb&#*c!LxDyOzCxKAWm9=I4N{mkS5A7rSPN3XhBb z_LbQ6Q@T+Wq_enXMzV?IAoG2U0}xtg3INrYSV2vYiMo9sn3?wm1p4Fy=21ufoo zZ_Ar#P9r}a>yLyw<)n&HedUR@m#^^6QC7N~XE!d~=g+1T$-@%u()S%8PF3q^VM0O! zX9;9YEziHyf9ukxYI4c%DJSTXXEJ}(TdhkB6^NPW70PZGN3zwweyw0~!k%>Wre{gK zn}P%LY*00P^G#H9f@mo@e?F=EetQJJbH8qo)}-bf<9A+?augLQd1lyi_R>#0qT~l;JaW5q4r9EtztV) z-?E`UsNu7AA{vF)w856Dg>$pXn4wT4tJZe^MtzxlK0xdj`lj>R@&0bKh)yy*GYtA~ z%M3f}1RMjdhndP@sQ4?p_X49GCbdc&m9tb@!gxBl>$9^JC90f^hXHH^HYTCHKS|5U z3-OmPy|60is_n&hTJp(Of2;FbUN@TuXkl>bx3Zr6%`s&YkOi<7c| zD7Bn>3j#Y2UzWPKc-Z5%_d5Dzz>t*Q0)uSIBRJ!G1@j2|-Y|!N5xv`*zl}hx#-%8^ z792Bkb5j07H`!Juw=azF^3OXY{i3w?F zJZrpqLxq*9#YmtuxEpkNy2a<2oAFMnc{myG#ykjB602eg$5u={^XZttYdj~cRz$;V z66lnf|NiIgzQ!9b%PQ-10$Y@a=!QgP@eEE_YSiSFK5W=icA+o0Fx{#M7_n8)uU|uU?bd2-nI$L3?xj(8sZ1)SSjv3?%I`1ioG|2K{L^W zf<0j@w!?me4MjrYQIdW8g1X*iEo?p zo4Uy#UR`k2f;Y{|LSL+jM|Zc*5sbo1Z%P{m4}8Q#K|6NNY_iwf1ma345)pKs{L?d% zoy9kF)w*jP9*&iTV)vKYsdyl{=D>y9P{2r1li^Hufr~+bSMMf z{CB^pt_YD)3Z`^8)Fctsi^5-j4lg#Or!ZEUQt8V?!m7WVH5^}DXZHlZ`crKK21YYh zM+7Rc@vjXFx~C+qDb6CNEW>7R`o+?L?SHOJ`CltLSh}&gTCx7A*71KaX8wO0|B1q4 z?ezIyNXRe((X2wjZJt0%R2Uc!v42R|{f+bAY5XT7Cr5i$Py5ej`u47i{I9{e#syjO zKfbp$iJ$}qt!=F%-1FDImc`j>K39;3PEC{lJVrm3gsusGX`=0kJ^N0NLfwMUvhw-9leR%A*FbvxmUPk8Zz> z#+)oh!fD=OnG{Rh?(diQJpFWAA&v9s5{t!DnWQBfFYafiO38(L%YBXUvd0!1>_62Q z&@2{@@S_KFcK2$7$iC>qubz@m(?hQk33Yrkl0rIlSm*9lY+iUi?!oj~MVKiA20d!DRHLd{SDLTH<;MOgfXdmn={8}|Jtg*|aQ*#x^ z4K=UtHa!}rQLGzJ zzl*VXpH5p}m>#XEKF-kX^?=ev9gR#@ukP41=o z=R1-ovTf`f&3@@LBa4_aNiMBY(e(fn6Pcd${NMBwRiJd813gKPJQeq5ik;sakk)^{n|;uR7pxEGOs$wgn?MlIMOL@}k_`=IwIpVMtX?B&_Sy$eCt;K@U68`@(UuYZR^#!-NS6MHsaqr4!p^*ef6eQxKr zWOYgqX!yWUz7BS<*3_8{haEO_qJHTRC~UEkomFj~4y>9{LWNbq++xn0So~?~c9t1T z2Jny{c#|HC)7U~1OC+&R{PX%k5oMKt$ZoCfSN?F1vMB$|J$6h|_#jNu7%H#<2 zQGYHAS*}7Ztqm0z)W`{heN%!fr30N-n?vm4(Ly|;mIr4`5pabjj5Os;R>KuY;Ux+C zzHdS!rTBygKR&QcC&-<59**dkaoIaVhT{T;^`5zX`nTjKCk72#PFYFk+Jo~6;BrLJ zLQDjiNw0L8BNZ55CpB@?Gu}gHgmUaHjTX_eJy`I8HDifiuEZHX#DRpIL;ziKR{mmT zE;!ue0QvPPjT;s6M_RXOm|*k=PnsP}5Sg1(k5TQnPNJP?>WFX>ldI5`qxg65)H_4v zEDq7wmg32wQr$#>=Gi18{Oit#G>*Lnodrp4KdQ5kb+J3(b#uU&)u-oHHCKnL7*7;N z)m7oItN>aznB9@(LHjiNn-V`@GfcZFNA37_pt@2Yu}cnDX6xyNKgX{OfxLy=I7?rs z`3`>1u26}+!(F3FfVqw=o4d}nr-^hKaI!K+EWy-Ri7PA^8_deeX#3r)}Pq| zKz!})KJ0%-hvhuF@|zNyKMrQ+g)21^&Ml_ZNXp3Mz)Xi=ybWZQC&`!sT|ahuh2NZO zBV_aF!~2-6xv1Cq>AQ5Ar($U(zA(!WWOUoQpoxd03=ZyUHY>gTQTKbAY;=4`eEyzr+Ny=8o z)04;}Xavtj%A_G#If_x|aMwC99>_r~g119;LC(SaA8$F{qn4l>AeiWdipPLjuY=we znVLnvV@HGsG)4W0FGxY8w*LBgWj22$rEArMic9CCo#C4^9X6R26Pm_eC(&w5F?jdd zlxk~;kiMq0b+P`$(jBVDw7EKt(JXHwX7`BR`1iAFNfjec06<8fdTp+|gq);q2%p$-H)ljZi`2);OtM~ol(mSE_YtnrB zcAZUcatp0Hn8a}wWnuiB>RexS@#%7+FZT?CYg+;AgK?Z60oEf8AywoaW&HBD9a@|G zaDmGYF3hYKm}-`>IJ;YcG$oWWU9}gIe4jMNaTrqI-xk2fDZVP3IdW&?t`Sy&X>}F1 z_@eRPiPftXPUR$|^1zZMWgRpk8~;_I@&W-IJNqks%O--=3)QR?o`VFtm_JcY3V*!z znTI;!o8aynnfoC9U^XA(cUeD5ciP_qc*O@~j`R2BJ8eGq_E(e47uV&k3KlP|pdvKJ z8J(03pqlVJXNYvo+vPmIlVbFz^~((%wlYis5`5WZhyus z#m-dFv)=o-KLgW)C1-gzkXB97&+*HPNO7!1j|7S!{W&}37#$=P}cMA`pDDPxML3{=jRi4^pjb}3CZ z{qEa)NBph0M1vWNz*m!>uU)g~g+ON0jH9U5+^R1v!@Gj9e*(Q&IK? zMLO4tA?czS>UC88!pY^ZIMCa zYXy^_@Er&|;9)=3hU_Lr8qKPf19RBzC2LeTJMuew>%v0uf zud>LK!Ys!HZ)T6ko-z;6DohD;{ktN{S;p_NVJSM7aF>SKpPdRDFwNf7UM^cOt(nO5=#d5?A6Z?rAbW z5lI=fZ-KHl#5W>uxoaLe6g~}nlE5$pqz=ld1g5!HQ7qdOC@H7sanr)bLAM1omsY5_-YZx<_9M|Fp1maI^d)I{2UM{^I(F zozH)=`y()Lb98jG`8NdQ|KPfPAka6X2Lrf5^-J9o$l>uaA`) z28K`_28QKNWaxKs;F{_G8vMV9{<|>vpXkMbTEYKo=zo_9|2y};Ya##TU?B8=?LhhO z%E*8B@^?Mozr0w6|F6B!{!`ue@8Eyeru+;1KIT95i+?Ir{$>APZ@xdG?SE{4^h}GZ zf4htRjJ^Nr)_=cq|A@Z-GEVrf#(xij|8GqGh{pc{oBn@;{n2&*(Bu4PZ2l+B|2{hZ z6T3K&==#63@$WSM6Y@V}^}ne9_mAVh9E1b^{~i4Ga8^}7K>Py>2l`@!Dne_3{wVz) DKK@GV From 12d9d0e5883a6da53da867691e1676d6f08e6a94 Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Tue, 16 Jul 2024 18:10:52 -0400 Subject: [PATCH 50/60] replace jar with gradle import --- build.gradle | 4 +++- libs/motej.0.9.jar | Bin 130711 -> 0 bytes 2 files changed, 3 insertions(+), 1 deletion(-) delete mode 100644 libs/motej.0.9.jar diff --git a/build.gradle b/build.gradle index 36b4a277..1f7d74e7 100644 --- a/build.gradle +++ b/build.gradle @@ -67,7 +67,9 @@ dependencies { // https://mvnrepository.com/artifact/net.sf.bluecove/bluecove-gpl api group: 'net.sf.bluecove', name: 'bluecove-gpl', version: '2.1.0' api group: 'io.ultreia', name: 'bluecove', version: '2.1.1' - + // https://mvnrepository.com/artifact/motej/motej + api group: 'motej', name: 'motej', version: '0.9-2008.02.05-patched', ext: 'pom' + } diff --git a/libs/motej.0.9.jar b/libs/motej.0.9.jar deleted file mode 100644 index dff6a3d289f22d20538fca2bf049081579fc16f6..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 130711 zcmaI7b8u(fx-Fbe$4-8+Z9D1Mwr$(CJGO1x=-9Sx+sWzJQ1_A++7FOb?5tk96ljfHZ7ZFxeqLmi;8Uq5l zm!24xlBA)Xg_WeCoSK+!P@rF6+Bw`i1O}3m1c#{i1-`=i`zwsUL+;-jxcy%n;QU>+ zwskVLpyM}ibaK!)bP{%RGPZFvx3!@)w9ElEADyC6F1m!Q&lYR(^7t0s* zMPf)#&BevnYHdx7Ld_#FX7FI?_KVpWZ6E`{bNOBGVWB%~grV*0A7|M5bf;~4e|up4 zSP|F?5~=m*j?cQ|x6B3JEiKR_>GD7KB!v-ZC$bT0qv{;LbFU!6F(#A|i_-LwguK;W zc3kA)r>kaz7|PpDhCE3X?;AjNRnnHthV`VuSP-tDf=nyF4zm#iu^A!b7u0V1DbW2k zE%OVcfhKFGx(1@opaBWi5}E`;qd@>aWg1eyxj4wtoAM2?D>R7*7R}`%82?_-fuS?6 z_Vaq0Y^bJy;qJ()BrOReoT2$PVn8xcranrPAG*ORVIO#cV9*Rd>Q(&SFKx=~+;e&) z`69k6tNChvY0&VKpQwY`p$VgYb#@UQkZOL{M`C^g4yiii(nRkQ4=9 zu-`#wIwz6A7+JUAF9q1HY;{TXf^;6)7gwHB84YAT-ybiadZ@t&9uOkY)S@+qDoyS3 z%`C&U6D*Un&5t3*zX)C+-z?X{lPfGuSXz{;PebAOcM5DYJwXb0>dpqefy*o`$wKb+ zYXU96PyKfS^f9NH0_@uV_@*KG`!1HBAim7d2@bIU>vAeW1?usM0P%}3U=XBKkH>0Z zCL_9-3yBOA$zyauAU&YKD*DcHQJz0pR%tCm<_n+8RirSl>rHRvZ@XJ!D=Oc{^Bh2W zRJ1qD`Y@eU+u2BSKM$ZI8R(;GB%{-Yx_C0Us1Lvv30!NBj$(Mg=1N zv`<)7=e0A4V{OXnOp9i*>M_VToh%h~v7LCoZ!q%xo&wTIVQ*EbV2f*u@iFRqTdFVK zP1e|xYL7eHF>2}x%fv-n1PqGbXxL&c^sT*Dgpk1M0;VBa)2Ywv;T|$S6qd9Imo=G7 zLI=i^VQ)|em!v$=KKM(wNH(VpE>&)7rX;cvK{=iVhO&TWAStycn1BS;j393yfQGo| zmW%D=8-4PpRG+MOXx@yLB03*xf9jC*gdR2rroS}XFNFmLc7~Q9#jp<30ql2nhG`#} z31>gR{Uozt>t);2?1%$M;x+o)9P1%z_I|MOv!80}PPAO+2`U}r;J$!;y`~mI1X<9Y zS&N${c{Xwcc*h{PfV~EJwCisw0fsD5*^lro*!A_#a0(Vq?-1;J--y+d0!1zp7xZK8 zXeOVtJA{4V6hLH(whW_AkypgA?z#z*7Z>b9fk;+Qfv#0RY*TdaW^*rW^~MME zKMq2n_4PFe3la6O!r@0x20CWj=SLetq&^uFM@ z0cW=wOBVuwD?Bp?8?6TfyEO8Jb1S#Q($ceJ&VaRFE2_B1liw~2^@lVZh;i&`k}RsO z)e$8mv3MU=EK)-@N#!sh;2>H#E9JYei%ON`L+%*qkx^{ikd+{nXgV(E6bzlTqghHH z@Gvh$*h#MJaP+ic6?_x zDs`Zm;R``L>op05<$Uzuz7ZOfwK)8sKm5l!K~a9m(e1EUahI*CDCDx*+CIl;f?*;m z)GGc_Z7t7->_D#&XHQdG5|G)YKiqVGOzagE=@A{&xd4>nmrC+YKv})}(mM*rm$NAa z^$N&OX^e)kj-IW*WlqASNS#V!%grQ*LQ;tgYMPn0A)5Gq`uAx;kq9Ft`#G1g2lYo< zNl6N0TdDO6LT#Bqau+mQ-$*IRu2k}aZUSeh1Yy)&$WU2F^UTLrnWlOWb93aA#aI&A zlU|(HRW0zQvhEp8L+8__k0B0+-VsYl+zXHS@LAMO z&!^_Q)5Oh4gKfMBTs9q)3#X^bGe9F9HC0)0zD8vyOuD1s?E{~05p-N%M7Yq-F-v9` zOZw#RA<+W-Q@O^nTkOS&r~PG>y+~v7pcHeiSQVR1L`J7rp2nf}kT*uo8zSqi&FZ@x z+HY05Rk*5$8{Isa%S#kEHq{IersH=5BUjL^9Ynz7i|JHlmH7|JTZ!bhuC?&9La1BU z0-iP~vWxqYsIH6-l?&KMuB(Y`YU-B(z^U00O9-DJ|g9&w3m3>Gs* zOPF*8& zgdvN>ya{WJs2&;~6M$;_^4oEKwg_H;&m@O+^#gS=`oGO>Dywzg013>YoOm5~AF^T;h=Np+mI!tJ&ifz&D0+L2&-cD(}EIuWj-TE?g z+GG3u^PeoCQ+&?54*EA6LjR{Mf%)%jC~jkDYi(|0s$}M1tZ($M6fvj<>!q}q^u3+N zc2Am+azLVQKm-X~6l;V}5Do@`fRA87>=g_F>_eZ{`De$7RECsU-%@BnxuQe6-5Txm zYOH$Y<;SIfG>~w4vqX_*QIW1s;$~I*d3lxfW>u9!{kP|KMjA+M$EL1thku&uwfpgw z=M~5Ieb4dKsACKsxEv8Mrxx&j`<}R^rLrS6_I1PnYm2qGS{@uux?dYhBaIRY>>#V^ zs=|+g%dw?mVM!ac`MHHg2|g{7*amjobMX*^(WX4JnnV9jGLTO0+byA$yVqCz8s}4(%kk>VAa6+6lHW@3#3t_Z2aDql5x3}`87AZyyS&LHB0<}(K z#P~3Ew45Pb_&~f0p+#`BI?iPHU>+?Mq6U&gNNZZul)_}Vvb}|Tn^EFjzTHZMMz~vw za2$7EQ(fB7#P0#ZQLt(qRu429jO9vkQnRg%yC&eZJ-5)JeT6mqulJ!XvBrLh7dgV6 z=z+6O@*$9)!mU#HaxQhJg+s(Y6K?HK{njreo>{P0$Jq|k0!$O>3?kc)BWJc|DDp6+9lJO0Ou{_4ujHlCn< za#y3mOfnu-J+Hcrhq{nWF^!3#EZ%5u%s45@huI)JdJs4m4Z|!~d`SB`Ip0hQ^H%() zYWZO$2!CH=`ijM*80p(#=PBp~wGnT8Wu=s{Mrh;))K9A3poa$`nu-h?>W*@+stuD0 zf31U4GfDM)mz4#y=Jp~oCxm7IBVD?&2(d>;f{LhyD1HqIQiIBaOOs}Jvz%vQnfeS8 zd}zL#&EQ%a{3KV@CDg?SkRB=Y;Op6zePG^K?N~U^YUD z-;;=LCBiMXTe2d3z^0d8C(%m@mtc6C7b+c2F%?X*K4hCZa6cy1e7T;I8WV1{q zu%a3jCzEC1IB17-u1-yY!=jJeGQEStas`E&tCPn;JcjOX!gvmvL20daC(UH7dm$o{ zjSm&D=Nj^EdTiNS>|ECc%ZF*yO^UNRRMs7VBt}Vk7R=6SrVQaQ%J~VL1`QViLO|+C zRu*%jhWf#x#Zt^9Yi!K*BSgr86j<*0d(T&v$$4Nfznwy}GFt~x6% ze_hNMl&u0&fXa%3aFM~Y2`|xW4w%jm>Z-@~pW}-qTUf7U8*ekchRwGuseEuF%Yi>O zGyMV(Ke=7Tt#?2>4jFFX>rs%}3A|2-+r(tY4b8>h9_+cK)`PYYRu#qp(LMR=sVq= zn&7FGTlHkJ>h@~5qe>pGLfokbgQkWCV|RoVV9ib}SyD4(e)~IfE=A5% zWX~Fm8C{>j<7-L28oB(*rx=@L?kz%nP-$I!GG;$u{qzb5aW_k6UaW1xR%8ixG7afi zNmx(CT(G=nV5H|gQJfCRJynk4tlDEpOi2W5)E8o;LN1eEMkHSbAh03uWZXc;%M39n z&PS(7qztxZ!vhdRTLR<|Z4AaI?ZJ?&%s+-<9Cz+Xt&{YAp;60=fJky>SWKq<^w^#X z(F<>;AetCf{F&XI<-7(s(Uv8G-&cIh)(dw{jBx$)Am5KgJu50MZTROwp>o{+hb>&iGLQ$>SQG^RC(!@-Hx>5<@y z&IQF2iYeMLoT2E@`lA$&$`?pnFqBA7^sOa-Q0c0~wy-@JcV`L@&!4S^hYO6i2WyXe zSFR~zA(!#9(v8%+B1#;m*KelnL9^x^gsb9-ag?5*>Dr?E z`{UM7TknNeh0OyoTelk}CI~+EQVr4B$CM6S>NOTQsXfyDEW;y>+eXyEbOj z^|p56g81Cwr{pNU(}7p0p#GQfNLhy@8$8pqVK*z)_e`@G+3SXZRZ{}%cd8~?X~y=h zY)jNr4Y zE`6795?2Gq7&D=e34$Oa^B@E85Wy`F0naz;yM43_(Rs=I9%C*ZlwwvKdPd_vh#sx! zlXp$w&?{~^zmjR-m%s7?ic(Oy3iQh6qklpr^Jp}{KU2|P?JV*EFUXGDC<9Fvd&`5$ z1*(KVszMHx%ogXSOa4ZqEIpdN$_*$NKPTJ2UKvB91#bjx3;_-Jxu)GHHn(ZiZnq6- z1}+)%de)>TUUx*x9Y7~(Ugv@w(~8e+kt2{&-f#=u`2M@mjm^3>Ca4uWAyo?lI4d*c z_Q0uK#)XSmQ&%2$Z1?nCxw}agl}#<&te&=Raz6W5<c)n`bCq93z z&H=3(-+K4y@BO1Lye4;)r1axjG4+ulE6sX=w#s6ihQmi(7D?%@76Al0R(_ai@+CJu zcO0ME*$-?-z=U*`d&;mDB>k^q2HqnEK*kNe%Fg%#7BLUrUfd&n%&Tas@q3xQAKF+A z{dadnLePb|$wFb1V%8}>SN?dQdp@^wwAQnu0r zj}kW?C`}Xu9pt!;Xu*A6~FEB;QY- z(_WezW43Zae3dp{;V$2!|4wR@E-p=AiYa}T(8D1k{JA4VHW~^K4ZnO+|;#F9o6`1u|U~A}WV|!1RCy_pq}`b(cj)N~a{_JF49lDf)YA z|BOc9*4iswbPwl+L-3Y1=C>|=ZI2Pqwj#J_;AP@NuRXrE9k$)hd0#;}n5*Mvs1j_o z{Uf+C?3KLCbchSwVdtGp`Y2UIC+;t@O~bPg2<7FX<_54Tf-VoR{!?p+8Yom1+ zDMw?K4%IG&*wDgn?kl8sbn27^dCtgdW6Ix z&5iV3MZr_a2iD)A7LuSs3o#4H#kD){b)3-S?f~y_8u)d(5*Pd_2X4IMl@h#pGdgQF za4APRCu@XsO-$L@fgg?rA_sB#!9S1sB1bCt8V&t&8tpiYvwz5zZ{uq-=a#fPTNvO` ztu_k16*or{e~!JKBH(wA+=n$@z!_Et*CU|t8ItMMBVuh@DPoDwy zT^JND0zYKX2^CqH8s9B4LIV{#Wq*ASsuSO2pBa8qRfu~k?A1-0c}Kbq=sF_!B}pyv zc@QZwjC2=C6-t}g@v=gQj~ajnpb{!mqu`-c2|qPxDn+v1bFgnpC0asqJ}-5TGDF0o z=t}Owdg&4m5*D*Uxy+YTBP8Gy?pdLB3CkGBy4WO&-_xm+zQ}iK899WrJ%R%t@Ugc% zil$P)z6P||^+;JK^M{P=cLz%>V4xrK{O+27+MJ2%?Ca!{59gJmC-mJnY%bkSL_P1L z*LWp4CCO<@p1g-WOO55F1P!gd?!-$PxU3|+k_$mz)i95~E!TzOXp-xJj8MH;~zYoB1FvCRlOnnn?H^zYhk_lUmIgZorQ;t(z zJ>Oou;I#p&P;cn@O(ECVMNm3Z)g0Mfn{La^`XiLcaHP)U*rnJLCvpV$ zo0ZW%CoqAoYwyYm*eqBm9UArADTccX_`A5Ob~z(~P`V4=xkSKGLGPh9 z3HjkI6n^Xb=&+N@=W}aq@ zNFADA@1in;vS`3spgc0d3tO*$Vj;{3Fe*j*6miDYjMXls$CNKkm~aN}t~>H97b``^ zE7&z@b1v=ZK9ORILa3i}ZQf~OrjBb4O#_swik4H%*O0jPZ{CP|Ec`0xnkZYs?ka#n zieFgn#qPHIfDU1iIEg2ECh_zRPhycd2X7!nKr!J*fu$jsQB*+FlYNmAInkTO^594- z9a;m;&q3Wrt+`l`|Ab_`{|Cv6|0oQc%w5c#-2Vk=??h`wEM?^3?-XelwsF*@(ndZr ziU)-^K(zqx3pHRB6UxiL8>EFoC*B67XY#7Ihzbb+R;% zWrsY@6|%-=(^(!BPu!sBD>}XfZhm`5pHY^JUavm0Mq*Yu8L{aVi<`ygHH>0Rqm;&K zW|y3l`IzXmXRSfp=o>*wp|qZW}L!_Gnk6>_bum4dqhhkNC4 zNx#w2mYoJ#XIfj!1osVMel=}IiJM7YHEb~yP}7T+sv?*!=<#Nd2 z1(3SRL|3df372;Z`EpuYC&I(=sX$g@uBhoX{ec5hIYzbL64DQCV;OqMjZF@Z+1HNv z#{KhEME;=9`weO`xSbNY!nDX}w4V}TTskx^kyvO{sf=rQ0Abiifq3dV_WVm4qJ&C* zmspr8+3G{BE>SEP&=KH!Fvp8!?;tOY3CSnmnl~En_)h}i9ugumX=gn z^2%VXF_G3LHF-^Vu8>}PB2857B~XLW4}PGiV%{}?Gd0&odWW-^UQ`xt{v}{Rwl$nL zZooIySTWU9cb^aybP}&U-@|)|jagcr2exc=z>vD=2#+8EGm5M4GNEfPEDXn(dY*bS z-+VMoEx`b3|3z+MF=I47+LTJbQ|pgtuZ($pq!sfcLfUpr;JCqUG(_n$c7UIgdvIUN zbYB|+dkA&a^A3u}p?Z{4o!(}G0$n9`%|{6H7YN>TR@6}RIdZ}J&OE+Igvv{eMrKiV z?hDez6S1MKE*g%s`!L8^iQiLBO)vGVkw8G7>qNfMX&rxDs{m&JFK zX92=gpz78|<(p4r%F2uPn`tm6^kOgBp4YC^u2avOzkI)+*YSWvYSBfqLW-jVMs*~O zTTr3eyeMF_1@F@z(~|0W=!zE7LzeQpk{Xs$E~*TwV|#MC^7u23X3GS+)#~qxNG!eA z;e32OPdZZ23h0eOfaK)+fiQCfw$=TvTM%% z=yEXArRZ4Fplc=WG&=MX{({^@{}ybgS-!wPS`7LbVzULlhCo^@Gk&73VQ;Xc9O?9i z9Ba+P!tL+CkNfhNw zpg^kC{&z#<7%41N=ygr1r>e{_mW?ywVD!&QT|Zm=Fs2W9d(@*!I7GtaOtpl7in>)C z%>@rCM9raX)+v$Ee0!J-e?HL59`gA459=L>0WoerwlEkn7~6csxLckM9yvB5ghA&~t#oz>#RKq!tpvm)(c$4WL zA(K-(KSU;EK7q`cFgf{-OqgYZ4BMkIwqI_@UKF2$}j#N8LCijLS>_g zrKZnMg2tF)G#Df$u6TVI!b(5L~LuZ_PeQO&Z9bl>R^$x za4XQxc(rQ(5&Lyjb^0;=v9llbJ(&0f_d|fy{b&_Z-~dr#Z#7+D&WE5VUEs(9TKqlu z;%4FsQXpNM;GV@+ZOFGjdl|W2u7d@mC$`4z=o}E#*jn|taT^F3Ld@N|}fk&tDypYipg&XQwMLj&r{5!MRlq zj_bs``?Oabtz`j!SjWt?%wEk;E9ZiUcpQgwY?o=B{StANGYr)=$%TsH0{;UESOmm{`M+Y$?7unlf7Wp!{2!3`7a*$CA-$9yv%bIL z)7(c7e(XZTf*=SHqk#Z}L4?Npk){I0Lxhw%iQ&?x8tqL4^>?^!yHTltdd_UlRilj( zCTpxORynt*baY(WxGq<wb1JeumuyXMN6=E@HV( zhY{jr>H!RH8a}IcoDKwLqEDla^eRhg}r5EG)s(s&&eIG7|nI3T1S>SGf@*Z8vvTP+1Hb z1TaiO2Dc0qbjr5=iMO+5?~eRPGR94*L3_a@)K)=gBWINlLgKekfA#p8P#Q)329u9G z_?oLAbwFgMm#+6lVTUuI^uC2bDq{(W>$H zDz%OA*9U%t<6N~(4SfTWDHP;^$}QSsIeO!;O9HM4?_;I$EwO|`0VDPb!DBAudHl&; z9ZP55X%nh7)U^$3is|1o@5`b2`i~c#4}&eir%5LDQy>8Iy2Gq2l@^q!2Q~Y3CM(CR zGz(f;^2_?ys@tbh54z>?Z-hd7ZyJfA^{DDF4C?PQ)NK z+eu7lha$I*WBT%?1luQakRk@1a6-p>NF&FyPqSPOGqamZK zwQ}K%gjb<)H|ZcFXD9#Hl!pDeX!l3Ty_vVb<{R9 z{j^~l2D2xrmM1yTFnOtu_DDhx(5_}w+S@YR<4kjDeatFy+pz4l=Yetu3mOUOqKaihY;j0q2(r#+pY z&-DJkg2y<_^dGyVVc3*4&F?x8C zb0NjW(vwunHC9{9G0q(vR38S)+dU?Gv|Oa66!(O`CX9`r$k1=fo>mZGsVuFORU+F} z+_AwEm9vr28zbr^WAD8B2iR_DSYU8@H6^q3wp|o2i>PbhO*0LcU7_j_eb2bu`H9OS$$4`Uz(< z*@vw4?w%GU$6CdZ%|Qh!9+{`{g=Z`B0J@!b>S0Zq7NJ2dXbpGKrFfGaaG0cMMadsv zKB+234fM~1K7|)I`_vlhx_;xg_2H^FDOR4Ib9P3Ju-QTv&3V5FT&tUivUL)=Y@rH& zb$xgUm=xCEj^R@zY4p!RkEN%lCzgC=nz!sDzXAWWEk@awYUJ&o18z$+!NboZ{v8|lb%`dS_ zJf@m2_YCb`w6DMF|I@>`?DmsG!V~SgIPnQro2sZ|d8{27FZBiCdrGQZU00)ml%}Yt zY*nL_*wqji!WPofHG_+q*hD@A>HOfQy3K6!~UFI2q$$4r%?(6bnPPHupfSTsdj z#BaiJ=;Zs(J|-n3Y+ZAlZm&vX<0#)Y(e`ZgM9xKQjILCIR~u<5(7NDwE{a^p0c5K? z#@=tD9?+AxxZ=oofu(P|#xk^1f{92T6D&^ z-GqQY3`?AF{pG%{kx3=L?GkYFjpM`R$(fBJuzIq$Wdj)1iz$U=3_HszEyz^Tu2gVa zNQmkl;P_;Q{qZFZr4&sh(zLM>x)D&ybZCf3p$Y}cVdU{h=c1+3in>+N8K|nQ%77}Q z(+a@ebKf8U#UQF`R@;R`iSCR!Achnm!%6N!_@2OJEVsJk3`PV^acAxn_b~*{2b`ZP zx2?kULKNkNKw0$@i4BL?<(-n2j6$;Hqu66eI(k7N-3*6LwM`6f0v#PhXURFzra_mE z_-9_1>9L@{2|C%N)wv5=Try{GfnAlxpNb}*V(z6Q|BU1|j$jI^bR=jdOBPoqL7!ai zsyReQi4tv6^NWv0MlFd5YJeJ-X-x6JBkPrDnT>fUL;vRP#&yxy#ZgJA-xVg6Ay*}r zGMddJPmH2=dFXnJl=avj8|&gZlP0b;Hd0-vqC0l7YGha&vY6cutf|x?_@E?_ zo(>n}qa8Xw@Cc4eD2Gz>Rp)k>x3yKVwKXCv_}bgu`V!+UiwYwpQRV?B)NGDrr5H** zQL}L&oz@0H*Gx{6Eo&yRc6P?NPDx5?X)5!D3lp`vW(*2E3v$Y-xQ2IiRiEW*i@Bi0 zas@H2;mT#^*15!GJk)m&>I{B+tK52!brZz1Vbb9+LpvTVP#PqGnl~)opg~gvt&00H zD{;0_lU{g@IIwcgSnUk2Mp+b0MCoT{)oRN;x{odB26s#;;CVh{!Q=0$$C{^7Ow&=n zd*H-0eBeagZ%qaOigvF-c)Db)IJDj=!5HfH$R*an8D8m&?S3V#&%+yf2p{TC?A%Yd z^d-XQM!a)eq9g^Dazr+~)bjCCb4IpD9Lur!k!Vd}{#mu)h;R%m_5p%@ns@iI*qfhE zFHk<)_GDf@?hEB~(27A~-eb;;k!Um^pdFB~;$vESUGPVsAR)yCGg zX3NQ3_BYX1jf5a0rNG6Fh!fTYpD$GscjqI9jD(@}$5QzVsbRs-C zL>URUY7=$BY-U4vb|Q$h4b>Ayngun;U#3?~_iLqirdfh7XQ?9&Gfto^7rwbq|9;NW z>D2x4SVn^tzKOYu;-reDpSoKbMpOIwG4}Ka+WoRE_U9WvaDuA=;*G%5)|A+1z}*k96C!aK zS_kw_#hzPd^noV%&zlF@ltbZxnn{IQm@6MJc$l48r$ydgXJ4c}VAZ>ho758|~<8y8=FJ@zWoOx~+Z-lFKE#@B_w7=(9j{Bp1x=WD*~^cqUP-l3JO;e(fy!IPz)O_&!|_(A8UKJ3 zKU4DYKRz$sp$_nE@)n-Abf;WB`B%9WSv7vMIfY%hFr;V1efb zzaU|DUeW9;U&(cpj8BS^$DZ2%)M@zIR9)i_p@K(vu~e8UNWeP@{@ceMy4dBEvKqE zI2*|4ubBECW)Hd-3sHznL4t+%dg<+?@;Cin^IM!0rTUnNyN0eWJbQxbAT@v0skz4) z#JWT&N+5;bLv#Kz(Dl^*s$1*a(AdWxLOVvoU~%@}wbr)F)LU)g<1xqGRx4l^sM>A>yT35`aPgcYrmiX%S(2o5b;9! zmDbgVt#Qwi-0xQb_I^S0Tp4I80h^GBIkw1q@|zsA(`Kg7wJSa`NDAP+b6T>bWH-7hWilsCL4KC^3R z?P8uWi9BtJFFOy^eLeU21a`&nbwTb@?13vMF?+gMvMTw6=*t6DW{d$c zpAs4JZ3P^Yg3Tgw3}QJnc1m|E%?cBg_lVCxq)MiUpO?;{!xn*UO|O(oP!V^QXLk|z z5m7{p0lr2;Y~*VcMJ*v?9x#5x>D4K9@&u#z}l72W(DV_Q8qT#iL;C%!x{yV zhqS8KL!;>4JZB!Htr*ISeL`K4jdfujS|>ey&a!vosjA}KUk}TGGksqT zt1EX82&T~nJG3i8_2fzH-m>!Id3`nWa|9;c;G>o!q${xCGr{dE3SSw^kZDmyi@C!s zT!l@bHp%agl>B6DG2ol3&oHz80F|n*FYT(gxXY!+r5zrdd%(6__vSt(8!kK!hNGNcg2W(?;;<9MrC)(c(_lrt)DJ5ERu$C)8-(;#Ckux0NR5>K7tamcj6V)qyRR8BrN{Cp}7L-z~}nZlINd7V1$V{JF{Yh#Mk zWLVQd-;Rww(UbSe8x@6CBkmtL_}2#O~(; z$(3R@%7?inIdI1)JAN;nX}5SJn|4=o5n7MFddv~2)zDw`mqN)GW5>dR&vy`90w0&! zke8`qF7YFoXbcGfl~2TiMds&|iW3#fH?P)1Jv#8H*jpzowu&w3B~%KhX!(s7!nTZo zd5N-GI8x8MKgVMAg@&0DHyIMDu0baBGqxDH>+LQs4mCe zB=JWX3FG%e%?i>UMKGRGzslzdM}Ps zEI}m?*4R*cMVEtI_01m-y1K0t&~s&nrXdg5sI&0L_NO`i)qVd*egp3jEUIoYHg+{z zr`l#tO!P~GEM{^x_uNgX~afcFpwl7WTEsft3R3e&N&&$%nm{-g)7`3)MQTfDzEf(4LEng{icn& z+9|vBsr>3XkIEHJ;`^o4`;OY`@b-^a4bCw^adJtVL=L5dH*bL_%eJ6R|F3(|e>k$V z8ynK2zpQ99-GAc9{_7UYKeVZcxy|28j>HWAKYePgX!%zJf$lSvnwUgH1(3T9QE*lvFsX-`~wV0<)93(F<_0{W|f;5L;EagubI^4uD~?`-*ceZOb( zgSE0Cr=P$PDLYZ`aN>CulpQdc|NDs%ox9{(%^!fP=DDfHj@xgv_6TSYm#^|louuD% z1)jg{R3nBIEMgHbE2+c7jU7KI#(O(O4b;X7je{Sxw0MUZyc_|L&}SaAhl*1qaWG4r zrv9N8g+vK?J$u=47>6IMxTq!C<1PU}q*)wr_I3l_@3@svjhkSg4ezj(EIIX&eK;cP zjk5F!rvx}Fn!I6E(I4bvqlG8VTBAu|*}|ychwT9^=*8H}MN?@(Dmd#|8ZzeR^!B3t z*6GXYSi{;%WrBDgYUI|5!OR19=4NN1LZyzCxeQ}|BAuDjelNp0bxoH!vSgtP3qJiG#F=V~~lW8ee=)*j> zfOO`sKNdf1MI%v?cDRM|lh!~0m- zeg5x;C)%OOl=5FygUo+aHT;)8=f8vVUqo({vb8FfGJ=l{(n_oiNij`hQ&pp12tKUY ztc1ndUGXded9PBb?f4Z7E<29H+u|h&a zhpXuk57YF-#wxGw*V8XQ*Immn`a%nvKWq)qPC01NgI#%$unZvw#dXF;*8Qs^wAHo_ zOfxf+cFGbh4d*U_;MG`44Gn#4n>1IK$iaAap`I|C|BJP^42rW|vxS3O6C9ex-QC^Y z-QC^Y0)a+CaCdhJ1b3I<7J|FG1qpI^-#vTgn^R|YeY-X{Gh7Wz1F%fS&xXu zgV+wVf&JiQ{O=TJ@i;5)R7b5?b)YF*&7fb8vu-%p8&c)=_)sK)BqIg3Q)25UC@hFYT#tHy`cQ6D~Qb!jJHiwR)^c`S}2^!d2G>`A?>sVyi&4I6R zS1tph_=9g+%C;a)ntkW5U>R8kkmq*0WEG6yuI0QIb;W5QT7FT z3C7lGa5)&=+BjAD>GgRoL%+v=F^kAb4Hbi_Uxi*5)$Lyymc`dS28w`5w&1`x5BCzv z8Wy%t_&Rf!ANvQz23`9R#J^5CWOfk3FUlBWE?O+q0}f(ItJDSV`E>I1M?6JK75!tk z050i*#D0tQ{IZx>Ol!e0^0!4X_gB3pvQ$7=zB{#+b~JcCy?v2$OhIwQeoT%Nj_P##r0bV-n>1@`fMcElYjd-7g{yeNZFLd%J2<$|Vl`K7G!Q15hKV zTPsOZrf^P0^U*cAZzLlVl2AjniVWqkY}_$ir@0NIJ4{n>Cw#h^?gQ z4dTdX9cT1)mdX>+=uk7J1aQlP+*bj`NGQv|WU+n=$F>}-7_t5pAPUj^E>!KZXkqbD z)j0B06=7sGoq=+1F&}nd(cCx1q&2YBY9Zqi_i+Wu zigq*tpTElnehg4Z>V|Lpl9N0>HC@OwEd*K_+?(HI1m~ig+7K01n)w0$n7QNZP}tl; zat#FzPQd4wIukuEj0>Jum6Y5w^EG{m^}51MPc1RUfj?MxyGGYqryY=#Ov$JIgq5I6 zeo(X|EChYk$O6DgEHgvkb4Tyeia)?Qk!5pjeS)lvQh>4Z7Uus$LuIs0*GDu2-8ID3 zpi8Q_(I*TzG4}z@M1f_eHd^v$pskokeWZg_i=$Ot)7l-wUO!*2FOKg7dr6`R74a38 zRVqZRxJ&SfJeLu}iteGo=M(SRV#Hd*ksUW`1;5-1^$?OKM9(h)DgRrq=|6N-?R_cK z-oo9&3Ud~qyXfiTB#7q{WE_LfNO?s+hnvyG z;H<7roKN1s#xD9`3$@r*d@ixLA}-^^jcR-f!lMmvI@b#g``%>BF)(bZ%vUq^ z(qsk;L8ZoE8I0&aI+JTm{l(*uk_0OKqgaYE+cD%ZUy@(brzgahbZ1DIC`60AV0^_o zERDg@w|e9s(XPkl!P`+OF;PO8cLxwnbx?=6r>0IaHIf9xkB~1kLk`b%bW$!va5KVv z%Dp5>PJcO|`dM5G%l9s!*}KsE&s{?7|Hm))9}=Va=!Lg{^_oL(WA1|vX9AZHS4>hz z!P8Vf9XCKS{|kXd6Fbi38?wUi?0124>!D~#MSy$0LOugugYt4xF@3&3DL(o)j1;Kb z#aDut{L&!tEk81y1d0_Z!Ib?8Kd;C0&W%o`x7RluBdA}o-FEQs_9J{bSu)w%_Xu;7 zGFoDB?QBC?@$~>dS`SN8NlSs?lq{VQUbk6}Ga3jM$~-;G-oz&NIe*0W)PdqJ<$W-+ zMY~xIo%1et*)?bT!m!6iK|eob zv3+;1Zxo?25Gc8AqdC&}PB)FMRCMB|SZCawn25GY`AtDbRngB9@jU-U;CtBfV~0)V zqv>l08xL+TrL3Q$isXC31IKDzm43R<_V~#!@R_)7+`7(UdU6dHlQZ>t+NYsx@f}S} zp`L7zC!)O$nI=K|x6D0@j-zF0hghng@+z3w($*1)@OM5-$@zX?cz??bZ@0&gFKe@q zWm3R-o;iSf2nm{rONf6TN}JU7Fo-iN57%YWeJV3cXKgZ)Vk-chqyN%Z=ogb%VY|70 z7_7>=lOK-R{_yd*1uq=BPf7=Lk=Aq8xI~cSnT<3QO5uk=28w}q|H;?wWRrXasI}Eq zS#H=nG7S`M>;DlVJU;a^Vk_ggvx9~{_)`beP}%hy8t<7DMDctW@*di+IlS6HoKvRSFQP^i*>A$;=%!e zbsX!FHLR4zwTyFEQ|;Ytfr;430cE9AW1StXyT&8OX45t+Vy z3(Xe%VOXE#qH94pVAAmZhhvB)V|*NUeeo1BUL$0-vY+mTc=TQjLNPtuPU-u_SNhYJ zm?t|w_%l8Cp7^VGv?>I*5>Ufcdf8TwnXUH+p1;OeUDDf88?Y91VkR6FO}fte;Cs)G z+)G~a1%C~|Hgdh;vt{hc$;qM4=|=+P;Iw$aXb>=MQ$RRqI_NYh?GB;w6@2O_*wG-0 zP`f34fRbQCq=%s;JUFUFa1!t$j^es30SjGuYWqbUJ+Qs@`9Ha!EXU#~q$YN=33_92 z>6yx_jJjFUN&Ps}<6R%(;~xciYU*NT5?p1nx4MLB5~{s?V;{PA`B^o8?&0N^G_j%d zWR+ErSsZ8TVyDq1CBt?tk{J`wC#zc4cn-V8(Hs4pp%1=HW>`a5f$?p0=0b?4kh*cw zs8%X7gX=Zp9+0c@W9^3lcC-`IT*juGlfBvLZ@gdr=dhlDHDM`N2m}AiH#T>M0zZg9 zEwAQ>a`-?6!(o)}t47a4sBoM7)DwpRh#JzC@YjptSiw_qAqrS;F~VV$97l3Qf=rtH zICu0>7FkH4YcljiP&LdvJyT(($n^d9aK;NcP6lJ*M+(Jg!{JdFfGf|yUO7zG{&iKz z-83X&*YR)#s>AOaw{*^gTlRspDPulDah!WhP^UTG!6keyWFe65&zY4xgrHtRt_d^e zBs9M!2i{%m`u*RBLV<#S0OnP9W_Osg%!c37uVlRny){!TI6cL2)+mkP8!zWU zh&tuad;vrkEYtUO2t>wkg5q2?%-KXHaZ`ZTEwU~o+m?@7s3>NHN~kt?NLS=Jru=L4 zlT*q?Yl7W*uve9&Yr#EU+y#!Z`69Ltt*|JfWlpnln>cnwm#KF&&s4cYwdtb4Mp`YG zhD)0!Abf9(Cl39n7f-bA?hHTz&f=x(DM#0pv(ahnbD%d`ZEkyrht1$G#=&2e>XLK-lr9>W$39!%9SIl~(*2=nWM(`ePS9&{q}Z2HZ1YuYxL zv_7CHi=ok%FejtF++`_k+minLGx3aE{=jf^UklP5lFi{1mtOZ8!{#e1Rt|k{oarF^ z0m&HgZJs=TJ)%82{XGXC8nJmxqIk^VFgo)d^HhoauSAjX{~?OP1Mm($Vk;4nC$5rA&yJdPASVxOiQh~$W2Pl(C?e< z85$w}h|Rz-IzHpYAU8o5Y-3`+37x*5Vw92EH_}tP^_h7^mn}Lzn2x)n9J^yH*yT#nL}J(Hk&@5f#JOt9_b;6ys)A>@A<+_}QPd-xJ07d!mm&z2Y` z{6mHKk@4crFZUoIy!-j!J_vdmykS#@W=+qXlO=tp)xk1M8-pC%K09s~fmoHvOf`|@ zfIY0*Tm4DU-}zgq-Nq3~VX2j{Fh08W+8O3pj?Qg;i9tLIbkH_rqvhmxN{U8B_<5fE zpx`s`wI3sgtjCl~$5qnI&ovHVE(sZ=(lkqaEkT`li;GGuo&0cuE}4pL9Z%W=OgF5> zWC^B)&K8cUZJqS{Mw?FC5fEL5;b5`N#hb~p33Ma;=h7!{5a9Qb;?shC`jouSu?%jq zSuwNinBZ7bHEXV(C#_=)tH5nRm5us}2^K?b;)NnT7O**rZ?~0RzKw?t_002HwI4h9 zYx5Wz*4U(6^T&I&uM76EJBIdib!ZBZ_vD(_rR;*0I}rYg`6{%dq$I1Y3C9FlCJha) zS8*{@WFi0oD%1q_NIr!!yxyi?ZX{5e!FBHJ1)687yyv}O-c$65SYJ=QN&3c8RgZ^) zo|@kV?X#AHcvL{m$=ls^wi1IB8=di1H3}wvtnqrPwN2FF)XNC)8srKjEml?5$w)`> zuf+N+^%08Ug*v#{3g4?UNIy+)--}4gof<_<5{@DqvjAF$1-AR+={jGmu4qPNBb}e3 zVru@vB2utxkZ6$7^C9j)yHBm&jWKhxI18nC0KhY zrG9{w@*{^82R@ec>xBZA6!tKd0uKynI8o}?*I5G2r36T1a3b4T)sgNozM*8N%R(7mbTVZQ z2(K_FeX6})U-RR+G2+SQP0AV*PMuy3qlYGnkL9_2uFmymTVvlVJ%`%-hAd1Ip}`wX z9vtRK4OcqBbbbP4ZK7fFNgHojGNW~8D|p>O z?jg9}1q@MtJ(qu1>;D4n((2vASz2T_;$Ma_EYVT4W6{xPdWkmFS7bqms}XW>^dM+h z_^m@6sPOQpw4D$`wCy1(Jr@=%KPGn9@`=kse~5h;$HGLS00Eo)BZkw7w-lP21I;0s zDA#EQPeRitqN9hp1P4L0R#gG34N^(-4RW0t*(WsuAvN8)th1!Z3qQGx@6AC7GL4r< z16Pc>xWOQwm;l?=?3<(Felr>1`XZe@9FD1j!YYOKrNz!PVyTEJf_%dy?zzPal8j zMvcN-hRh}#&8|E2;P=Nkb306vut$W&U*fTh1*w~pJ6<>a^6?5M{e3_-(+NxP_o@s9AJ8&?mA~N3Xa%)Yqf~lU>?}X{(HF^v#iC^UjivPso zj#CQt#b~6~7&}~Zd(k(jQ$MB7c^gA4#7_6-UVErJZrVjrKoAl#NmY1zf+WBF`Kh4K ztos`JCAE%n$rS^q^5Go+M@M=`^h8IRx?_d61_D*(gUDgW9_%`*_P$@@jOw5so3_=% zMUkc*mR3tvM$QG&j$zJ)=1;Cmj9^^xuPBe-;CXpe<=st|jTRmSI!*R^x?PaH zS$hp3ywFl)tnxY0TF(ZUL`Dfs7iCV{l*!rfJ#7(6;Rm>X@cZmah7~?a==aG*-?G+h zVo7>qY4K1C_1L8qZ^T~l7Ip@Av$a7|$Z&qUB%#)M>i#hf<51{LBy@02d*e;iy{TBY zA2=@s!gw1J12L}NBmBfCC-`XXttB*Sgt&lmITnY5Yg(cFwQ~ELXE(1eAJ_WU8$#`a zjXgX&jtxG_94frM<=fv`k>_<=b)fe>l_J2uQdqKg{ryMit(v=uyN8>MqotFp!{3pr z|1C~cZAB471=FC^>)5$YHCXq@r>HY!>JXfwh*?BLO=UZ2XpZz0sE;Y>yxHhqucV$~ ziP-Bn;s+j1rEu@lZCa9MebT=F7W6y&^Z4gt(dmPl_kQ>n6X&UK5011><(iH4RZe*O zIkq<7*Q`|Jx$FM^>F<^2mE{Q)7ezl2+dHgT#2?|loM6?Df!ZuU#pqlJNA9D|z+bRp zTE*iFUaR`^3!*aAWD=|kw-qYY+>;yu2bZkUZ(_ZTGXCXxy4YMo`wxOl@ne9`PKt9J zb~*WEU9BQUly#GvqaZzgc&SJ$0Ni!mnp74X_C<7 zo}N_UzYm6!)8q*+)Iw<){*tWw^?@ZVY#EbY2#BY(iq!6khuFw|kF3-^`c;N-?+VrFJxZ{h0XVBv1z$|UmteG-5FgMW7WlGRTXF+?z5VG)r|Xnzz_ zlVXcFh-fn!>WJrm(oFqQPEydF;z=*}d-hZ@b5rjq)|CAU!k>C4-N8;*m)xF}&uV|Q z%WXgN@#SEc=>w8?Y2Ig(p*t9%*_+inv9%w2E&Wg%dm(U7wmY`j0LlZb0bmWGj)j~T zeQn+aKK@mf^7I6=A@ac3D#k=j2?65y)u(*FrQh~-ebedkXDkD=fjO0j0~E-JzQ8B> zm7Nue`%iEe)llJVx0!*HuD`2#QcjjF^Oz4HIho${)Lz5%}eG2=VdW6uuvETj6YsP|ZpodC}#w?{+G5e;jVPgV6@E zy^^^^55uCebD~L0uS#6~H_iHNeiZf9J_i^xfY}>dF-fqCtx@n7lo?!eb@|PjkWou@ z6=&po=UfpQJ;lfie@gRF`5*ia7G*#YS;CE^2J3~=-@cch5-3v8XWcbF$MBejXwbXH z`U=fWmReM5mXpXCOn=j6GBXBUG5UbAMKZ}Y3N3}h|^=vT4%|2DlfRsJ4GGjgS%=R2(T zONh>dt!QFSYmu8z+La}2lrXClbm68-1^rn+QHOkjCPyFE z?Tmc%Fh~7i>?vGfAm7v%eC4^aNA@Sf9r4*Rwa_iqdCD==ys#S_7NB zu~MBQVKm<0A-#bUNM70uWYzXs3WH-@3Z_STc-jh<^Jp}HeY;jG}94D6<)d{ zYc18AeLoG%3P&S7UKZp~FE$6~JW!ZL(5`+%!TEgP=ECmv^+ZeZ>F?Hlo(<&F2J{XH zMVkI{6^D|VVjuy?7mt<1lRxK80M4%tQiy>0fH~);=$@E+2Q%8`MzLVo7sw=A{(Vpr zl`?f#Wv=o{1mwy}`Jnqe4w1rAg#88*763jvSG?Lc6yY~sd_&AKnc7AmIhz>VBVUJ1ic*AgWF=Y0&hnH5wi$=N1+)5+;RT{r*ZI)f zUg_A-ecgS0G#sSg$4pZ42y)|!0~hCq_yoHjN-srBb=pEOS(goUYBBJ!2TaMqQdmIq zojSipE7k!fT_6(=HkBB+jFPd^YH|x9M#stbe)4{qK;soi&IJWget!xQ{F1FK2d&2S z{L-_V%p$y%Tb>?ECk$IjukdXfXhJQ&4ZX8we3N<$3r6pUGu0paJ>5EK((l_z)*#xJrJAZdE&RLhc!rxKe`!8GN zLjM=aO-<}g9L+3DolIQKnMD8bAo|zC|CMd8Y~pBP{~xPSnhtIt4a`7C;?t1KCQ+kk z2abgjm<-SNm@GZhOyT7;FuMvVmdXxH&8XzBL5sNor9jWy;RXUZ%klY(Cn)!4wwQx+ zN2E|@-d>XyrzruHgY}y%x5t+Yqd*wuNCOxsK(lQMS<_uqnGSO2K;94Kgio=k_J=)%UoqqN#K7iMb&SIm0!6{Fl{j}1X7o1uozZkQbhB!0?zy^K?T8ubn zgpPXh_ zdNI`~)%R=Fm7UyWqO;}em0;%$yc(K*c+Dnk|JhEW4R9E`KT=_NM+=!&El_bUn<&e)V^{FP)m z`wp#Y+bq3+2W;N)D<{)XL583%X(YV&G7=W1B19@Ya?KV)#Bd+fZv}!yQ@!Nr$4!mA z;PqXuKiaQ<=Cd1)%!?pt4G`S zK?QZe8u)+GqBf7@9E;Yd)T4BeC-4A*6LtDAQM_y^OltkGSTh=bbYvVfksQ35PA{>7 z09}(YYR%;%uo0;yO}UVAIqGFpkyx?RB}EWFYB(-PxKF-(JE4i#ts-crKgYW^E_~a+ zM;`6XV@NOg#-_1u4c`_KSIPnMUJ{EcyqSUG5+*`y<0JjrA~1-BW@}V9Dlk$CaXPgt z$bJW-hzsyYmzKk&B1B*Jx=Gm2kV>L z$gh3Fw6d}edDADeE81Fyq6ddUilZLpf!WM=H0JdN5cs%6Ce zc)X2rja`S`owuHCn#C{p<4ZKJqB=T#Lp)iUEbyMpxpS(CCZV2Ti8uisj*||F{(>ug zYrnBM6Vx~XOQ@GbxKuB5shAi!7-U4|hstVC1voiK+%b?6;ScZ6Z;Bm* z%B=L9&kYpOVvDZkYHh2hTI}}B^lvapNvA)-DQjDf&^8sI200W+$vt-f&8lX?YJS1e z5PJ&spfk=r$Euk&UwC^Ay(?gbF;!$}@1}r~HZ5Ay2f4bU=#S;CK~{c_72|u<5a@7&bR6 z!%pQczj4WJx#=>ZA0l~(uAe}}>_UKg>B2`roRIJdx^SK8g-yO#fExyWgw zN;umvNYYmOX>i9j{Rk%~pDzk1QJZiV?T;0?hqRG*pyYh^C1}4b>Jc|=T{46|+aAk6 zcs7>F)JAnrpzn2Qp;r4fc)oOC0%MgnIv$ryNYW*``l!O9DsNlM05LAH;>R+jX4JhK zky?pc-jl}ZCWj6}lm?nUz4y!CccYVQ8GEC5q0Ii5LdpDZ!S|nT(C&SU98&-)tayyN zk$-?odO?*?E?zV~wJC~(Miw$5FSn!}L%V*Bqg{=8aJ$-UK zo$p{Z-On=U<@Gm44}A{aq4CH9Bn1kC)X$KS3Ph!crYcxc_bOF0)!D>UCr(x$CeK<8Lg#3TlG^w^Y4$5pLpplcLwPchigs064j z{ciqx!Akxkm@Lt_rOza9Se)vKJ3*So-O@wYXz*^Y(zlwnpFrh~T&xZKSKkU&e&vAz zbN-xVn!TPtVrfGnudhJapN|OH7Bx;`u5zY8F67k~=kS$bcO{M(y%q%oSdT$w?a0)% zo@GP>BZo@msAW}@bJp9Td9n=8`2qNIJfOwln-c#pkQFfGhwLL*XGwRUj@A1oDKRp9 z1mrys=Ww5ezca#e3%`=0qW^19F6nSP+4@l?hDN>_{su5OHvi0D7>PUno(%Cl%$0u# z|B)oYb_`>9SK&z6qP_lNJ>~+GR!Z7zv?ISR4k2+?CIMUdB0fs^)WN2`tv!T@CC;tL z18-4YqrTa^KK2W@ls}=X{uMdWVbT`x{5*3svLYhTaP(sH=i@VlQ1ut39RIBqLsXS3 zu3}#Jkz)UTs>yn)0_pdG2Un6t#&7Df-9%5S?#gm~XPfv;Gs||IA6itbv=?#X>8xU9c<1{~60co0JmQ zFa*6MrwIw*HdrTDxDf#=x>NG*^wb=s0ppEkDrdSO?9lkJUpK9eWJ}NW$9Nw zmt#=u5WX$G=It0JGjb=7g>tegIt5x>yad)|fCs<1_JuzemMZp_oj7{;Xf4TI#GoC)#c8px>$oB4pjP`2yM_emW~1wu_24*=~bK4jx(tU z*LOCJ><_<;$LvHvNyin8XX`cAWa)rSq#~b-CFTQ2C&7`z7j`io3jGN7+Psi*b`Acr zAIKaOymBV{$aacUmAzxKhp)sK@AfTW7u!?D300A8R2ewVLJf@3R28Lf zB<;!z0p&ADd!wm*fme4v#;ndOBdR@u=)LVDr+H}3LNkBfM7fmWIWLw#WaAB+ENb@q z^ZRsv>G|nphw76|$MkeBv+j*(or8wN1X2~ES8IdB;7;Izu08b^S)a!)YsGX7&^Dml zp=*qx-a*%icBStlhdXOgtdrJ>>U9(ykhhQ@2i}Imt(Y( zzcZ>)xASO{F1N)x{>-h4{ukdXyIu zHM6gpk2DfFY;wW^(N~)!P}6n*L{sdY_A8S<1YXWc{RUw9b{1IqRUt{PLFNrX-oBES zKZA(B@l7u(Epiv3^MUV`gp$$IL`^83Xl8OQ3GGXBYV+HA+$Ywr`q&#t3>I6roB==X zKBRzIz(;QJBR$;Kk?86*qpyXcK_(m{DIXdM--tt$huJOJ`FVB6F+KtKhcHN?YBh1| z(=|sL36xa%9%qjzs7Nd0cag_wn})nvUeZO3ZjQScQV1k|tgC${P~(Z1m7DeK{A64c z;XGCe((WNOaMNql!S1rvK}`t8CO1u0)<%jSOGqe`V2w)H#L*{&ChZ|UQ;E(&I+QM+ zH-#u~(4~9o@R*)M{#=D4<16VKJ(;sQBAC!R6Hw&35&sI}G0YDVK+FsL79yCSPTaaf zTO)D5II|*uM?;GMIOrnriNFg7^7o+9ltV?AP@!CYTe!S!5oZ-uE>U-430+8G?Vn&} z=_~IzxXha5u0G;NBriUyA^J*WhadF!pn-5~wNvst=m-DzxR~u9T%4``_FjfXeQm=0 zSOY^_K&>u9zl^;rEH2LsvYuwQLCzQ6ojUUf?mx+CT?^?-rUXTh3w}be$m%2$R+hd> zSjkRbOMl#7e0R$4m@n1-7H3S&3B~X`3v3Phquec5PHP^DkTYv9O^0)Q<*TdXq-cVP zckIQDQVj3qZp?ReE#BQ4L)S(eX)t5wN%<;3r@Fz;GrqylcXqB8Xn3%qRSCrZIO>^| z@eyI%)FhEa2N6^N2PkLfov|o{>a@{5G;2wIYnBZfOx!l8)WO-}t^E^Xl84^1y0M#Y z^?+eA8#=_iz}dHoAC~gN1$Sg>BCpsodaD~XE{KrANh5Sc7F{xtL}6>w3lmFw{3$ZfgZ7`LhpRtZR*Xwk7-zU~SbSOtn=9 zjI&6swzX@U{8Iu?49K?UEo^cymHYlOMODugB}d1fL)?_njZ%P>GqHj;{lNQ*RWxZl zA4~>J#%Pg=D!k<^ISfs^tr*`ZHQLT=vaeQP$?p)4zHNGn8MHI}vI@()DVYN6$IhwwN zsbq9SGxj-xTl+fsApoZe`1`cNHDQ6Qw0MHL%QfHW_B_d~QKUj%u4bmED#aixtN2>X z1E!<#hlsLFAUUo8x;r*r6&Wt>IH8$!v~xn!2H)r_1~Wmg&|xdWr-F8@f=Xbo z@2&;?PocYnK@9oCyTIGNUI2Q!cWIXnkN$QE^^hNZ;5mnkp4gjkp5r!k;-wf=+8y}z zfMASBhu8)jsxYMXM3z(U>?v~&Z!anHUTu!v1J~0hQ`Iis;RdLRWRWzE-M5G|IqXPS zXr<+c5Q5!LJini}b!@|fbDW1i-pW*{o_EN{=ljL-`F=I|{boXO{tGKNyy>9kGR`R~ z;~*Sw73<^R{rFN1!6ch@>l~(_TH`aeSjVnT0S@2=gh^iHZYaj2j>V!sJsl1Zqo*?X zGuA|xvsj6>)olx)G59TiZtt>@;(No&NHxqHi1_eC?m>8SQWGVjujTwTf7++v{ryI! z(#~_3B6&*89Xt!C*93ex8mj{iFwH>M>>=xEm(noD43j!H_fUm|n=fdmE8)8mI~RoaCml%0RjJv5KTZj@h3EAx5s=s1YCf8zfkK+h&qwM;jqkZCcfD?~V&f zQ9wFV@waKW!0eZ>87OijGdO9iF0vO6*AD47TTJ1XO#)cygy7v6xfc92BaxEyV+VEg z5$tzf53Q5}3J$>2l#4|dmwsfKbM&64jgLm{C{-t74vBTJsQ-)CX*v(;gsrkt+|ei! zX5G0WhGIEl{q6_SL94}wWo<4qwV#DkRCZcA>DlNS32wHHDkqIcqh z-#PD?rp`h`d;zJ7^)Dl{v=ca(QHkWH>)q8Bm(GrAak#S0_xu^_l-IRCg8}ZxK~qL! z@{SBxv+)QzT_sA_meW4C!xI0fY#5+aKhd7d{_%@D-p{CO1bLF?AyfumteKBsZF~l6 z4i^Xl7vQ0JOP0V=apkV`Re>f0(i;U+dkBfnwf%XG%f^hW816zb3xMk@Gn-8DAgjLb zwb?=?Od;>35InUIN@g?pvsaE078Y0?ie^J2Q$NtOA zYx;}8aER*BLSSNjfyZ=qu3+tAe!9xYiObMWBZqlQVGD^SdT**x4|g^!_mvi8%Q)Tt z-t+PNo|)U-_4a`|oC7%kKrt07-d}+kLdBh^*;4&{WF${C1qn;P2vU!Qe0-=MyKn~1A=@L+)ln?Qk7WqF;9QQKmm8G%627?OCc zntlzbs8oeo%8=%2utjCp#F_&kx2%&9r3TJB<0^;p$lXzel+3e4oq%dsF#TdVouSMC zH1F63OyGj=t&WZJtq$sAGFz&*u*JF-fl!p^?!VT|w9m5%T+}{4Eg_=dgBA|(Anu{- z(!@o?x&(%(s$rwjOrq_ays0d6Q5ky!ir5YOty02MtcC( zcB;_0Cj{TR=XIe{A(J=WhMXkZdH1iB`#%d+dWR$jOKImtZr<^}18HJq<%VKGy(Y)d zF2iymwLVyaqkdGtG01cpf&SYdxR8>~tD=357H;CMt-(NuJcmiV;balH$~d{EwYp*z zy;n-;5}F0~#FX@RWLP75dleneI;EK!`b*SUzj7$B)IxT8F1AZv(g7!Kv|_CQMVClG zjCsU2riiMD>JXn%k$}{Io`6*C8GM@h>x%T{#O1>R6dW0Oxv=Xng?`LME%Bn_9SInk z@{3Wt;Lw6uG?7V2(m0yzQY+c&1tdjJN4dB8yJrW8rKL?C0vG2r=^vO4RzI1|UKznt3!;2!Chb6}(L%ET=kuy|5dlq=xPw(HFA8=MzJ~;YkEFQ~ zSDR!BQ-3n~yuYxO%pMC0sP3FdLcoE8-0Ym0|24DZG9Vz!j zRVjG1t1tC`Vy4wQH7N{wn@IH6{>)47`}t^x))kmKLj`Oq6hgSOY-m5YLxIq^0xDt3 zb5?)W@Tq}Gaezs=?sXqRKUG@mQV&tBK>zVB_A-rSJSy*6Algn#)CM#Yv+A zl~TacPj~Z;7ycew82P&eT`QmZIQD)}cK-J?f%Bi5kgcxw*9+BOQ&LJowQZ}t-!)+t zN%{jClLRy^H@5~ZQ?#Jt99GB?SVq-(UT80xc;~ZF57C}CCqvWad`7zY)Qf-npX}$? zn;V=@I{Y)!!^}GOqIG5q;%i7%w0~*B!cO3Xt_>}ntk09@+PfyO58%%7`N!(*uGAZ9 zdW90$N;8`;|I|XJ@matEL^`h^jN=}w9(5^1<_E>L?=$x6d)Z)7!H2z%MWyx?-wuSl zS9IcgC+}zPgEFu0Y-OIM$&5}wj;+w)v z1S{6m{yF76L2+}mi-#jXO(2iU%6f;To5Uk}vjR*97(D-utlv*9max(U59yY%WuPRb zb;#RNw8QIY+tM3%!8!aXQqRHN3z*U-CG`uFLrAB$OKjJ_Y5%5;7?TH+eOGTl;D|$c z09wpeF4RJ4)*<}39v6Hwp^LqN!mzjHo+-G{hAh{Q*>8UVU}Z)I#gX4d-Fl`5rDe#= zh5XK@#sF@ew0!Xc?Z*zELlZ*XUwvxnvEu-Xc44>#EGDYwsq+Z*4VZb5Qa~X^Rb3f4 z2ANMA`5|v$+r?~~|DJDEEC&r7YS^?J3Jd3cabBs!eJ{qRw-WH?tfIccP1PcavMvXU zpQ0h!@gVAGxUx$PwUIwqq{0QmGfSFb7B&+F95rOn5ofEYNeI;n`ofvS-2-G|rDJD! z)w8&TE4Y0=xnIGtZWQ#~+%6PCFQfcskx!5F=>~e6}?QC4d~_W@@yDwTpoZgjWQfC)7@b&mZMHgB3XgYK(S*C z`n!Wv`GEWDuiI|n|DGUl{?q*H{nbHw{mc9#sSB%!w`w;qj9`n4e?cX-mX0DJ6(=lR zLBn1#_|C`hu0hHmaDT$ z6(2-7BV}@%LX*gaqwp(dq^H?h+PAeG63%*u@8Ux+!Fl_7Os6)$qKBaMPk~!NRnQj=hk?ol zXwANH9?`bscpFw@N?a!3jJ*rOCSOO#Ae7c9vW0%}5HlgJi7i-FuBhd}?}9dvW1MC< zh$QbpAIHf6y7ncHR2J|VxyavWxqy=2X7QxGz`M_W6V$Ixjt|3?)Q8c_doR8uE(8l$ zHI|lA=<8EhHMQP}A?su27-e1&k7fN@Y3IJL05BQoVgBq>(&&sw18XNWk_;sZI%YYR z$<@xGy@5SvjB2R`M^9A-f$cMCRzMIFrk|29qmidxlk^Hp|h&CMG4G0I;2k;hHrZ;r=1UQKdbO0I!tSRH0p$Uj+l<|^nZh6g?c8inF$OsPTDXa&z? zq3E;wx$iOb-@XwG;*sixzOT+w&yAazIzBA)peY$NHgq0zDV42S?`iUvo`$QJbC7ri z=RC75g{s%e>P*vv@*F zrLN*8Ya7JGU0$mDE$K{iTff0TV}HEat%H?NFMr=16Yx1^Mr_r9PtsEl23IH~0J~I8 zZ+>J<5PW4g465+s`N|Ojmo^j6dx`ozf@0+oJ{C_!>aTkM?RL1@aJ8-u9MN3s0S8w& zmH5tW#D|;Pi=Q&{K})=ke;4&v?v-$A-p_*mzvTRX>mtnckF$`hy5jg=(id0(w|Uru zWLuL(k$}#kVRA-Mn9#NbpJ*wt3a0NHzZcac7&NroY@s0t!bfI$Z$dp#4^&}5(89y$ zt!Jla^9Z_Gb_cv&WA(sR5S9RKp)3YPX0f0w5|Zv)$HgmJ&MCjf&pA&PTCL2KgroP* zLI~|LVYnrY8P+F*Dt#=QSu^QIna%FqFsdzn!2tm_*)yk4)| z+OE|sRSM(G%SAtbpry)ofy(lAyn2F|^WJVmJBCGtw0w!%0CZ+0&m)xE%F>z9w+=j+ z+<&-ZDNt~L+cKljEfE%Aog9n4w8M}6Yj4wSyozVjy7w-)m4uqWXQP=9TF%KN?0tf0 zOi4`y8BmefTv6rDYlXj4-xjcY&nogK2l`h>JH4a(9kgUk8_j=efs;<)+iRt(jP+#m zGXor>nYD{&l;+MXlcO?)bkuHr(uyDObri1Gd|EwEpq`hPsh}^SihOimNYhoe?9@ki z^&Tv;`XH6HOY5Xr+T`3hA?@QY>id@c9&%l3>aWmJW5l{dJ~elXfQ3lJ^u^SjyA0=7 zdlZ)C*o}!9k8wK(Z~o4EX?LUZyL?~8Z+Rat`JYEM|E*gk_kTJFjT6tvv{ zqro)2gSp>9<(HxHr!C0 zW@47NA|IxrA;yLqQb7WKn4@7ET8x@eNA0x5@~kG z*Ry5z;_gJ!Y){9nmDrEB=I0PkObI!Q$cWl6O!?ec8{4kAzUh=*U%SoED3ihh9`feQ z)K;JQN;m74yyd?7Ye;>Es&yhYEHl9c;g(vO6+pPX&vCmA61%Ct{LCY!#c%Sg#7}W_ z2&(yviM##CFXoC<9<4^t)Aa2{-BhSFN@Vm3w!fzrwTA8&67~yE! zW%w6!q2at8vZn`S)O?H{dHb(HYPl7>nFyYU!?4$^BNwAqUY{d)FCnoBR_7R6DFsa# z7-3D4#z-NudYj!M+>VDo=o zIs6ur;g@3}dr}W>Y?p*IkvG*Dj-?xOipr^%k_%`YneY5^g0;+Dewl4DlMJ!Zc}ns| z7CPm<%mEiK*&)4O&*cq2cbmJt{XjpSk9;jVP7jN6*{RPqile+N8JxJ#D%7!z-BKf8 zK84nC3X?#SyuPp$sYFJy1&0(hb%GMRtOG<{6jG$!q^ioRVVfOh^PuouMV5Z5BhBt< zQ&@s`^N0J$r0&NlAUnWUNGeT|$I2bc8VJOow7KvXQbpoz47)C+&o#6GIPM)lGT`!0 z-b893eGJEEweZqnC30jX$!~9qRRt&I1HB+NcIqneG0Ls%_xO3NGMZnc^p8+sURj%7 zP#VswuJue;gdZQ!ng`=%AZ%w$gT|Q9Pf5}zqLXhhssuIg-~a4jaqdEJvVGvu@*hKI z{*O+0u79%~oB| z!YOFPP!5{~r?`CSiL54sb1rATUd;sDU(I~9Zht|22INyiGXv4LP%k8;)$G=&Zdux+ zi;P^$&E!@%R9)^(tU1!vkt~1)r#XIGPVI8GE17g1`NJ{a%obSfV+tpAS$DLui%vqq zXOq@Cth2tMhDUihwfBq|C)%%QJ>Y?+$kMTfmR}`*08UJlG+T{rFBuY|7NB|X+tYeF zCq1)X19r%J6wZ8bKEFMtr)LIV_4;D0K`xFM8_SqZwo?2f)u7fBz5Be(d@m4b{?|68 zqcE4FUHJ#+>2)vhn`Rv;Yv3y$yNO-?D1vPP!-Gy-ex|b}b{HMxQ#4%*#e0yVd{!7Z z4hI;btc)087h~aAO{ZQZV!wcRwcP0K&YFYxkdNzCg^0|M_Uc}&Tlo!o{qZ~p5&4p1 zxxu~wus-)Kq=*yNPZdBBJ%NB=Vtpw5nWa;&&%~%y3q5BlQv1u)tH_#6QfVkXN+zN- zDpImFVz&-X!Ifj6`TWXIAbAR861f#vV->+ks-i~9b+Y-|9Q>*sI0Qzqu)8fBSM4No z{QFF9zjk~XtJBGSr)~r!YFAt}I$1+GB2yROj;Zrl0i>9d&mF)@SHmwC@+hZS0p~^f z?$HOG)a7!gl{X>D*xAUe8jW_{Blo$tt9IGQn>FH6<kV%(sf5K1j>tbZ$F?Jit%q-5!{mFB&htWA+`&b zjFUIO+-iY_1=ojfoDc6}zX`7A@P!2J<-QUUwH8sT`Z7HwargD^Bs7aQ3MyUrjbM5B zqxsOkBS+KyB7DPoyM^ZdzPb?Y%qJn*g00A;EV-(foMe~!NdRAe=?K>rCfqL||80}3 zOe)-(NhX~vH!)DJJTxubV9T^n)fb|Gxtf_g^52QWH>FBilE+$@9UdL}UU;Tdj z`GIha)kWipF5Qzdb3hK=iw++!WVAK-5ddO6PFhe;-x|9E%S4Q|aPKW0l+3KQwM~sB zX`%ru8yEg`2;e0YYYIMx0@{-Y8>&;@fiRNnZyC)7` zpcD=i3Dc~OLIDvc2YGE3A0h*~diYq8H4Y6GvlYJ}f}Qg*S*xvUX7SON<=4^=+0gCi zRzi$4u)q{r8oT~t{tf)qz^`+cP6#3>i)iSj>K`UBk z5RY}(Nn=zV8*Op%{huq0qt17ZnjdUL;Ny?`@7V~$|G}i-zs|i6;{a6kk8>~8p-aCY z-BTGFmK{D}K3$T~sBln-7{ZQNOUO9IVT*p!VP{9_HjIku1!EK{5>ZGD&2XFz&oy4~ zh4d%#J0*do2dDj_8e${&&PJB+Y4`3-9^hiiLd^nrc`{n*W^5Qlq3N zP2(dHha1g}bncSIpy7cB#89R#@DSrJ44n`_+r%YQMs53?6;hV00x=WweSI>Ky=(zk z2d&EsuEx^$iTk{6NmQ|EwGm_C0c0iCCcXB&in^fBNZ}64n+}Uimbla&Mwj)W@}f&4 zyMMk3o!8#|A|yOZWj)g~bFMlxtptNJ=F;`>&bp@c&MSX3bW%+ce#yYIsnk1oB(X9U z!4`(RQ*mL%?3*5{;?_srKwC0^Tf;=BReOp32Mh=+XdJVQ);g9F`OJU`_I;z!2nxs` z)J_SyJj%yLoG$}<0|k=5(s=xs7CZQhxtb`-ofWq&$B%~Kw$%2So4D6JVVLQK0X+iD zd2PrHpjq1E1_k-F=^9lrWK*R2af9uhF?{2N>(rp35+X{lmC?F8iv_ctD|f?%zm{U@ zKX8Mq&=LJyZen zO&Yru&|8cLloxPYBEE4)km&xB5FQ!{hn04R1a?gg)vyxb4|;MrK}g&0szdhBk?GHJ zj&=X(%I>TX#W^v)SygN*6F-_PuCc;pN@@$mM2pT?5W!iU0Hc8nDKGOx;Y``hJd!6~ z*LiLtGsYXG7eCDz00$oFrxit<6l2rXMVS{}eG)*PUqYdY$sTDV$IQOUZ(7PsWxKo!y7bsPh9&8#CxJq3Lp3$klUKW+(I z97`4T{K1(pzj(+Q^cJ(}5mg_ChmJzrbMWUtKmHCXi$ziNX@06R>>QkyS>=<5yOK2J zmD6Iwa&K{!?on!!5GPd8p*S|l1Oz$93a2Opq zG? zKsgyom3gfeWkGFjzTvI^UiyqXHi=)#XL(Sa>CXA+ey;CS%SWWYQA>|<$PzY4jBK?t zmjbAz{UtW#=4teh?#sAp%`wj#c6jLV6=>2+b=Tw*-T@+`~SBvne#fuy1NADLJ&8pu)x&=!qUnWFxJy?nWYEIx+c z2y1-lV$!g|rQnj=cw$r%A z9aET$Jg%&~u8jQFN5Fb%*^aj=f=}R%6@~?*byIou81tA59^;Wy_M(dgUcC?GQ@yWg z?$hMLu7xsp{4>SUih}zmy<+{oc*t!b+&*D6PG_`Tm1u{3yuM-a?J;vd#eTxXVf>#_ zgwBY9=p|Qu8ErOxkqJFG*2U;vH53uDBj+jIFK#Z{QDnEYlid(Z>@UF{5Um1!VfFl( zklB;2)xp&)9UM_g$6ld$H?ZTUkjkF^8p%fsS!g${Uw#iCQ;2JyH`!Imss>Hd%Sctq z`czG4_rU$y^~lfVH^MxwAh_OjQH12*IGWT@^zdOhm?Tg%a2fq`M!?bVrTp+iA{_Wf z3mxA7@%7||waYHauCF4q65YX7Z^V~Co5h7B$tp;BLjgSQus)>G4A7!8i+;yR3R z*jk5NELj4-ZNFu7Yhe=L68Lew>&%DC5?sJIE5~u#cKYM%M)T|4#RcalYcz5*(=?)SqD8T^#?w_9n=W|7et88%d zBle?pS#u}Q$Qjy_yz^1$u+sM#n9Ww&Sj0TBg1NhkA_kn)g(>SMpbK<^LJ7h@(}4QK zgqJ#At;zb_qcdjlpsTh}k0LnYh&;y$D+7k@c*RJlY0An6;iqRe9>eX=(x;g!FvQo` z0)RFFJ))@)!@>~1Iv7l$ImrR6W}BbXo#5KBySzGUc)u~XY>fsJxkwHIU;U`Fe0($q z`D0TWtGessqIK`H&qsGPZ$F`0-dTrtKHb6lCMDjz!8yAY6f;-d19Qit@<_XuX2V(cZo>&7MN#GQ^f(0Fgx}t6J^|4~6$u+`^3ani%si zzoG1!0>629dpo9Z{@h4wzxrjNZO9(V^7dPUQe34AnO0+?1;1-5r%SgPMuA!@{o72| zwzC_QsT&T+n`48MmL7F74=`R0r#VO%dr1U7hOg#gmK^m0r%C zT)?<1OcExrzn_~f;us?xCFKZZ8+VxgDDF5D3R{25gi-Xlv~dz7rQ#;8+#&s} zr_2Dxnpy=Fo)LBN&^rPOP&O>ggB0Ih_O;hNTU7}ZrRTcuLfk0tLCEBjh%Mt z&O75@fzxiG$L#e+gM8|JIvw~}cb(`Qg1Qjx) z$V*S)Cty2H)%?Kn#Fm;7J+hMamb=7r?pr>I{s8N^4*36PmB=K4PX*E z_5c;t5nH=1}00{k_??6So5(ZSo51kA z^-s%&SYNu8D5p=T`Mqb%0*iMLQqBXd{7Co~M`Y?Gkbm}%;c%IW+tfNlT9&@P}@AQ<=akNpV+*V-=kr4qt#u^hP+0|W$(GHy^4P&*pgZTtP27VBpPn7i z9=CGaDJJ~`WJ4vcg)n*NaD$!9#_NE2Hh^d+&P(RzM=Bzd@C~?wN_|hrIB*=5uOOc( zhPs3~E@SyOR~+5B_YKS=rOE?bXz$NEfFa0~O_5g_U0e<1Ov+V6eZT5W$*VBm^AkdU z#SSD&BYschl?h9CNX8bB*p*q{CsEB*5$X-FfMoU>zYxGpAr0@+E? zKN}IMiV!W0Xv$4R2uJ7d6?!?9)U#NpbbtM|Jn3R<;uiF=0MY%A%aa2C({t|MW_y2e z0(nQXe{X5$sqZ-8ile<-nELLRr%;rUwa70jZLfMHJ7kx!3EB^OY#yvi%b>(|d}=gE z$b-MwY3NpP8AQDWhlYvbEs2KHq_H1`XeT20Ot}Z+^=Tw)$KI|Sf||g3>^_e>(6x{I zLh$|dSo72Ui&*$b!@8SaU-gRD(p^iH!&%#4b^P^eiwHC`3Ky-g^HLUd@Cx%UBYSmgC+Ut{7u-8$zTKRhQZ z0MCpT&`4710t;}gh$JmE`V>NA24Du5g$|uHS>HcuG*9gixreK5FuPS3b(ak!F;UbF zHEc@~81DdiWI}$R@7Ub+%rRwCr!|=?OU7N|Y)ZIi;J(YC6ayyd9em??(-aS`5NODp z>q4TXV?F1qf~DmqI|i5nzXQ~JLSl~OI04rXp;r%@xAQ=y!w9ku1K4-MrS2cw7|-&o z4cZVHNlDIO#@8hbYGz5K0hJwFU%!=Ytlxn-$iiAUsgKbOOO?-%Z=J$lSIrBpr9MO8 z<34_lcibqeJAvyqtM?a4wp+GX;`w$tZHIj{lNMbN5YN&0a zP@3v*L~C8=o1O{O!{qVOe8c29^*O}XoUW#VZe38gJfx|nxrR+^=J$59MLw%@Rcf;R znP^3&j150-!+s^j(s6t-mSOv5unbW&k@Hn}!FnS=E77EY0LIKTBAU{KwWfL%S2#Wuw{>ko>agqEk0`lXaky^4r>1oevta)hwmN>MVc! z3>OKJ&m{UM{5)nFJYozZ+!ab-`9@xNYNAK(7+()!EJ=fCxK_>V*5-%|X)rjF5cR_Tf6iz=v~7h@VG z#FI#5;HWzEP^44dx7$#)>^uv*kH2H}MNy<{(eI1@GraBXyzi4Gez@$3l^J6CWi7umZ5c zhGy-u9IGZX0;CsK#sR&7u2O^0V`BaJOaRH>L|JC}6ty@PF;&1&6rrCy2L1y1ETPAK zSd?|?P16ttt8uK|2Q*Rzio$^GNKWy*?+4PNb7o5ovHV%}k!-ajpN){3N1E7_(=)=J zUC|kt6!i)zm`8A!7Cp}9+rZl&FTiNdR%>%GcB@iddU`J8)$1Kj<4ne=azyF~-*)_$ zj5F=S_}J7ILye0nt&M=w>=S4HGI^*|daBP?@NH{7snNPhqg*u=TIj>*6NW`?ccwn9 z!M@u&cLZOg*gWpHeUXSFK5lkbX7Nobv9oh`zvjqkJim$`aOZ2a@Tt z;YBRQ=v(2n9Zi==nLACAiJi&7{G|S9*z%L^E zoPah{!Xz$cWDMX)dPSn;8UnQ@H83J;gr4Zv)GBJhGB}jy?{#lN)+qEUiZ)N0;9l$> zc2i#YEX%G|F?I;KK96n(ZCirc;CNSuP%VvZg?Sd(7krTzVTmH~2;j@iCo*qR_9U=% zGU&VJW61M&>CG_2&uO78fnVATzQOzhZyQ|J+OQvZ%lr?u{_lAE$71Af{waT%+5Hz6 zl{^huO;t^_cZ7N&E;Mj4Y5^r=Q6&{&KL{~s5K<6iDhlh`UgCBq>xnqdjEvTs43Eo( zkh(eq{1)4^dG#(Hmt|$%XQ&4#uIqDw=lq9!Q1^Kd&%j;JCxL|CXYT#>{(yIMA;!M% zg|UT>qb-leN)m?5aD^@DD=u(8o69wFR7K`-Eu|abS-2~9_7ZbB>HM|F4>gGB0Ql+6 zYz&g$qw}>7O?^hJYA2&qqON+e_MxyBka6GKOojmNG3jj<>p4*!>EFg@mC@Tv+-UDo zkKUoW%qi58)ubomGBk3QIISEbe)nb~jRW{|V0`nX*P6vt8ET!=Rh?7@7t3u1Ca|B_ z!=Hq6EuO+#4xDgK2!@moy^&m=O;XIcWZ^VP`fmAQpbI8*z>9i@LKb&=yKFJB1fZ0Nkj-sF~+y_c6gvfmGBy8onYG#PK?X z`HYoc$^7y3Dt?i#WbLC!;#c{149zzM7X9jo)!645xPv{1=o(wtE4sjg(qkK102V37 zQ((q9vlSc2Ifamh=ct_pJ4m|f@Kjq;6$hnG80GHIU&qGQ;B3S?yfO!A2s-SyAua*z z87q;;0T$RcnC`k|RQst^6enJJrUahAJspAiQ>!!5Ag#50mI?7;5|YWJAzZ*p+Zlq& z7SvOC=;;2nOAk5CMe%S{OB8(nY~j_Wq6!cWFH7G?26*E{2iu$Nrkodw1Rrm%?q)IJ zQd40v1?B3A$iumokgLlTQ;ec6pft?M4K=@dHQ!-wcCcC2DYHdyB+qur(+eJ?Rby)) z=HS9N;JfVPMzxmkol#eFqA?MSb*L28l7F^b{Np&oPDw@E-OOp(6OP?u^)8NQaKaV^i=`J)|~`tw|RpO5tye zf{Q4-V=`$>>LSIE9izPz`^(Qo^Yb+xjTP6_`47%ys|X$+Jo){hxKZwPI}{n7J(Z+5 z)YKhJTO;9#=XWPb2)-q8)$A!iAkuJE>=8peQ+a6(_QJ+fy%Yr(gZ|!Y8IyeYg#q%G zFA1TbOzXafrBIBU_fV84oH}NKG@`GP?v$P%>FU<*dy7TPR~RVLCqdXZ48bQZXodVU zSk^0?)+@f+D~Rb3%LpIK46I}9#3^rQm}%NHlwT~Ae~8LAnCb_l=_U2phGNHHKJi#U zxnbmKrcvOc;t-siO1r|o>85eaR>uqY7f^&Zz!z0rR=*&|ou@K=7zDNG;(*_C$kljv zZLIK~_(yDj1ibq3z&|H$r~}0ZLO<#et^cS;{(jW`!886_YVqGVcm9V=S*v!Xfhvg= z5H3bCO|?IaQCqNBA>9&=7^E`VCfz6wrXpfG`exdcH8j)|!rG1edpRc&?ulrO#r(N+bPiTKu{wp|`9`v}C{;{sI!jfgL)*vPTJS+59xqvcy_3 z5fZy0%R~59{-j*;u!|;vBQqELzNH(0SV=@NFT}#= zis5Dz&!Tig<9dNMrOvg?ypoAD#lyr>fL%+YaM;#qH=jwn62e29VNH-YFtFC`>K1o* znjR$g%N+tAUgw3IO&T;0SJh>qn|@Q_Q*x(K<9PO38dN`0nPAC%)uhDp)-wfiveZa@ zp=g=ho>8|C64>up$U07ipyV#&8MKD`>a=|cZb`>A&b$lrtp%Ij$q&+I$a^kT4arBi zgk(uBl!P}v-@;_chR$XCY&o+P$I!{onthDF*$ruGK#9I4Q=^ZO{VJFXb(+!HZ)NgJ z^UrQPL*0N))--==k5Y%%)>!j+-;Q028CJD#s;<6MQFVX)!}NltwVvkZ1VO@O6Th5-xcFw8C%>;5Loe+Zu11cC z7Ob8jwo3!au)X@}`iN(08Kuw=-zltI(4JBlPgb1X{0X2&+`%TO{Jgp*PI-KFf3tbkC$gXG5b_<+B_*)kFE%<{oQPX1%K^6%jM#}2|j zf%7lwU#lUjgl38K9zejrK+1^jmk2F!aE+o5f(%mxN)ilK2Uk}hjPD_drDZYk^>cRS zvusLcxp)7}VWteZI*44w)JJ9QBIP|p9D(N|v!Li@xZ=c2txD%_rx)U0ox7B3r-^VoHMtH$!ZTBJZ4mtVjXKLHPX$hg0>}N=(4O2 z6+FfzHIYTt(u6Kp(GqFY9p`=p}9HrwBgAw<&-mGV^FZ5t7_S?Sd^RRN=-(dLzv za4gmo=H^oJEHz1;)Az>rxe^N9cGjrFQzhB!#A;l1cY8XBb*LR|4#4y>MVyo})Mjc7 z*ya0{?#V+Z@MP{n8dDpYhOl6JT;)U4+A;6&rZD7LMkS@ucE8Te3rzdVI_aNCa2wfS zc2^>8Us1z2HIq`Ab5-P<)eGqyw6MNd#)-`2?X~KpYIFy;^q3@+*{&M!cnEn!ugcGr z8O0Kp&q`GUm=%kNaMNHnfemINJ~O4#)hQ8FVQIAT5NoV6zcpg(c3OWnwioiiEnSmI zBED)w0T9Co93Afqz^Xe4Dm8|{waaQvhVh0rgu~gAzjQj4BdxmZGr+v+b?8E0ble8O zpkQ7XDs4Ha7mK8Z*j}bJMB83kYV8OZ4#O_4REDj9Yg(r%4X7h1Ir!wIS6Hp36_zyn zDTxq&_u~?am|p+L$1Di8B}i8aHHq&cPvrtehOQv+&=|*s_>kAQ&ojf6BJeO20!9S@ zOf|Yy69Es0WOMgmsUbp^a ztszLe2jOD2jYrk5+WYYzmN98?V_gOWh2moBOle?57&RfqnV7@43>Q=v8E&|`ZB*8%5;k-+ zfuTs49xET&zOi13uN{L%boD0M+_#efe7rkS9WS*ZQ?J~@+<31XYOL&Mj|gw;-6;|6 zrIq~2J7V^gaa(DK)VPl1SZeCHdy!1jI4cU#ke-?ag%IKh+(o4C3J~FZQ;s9pRHZ>i zWl0Ca_bpdV9y=x*?Q#> z8!nZ{GOKIQ8C0^|V8tk$KiM};H<6HM+b!X@l~YU0-ZeUyi=@&hMvb3QI2IaXYF}rC z$o3VT^saR@tcJNWY@ZGJU|zczgT+<+rtS-?rwXiR&Wf&vV$YA8+Irpi+N-4Mv6!pS zN{+syCa<XK%y*Xh5i`JVyJy}{|l%V>~O60zaG?nrDrNI8+ar z+&NTlnBX~+}VR)5mEhB!|CaJVcjI>uJve@w&Zzp%_7Wd5N|LM6n22b3U|vAy%;w(Xaqw zw*a2g37T^u>dQiyp)*#$=$IjJY!_%efSjHHO*^iPA(VP0#<-OrKyiq5AsI{Vl>6bq zpkHzmDa$ojcR>*ZZSeuaZBO+Dq@Np25ei&xm zA$fkk-Ig+lvQaEriW?_mm$Nd5xL#=80ldp=nf+*V^!Hl~^7)P8DO4je{sD?DLT}O( zPnK-4CHZWAiW>{IGg;1!Q)X|*Vrjaal2Oy|0TL4S8*BC>&eJydoBExZE#TzUXFMTu1SVoi}xp4it2C`y87|8J&LKUd!zQ4vZNdDLr+)Cc9m zTWLYrYxXf(H=aaq_Y^_8rn=cUl$090tr4yemyZj>NgPyDc`*R87EX5EV^Nm8Mf7|Q z@VL}KKxbmRlM+_gj5xZdl19U9!^;;sc-{&oDpDADyaR?D)mDf>%Z00JoAq9@KI|yP z!57^QZgnpR_c)G37niocOAf|%wy%_K8IQC-WJ0Xqs(-vs;E1cLZC$Tle9vfeYf?4c zN@=pjM##G!c$9uZ#yoXU9Apij#U{0!H{foWtPK+1^h2}SI(RSuo3=P!To9y|aKxc0 zbT#8AHYBkreS^?Bro|9|VCIg3pk(od^KN2mBJYa40O<=ojxAK}yF81uKWTg)2YXj1JL{J3nwlsOu~XN{)lXG|JExDxRpz(e83(I+NxTF%$$~iW zMyv3bdrn+eJ+KDH(Jn~KH~d4rk%|SLNq)4Fh5o~5>hG+H{D1#!{>6{t)btgXh0yp( z;hL90X$yi28XAD0Q#6r&(Xh}(`fS=FCVq{V@mkw$Ic+g-F@9rEOv%7*!O?!BqWm)v zaPmQcnX6vc>$T4IUr!&)ho6eI(zramZ0XE9rf= zzNXnbvOc?+%A%77g=>$y7I6o4UG8-WnG7;ggSlI=DJO(WZw42nDVep=AxX}i@YRq>6ta?R>8(*o)5oAxdOGP?8xl+90S@^ zByXM&)V!KBf;^kU8ghY>2l`8rm*K7M!nZT{P-BW_E{1%ZwsJrS3MU1KVYL9MANB<6 zj*s7AQUuitI;q*Sq)@}bYqfG<<1bO9NaPROnxzZ5IAJve3C^N@fyRf+(N=!U>Lph^@Fr8qn9z<^*SoQapar z@sypKA-6r&A>^;6Q8ffHAyAjbX>5W5PuFl1D!zN)L65Qos`(DCbw`2@z9Lg1gSd;X zPVV9tUo+~$*Q(>rsn%fOm?~{keT;eay$hd9N05o4XiY)NMbSKlJt8np-Duz~;cSV0 zf6SCU0YSYW3V^%WHQg@-!-KYxUU-)eI`J}dYKYO1T6!gMH8GbfPWmfId2vO189(duY*A6j;NHCpAd1*;ZXygg}`4jRFP)#IcNP~WqA`<^GpYeB4 z@%#-`rgp}zuGXfEqJMpgIy$(yINE(=4E)Cp@c+*;{pBv$=IP`_poAzk!kHLt@6D}? zY$&7_O_p6G0Us5hTStp$@I0}D{!^Di1@&L#qwWDPIe3pF67;TO%@58Kevp~H3IG&8}FOW0u% zs&uJMA&B0Ig{B#?N_l5K`p=d^SC;rPCkl6sBTO8#93154;sEHm%|{?Z7FR?=o(G{Z>dwL=_fL1YUnI>9yAwd2Z^L9qJB7dg z?#Q6nj?`TobC1=PYflVise($FF@$=&MG-(hFE5m!j2;}!eOzeoyo7X--wO34M{z}7Y8X?>E$+c zqCi$D+_q30UB*w1am|&fO3UQg@mm_=1b=(jACedO%qI~X`*al1M)YZ`0{w>xyHev_ zzcYXJo>l2w384hcj6TAtFYv>L zZcpSsTU|2ha;B+#5q?#J=6VZv)mUc_zV&xOQQtK??Da@lmn8=2+nMvis-`mSxB2aE z&XM^5i!zcQ#ts?@19EOg0KR#2#73dj5t8&{y$fH<>jM00zd8!w10fe z|K4f)pFQS(T_OFcF zn{4irPlf%uneSNgKz`@lv22-)w&9O-K-YB5{nptK{# z#L`HaWn~M-+pvH>$zwqbDwK@~_aJw_fF{P1_{7h{Ge3W1i8idr~JJ zBmt)|+0rJjS#bkruCx+l+;oP8s;v%n+mZYnleXajNGe9e*ZiFI67S82B>_5&^ILl+@ahjYoaK%RAt`ju(=Iu3XZM5mKn}Wqk69{V>XO6+A%c2 z;x)?&hTf&j%Qo`L2{OeQ3nOQpX%@M1Xjk=^hL)Zf?8{TeJUmZ)NqUOUn5hCU9q9jy zqpGdeXH3%Xvo<^;_E3goohiaSAdev9BHdeVcx-xEyLOVZ-j*Q2jc+U^dlXX8O;5YT zp$tQg;jOo}0PEq6!Ne#65NEqeq#13wRM|zI?Xj{I@|*S|b1JsWV}n6EUb2+RrSm40 zy@olK(^mrRsY?Di+HshF#F`20p{;tje~q9gOGK6`6H@A6ScL=^|xE z@>DKSGLPs(isQPZ?Yd{dOhspXatYof-Y=}%$2Fwx&u>z0ur>#*b&^nu&Zl^!yl1Q> zF{fBN(xrVw$=o4#=$$Q3{2i#!4tWOwJjuMHL*)7Z`<61Q1GcWDL83CNyfQeSvGRm9 zDh6O$OJq-1I8!J&-H(l$7c0fP*e4>5g^*J+ap`d-UkTf-Kj-@>inmzqKY;b?AA!a3 ze{p~O3s$QC4yBP@JJw(zi44}Wt8DsAB7+>J(a@onOapVbHjm)$+%4--PK0<60!%Qm zI{g8PCdM-R%sp40wNg2OGd^V`pQYQRAaVm`$$m`Y2?*kk-Xnaj&%J z()v!hh74zx~{T#`>v*fA0X<@Hg6;OFj6IDyv=^;2l(iW^I@>@ z83Q|qMg~;*Oy}cMr<^C9L%vcqkhycuXi1I@pyaaxkY2f+2dd*|cnpZz5<=%nuacbU zvJx5?0X=Ffqw!vMq@v~G!_DfomvF!7cRj7RP}4P!zA`-9yE{^uehvS82HT5Mv;WetlxDSnd&)306c93}CUQtN|Jon+_>rgru=KR$b&#axh6e z-Xp}~7=2ZZvmt&h4(-(1vc=ZDf%Rw(?5vO(S-yQ`o-foG%uys3eM;UgOiQAlS?{kq z=}XtC%i0HYr2i2*bpH)>#H=l?-Hh%2B3%E`fY#PTlSF%mm4q5sK|*>4muCZuEFObb zCao?4Bgp~S$gwWP$BA-gSqq^yJ6bSTZ_HR=G}{zKeO?%`!*Ttd`^ z*4!^ChB;J)!NFa+;{r&NSuV}Yd^Ov#Jwr0dlRtm5C^8d?j#z{Y4%6L`qj= zGe{H#QYHi#&~nh2?NH7ULi>-3bht5AX>kfk0-Hz}2MpIZ7@5fN@nIcdZB~@l@smhY zNtv-q9O=-J2p)84nM3jBN0E)DVWDQ@GA?ROrmZ7t9yR2W=)9}aa;D=xJfUByd^u!} z8Z1$Lvo}=9lcw`=cz!h%Nh!x<74eytDwy!l>RR2E)^ted!03{H*D7d$eO6AU zF0IYj(MM@s&%?rwI{Z2$5VZjf(P&ukKruupf+D{C`|}9ijQJ+1v8jN34zs=j_|v1z zHe#0wT%6cJ__KrQiv^04-wmt+qs(=WZM_}RFVI(-uviezCT@H3qA}v~Iru_EDDFvw zg*?QyHO%&i#KDkDZaStlS>Eg7El#YqBsJB$F~W3ck{n+?nma6la=dbR6_vL)bzc77 zc>7HU@w>-dH`k(cdyc0^x2!XbVp?%d9>(*LIJNGiwoKozpSyR9ss&wU9n>(b_dd0k zMDO)yf~xk4By+H0r>yEY!%-S+)jx?^K7twm4ybl2b#X-x$a~}-x2CKt$AL{1T5c{7 zUg`(zc*SVtu~n_FR8oLY-p3Z7XE3r3wx@nj6Qz6%exP-@Jdpkl{=!wl zjRD$V@|K;K_Ku!2hj&pfEy8vyF9qwtL-o*~*6+Mw#9QOOrE2VU5|fOfDYy8z&EU&Z z@d)|ufS#S-`5a2Wmre0AJ$_8@hT@vnRqYA6|4MS%R*B$V*#5yq;E*W2f+3H?szM1mhTNB=?8W|9gwB*Aby+}LDIEAyg9LeN5Q;o1&My{ym8Ip>fZ1`ScYLvd1Aswgh0TX2S-2f2*NmAgbsFzuJ z#I&DRCu05geHX&I=Y1VQhueL40ll+fUcZjn2vdQc@d$WA4(u=L#sR_a38u`y)`*2X zc!toR}SlAf(=ii11z&(|b!$0+oK(CdmI1C3eV$1r|| z`238qClQ)U)?62|hv!7{GaQx)CbZE~yhVk#g$XD#1{-8#-xj`Y3AYEIv%(^M$qV;|MzFR*`e`7V zvWJL+f%-FQPYdfDcpJpfb?3b45_}#kExaDV{xDEE6u>qh0@WqWFT_}Y7FHAyKVCMM zBT9TZD(wT77sTsf#>MMm78)?>cs{{!7%jjeh6Y99qLGWOKSp+pr!*|JGk`0x=ecrz z{`(INz>0^VkMTqFmHdx|roU?d)PKK-9PRBL9T-)u?Vaq*S{gpxdpK9vnvEk}_3`SpaJw6dA>dlA=LKM8?O^4W+ey&9Oy4@#WU>g(j+CK@7!< z>5lT1=xc7Bb*(_=Y}N+1>yH!O`(LN0^`9^rs)$LLlf4`7v8^KE033@sjpW@JQkrj|clhqai8QTHwa_DY zb9_dIzS>XDJ)gfNOSa#sZ?%SugD%)Pqy*=Cr^^vVU+{D#U4{yMiB}*4_mOF%HC&kTB)g`Map0|TG@gr`{u%0LT7wt`Ziq{@& z4A1r5!=#SU%b;twg-^typoIwm&}*V@J;`|KoenOR-7??|a`E|MMM#J7TV@l^dcG`K zt*`rTiNcI{*Dvi8ZhUMK5}8w+N$7jwANc#~O4$TqY(K2!rJfQW)i#72-%0ZrBOQ_i z#LvadA5!F0z$-*z-+iRYCl_(Ku?FB5TYh$6ulmYr;|V4+=9*Cb2C1z54pGe-J7dr% z>i6{hXQ+u=6|0nU2$l*@l@C0UOF@EJe>9MkUygrq3Uj~9Sn>Trb=!B#OiTZ8h_FsHlRiVD8J+#_Jz`Ju zzBGJM+?#Oo+DblXF%R@%U~;G%1xakdd1^-ER3^DiEL4dGBj8sfa&S@8`$BvYkc~mK zMJz=pRsiQw(ZpGksLp^A1B>H7yC9tFlayT_%&hMpm1f4j0m97M)zs0$+{K$w*v#XP z^ffcFfB*7tB`i*LL*)<686FH<1RUREO<6(;ikli93C?OwbEY(E zc{aSKat!rygsJ`QD`1p`Z(d#6^Nry&*Vpm==Z{z10e>zW9juzFM8CBsZ*{UZLbCkz z)4L%4o15;W@n0VvkBh0{c*Do~p1ZB0oSSXC4p%OUHddBcHI&-r&oW4_d>+AK-y_EX zSIxp`6Wrk%OPgjB^srwpti;Pf;Jw2gC?j8TTDnFLpRYA0uwmnGx1E;az#exxW+wB9 zjH!4r%XE!_N?&P7;{1k~^GuV`ZJWXPflKqgGK*s%3w1ca@lVJYm1aO!7FVK6PiLe_ zcx=~podu>5CMOc5WM^MucoCE@6!}K&W9}l(gwo;*< zvLNFRd8@5c4_cKWERpxVkMKTJX2DixHVW+{uUa`%&D+y4f%fe1l$b-GeZrD@43LWM zV(|Zw_KwkYu-p1~W7}?QJB=FKwrx9&8#|3{n~iPTw%sJnyV~d3=j?s{=k&be>@n7- zd|M;GbxquJ&MT}{evrco4n^o7-2pRMX{4UV8BN4`DCt2p)I)EJ5FaTm*(2R~MoZBl zOHZU%F?bq=ZH^zTu5aj`J5Dz>pOce{pDJKV1x59^4_C*`ZDPuK#Xt`qW=>)8andQ9 zw;$~kg;7zd*pVC}=tm9V%u-&9%HB(wn{=@fi_T~)Mp&Rk!^D2n6})QOZ zD6Lb{pCZ{RS&+R53HCLA2KUgz`p{_c^xZqaHCZ%k1}OKoJJ1(eB>#*W+$V5b@JASA z0D}e>VGs&X4h&^f!_xBQF$R&zK(9$KSDP?Uy^4Flz5juxW9oEDW%l;_ctzs3N~$mb z=D~l&oc8}e=KpwDu~tM;MfITrWuqB=2{(X=M6>jd`Jz!CY(Z%j4oAYRV=%xG~IM0`W{Cr@n%`lEA-8!^Nl-Z1%ZETZL_QKBVc?KEJ&0CIfvhFs9bLsm_=0#>92@E2x@;6 z&c_jqGL$PD9JVw!UQbXc*>>>ZG22UIDH4z2|`+S-X;9&pj}VY4&6N(jQXBi*5^netWv>! zuol)GR1{is)f@3KhB^bQ5XNpv){_YnX{~`G@JigZcX?5mx@IaprNrW~HcW}mb1EhG zMH($tmg6X;1n?;FF{p_0c>_F-jhzx3DtHBX^$`oURq(gDLTSJ_BHS23iLG{;CSXTa zlfNwn?f6qlB#F(bzrV%3&}Y-@h9J^JNmZc$5vq(Q@KJE+v1_w$YHHn7p1s7TXB?1d z`%EER=H|MYmwinX*v*oeS#ug{gRWAO-zIms;G&xBH@Y5;tZ$Q~t+q0QUZ_+R7q?#O z74?1UuMndl-;(euj!>4X9^Jp=B`t}7*qTGB$k|jMkF^c=srb~&F8qvFLPJCYI=$NZ z7?U4$>$F^X62*44)YaH^>>8v;*0?)Fft_U%L9BLxKwF17ClF#|VFsIZ)KTuBhc4Mi ztVOXZPeQyw{rRK%QN;j)Yk)4T7*V$`L;-L{!XAa9?4hOFqfYjV>)l%+97J=fM#>Iv z@Ml_OhzEQJvJY#kWIB4q#|xD~&KPAjU-Z*=HvDEWbLO!+$cvx(32y00!&akp3==rL zl-xq+Zua_lyl!w&-ex_USz1CS=R7kn1D;+=_uD!}pQPLICygxs4vFQa)r4r>i{t+KW2JebmcRm%0tv7IE9$v&}f#RQ9UfONG-g z^hS8##Dg-Hma;?6eUM2)Zf#YI4CA`pWlUODALG`eMyio6Fp5KyJKmK9G`ZD|NkY@= z8SfT$!yC1WO(M`E;ll%NSnB5mL*;Rgbkw$uT8@;aOwD563kp5oJPa8<_y-C zuBSRF(9qCdw{NZ|8utreR*Y(0C(=D9GdwTv4y$bWK8)pAZNc{1&BE*_DaT9GSD(Zh zR?Pf#-`fjo$@OCqbdj`z8AU6#XYVgBCe2WdqvngaDJjZsvx%O+ z{ztza#?UptIc`Bt`IF?Bu!Qxm8wBllsd6)<>y&$NYuOW7TKG}ssKwUKSRGNC+S8Tn zoB;PYcI;}71FkO3c(T_hzg1Yp_ayj1Z5p}uXclk5=Ge7MFVzl(lB0vdJ(nQ{pA}q& zI|95;SpqI%ju&5)ZoNv+Sldz4sE31djmeWH@$q7O-@JmotBl9z5P`|CT5WneC2!?m zxT=9`&{0sBPfpwoWN)sSn{&pPqfK{xgLb<7itxc%s;HC++DM>G*~htI(_An~<0m1K zzI>);#(KyeQROf7i(l1~mx1WL`hzAJ4|4~0P|n)}bZR-4vD*VXFgqiB3}E|SsqO2r zXKE(pwqc&|!5cUU!P0YqGa*Okd;DyPNI|ip;G&9eSR$4`u8M&8K7ls6DXDIqp z!>!Ln)pBi9CkS>a)!PH%a_$W){@PjBW@eA^2E;|rKQ`w6%<|vHYLSY68%g6(k5Q); zf4nSK9wb8@D1(-7eOV8@$^#Yaa3l63Wjt#~c;>n}JskEI-ZLAT0lAm2Tyvq$H5pDAs{orkh)@yjl~$8hpJ*>8`j6 zJ6x-o*sjMhnv+8w3Ce`qKEy=gKt-rngZG@jycD|uQ=|9|_6=yVp!1qiFCsb{3a8V=tG;l=FaVm{fSekw&jZnvS`A@YC1xR2yFEwn%S_NZ8Bv z2u*Ai%)9sD!{!Py>D#>yNX?WOh|iwQvZ+ufZ;nmJ>NhzR2T`K6%ob^88tk}b7e5*m zR};D`HTTs9y>o-mmMZH=+rL#V$~m&fmIc0$>ww9p+%pugy5(DO)jRCBUU?r=FKy$* z*E2$Sw0763H*nNHYv0`wNuObbsX$VbWzc^Ind}tZOk+4q-|0cQzbC&_?4wjUbJv1= z4#)heq@#$I_`>my{t6io)JHfFW!C@}Pnd4eeSx@P)vW{>35lQM_O+lfTtENlotf!L zAmANs_9(y}DGX?w{DDJN| zbM_8l#jmGN+&|Jx{6}T}4?nh`1x+bjWlV^x_Y~pab$mUTrKB0?3e7hD^V%r|ngR{F zg8l+I8w>0C<#kF}JQF+9B;oI>-q+o(-Zi$oPx-M)PkK9L9m!@a*m;cDiiRwO7AzuV zo6FiprVdL2CZ-enj~Syrj#~j~mmLtB?>kz(94 zXrX1rdXSTrk{V-k<;zQI4mz?eR8&|eY!>9TNd=_R896f<%;{p}LDC7KtE1U;<|abA z4(uK$lCAp#;AasVSh5FJu#X&qy7g9LwfY*Sm{j0r_4uHIv>{T}m`E)of1AsD~rynj+6e5FojiHbqOawkS{+sJclf+Nkhh}-Q1J|J}<3f;V- z!<=M~!`%+1U_)Npo5snE)xdt_5IfGhQ zJ&F|J1j#IA7s}59#>}HehRas25)0&xiul2^qDL{(E+u1=;(;u{(K0}4{w?GG; z_LWHZ8ltu~eo?e!<++#VgI`4V?o_cAw9-FR}UwQn!CXby`f8)zS%e{7%dEgnJc#go3=q3QH3 zy1{L3VR!VuJi%ved%gyrHir_Zf%q8NzxH`tGk*%#O%B4b!s@J5z53*d;#;l!I?UUr zd&c$Cg#9X7A;>q;JA#t2kV3FrK)hC>->B3f1uSt<-E4PVp%QhoqUd<-L6{v$NxFqlvda&%N(Jx+RqQI#Su42c|)nAZnn zWZl4IXDupak|mAHv$L}lX2%6SAKy3lEp%KE&frA(;-@LBD|yUMo}qS)=5HiOE`u9P za(cz^?KOv>nQM-jk0EQS;9;5XPvoVmO4SDsJICflX_cC=*1VIj=oWYCN8RZ4F9d-1Z z`SNs#uCk2CRBCMWB6BMD-7otf{6SZyHy0&91)%UXm%4<5-3bS`KV5i8oGMs05BhgV z<=ghpop2&oxlR1o?{>!)A)--tU#@b=Z+y=!B^cEz7Mdl|TCv_m9BT+z zp!6HSRck1v$9f}o$2Lyh%OF2xbGQRGDSN|GIYlhuouLYuUHNu#G|N{bmL%NxklDRF z=L;{1B>`|+ZM=bNV6S)}OzPa~5zp4GRwD(|NCh?JUug{-6{-QnQDqY2IdyWZkgeu@ z4WcTXfXdR+7@wbO4F(?vW0@WxQ+Hl5H@K;`s+2DLeZ`Aut0RpX5EdE!*!&>)Q&{}F z-J!B-i>i$K6W%(d7B5??J|TQvz|XpchBj=P2w1YazfnoUQWGuXBC}D^#dINMS*H(2 zr@PG`*dH5(csd!9LXtQ%l%6~0iQs7~K9s%#C-O(evUL;fI$#w4Fn#m2a`V#R;9zs} z{X;esfn_qeTt+<)CvMbe{&_IOtVwg^A&7ZhrMzHC*NDDhA0|v&ULh;y#_Xj>6w>WO zANOn{=z*tTp=ML0ga(Y6IoYhtEK|ESu%;kbi$-FiT~BtT%w$fp{HsZ*_W9QKRDIua%qeB3P96XHyDcKuG&dCPasJq?gE!Vb1E&0 z4N{-Ljy4X&yR57i-mMwL9KaHU!XLvf$tVnfSvW*t<>{zJiH*XTc3a4MwifFLb+sOw z7`iZ-Yi`Rhr$~qy`*xc57ohN?sg#V?RKy#hONIWIClgjl^Fk)g((%7C8wi!DAHF(qY!*X`c~d@x#EIEzu(m z8RqW-2`xJXDA+T#n(;RG`d9%sC}Pof&6Mx>$^|WRmC3{3Ba9}O_BhnnK^FxK<1@Zw z(1h9dG8blBeGZ8Vu~X9nYY*F7eu%Z4DN3cxIxxB#t(6??J(^IJiRa(zq$YnEkkG8j zxs!iTkRr=BBqz1MV4z9KKEb~;KQd;=xaJ?sbBk!i5+K<3e9a7_S|;Yol&hk8I{9K4 zk-Xt1`vKel`v(}?D<8d6U$=?Y!G=E~ZDLTayfQrx<{Tr-dZdmp?t;Bj5=i?95PGRH ze+m7!nd>`s&C)i>Q>4#QQydJI+V+Wy$?tO$&jBt+y)Gm8mMK;~(YbqT>uX-$JA`t~H zkqxbLDaSf2FG=!njTQW^(DDLy=kGyH%WCzgHFz!T=kAS(O$|1M6`Ja`s%hJ>4tJGw zF6wrOEp>EYGF@0#7|ow3sFKh0EU$-!8WrXrfi1&as=5SxZ5psj*4|q3%+OGuF(I8+ z%*jRA6VZ7@H%r&{0(ENhO7qfK_?D5gdt|t<6QMn@}E^Hnr(bW74em+%oG0~7mhVFmT z&3S?=cnv{Zl%My6o41DBB&_BPm`8yuJqKl5>#D+#_XdNLY%-pz$90w6$_%Hl-Hhvg z<4l5mSbsXisNI{y!W|QDKuh9ckvu^xxCwbUYm6s~zH;XdAiqrj;xz#eukg2)1PT=!1Q~_1T%Y99*S-@4o1ngq{UNM-jyYZ7|tL&N2sLKm~m#M z9`NQ4S>=xD>(|X|6ifHetXgfVLjkG6h&Ivj7Y&jCmDTeuCC1{RBP@pwh_qRYaRjKEtXt(pK~V|5go3 zamrLF7l9t*5D&8{psKt-BbuyRQ~t(#*%^@29#VNJOJpg&!)zliBuz*s#&pK%a0WI! z`v%eQ3egZjiwapG_CTg!dbdUiGR7~SY3xGwOb#Rso)3)1nh;5q!R7pcmGxs@)sI); zU(f4gQMqP(fJ_7GkD10FVPyOVjM}!ypHX>0R&CT9X&0h3tgMwS{D@$lzA~DNv69WP z+$kCC2*EAN&w)_ccD|P1a5msp`k3FzVuQ54VnF;YY@pk$qqEdGrTl3y5WeK4t)593hKBw;{4M_zh#Erke4P-6ER3mKowN7$w>( zTW=a8|ANsuxIz*D<4qd+MXufse!xAug(1o#)`216qqh%PZX;%l0dv2ODj!^QFe~X6 zX`Oysr5_ANl_#pIhBnvIX^_i~8e>IP6&K_cj z;y#V%zThiP{V3)io+=l=$ae|I*$75N%hlcdJfPIQ*LcV=lT=xSo5Yr}d}KL#DxS)Y^A$C81DOo z9ED_!`5B6+NvOOEB7Y0iXv_$cB@8SEBkM7}1p(|^HYpm0H5#pr+NB%dYX|O=(4&|~ zukPwOXzdGv>!Dd6WEK|t;0E(RGY^Bz@!OBE6QbK{D)+xhj4t3noGxR)4(06?>50gq z6ipA~=R|3EsF%j2T^lG3MGM}i++w@XizMvTRuxMD$l?!xEUrg&+*C%wSuy>V#dB%^ zi4QpF7sR$ZK)*?ZLBKjFkb~gm!;qJ}6R$}TXhH#y2(C=Kg$5u|)Be#Yt1}8fV*J_c zK7d5V{8qf3Y4~3xy8rk^qOfb+jwgV`xV=q`6AqI8bBxa)a|>CH9ll17gU z2&sknP#jSwW9CV8598ttrgv0M_`}&C{ z+v{m!*eP{5CN8g1%Y63c^?_i1!wpRhh78*xpWPQai;>6A6;N|{7W-~+wr{x#P{ph(!1P$` zVJ4rQi-$tcn)0X08{jO$f+)bzFD9C%Lao{C+@j3O5>wd3p1IN_5&PhDh7~H3Vv*~w z-Dcq4vEYIO1F#C{amjW12ASI~+b2muNr&NY*Tv*Lf*Ux{!Tl;*H`_=EJm-U-1yM}Z zQbfKMk{_gSKZ3j)phg%g>)sI%ZC{Ipfgp82_rxACm-ml7wK(*pTqQEgTdJ=1P4{T; zNzpLVNCP$5BT&PdU$hF0cx6~w+yyn$j*V};- z%v~kKKi9);-DxS>9ElQFbt0$iIBo0Yk9+kLz=Ozdew%p|Ucz;t4C>=LmyAPCH?H$A zACj1w?4#+QHDVoJe3mjlMJZQ!hB-r!p9X%@lxK__mWd@jmDw}30}1ChTJHmt(7*~d z4%?cT^2#lDNDHbo1wL7;mwIHIy$tZ=vGW|)SO_czOakePM#(}^lyRo7f1#N68$~!0 zy5km;O;66pzN_Ig?2}dGAecApxd>}dLuW+wc>M<+kFbZ2kaLmjMvZw*ZR3?>yFkKeDZ#Z6|_Kvf4`D47g-VXwBgR=UVbH21@TC$5;=~mt<_r^fY#$6>`1U! zBa)0JPtpM22!%60(m;;1`*>1q`6Dent@(Tlz55OA!5#u=lGxO}9J0bx#W*&)O(gt% z$|PM-`5<;JT)KeoxWiaNEpVMiBEdxX!PvfB4fNeSY502tK^ES-@)whf*gN&vd<@v^Fdk`+;WTFj(%xA!ai?nT`=Yh^ezz@m z%|?}Xfj)eY1-y9wr-R6UotXS%O82)_@GtEGI79NdYO1Lf$yLkwK~pGGkyR$gBFi*(iu3H)DrzHuA7V4%)iN%K zE&m+LjYZL8FiGNIN8@l78Gku;uZ-KjLv?aR?(UQi{VWvb>P=(40O)q4N zkRU1E$9-XU%;_Ag{ZNlG?T;fjlj)#Yho6(|UbsG;m+g#QQGR{YqP&F9Zx}I%zs&84 z4mxpmC5!<6DLBT!H+n=m7!~T0>9f6!)0a4z;+n2YCb0}H zPj{|G{3EJBw>a^LdLdn}A7+A+x*Iz;J4mGZLipRe4UI6~N*_p)=aH*?KnU$+ail1> zs=FXubUVV0&r{p)qLWg#ReKNs1=9Z=iofkbo#muudjQ@)n$YtK!g8Od10WFi=R_iP z7<9g3$LEG((q$&q`jMWq9f!P+qJ)zD8h@~dj>JS^OUcMcVYl5JTYP*W|H6ERHHCTN zgBTvlgX)90oF}xR9d?QA?&e|6Z@QFxrE24;6?rz;E!14&2P|kD>n)M610u_STA3er z%_>+qea3v0p+_OLCs(hh7nHLnMv9N@`?2THU9=xc>*C&>VwOYlDix&Eow`;Vme?`swp0}Jve;3&qnttIn7X$g#PfsCL13&k19FkhRs zMiSS-R`Qz|9_zHc!hc)X@0#nU*;lh!PjWt{A9A}-9AEPB`2rPhwFGkp-}@1Sp_EaB zchq_anzIi3G6OVD&|iNyF#3sHGDD)ube@X}wi#z(P3{MNuYns)qBpvV$uu;Gg)(hD7P50Eb)23UmReVCl=~V}wtmXCjE~1~7%|Va3*he0 z7SH7!Sa0cW+xN`_zlc|H1|%fYrF7w;a>VO|VV=!TI8TDgQFfKA`7YclI~kC?Kf3vy zuo}txp3KccW3L1(X;g@7Lvy28t<2O+hsKYr^-wfnB>_fW3I{;F7gpQQ@$o}dWcCD~ zup2|qI4mHXc@cqZ}hw7`lP4m-@U{XDsf4AX}ehh@*Nu64d z9#MQu;)B(?))0ZwlLDm?CS@56K78;N7PJn#S}NkiZafUl-Z+$i3c}OqasOei#)W51 zr0#fUrk3jlkgVrv_tNG^G!OgtPZ5*$Gtlk#94Yyx>iNU1I4_h&)zEzl)<%>fn$o6* z{ApXclJEErH`*0-Oilh>J>gVw<4n1XnbbrcQ&4 zzw_LuYMDe6mAY_ zyW)K-x1Mnk^hxS#dg> zvish3^iVMU@m*W@1Pu%-c%GSeD=T74t5w^u6EBdrsn`2cLgpv~PUZ+dJcG&*4J{sy1gFB9UvtZta(gRJ{(9}gFafW=BF+G)jmJ4$^hRLgs>>Wnkag`ir zpRBhDZe3&kO1|Tc;Fp0lI-!?{Tj^RDMSI}p^Bizpdo2g;QRC~ z-n9M_F4FE{4k36CTx5=#i4lr0T6A^kuQrr`Eu5vAY4UC(tv~;!;Zi1zmX8zi^E?SY zahYEH5PY6<=K$XJE%0agGV58?DV;3B+@X%+sunD=HOj9(po{K6NBt4y{7quf^Yq2MKSkg10S{$@~ImJ6D4s)lnYZQ#t=*OatV8|B)i|)778ciBD zZ7{oxSS@2GuTppgc7i~oYp{zf+e!FNKr>1--uTmRT&veaFB|oCBiwSNc#8cqHRSh* zQ>^vt``^>-L3m_JEC2w}|IYyaBf0%A0EYW(7~wR-C;tMFX)JCcS?W;KVNrXKR5R^v z1MXQJd2M+X@^*ZH>t}=V9h;deJ238(^V>{=8IfNzirh%Tox%@=P6G-f za+4N$jH1yJQNfV8(sWBE5~|OdB;7H!3<2sWv(1LxUEICxXHRipsy}w5I~S3+KW&^q z1Kw7z+?s|3v7Ynvh=?Yt*+OHqiFPQ{Ui^GFV1AThZm*e%ox7FyX(IW+_GFqdTSa`m zWIO7REAMV)~A&=FS*+F81vqD_f zuSZvLlMVbX!=>RCL4J22da35lR*ywEVRpOk($NQEbYa{VAgoc$G zO>33)-2h9x!M$(Ndo`ANA>H2#Ew(wKVQ+h)5A4+ks*?;q`3>tWI_P^OzEP8+vYA5^9jE<*?<)Yl%`V*j zcq8SZ=n2K=j4FoPwoQHSsCe`vn}K0iW-A!;+KWLSXe=7w8fOei)VzYiIzqk3U+VW0 zW{g0sqpKH&`z?6Qx0)uLW%QT&`Hy#fW;|%eSUlVPk_n~3myNo}+`6;*Tm5!tPy2tV zAM*bhzW+#+|9ak^Ep$FzVo8uZ2Gi)8BH_;-=*?>YaG+IrLO{6<|x%_1r?Ol&MhNz-wyl2mmR5G)j|FxI!P&SNX$x)8D z94{Q@nryDfo(<|zbY+i-=_NK)StOZVv<99FmZ_Nk*kLw+BYa%2N2adUQct}{h+)ug zIHh!zi)7Bjf(GMrv1fAc_i*(meB5+mEsLL?M&^j7H|nubMn4rIkj2&Ti^WJnh@!1| zX&1`vdOQ-d^`e6oL1IhJtV^NSYdCz7m@+6b+~{sqsbu$)t2xogWTYu%jZAu&>wd7A zgwj>&jdxS&7x=ICa1oJReb|g zRRidkn>1PM7A$9E4lKRV0brH%4s*L}m5Zycyj|9tZ=jdj%k_P>O;%)M(>yF3ty%}p z>4QviA{chDmR=v-&S9%3Th4D*FSmULB=T;NRNuek!*j2^!Ogrw9q*F)E8JE%9I!P$ zYwlWur0#QHYwP?~R`KR!lxzX=G>JcE(0>Y*e<#qtUTuDPjQ=Yv*{#C4z+i-l6d&_J z3B!JL*eA^;o(pd{!(;{ZNpoKTd7&CCM1BAoNIFkhPH~KyylA@A?Er2LNCMR04y6&? z(4tJrT(}ta99ysANDyuC7J-Sx_B0!TKS(A9wm0O`w1iCPnQBHL>kb$ey4eEmsO7lU z?mkW!+{RSTm!F+zCNUt5)z~@|p47ubHdJB{yCa_9n=qUjV0S=3m_lNtzT>MO4W@Xh zj)L#|&3!nn`8!}9j4P&KFuht-?STf$e=QpDAOe+dPgs%TB-Y7AI&n56G>R%R4=4j-CE1C*5EcOoO;O) z5K?@Vd9?aj{i_Px33bcXV3(9!vY(6V)%Fa3wlutlnlyVW@5OrIYF>VadQ8I8hw)HP zpcwao&F56I@_S?%HQJC4Tu?9!c(hHO#9_sDLE%i@8SKVgJmfrauvt7k*Cg0#wDt9W zthCbDYSLswF*%~c#?_{|<(e=+qR4aPm}KQe{O$t1w7cf=eEw+1XIN5mi}VdZi|5tR zPurNEvSI{_NC~O73C!#@!<*Q)I8!u-p_ey5e%D(G)8dKS{}wHOJJSC*w1nk|^E>;6 z@PZ-|LKiFeBUb#TMfvQ1rzIr#7cIFF-0&ex@?5z4_DhGa>i7U!r~(rW?TG-iu*it& zduB_M5zR(Pl`Hg=bA~xr_kL_gPC#ep`8vDAO=Ptw+2)Z%iVJhF#EzxdfE^MjAquz8 z4XKR4ob1d9w;2%N7$|w~8%=Y!qr^KI?>7eDr$+-7&Vv?uoik(rpatz0Eo8rFndi@^ z@=hz(x>Wm33#!cbm}TljQU|eLv=osgkTbDvr>JZHqDA#DT6+GImMuE{vbE*`qy7V0 zfVOPwW&EWr(!Xe-)GZskTL#ebGrwBRi1;70B$~#0VgIJ35kO0;Ig3i_+mYliZLy`7 zHeSGj0cZ>O$2W>258H4eV1*M8QIvB;2c0( z_LS2HiR6U-Q(Hy>+5+hB_zWnV{}k1F1Bt`$&3pKZ7Is9`R9kfBrt1DpXj>dP`h(ER zoxf;-m7FR2_h|Xs-TJ?w1rUg`Td%%Q{n8fxf_wqgd+%ME66)3P@2BXzFrjH~TOdyq zedRbnz!9{o%yrC%xLNDAo1I=@b_BE#ih=t|Snjxg_4jt{x}Il=;9YR%05>UjguX-F zo2N(iuII3|d>ykfGDt)+8J8~)um(R?&30-&)=%$0K+-Q$U!HHG(I-mY?b?%?H^)P^ z&}NOh{W!-1c=PCI@j`%~K%!%P=c%2FW^U2_7j4P;7j4o1v$p)Eg&9E0Z*BRTmVeTg zEqwhtKqLatg7?p~{AVPp{uPPr0g-6%)zR`lA`uB75}{ns{)$Akzax>@U$p$M+VTmY zEtfw3q%8nvK&vu<9ypq`eO`FhCew?2w{`YA4+s65Sq(ucxnM$5tOkA1b zQ3*t)tt2#R{D5hqkDPSg=lecZN!}l3_i%4pS% zSn1eKt8e?uZILkU8AmaaicDXL8_G!?2Tq8mptS>1O8d~SUU2HJ8pJB>OcnpJ-E1Bp zZ2|nC{{xn(->@M4S6Ju}D_QeZz1>~P#IrHhe=lgj40iWmnue5~?khWwv9MG}- zKWR$}yJG(Tp0-f^VcJAoLD1IP&e+BY@cH|xU)kCbMH$t{CcakuyY+06|3`~yjrcoK zM8rgughmBm@e)vCWv}HzNsmzz_6wVpdWs+eAh2uWS7HWMXQP4Z_=zX>R}>!yZr3_% z9f=HamrL&p_X+n4&cltj(@kApkeIG$XbsFC(1m%leTVh_=7YDSNV2nDwIn~{Fb2m3 zTj~t!y<6R|E>Pi#4M5|e%k7* z*PY#2uTQXxrsE81ryP}0U)Vr3U);)ZZ{%hyaxj}R)tJQssj~|CYGp!-;(fUV6z3y< z=Nhx%yN##07@l=!dogrxY>YW#Pj!_{cYXo-q3{HLY^k?f>@H#^!Zw4B$`x|xIw`m) zfsQ_8X-m4vs&{A}Y|XoPWm8;zp>!Nm?v`@!1s*ms3gI2`2vY9{!H-q3X6yA7aIt36 zHQ|wE?+Oi>hxJ~`cB;xyK(mV zwP%%2zK_+On}J2eXV3i@L*B0|l0Y-@TFE^(#+6irsUL2l@O2gnLBBO5&6zY;`CzM< zMrs^twM~h=H{3CbW0bxaFs*sPVvO#6Jv2+JcqQR$OE20KXlUG|vJ7LK$yiSH`{ zL*ABy_xbk{d$)b?C%x2VBQ_J1WL1n+gy0j6+1V zk5i0g5?Bu+E+<6;Q~DGXR?a4doSahX*aZ}X856Idyoc5N5Yw`e9?R`SWB?atwKacJ z61fAl0cd-uVjUo()CBJ*u)%N5pJytewL7beXMzf+z!cgA;CIOeD}oi1Vvek%s<5XF zk=uLin}B#^T5>B~`1XsL>-SJrtykTE%^A%!h%WKM8zb@#DhuXwT^|FPOom6yO#{>I zF1-*W`BV~9_%LvuuyU5j z+|Ho5Ot{{T?(|VI(9XQ~;xY?N+fGLa!-S1+Aj}4ak*4iqetyx_F;reWvxPn^dbG0A zL!s|uL;L~O?%VTjw&i+P1VQ~(3XT`N9VOa+2TH`WRmOS;Z_);27mcKC22E>8gwEz8 zb$4`XS2XF9IuFOGx`lLhefdY-?uO3@mDx{ro=0=Rl77!W?7qB(9=fvgDiMNZE!wpAUg6GW&*AM(~7mdJz z6lX9ZbF7K$7P<^t%b&898{>S|zL~N5t`+H|s=Iu$z}PH#o@yq?Dlh9BB|57SyW@VnJnsU_O4$*pg7U zx{5$Q^$>AWb!KKkh-Z#pXr8aD=Y^2M#CIcH^UcCFxx;)P8dNhH{V4M?+^qY9fM1BL zwYRaGT;4F2%1PGc?L!HnZ6161GqN_^YR^53LR0FM9{bohh>vd%s=`Y^j@bNB1k=WUMyWC@RGG4Q*V)RpQf@ig&Hem4V#;Z}_-e?)_y@4GzZ&U@^WzzxV!{&bfeLEaDozo=%1_;YQ1XBvPHYV_-C@+=562Dv z*dqB&UVs&>O&Lc_u8f~lY5zly6xdmeZBQOkdWgh=1(t~-IGZAPYcs7?fQQ)@UDRie z5$|FW+p7qxt_QKNDg`-CSOm9fV7Lqu(0s!TCXul93h@yv&Mj?jGHq1a0jUQ!Wv5D= zWsP&-x7mI#n#KG;kFHwaz70(EAEmy&D2~7J(|vRNwx(IPJ)YO)c42J~ZtKiMQ!pRy zd75KQ;$gwc-9T-J`RJqoF3W7JCNsQVc=?T!uH(gOO8-igLT>1}$Y^VE)J}t`a|N6l zu0z$2XyVa$i-0yDb*!r4^S5r@iZAiEi$+_Maot&CRZV^-R{_vcTd&MaSEi$gG6#zO z4>+&R&{BJ^_w{xmW8+j<6GB5bG+JA^DG1nOj;P6fDTl@e3L5WoMhi<@S^@5U!10{7 zrYXq@>3r-ds1@Vjw?trtb_e}{zXX3v9^=BXVov@>X~$uzlNl;b=}KyS#P)_--z^jH z0|rbh{f8u1S6o!*0pflktSYgZGzQxe+~SS&izOHJ`tbwVrF{l)XV4}g>hv{W{q7q6 ziCFrlo|^WIY>EwTJGyK5^y4G+E07I8=4zQps=o*AE@=!~aGMf$I51Kbx||@K$`dhM z#s}q} zPAO3tOlEZd`a*TB*> z6SI;REMVc<=0aBCmUGnrMgQZ&WWGtEk7R9+qmnjCf{CvkLnh?pjgT9*&Q|YcpC&!! z6@pueMRHRcP7Vzvo%dV!hfaaSLS~I^<<@|=X3I1<9Y2kZo+@g+04=PI{PBf8W|F?y z8|$BNmmd=f@z&!#X7f`7{kFa7RQki8aDKkvWf2cwX$z<0Z7{AXN^fd2 z=iXJ0G+~=BfzrVA+qVwlV|1EcUrO?RUgo$@M+r%du`?P}y^p9rjl$5GEZs{sbT3C0 zg++wS%(k~5$~K&plG8Y<>S@QtXG!12qnbAuPemkUjfnRRT!5Ag|h_jOq!d1YG z$8wryyfDDOJK4G1?plIXz#k|)ifnjC0E-ILM7SsDJ5BBsdV!6!nB%4#rS?njq9u1r z2km{)#cUZb;fHFH7K+*Z#&45V-sNP&m##u<53$#U1l`PON3x$}54N{Z0-fM+>NE@2 z3FP2e0&KjdBO`coO3|cD!H~F0MVWKAO2Mu|%>Wlxp_W$SGghw;Cv?0t-~kprpzf5F z|5l%l9MzbKUg*4aC|nb>=`;>4L>2FesSJEbv4n_l#zb3wOlr zEv#Qe=}D2@&1Y{`G)~hDRFlTuXjkA?Dqtj>%(+hsE0Hjhc^F&81KTu z&fy4D(xA994J8Yq0u`l`ov`P^(6XHuS{q6C&i?V97us$2y*Dzd`CJ8Rs{7oY-eu9C zB#g_%V>$>GZXQLC`BghKytO02`LOyPls>t}+s$~QRNZhh3$Kj-d-(vTA! zv-~ed0gZ5=ck3(Jd>Y?#bbg{r-YVC#y~09=NScjYz#<@Rt5+=ApDF6m>_uKtO3X6P z{oHePPge?#IvJ1sWZ^~~oYf%P*B$yKySN}0^{Soh5S;Vfbs)7gK@97lJYDo2~P-ZIdoVyY5l zg*nKjeTrAZY!Z2;PIQHpjvj!u-=%x?`ep z$rZ8IdO==s7~j>?+OC9MY4>DG7-@AQi6Tn!WQSZz@)Up#s{= z40EnYoF@HxGN=b}Y|-`4jAmgyz%!}hpLoH^h4hikEAnYWyF=y8h${l>jTt#Op)>L; zNY3Xl%fot(^POWC@B%U^?&1n#8`;3Ucl^NtG_j@ zW`s@?Ta{V~Vq8KFs>rt{w)TW|5!zOmafx#ghIJ9%F4bRJKYmh%t-MY!h3mE*3EBFg zzch;#&@OmIe$rYMPv+%_YGBMRXhpDAOK^ed|I*9^i{N~q`BB#&lbZ=N8liVKqxXtN zJ}bI=Q`7W{SMX}b!QloPOE0R`LZGK%EFfjEbbD zRPf?Zrd;6nIUFHdl|meL5Y;Qgx-lHB&}7o|G`p-@&?dCH8^5k5Ko=1$tu$Lp1vy6O zo$fW(Ow>eG1#g`~AF2UyWeB=Ya1SgG-~V)r_dc8B1%$m7 z(|er#QW?cL2KJKeh|84fgi347o+pgmV^y?)Y?l^AZKRCcOtb}9W0X`^F$i zw{6?*vTfV8tIIaJY}>BtvTfV8%`V%vZNJ)kpL_4QC+^wry|_Oz;){&T$jmRt8f&gO z=NPjIvRPmV^0!)aHzd#-9X2h2xf}p3!WB3NPe^$j!V}T=tlV9i+E#>SiS97RcK>o> z@OHuOqT}YY@(Z8~lq&}8qWD2{aF0N5+=5*tg9`C2CAS+`edu$Fa?IY8{Y3n9O&H;5M2IdxNn~T=Esjo4ttuyBA5GH{Q$|4ak?bZ0VL(#h_)o$W09$Qgm3OtcKtBB; zudAAYtb1o|a4QGXY`KMP5eIEJFNQQ-AhrDZ=3ZI&tx3KDtT%VxK2M<*^c_x*&Aj?s;4ZeGXKyQs& z5O(%9Zk1Vp;^_R`Jw0=N0$B~Su6ciAX+zx9h23g9Q}u}I2*0djy%u;N_v(k)8A9lj zA>#C+K;AZ%r}x5F+D@9GdJ{M6uPP{Tk>x<|ifO&#mFM*$tr+?g$Gmno1qD2&2%K@0 zjI}aAG36bNz0g%YCMS`gt;IT)N~H80K|036)Yqk&)H8OHfFEr_sY^<*%q#j*Xlt4`j9Iv-?MmGeA>f04_7h4IXb^*|AUXur;;fJj_GnGeal$Yqe zKNHZ9q=vLIp4>&C;8kr7S`U>dNr-r?F~1fxQza)r)xm5qcuO>0lCHo~{>`<-M~z8o zTxYT#hMzR9Puv`?24QaOq#<2FkFT{}h1ii$@i; zwMYm+6--1-Y$oNmLhjY@_#NlsCMFQNeL`PlJG$>Ru)@uSLR^xQq1(PqW7eD0)owu= z+lz`X@S3{Ic>^v`mO{>uZ^x&4WHNvZh{1v8W-)}ysdOppU-g_riS}}q-M>x%i|r`m zPwu)W2*vpD%X^%`fm63<7deKLpgwnuPIqP8#;R1EMd3`47lauqov`IIQ`7|{kWTW- zuhamoUcUiR#XVNjKEK>T5xa?sA6vhHw`C!?{fF z5!;sG7X39Bc^{+4_hdS^wz+%~iPI)1w&3UNh{JL>#D#p@^Ki&j$rj|e2Te#U#=zJG zrpr~_pik(t=zvB6xH-sG(;?Ub6cIYbS&piPj7;-I zmxW04bp5UFrlkA)Hi&+t&gYT8aUwS1TcrAe7|bfa>r1!zN9%+xrI4lx&&bQTCAEl{xQd5 zLom(t<5H>;EVREX@CTyHR)-poS9iKS>a-7~$ENB|z-hJgk7yDf(BvDY_P?A|nWKea z1-kaZJ3W!k>|4w)U(k5h{j3*R5j)b7%77_v!L$H=Ib;yu5)z5vM^o~RP zN-6k%Jr8e3EI|t8>qhIAkFOxnC*2go+dul|>jpDur?{B$iQuS0FLEwPqXFg6Ik#tT z-%hIj~)x%WlBLXoCZqJV& z3ogEVA6^XUbAr7G(q$^aheeB zOGrYVXK1v~Uh3qYSd1pS(8oG>V1)wG?~SEY%bf!!!@`hham2WUH9N$|K-rJbWpS&_ zhds^w&pxM<7NTP|1|~rEc)D-~VLAbbalOzf22+WX*yu2q@B)8LE8?PCh-Ii88QFpz z#W#w~nejfPwm`=dKGaO&mP~!Wa_Mpp^IWe#XAlQNhH(dcA=~+Hk^Qd*_g0Qp`X-L% zw0!#dhF=qftSt>44DJ5O;JzY0#12seF7UI#K!VI%A1L(dJ3eYm0-EhE-Vhc82;%cM z%vA;;v0bqQk6TpD&o* zhHoeWL4mi-Lvdv-q2=uN>Fd=IX8P35Lv;DXnnfhs#}g3hYV?B4L_Y@tO%6`d3Oi!m zk4~BUPZCvQE@A@}ue)E;t0phi;+;fBF-;62oQs_)raVb^w=u5 z4KS_2@3#CI#AZ~DV!Ltz^rvjZMMzucjufzKbR5(~ur%rKf-3FwW=Ew|CXD1P*r92C zcpOMgoP~!}Jqou~G~Ie)1AQcIoh7o<5E@l-aT1L)1UfS(Nq*63C8k!}}K=sK)s87=qGK)x+*Pgev{7IcEj@=i5 z{WWK|-VRo<T@JLmznW=Ma9AV6bPTD&!GG7mGPw649 zOrSQS08{tdO1cF__<`f}C+>z|89=#)y!j3Bh9hgqMim#%X=w3zq>SgzOeOKrdLekzwnz&8t zQG%*-rlsTf0Xxx$`V=d_`?9D@#q1U=|6uspEylqulY#+d@B+2JfiJdsg`m(HuBFjq zij$LW3<#QI&pg6_G>+>zBp1YsaX`j@4!q}^#|$iSZc&;?NUfo0S6#Q#o8a6$fhAHH z1iG>F>fEd(zOgKv6A&`6-GePfKUb{TM=eQ-ZntxljxFN)Y22mUd+yId}>L`cbgztP@Gx&d8VBd%aam@@@aN`_5 zUb~3nO#a?w-}U6fp&b^87D?fPx+%8VM|LfzqmAQI=7osTe*1X6=l!GRGV$C>HSk4^ z{D13x^si;(|D;DNT?=bt1qV}o^M4}81f|ulvN76c2GhFbVt}1F@l@zks8|^g1vXwl zV(bs{d|+@S*>;OrsamGxis3+%Di>WBeUEw2&5Ub4EU**5UBn5t-87j_y3XUUPjAMP z%k*<*%lQk*3HD9r&eumyZLhb})yr>pJB^XiKYkA1o}XTewe2bGSj~^4lqy`~FH*QY zhhG{LO{iCD&cUNB*{!$gjt^2YMy5q&$$9uRvM1y#IgpGbUb$)H85lHW_=a zRz!E1cv&cAc=-r-S?qK9Xqp~VT8%$lx1T5M2(+Z{uAq)4st>#FBM?V~LQL3eXzR@8 zHt$?%ah^0s^5RXwMMOaQ$8F?WW`Cz9$@C_liY@G^F*EI@(XJ;6Wto+5S1n_+O28JI zr0?_UDFHi^`plx3wj{ECEi)#yp~F!BC6$VQl^-H(0)SaWO_FpcKAUMi+P<0_76O}8 zaqJscaW^z*n8_(+A=01i6ckcaEs-6Pqv=HQ?prz>+`eL|7u9ZdFmJj#jOu~?<*xG+ z?OY1|s9y_lk^nYaVFQ>ASw?|mx`u3>(dk?&eK_T&AO2-w?*#}cH_?I03E zr&KGY7$hXo1yqP_xl`#gAiS{O@Re>!AZ{OjHuP8@SaZlR$;pEavk&Nb!^M#HE4vB< zok(7()%&_(0OWAREVs%hl3y{1L_re|C6oR0Ur)tq!U8tSPMBfipE+a(}*DmKruKvgijFl)`SGVj#cL$Q*7#rwGA`HUq zD!4Ly9Pp;iwb?6{8zE4=RL?5nR+m?A7svO`T1AgnMqeokcT-y|? z4fdHi{Nwuk*;tm=CRR(<&cPPYqohI{-T2i45jJ9SS0rW)X%mLbBqc8Riol!lbLiyGPZ9Tq%e*p+>S>KSYpW$1q=}G~aMhdE9E&QW#kWmFJSIN%C%c&@DzN{{0 z*;QF`!U5+dLo!!2Q860&P)g$FcT0YlT*vv&dLVTcbCzmd!*P6@o-T;iau=3v%RW<^ zP!hBF4()`^4kuVdPjR#2Tik1@0wdqvgNT?~-Ep!l;f(`#BBwvu6NJ?98lnRVe^ALi z@bIXNFBG_`qZY@g_9c3Jn^_1FKg|2}XJ?k)EC|uY7i$K9|6LY<brGuW!=MHSBI@qERWKc{dvM zJiWw2t7Om0mr(6QAiSe+A)W9Mefd?L&b@jK_$iEd;Hlkm;JI)jiMpzPp~aI?H=L znn2flFk@U(x`sqgleWOq`b_o#EUiMim>0E(CyB7clZWOV?PlVa3;xzt8NGu^BZNjeTmMo9*LU(99!r6R~?vL;bmrjWh?-Qv$_XO|cfN%)kcL zBoJgcZS7<5<99LV3$NXM&|2CU1xOVx{782{4tMm|?;YL=!P@-=A>wJ4TQuh$LNAC( zUAr%;DNPoeLMij~js%G9AXbA+O?qQ2sTO5pfK~%8p{Tb{f9m^I=dW+OzdC_Q{h{X>K4VvGRy5>0is#%VmkZO?l!xvAatz226$2Ox)@K`V3LlbwNPv493-Kj_Ux zPdlM>Sz4CZB0Z$$DZb6VVDk`^`>=xSjc+?)+FyuQw(>c-p|x({A>~!lbUzExN&WUW ztTfnsoHBz(uU;sGG9yv5WN|$}&VrH}PEuZG{iUEa8MwKoLhyD-HN{zx4s*Wf zQi{EC-8lJzVEJi8ebHc~L00wpN#KjU?S(yi;>uy%46NUzYoW@}I1nqCdfh$aS}%yM z7*c>kjiJmzldd@1&V9j*r|F}Dg&t)OHvjvMYT)@)y3*nJ5b6lB5!JadfGsSGF*2X% zX6g(I72=E1YgTt2+`#V~n!v&9x2Swvv? z)7Cx4e*xkV=f45sG-pC<(CbH)4)xAYTg%cJUCd@mckP&u{`<>jPdVXQ?g)lc#1lml z7wEMJ(~JIOO{Qh#6wtM>Yb4r(OWZ#qt6W^E%l0ok5dUxS@E_Kaa#9j~UwYit!id7@ zmC}32{NSLI9`6B#0-VrLI7*e{fms&K)QVw{o9)jVMcF^xcKXHS%Uz}dmRUJ(56;If zh7M0Ty%o-m$>^Bg@lX`ZsowBv6?3szU29+1wMcKOD+Kga(r%2cTs5T1+ol!SY9bi~ zJmEWJ;&%vT=;9{}Vr`RhmN+mNOgeO^ppfL~bM!-U%p{0kLU<9j1+?Uv0KeKkaYpXA zV9jbM2?GINyFNG^6q3oX9RuIHhC$4V>CpV}z_D$KXWdJ~?!-7?glH0WfnyZo)ZyED zmik$oit)1~2Bu87SHfyQZAHH%OU15v@nG(M_$%drn}wAN%4p){O&`}wYNbWPCq^36 zY1P(?wZ%+xOp&$lXQsqehf?6bcQSJ7iJ%#8do949C4p2EL(e*mH+Mwd zSe>S{Z&%;>CyiIkf@;cq{Y98x`GJ2g$tC;0(>T+A%vMQIK2=Z`Li(fzqUpEfQxhzh ztCund@c$tJFF`G@1p+wWt8&#MrraF87WTOD!=&u~-RpH3eKRkTW1*)$kJ0N4l=qeO ziPd2ceW;E#`3C?9qx~hf`-Ahu^LeJd)9veK*Bi(d8_$evj}4n4haG)-H2EwHrYT`( zv=)TSUT2=^`sVrN%$9DkHWDR4I?|xWlZJ)dAU5e`iadiNCuHmSCBf#j z-NY-Hry8rnAynV=4_6nPz#c{u5(8?q2OE>(>s$m!tcGIaVkoj7nu@G@f*i!41DmXo=_Sz@T6b9`1&i*WKoMf4k{pHL@AL!%LxPROLT zZo`S>?k3i%IQCXfK%*QSjirT1#-#9L9kS)Xz0MO9Y>S#hW&@M5yV=O#Ba))IImLhr zksvnybUZ1qDGnYs$O?2vPlbSH-B)39XQ?1XoGJZ2Z-R~7LK{63kxjcdnttOt9rmhd zF6+z;k~>g1C)Lo5Ys?HqcedW@5y=NdUk$|#zi;fXj|3~*7P@a}N`wXjM9_nfglX|& zMkg$*z0{Pb53jVa3zc)Oa&{zC!#PBM%%G~^HDNEQo9Z-6Z!f#@{G$X=d;^Nc#KmCO zf2B1JtIkY>Nu6U>@dt%OlpR+iyTm%P3qe;FLEPpf3fBNW3!%&cp0u2X!5XzU7aQ2{ zHB;~|PH7~&X$oN>auVvAJw@(8i4^L*2lsfCnx2sJf*l-kh)bak62U!P_<3Vc*f+pE ze6eeV*e59nztZ6_LlulnUA9I}NEpmH^4GIit3qHUV1k&faJ3nTA+zCFiINmlcCD3(^K`pch@mph=8QZh*|KO|+ru(&z5wlvQPOoJ zRB{4pd5BR}JQ#(@VA_bV{fMxBPQya-t>8)!#{dHdvaWn|mL0L#!WYb>3Ez}06Gdm_ zD73(OkhtE)0;wWqp@Jfa@=h&Ha|fZHQwor@rq=i+NrU3MmX@#R?e`cDT8{Kh6d9a( z<-EdxV(A72>p}08nE(gvicEceX7cP6r(27*tBzRBJ$Jo$VSTJiXNk5bJ|;1_`t73A z%rQS5K0`N_0~Ho+S}n2PRiRh~Yh9xEz+>xN$ijkdm)KEX*>qP~byu4Pc#ie-{h=*; z0~-epM2X$Fgi-@COWTb~re{?W0#t#-lF$srBWRHMGAZfZa^{W<6RN~nwFxg?5zTI7 zrhO)-q9%{yUjdS?i8}{>KKX6@+QD4wZz@OGtTFPKk3wn- zRb};SUsj|VlkbM#coB$w4E$TQ2KA;ivNCr{0JrV?COm^~MKahU; zyBVpQwEOF&t*6*Oq%m%$JWo77?9QTo6G*0q(?8OC2R85?acOA$qiHtL3 zWwgNSiPkzWUwdfQsK2D8f)qhFF)}H0$4xBQgUr-1QI@buM$i5okRcF-;53#{**amv zu?n`vI2rx>S!fy{kQ)VxNUA@kcFLDYfUE3#i7(}Vq^lzzki8O%CGh6<1{bV`B$v& zi6C6OggDYIvPgXVsRU$3s(UF?v-~*4Mfn);8azpBG`&sg!lmRCKkEb?QOj;H-53L{t`d##56lCM8a-n8=OtXGTYB|UADHc^$!*1 z(z?qg9sTUgWw^eKb)yH+t;D^|F19iaX@73_$A0P;U(RE6G98jb3gVxuY&KWII!IaJF5MvY`Sqe-vvI`gxGM zFa3Vhhmb@An@8z$uBs)5loopumVDkcC((mq%AG8lr>TnMP(ln^5(!<}iXOq7pMtXs zc-Wj#d^MH8Ci>O|Ei}3`;pIEGl+JPe#g93W-Mjj3B5TTV8baY;-Dl^o-^v~dA1dRJ z`*_a7I*;aMriB^94p!Q5K?y$j^3CNoWECT@-NWKrLIkX1sO~JcTrS;J(%2e&>a>4( zRbd>Sc0xmW4gS_&xf>xFTp+9jabOG;d36@@$cnj7Z>KdWN)nCn#Hyn6UPK!h3SP`P z*Kya0udvcmBwl|$I*svsB!(uNR9?Z>44L5S86Vmqu zTOVK=U-?}W^TH~R?e(WhP~vyy2jN#7SnxIA@ZSd-{}0RVA3Ef(vw`)Ov@|_TV6Cvw zR&s>Zk_;raehyg9<`aNmJbL7h4VC=rJ z^CO0o*Pp06t#NaEx)JBRF+gbzp9LAW*gqC3VFisF#T<+HOmmIZ)|z0iOA^JbIF3KI ztWPqhU_}+g({aF$O$y+HVh&X?^`R+e8p$*SFO)cE({4Vj4TWWEI^<2U)QAd*n{2~S zg*_t$wnbKfS$$<3rcMiy%~ZHEUL#jL6r-L7&v;c$uiL4<`>xZz9z{p)f#5td&N`Z! zc_Ff9Nrg9X{R!$&A4DVf7d>UR=@oX8X%QrNBxQ5zKvfPyj+>ZhhCN1B^%L;o@Dgcp zX7_v6Iq1mKGin;6F5}eiXmb_Pv?A7BzPx<-}E*FY2Oe{eZZ#A*-*lHi`ap<)qxi`!`iEkQ)}+C35NzPKmbAuP27qc|9le85nS?=wAu^q# zs50#+CfXt|N{-QwWoh=I&?&WHH9?`u^18w zp+h!X=CYhTd~!t!QPC%h6TR-R=_Z%7?WUX&)613EuY6)hwz*nk3eBNsD?mpkc$g{p z!LljeZlMUc(u(VAb3r=5Qtncgn~CwS%)k-~#a0QNQxp0-k4^;iHf^% z=Z;p}tf1Qx8SK={s9JW64~}cYv2TEL7x?o>99T_pfEuZ~z1;;DnIs&+Kpm313A#tb zV^ZSwU}o7~dk(hb*HGn^ebqpN70Rban`5^btA&fO5EKp$? zwI&80>s+Wi;dY{-JITknj0J3-3AW-^xq_{v9Gj@CX`w70kT)zZ0UghR&^>CTh+W77LGO6lY=2lGrI=?=g`SPs* zd$5AGA;poA@yE7{XM)g0WdK9Y2I65aD&hI4eM$W%jl3?G8%}6WBDk)ybKcy#Zo`8? zi|2$VMu{jdVY&NkENc|_zB1N`D_kWfXa<6E`@^rxUpjPc^){?zG_z91B?G zXB`Hvjx;&BM5sr_mBf*_BCr z9k72N7yjH6LK)&0g7?#~ut@=Z7BjPPN#?w(9yU*bWx6JN6l&r1`uLNfN=LOJZ@&)M zp8s1I{X_QrALBI;gPLunc9P>ciID&!)lUErC@ApqLzT1Z6IMzuBkKrYCe&^U?wX=a z`2KQKUtGPw$t>YkrZCDGZVpv?p$QNd|2chBMTx_pfb_hQL@; zBt-|>cegtV@OgOi6h<)lv>5Kp)S)Yy;b_oTcKB89puEQJ(C!$zcg+@#6GDiN^ay){ zUBMN5nCzFt)w(LfVaPclzboT$2nCoUBF91eBAr}-?vFlZ#9I>trk{ML8KR-L%@Qi@>AHIGk1f!AXrWa0TJTyE z?N)7htzJ9E+5{J`L()^o*MUBuF2(vGI+AU=y*-4=lW~4rhIBc{k;}U&5qV>tzKt-> z43obSq+C=;j#7TZ4v0ys*nIw!tzd$QC4e4K&c{&BT4*bs!g8hUV;e^6AiVLKVXO%> z_Af1Uq9iwn!oL_0OU2DcIyS;GNclar!)MlBnQfqIR_kq8)^cM`bDbJAyj*tHv0XRV zctM?&dr*%d<^?$(GRG-gnttvna1Lr!S2Hoi z(YFg}HuuBt%--xlP^xbP>=~)dV)Tv42RKPtH_u)UI{M)O!@Q8xFv107)YczZ@fQEg*EqdX>NL)J3czS#PkhKC7bJr`I zcetsV!@4gvHZD+NGU+w2&a^eotGTOIR4AXymF-M_K5ne8H>DASzblPRJdU$6ZjO1} zj*oq16<<3+zfr|WFsI`suVYIkyL<4}abi3Qxe@xTcer~}vv9Ss=I8v7Z67*f^w1@o z*=+Pv%9ENrq=E%n_v<)na}f6YX8B&Vsy_Ws1eW29vgp zD~ALct40rVN&{~q(v-D~Ie$zc$4BR06biSgFJp#>I2*5)M0$!G-$_Z%q>da`9ygfb08J{gIieoiGEa(P%_-knL!z&7Ip zu?I?Ef5Ejsyu{StkNU~*3P>XUQ2JFRmc)Jq0Ac@^19?;jOnl#xjf@XT$tDuLy$W*c zT{lf86SHEJc<5iW2egmb5Ioot)$u;n97y2A3t)pTqpMshkqXS^aAP)Q3#DF7r2N~m z1O|hS<^2>m`eZYx>k_aeif9>oj;0L_tO)cReT4;!M8C-N8tqOIpa z%D}2wE?{#Q={mu$9A}F%=~1jnW82e7MNG`f6*9Hz>@jMe^gPqW>vOo4+-k=`wd@vV zM+T_m>n{GjNpjWcm6gQD)}p%6p>1WpqCh@8K*fd^bhT_969gHqeoTaw5)$7M;t;17 z0yj7!o*MOI_U*}ONefx!6y!In5e9D3$%=fZIAKPG|Oh$5C9dbI(zEEt`v zv2u&k>yRH(B6n!x*QnU_BNq$`?J;-M2s#Cxt&_B7?CmgG`QW!!P>5r&4PQ?B&32Q# zp#w46`3dSK&z`;gxr3^N!SIv5qG*y6s_FEiaAM3aY8Mg13PCYEQ)X!ViKq-4`)IBS zA<(fEN2M7f0gb0(m$5mZ3D1h;EM7M*$<4kbfrR=gJ#tdr2b0kqDy;UzWo%nGL%C%I zi*eU>KeC{&g|KY)H`^ZNQ)!@j%l);@$rDEB1QT57>hIQii10ob$DXbneVl{HzVl{* zz9yB3y3?Xa&Khq%)zi(5t)BIxMH^V`gd(a_QN8X5(+c>dRphV-Vc%t*2Fluujf;7D zT*!D;KaPt@`Px1?`55l(U8FH&DjuF7xu^x81``%Hc}LoD71Rj9r7#N8v0-VDV<*Pl z`^#-mjLyke4+{=#-u@_+S~RC)U_)n$yuuh}3><04sy_7GvyYlcMEZHZzNeDNtnEXK zv=rxCmNqJjzP~<&usD6VO2?W7!oL=-Q61xk)VOo(?z9~xg+oAPcG01K zA-XUKNe*pZ!*b>}rE*WBQ5wlIOKhkWEZP&A+mwP%?zlEQL!#eCY3>L1hl!st28GEc zJU%jFOX2iVz$JXXeRb+Vb&fRB1*I!-dy*)hp02?`S4COui^FR9QQ|LR8N7q2%xV3Jq8QujVI&Pb+t zh(apW=cT~W9E8O6jYE&)T#6QaH1xHtq@-T1951ZyeX&aU-4`cz48wWYBD+B_9($x*!6Ak6Hn}9lCV8~jivPai#8LiYq9F#z9GQCBz$dPzBH&(E%@iy6 zfrN_zmnX`lfIrUe@T%6;u_T`2K}K=N2tNJHE2mgd}6)BqQOy z&3#FztUndDWSF4|=03-Y6NkH2QMp*3En#t?tQ9-aK(%1h)Q&?_d|rjdDWxVE-2z(E z!bnR%RldB`zHRQPR&Bnnh7%*Lk-2zfqiV|Bk$seZ@nvz|@=mm3&b)Uv?SkiS#Uz~j z+>J0gco61j2Jf`R(>p1YR+VE^3q=u@+C{Zy)^wVEMv;>sqLpbFWObaJyso2{t6c7)X$ZaV~#Jk7j1bsP^NyL z332!x_iy-?vHK--xf1xUr~G^x)N-tVxwp+6EObhSJ_W|U1YhXSvd-sD`hva65hxjb zLRXE$J%m1kUDJq%K>#kUd0FX^YAWRg2rVZi^;dV}@n}Msph>W4W;+4a*2g7V7W<*~ zoSI8Zy*juuNKA|6U5ka37y86crtm%&$shF6vW_@-21SNF@{%=p>Kc%l{-!AD7v1PE zT;)-Y(qUs?9noSkQ4TJ+DIrG!9pl^YSrX+6N2#CEYFxtQdQ^EZ0ZWnB_% zOA;*mD0-UlEr|EV>`@o_-5Qq0U~@axs4eiq)GGSGLLsuc#6YK10M1@B9Iygc!AaY) zz*A)29^swG_ney-=d?1M-t9D7WubXLwzVk2xh*h(ZBm%G0Ki||!9y#c*Ub=_q###8 zi6=xK{SBmHNyOK4c$t<}#TebZ8Rj~toyiw~l?PUfS6r0^AB)!{T9dDifTb?tWwy8z zz4*e5eoGUFRka1Z3sja8n5LgX9YcDMTKy9B4$O5uqb>pNWUrxk*12MRU1GOc^#S)9 zN<7n`*Qqm45nPM6x@M2TqrcqTWY(AKet4SH6OY(8PUeTQ9+|igs{^_eWknow`}XFi zXK!UA*-?^*HUaE5(u<{R z>lmx6Aj1YxQL&1Ot4iEwk6GhJ2Z*UEYNo`WV9zTp&>nNh``Ih_t;+iel{WmY)r)2BC;%!qhEo5Y0ZNXmoBIG<`#d>yh(+IXJgYVi*~c{Pf&_r|+j zoxxoStDd5FAg&RMcQnE+a+02+8i>j4$je=5kL^sqLmT`|V;EN-)Jvh8_WmW;6ys|M ztG(w9-=DUWlTR?6h?fJWT&Juy{#D%~S0tI;>U%C}bsYrgk-Vdxj;G zhNccR8u3X3S);Yn0|;?0IEjrKiBdF)f*YC> zp}_hET^PgP+k{63?7(%YZ&#nIKN+!A_Pd9$pUMHX>wJ(nt^hDU{!Hn-+TdASLVf#Y z`(<7D?{m=qb$~K-`tkw#?+x%me?0XMeaAl%I_8|xh)~p)sf9VvKCuf$t6bn%Ww@fET#zDN$MTX05`qS+Ssbd?4t_&}jI+MuKk9)z_#_IP zrY?wpyfdT=;ux!3j-m1zlcm4-bw`lGBNwmJ7~Un~KG~+_=ow*R4b`~K8Ooc6HlS{E zYWasc0yfp~F%`~Jdh5>q_%7tr2(_0DS#OD#mF*6qoXuG7^yb}_8UD(3()u1VhwgS! zd??(>RwPF4b*arT$N9+;aF=A=sI5IlhVgl9Ii0p5m<{dnrp(hP24gJ7R^+U}CUs7g zvOpkUUr208MdDcHLGMP%c`ka#kX&(5MbNa^ok!GE=9|yYBYMv$;cZ@Nf z@h^erTWz^k$rX9;7^HlF6IKS_jw^L^iY2{aQ~VP3ap|(>epQX1#9h> zf1mzJN;rMpsegZ$@c%Py@z-4vu(mVgcXV*Dw)&?f=b5l9|5a-Zl!@~xClcre76Mx1 zm))tP%3Y3DG(s+g&{!xk8ECZ3`+^da;1vt9G-kYA6cus)Co(Z+c4$>H~`&MRho9K z9TX$jCFPD0hi>o@rG=5Po;!TbY2ku&ks?s(^cA&%Aq0FOHq*K9V#czR#eMug!|ss- zmB0o4l_=s{ip2X8DTotKA=P>cTPiM(>gP$O7Fjqes6%Un+{eY2CUSVIFk2hEDHEc# zkw|`mld0OL1$Kir5z>8k275w?E8_!_5!QhkRJEo6Sj>s~QC^H$zh-JRqb#**p_Az{ zy*7hUrY2#mmK=JoHKbRG%>4iz_N50Lb#j^TJueSN7etIJI?O(?ba!a|GRTq2G)lXVG8V8u@WFRCR6ue#3pi6!n_Kn>nxOh}>wu<w?5M+(eA zeUW`$b{+ikHRlrxk_{rp=3A#VMZt}$4|V%7V>{;;i^K29H-jpt9eZau*B9IAds3P& zBC8#DNA_`bb>x6GwKtZhTd?g$jJ_Zyz**OhnM(%`k%cdot% zc4-d~QYOg9DfGHN9Sr$1bMFrNPLuK>gj#nGT%2Gga<8!OZgIT$u1DRk&CkAogb&}o z6Foh=_d|u--0+x@6veWaJ!&Zs)J~7on8b?pUP?F1Yla8=%H%~vWlv84tQ(E_N zyu>)vFgt^1en?l?ZFP>gr4c2F-ox7CwBCaRO+oox-0Ks{DII4sJr1dNT4tRMT6edbY{fN9*zM zrvQQ)#1vBgE2lXBx29A7x-I_K0{wR!X7wkBwfr-O9lqr%7R|)QzH$Bk5SS>dBqSlA zHNsN3ckbNI&K#032rxA6S)=#8s(BzigAMRu5(;rqtKmUDfYhKv5YBIg?1FHpu^(d) zci#x7biarR4+W4k+CXm$;7>++hh+Q6`r@0_ugAYK zxctV5ngz9rOEqBAJf-tH)bLy`u_;e&}3 z-3k4R$H_xfZ%xISDKL9yFS6H2k66Dcc9a}8IWlO!=*uwDZ5KV8T@8nqT1$xK=||9B{XFS!M}uHGhg^Y(Xq1xwbIh&r_}9js?=Q+|;N-w;z@t%`

eTAHb}o%*dMKG@moZ&FmqtTN)m|uKT_UGDT@b)K9zq*j+$AxU&4dc9!hFZD7RtAO6d~hi%9|!#1fuR`CA|u(*E! zRs>?oKYOnK3$5hPxDI(ep%u)1Xz0zpw-RBo3hNB^^62P5F%|QGDbV$PF+S+Qsy;M^ zK&^fmK7jptTR^drP#S-tl?uI2F!AgA_x~+g@&4r(3b}m6751k8ZTobTmy#jigYz7R z!lPsGAS0s9WvPOCj$FHrtc`j>5H3^ z-&$I>QTB8G_U+~hOa~BBtRKxt`rX^v(yOPVyHXou4YRrPC#o(2hd|}22Ak95b>!K* za#9muV1GC7WfQyKG+0lY0V}%v8}vl<&ywJnn-Jd0LlAW+BS$n9bA}^Mub`qHIxD;Y zDgoF0J;apmWa!0R_roIUjnBh+xBQ~1t5xZ$<2z0GG6`-rCs3%mh)d9QNr689Bd+0W zCG&A4@@HMVNdK!sXd-&yTkPwt9}$@q3&KIHWU9Ziy3qE6Sn0N5a&3klxztE6e`RSkBNUq?pdx5RVYdxFPk&>4rO;4gsGi#2Ds;?20Q)_Wh^ZGqNK__VTid&c$9J&{ z=yNa~z?$4f*gFeuv8tXDq5(fN0zWi7muwV+#49=UjO`QR5A28UU5Jl;Vc+a;3qpkd z4jKP$0pR?}+spsF02V{PqRpMLKWJMIkFp^+!zUny50A2jN{*M5o>p^{mz`CGQeq25PqVH(oph;~+aPEo?Cl^VeIn`asL1bUGGNb;F@@Z7gY028O{h zGi-HW|HFOapNKr+tCMI(2aVg>w4^%HbEKTj@x(|ySqbHE zAe=Q!7(o^hid8Gwcbw|Gc=qb$jG&(0+@I529;p%d+OG~gCvF`x582P7va~w^i*xn( z5vyNq5uDzy2(XB}EFCcJ`sA(@-AEjK?yYR#pE`7G4!SIy`=kk?v4;-xq{(#VXE#7L z5x;lfcIi8~W4w>g>%=dg(M5s`Cx=@b0aqD_9^i=hk+~9FEj-8Bp-=N){%WxblgNxE zj)GdCD%a7(+ikAE0%D;?`z>B?+0##qDC9HG4v^BWhac45t;UVvPdo8?Zga=+e@J`F z;JC6SYt$Aqqs7e3Y%w#V#mvmIn3>UH$zo=UnVFfvV&+$N-=4lbbEo4?d=XWDD(cVK zXJzKf+?gv)?_KYWdCow7sL+Sy^T8euJ%_L*AHOT59$54|$JxrGT0MN`Rer>V+#T=E z=TL6nY`R`fmtswL=~Fk~0^U_;Bsr*&8GE(J<~{2h4gC~8BR)asw6xlNzl-O~V;;L@ zli*A0L^PdmKCFPRk%>xG^-wYWJS-7^xA+|4r<$ePQz})pm%3r==7)2R?93P}ZRV({ zI$s5ARO{UED1W)^2|oz8O8ShG>xE*AF3i3dC^^wXFzgxvRZ(;7#)(Lx1&k7x4i> zktWdER6)zp4@;<>lP(k_;2~6VfM!yd{7@IyvuTfoXB=M8+y2S20Cc9yuk?)0Y+b{W zS7X_;6MAMJS!E%i^0@J^D=C(iCZ*-JFu_+`raU&vdTtg8|~mhkwlH2>+Ws z{Ryf6&7A(AL8|8GU zACX093MU7=2GW%1j|^>X9KsQm3m814uM?6u6{G352}N$&wPgdIW*+eU-%aSh=daQ> zjz&Ue4hA;X)w-u(uJ%8 zg9?3@K#mOky_1H0O$8|+pyzC~E!EA&`R@7P8oCqn7*Y%-GW6g&whMjrHj?YAGBfqG znYPi3w+V6*1SM#7P%EW>(J{E+pCy-A&~tyRh}C4!<&BIELqXf*FzwA#0@S`zRIF{U zDQd%*-24RA{Tmc>2{iWJFxCaLp`lWK3<;3*c~NIo5n&L!V8c$+i#KoeL!F6+0fWCu z`c6BClOH<}>ibkG1GY;;du%^dIU_gUYqjahiYBuwm+MW;^O`9YsPsl%a!O&iRen#4 zCRt3er6CXOvUtZF*B2A>N4%UYv9(g zc$Zxrin!P!E~1nYIk~)X&N~Xqz&Y}42naeQit^pz5v@3T7;tv2W0iojf=*wxYuM)G z0z<8@umlA`fQb<^PzvZ0B0E*0?d9JKh1>Z=q<$sX3;#%i{u*Nb!yEqhSNXp|_>XEt z;=e=q3;qg8Ejz%o)3G!Yv-FYGHW9PX{inbHO+GQ+**}O6heks)G&Z z=5vLyp=}*x^%ehpQaw_RQy4Pe2qfAA;0VF(x!K(xS*MjkW(uzh`N`fzZ{Zs^}= zmqRwP8v!8Q8*ohjJKCuL|F8le+??)@BT{tKb98bLw>Gx1x6*S2@TtF_kyG>!D8P!q z0F&2nzR1i)H3&ae+(iv42)}GypMGUpVwX6}D_b<)uka)~C|G^^!FqZo?LYV`*gh~h z0x3b{^+JkG3t$&ef^Y!btF)#wovH;(6)QbIJ;UA4`rjL-S<&44*`#ZE9TvT&{X;dXf_&1ZpfVDqO)&A zvRK*boONv~lit6ZNRD3d56c11c>j+!{})i~jqIF^931Hc^(@Ww?SG%ZuS7`UkDvcl z36=TRT-JVGziHlKAFdL@cU)>$Wp3te3isk1d>-lLkB!9YtJWYsNo4%JfbfaLW=7`+ zZlY_v-p1DR{N()(VjD$+N8_6(fSCo)%%|K&@1J6yYR0ILxL{~nr}bS z_{gWqq$sxpXy2V(K2kamKM&<2ijBdiru)X9mNF9of@;adf{Tt@OUIfhY{*p}$6k)O ztB3ebRxY{tUV;a6NHk?DpBCYM>VfkFI720iE_NDU*Q}7|;r-%Z@A=H{4}i0@{6|#% zMMM5P&tInZw?q7^_9ye3e+~U%ZMn1E)3e)1USII(Ai9lBboC4o1|_H^XD7r*B^T}i zR}0d#dWM@~vNU!j)Z#S8hPqRe5zhLCn^5C)G!imSBctM=$DbJm;PcZXV|`$HzR{5&I{QMjj>I?kaHcq;eG~57B5&e&-_^Sl)=Tpd8>bV)&OBosd?NPksq%Dx; z0n1d48Ru_- z(T!+d{Yc2AR*S3$T#7t0pL;@a5$i!q-znKrNeF$fZe4fiXMvijswzDc>Dnm7Sirf; zvpQRNuuiC@sP|&J#C?}6Zy7i9u~DY|+IFOGe>}d)for=Q*2)g0Mrw5&faxTVWux-m zz=6OXyh~~k#Rm;CgK^dELMAl`y4;w~cwxIJkV8*mtJJ}Fa1ApJGG^)C#j(WS2i}?Nj$+x!H>>@4`qbzA zPIQ%2a>ncN2Kk5{q%@bFhli){6fyV<}<6MXC5jM zi;+0B^E*S$frP2lH)@hC+WRkVkb+X_sGvw%+gu`jl3Dph z6)J4=*V;rRGI5FV;}F1_Kz7k-vtTk3hgKdtO-q^Ib_$eT<>%gmZ-Af z602CyWVtVIXwPos;cY#Av?;|W?%-@UJFX2@X< z%~F9WSdn23HHD)O$vO8(6;{izk2UlmMl0&iEGAe|zA*&uP{Q0{MYKeqwnvVWjgAk2 zmo>H-r+Y;$jI_=sZhj0lb8{fAlgW0PFoDcKz2&Fw!%WHnOs@cl(=x2FjmX%*dheREo#f z8C%SoA9&ZVVK0*!3G+P|Z3jd6^EdFTLgjtaS!qn2W=+el`B|B!D=+i{{F2w3zCdV+ zOuXCfFyV2(>ag*A`}{2Xq4GjXG$@A?QlG&*aC=8e$gY&;;X+8tkKT+91BcR|W&4|} z#b}XgdF`7ROvoGt>seBkTm!ZKq~FMh7{cI<78uKw4M?ob%XhpEqsbGV#sk)tx@%gD zFm9Bxw86a2>{+ZeY>auSLwW@z##sL@xr>+Y?3vO}gg-CdQf|U@=r?z0;a{1*#F@XW zM`Jkuc!zNw)YS@Il-B1Tm~+oN*sl)6!C7$uwn=@ZLPaFYl*?EuZ`*9K_oK>Rut`4sK6^$enAd;LP7F zVA1s!hPsm4Qc}vDn-aFuWn4yl6pl; zlIrseqc=uYp4w?tp2i6dS*hbsx+)aWnRdN+U3oid8p*}x*OMH94MA=saIGYG;?D>v zW;k#xhME8R#m;4L!0X<^1iz)%9437toKLZVTz|6r`dSTPu#N|e1FtJ;{M*6QXa@-%Sm31FV9uqX~IW zgU}VhTDRX@Q+j65i)S3Cab?*B->5T$wC#|@DzWIAIAd-X3%XESY6mBU)3c+KVm-uU z6QLM9c3sULV->Exjk9?HUf+Khk0-9?+CZH7;g(s@d`;)&GG#em zsrQ>?dPZGxkbN`pTpwbJFv(~eeyE90_foUF0`6DkfRKK|#`Z+jW>P9Ib>W&F#evHr zQC5VtM2`#hOX=J);n36NMCt9g+N)I!(#8yp6$~jI;cCy&@ zS5by5&NeTm#Ii583W8@DTb^+p+HT*b#~9iGTV-7?QPGS@dOCCt_m=7$DKp|Dy-X-H zUx}d-O}8Iu327|EXhs%1s+t#aaUe9k(Q2)GXt=d*&25ukswNm1GggxbpkS7b#sbC& zf}mUSx}ngzh;28R@t%HV^-8|^DlM6RzU27z#w*?Xv-@OWuoz$6k!XIfm3x5FWTB`y zU&9eu{(vQ?5U1tL&W+r;R63_9SL*>v*3>7x9+73?Rt)GX)exN&@NYB6Om?ui*xR7$ zf#I0rR9>1-kouOwNHqauOMO^yEh4Q|Jjv6N@eGQE%sB$-oY(gD+vA zbkzu0KYFJF)zKxn1R#AmL9nN^u~4+~E;x})Q;h=LA+3kSG>quO*Cql{Ye+5@lo;sz zb`CSsBgZLqG>x+49QPS0-Y$~dzROWVD`cxV547taq2xYb0)3(O5TixuSXJ6*@ZvN^ zeaq@l1|1Pgt^DpPV;E0ND9Lx0)&vOxU1eRKilg%m{mZYO8>17P0gNXB^q=xXg8vz7 zovidN|86{9^4gME00EQuSFsvv7I6y;DNQR>DTPCUFQ|A57ySCr3?KsE=GhN}q*daj zb1GlKUkL)yC_xbcx;7;@qd#XwpuH9|oA0w6&YE4Uy|s0KUHv1u?Sbm$kQg2KpWH<_P8Wd#0 zbT^^P5Td5%XJ(ZIO)S5s8f$i@57)g8L~Gj^{ZR2j*@8roF)Wc#RJQQUUL#}zH^$)H zVMjHFo7tsSWHk+zfI7n=tsVM&CcJ!*xnDVlcImf9?G0yNHTTssB*T1sM$h{rFF=gx z6w&1JCXKIpQLFXyV{1R}u8+KGmZDzdsuQ>VO$tkH^(fYj^mm6NS3lIeX2}SF=CNha z5}#Y{%(ZO)F%Fu0m618PL={-sNEOLvP?gnEfelKh7Oz&Nv%AcFc%{>cFD)C^bJ~$B z)5G5V48xvuGOZoG#9tep6hI zTL~ecWHLzLvM$nMEe2kS)$d(G)-Qyw6OW`lpI-@q`zO}=X!_Qv$GfW=a8>ji+9wz; zyAq*8qwNZW<|~n~QbImS>uKtJiNYaU+PZ8ec7l!ro!Q;BLVsoF<{)EuBDQ^q>qnP_F>L8 zeMWE@Q|Zohn}l8~CwiET(fl1=LZ^fgW=Uh%Byp z1>GtQu`1^gE>sK6Wx;1h!Vzf0j?_PXa4)EjRCUPZ5cJ9AvUuC6Oc=AFIIT>uW~sk| z{AH6)-xf`A0LR`A`2O#;o4;gA{ycV7d$V6D$bTX`@;-l3;D&ydk-FNqMdQpE(wbcS zVNxi>0Dh%I3E`&&i)R(ZW#ht1fp)+5M`;x7utDChcoJ>r^$_vC0jnEcO~d6GlL-MLs#v7{T>E&g7TqR!^Cxd=Fc9?^ z#|N!n3QN=vU{u^axzQ6)+!6h~y068Dg9G@)jYB;pVm89vr?K8=eJ%%buYFZJIS=ONJ?~k3q6xZF`akbSGaV^ zBLgDrDT;e;(ti~D0p^Ey_BmEWIas7|EcMcJMr$Ju{BMX&AYL9e_OP*aKH!*_3es{2 z?vZO70$&o!>z|+xEh_@srk7#epvh+kJM(u`WV7bTruj>v;FPQ@SWT+Kwr|-ZWOc)y zWp+R3^0f&}`HS0yZ?nQKc71~FkQf}Vfn~7-;#6doG6@r#(h~F%zLuB#c(*q8t$>|* z)tQWWO@oYjIdhXri>R*bya~4jO?iEZ4AfoZaJfZ^?b|!0xha;5S+1;z!1hWH*jaqP zXu!`MhAgwddXgOpJw$l%T7|(u-?X`h-{#rg^YM5ZfRWjMBtP7L`fgV`JwrWP01tMc zwG11SP}kHTLqp zhV}M>cLwYUeuC}KH@h**3q@GBX*BQ{sgXR>`SgY+OU!!#{2(8+6s=ZXVdb{i>|%V7 z;bF|^@O(W0`<16GnL*GrBQWVXIqJCBVT9B^?R4_> z{X}_U?xRv)drwry%*s<83 z06EJ*oQmwP!O95?qQ%Xen{?HV2g4$lcMc5D(=Y*|&mk*fR5Q=clW5|iuCvGkrkdYMn5tU*2+0VHP>es4OCHai~B|nmlXkkv&X=wl6$DpJvF% z?YA}=9yCW{6#yBV|9H2<_#coVpl7LPZD1r|qi1g@WM&Vz^8i$V|AvP|r4<=Ky-Pb- zhN~VX_iMyg^1WQe&tMG1()gsSX)zHg5Z~!|>1S|tt45h;1pNWt`(e}M!Y>rw8?e-( zV&;3VrW9v8(C_xKbjaVv%bmB%2xbP* z_>xp6>(7G(`F|O2lu?T-gD&ILf$#fSXOurLF$WZ6H_;o?XoCZY!&fh*~Rz{ca2 z?@UCx7=hJ34Oz|6n&v&)-2@he*n~-i`t3Dzt{5DRlx0}vNGEuJ%tsGbJ!LxO606Xs z6Qq!4R5yvJ^8M$UbbO6WL9S?0tQASsw8sE@Jy9T^lOe#WxZj<_k53C2rvF z`knmf>}d&jzqYp)ZDWie{1dHHBM#wFqw&XueoXL7)o zV=J5ok7iV{gFWz}AQ8wG%YW7q>a4I!KgKX^cdVNwsObz(=S)u8mWR8o%<%_uaI%r$ zx56{~dDfqna^p+QZ}4~w9Bdwj2e~!hf8bE@*`zzaed;TfY2eIsLm@Akj3%rcW!}J~ z)EXmRz>=*32UjL^8n&6KYoV~Ph$8QDjTQ?Qj?xDv(ZIAXXB_tB??*y2H9AV| zCoIQK4ZcW75`W`Hge#EjM+`ZC$uJX0!8n_Nzxf7IDP1H!lBvS`{5!`xo_(UT0=PJ* ze+2V?rT+is=EUs*S9gxT@ccIf2P&`qT66lo=4r{h7^EQ(iWpw7NNOgjfk01_@Oegn z9x_oMw4>k3ootPDY0NT7A;T^R6VFiu&vU;|)XjktxV{H?Cw`Ru1^x}bokQc+g)Ju` z$DGw;;(+HqU?c~+>~R%%rIJ}-;zCSDJ5Nc^bVDY zP`M)p;ROW#1EJrFO*7t^h|45B$s;#=2lfU!;M*KNf&}V=I65H$#w4PE+6dj-E~sJ& zK_>C2PJ)!AiZu&bfy0_wnS+7sP{pTP&>n`wRe7*gqxdD*gg5jgaTPPpz99MdnGtFw zTF9FM2@e9sy!@dX0TlI!V0zMvDM?F zNnb@_ue)bQ?sYYJae)EV{N86`x!h)1msmWX=``g~*BiPnX z55K_>FN=1*1YRF+1!sY>z4vs^X!PN5@6?aLEOsP2VuNZL>;}AT^7;W>eR`%|qaNsl z?d6fp&JRHBe#B3Y*gg2`Ld&&}N@9leKb<@VxzcWRLGn)hz3d9-1Xmi!!-uPUkO%NK z%T-@|e1b#B5`%$T9e)tXW_zSv-8;%j8L>Bw5FBxUtiWmK$sVHIWYi^R)UC-#6i2*7 zAQW`=L-2?`dVebONrje6%VypZUmiRp9pCFt1!qr#sNByr1lt*02`$!Ww4EA1%3?qm zkg{@uPDXk%r``Wv$6oQXxP>WHEtf0DCbw>DD`&a6{|j==b+zxuhVtNYi3=n+{Rk`U z0dZcAjDC`gF0M9?1&Xy!5Z*41S%yH;@g2CU2W<2UP~!_0<4aiD9o*n|-il4|gz7#w zpD>q8s){W(kq6{+H(M4CU=V%q3ainnaH0slLk`(bo#!{-Oe*f>_A2OE?#0mu%_6kB zo_D*s^@7v`IljoIUQ63^%AOds>-D%3(*pnS(Ywlly|t8ZRmafrHdg}uVutk}Rj zQ<3EFgqe@|BwH^j&A?Jx@)I}9er+T>T#rL(R~5HWtEWLr7``rnG_7Q7TH%a7A_c^S zClSx1Yc|W|&?G&1^$MeKZhu&uO9cZL#2qiR#6&af za)T$I!EYwW1j`t)g+B+2&LGueG?H)Dplg_(yofyJhI@}l*cXL3_rpT(hH~wI ziPLsWSr>yI0gHB`N0hTFjD0h80*_qM z-@+0(#(4G161e0Nf$HPLg|1JiWc_T5FYAi}p+!6={)GeUCtPCR5))MBR&z%@?6gU+ z#&mG|XIjX#$~+8#YamY4U|NJap-EvNTDHJpd2*)+_{jHmtO1pVut7oaOQp@4 z``!6A=HTdA*jP7)oWDVeN!^5^>qsFW;d$P4`Q*!Aj-CnV6ZO|I9gH@QK8_n5oK(tw z`#7qv9vH1xqfjeswy-Iz(-=5MKW}9nelTX=515eFyF^vZ5zsTGyTq|haB~`QZBs`A z)fA2)IMdP#!I7_zWNIv1suEUKgUMmES+r0XqEC5EFVB-=0zn@wF{5L6Kpx`uuhF0i zqkjo8g&-J37)w)*wNPOVyiKr40u?lAP}$t$Zj^Gn3kdsR#flNP^ez=i*qEwP*xlHB z%(_P!2GbMjgD<@=sCzh-y{&-Z74rSiBt-i#TknHE%odHFNf{Z7qDn4P?B$0~S=2cF z2qH=_OhRvRrcHkGB~h+RyG9aaWU*GKf}G8Wq+&atNNp4OS+Lx6Si>2mBoP*D6$F9A zp_G!l6Wz6KB@5RQ2kVv(3cMtG66$PRe&VITo;8c@MSuxXvWU9r2y`swaHon>2@VU) z)D)xXJWVChucx>!LpYUOY$H~3;lRpkpP4rWtGAe|W=(%W%b2l9Jy93$IjJvHMu3;* z0J(%t;~|nPia@gDEB`?A&63Cqk$>B4)U-p2%%7a-)1+*+7k+;*>jXpykwokMr)(S? zq3`pD_L=H<+PL^j72W}7bj45T@N!ap(Nk2Qakxb7(HTU;nM3=iUQZwf9*0u~Pz=wL zHxD-q6*#)xQ$OQ7@|FaJq6ZQT4#6QfSZ8cJsVmy~yh@9Bb2Ybbxm<0C1fIzY*hO3i z7zn`wyunDTrI=#)k+3G^^WTyN`*VZ0P^~#1$C^1@AH~l&Q6r+6$3xkRgB z^6kRe0}1_jLpR|~f0Cgo!A$vVVga?E%N;`IRQr2Mz(mW4OQ?#gS?_(D8WOGJa|+y=LFDo+ov-8=3PXCY8P5)QwM)&V|+#h*-xvIslEe+l>*6I10pZs#_!q`5?7sf0L z_!jD?D^#)G3RqODOj*??d=}G<*SYZSg3k4GF%q)tmp8fb=Ts1}!{FoE;hV(UM1TJp z^^mb<7+;72o058#<*+{DHgU~+-de=>{@Mfj;nekuuOPlVz3SxsMBh!bU)ETW!;+_^ zz=-LRxEEm&=6AL3G~!($U&-t#=8#*NUFaZI^+UQPiVKLcnt-Q>ESla13s9QWam5NO zAX*9}x%i}Egl~4fLE<#=S@d;4JYrtHXNItdw={Kyf-H)w@@Ldlw9Q}Ar}p(9mmHl- zFjPA{NvUQ{_m5;uW&*8%#%&D~y6*NATJU73Rpq0Npj03nwcWJ5L8@25eG@4?FR0W= zs`mLn_C@oIT*|{Zivy@q$B$iP@iHbO5v>RXx&4Q*39#oP>N3#LwFAA5+B%;!vWX$q zQ4H1!EGT^UZEH9ajU6usi}5U~WV$qbCrOl*R{b=OEG6h}utdh`8E|4$5K(DDpdKiW zr3+wqCh)bl23-Xt7D^Z8;?_%XhIZ=`;H^wmZPP!WC;E3dr=W2N3WKvkh3NRUmu9O? zX|4v#SjtyD9t*6L7Zu$hR+k?VBKdRSnY9idQU}|KH(8@L`bX#_EkL81162mR2VcL# z^TP>=82Nc9-K3?852}9)JKZmn9d|BXG#hV_Yy($XCGoXKE?!|BNz4z+nU(;*&3J+d zZ?}UygCY;6)`w*8M+Um>0kyj7jBzejWAk1DnU1()&{kP{r9^RkU5sP^g_qN^)~3Ym zWj~RZEI?~$o(qRAB4)NQVZ&9a29Ktvs}*ULnV zHpLcEtG0?TT<~JQ+xT?LPeZ-h=mAq^)RPg@M^A1>YZ__v>D0hXri!njhuD>%@lcw$ z#pPg<4i-9Fb_|;0z-@+v4O}#JhJ_9rp6+KP6<=B%~B+d3|m zI+wf(d2OvmI6ySUiP)Xt7BYlGdPLyT$8#UCW*#_s{cSIsqb49C7xGef=CtH#(3^1C zE@*7?Fd^2sqI!B@0ZTc@clH%?6DzA~cM{Zyz$>EmnjVyNPciLai^|b~e3`oGLotxi#)zy#&tvo(Y3`Ilkrm1o^=%THzJvkeYU0WPv`(Kh%Rkzv zcQv~DP(F-6IfWBt`)Q~Yf58SuO-e-lWC@B)=PBO{jiedF9+$o9FYldV9j|uPX?*=LGK~pTaJb(DKt#_>}+8& zR{pk|I#)~lBSmG1&hlN*1K)B_Wj)0+_0sRbLMg;o#%3bxMh%qOdHCE1GJIu4`&WIl z5Er7?-ME$N+njsHLaD0E4RNDY(EIaNE#l-)g|QV;1E;Le`-v6$UJX1YQ#Es+>rV%v z%zXl@S6Jtd78%z?tb%8)_3ny>^&ZCNxUHZHgAekqK4oUMPgK`@r`@$UzhZSuPdH~d=#>8k@hI>nOZ%o{tk#P8 zlbUN0Tb|Dk)iv>5vn`0WO$IjuzuiXvlg$>!`u-t}XNZe5Ij;W34uKW940=wniHEnJ zrS0Shbr!Kh#tlno5r=*1sCy6*+pBe7EwX8_K>AFT7+SL|aI5Sm;ltXJ$DQ-wDfht;{j_2VUjaG0tZQC+;Wtc#%r& z{;iWaIN9shsSb8e|3#YIW%UT9=ckB4&vuZx-GyKm^Zn1uZILdcoOTyrc)hJW(mw%X z2n#be@V~A}B=7OE#sKM?C&E8nlZgJ`V&#A9{3KQc%oW-EYhbxt>5ocyvQ_J8&6Rxh zU~+bD1L$|O92S?3{Cc{<>=SGmX#3b+#k?mT(VRn}#2&4=Cm0jn3 zDULAxxk&05c-?bORp?|s^MzMnl(d}QINuIM>?Q;11b|KlTq;exc~0S(W<%S zhdF)1hSQ#(YqeQw!x0@L`H@s4fr7oW5Vkxlj6Y{w(+~m`U^BJjtybw)YvB*gVncJt z;U5J=VQSbVAdODNNWCN&GlWDP7cpeyy~8mYjI- zm^J9ZRZEM=(j9Wmgi5hHO28%Q=a}m{46RbCgH*1$I}BGa*XZZu>Z{jKs@hKn?bB$c zK{L+j`eO+@-=0Pa9BLB!^-@|{?^kFGY`&PQ{`4yp-p*IG)NJyF*!u3;S9Nh7X=XC6 zLAPgii{cKPD@kOp_p!#@bSFnzjEkP~KAw>XWx>w>_z40BA?aIrrS7d^hkb-E5ez6k zDrBea2a(*57_gnL)E|(K*#soO1x0wKyQ<`)o$1YI4RE9|L{na*ygY1^+gWPx&p8Th z=|YADefndBvzWzD&7F;3FzzRy4HCXqiNSlK&M3fzx_=GUdxVao9Z|%Qn%^K_nsJwB z)Ku-4xiGz(DX{*@76?+lq_s#SiTGHWWVnR9+wQOZrD!sq>W2xj*s_~GzVLKUP_pX} z=BwWq_L9sF-+ciLG4&rA;{PM+RgKI{O#h|)06@Ls3}Ey#nORzsaF%i-yI6SnYl5u2 z24?nGXYva8Xb2%}YEU&b4eC zKAybb^pV1#Rxl%bVR?AieK$m+Y*u;t%hlX;cD30DRIAJ3<+EL3AH;PSuh3iuEfTr7 z+e)$eyhMG2b9TPsU12n%8CV$Ck8UoxzPZN{q`uj_vHMFIDqcHrF^%A3dWgbM_f57p z)YoE;(-yhRGs2WsYQ&8vlPAE;*rHJ=5~mgD$0hQtfpdHaiV4$f8rzg+)^aC28rf!w zGD_)lr9>Tj8fw-IgsFrN``|^1^3f9rrsSfFO2tK~PSEI33ahYPndZRhgk&PwQ6jMd z#g$@&Mo`y<=>z0_pdYx{1s9^=W1fL;=?Umop{|fKl=>+E ztfvvFZ#UrBB;DL^p&@regRV97%;Xl(OrjLX!x>U4mu6RDZO_2Jlb8w&=AfBG<2FF546#d6br z`K*u$9}0w_6vQA9!~_W#J|gZAkNS1RR51$f(H-I)Y0%<5P$mdNrxaJ^vCI&E;x z5MNA!ANdcZahPm0->=qAaNMu*y?I|kb+SA2n9AGUSD7DylgYpKPE!@im#0kSs?1Z8 z{7{=SZ=Fhk)d%XWuaPe^Lo=ZrM0#8z@w%2%6vnj|k9SwynW46`WOajwENa58UCX16C zS?V^`a}xJG&aNI}x|k0Lu;`NFO^u{Oueq*PA~Y2xS_~1X;`r3XCPb7Hn}E_}5)r01 zMrjHg=m4d4d0cTOO7*1V8G?)VsHHpw);Rg3>}q*RgsP(n4Y0QIO?yB&@o1+fS7*e$ zucjiKN}0xNFGGb1#2HL`zFm(pMf~+%NQUZgai+Xb9&{s!R(CSA??zZ^*U7+UBMpuW z6Q8fgUa=1xgJ46>mFsALyq^a{k={p-PIg@sZ>eLpgNU4C+<_%w1S%n189 zG(OIoc;4d@k}09$E`6Zj)w?xK^rb1Xm2d>c)P;ObEwkEO#K?v-<9bJN^;-8%-+LuT zo&h}TQ>6;!Q6VO_YL#nF#vJfC5^JVLR7W6TcC$_X5pqjUI^bg5bou*gA1E-sG3N9pvx+kfkM!@o^FM^GjlK&9#fMet)UvyO8$I`JQayI!h*f6@30jS z5LA}+LlVN3eIsdRP~K;NA|;Xk$9};&OH`U%f-qy+<(vc^(Wm^MzIe&(nu!Ldy*Sbj zjCLl--oZ_!kR6gQ>&>@o2lE{pZS6C3am2L9QPpPGYm!QvY=QRpSJY+xe1a3;0(*i|IJ&31y7E8JcP(a1GmFNPN?G zJv0##ZAWJ#JR53`*{Hm1?jjpDVZ0&&IudP?af@X9%<*|innP^q4cgkqNt$XR=^ zS7Qb2Y(2lGhk}V&5s~y4yqHU{RHGx!DAU@|G55@0pOzjGQ!1%~v3~!CnCK3f%BBo# z+=&NyYIV1;x$=!I_YA(iS5>;#(%2$3GP;FjqNXblb-#uMeA!KJSYEP=Mcorj6}*{p z85Jo!|4-R@fGMuZa;}8Rk?+P{rCmMcp;U zv3JELF0%I$%fzU#U!k)K^&b*dBgSSTK$3mNFU#*!*PL(3mmc(GqNU}%gl0eZKw((I z4(JAvMiHJE)v!_x5xU&G(Ty8!;$a&w8UKa_sT+fy|I*UhN-SLzFBjH<(O5l*nr1s0XAsq>O+Eh z5aJ4Flg$}70i23{$Q<=b!(C<~y;V}A%}`j06ANT{8qJK3ftm!IqeiIrcdMY!Q|1`* z4|Y-hJFs9rjP*Dld)%V%1-d^SKo|(Ap|cYXr)`E%o=8Vwh+vE-jU`pzI(8V>mAaRU zA4MmY1B58&R|-?O!aqKTF6pUZ5UYJ>Jwje$_!*XGMVk6aZVe-+l*gAsI?gp=9;!$= zijoYl`FXt}ZD2IXst&%a&{`1$3m8&oHr=?qd}Y^3vhg+*ilEH7A%RjjXKRgq8s_NZ z1G}-EKXW01_AHErzu8W=2~kRq0LC@UBLR}9E`%@#TD4H4x5>^WwxAtGABrApm{A*E zKUB}yyKMjEN9&RkzWSbvos*`Sg&4yUVp_e#9l;!(nA!9%kbC^6X0*T2Ome z=90{Kn7uI?T&a^xW+xj{D;2GhmQE=^dCAJvw@>SZ-kXkr&_(OU-`@v6AzE%*V`%my z<_-t#;Ld-q-OnSQ@rrVZF--BS|JXF~7Ga?22L%)AZDHH$HGUcBNTp!nSzy-0)3N=a z;l7@$ljpwFLV+UoQna;(@JNO4J_gZQM72|5}?z0Vqi z{rGM&BcnnAn4dryi(iAPzqsp>x72Y*QGp+@i*#wG-Mp@Gjy=M_ z>fErj!+b6pg^&!HI<4Fyu(aZ`5 zFE47~(H1Daq(?qdlT z$_~fCOz}-YJv0)@E?vT8|4a=ggFgh&`uaUTNOf@D-G6o9 z{n2ozWN&6-Vr2hsUN`gi_CG+Atbv7oU4!|ndHHr%gWpF)x-dB*escFJ6mIJsq{d#5 zxblZQZgO(J-`hbw)0N=sb=ul8*VvfOVV^G_@8ERN=eQYRJQ{P5UOhxtsStY^Ve|)X z-LNGW%x?8j?NsZ5&VqHw;}?0=?zaJD4S+ZzC0MUg49V+^ z@W;U$c@UjkCuCV6w9j1Jh;O|fOpCEFnSM6DBc~yyWXUD>gk0bDH^rdIb8c{$=}DLu z#3_DPEq>+E69Pj{Sv|$sS!GtrVDz^o$|w4o9c1jQ2;K=#7$NrosGPIy0+QLJ%n$zQmM^+jFf<%b*bMfz?0^!w(5z5nRfHHyxvh|aarGBqaXR+K>K@9b zD+fuoKIIwc%SM~B6WQ8r8?XxqDr8&OJVv-JP=v2Km#qR?0tFjCs~s6~+r~A9srWWK zqy1pynGh!m4lan*78^=LSBEn%Z{grD*w2tiQT~|FN((`JKW{Xf*4`+XivJWdZ7aX| zlfMk3w*1I!rXu9d;Ip}_c(xTfY;b{uDo6`_{<}VW(sLwB5brl8qK;DuA z==78bwJ!9k!m>DW*PO0sXB0gQAX>=&K)x?33e8vHK>BKMxHZ-2MtLGpS`NFn!Ua@P zw(bq`MGyfA{F(@Bu(cBzaT-eHgkrKg%-2bZX|vroxPG!oNkz(yI7Dn*`lF?#@;w+^ zM#@wREfOp#W_4h5$`Y{L6mwOcBs0eHF&tXNd$4P0j6c$Cp*AM<{P~g6l!_ZIYn9^U z7kxrnO{h?S9r`FvDhj$MtR%>8aL{D%$-fCE#Wp5MJ!ZHS1DZ!eY_?%xE3dETcf~*1SI2FMA$xkz&Likf?H2$R_@)B#WZkrIR}+ z5GJaKZtyhcl%YhHJx~WA+`X2@?~vm+H88oR1{1>(d8lm!XU^4tmd%ee<<-54p61Y$ z#k@Z{-|GC#sBFqR2d5xClRo>2X0D=M%vyi7y9?#{_>C+^l(P}$Ff2A0&HK5yY)i4u z=j(XvxJifa!CF8oo4uJE{#LB^aE}=@ui71r9Y5TQBo!o`s11#1T|r_(a{OTEUIN{g z;t$dTm!uz(8I7A8_8!9>Q5Do~Jn1~Rw`I8|s0TB?PB)1Qx$DKUG=(!=PB$hy^6!*7 z5^Uu=j04M*U^DI}tT=8-=FUakvXeOBLOnc3a?~i$WqO04aDEmKZJ(ISw@_Io7i?z& zMfDJ2MbkHy9@2M5${#){Q#%m^5NkY!aro(A_i)5{WyQvH!?q3bcr}GHCq3x9MufX! z(QQG}`f_f`Hu-hfAMhO}`PiKbu0J4M0y+j5HTGVKR{Jp?;kLd#5ROk$4P3ZH>`2b; z5WhvxIqVXQpU3VEjyU*)SK99G9Ch@Ah<OYTeyQ z%<~k`vP<8WqBY<^kNKHk7--G*9bA;z(Hfym*ng6KELD#0Qw#HrnJ!N|496+R+|A%9 zU2rIb0~&sWd=wWd>AZ2u!_h{h(ObFDOE_dXrzWP_fF-N9C#r)PJkEhn()23D26A2B zi~JYaWvuIdZi|#67f-_DaPxCZ&!)XhTGWdLw+s66W*IK)Ny*BK6&i1>KF}IY0iA)R z4Lzz{Tl3f9}WAH#fJtr{Djh&#Rjk?{l4Vu5+DzT~o?y z&wt|W@H2b)h3OVGVrsJa<<-h}>R+nT-}`5W#>MwZ|1wx?L%@aCnF_-lC>`re4@OMT zW603R4mo5taL%r8-lDEQG_DR~lz3GYM~i*VN~CyFsAY=NSb-w?kx&u_c|#zcat`<{ zm&gleKJTx;+S*zFj$%M=jYf*piY=td7Q-1bEjM+8pwn_8i>1zgeuCcnUNRLhE*LFNqKRZ&eeS__4&Z?+DV$pR1PQ^M+ ze63&U+FHCSy}iG+vWM(_E|;D{YHRArzMoB*kF19uB`s`X4suRhN)p)Vl~S|_^vvx4&B!ngB3-A$tf+i_$bN|#%CdIY--qdk7Q zO=y;cPdH$gEGD6ZBp{IzgS3>~Sa$`tc)rp1rncosSEloWka z^~_ZP1Z(FImi59VI;*D2uTmeSpQCp2mST5G)4Av&85fP-=8tL6*u}i%d>&&Z{?V60 zyvh>i?DqL}EFbMRLh1N8{?-g_VqqfAmTu-3GDl?^@tB_1tf;Lrhv3E!CDph>?luQ|g~-JrTbWMeX5zl?2X$S>%4=&38oYp?@8W z+CvqteDYn;j$McfrQ*}M+IxXkM4sGAy&ozZxIAXg>b<*p2l?_dw?^z*H_T_Z*Q$e% zZ)2aP!4@vv=wb0oTE)L=uo^aj_R^Te&@hJNZ1KGr?47;SlO=KQZK1^#Ra105a1g7Y1h9Q0(_TEV|JxVJ{o(xyt05^&o(&zSIB&>=~U*+inxChBXT zpNKBaZX?DgF{Wl8o*)@Khe5x>l3YtV7hpc3ViNKoBodb-EzrDxF~VVydO|yNNASXr zd?Z;3Id-alt`B(vQaWaW*#V;PCIe}C${Op+Dek8D>)w%Y#&~KAu z-`?$x3nzZj9*QMAZP)P1bIUZJT0rN##&_v2^+7u-0|kNsozZhCtm%~IRKb=3{sH7c zL~lgpH}y9(DTvWS+ol@HR<;?*i8xA^S}`lm?|;sf!kfDE#e-p)&mZ$cYE(-^8iBmu zq<9lD)s5DhMjmTC^4)i5ht_^ETFtdXroSUe?##=(Yr`jK?5DrN@A?hAPx+!I-`%4KY?y9_wh zw%^??f88JKs;-efM8kh}{{5v4eeoP6ofIdHLE9WB-voOCrN;E$be3YJP{~f!GBzu} zhgAepT6AY5Bu#v)6G{aGmeh)7<->N*edz4|f%c8$)Mw(jC1bta46EU8SEXWZ1ulkm z)1Ff{y;b5Arc}iaDHq;l-)0zL@O)@Tu*?5i$AW(;>FFo-*_F^Amw&t-Ex%i0Oa549 z#D1SHN%~TXB9mM|&X}~=a#VrG^pemuLGRE&^ZV*8Vw_Rhluv_pHTm^-|7oH)dL?$` zpo`CfdmkJ2Qva`R{|Tz_}OT%FsvE!5Cbcf0v2kBOM{n7zJIkMX78* z@_ppB@sB^NKRziNc181gokXwf!NwMGhjnc}oW1K~Ve_1Oap0HET8?+EclXz3E_-9W zz*N9>Rf^Wb>bl{U+QEwv&3nsF#zcp>GWBlsN-LF|d!Xge!kf)E2_d(T`6nh`R(#uK zQkG;jjApGPYBAhZC$taWsOG|>2Yc=Z=wO^vz@M#See^Cc zr(OZupIlb#tvnL$#fO~gE+6_f?#1KskL?eCFxAjuSMWpn!Ez0Snp_z_x8wQxsER~q z8E>QL_E0m`Bg{Uueqnv)ktW+F1$`4w)2MXYiW<5z@>cnlj|0w+DC{5_E>jRSzTsGV zQOwgJo=;e0eA9G+Fi+c{1O1@^8Nqy7z&vK?8@iRtY}!+%XXkr)rxu(zE9adGe+DdZ zvaoGD>}80*pty(JAu!ay)uq{LT+FJ~KrDynmm5O6#>s$BYtvpnY|r;iT75He415(w8tZ)Pg#v0a?AL-bUUs;hN^BgY zcA1XaH+}P|;L0Lb-eu2i4$b)O{%1y^&)>%mk~)W7=@>F(!5(t?%+q5go5$uJoWhtL zYIJ*p9x`?$m~#(agIF}UO2q}&s;NSbi~KjUMtB`!)|#=(?~tofQlhA4t>TCZIv5!j z+`%8jTC2XF))b1LqZg5Q-@>T*dE|<8RAM=*to6+T4WAcTwxt6b*1qjuh zUrCS!^NlpW2xAWT;U$?kB%0uJcCIl0O2>V0E%JRk!BxNa3QNNHR-ySsS1h$28%2NT z%$3f3a1Sem-_)gD<3`2eJepbkHQrNxN`CbX{9J@=^6y)6&(h7R65ptzz&RI*F>lts zMf^g!Dv{;GfR+h|_%{8JIl-c_-ixr3pOXD$k4@7IY~!s|V>+@hhO%!3inL3pG`f@u zB#k|B$l0W=zP7nQVE*_^nM3woNBm2k*=MsvTLbHopZLWhD?jZja)+z%C#hc|Np&Yj ztCBBWj;z?0_=-SCmWr!-5#zm#QEV3DH{CBg%j6IZd}%?T3NdRra5a$UziJ>XyY^PO zPX%XRaQKNzFjGELd(nDHx=oU{s67t85$6Y!ev~t(ry2);_SBb`4cF7|Tpkl}8xDTx z)9m+9YyZ+ztsSk@gaLMMf*Z%n@E>a%3p@zAmBxm?h8vgEj2tF|@o9U+%q%AY(OA$) zetNJ6_1m>aGx4{X59grLu_GDW6O3&@~|XQufJ@J(0sx%6{tFku9o z-rfK9T(LCBCO(jMQ#g;9i7VC2Krr##N}vE`-VY2WXZ_*$R$qTQ@!b`z(>xB*hK#e4 z1vl7<&yS{_4LDWT@7mqKWo6drZD^*ywz|ZzSG38aDBgipWTa`Hk2N1p{f_iu;}}c7 zaO_X4C3(HEUaMlUkEomGDpFfdEUxuuUf*IKv`#ae=Xio&%rLxpn$WV?|8fj-c!q?q6?+u6T3M)%Z?`=)yMFoh;K7w7DjD52NHk(KxO&A3Q?Kk? z?2Ij3fG>-G93mVYtA$?El}8dK*pnKxPO2#L$nr_2W8S=ug8P+*mRKx&fqQO_|2%)9 za6Sc^``qcx%nXiv$$0F#w9#=$+#_=*M!s(7AtxNS$d>BnkImnv|J3p+JpT8&HCT$nMxh?*XA;xP{? zZ!)EtZr_*1rx9W)Yy|RNy}_^B6;Y>}YCb!nlvq&(pokZ%+qH-kDoWt=Uoxh;&njL@ zNAr^GtL|L~>k2(Dly@bg*@8Gf1+huQWN z``t6)yMh<(CPCF}GU>!{q$T{Um*@@M^0@4qiPL^D4=I&g{cqlG?yfbNIcGNGAeYWB z`SU|uQRLeQoFV!odL2Zx3l#E^I|>081`x@=tanOR8+xyza(}jETIVOqtEKp{sV1;^ zI{2RGEva}SlcA<>c#iJZ^lmbat?AVKvl%IOR|?Mw)Mp9YRSu5-TA$FflB3&@qsO-) zYkO*^LwamHTWgz>cQ(hPI;U-bhxl}7E8MHd7}S0unnpSq_mqroR@Zx}YFas=T}3`m z?Z>NKRz|}i{i&RZ>lsQm@Cttk*DwM&wAO_NnXJS z3~%7>)Bx2;Go7Bqr^wWN9HE4m*M|ll`5@L1`&E4XXCSxx;5~V->d?jbL#sZ&^jqmb z&;NHt$XQ+M+@9U6qd6T94iYj-)+sbzHxUYvV%d-g1lp)98C42deIAZD69aa9bGw_l zx#cfn#dOKb1@3ykc%fNnK*@k&jPas>IIn!K^rhanaQPeGylzb1?yB36iKoGj6P``> z=n~q#YVPHcR`;&lnl$H}UG*_oeoagJTgRc{Hkx1}Rnvq;%;_R!R=|Xx5 z#OTrPe*MiD~e|pchbqwZnwHbpAWVrQ0IE*zSHssOb!SAGYy~L z^r2R%PV?Yu5evY^V(M1$c4H)D)J}QD=6R_JiG_e^Aie3;6jxxT)Pjh91+M*I4Yh#R zwOb+5W6xS&8QCcFza4Y%)$P3Joa*wF4BZwRHS_^)_*atb^5>FE!y>onR&=!b(UI$H zCsK3mu$rrWq+W=bcjDC%jMOMlXnCjL;F}X}r5%dLu5^o_0HcjHH)PJFf-Qp{uY91{ zno{-DSmG^+f2r!e@2h2?0MFS)7qlSR5UPR*}O^_tFI(x*3$GmlPJPaHN@<%sHDI?{v@YnK;vx(v|fTS*j%lA)cbW!DqsL zP8{7X$u;HvS3?}?rqj}HjU4YBwYChYEe5#JDyFAg?<&3e>=-irC4o4!PR}|bs-HtW zV0za`J-}r2t5i?R=P$3&W9Zh{s7OnI&jEkPG!j;fb87kv6`l5MQB zh;LT*9R0bNnJnY0<0z>(Sa+gUl9;e6xrR2bg*~(Wj#~eQ-ZwQs{znFTD_+z$`I|=C zoX#Sz_0)e@;5O@g8JJzflpj(^HdTJlSpT-}R$r;x)!-HMvHF~GW4@TQ>m;q`9d5qb zT0_41$?jpfmWhSva7(hhb|SaEJ`;fu!6V1odv^2A7o$a{`iQ>FihS8$r_*@YPxYyG zBMM<4Un{1J+xzyY$8FNxs&k_k4&c z#iUq;dhCO$^sT-#8ci-}oV~WN5D=hdbi*g|VY-3a$XxJQ(q19PPu;85Yq`$43j_oo z(Ldaj=N{rz#^Z|2^14S6?fK&;r?IVBvKLCc>0Hw0?h7+(!SBe3HU>X4nYkO>t1dIi z1(_*7Bf73FX?$^~YH0T1KIRVjBYM5d9`)CUSkjaC#X!u?T+yP_=p8NJ&r4rxB__NP zu%FSV-Q-H9gbYG%;9cS_|~iAHY<1!*Al zP*QrTmL=>GqE!rCw|e#P8P~{zIPUV;c(he{QHJ)#Odh4-41p@in=ORpiwoJKMky$I z;q3+9=SvZ}i|vyMi{+5)GEDJQ_(0_M6=WnkH)JpR$pMZ#X`}QPlDftP*Cs~F5O~7R z+3^Ne@Qw&w$qdHmu(Sumx z?S+c&{6dA|?YS*i8{>$w^~ZOxvBp`kjN(_C0-vrCRIf6bvlM%wZB3#szgii3>9@T` zB;f5;yiZj9gh=!HPIm1oVpFr~1Fv(^IFG}B@-FzUQ)(nrkq;GFW?HW^pzEyh1?_1W zyiiw2_SrD1dTr)eC8<&Ve1xiOm@BL?tn}QyoKIW<6Qs8#r9mTTRU%GqVXq3g}IZM8-`(V6u+tsl#Vx}(r%Ofqf^P3CtB(fe3$9;-0x#+Dox)N+v8duj7(EvV9&KTtF1c(aR+lk)C``ZIPWnQ-g-XG~rTBk(8p z!zn}~og{cVNLT6GN?@5YSe+6zJ|*jWk-JeTY1}b+?h^i5nOMlK($$!j)jOfVG#>PM zf?-w~5sP2*HMo|IZkH^e*Goldyngmmko%2hXFuz3LtHL?E5*&MQ#82``j}|Wb;ydL zg+9x0EMKg6KjbRVKIe`i$a@8COfl1KnV_+b!MEnYdOS^~|1~SzTI5erDE85Pf{MN$ zXM-wfZZAZoKZg%qx9wB*9_+)ER z$I()0gq7cy=8)jzv`tvfR;iV36ijEO4y;NrC|y@ewxOptr=d?;4VgA6G?~aYc5=#8DmDW=qlgzT}g9Ne|=_l-xWeUsOf3H{0>K31#9`srt{k z?OY08$54w+dzZHpt*#+p^(-I1-8A$2)49<>fs0{H=EGO@{67w-3<_l4v25QAa3wn3 z)%0U2lUP13%rvStxE3eQ;s^1w?v9;I;TDA2D95nsKE9%CvB!RAGCIF^-0^9VUF7<^&ElEIZRYlZp?uhyFdFfb_usDKI@fvafrXa z=V=w{8Mm8e#xQK(rBY^(xWlo%1-^Ot#FWsW?rl{~!4CUP5Tj5lYUdv6qpSWik5-s` zzJhDI{^ea*V$$zdastMMIrLU!s`f5c&4=%wg3O-P*&UKf&=3&BiQtU_5Bd5!c@%hT z$1gPMlO3KYLCZ^@Q|MQ`f;0;Tgqfe5>a*iqYqH>cWFaQjm?hIQ#)%QKq%y>{Xw!Q+ z?e*z7e>!fuf83a?buOYlRsV=#*7ajH`O^=lM`SJXF~|%)#h&PfTwPZ7_?gkOufd?D~>sWy!462RmS zb}s5k$Dr0PJ#S}-)*aczaq+1SZjk+y5^qa}Zr$rV{cF4l4O7<(EYe8`?u!J} za2maEo7m8Qi~Y{_W{cd=j@(s5cK6NJA^PT!=-g7AlnjBy3==WAYlEz`MO~Aap&VVU zf?y5v%kd{Z=xK9)*ptK>1uREgrl(&Wfbm$;pT=_Z$pn{O-s`05w_RbN>a7ry`~YD_f|-X zfuz=RY{+Kl8=I$3b$^To51i1cLkq$xEi zJXD>%q%`;WmKcLYUxu?i6OCGr^SehrTaUUML+;kny`NmUHnCXd{yC#32$dAmp!10_ zwGJ08R?jDz?kgE%)u?_%UmpaJzBUnEV!$2gqoDQ8ykgj(JRUpRLSAVcH1MW7w1h&& z5HI-aBu}C@*?Y|I1JuhygOz>v`?C7(J-tIvk0q!0gWvaD$@4Y7kW5*uW)=|z=&DVf_s+S+W8A1V0XEihq=l42Ln1dR-bqT>@m1S480IyN%J^PJ)W-@DBUf+!L@ z)DJ?*BPpyIW&BV+q>B!y<6v;Oo@q-*aZ~V}*1!owaTD{K)`+0)yb$P}Mbq{u?Ze(b zjw@w|iQ>k9Nx=ghnu@8I9Y9eKCAGN$+UGKOFG3Lv!FLA%C4RX_mHg#g<)HZ;76^i3(A(SV z0m90FBTkf1C^YcX1JsdrtZEAJI}aO|O`+BJ1Yq8R_Z$?C5#04X!2Lm@o7oG(AHgrn zfIWQZ%;5nUk04Z>>|HHQensOxnz`BqY&j2bZp)1V_=?_vKn(TrJ_1}IS_ zkOk&1O!4TCW6dyCTzJ*Q?ph_gTHM6FC-xD z@8_KIaR&5S@X@xgTryEY3N$YZXg+j_Z~l*^?BZ+=GzM;4cz`#a&IEL(59E#dw?N>N zrq(Z+VE9fy*<@%C(qtBZf^PzC9lSRLu76WMfiO#K# z7+4iUJ5w9ji7l+l+USG4q=39YrbE9UR@48On6!rM$?Yk3qs<6n=^)k`vZ?g@Suy_` zK5Xf^`%`xK0R0w_9-98%>M!W*u<0V1QR)tQgM&tVVk3a)CD%#PKU0YN(E<2V$E2sY`!{^p(&v9C8G_Vo<}vAIz5asE zeUkJax0H#B0AKHz^lZL=!-p+>&8^EGtDyI)1V#wDW(EEKg3be*&hzOM4<{g-gT4d0 zRRstB1)cY#vJt4E34-|CWCMI?>B)oth7Vi%*N$uUTA*x%Knl=wld!*_^TDRu>wnLg z0y+Z%Tq9ihZ7RVhl8FCKhs}QHUQX5wq>cmpt59t1NB@=WWawaFX>4foPls|+1vpt7 zIr{*ETm$+q$R*g{kAK4dDIwVTk=i*e@&@RU1@Ns3hIoe_+tmM<%&!5?L3SVmZ5X{I zWToN*ucZz;NGl%b6z`#w5D+pl{x4}A&k-aQ1~18m`=H>oj};tVHk?$BboK|csS~<< zNHS$@_qNzUW@dr$5QNIiZXTRuP8fros0xszG*ztv*g!IoSVwg(5iALvXvN_r1-s~E zLgv0m1LYP0#YYd7Cr)rU87d(cXE4yd#d5H?cI%{Z9z^=K@Hkl{P*75!#n3`QyDR<( zg)OI|Vo;?Qkdpu)`Js@sHPFakM^leo^??!`RvUzfPM7(SeFLPk3(|pBSj_tWOFFP~ zlUDuN2@-Bv7No)rl^fH>zfT2r8W#Ll>REsaNduDz399t_NpFUohJ>ZLrL&>UK{>%` z2RuV>=&OPB^+0DBeq+HWhK?g-ds|z3I~FxdTL&9c$Q<-w771J6*tjCbAb<@3STL16 z^ze5I|3x}=P5>i3 z1`GUoGVG)}=v{aXkqqw`?9A@TuoJ34=yA%^aZqS-pbDU~>A!z6?1UPKc`q9~0TWh= zhzK=CIBeifr~pj)o_yG_apaR>Fs4M1Hq~(U!UxzeEYy=>ys%Xxfk!P1c9{vBIT;3H zLIRQOMpLM{HK<7kFvwL1MF>pg&tAnQ2Ylh zY+1X0R5QH>KrzsZK@VnpsG*_1c0QpNCE*NajCxUN#sJwL%pIUBD*e(4%F=mCxADJf@ zPgNa})h)n`KE~V=`y=xN8@la4VY34EH5@^wLjzUwvXXyd!mc3_(r$x2Af*n_Cum}j z>Mx?HE3lW)+YpDY!XDm#f#^|nv+6Dw^CP$dDzt$bR)<6UwdMg^OlDL|3{_B&{lMN+ zLS-C56B;UR?__!~#eyT_E(Y&j8o+=d`jK2e);S3WUqIA7fiypm<8+{z=b;3Qx(-d0 zFmyJABN`LQD+#dfh0qLM=&i7uddETVg$kKomg@vUS%H$HfD%ds?5ZDhK?jxlzpZLG zlAV*NmM;JlFkCt^)w!;J0u8=+y$vI?sGz(c#{-~8QCbGjz+W9B9O**G9c$A8YXH1d z;QjsN8Nr6Z7p`7dN&%w6kaYxTHBK~!=0T>M|4fkW>_7xgQxiBss^FVCf;l|GJphL8 z4NXnqL*WbiWtU>E5OBA^d--?H!KVjcyZ3NKA6vqL58lt>+y?`91e;?5hnfEZ|B7gQ zY`xFX#q`z*v2p*GdMF0!ud__Y7FQ2$HbMnkJDSqr$g9x%R{?jAr*t^v6ztH! zNBM_?FhUzdHLv6R6Qa2ug&qz>2VFe5pf~-eIu8{Oq(c8|G{>VU9S+t7y+ZjT;N+Bk zbv$rO{%~v)=yMmsLH|P^I>>$E&M@q;&*2~v(!ccwe6o)GEBp}y4HYisXmK5OzYm?L zVa)$mqKBhZ98L7FcWe=;oF>Qp|0D{#To1d;h2AA_O8%?V;B@$hz0X4LIlfE(t2E$u z(}x|QLT}$pKZcdeuT7j^_U6F69KVZyw1N)%h=bPjhD>VTG z@CW&UUuK70C_$SZ*Mh%F?2ogJ!>)*+vsDe^zW;0F4%vrawR5c04pM@jt;23-Al{9B zKO-gZ68r6H=IH(Tqe^ht2MKh$xl#7tQuwo?9riK-xs&kwDSZJi4LH6{j%MSq!vUV( zeDI00>OUs&=X@N#1rL2JBcujaBL7=n`@IMT$GRN8Qx1KiP_OPk(%~!9;p@w9niY7*#4jS@XO`!$#>``u-ow;k~q>4|0!vR From abda742229190195c4883f68051b8db48a9d11f9 Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Tue, 16 Jul 2024 18:17:56 -0400 Subject: [PATCH 51/60] adding repo for the new dep --- build.gradle | 3 +++ 1 file changed, 3 insertions(+) diff --git a/build.gradle b/build.gradle index 1f7d74e7..0677fc00 100644 --- a/build.gradle +++ b/build.gradle @@ -43,6 +43,9 @@ jar.archiveName = "nrsdk-"+props."app.version"+"-jar-with-dependencies.jar" repositories { mavenCentral() + maven { + url "https://repository.ow2.org/nexus/content/repositories/public/" + } } dependencies { From 86182bbcb4e07f1005f2d03e0278c249625692b9 Mon Sep 17 00:00:00 2001 From: Kevin Harrington Date: Tue, 16 Jul 2024 18:23:36 -0400 Subject: [PATCH 52/60] remove unused dep --- build.gradle | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/build.gradle b/build.gradle index 0677fc00..a49e271e 100644 --- a/build.gradle +++ b/build.gradle @@ -43,9 +43,9 @@ jar.archiveName = "nrsdk-"+props."app.version"+"-jar-with-dependencies.jar" repositories { mavenCentral() - maven { - url "https://repository.ow2.org/nexus/content/repositories/public/" - } +// maven { +// url "https://repository.ow2.org/nexus/content/repositories/public/" +// } } dependencies { @@ -71,7 +71,7 @@ dependencies { api group: 'net.sf.bluecove', name: 'bluecove-gpl', version: '2.1.0' api group: 'io.ultreia', name: 'bluecove', version: '2.1.1' // https://mvnrepository.com/artifact/motej/motej - api group: 'motej', name: 'motej', version: '0.9-2008.02.05-patched', ext: 'pom' + //api group: 'motej', name: 'motej', version: '0.9-2008.02.05-patched', ext: 'pom' } From f0c79d2083d993f5721d608b295e813ab5098c3f Mon Sep 17 00:00:00 2001 From: Kevin harrington Date: Fri, 19 Jul 2024 13:48:05 -0400 Subject: [PATCH 53/60] Adding the Depricated API back in to maintain compatibility with scripts. --- .../sdk/addons/kinematics/VitaminLocation.java | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java index e4475982..7168c57f 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java @@ -28,6 +28,16 @@ public class VitaminLocation implements ITransformNRChangeListener { // this.setSize("NO SIZE"); // this.setLocation(new TransformNR()); // } + @Deprecated + public VitaminLocation(String name, String type, String size, TransformNR location) { + this(false,name,type,size,location); + new RuntimeException("@Deprecated, please specifiy if this is a script, assuming it is not for now").printStackTrace(); + } + @Deprecated + public VitaminLocation(String name, String type, String size, TransformNR location,IVitaminHolder h) { + this(false,name,type,size,location,h); + new RuntimeException("@Deprecated, please specifiy if this is a script, assuming it is not for now").printStackTrace(); + } public VitaminLocation(boolean isScript,String name, String type, String size, TransformNR location) { this.setName(name); this.setType(type); From b30018f94c91ac52da0927910917e46b7a47a596 Mon Sep 17 00:00:00 2001 From: Kevin harrington Date: Thu, 25 Jul 2024 01:01:44 -0400 Subject: [PATCH 54/60] changing the storage type to be more compatible with json encoding --- .../addons/kinematics/math/RotationNR.java | 29 ++++++++++++++----- .../addons/kinematics/math/TransformNR.java | 7 +++++ 2 files changed, 28 insertions(+), 8 deletions(-) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/RotationNR.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/RotationNR.java index 8b698fc1..85f34bd8 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/RotationNR.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/RotationNR.java @@ -7,6 +7,7 @@ import org.apache.commons.math3.geometry.euclidean.threed.RotationConvention; import org.apache.commons.math3.geometry.euclidean.threed.RotationOrder; +import com.google.gson.annotations.Expose; import com.neuronrobotics.sdk.common.Log; // TODO: Auto-generated Javadoc @@ -22,7 +23,16 @@ public class RotationNR { /** The rotation matrix. */ // double[][] rotationMatrix = ; - private Rotation storage = new Rotation(1, 0, 0, 0, false); + +@Expose (serialize = true, deserialize = true) + double w=1; +@Expose (serialize = true, deserialize = true) + double x=0; +@Expose (serialize = true, deserialize = true) + double y=0; +@Expose (serialize = true, deserialize = true) + double z=0; + //private Rotation storage = new Rotation(1, 0, 0, 0, false); private static RotationOrder order = RotationOrder.ZYX; private static RotationConvention convention = RotationConvention.VECTOR_OPERATOR; @@ -42,7 +52,7 @@ public RotationNR() { * instance */ public RotationNR(Rotation store) { - storage = store; + setStorage(store); } /** @@ -387,7 +397,7 @@ private double getAngle(int index){ * @return the rotation matrix2 quaturnion w */ public double getRotationMatrix2QuaturnionW() { - return getStorage().getQ0(); + return w; } /** @@ -396,7 +406,7 @@ public double getRotationMatrix2QuaturnionW() { * @return the rotation matrix2 quaturnion x */ public double getRotationMatrix2QuaturnionX() { - return -getStorage().getQ1(); + return -x; } /** @@ -405,7 +415,7 @@ public double getRotationMatrix2QuaturnionX() { * @return the rotation matrix2 quaturnion y */ public double getRotationMatrix2QuaturnionY() { - return -getStorage().getQ2(); + return -y; } /** @@ -414,7 +424,7 @@ public double getRotationMatrix2QuaturnionY() { * @return the rotation matrix2 quaturnion z */ public double getRotationMatrix2QuaturnionZ() { - return -getStorage().getQ3(); + return -z; } public static RotationOrder getOrder() { @@ -434,11 +444,14 @@ public static void setConvention(RotationConvention convention) { } public Rotation getStorage() { - return storage; + return new Rotation(w,x,y,z,false); } public void setStorage(Rotation storage) { - this.storage = storage; + w=storage.getQ0(); + x=storage.getQ1(); + y=storage.getQ2(); + z=storage.getQ3(); } public void set(double[][] poseRot) { diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/TransformNR.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/TransformNR.java index ae45efc1..e1d38bc3 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/TransformNR.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/TransformNR.java @@ -3,6 +3,8 @@ import java.math.BigDecimal; import java.text.DecimalFormat; import java.util.ArrayList; + +import com.google.gson.annotations.Expose; import com.neuronrobotics.sdk.common.Log; import Jama.Matrix; @@ -13,15 +15,20 @@ public class TransformNR { private ArrayList listeners=null; /** The x. */ +@Expose (serialize = true, deserialize = true) private double x; /** The y. */ +@Expose (serialize = true, deserialize = true) private double y; /** The z. */ +@Expose (serialize = true, deserialize = true) private double z; /** The rotation. */ + +@Expose (serialize = true, deserialize = true) private RotationNR rotation; From a7ddf0e9aa8ee33e6ca644284c49a83d51f9741e Mon Sep 17 00:00:00 2001 From: Kevin harrington Date: Thu, 25 Jul 2024 11:11:09 -0400 Subject: [PATCH 55/60] Adding helper methods for the transforms to allow pure rotation transform construction and more accurate API for getting rotations --- .../addons/kinematics/math/RotationNR.java | 81 ++++++++++++++++--- .../addons/kinematics/math/TransformNR.java | 12 +++ 2 files changed, 84 insertions(+), 9 deletions(-) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/RotationNR.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/RotationNR.java index 85f34bd8..f5ad9e74 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/RotationNR.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/RotationNR.java @@ -33,7 +33,9 @@ public class RotationNR { @Expose (serialize = true, deserialize = true) double z=0; //private Rotation storage = new Rotation(1, 0, 0, 0, false); +@Expose (serialize = false, deserialize = false) private static RotationOrder order = RotationOrder.ZYX; +@Expose (serialize = false, deserialize = false) private static RotationConvention convention = RotationConvention.VECTOR_OPERATOR; @@ -307,7 +309,10 @@ protected void quaternion2RotationMatrix(double w, double x, double y, double z) throw new RuntimeException("Value can not be NaN"); if (Double.isNaN(z)) throw new RuntimeException("Value can not be NaN"); - setStorage(new Rotation(w,- x, -y, -z, true)); + this.w=w; + this.x= -x; + this.y= -y; + this.z= -z; } /** @@ -329,33 +334,91 @@ private void loadFromAngles(double tilt, double azumeth, double elevation) { setStorage(new Rotation(getOrder(), getConvention(), Math.toRadians(azumeth), Math.toRadians(elevation), Math.toRadians(tilt))); } + /** + * Gets the rotation tilt. + * + * @return the rotation tilt in radians + */ + public double getRotationTiltRadians() { + return getAngle(2); + } + + /** + * Gets the rotation elevation. + * + * @return the rotation elevation in radians + */ + public double getRotationElevationRadians() { + return getAngle(1); + + } + /** + * Gets the rotation azimuth. + * + * @return the rotation azimuth in radians + */ + + public double getRotationAzimuthRadians() { + return getAngle(0); + } /** * Gets the rotation tilt. * - * @return the rotation tilt + * @return the rotation tilt in degrees */ + public double getRotationTiltDegrees() { + return Math.toDegrees(getRotationTiltRadians()); + } + + /** + * Gets the rotation elevation. + * + * @return the rotation elevation in degrees + */ + public double getRotationElevationDegrees() { + return Math.toDegrees(getRotationElevationRadians()); + + } + + /** + * Gets the rotation azimuth. + * + * @return the rotation azimuth in degrees + */ + + public double getRotationAzimuthDegrees() { + return Math.toDegrees( getRotationAzimuthRadians()); + } + /** + * Gets the rotation tilt. + * + * @return the rotation tilt in radians + */ + @Deprecated public double getRotationTilt() { - return getAngle(2); + return getRotationTiltRadians(); } /** * Gets the rotation elevation. * - * @return the rotation elevation + * @return the rotation elevation in radians */ + @Deprecated public double getRotationElevation() { - return getAngle(1); + return getRotationElevationRadians(); } /** * Gets the rotation azimuth. * - * @return the rotation azimuth + * @return the rotation azimuth in radians */ + @Deprecated public double getRotationAzimuth() { - return getAngle(0); + return getRotationAzimuthRadians(); } private void simpilfyAngles(double [] angles){ double epsilon=1.0E-7; @@ -443,11 +506,11 @@ public static void setConvention(RotationConvention convention) { RotationNR.convention = convention; } - public Rotation getStorage() { + private Rotation getStorage() { return new Rotation(w,x,y,z,false); } - public void setStorage(Rotation storage) { + private void setStorage(Rotation storage) { w=storage.getQ0(); x=storage.getQ1(); y=storage.getQ2(); diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/TransformNR.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/TransformNR.java index e1d38bc3..de2b38ad 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/TransformNR.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/TransformNR.java @@ -13,6 +13,7 @@ * The Class TransformNR. */ public class TransformNR { +@Expose (serialize = false, deserialize = false) private ArrayList listeners=null; /** The x. */ @Expose (serialize = true, deserialize = true) @@ -118,6 +119,17 @@ public TransformNR(double x, double y, double z) { this.setZ(z); this.setRotation(new RotationNR()); } + /** + * Instantiates a new transform nr. + * + * @param rot A pure rotation + */ + public TransformNR(RotationNR rot) { + this.setX(0); + this.setY(0); + this.setZ(0); + this.setRotation(rot); + } /** * Instantiates a new transform nr. * From da4cf322bd1e1953c408a2cf5924d9796aeecb21 Mon Sep 17 00:00:00 2001 From: Kevin harrington Date: Thu, 25 Jul 2024 11:12:40 -0400 Subject: [PATCH 56/60] rename variable to correct spelling --- .../sdk/addons/kinematics/math/RotationNR.java | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/RotationNR.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/RotationNR.java index f5ad9e74..fcf75581 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/RotationNR.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/RotationNR.java @@ -62,27 +62,27 @@ public RotationNR(Rotation store) { * ** @param tilt * the tilt - * @param azumeth - * the azumeth + * @param azimuth + * the azimuth * @param elevation * the elevation */ // create a new object with the given simplified rotations - public RotationNR(double tilt, double azumeth, double elevation) { + public RotationNR(double tilt, double azimuth, double elevation) { if (Double.isNaN(tilt)) throw new RuntimeException("Value can not be NaN"); - if (Double.isNaN(azumeth)) + if (Double.isNaN(azimuth)) throw new RuntimeException("Value can not be NaN"); if (Double.isNaN(elevation)) throw new RuntimeException("Value can not be NaN"); if (elevation > 90 || elevation < -90) { throw new RuntimeException("Elevation can not be greater than 90 nor less than -90"); } - loadFromAngles(tilt, azumeth, elevation); + loadFromAngles(tilt, azimuth, elevation); if (Double.isNaN(getRotationMatrix2QuaturnionW()) || Double.isNaN(getRotationMatrix2QuaturnionX()) || Double.isNaN(getRotationMatrix2QuaturnionY()) || Double.isNaN(getRotationMatrix2QuaturnionZ())) { Log.error("Failing to set proper angle, jittering"); - loadFromAngles(tilt + Math.random() * .02 + .001, azumeth + Math.random() * .02 + .001, + loadFromAngles(tilt + Math.random() * .02 + .001, azimuth + Math.random() * .02 + .001, elevation + Math.random() * .02 + .001); } @@ -330,8 +330,8 @@ public static boolean bound(double low, double high, double n) { return n >= low && n <= high; } - private void loadFromAngles(double tilt, double azumeth, double elevation) { - setStorage(new Rotation(getOrder(), getConvention(), Math.toRadians(azumeth), Math.toRadians(elevation), + private void loadFromAngles(double tilt, double azimuth, double elevation) { + setStorage(new Rotation(getOrder(), getConvention(), Math.toRadians(azimuth), Math.toRadians(elevation), Math.toRadians(tilt))); } /** From 79b257a3d7ee6bc45a1e54162849d0307d482490 Mon Sep 17 00:00:00 2001 From: Kevin harrington Date: Thu, 25 Jul 2024 11:14:25 -0400 Subject: [PATCH 57/60] adding to the comment to make the dataatype more explicate --- .../sdk/addons/kinematics/math/RotationNR.java | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/RotationNR.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/RotationNR.java index fcf75581..ab7506d7 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/RotationNR.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/RotationNR.java @@ -61,11 +61,11 @@ public RotationNR(Rotation store) { * Instantiates a new rotation nr. * ** @param tilt - * the tilt + * the tilt in Degrees * @param azimuth - * the azimuth + * the azimuth in Degrees * @param elevation - * the elevation + * the elevation in Degrees */ // create a new object with the given simplified rotations public RotationNR(double tilt, double azimuth, double elevation) { From 188a01f344ecef4eb4c64664fc85c2440964a041 Mon Sep 17 00:00:00 2001 From: Kevin harrington Date: Thu, 15 Aug 2024 10:32:47 -0400 Subject: [PATCH 58/60] Allow construction using an axis and and angle --- .../sdk/addons/kinematics/math/EulerAxis.java | 7 +++++++ .../addons/kinematics/math/RotationNR.java | 15 ++++++++------ .../addons/kinematics/math/TransformNR.java | 20 +++++++++---------- 3 files changed, 26 insertions(+), 16 deletions(-) create mode 100644 src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/EulerAxis.java diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/EulerAxis.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/EulerAxis.java new file mode 100644 index 00000000..4bea9e3a --- /dev/null +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/EulerAxis.java @@ -0,0 +1,7 @@ +package com.neuronrobotics.sdk.addons.kinematics.math; + +public enum EulerAxis { + tilt, + azimuth, + elevation; +} diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/RotationNR.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/RotationNR.java index ab7506d7..ca56409b 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/RotationNR.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/RotationNR.java @@ -69,12 +69,12 @@ public RotationNR(Rotation store) { */ // create a new object with the given simplified rotations public RotationNR(double tilt, double azimuth, double elevation) { - if (Double.isNaN(tilt)) - throw new RuntimeException("Value can not be NaN"); - if (Double.isNaN(azimuth)) - throw new RuntimeException("Value can not be NaN"); - if (Double.isNaN(elevation)) - throw new RuntimeException("Value can not be NaN"); + if (!Double.isFinite(tilt)) + throw new RuntimeException("Value can not be "+tilt); + if (!Double.isFinite(azimuth)) + throw new RuntimeException("Value can not be "+azimuth); + if (!Double.isFinite(elevation)) + throw new RuntimeException("Value can not be "+elevation); if (elevation > 90 || elevation < -90) { throw new RuntimeException("Elevation can not be greater than 90 nor less than -90"); } @@ -87,6 +87,9 @@ public RotationNR(double tilt, double azimuth, double elevation) { } } + public RotationNR(EulerAxis axis, double rot) { + this(axis==EulerAxis.tilt?rot:0,axis==EulerAxis.azimuth?rot:0,axis==EulerAxis.elevation?rot:0); + } /** * Instantiates a new rotation nr. diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/TransformNR.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/TransformNR.java index de2b38ad..8505a040 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/TransformNR.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/TransformNR.java @@ -441,13 +441,13 @@ public TransformNR translateZ(double translation) { } public TransformNR set(double tx, double ty, double tz, double[][] poseRot) { - if (Double.isNaN(tx)) + if (!Double.isFinite(tx)) throw new RuntimeException("Value can not be NaN"); x = tx; - if (Double.isNaN(ty)) + if (!Double.isFinite(ty)) throw new RuntimeException("Value can not be NaN"); y = ty; - if (Double.isNaN(tz)) + if (!Double.isFinite(tz)) throw new RuntimeException("Value can not be NaN"); z = tz; getRotation().set(poseRot); @@ -461,7 +461,7 @@ public TransformNR set(double tx, double ty, double tz, double[][] poseRot) { * @param tx the new x */ public TransformNR setX(double tx) { - if (Double.isNaN(tx)) + if (!Double.isFinite(tx)) throw new RuntimeException("Value can not be NaN"); x = tx; fireChangeEvent(); @@ -474,7 +474,7 @@ public TransformNR setX(double tx) { * @param ty the new y */ public TransformNR setY(double ty) { - if (Double.isNaN(ty)) + if (!Double.isFinite(ty)) throw new RuntimeException("Value can not be NaN"); y = ty; fireChangeEvent(); @@ -487,7 +487,7 @@ public TransformNR setY(double ty) { * @param tz the new z */ public TransformNR setZ(double tz) { - if (Double.isNaN(tz)) + if (!Double.isFinite(tz)) throw new RuntimeException("Value can not be NaN"); z = tz; fireChangeEvent(); @@ -506,10 +506,10 @@ public TransformNR setZ(double tz) { public String getXml() { String xml = "\n\t" + getX() + "\n" + "\t" + getY() + "\n" + "\t" + getZ() + "\n"; - if (Double.isNaN(getRotation().getRotationMatrix2QuaturnionW()) - || Double.isNaN(getRotation().getRotationMatrix2QuaturnionX()) - || Double.isNaN(getRotation().getRotationMatrix2QuaturnionY()) - || Double.isNaN(getRotation().getRotationMatrix2QuaturnionZ())) { + if (!Double.isFinite(getRotation().getRotationMatrix2QuaturnionW()) + || !Double.isFinite(getRotation().getRotationMatrix2QuaturnionX()) + || !Double.isFinite(getRotation().getRotationMatrix2QuaturnionY()) + || !Double.isFinite(getRotation().getRotationMatrix2QuaturnionZ())) { xml += "\n\t\n"; setRotation(new RotationNR()); } From b61304b79dc69418852dfcc8cb5362be32202b67 Mon Sep 17 00:00:00 2001 From: Kevin harrington Date: Sat, 7 Sep 2024 11:40:38 -0400 Subject: [PATCH 59/60] construct from other transform --- .../sdk/addons/kinematics/math/TransformNR.java | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/TransformNR.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/TransformNR.java index 8505a040..bf85e606 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/TransformNR.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/TransformNR.java @@ -45,6 +45,14 @@ public TransformNR(Matrix m) { this.setZ(m.get(2, 3)); this.setRotation(new RotationNR(m)); } + /** + * Instantiates a new transform nr. + * + * @param m the m + */ + public TransformNR(TransformNR in) { + this(in.getMatrixTransform()); + } /** * Instantiates a new transform nr. From af1c55a5f241389f6e074ed763b2ede020a5efda Mon Sep 17 00:00:00 2001 From: Kevin harrington Date: Sun, 27 Oct 2024 17:40:23 -0400 Subject: [PATCH 60/60] removing all print staatements from Java-Bowler --- .../test/nrdk/BluetoothConector.java | 8 +-- .../test/nrdk/ByteListTest.java | 4 +- .../test/nrdk/ConnectionDialogTest.java | 6 +-- .../test/nrdk/ExtendGenericPID.java | 4 +- .../test/nrdk/GenericPIDTest.java | 2 +- .../test/nrdk/PingSpeedTest.java | 6 +-- .../test/nrdk/SimpleConnection.java | 4 +- .../test/nrdk/network/NetworkServerTest.java | 2 +- .../test/nrdk/network/UDPClientTest.java | 10 ++-- .../application/xmpp/DyIOConversation.java | 14 ++--- .../xmpp/DyIOConversationFactory.java | 2 +- .../GoogleChat/GoogleChatConversation.java | 8 +-- .../xmpp/GoogleChat/GoogleChatEngine.java | 6 +-- .../driver/interpreter/GCodeInterpreter.java | 4 +- .../sdk/addons/irobot/CreateArm.java | 2 +- .../kinematics/AbstractKinematicsNR.java | 12 ++--- .../sdk/addons/kinematics/AbstractLink.java | 2 +- .../sdk/addons/kinematics/GradiantDecent.java | 2 +- .../addons/kinematics/GradiantDecentNode.java | 2 +- .../addons/kinematics/LinkConfiguration.java | 2 +- .../sdk/addons/kinematics/LinkFactory.java | 2 +- .../sdk/addons/kinematics/MobileBase.java | 14 ++--- .../sdk/addons/kinematics/MockRotoryLink.java | 6 +-- .../addons/kinematics/SearchTreeSolver.java | 6 +-- .../addons/kinematics/VitaminLocation.java | 2 +- .../kinematics/gcodebridge/GcodeDevice.java | 4 +- .../addons/kinematics/ik/DeltaIKModel.java | 34 ++++++------ .../kinematics/math/RotationNRLegacy.java | 6 +-- .../kinematics/parallel/ParallelGroup.java | 14 ++--- .../sdk/addons/kinematics/xml/XmlFactory.java | 4 +- .../neuronrobotics/sdk/bootloader/Core.java | 4 +- .../neuronrobotics/sdk/bootloader/Hexml.java | 8 +-- .../sdk/bootloader/IntelHexParser.java | 4 +- .../neuronrobotics/sdk/bootloader/NRBoot.java | 16 +++--- .../sdk/bootloader/NRBootLoader.java | 8 +-- .../sdk/bowlercam/device/BowlerCamDevice.java | 24 ++++----- .../sdk/commands/bcs/io/GetValueCommand.java | 4 +- .../bcs/io/SetUARTBaudrateCommand.java | 2 +- .../bootloader/ProgramSectionCommand.java | 2 +- .../sdk/common/BowlerAbstractCommand.java | 2 +- .../sdk/common/BowlerAbstractConnection.java | 16 +++--- .../sdk/common/BowlerAbstractDevice.java | 6 +-- .../sdk/common/BowlerDatagram.java | 2 +- .../sdk/common/DeviceManager.java | 4 +- .../com/neuronrobotics/sdk/common/Log.java | 6 +-- .../neuronrobotics/sdk/common/MACAddress.java | 2 +- .../neuronrobotics/sdk/common/TickToc.java | 6 +-- .../device/server/BowlerAbstractServer.java | 4 +- .../sdk/config/SDKBuildInfo.java | 2 +- .../com/neuronrobotics/sdk/dyio/DyIO.java | 16 +++--- .../neuronrobotics/sdk/dyio/DyIOChannel.java | 6 +-- .../sdk/dyio/DyIOOutputStream.java | 4 +- .../dyio/peripherals/PPMReaderChannel.java | 2 +- .../sdk/javaxusb/UsbCDCSerialConnection.java | 18 +++---- .../sdk/network/UDPBowlerConnection.java | 8 +-- .../sdk/pid/PIDConfiguration.java | 2 +- .../sdk/pid/VirtualGenericPIDDevice.java | 6 +-- .../sdk/serial/SerialConnection.java | 10 ++-- .../sdk/ui/TCPConnectionPanel.java | 2 +- .../sdk/ui/UDPConnectionPanel.java | 4 +- .../sdk/ui/UsbConnectionPanel.java | 2 +- .../neuronrobotics/sdk/util/OsInfoUtil.java | 4 +- .../wireless/bluetooth/BlueCoveManager.java | 12 ++--- .../bluetooth/BluetoothSerialConnection.java | 2 +- .../utilities/ApacheCommonsRotationTest.java | 4 +- .../utilities/BowlerDatagramFactoryTests.java | 4 +- .../utilities/ByteListTest.java | 10 ++-- .../utilities/ExternalLinkProviderTest.java | 8 +-- .../neuronrobotics/utilities/GCODETest.java | 10 ++-- .../utilities/GsonVitaminLoad.java | 2 +- .../utilities/LoadMassTest.java | 2 +- .../utilities/PacketValidationTest.java | 6 +-- .../utilities/ParallelArmTest.java | 4 +- .../utilities/RotationNRTest.java | 52 +++++++++---------- .../utilities/TestMobilBaseLoading.java | 2 +- .../neuronrobotics/utilities/TestTimer.java | 2 +- 76 files changed, 260 insertions(+), 260 deletions(-) diff --git a/examples/java/src/com/neuronrobotics/test/nrdk/BluetoothConector.java b/examples/java/src/com/neuronrobotics/test/nrdk/BluetoothConector.java index f56e5479..6296ff72 100644 --- a/examples/java/src/com/neuronrobotics/test/nrdk/BluetoothConector.java +++ b/examples/java/src/com/neuronrobotics/test/nrdk/BluetoothConector.java @@ -19,16 +19,16 @@ public static void main(String[] args) { DyIO dyio; BlueCoveManager manager = new BlueCoveManager(); String devices[] = manager.getAvailableSerialDevices(true); - System.out.println("Devices: "); + com.neuronrobotics.sdk.common.Log.error("Devices: "); for (String d: devices) { - System.out.println(d); + com.neuronrobotics.sdk.common.Log.error(d); } if (devices.length > 0) { - System.out.println("Connecting to : "+devices[0]); + com.neuronrobotics.sdk.common.Log.error("Connecting to : "+devices[0]); dyio = new DyIO(new BluetoothSerialConnection(manager, devices[0])); dyio.connect(); if(dyio.ping() ) - System.out.println("All OK!"); + com.neuronrobotics.sdk.common.Log.error("All OK!"); } System.exit(0); diff --git a/examples/java/src/com/neuronrobotics/test/nrdk/ByteListTest.java b/examples/java/src/com/neuronrobotics/test/nrdk/ByteListTest.java index 962aff83..bed83712 100644 --- a/examples/java/src/com/neuronrobotics/test/nrdk/ByteListTest.java +++ b/examples/java/src/com/neuronrobotics/test/nrdk/ByteListTest.java @@ -15,9 +15,9 @@ public class ByteListTest { */ public static void main(String [] args) { byte [] b = ByteList.convertTo16(526); - System.out.println(b[0] + " - " + b[1]); + com.neuronrobotics.sdk.common.Log.error(b[0] + " - " + b[1]); int i = ByteList.convertToInt(b); - System.out.println(i); + com.neuronrobotics.sdk.common.Log.error(i); } } diff --git a/examples/java/src/com/neuronrobotics/test/nrdk/ConnectionDialogTest.java b/examples/java/src/com/neuronrobotics/test/nrdk/ConnectionDialogTest.java index 967fb8dd..3ac6658a 100644 --- a/examples/java/src/com/neuronrobotics/test/nrdk/ConnectionDialogTest.java +++ b/examples/java/src/com/neuronrobotics/test/nrdk/ConnectionDialogTest.java @@ -16,16 +16,16 @@ public class ConnectionDialogTest { * @param args the arguments */ public static void main(String[] args) { - System.out.println("Starting"); + com.neuronrobotics.sdk.common.Log.error("Starting"); DyIO dyio=new DyIO(); if (!ConnectionDialog.getBowlerDevice(dyio)){ - System.err.println("Dialog failed"); + com.neuronrobotics.sdk.common.Log.error("Dialog failed"); System.exit(1); } Log.enableDebugPrint(); dyio.ping(); dyio.disconnect(); - System.out.println("Connection OK!"); + com.neuronrobotics.sdk.common.Log.error("Connection OK!"); System.exit(0); //while(true); } diff --git a/examples/java/src/com/neuronrobotics/test/nrdk/ExtendGenericPID.java b/examples/java/src/com/neuronrobotics/test/nrdk/ExtendGenericPID.java index db874d73..8d3510d3 100644 --- a/examples/java/src/com/neuronrobotics/test/nrdk/ExtendGenericPID.java +++ b/examples/java/src/com/neuronrobotics/test/nrdk/ExtendGenericPID.java @@ -24,11 +24,11 @@ private ExtendGenericPID(){ System.exit(1); } try { - System.out.println("Extended get position: "+pid.getExtendedValue(0)); + com.neuronrobotics.sdk.common.Log.error("Extended get position: "+pid.getExtendedValue(0)); pid.GetAllPIDPosition(); pid.GetPIDPosition(2); pid.disconnect(); - System.out.println("All OK!"); + com.neuronrobotics.sdk.common.Log.error("All OK!"); System.exit(0); } catch (Exception e) { // TODO Auto-generated catch block diff --git a/examples/java/src/com/neuronrobotics/test/nrdk/GenericPIDTest.java b/examples/java/src/com/neuronrobotics/test/nrdk/GenericPIDTest.java index b1c169e8..579f0fc8 100644 --- a/examples/java/src/com/neuronrobotics/test/nrdk/GenericPIDTest.java +++ b/examples/java/src/com/neuronrobotics/test/nrdk/GenericPIDTest.java @@ -32,7 +32,7 @@ public static void main(String[] args) { pid.GetAllPIDPosition(); pid.GetPIDPosition(2); pid.disconnect(); - System.out.println("All OK!"); + com.neuronrobotics.sdk.common.Log.error("All OK!"); System.exit(0); } catch (Exception e) { // TODO Auto-generated catch block diff --git a/examples/java/src/com/neuronrobotics/test/nrdk/PingSpeedTest.java b/examples/java/src/com/neuronrobotics/test/nrdk/PingSpeedTest.java index 8f2a076d..647bceab 100644 --- a/examples/java/src/com/neuronrobotics/test/nrdk/PingSpeedTest.java +++ b/examples/java/src/com/neuronrobotics/test/nrdk/PingSpeedTest.java @@ -36,7 +36,7 @@ public static void main(String[] args) { // } if(c==null) System.exit(1); - System.out.println("Starting test"); + com.neuronrobotics.sdk.common.Log.error("Starting test"); Log.enableInfoPrint(); GenericDevice dev = new GenericDevice(c); dev.connect(); @@ -51,10 +51,10 @@ public static void main(String[] args) { double ms=System.currentTimeMillis()-start; avg +=ms; - System.out.println("Average cycle time: "+(int)(avg/i)+"ms\t\t\t this loop was: "+ms); + com.neuronrobotics.sdk.common.Log.error("Average cycle time: "+(int)(avg/i)+"ms\t\t\t this loop was: "+ms); dev.getNamespaces(); } - System.out.println("Average cycle time for ping: "+(avg/i)+" ms"); + com.neuronrobotics.sdk.common.Log.error("Average cycle time for ping: "+(avg/i)+" ms"); dev.disconnect(); System.exit(0); } diff --git a/examples/java/src/com/neuronrobotics/test/nrdk/SimpleConnection.java b/examples/java/src/com/neuronrobotics/test/nrdk/SimpleConnection.java index 393d8c80..cfe3b323 100644 --- a/examples/java/src/com/neuronrobotics/test/nrdk/SimpleConnection.java +++ b/examples/java/src/com/neuronrobotics/test/nrdk/SimpleConnection.java @@ -16,7 +16,7 @@ public class SimpleConnection { */ public static void main(String[] args) { SerialConnection s = null; - System.out.println("Connecting and disconnecting"); + com.neuronrobotics.sdk.common.Log.error("Connecting and disconnecting"); //Windows //s=new SerialConnection("COM5"); @@ -41,7 +41,7 @@ public static void main(String[] args) { avg +=ms; start = System.currentTimeMillis(); } - System.out.println("Average cycle time for ping: "+(avg/i)+" ms"); + com.neuronrobotics.sdk.common.Log.error("Average cycle time for ping: "+(avg/i)+" ms"); dyio.disconnect(); System.exit(0); //while(true); diff --git a/examples/java/src/com/neuronrobotics/test/nrdk/network/NetworkServerTest.java b/examples/java/src/com/neuronrobotics/test/nrdk/network/NetworkServerTest.java index b8251eda..5e5188ef 100644 --- a/examples/java/src/com/neuronrobotics/test/nrdk/network/NetworkServerTest.java +++ b/examples/java/src/com/neuronrobotics/test/nrdk/network/NetworkServerTest.java @@ -43,7 +43,7 @@ public static void main(String [] args){ new NetworkServerTest(); }catch (Exception e){ e.printStackTrace(); - System.err.println("###SERVER Failed out!"); + com.neuronrobotics.sdk.common.Log.error("###SERVER Failed out!"); System.exit(1); } } diff --git a/examples/java/src/com/neuronrobotics/test/nrdk/network/UDPClientTest.java b/examples/java/src/com/neuronrobotics/test/nrdk/network/UDPClientTest.java index 0a215ba4..bbf9c40a 100644 --- a/examples/java/src/com/neuronrobotics/test/nrdk/network/UDPClientTest.java +++ b/examples/java/src/com/neuronrobotics/test/nrdk/network/UDPClientTest.java @@ -28,7 +28,7 @@ public UDPClientTest(){ clnt=new UDPBowlerConnection(); // ArrayList addrs = clnt.getAllAddresses(); -// System.out.println("Availiable servers: "+addrs); +// com.neuronrobotics.sdk.common.Log.error("Availiable servers: "+addrs); // if (addrs.size()==0) // throw new RuntimeException(); // clnt.setAddress(addrs.get(0)); @@ -42,15 +42,15 @@ public UDPClientTest(){ setConnection(clnt); connect(); - System.out.println("Pinging"); + com.neuronrobotics.sdk.common.Log.error("Pinging"); long start = System.currentTimeMillis(); int numPings=10; for(int i=0;i> "+ message.getBody()); } try { String ret =onMessage(message.getBody(),chat, message.getFrom()); msg.setBody(ret); - System.out.println("Sending: "+msg.getBody()); + com.neuronrobotics.sdk.common.Log.error("Sending: "+msg.getBody()); if(log!=null){ log.onLogEvent(""+message.getFrom()+"<< "+ ret); } chat.sendMessage(msg); } catch (XMPPException ex) { ex.printStackTrace(); - System.out.println("Failed to send message"); + com.neuronrobotics.sdk.common.Log.error("Failed to send message"); } } else { - System.out.println("I got a message I didn't understand\n\n"+message.getType()); + com.neuronrobotics.sdk.common.Log.error("I got a message I didn't understand\n\n"+message.getType()); } } @@ -146,11 +146,11 @@ private ChatAsyncListener getListener(Chat c,String from){ for(ChatAsyncListener l:listeners ){ if(l.getFrom().equals(from) && l.getChat()==c){ back = l; - System.out.println("Found old listener"); + com.neuronrobotics.sdk.common.Log.error("Found old listener"); } } if(back == null){ - System.out.println("Adding new listener"); + com.neuronrobotics.sdk.common.Log.error("Adding new listener"); back = new ChatAsyncListener(c, from); listeners.add(back); } @@ -203,7 +203,7 @@ public void onChannelEvent(DyIOChannelEvent e) { Message msg = new Message(getFrom(), Message.Type.chat); String body = "asyncData "+e.getChannel().getChannelNumber()+" "+e.getValue(); msg.setBody(body); - System.err.println("async: "+msg.getBody()); + com.neuronrobotics.sdk.common.Log.error("async: "+msg.getBody()); try { chat.sendMessage(msg); } catch (XMPPException e1) { diff --git a/src/main/java/com/neuronrobotics/application/xmpp/DyIOConversationFactory.java b/src/main/java/com/neuronrobotics/application/xmpp/DyIOConversationFactory.java index 5bea6a76..331dde14 100644 --- a/src/main/java/com/neuronrobotics/application/xmpp/DyIOConversationFactory.java +++ b/src/main/java/com/neuronrobotics/application/xmpp/DyIOConversationFactory.java @@ -26,7 +26,7 @@ public DyIOConversationFactory(IChatLog mine) { */ @Override public IConversation getConversation() { - System.out.println("Getting DyIO conversation"); + com.neuronrobotics.sdk.common.Log.error("Getting DyIO conversation"); return new DyIOConversation(log); } } diff --git a/src/main/java/com/neuronrobotics/application/xmpp/GoogleChat/GoogleChatConversation.java b/src/main/java/com/neuronrobotics/application/xmpp/GoogleChat/GoogleChatConversation.java index fcb3efd0..b56e0d61 100644 --- a/src/main/java/com/neuronrobotics/application/xmpp/GoogleChat/GoogleChatConversation.java +++ b/src/main/java/com/neuronrobotics/application/xmpp/GoogleChat/GoogleChatConversation.java @@ -42,17 +42,17 @@ public String onMessage(String input,Chat chat, String from) { public void processMessage(Chat chat, Message message) { Message msg = new Message(message.getFrom(), Message.Type.chat); if(message.getType().equals(Message.Type.chat) && message.getBody() != null) { - System.out.println("Received: " + message.getBody()); + com.neuronrobotics.sdk.common.Log.error("Received: " + message.getBody()); try { msg.setBody(onMessage(message.getBody(),chat, message.getFrom())); - System.out.println("Sending: "+msg.getBody()); + com.neuronrobotics.sdk.common.Log.error("Sending: "+msg.getBody()); chat.sendMessage(msg); } catch (XMPPException ex) { ex.printStackTrace(); - System.out.println("Failed to send message"); + com.neuronrobotics.sdk.common.Log.error("Failed to send message"); } } else { - System.out.println("I got a message I didn't understand\n\n"+message.getType()); + com.neuronrobotics.sdk.common.Log.error("I got a message I didn't understand\n\n"+message.getType()); } } diff --git a/src/main/java/com/neuronrobotics/application/xmpp/GoogleChat/GoogleChatEngine.java b/src/main/java/com/neuronrobotics/application/xmpp/GoogleChat/GoogleChatEngine.java index a3df5e94..ae91f14e 100644 --- a/src/main/java/com/neuronrobotics/application/xmpp/GoogleChat/GoogleChatEngine.java +++ b/src/main/java/com/neuronrobotics/application/xmpp/GoogleChat/GoogleChatEngine.java @@ -136,10 +136,10 @@ private void setLoginInfo(InputStream config) { } catch (IOException e) { throw new RuntimeException(e); } - //System.out.println("Parsing File..."); + //com.neuronrobotics.sdk.common.Log.error("Parsing File..."); NodeList nList = doc.getElementsByTagName("login"); for (int temp = 0; temp < nList.getLength(); temp++) { - //System.out.println("Leg # "+temp); + //com.neuronrobotics.sdk.common.Log.error("Leg # "+temp); Element eElement = (Element)nList.item(temp); username = getTagValue("username",eElement); password = getTagValue("password",eElement); @@ -157,7 +157,7 @@ private void setLoginInfo(InputStream config) { public static String getTagValue(String sTag, Element eElement){ NodeList nlList= eElement.getElementsByTagName(sTag).item(0).getChildNodes(); Node nValue = (Node) nlList.item(0); - //System.out.println("\t\t"+sTag+" = "+nValue.getNodeValue()); + //com.neuronrobotics.sdk.common.Log.error("\t\t"+sTag+" = "+nValue.getNodeValue()); return nValue.getNodeValue(); } diff --git a/src/main/java/com/neuronrobotics/replicator/driver/interpreter/GCodeInterpreter.java b/src/main/java/com/neuronrobotics/replicator/driver/interpreter/GCodeInterpreter.java index 0a2ed7dd..2244a049 100644 --- a/src/main/java/com/neuronrobotics/replicator/driver/interpreter/GCodeInterpreter.java +++ b/src/main/java/com/neuronrobotics/replicator/driver/interpreter/GCodeInterpreter.java @@ -143,7 +143,7 @@ public void processSingleGCODELine(String line) throws Exception{ nextLine.storeWord('G', 0); nextLine.storeWord('M', 0); nextLine.storeWord('P', lineNumber); - System.out.println("GCODE: "+line); + com.neuronrobotics.sdk.common.Log.error("GCODE: "+line); for(int i=0;i l1+l2) { - System.err.println("Hypotenus too long"+x+" "+y+"\r\n"); + com.neuronrobotics.sdk.common.Log.error("Hypotenus too long"+x+" "+y+"\r\n"); return; } double elbow = 0; diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractKinematicsNR.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractKinematicsNR.java index 8e88e252..627f6e05 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractKinematicsNR.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractKinematicsNR.java @@ -278,7 +278,7 @@ protected ArrayList loadConfig(Element doc) { localConfigsFromXml.add(newLinkConf); NodeList dHParameters = linkNode.getChildNodes(); - // System.out.println("Link "+newLinkConf.getName()+" has "+dHParameters + // com.neuronrobotics.sdk.common.Log.error("Link "+newLinkConf.getName()+" has "+dHParameters // .getLength()+" children"); for (int x = 0; x < dHParameters.getLength(); x++) { Node nNode = dHParameters.item(x); @@ -309,9 +309,9 @@ public void onConnect(BowlerAbstractDevice source) { } else { if (nNode.getNodeType() == Node.ELEMENT_NODE && nNode.getNodeName().contentEquals("slaveLink")) { - // System.out.println("Slave link found: "); + // com.neuronrobotics.sdk.common.Log.error("Slave link found: "); LinkConfiguration jc = new LinkConfiguration((Element) nNode); - // System.out.println(jc); + // com.neuronrobotics.sdk.common.Log.error(jc); newLinkConf.getSlaveLinks().add(jc); } } @@ -341,7 +341,7 @@ public void onConnect(BowlerAbstractDevice source) { setRobotToFiducialTransform(new TransformNR()); } } else { - // System.err.println(linkNode.getNodeName()); + // com.neuronrobotics.sdk.common.Log.error(linkNode.getNodeName()); // Log.error("Node not known: "+linkNode.getNodeName()); } } @@ -977,9 +977,9 @@ public void setGlobalToFiducialTransform(TransformNR frameToBase) { * @return the transform nr */ public TransformNR inverseOffset(TransformNR t) { - // System.out.println("RobotToFiducialTransform + // com.neuronrobotics.sdk.common.Log.error("RobotToFiducialTransform // "+getRobotToFiducialTransform()); - // System.out.println("FiducialToRASTransform "+getFiducialToRASTransform()); + // com.neuronrobotics.sdk.common.Log.error("FiducialToRASTransform "+getFiducialToRASTransform()); Matrix globalToFeducialInverse = getFiducialToGlobalTransform().getMatrixTransform().inverse(); Matrix feducialToLimbInverse = getRobotToFiducialTransform().getMatrixTransform().inverse(); diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractLink.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractLink.java index 95fdf2c1..3eff4627 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractLink.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/AbstractLink.java @@ -125,7 +125,7 @@ public AbstractLink(LinkConfiguration conf){ this.conf=conf; slaveLinks = conf.getSlaveLinks(); if(slaveLinks.size()>0) - System.out.println(conf.getName()+" has slaves: "+slaveLinks.size()); + com.neuronrobotics.sdk.common.Log.error(conf.getName()+" has slaves: "+slaveLinks.size()); for(LinkConfiguration c:slaveLinks){ //generate the links getSlaveFactory().getLink(c); diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/GradiantDecent.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/GradiantDecent.java index 68c1e92a..be62c8e1 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/GradiantDecent.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/GradiantDecent.java @@ -83,7 +83,7 @@ public double[] inverseKinematics(TransformNR target,double[] jointSpaceVector, } }while(++iter<200 && notArrived && stopped == false);//preincrement and check if(debug){ - System.out.println("Numer of iterations #"+iter+" \n\tStalled = "+stopped+" \n\tArrived = "+!notArrived+" \n\tFinal offset= "+vect+" \n\tFinal orent= "+orent); + com.neuronrobotics.sdk.common.Log.error("Numer of iterations #"+iter+" \n\tStalled = "+stopped+" \n\tArrived = "+!notArrived+" \n\tFinal offset= "+vect+" \n\tFinal orent= "+orent); } return inv; } diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/GradiantDecentNode.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/GradiantDecentNode.java index 85bc3378..55a04f64 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/GradiantDecentNode.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/GradiantDecentNode.java @@ -228,7 +228,7 @@ public boolean step() { public void jitter(){ double jitterAmmount = 10; double jitter=(Math.random()*jitterAmmount)-(jitterAmmount /2) ; - System.out.println("Jittering Link #"+getIndex()+" jitter:"+jitter+" current offset:"+offset); + com.neuronrobotics.sdk.common.Log.error("Jittering Link #"+getIndex()+" jitter:"+jitter+" current offset:"+offset); offset += jitter; jointSpaceVector[getIndex()] = myStart+offset; } diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/LinkConfiguration.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/LinkConfiguration.java index 0ccba290..a5aeec65 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/LinkConfiguration.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/LinkConfiguration.java @@ -250,7 +250,7 @@ public LinkConfiguration(Element eElement) { if (staticOffset > getUpperLimit() || staticOffset < getLowerLimit()) Log.error("PID group " + getHardwareIndex() + " staticOffset is " + staticOffset + " but needs to be between " + getUpperLimit() + " and " + getLowerLimit()); - // System.out.println("Interted"+ inverted); + // com.neuronrobotics.sdk.common.Log.error("Interted"+ inverted); } /** diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/LinkFactory.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/LinkFactory.java index f9e67764..35a85f5a 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/LinkFactory.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/LinkFactory.java @@ -302,7 +302,7 @@ public void flush(final double seconds) { // TickToc.tic("Done Checking "+name+" for flush "); } - // System.out.println("Flush Took "+(System.currentTimeMillis()-time)+"ms"); + // com.neuronrobotics.sdk.common.Log.error("Flush Took "+(System.currentTimeMillis()-time)+"ms"); } /** diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java index eee4597b..63b3043a 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MobileBase.java @@ -157,7 +157,7 @@ public MobileBase(InputStream configFile) { NodeList nodListofLinks = doc.getElementsByTagName("root"); if (nodListofLinks.getLength() != 1) { - // System.out.println("Found "+nodListofLinks.getLength()); + // com.neuronrobotics.sdk.common.Log.error("Found "+nodListofLinks.getLength()); throw new RuntimeException("one mobile base is needed per level"); } NodeList rootNode = nodListofLinks.item(0).getChildNodes(); @@ -370,7 +370,7 @@ private String getTag(Element e, String tagname) { String nameOfElement = findNameTag(e); if(tagname.contentEquals("name")) return nameOfElement; - //System.out.println("Searching for "+tagname+" in "+nameOfElement); + //com.neuronrobotics.sdk.common.Log.error("Searching for "+tagname+" in "+nameOfElement); NodeList nodListofLinks = e.getElementsByTagName(tagname); for (int i = 0; i < nodListofLinks.getLength(); i++) { boolean isDirectChild=true; @@ -407,7 +407,7 @@ private void loadLimb(Element doc, String tag, ArrayList if (linkNode.getNodeType() == Node.ELEMENT_NODE && linkNode.getNodeName().contentEquals(tag)) { Element e = (Element) linkNode; final String name = getname(e); - // System.out.println("Loading arm "+name); + // com.neuronrobotics.sdk.common.Log.error("Loading arm "+name); DHParameterKinematics kin = (DHParameterKinematics) DeviceManager .getSpecificDevice(DHParameterKinematics.class, name); if (kin == null) { @@ -416,9 +416,9 @@ private void loadLimb(Element doc, String tag, ArrayList } kin.setScriptingName(name); String parallel = getParallelGroup(e); - // System.out.println("paralell "+parallel); + // com.neuronrobotics.sdk.common.Log.error("paralell "+parallel); if (parallel != null) { - System.out.println("Loading Paralell group " + parallel + " limb " + name); + com.neuronrobotics.sdk.common.Log.error("Loading Paralell group " + parallel + " limb " + name); TransformNR paraOffset = loadTransform("parallelGroupTipOffset", e); String relativeName = getTag(e, "relativeTo"); int index = 0; @@ -928,7 +928,7 @@ public double getMassKg() { } public void setMassKg(double mass) { - System.out.println("Mass of device " + getScriptingName() + " is " + mass); + com.neuronrobotics.sdk.common.Log.error("Mass of device " + getScriptingName() + " is " + mass); //new RuntimeException().printStackTrace(); this.mass = mass; fireConfigurationUpdate(); @@ -1046,7 +1046,7 @@ public static void main(String[] args) throws Exception { TransformNR TipOffset = group.getTipOffset().get(limb); TransformNR newTip = limb.getCurrentTaskSpaceTransform().times(TipOffset); - System.out.println("Expected tip to be " + Tip.getX() + " and got: " + newTip.getX()); + com.neuronrobotics.sdk.common.Log.error("Expected tip to be " + Tip.getX() + " and got: " + newTip.getX()); // assertTrue(!Double.isNaN(Tip.getX())); // assertEquals(Tip.getX(), newTip.getX(), .1); } diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MockRotoryLink.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MockRotoryLink.java index 5e2fd4ea..f6c0683d 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MockRotoryLink.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/MockRotoryLink.java @@ -33,7 +33,7 @@ public MockRotoryLink(LinkConfiguration conf) { @Override public void cacheTargetValueDevice() { val=getTargetValue(); - //System.out.println("Cacheing value="+val); + //com.neuronrobotics.sdk.common.Log.error("Cacheing value="+val); } /* (non-Javadoc) @@ -42,7 +42,7 @@ public void cacheTargetValueDevice() { @Override public void flushDevice(double time) { val=getTargetValue(); - //System.out.println("Flushing value="+val); + //com.neuronrobotics.sdk.common.Log.error("Flushing value="+val); } /* (non-Javadoc) @@ -61,7 +61,7 @@ public double getCurrentPosition() { public void flushAllDevice(double time) { // TODO Auto-generated method stub val=getTargetValue(); - //System.out.println("Flushing all Values"); + //com.neuronrobotics.sdk.common.Log.error("Flushing all Values"); } } diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/SearchTreeSolver.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/SearchTreeSolver.java index 3fb6863a..87d71c38 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/SearchTreeSolver.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/SearchTreeSolver.java @@ -65,11 +65,11 @@ public double[] inverseKinematics(TransformNR target,double[] jointSpaceVector, if(vect<10 && orent< .05){ done = true; - System.out.println("SearchTreeSolver Success stats: \n\tIterations = "+i+" out of "+iter+"\n"+conf); + com.neuronrobotics.sdk.common.Log.error("SearchTreeSolver Success stats: \n\tIterations = "+i+" out of "+iter+"\n"+conf); } if(i++==iter){ done = true; - System.err.println("SearchTreeSolver FAILED stats: \n\tIterations = "+i+" out of "+iter+"\n"+conf); + com.neuronrobotics.sdk.common.Log.error("SearchTreeSolver FAILED stats: \n\tIterations = "+i+" out of "+iter+"\n"+conf); } }while(! done); @@ -213,7 +213,7 @@ public configuration getBest(double[] jointSpaceVector){ } i++; } - //System.out.println("Selecting "+best+" config"); + //com.neuronrobotics.sdk.common.Log.error("Selecting "+best+" config"); return configurations.get(best); } } diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java index 7168c57f..78068fd9 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/VitaminLocation.java @@ -50,7 +50,7 @@ public VitaminLocation(boolean isScript,String name, String type, String size, T try { h.addVitamin(this); }catch(Throwable t){ - System.out.println("Vitamin "+name+" exists in "+h); + com.neuronrobotics.sdk.common.Log.error("Vitamin "+name+" exists in "+h); } } public VitaminLocation(Element vitamins) { diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/gcodebridge/GcodeDevice.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/gcodebridge/GcodeDevice.java index c6baab1f..19db038f 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/gcodebridge/GcodeDevice.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/gcodebridge/GcodeDevice.java @@ -262,13 +262,13 @@ public void flush(double seconds) { public void loadCurrent(){ String m114 =runLine("M114"); String[] currentPosStr = m114.split("Count")[0].split(" ");// get the current position - //System.out.println("Fush with current = "+m114); + //com.neuronrobotics.sdk.common.Log.error("Fush with current = "+m114); for(String s:currentPosStr){ for(LinkConfiguration l:links.keySet()){ IGCodeChannel thisLink = links.get(l); if(s.contains(thisLink.getAxis())){ String [] parts = s.split(":"); - ///System.out.println("Found axis = "+s); + ///com.neuronrobotics.sdk.common.Log.error("Found axis = "+s); thisLink.setValue(Double.parseDouble(parts[1])); } } diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/ik/DeltaIKModel.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/ik/DeltaIKModel.java index 823a6f3e..5c55a71f 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/ik/DeltaIKModel.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/ik/DeltaIKModel.java @@ -49,13 +49,13 @@ public double[] inverseKinematics6dof(TransformNR target, double[] jointSpaceVec // Start by finding the IK to the wrist center if(linkNum>=6) { //offset for tool - //if(debug)System.out.println( "Offestting for tool" + //if(debug)com.neuronrobotics.sdk.common.Log.error( "Offestting for tool" TransformNR tool = new TransformNR(); if(linkNum==7) tool=linkOffset(links.get(6)); // compute the transform from tip to wrist center TransformNR wristCenterOffsetTransform = linkOffset(links.get(5)).times(tool); - //System.out.println( wristCenterOffsetTransform + //com.neuronrobotics.sdk.common.Log.error( wristCenterOffsetTransform // take off the tool from the target to get the center of the wrist newCenter = target.times(wristCenterOffsetTransform.inverse()); } @@ -68,17 +68,17 @@ public double[] inverseKinematics6dof(TransformNR target, double[] jointSpaceVec // Compute the xy plane projection of the tip // this is the angle of the tipto the base link if(x==0&&y==0) { - System.out.println( "Singularity! try something else"); + com.neuronrobotics.sdk.common.Log.error( "Singularity! try something else"); return inverseKinematics6dof(target.copy().translateX(0.01),jointSpaceVector,chain); } - if(debug)System.out.println( "Wrist center for IK "+x+","+y+","+z); + if(debug)com.neuronrobotics.sdk.common.Log.error( "Wrist center for IK "+x+","+y+","+z); double baseVectorAngle = Math.toDegrees(Math.atan2(y , x)); double elbowLink1CompositeLength = length(l1Offset); double elbowLink2CompositeLength=length(l3Offset); double wristVect = length(newCenter); - if(debug)System.out.println( "elbowLink1CompositeLength "+elbowLink1CompositeLength); - if(debug)System.out.println( "elbowLink2CompositeLength "+elbowLink2CompositeLength); - if(debug)System.out.println( "Elbo Hypotinuse "+wristVect); + if(debug)com.neuronrobotics.sdk.common.Log.error( "elbowLink1CompositeLength "+elbowLink1CompositeLength); + if(debug)com.neuronrobotics.sdk.common.Log.error( "elbowLink2CompositeLength "+elbowLink2CompositeLength); + if(debug)com.neuronrobotics.sdk.common.Log.error( "Elbo Hypotinuse "+wristVect); double elbowTiltAngle =-( Math.toDegrees( Math.acos( ( @@ -90,7 +90,7 @@ public double[] inverseKinematics6dof(TransformNR target, double[] jointSpaceVec (2*elbowLink2CompositeLength*elbowLink1CompositeLength) ) )); - if(debug)System.out.println( "Elbow angle "+elbowTiltAngle); + if(debug)com.neuronrobotics.sdk.common.Log.error( "Elbow angle "+elbowTiltAngle); jointSpaceVector[2]=elbowTiltAngle - Math.toDegrees(links.get(2).getTheta()); TransformNR local = new TransformNR(0,0,0,new RotationNR(0, -baseVectorAngle, 0)); @@ -100,7 +100,7 @@ public double[] inverseKinematics6dof(TransformNR target, double[] jointSpaceVec double L1 = length(l1Offset); double L2 = length(l3Offset); - if(debug)System.out.println( "L1 "+L1+" l2 "+L2+" z "+elZ+" x "+elX); + if(debug)com.neuronrobotics.sdk.common.Log.error( "L1 "+L1+" l2 "+L2+" z "+elZ+" x "+elX); /** * System of equasions * Theta2 = asin(z/wristVect) @@ -139,10 +139,10 @@ public double[] inverseKinematics6dof(TransformNR target, double[] jointSpaceVec ); } TransformNR sphericalElbowTartget = reorent.times(newCenter); - //System.out.println( newCenter - //System.out.println( sphericalElbowTartget + //com.neuronrobotics.sdk.common.Log.error( newCenter + //com.neuronrobotics.sdk.common.Log.error( sphericalElbowTartget sphericalElbowTartget = new TransformNR(0.0,-sphericalElbowTartget.getY(),0.0, new RotationNR()).times(sphericalElbowTartget); - //System.out.println( sphericalElbowTartget + //com.neuronrobotics.sdk.common.Log.error( sphericalElbowTartget double theta3 = Math.atan2(sphericalElbowTartget.getZ(), sphericalElbowTartget.getX()); jointSpaceVector[1]=-Math.toDegrees(theta3) ; @@ -167,10 +167,10 @@ public double[] inverseKinematics6dof(TransformNR target, double[] jointSpaceVec TransformNR wristMOvedToCenter0 =startOfWristSet .inverse()// move back from base ot wrist to world home .times(virtualcenter);// move forward to target, leaving the angle between the tip and the start of the rotation - //if(debug)System.out.println( wristMOvedToCenter0 + //if(debug)com.neuronrobotics.sdk.common.Log.error( wristMOvedToCenter0 RotationNR qWrist=wristMOvedToCenter0.getRotation(); if(wristMOvedToCenter0.getX()==0&&wristMOvedToCenter0.getY()==0) { - System.out.println( "Singularity! try something else"); + com.neuronrobotics.sdk.common.Log.error( "Singularity! try something else"); return inverseKinematics6dof(target.copy().translateX(0.01),jointSpaceVector,chain); } double closest= (Math.toDegrees(Math.atan2(wristMOvedToCenter0.getY(), wristMOvedToCenter0.getX()))-Math.toDegrees(links.get(3).getTheta())); @@ -192,10 +192,10 @@ public double[] inverseKinematics6dof(TransformNR target, double[] jointSpaceVec TransformNR wristMOvedToCenter1 =startOfWristSet2 .inverse()// move back from base ot wrist to world home .times(virtualcenter);// move forward to target, leaving the angle between the tip and the start of the rotation - //if(debug)System.out.println( " Middle link =" +wristMOvedToCenter1 + //if(debug)com.neuronrobotics.sdk.common.Log.error( " Middle link =" +wristMOvedToCenter1 RotationNR qWrist2=wristMOvedToCenter1.getRotation(); if(wristMOvedToCenter1.getX()==0&&wristMOvedToCenter1.getY()==0) { - System.out.println( "Singularity! try something else"); + com.neuronrobotics.sdk.common.Log.error( "Singularity! try something else"); return inverseKinematics6dof(target.copy().translateX(0.01),jointSpaceVector,chain); } jointSpaceVector[4]=(Math.toDegrees(Math.atan2(wristMOvedToCenter1.getY(), wristMOvedToCenter1.getX()))- @@ -217,7 +217,7 @@ public double[] inverseKinematics6dof(TransformNR target, double[] jointSpaceVec TransformNR wristMOvedToCenter2 =startOfWristSet3 .inverse()// move back from base ot wrist to world home .times(target.times(tool.inverse()));// move forward to target, leaving the angle between the tip and the start of the rotation - //if(debug)System.out.println( "\n\nLastLink " +wristMOvedToCenter2 + //if(debug)com.neuronrobotics.sdk.common.Log.error( "\n\nLastLink " +wristMOvedToCenter2 RotationNR qWrist3=wristMOvedToCenter2.getRotation(); jointSpaceVector[5]=(Math.toDegrees(qWrist3.getRotationAzimuth())-Math.toDegrees(links.get(5).getTheta())); diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/RotationNRLegacy.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/RotationNRLegacy.java index d4f15caf..62ec6ebd 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/RotationNRLegacy.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/math/RotationNRLegacy.java @@ -47,7 +47,7 @@ public RotationNRLegacy(double tilt, double elevation, double azumeth) { loadFromAngles(tilt, azumeth, elevation); if (Double.isNaN(getRotationMatrix2QuaturnionW()) || Double.isNaN(getRotationMatrix2QuaturnionX()) || Double.isNaN(getRotationMatrix2QuaturnionY()) || Double.isNaN(getRotationMatrix2QuaturnionZ())) { - // System.err.println("Failing to set proper angle, jittering"); + // com.neuronrobotics.sdk.common.Log.error("Failing to set proper angle, jittering"); loadFromAngles(tilt + Math.random() * .02 + .001, azumeth + Math.random() * .02 + .001, elevation + Math.random() * .02 + .001); } @@ -70,13 +70,13 @@ private void loadFromAngles(double tilt, double azumeth, double elevation) { double s3 = Math.sin(bank / 2); double c1c2 = c1 * c2; double s1s2 = s1 * s2; - // System.out.println("C1 ="+c1+" S1 ="+s1+" |C2 ="+c2+" S2 ="+s2+" |C3 + // com.neuronrobotics.sdk.common.Log.error("C1 ="+c1+" S1 ="+s1+" |C2 ="+c2+" S2 ="+s2+" |C3 // ="+c3+" S3 ="+s3); w = c1c2 * c3 - s1s2 * s3; x = c1c2 * s3 + s1s2 * c3; y = s1 * c2 * c3 + c1 * s2 * s3; z = c1 * s2 * c3 - s1 * c2 * s3; - // System.out.println("W ="+w+" x ="+x+" y ="+y+" z ="+z); + // com.neuronrobotics.sdk.common.Log.error("W ="+w+" x ="+x+" y ="+y+" z ="+z); quaternion2RotationMatrix(w, x, y, z); } diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/parallel/ParallelGroup.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/parallel/ParallelGroup.java index 2db1dda4..c3b5851c 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/parallel/ParallelGroup.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/parallel/ParallelGroup.java @@ -90,7 +90,7 @@ public void setupReferencedLimbStartup(DHParameterKinematics limb, TransformNR t tipOffsetRelativeToName.put(limb, name); tipOffsetRelativeIndex.put(limb, index); getTipOffset().put(limb, tip); - System.out.println("Limb "+limb.getScriptingName()+" set relative to "+name); + com.neuronrobotics.sdk.common.Log.error("Limb "+limb.getScriptingName()+" set relative to "+name); } else { clearReferencedLimb(limb); DHParameterKinematics fk=getFKLimb(); @@ -106,9 +106,9 @@ public void setupReferencedLimbStartup(DHParameterKinematics limb, TransformNR t // for (DHParameterKinematics d : getConstituantLimbs()) { // if (getTipOffset(d) != null) { // try { -// //System.out.println("Setting Kinematics for follower "+d.getScriptingName()); +// //com.neuronrobotics.sdk.common.Log.error("Setting Kinematics for follower "+d.getScriptingName()); // double[] jointSpaceVect = compute(d, IKvalues, pose); -// //System.out.println(fk.getScriptingName()+" is Setting sublimb target "+d.getScriptingName()); +// //com.neuronrobotics.sdk.common.Log.error(fk.getScriptingName()+" is Setting sublimb target "+d.getScriptingName()); // d.throwExceptionOnJointLimit(false); // d.setDesiredJointSpaceVector(jointSpaceVect, 0); // } catch (Exception e) { @@ -149,7 +149,7 @@ private double[] compute(DHParameterKinematics ldh, HashMap IK TransformNR taskSpaceTransform) throws Exception { String scriptingName = ldh.getScriptingName(); if (IKvalues.get(scriptingName) == null) { - //System.out.println("Perform IK "+ldh.getScriptingName()); + //com.neuronrobotics.sdk.common.Log.error("Perform IK "+ldh.getScriptingName()); if (getTipOffset().get(ldh) == null) { // no offset, compute as normal double[] jointSpaceVect = ldh.inverseKinematics(ldh.inverseOffset(taskSpaceTransform)); @@ -180,7 +180,7 @@ private DHParameterKinematics findReferencedLimb(String refLimbName) { // FOund the referenced limb referencedLimb = lm; }else { - //System.out.println("Searching for "+refLimbName+" no match with "+lm.getScriptingName()); + //com.neuronrobotics.sdk.common.Log.error("Searching for "+refLimbName+" no match with "+lm.getScriptingName()); } } return referencedLimb; @@ -195,7 +195,7 @@ private DHParameterKinematics findReferencedLimb(String refLimbName) { public void setCurrentPoseTarget(TransformNR currentPoseTarget) { if (checkTaskSpaceTransform(currentPoseTarget)) { super.setCurrentPoseTarget(currentPoseTarget); - //System.out.println("Paralell set to " + currentPoseTarget); + //com.neuronrobotics.sdk.common.Log.error("Paralell set to " + currentPoseTarget); } } public double[] getCurrentJointSpaceVector(DHParameterKinematics k) { @@ -227,7 +227,7 @@ public double[] inverseKinematics(TransformNR taskSpaceTransform) throws Excepti } public void printError(TransformNR taskSpaceTransform) throws Exception { printError(taskSpaceTransform,t -> { - System.out.println(t); + com.neuronrobotics.sdk.common.Log.error(t); }); } public void printError(TransformNR taskSpaceTransform, Consumer printer) throws Exception { diff --git a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/xml/XmlFactory.java b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/xml/XmlFactory.java index 6e73e2b3..1011ff88 100644 --- a/src/main/java/com/neuronrobotics/sdk/addons/kinematics/xml/XmlFactory.java +++ b/src/main/java/com/neuronrobotics/sdk/addons/kinematics/xml/XmlFactory.java @@ -92,7 +92,7 @@ public static String getTagValue(String sTag, Element eElement){ NodeList nlList= eElement.getElementsByTagName(sTag).item(0).getChildNodes(); Node nValue = (Node) nlList.item(0); - // System.out.println("\t\t"+sTag+" = "+nValue.getNodeValue()); + // com.neuronrobotics.sdk.common.Log.error("\t\t"+sTag+" = "+nValue.getNodeValue()); return nValue.getNodeValue(); } @@ -106,7 +106,7 @@ public static String getTagValue(String sTag, Element eElement){ public static Double getTagValueDouble(String sTag, Element eElement){ NodeList nlList= eElement.getElementsByTagName(sTag).item(0).getChildNodes(); Node nValue = (Node) nlList.item(0); - // System.out.println("\t\t"+sTag+" = "+nValue.getNodeValue()); + // com.neuronrobotics.sdk.common.Log.error("\t\t"+sTag+" = "+nValue.getNodeValue()); return Double.parseDouble(nValue.getNodeValue()); } } diff --git a/src/main/java/com/neuronrobotics/sdk/bootloader/Core.java b/src/main/java/com/neuronrobotics/sdk/bootloader/Core.java index 3c043280..f0ac71f0 100644 --- a/src/main/java/com/neuronrobotics/sdk/bootloader/Core.java +++ b/src/main/java/com/neuronrobotics/sdk/bootloader/Core.java @@ -55,14 +55,14 @@ public Core(int core,String file, NRBootCoreType type){ try { tmp.add(new hexLine(strLine)); } catch (Exception e) { - System.err.println("This is not a valid hex file"); + com.neuronrobotics.sdk.common.Log.error("This is not a valid hex file"); } } //Close the input stream in.close(); setLines(tmp); }catch (Exception e) { - ////System.out.println("File not found!!"); + ////com.neuronrobotics.sdk.common.Log.error("File not found!!"); } } diff --git a/src/main/java/com/neuronrobotics/sdk/bootloader/Hexml.java b/src/main/java/com/neuronrobotics/sdk/bootloader/Hexml.java index 870d5934..4acd5460 100644 --- a/src/main/java/com/neuronrobotics/sdk/bootloader/Hexml.java +++ b/src/main/java/com/neuronrobotics/sdk/bootloader/Hexml.java @@ -48,11 +48,11 @@ public Hexml(File hexml) throws ParserConfigurationException, SAXException, IOEx doc = dBuilder.parse(hexml); doc.getDocumentElement().normalize(); - ////System.out.println("Root element :" + doc.getDocumentElement().getNodeName()); + ////com.neuronrobotics.sdk.common.Log.error("Root element :" + doc.getDocumentElement().getNodeName()); loadRevision(doc); //NodeList nList = doc.getElementsByTagName("revision"); //revision = getTagValue("revision",(Element)nList.item(0)); - ////System.out.println("Revision is:"+revision); + ////com.neuronrobotics.sdk.common.Log.error("Revision is:"+revision); NodeList nList = doc.getElementsByTagName("core"); for (int temp = 0; temp < nList.getLength(); temp++) { Node nNode = nList.item(temp); @@ -62,7 +62,7 @@ public Hexml(File hexml) throws ParserConfigurationException, SAXException, IOEx //int word = Integer.parseInt(getTagValue("wordSize",eElement)); NRBootCoreType type = NRBootCoreType.find(getTagValue("type",eElement)); if (type == null) { - System.err.println("Failed to get a core type for: "+getTagValue("type",eElement)); + com.neuronrobotics.sdk.common.Log.error("Failed to get a core type for: "+getTagValue("type",eElement)); continue; } String hexFile = getTagValue("hex",eElement); @@ -77,7 +77,7 @@ public Hexml(File hexml) throws ParserConfigurationException, SAXException, IOEx } } Core tmp = new Core(index, lines, type); - ////System.out.println("Adding new core: "+tmp); + ////com.neuronrobotics.sdk.common.Log.error("Adding new core: "+tmp); cores.add(tmp); } } diff --git a/src/main/java/com/neuronrobotics/sdk/bootloader/IntelHexParser.java b/src/main/java/com/neuronrobotics/sdk/bootloader/IntelHexParser.java index f9e6a5ff..3e00ebd9 100644 --- a/src/main/java/com/neuronrobotics/sdk/bootloader/IntelHexParser.java +++ b/src/main/java/com/neuronrobotics/sdk/bootloader/IntelHexParser.java @@ -77,11 +77,11 @@ public IntelHexParser(ArrayList lines, NRBootCoreType type) throws IOEx if (l.getRecordType()==4){ byte[] haddr=l.getDataBytes(); highAddress = ByteList.convertToInt(haddr, false)*65536; - ////System.out.println("High Address :" + highAddress); + ////com.neuronrobotics.sdk.common.Log.error("High Address :" + highAddress); } if (l.getRecordType()==0){ l.setHighAddress(highAddress); - ////System.out.println(l); + ////com.neuronrobotics.sdk.common.Log.error(l); currentAddress=l.getStartAddress(); checkAddressValidity(currentAddress,type); diff --git a/src/main/java/com/neuronrobotics/sdk/bootloader/NRBoot.java b/src/main/java/com/neuronrobotics/sdk/bootloader/NRBoot.java index e3d4569b..b5dc0e74 100644 --- a/src/main/java/com/neuronrobotics/sdk/bootloader/NRBoot.java +++ b/src/main/java/com/neuronrobotics/sdk/bootloader/NRBoot.java @@ -42,7 +42,7 @@ public NRBoot(BowlerAbstractDevice pm){ //JOptionPane.showMessageDialog(null, message, message, JOptionPane.ERROR_MESSAGE); throw e; } - //System.out.println("Connection to bowler device ready"); + //com.neuronrobotics.sdk.common.Log.error("Connection to bowler device ready"); } /** @@ -54,10 +54,10 @@ public NRBoot(String serialPort){ this.boot=new NRBootLoader(new SerialConnection(serialPort)); boot.connect(); if (boot.ping()){ - //System.out.println("Connection to bowler device ready"); + //com.neuronrobotics.sdk.common.Log.error("Connection to bowler device ready"); return; } - //System.out.println("Not a Bowler Device"); + //com.neuronrobotics.sdk.common.Log.error("Not a Bowler Device"); boot.disconnect(); boot=null; } @@ -72,12 +72,12 @@ public boolean load(Core core) { String id = getDevice().getBootloaderID(); if (id==null){ - System.err.println("Device is not a bootloader"); + com.neuronrobotics.sdk.common.Log.error("Device is not a bootloader"); return false; }else if (id.contains(core.getType().getReadableName())) { - //System.out.println("Bootloader ID:"+core.getType().getReadableName()); + //com.neuronrobotics.sdk.common.Log.error("Bootloader ID:"+core.getType().getReadableName()); }else{ - System.err.println("##core is Invalid##\nExpected:"+core.getType().getReadableName()+" got: "+id); + com.neuronrobotics.sdk.common.Log.error("##core is Invalid##\nExpected:"+core.getType().getReadableName()+" got: "+id); return false; } @@ -110,13 +110,13 @@ private IntelHexParser getParser(Core core) { */ private void send(IntelHexParser parse,int core){ boot.erase(core); - //System.out.println("Writing to flash"); + //com.neuronrobotics.sdk.common.Log.error("Writing to flash"); int printLine=0; ByteData line = parse.getNext(); while (line != null){ if(!boot.write(core, line)){ - //System.out.println("Failed to write, is the device in bootloader mode?"); + //com.neuronrobotics.sdk.common.Log.error("Failed to write, is the device in bootloader mode?"); return; } diff --git a/src/main/java/com/neuronrobotics/sdk/bootloader/NRBootLoader.java b/src/main/java/com/neuronrobotics/sdk/bootloader/NRBootLoader.java index ba868781..e7471a2b 100644 --- a/src/main/java/com/neuronrobotics/sdk/bootloader/NRBootLoader.java +++ b/src/main/java/com/neuronrobotics/sdk/bootloader/NRBootLoader.java @@ -44,11 +44,11 @@ public NRBootLoader(BowlerAbstractConnection serialConnection) { @Override public boolean connect() { if(super.connect()) { - //System.out.println("Connect OK"); + //com.neuronrobotics.sdk.common.Log.error("Connect OK"); try { getBootloaderID(); }catch (Exception e) { - //System.out.println("Failed bootloader test"); + //com.neuronrobotics.sdk.common.Log.error("Failed bootloader test"); disconnect(); } } @@ -95,7 +95,7 @@ public boolean write(int core, ByteData flashData){ return true; } } - System.err.println("\nFailed to send 10 times!\n"); + com.neuronrobotics.sdk.common.Log.error("\nFailed to send 10 times!\n"); return false; } @@ -132,7 +132,7 @@ public void reset(){ */ public void onAllResponse(BowlerDatagram data) { // TODO Auto-generated method stub - ////System.out.println(data); + ////com.neuronrobotics.sdk.common.Log.error(data); } /* (non-Javadoc) diff --git a/src/main/java/com/neuronrobotics/sdk/bowlercam/device/BowlerCamDevice.java b/src/main/java/com/neuronrobotics/sdk/bowlercam/device/BowlerCamDevice.java index 9ad69fb9..6a6d7e61 100644 --- a/src/main/java/com/neuronrobotics/sdk/bowlercam/device/BowlerCamDevice.java +++ b/src/main/java/com/neuronrobotics/sdk/bowlercam/device/BowlerCamDevice.java @@ -89,7 +89,7 @@ public void onAllResponse(BowlerDatagram data) { * @throws IOException Signals that an I/O exception has occurred. */ public BufferedImage getHighSpeedImage(int cam) throws MalformedURLException, IOException { - //System.out.println("Getting HighSpeedImage"); + //com.neuronrobotics.sdk.common.Log.error("Getting HighSpeedImage"); while(urls.size()<(cam+1) && isAvailable()){ Log.info("Adding dummy url: "+urls.size()); urls.add(null); @@ -99,11 +99,11 @@ public BufferedImage getHighSpeedImage(int cam) throws MalformedURLException, IO images.add(null); } if(urls.get(cam) == null){ - //System.out.println("URL List element is empty: "+urls); + //com.neuronrobotics.sdk.common.Log.error("URL List element is empty: "+urls); urls.set(cam,getImageServerURL(cam)); } try { - //System.out.println("Reading: "+urls.get(cam) ); + //com.neuronrobotics.sdk.common.Log.error("Reading: "+urls.get(cam) ); ImageReader ir = new ImageReader(cam); ir.start(); long start = currentTimeMillis(); @@ -175,7 +175,7 @@ public void onAsyncResponse(BowlerDatagram data) { tmp.add(imgData); } if(index == (total)){ - ////System.out.println("Making image"); + ////com.neuronrobotics.sdk.common.Log.error("Making image"); BufferedImage image=null; try { synchronized(tmp) { @@ -191,7 +191,7 @@ public void onAsyncResponse(BowlerDatagram data) { } images.set(camera, image); fireIWebcamImageListenerEvent(camera,images.get(camera)); - //System.out.println("Image OK"); + //com.neuronrobotics.sdk.common.Log.error("Image OK"); } } @@ -345,27 +345,27 @@ public highSpeedAutoCapture(int cam,double scale,int fps){ return; } mspf = (int)(1000.0/((double)fps)); - //System.out.println("MS/frame: "+mspf); + //com.neuronrobotics.sdk.common.Log.error("MS/frame: "+mspf); } /* (non-Javadoc) * @see java.lang.Thread#run() */ public void run() { - //System.out.println("Starting auto capture on: "+getImageServerURL(cam)); + //com.neuronrobotics.sdk.common.Log.error("Starting auto capture on: "+getImageServerURL(cam)); long st = currentTimeMillis(); while(running && isAvailable()) { - //System.out.println("Getting image from: "+getImageServerURL(cam)); + //com.neuronrobotics.sdk.common.Log.error("Getting image from: "+getImageServerURL(cam)); try { - //System.out.println("Capturing"); + //com.neuronrobotics.sdk.common.Log.error("Capturing"); BufferedImage im =getHighSpeedImage(cam); if(scale>1.01||scale<.99) im = resize(im, scale); if(im!=null){ - //System.out.println("Fireing"); + //com.neuronrobotics.sdk.common.Log.error("Fireing"); fireIWebcamImageListenerEvent(cam,im); } - //System.out.println("ok"); + //com.neuronrobotics.sdk.common.Log.error("ok"); } catch (Exception e) { e.printStackTrace(); } @@ -388,7 +388,7 @@ public void run() { * Kill. */ public void kill() { - //System.out.println("Killing auto capture on cam: "+cam); + //com.neuronrobotics.sdk.common.Log.error("Killing auto capture on cam: "+cam); running = false; } } diff --git a/src/main/java/com/neuronrobotics/sdk/commands/bcs/io/GetValueCommand.java b/src/main/java/com/neuronrobotics/sdk/commands/bcs/io/GetValueCommand.java index e5f1e28e..8f56c790 100644 --- a/src/main/java/com/neuronrobotics/sdk/commands/bcs/io/GetValueCommand.java +++ b/src/main/java/com/neuronrobotics/sdk/commands/bcs/io/GetValueCommand.java @@ -55,11 +55,11 @@ public byte[] getCallingData() { public BowlerDatagram validate(BowlerDatagram data) throws InvalidResponseException { super.validate(data); if (data == null){ - //System.err.println("No response to Get Value Command\n"+data); + //com.neuronrobotics.sdk.common.Log.error("No response to Get Value Command\n"+data); throw new InvalidResponseException("Get Channel Value did not respond."); } if(!data.getRPC().equals(getOpCode())) { - //System.err.println("Wrong response to Get Value Command, expected:"+getOpCode()+", got:\n"+data); + //com.neuronrobotics.sdk.common.Log.error("Wrong response to Get Value Command, expected:"+getOpCode()+", got:\n"+data); throw new InvalidResponseException("Get Channel Value did not return with 'gchv'.\n"+data); } diff --git a/src/main/java/com/neuronrobotics/sdk/commands/bcs/io/SetUARTBaudrateCommand.java b/src/main/java/com/neuronrobotics/sdk/commands/bcs/io/SetUARTBaudrateCommand.java index 4d75c607..ef5b13e7 100644 --- a/src/main/java/com/neuronrobotics/sdk/commands/bcs/io/SetUARTBaudrateCommand.java +++ b/src/main/java/com/neuronrobotics/sdk/commands/bcs/io/SetUARTBaudrateCommand.java @@ -49,7 +49,7 @@ public BowlerDatagram validate(BowlerDatagram data) throws InvalidResponseExcept if(!data.getRPC().equals("_rdy")) { throw new InvalidResponseException("Could not set the UART passthough baudrate."); } - //System.out.println("Baudrate set return: \n"+data); + //com.neuronrobotics.sdk.common.Log.error("Baudrate set return: \n"+data); return data; } } diff --git a/src/main/java/com/neuronrobotics/sdk/commands/neuronrobotics/bootloader/ProgramSectionCommand.java b/src/main/java/com/neuronrobotics/sdk/commands/neuronrobotics/bootloader/ProgramSectionCommand.java index 41c3f1e1..8e651d04 100644 --- a/src/main/java/com/neuronrobotics/sdk/commands/neuronrobotics/bootloader/ProgramSectionCommand.java +++ b/src/main/java/com/neuronrobotics/sdk/commands/neuronrobotics/bootloader/ProgramSectionCommand.java @@ -32,7 +32,7 @@ public static String hex(long n) { */ public ProgramSectionCommand(int channel, int address, ByteList byteData) { setOpCode("prog"); - System.out.println("Sending to address "+hex(address)+" size = "+byteData.size()); + com.neuronrobotics.sdk.common.Log.error("Sending to address "+hex(address)+" size = "+byteData.size()); setMethod(BowlerMethod.CRITICAL); getCallingDataStorage().add(channel); getCallingDataStorage().addAs32(address); diff --git a/src/main/java/com/neuronrobotics/sdk/common/BowlerAbstractCommand.java b/src/main/java/com/neuronrobotics/sdk/common/BowlerAbstractCommand.java index becd6c7a..d9a0a008 100644 --- a/src/main/java/com/neuronrobotics/sdk/common/BowlerAbstractCommand.java +++ b/src/main/java/com/neuronrobotics/sdk/common/BowlerAbstractCommand.java @@ -129,7 +129,7 @@ public BowlerDatagram validate(BowlerDatagram data) throws InvalidResponseExcept if( data.getRPC().equals("_err")) { Integer zone=Integer.valueOf(data.getData().getByte(0)); Integer section=Integer.valueOf(data.getData().getByte(1)); - //System.err.println("Failed!!\n"+data); + //com.neuronrobotics.sdk.common.Log.error("Failed!!\n"+data); switch(zone) { default: throw new InvalidResponseException("Unknown error. (" + zone + " " + section + ")"); diff --git a/src/main/java/com/neuronrobotics/sdk/common/BowlerAbstractConnection.java b/src/main/java/com/neuronrobotics/sdk/common/BowlerAbstractConnection.java index b9100408..4efe00d2 100644 --- a/src/main/java/com/neuronrobotics/sdk/common/BowlerAbstractConnection.java +++ b/src/main/java/com/neuronrobotics/sdk/common/BowlerAbstractConnection.java @@ -343,7 +343,7 @@ public synchronized void setConnected(boolean c) { @Override public void run() { if(isConnected()){ - //System.out.println("WARNING: Bowler devices should be shut down before exit"); + //com.neuronrobotics.sdk.common.Log.error("WARNING: Bowler devices should be shut down before exit"); disconnect(); } } @@ -867,7 +867,7 @@ public ArrayList getNamespaces(MACAddress addr){ if(tmpNs.length() == namespacePacket.getData().size()){ //Done with the packet BowlerDatagramFactory.freePacket(namespacePacket); - //System.out.println("Ns = "+tmpNs+" len = "+tmpNs.length()+" data = "+b.getData().size()); + //com.neuronrobotics.sdk.common.Log.error("Ns = "+tmpNs+" len = "+tmpNs.length()+" data = "+b.getData().size()); namespacePacket = send(new NamespaceCommand(),addr,5); num= namespacePacket.getData().getByte(0); @@ -995,7 +995,7 @@ public ArrayList getRpcList(String namespace,MACAddress addr) BowlerDatagram b = send(new RpcCommand(namespaceIndex),addr,5); if(!b.getRPC().contains("_rpc")){ - System.err.println(b); + com.neuronrobotics.sdk.common.Log.error(b); throw new RuntimeException("This RPC index request has failed"); } //int ns = b.getData().getByte(0);// gets the index of the namespace @@ -1017,7 +1017,7 @@ public ArrayList getRpcList(String namespace,MACAddress addr) for (int i=0;i getRpcList(String namespace,MACAddress addr) BowlerDatagramFactory.freePacket(b); b = send(new RpcArgumentsCommand(namespaceIndex,i),addr,5); if(!b.getRPC().contains("args")){ - System.err.println(b); + com.neuronrobotics.sdk.common.Log.error(b); throw new RuntimeException("This RPC section failed"); } byte []data = b.getData().getBytes(2); @@ -1096,7 +1096,7 @@ public BowlerDatagram send(BowlerAbstractCommand command,MACAddress addr, int re BowlerDatagram ret; try{ ret = send( command,addr,switchParser); - //System.out.println(ret); + //com.neuronrobotics.sdk.common.Log.error(ret); if(ret != null){ addr.setValues(ret.getAddress()); //if(!ret.getRPC().contains("_err")) @@ -1249,7 +1249,7 @@ public void stopHeartBeat(){ */ private void runHeartBeat(){ if((msSinceLastSend())>heartBeatTime){ - //System.out.println("Heartbeat"); + //com.neuronrobotics.sdk.common.Log.error("Heartbeat"); try{ if(!ping(new MACAddress())){ Log.debug("Ping failed, disconnecting"); @@ -1549,7 +1549,7 @@ public void write(byte[] data) throws IOException { while(outgoing.size()>0){ byte[] b =outgoing.popList(getChunkSize()); - //System.out.println("Writing "+new ByteList(data)); + //com.neuronrobotics.sdk.common.Log.error("Writing "+new ByteList(data)); getDataOuts().write( b ); getDataOuts().flush(); } diff --git a/src/main/java/com/neuronrobotics/sdk/common/BowlerAbstractDevice.java b/src/main/java/com/neuronrobotics/sdk/common/BowlerAbstractDevice.java index 5847bf33..51b2131f 100644 --- a/src/main/java/com/neuronrobotics/sdk/common/BowlerAbstractDevice.java +++ b/src/main/java/com/neuronrobotics/sdk/common/BowlerAbstractDevice.java @@ -110,7 +110,7 @@ public void addConnectionEventListener(final IDeviceConnectionEventListener l ) if(!getDisconnectListeners().contains(l)) { getDisconnectListeners().add(l); } -// System.err.println(getScriptingName()+" Adding listener "+l.getClass()); +// com.neuronrobotics.sdk.common.Log.error(getScriptingName()+" Adding listener "+l.getClass()); // l.trace.printStackTrace(); // new Exception().printStackTrace(); BowlerAbstractDevice bad = this; @@ -239,7 +239,7 @@ public void setAddress(MACAddress address) { * @return the device's address */ public MACAddress getAddress() { - //System.out.println(); + //com.neuronrobotics.sdk.common.Log.error(); return address; } @@ -427,7 +427,7 @@ public void loadRpcList() { ArrayList names = getNamespaces(); for (String s:names){ - System.out.println(getRpcList(s)); + com.neuronrobotics.sdk.common.Log.error(getRpcList(s)); } } diff --git a/src/main/java/com/neuronrobotics/sdk/common/BowlerDatagram.java b/src/main/java/com/neuronrobotics/sdk/common/BowlerDatagram.java index eddc8927..93cfc971 100644 --- a/src/main/java/com/neuronrobotics/sdk/common/BowlerDatagram.java +++ b/src/main/java/com/neuronrobotics/sdk/common/BowlerDatagram.java @@ -244,7 +244,7 @@ public void parse(ByteList raw) { setMethod(BowlerMethod.get(raw.getByte(7))); if(getMethod() == null){ setMethod(BowlerMethod.STATUS); - System.err.println("Method was invalid!! Value="+raw.getUnsigned(7)); + com.neuronrobotics.sdk.common.Log.error("Method was invalid!! Value="+raw.getUnsigned(7)); Log.error("Method was invalid!! Value="+raw.getUnsigned(7)); } diff --git a/src/main/java/com/neuronrobotics/sdk/common/DeviceManager.java b/src/main/java/com/neuronrobotics/sdk/common/DeviceManager.java index 06a1dab1..0f7d639c 100644 --- a/src/main/java/com/neuronrobotics/sdk/common/DeviceManager.java +++ b/src/main/java/com/neuronrobotics/sdk/common/DeviceManager.java @@ -58,7 +58,7 @@ public static void addConnection(final Object newDevice, String name) { */ private static void addConnectionBAD(final BowlerAbstractDevice newDevice, String name) { if (DeviceManager.getSpecificDevice(name) == newDevice) { - System.out.println("Device " + name + " is already in the manager"); + com.neuronrobotics.sdk.common.Log.error("Device " + name + " is already in the manager"); return; } if ( DMDevice.class.isInstance(newDevice)) { @@ -68,7 +68,7 @@ private static void addConnectionBAD(final BowlerAbstractDevice newDevice, Strin if(DMDevice.class.isInstance(sDev)) { DMDevice inside = (DMDevice) sDev; if (inside.getWrapped() == incoming.getWrapped()) { - System.out.println("Wrapped Device " + name + " is already in the manager"); + com.neuronrobotics.sdk.common.Log.error("Wrapped Device " + name + " is already in the manager"); return; } } diff --git a/src/main/java/com/neuronrobotics/sdk/common/Log.java b/src/main/java/com/neuronrobotics/sdk/common/Log.java index 51f3cc9b..5276cd0a 100644 --- a/src/main/java/com/neuronrobotics/sdk/common/Log.java +++ b/src/main/java/com/neuronrobotics/sdk/common/Log.java @@ -89,8 +89,8 @@ private Log() { * * @param message the message to log as an error */ - public static void error(String message) { - instance().add(message, ERROR); + public static void error(Object message) { + instance().add(message.toString(), ERROR); } /** @@ -165,7 +165,7 @@ private void add(String message, int importance) { if(debugprint&& systemprint) { outStream.println("# " + message); if(outStream != System.out) - System.out.println(m); + System.err.println(m); } diff --git a/src/main/java/com/neuronrobotics/sdk/common/MACAddress.java b/src/main/java/com/neuronrobotics/sdk/common/MACAddress.java index 949553bf..93a50430 100644 --- a/src/main/java/com/neuronrobotics/sdk/common/MACAddress.java +++ b/src/main/java/com/neuronrobotics/sdk/common/MACAddress.java @@ -162,7 +162,7 @@ public void increment(){ * @param address2 the new values */ public void setValues(MACAddress address2) { - //System.out.println("Setting new values: "+address2); + //com.neuronrobotics.sdk.common.Log.error("Setting new values: "+address2); for(int i=0; i<6; i++) { address[i] = address2.address[i]; } diff --git a/src/main/java/com/neuronrobotics/sdk/common/TickToc.java b/src/main/java/com/neuronrobotics/sdk/common/TickToc.java index 9ce2198d..cef0e325 100644 --- a/src/main/java/com/neuronrobotics/sdk/common/TickToc.java +++ b/src/main/java/com/neuronrobotics/sdk/common/TickToc.java @@ -23,7 +23,7 @@ public void print(Pair start,Pair previous) { m=m+" from last event "+df.format(diffms/1000.0)+" seconds "; } m=m+" "+message; - System.out.println(m); + com.neuronrobotics.sdk.common.Log.error(m); } } @@ -45,7 +45,7 @@ public static void toc() { events.add(new Pair(System.currentTimeMillis(), "Toc end event")); Pair start = events.remove(0); Pair previous=null; - System.out.println("\n\n"); + com.neuronrobotics.sdk.common.Log.error("\n\n"); for (int i = 0; i < events.size(); i++) { Pair p = events.get(i); p.print(start,previous); @@ -65,7 +65,7 @@ public static void setEnabled(boolean enabled) { if(!enabled) clear(); else { - System.out.println("Start TickToc"); + com.neuronrobotics.sdk.common.Log.error("Start TickToc"); tic("Tick Tock start"); } } diff --git a/src/main/java/com/neuronrobotics/sdk/common/device/server/BowlerAbstractServer.java b/src/main/java/com/neuronrobotics/sdk/common/device/server/BowlerAbstractServer.java index 4e54abab..955ce06d 100644 --- a/src/main/java/com/neuronrobotics/sdk/common/device/server/BowlerAbstractServer.java +++ b/src/main/java/com/neuronrobotics/sdk/common/device/server/BowlerAbstractServer.java @@ -129,7 +129,7 @@ private BowlerDatagram processLocal(BowlerDatagram data) { throw new RuntimeException("No namespaces defined"); } for (BowlerAbstractDeviceServerNamespace n : getNamespaces()) { - // System.out.println("Checking "+n.getNamespaces().get(0)); + // com.neuronrobotics.sdk.common.Log.error("Checking "+n.getNamespaces().get(0)); if (n.checkRpc(data)) { BowlerDatagram d = n.process(data); if (d != null) { @@ -329,7 +329,7 @@ public synchronized void pushAsyncPacket(BowlerDatagram data) { run = true; } if (localServers.get(i).getClass() != BowlerUDPServer.class) { - // System.out.println("Sending packet to "+getServers().get(i).getClass()); + // com.neuronrobotics.sdk.common.Log.error("Sending packet to "+getServers().get(i).getClass()); if (run && localServers.get(i).isConnected()) { // Log.warning("ASYNC<<\r\n"+data ); String classString = localServers.get(i).getClass() diff --git a/src/main/java/com/neuronrobotics/sdk/config/SDKBuildInfo.java b/src/main/java/com/neuronrobotics/sdk/config/SDKBuildInfo.java index 8c36eaab..b9bb914d 100644 --- a/src/main/java/com/neuronrobotics/sdk/config/SDKBuildInfo.java +++ b/src/main/java/com/neuronrobotics/sdk/config/SDKBuildInfo.java @@ -117,7 +117,7 @@ public static String getBuildDate() { } } catch (IOException e) { } - // System.out.println("Manifest:\n"+s); + // com.neuronrobotics.sdk.common.Log.error("Manifest:\n"+s); return ""; } diff --git a/src/main/java/com/neuronrobotics/sdk/dyio/DyIO.java b/src/main/java/com/neuronrobotics/sdk/dyio/DyIO.java index dd2cf441..b9213685 100644 --- a/src/main/java/com/neuronrobotics/sdk/dyio/DyIO.java +++ b/src/main/java/com/neuronrobotics/sdk/dyio/DyIO.java @@ -311,7 +311,7 @@ public String getFirmwareRevString(){ public ArrayList getChannels() { ArrayList c = new ArrayList(); for(DyIOChannel chan:getInternalChannels() ) { - //System.out.println(this.getClass()+" Adding channel: "+chan.getChannelNumber()+" as mode: "+chan.getMode()); + //com.neuronrobotics.sdk.common.Log.error(this.getClass()+" Adding channel: "+chan.getChannelNumber()+" as mode: "+chan.getMode()); c.add(chan); } return c; @@ -501,7 +501,7 @@ public boolean resync() { Log.info("\n\nUpdating channel: "+i); getInternalChannels().get(i).update(this, i, cm, editable); }catch(IndexOutOfBoundsException e){ - //System.out.println("New channel "+i); + //com.neuronrobotics.sdk.common.Log.error("New channel "+i); getInternalChannels().add(new DyIOChannel(this, i, cm, editable)); DyIOChannel dc =getInternalChannels().get(i); dc.fireModeChangeEvent(dc.getCurrentMode()); @@ -576,7 +576,7 @@ public void removeAllDyIOEventListeners() { * - the event to fire to all listeners */ public void fireDyIOEvent(IDyIOEvent e) { - //System.out.println("DyIO Event: "+e); + //com.neuronrobotics.sdk.common.Log.error("DyIO Event: "+e); for(IDyIOEventListener l : listeners) { l.onDyIOEvent(e); } @@ -646,12 +646,12 @@ public void setCachedMode(boolean mode) { * @param seconds the seconds */ public void flushCache(double seconds) { - //System.out.println("Updating all channels"); + //com.neuronrobotics.sdk.common.Log.error("Updating all channels"); Integer [] values = new Integer[getInternalChannels().size()]; int i=0; for(DyIOChannel d:getInternalChannels()) { values[i++]=d.getCachedValue(); - //System.out.println("Flushing chan "+d+" to "+d.getCachedValue()); + //com.neuronrobotics.sdk.common.Log.error("Flushing chan "+d+" to "+d.getCachedValue()); } if(isLegacyParser()){ for(int j=0;j<5;j++) { @@ -659,7 +659,7 @@ public void flushCache(double seconds) { send(new SetAllChannelValuesCommand(seconds,values)); return; }catch (InvalidResponseException e1) { - System.err.println("Failed to update all, retrying"); + com.neuronrobotics.sdk.common.Log.error("Failed to update all, retrying"); } } }else{ @@ -1096,7 +1096,7 @@ public void startHeartBeat(long msHeartBeatTime){ if(b== null) checkFirmwareRev(); }catch(Exception e){ - System.err.println("DyIO is out of date"); + com.neuronrobotics.sdk.common.Log.error("DyIO is out of date"); checkFirmwareRev(); } } @@ -1124,7 +1124,7 @@ public void stopHeartBeat(){ if(b== null) checkFirmwareRev(); }catch(Exception e){ - System.err.println("DyIO is out of date"); + com.neuronrobotics.sdk.common.Log.error("DyIO is out of date"); checkFirmwareRev(); } } diff --git a/src/main/java/com/neuronrobotics/sdk/dyio/DyIOChannel.java b/src/main/java/com/neuronrobotics/sdk/dyio/DyIOChannel.java index d3a193f8..374f5805 100644 --- a/src/main/java/com/neuronrobotics/sdk/dyio/DyIOChannel.java +++ b/src/main/java/com/neuronrobotics/sdk/dyio/DyIOChannel.java @@ -262,7 +262,7 @@ public void resync(boolean all) { return; } BowlerDatagram bd = getDevice().send(new GetChannelModeCommand(number)); - //System.out.println(bd); + //com.neuronrobotics.sdk.common.Log.error(bd); fireModeChangeEvent(DyIOChannelMode.get(bd.getData().getByte(1))); throw new RuntimeException(); } @@ -526,11 +526,11 @@ public boolean setMode(DyIOChannelMode mode, boolean async) { "schm", new Object[]{getChannelNumber(),mode.getValue(),async?1:0}); ByteList currentModes = (ByteList) args[0]; - //System.out.println("Setting # "+getChannelNumber()+" to "+mode); + //com.neuronrobotics.sdk.common.Log.error("Setting # "+getChannelNumber()+" to "+mode); for (int j=0;j0){ ByteList b; if(bl.size()>20){ @@ -60,7 +60,7 @@ public void write(ByteList bl) throws IOException { }else{ b = new ByteList(bl.popList(bl.size())); } - //System.out.println("Sending ByteList: "+b.asString()); + //com.neuronrobotics.sdk.common.Log.error("Sending ByteList: "+b.asString()); chan.setValue(b); } } diff --git a/src/main/java/com/neuronrobotics/sdk/dyio/peripherals/PPMReaderChannel.java b/src/main/java/com/neuronrobotics/sdk/dyio/peripherals/PPMReaderChannel.java index e572c773..20a70eb6 100644 --- a/src/main/java/com/neuronrobotics/sdk/dyio/peripherals/PPMReaderChannel.java +++ b/src/main/java/com/neuronrobotics/sdk/dyio/peripherals/PPMReaderChannel.java @@ -133,7 +133,7 @@ public void setCrossLink(int [] links){ private void updateValues() { if(getChannel().getDevice().isLegacyParser()){ BowlerDatagram b=null; - //System.out.println("Updating value map"); + //com.neuronrobotics.sdk.common.Log.error("Updating value map"); try { b= getChannel().getDevice().send(new GetValueCommand(23)); }catch (Exception e) { diff --git a/src/main/java/com/neuronrobotics/sdk/javaxusb/UsbCDCSerialConnection.java b/src/main/java/com/neuronrobotics/sdk/javaxusb/UsbCDCSerialConnection.java index 57555527..5d646790 100644 --- a/src/main/java/com/neuronrobotics/sdk/javaxusb/UsbCDCSerialConnection.java +++ b/src/main/java/com/neuronrobotics/sdk/javaxusb/UsbCDCSerialConnection.java @@ -321,14 +321,14 @@ private static void dumpDevice(final UsbDevice device, // robotics // devices // Dump information about the device itself - // System.out.println("Device: "+device.getProductString()); + // com.neuronrobotics.sdk.common.Log.error("Device: "+device.getProductString()); addrs.add(device); // Dump device descriptor - // System.out.println(device.getUsbDeviceDescriptor()); + // com.neuronrobotics.sdk.common.Log.error(device.getUsbDeviceDescriptor()); } - // System.out.println(); + // com.neuronrobotics.sdk.common.Log.error(); // Dump child devices if device is a hub if (device.isUsbHub()) { @@ -434,9 +434,9 @@ public boolean connect() { e.printStackTrace(); } - // System.out.println(mDevice); + // com.neuronrobotics.sdk.common.Log.error(mDevice); // Dump device descriptor - // System.out.println(mDevice.getUsbDeviceDescriptor()); + // com.neuronrobotics.sdk.common.Log.error(mDevice.getUsbDeviceDescriptor()); // Process all configurations for (UsbConfiguration configuration : (List) mDevice @@ -445,7 +445,7 @@ public boolean connect() { for (UsbInterface iface : (List) configuration .getUsbInterfaces()) { // Dump the interface descriptor - // System.out.println(iface.getUsbInterfaceDescriptor()); + // com.neuronrobotics.sdk.common.Log.error(iface.getUsbInterfaceDescriptor()); if (iface.getUsbInterfaceDescriptor().bInterfaceClass() == 2) { // controlInterface = iface; @@ -470,11 +470,11 @@ public boolean connect() { .getUsbEndpoints()) { if (endpoint.getUsbEndpointDescriptor() .bEndpointAddress() == 0x03) { - // System.out.println("Data out Endpipe"); + // com.neuronrobotics.sdk.common.Log.error("Data out Endpipe"); dataOutEndpoint = endpoint; } else { - // System.out.println("Data in Endpipe"); + // com.neuronrobotics.sdk.common.Log.error("Data in Endpipe"); dataInEndpoint = endpoint; } } @@ -590,7 +590,7 @@ private void kernelDetatch(UsbDevice mDevice){ if (r != LibUsb.SUCCESS && r != LibUsb.ERROR_NOT_SUPPORTED && r != LibUsb.ERROR_NOT_FOUND) throw new LibUsbException("Unable to detach kernel driver", r); - // System.out.println("Kernel detatched for device "+mDevice); + // com.neuronrobotics.sdk.common.Log.error("Kernel detatched for device "+mDevice); //} } diff --git a/src/main/java/com/neuronrobotics/sdk/network/UDPBowlerConnection.java b/src/main/java/com/neuronrobotics/sdk/network/UDPBowlerConnection.java index 78e4a1af..f8597068 100644 --- a/src/main/java/com/neuronrobotics/sdk/network/UDPBowlerConnection.java +++ b/src/main/java/com/neuronrobotics/sdk/network/UDPBowlerConnection.java @@ -161,7 +161,7 @@ public BowlerDatagram loadPacketFromPhy(ByteList bytesToPacketBuffer) throws Nul long start = System.currentTimeMillis(); //Log.info("Waiting for UDP packet"); udpSock.setSoTimeout(1);// Timeout the socket after 1 ms - //System.err.println("Timeout set "+(System.currentTimeMillis()-start)); + //com.neuronrobotics.sdk.common.Log.error("Timeout set "+(System.currentTimeMillis()-start)); start = System.currentTimeMillis(); try{ udpSock.receive(receivePacket); @@ -174,7 +174,7 @@ public BowlerDatagram loadPacketFromPhy(ByteList bytesToPacketBuffer) throws Nul ex.printStackTrace(); return null; } - //System.err.println("Recv "+(System.currentTimeMillis()-start)); + //com.neuronrobotics.sdk.common.Log.error("Recv "+(System.currentTimeMillis()-start)); start = System.currentTimeMillis(); Log.info("Got UDP packet"); if(addrs== null) @@ -186,10 +186,10 @@ public BowlerDatagram loadPacketFromPhy(ByteList bytesToPacketBuffer) throws Nul for (int i=0;i -0.1) { - // System.out.println("Setting virtual velocity="+unitsPerSecond); + // com.neuronrobotics.sdk.common.Log.error("Setting virtual velocity="+unitsPerSecond); getDriveThread(group).SetVelocity(unitsPerSecond); } else { SetPIDInterpolatedVelocity(group, unitsPerSecond, seconds); @@ -266,7 +266,7 @@ private InterpolationEngine getDriveThread(int i) { } } for (PIDConfiguration c : interpolationEngines.keySet()) { - System.err.println(c); + com.neuronrobotics.sdk.common.Log.error(c.toString()); } throw new RuntimeException("Device is missing, id " + i); @@ -392,7 +392,7 @@ public void run() { toUpdate[updateIndex++]=key; } } else { - //System.err.println("Virtual Device " + key.getGroup() + " is disabled"); + //com.neuronrobotics.sdk.common.Log.error("Virtual Device " + key.getGroup() + " is disabled"); } } } diff --git a/src/main/java/com/neuronrobotics/sdk/serial/SerialConnection.java b/src/main/java/com/neuronrobotics/sdk/serial/SerialConnection.java index d2a5a043..3b93d64a 100644 --- a/src/main/java/com/neuronrobotics/sdk/serial/SerialConnection.java +++ b/src/main/java/com/neuronrobotics/sdk/serial/SerialConnection.java @@ -219,27 +219,27 @@ public static SerialConnection getConnectionByMacAddress(MACAddress mac){ List ports = SerialConnection.getAvailableSerialPorts(); //Start by searching through all available serial connections for DyIOs connected to the system for(String s: ports){ - System.out.println("Searching "+s); + com.neuronrobotics.sdk.common.Log.error("Searching "+s); } for(String s: ports){ try{ SerialConnection connection = new SerialConnection(s); GenericDevice d = new GenericDevice(connection); d.connect(); - System.out.println("Pinging port: "+connection+" "); + com.neuronrobotics.sdk.common.Log.error("Pinging port: "+connection+" "); if(d.ping()){ String addr = d.getAddress().toString(); if(addr.equalsIgnoreCase(mac.toString())){ connection.disconnect(); - System.out.println("Device FOUND on port: "+connection+" "+addr); + com.neuronrobotics.sdk.common.Log.error("Device FOUND on port: "+connection+" "+addr); return connection; } - System.err.println("Device not on port: "+connection+" "+addr); + com.neuronrobotics.sdk.common.Log.error("Device not on port: "+connection+" "+addr); } connection.disconnect(); }catch(Exception EX){ EX.printStackTrace(); - System.err.println("Serial port "+s+" is not a DyIO"); + com.neuronrobotics.sdk.common.Log.error("Serial port "+s+" is not a DyIO"); } } diff --git a/src/main/java/com/neuronrobotics/sdk/ui/TCPConnectionPanel.java b/src/main/java/com/neuronrobotics/sdk/ui/TCPConnectionPanel.java index 65d66d6e..93e1a252 100644 --- a/src/main/java/com/neuronrobotics/sdk/ui/TCPConnectionPanel.java +++ b/src/main/java/com/neuronrobotics/sdk/ui/TCPConnectionPanel.java @@ -75,7 +75,7 @@ public TCPConnectionPanel(ConnectionDialog connectionDialog) { // try { // s = new Socket("google.com", 80); // connectionCbo.addItem(s.getLocalAddress().getHostAddress()); -// //System.out.println(s.getLocalAddress().getHostAddress()); +// //com.neuronrobotics.sdk.common.Log.error(s.getLocalAddress().getHostAddress()); // s.close(); // } catch (UnknownHostException e) { // // TODO Auto-generated catch block diff --git a/src/main/java/com/neuronrobotics/sdk/ui/UDPConnectionPanel.java b/src/main/java/com/neuronrobotics/sdk/ui/UDPConnectionPanel.java index b23a7b06..dd933df4 100644 --- a/src/main/java/com/neuronrobotics/sdk/ui/UDPConnectionPanel.java +++ b/src/main/java/com/neuronrobotics/sdk/ui/UDPConnectionPanel.java @@ -169,7 +169,7 @@ private class NetworkSearchProcess extends Thread implements IMonitorable { public void run() { setName("Bowler Platform UDP searcher"); isRunning = true; - //System.out.println("Searching for UDP devices, please wait..."); + //com.neuronrobotics.sdk.common.Log.error("Searching for UDP devices, please wait..."); int prt; try { prt=new Integer(port.getText()); @@ -180,7 +180,7 @@ public void run() { clnt=new UDPBowlerConnection(prt); ArrayList addrs = clnt.getAllAddresses(); // if (addrs.size()>0) -// System.out.println("Bowler servers: "+addrs); +// com.neuronrobotics.sdk.common.Log.error("Bowler servers: "+addrs); connectionCbo.removeAllItems(); for (InetAddress i:addrs) { connectionCbo.addItem(i.getHostAddress()); diff --git a/src/main/java/com/neuronrobotics/sdk/ui/UsbConnectionPanel.java b/src/main/java/com/neuronrobotics/sdk/ui/UsbConnectionPanel.java index a8fe9ed5..f14e2bb1 100644 --- a/src/main/java/com/neuronrobotics/sdk/ui/UsbConnectionPanel.java +++ b/src/main/java/com/neuronrobotics/sdk/ui/UsbConnectionPanel.java @@ -121,7 +121,7 @@ public BowlerAbstractConnection getConnection() { * @see com.neuronrobotics.sdk.ui.AbstractConnectionPanel#refresh() */ public void refresh() { - //System.err.println("Refreshing USB"); + //com.neuronrobotics.sdk.common.Log.error("Refreshing USB"); connectionCbo.removeAllItems(); List prts=null; diff --git a/src/main/java/com/neuronrobotics/sdk/util/OsInfoUtil.java b/src/main/java/com/neuronrobotics/sdk/util/OsInfoUtil.java index 78d38cba..88c70b6b 100644 --- a/src/main/java/com/neuronrobotics/sdk/util/OsInfoUtil.java +++ b/src/main/java/com/neuronrobotics/sdk/util/OsInfoUtil.java @@ -12,7 +12,7 @@ public class OsInfoUtil { * @return true, if is 64 bit */ public static boolean is64Bit() { - // //System.out.println("Arch: "+getOsArch()); + // //com.neuronrobotics.sdk.common.Log.error("Arch: "+getOsArch()); return getOsArch().startsWith("x86_64") || getOsArch().startsWith("amd64"); } @@ -54,7 +54,7 @@ public static boolean isCortexA8() { * @return true, if is windows */ public static boolean isWindows() { - // //System.out.println("OS name: "+getOsName()); + // //com.neuronrobotics.sdk.common.Log.error("OS name: "+getOsName()); return getOsName().toLowerCase().startsWith("windows") || getOsName().toLowerCase().startsWith("microsoft") || getOsName().toLowerCase().startsWith("ms"); diff --git a/src/main/java/com/neuronrobotics/sdk/wireless/bluetooth/BlueCoveManager.java b/src/main/java/com/neuronrobotics/sdk/wireless/bluetooth/BlueCoveManager.java index f34921de..8601b716 100644 --- a/src/main/java/com/neuronrobotics/sdk/wireless/bluetooth/BlueCoveManager.java +++ b/src/main/java/com/neuronrobotics/sdk/wireless/bluetooth/BlueCoveManager.java @@ -174,19 +174,19 @@ public synchronized void serviceSearchCompleted(int transID, int respCode) { */ public synchronized RemoteDevice getDevice(String name){ String addr = name.substring(name.indexOf('_')+1); - //System.out.println("Getting device with address: "+addr); + //com.neuronrobotics.sdk.common.Log.error("Getting device with address: "+addr); String [] s=getAvailableSerialDevices(false); for (int i=0;i 0) - System.out.println("Gcode line run: " + response); + com.neuronrobotics.sdk.common.Log.error("Gcode line run: " + response); else { fail("No response"); } @@ -140,7 +140,7 @@ public double[] inverseKinematics(TransformNR target, double[] jointSpaceVector, // was // created } - System.out.println("Moving using the kinematics"); + com.neuronrobotics.sdk.common.Log.error("Moving using the kinematics"); try { arm.setDesiredTaskSpaceTransform(new TransformNR(10, 10, 0, new RotationNR()), 1); arm.setDesiredTaskSpaceTransform(new TransformNR(), 1); @@ -266,19 +266,19 @@ public void G1() { GcodeDevice device = GCODECONTOLLER.cast(DeviceManager.getSpecificDevice(GCODECONTOLLER, GCODE)); String response = device.runLine("G90");// Absolute mode if (response.length() > 0) - System.out.println("Gcode line run: " + response); + com.neuronrobotics.sdk.common.Log.error("Gcode line run: " + response); else { fail("No response"); } response = device.runLine("G1 X100.2 Y100.2 Z0 E10 F6000"); if (response.length() > 0) - System.out.println("Gcode line run: " + response); + com.neuronrobotics.sdk.common.Log.error("Gcode line run: " + response); else { fail("No response"); } response = device.runLine("G1 X0 Y0 Z0 E0 F3000"); if (response.length() > 0) - System.out.println("Gcode line run: " + response); + com.neuronrobotics.sdk.common.Log.error("Gcode line run: " + response); else { fail("No response"); } diff --git a/test/java/src/junit/test/neuronrobotics/utilities/GsonVitaminLoad.java b/test/java/src/junit/test/neuronrobotics/utilities/GsonVitaminLoad.java index 2b280f4f..49bf3d45 100644 --- a/test/java/src/junit/test/neuronrobotics/utilities/GsonVitaminLoad.java +++ b/test/java/src/junit/test/neuronrobotics/utilities/GsonVitaminLoad.java @@ -26,7 +26,7 @@ public void test() { .create(); VitaminLocation src = new VitaminLocation(false,"Tester", "hobbyServo","mg92b",new TransformNR()); String content = gson.toJson(src); - System.out.println(content); + com.neuronrobotics.sdk.common.Log.error(content); } } diff --git a/test/java/src/junit/test/neuronrobotics/utilities/LoadMassTest.java b/test/java/src/junit/test/neuronrobotics/utilities/LoadMassTest.java index c5fdefb0..a57a319c 100644 --- a/test/java/src/junit/test/neuronrobotics/utilities/LoadMassTest.java +++ b/test/java/src/junit/test/neuronrobotics/utilities/LoadMassTest.java @@ -18,7 +18,7 @@ public void test() throws FileNotFoundException { File f = new File("carlRobot.xml"); if (f.exists()) { MobileBase pArm = new MobileBase(new FileInputStream(f)); - System.out.println("Mass = "+pArm.getMassKg()); + com.neuronrobotics.sdk.common.Log.error("Mass = "+pArm.getMassKg()); assertEquals(99, pArm.getMassKg(),0.1); assertEquals(pArm.getLegs().get(0).getScriptingName(),"Carl_One"); } diff --git a/test/java/src/junit/test/neuronrobotics/utilities/PacketValidationTest.java b/test/java/src/junit/test/neuronrobotics/utilities/PacketValidationTest.java index de5ff6f9..bb46ea0e 100644 --- a/test/java/src/junit/test/neuronrobotics/utilities/PacketValidationTest.java +++ b/test/java/src/junit/test/neuronrobotics/utilities/PacketValidationTest.java @@ -24,15 +24,15 @@ public class PacketValidationTest { public void packetTest() { Log.enableInfoPrint(); BowlerDatagram bd = BowlerDatagramFactory.build(new MACAddress(), new PingCommand()); - System.out.println(bd); + com.neuronrobotics.sdk.common.Log.error(bd.toString()); ByteList data = new ByteList(bd.getBytes()); - System.out.println(data); + com.neuronrobotics.sdk.common.Log.error(data.toString()); BowlerDatagram back = BowlerDatagramFactory.build(data); if (back == null) fail(); - System.out.println(back); + com.neuronrobotics.sdk.common.Log.error(back.toString()); } } diff --git a/test/java/src/junit/test/neuronrobotics/utilities/ParallelArmTest.java b/test/java/src/junit/test/neuronrobotics/utilities/ParallelArmTest.java index 4cd7202c..e06096be 100644 --- a/test/java/src/junit/test/neuronrobotics/utilities/ParallelArmTest.java +++ b/test/java/src/junit/test/neuronrobotics/utilities/ParallelArmTest.java @@ -53,7 +53,7 @@ public static void main(String[] args) throws Exception { kin.setDesiredJointSpaceVector(new double[]{0,0,0}, 0); kin.setDesiredTaskSpaceTransform(Tip, 0); - System.out.println("Arm "+kin.getScriptingName()+"setting to : "+Tip); + com.neuronrobotics.sdk.common.Log.error("Arm "+kin.getScriptingName()+"setting to : "+Tip); } assertEquals(Tip.getX(), group.getCurrentTaskSpaceTransform().getX(), 1); group.setDesiredTaskSpaceTransform(Tip.copy(), 0); @@ -61,7 +61,7 @@ public static void main(String[] args) throws Exception { TransformNR TipOffset = group.getTipOffset().get(limb); TransformNR newTip = limb.getCurrentTaskSpaceTransform().times(TipOffset); - System.out.println("Expected tip to be " + Tip.getX() + " and got: " + newTip.getX()); + com.neuronrobotics.sdk.common.Log.error("Expected tip to be " + Tip.getX() + " and got: " + newTip.getX()); assertTrue(!Double.isNaN(Tip.getX())); assertEquals(Tip.getX(), newTip.getX(), 1); } diff --git a/test/java/src/junit/test/neuronrobotics/utilities/RotationNRTest.java b/test/java/src/junit/test/neuronrobotics/utilities/RotationNRTest.java index 7e984f06..8444d2a5 100644 --- a/test/java/src/junit/test/neuronrobotics/utilities/RotationNRTest.java +++ b/test/java/src/junit/test/neuronrobotics/utilities/RotationNRTest.java @@ -52,10 +52,10 @@ public void test() throws FileNotFoundException { for (RotationConvention conv : conventions) { RotationNR.setConvention(conv); - System.out.println("\n\nUsing convention " + conv.toString()); + com.neuronrobotics.sdk.common.Log.error("\n\nUsing convention " + conv.toString()); for (RotationOrder ro : list) { RotationNR.setOrder(ro); - System.out.println("\n\nUsing rotationOrder " + ro.toString()); + com.neuronrobotics.sdk.common.Log.error("\n\nUsing rotationOrder " + ro.toString()); // for (int i = 0; i < iterations; i++) { @@ -65,22 +65,22 @@ public void test() throws FileNotFoundException { try { RotationNR rotTest = new RotationNR(Math.toDegrees(tilt), Math.toDegrees(azumus), Math.toDegrees(elevation)); - System.out.println("\n\nTest #" + i); - System.out.println("Testing Az=" + Math.toDegrees(azumus) + " El=" + Math.toDegrees(elevation) + com.neuronrobotics.sdk.common.Log.error("\n\nTest #" + i); + com.neuronrobotics.sdk.common.Log.error("Testing Az=" + Math.toDegrees(azumus) + " El=" + Math.toDegrees(elevation) + " Tl=" + Math.toDegrees(tilt)); - System.out.println("Got Az=" + Math.toDegrees(rotTest.getRotationAzimuth()) + " El=" + com.neuronrobotics.sdk.common.Log.error("Got Az=" + Math.toDegrees(rotTest.getRotationAzimuth()) + " El=" + Math.toDegrees(rotTest.getRotationElevation()) + " Tl=" + Math.toDegrees(rotTest.getRotationTilt())); if (!RotationNR.bound(tilt - .01, tilt + .01, rotTest.getRotationTilt())) { failCount++; - System.err.println("Rotation Tilt is not consistant. expected " + Math.toDegrees(tilt) + com.neuronrobotics.sdk.common.Log.error("Rotation Tilt is not consistant. expected " + Math.toDegrees(tilt) + " got " + Math.toDegrees(rotTest.getRotationTilt()) + " \t\tOff By " + (Math.toDegrees(tilt) - Math.toDegrees(rotTest.getRotationTilt()))); } if (!RotationNR.bound(elevation - .01, elevation + .01, rotTest.getRotationElevation())) { failCount++; - System.err.println("Rotation Elevation is not consistant. expected " + com.neuronrobotics.sdk.common.Log.error("Rotation Elevation is not consistant. expected " + Math.toDegrees(elevation) + " got " + Math.toDegrees(rotTest.getRotationElevation()) + " \t\tOff By " + (Math.toDegrees(elevation) + Math.toDegrees(rotTest.getRotationElevation())) @@ -89,14 +89,14 @@ public void test() throws FileNotFoundException { } if (!RotationNR.bound(azumus - .01, azumus + .01, rotTest.getRotationAzimuth())) { failCount++; - System.err.println("Rotation azumus is not consistant. expected " + Math.toDegrees(azumus) + com.neuronrobotics.sdk.common.Log.error("Rotation azumus is not consistant. expected " + Math.toDegrees(azumus) + " got " + Math.toDegrees(rotTest.getRotationAzimuth()) + " \t\tOff By " + (Math.toDegrees(azumus) - Math.toDegrees(rotTest.getRotationAzimuth()))); } ThreadUtil.wait(20); } catch (NumberFormatException ex) { if (elevation >= Math.PI / 2 || elevation <= -Math.PI / 2) { - System.out.println("Invalid numbers rejected ok"); + com.neuronrobotics.sdk.common.Log.error("Invalid numbers rejected ok"); } } @@ -104,7 +104,7 @@ public void test() throws FileNotFoundException { // frame(); // frame2(); - System.out.println("Frame test passed with " + ro); + com.neuronrobotics.sdk.common.Log.error("Frame test passed with " + ro); // return; } } @@ -126,10 +126,10 @@ public void compareAzemuth() throws FileNotFoundException { Log.enableDebugPrint(); for (RotationConvention conv : conventions) { RotationNR.setConvention(conv); - System.out.println("\n\nUsing convention " + conv.toString()); + com.neuronrobotics.sdk.common.Log.error("\n\nUsing convention " + conv.toString()); for (RotationOrder ro : list) { RotationNR.setOrder(ro); - System.out.println("\n\nUsing rotationOrder " + ro.toString()); + com.neuronrobotics.sdk.common.Log.error("\n\nUsing rotationOrder " + ro.toString()); failCount = 0; for (int i = 0; i < iterations; i++) { @@ -154,7 +154,7 @@ public void compareAzemuth() throws FileNotFoundException { RotationNR newRot = new RotationNR(rotation); RotationNRLegacy oldRot = new RotationNRLegacy(rotation); double[][] rotationMatrix = newRot.getRotationMatrix(); - System.out.println("Testing pure azumeth \nrotation " + rotationAngleDegrees + "\n as radian " + com.neuronrobotics.sdk.common.Log.error("Testing pure azumeth \nrotation " + rotationAngleDegrees + "\n as radian " + Math.toRadians(rotationAngleDegrees) + "\n Az " + oldRot.getRotationAzimuth() + "\n El " + oldRot.getRotationElevation() + "\n Tl " + oldRot.getRotationTilt() + "\n New Az " + newRot.getRotationAzimuth() + "\n New El " + newRot.getRotationElevation() @@ -163,7 +163,7 @@ public void compareAzemuth() throws FileNotFoundException { assertArrayEquals(rotation[1], rotationMatrix[1], 0.001); assertArrayEquals(rotation[2], rotationMatrix[2], 0.001); - System.out.println( + com.neuronrobotics.sdk.common.Log.error( "Testing Quaturnion \nrotation " + "\n qw " + oldRot.getRotationMatrix2QuaturnionW() + "\n qx " + oldRot.getRotationMatrix2QuaturnionX() + "\n qy " + oldRot.getRotationMatrix2QuaturnionY() + "\n qz " @@ -197,7 +197,7 @@ public void compareAzemuth() throws FileNotFoundException { oldRot.getRotationAzimuth(), oldRot.getRotationElevation(), oldRot.getRotationTilt() }, 0.001); } else { - System.err.println("Legacy angle would fail here " + rotationAngleDegrees); + com.neuronrobotics.sdk.common.Log.error("Legacy angle would fail here " + rotationAngleDegrees); } // Check the new rotation against the known value assertArrayEquals(new double[] { Math.toRadians(rotationAngleDegrees), 0, 0 }, new double[] { @@ -206,7 +206,7 @@ public void compareAzemuth() throws FileNotFoundException { } // frame(); // frame2(); - System.out.println("Frame test passed with " + ro); + com.neuronrobotics.sdk.common.Log.error("Frame test passed with " + ro); // return; } } @@ -223,10 +223,10 @@ public void compareElevation() throws FileNotFoundException { int iterations = 100; for (RotationConvention conv : conventions) { RotationNR.setConvention(conv); - System.out.println("\n\nUsing convention " + conv.toString()); + com.neuronrobotics.sdk.common.Log.error("\n\nUsing convention " + conv.toString()); for (RotationOrder ro : list) { RotationNR.setOrder(ro); - System.out.println("\n\nUsing rotationOrder " + ro.toString()); + com.neuronrobotics.sdk.common.Log.error("\n\nUsing rotationOrder " + ro.toString()); failCount = 0; for (int i = 0; i < iterations; i++) { @@ -251,7 +251,7 @@ public void compareElevation() throws FileNotFoundException { RotationNR newRot = new RotationNR(rotation); RotationNRLegacy oldRot = new RotationNRLegacy(rotation); double[][] rotationMatrix = newRot.getRotationMatrix(); - System.out.println("Testing pure elevation \nrotation " + rotationAngleDegrees + "\n as radian " + com.neuronrobotics.sdk.common.Log.error("Testing pure elevation \nrotation " + rotationAngleDegrees + "\n as radian " + Math.toRadians(rotationAngleDegrees) + "\n Az " + oldRot.getRotationAzimuth() + "\n El " + oldRot.getRotationElevation() + "\n Tl " + oldRot.getRotationTilt() + "\n New Az " + newRot.getRotationAzimuth() + "\n New El " + newRot.getRotationElevation() @@ -260,7 +260,7 @@ public void compareElevation() throws FileNotFoundException { assertArrayEquals(rotation[1], rotationMatrix[1], 0.001); assertArrayEquals(rotation[2], rotationMatrix[2], 0.001); - System.out.println( + com.neuronrobotics.sdk.common.Log.error( "Testing Quaturnion \nrotation " + "\n qw " + oldRot.getRotationMatrix2QuaturnionW() + "\n qx " + oldRot.getRotationMatrix2QuaturnionX() + "\n qy " + oldRot.getRotationMatrix2QuaturnionY() + "\n qz " @@ -300,7 +300,7 @@ public void compareElevation() throws FileNotFoundException { } // frame(); // frame2(); - System.out.println("Frame test passed with " + ro); + com.neuronrobotics.sdk.common.Log.error("Frame test passed with " + ro); // return; } } @@ -317,10 +317,10 @@ public void compareTilt() throws FileNotFoundException { int iterations = 100; for (RotationConvention conv : conventions) { RotationNR.setConvention(conv); - System.out.println("\n\nUsing convention " + conv.toString()); + com.neuronrobotics.sdk.common.Log.error("\n\nUsing convention " + conv.toString()); for (RotationOrder ro : list) { RotationNR.setOrder(ro); - System.out.println("\n\nUsing rotationOrder " + ro.toString()); + com.neuronrobotics.sdk.common.Log.error("\n\nUsing rotationOrder " + ro.toString()); failCount = 0; for (int i = 0; i < iterations; i++) { @@ -345,7 +345,7 @@ public void compareTilt() throws FileNotFoundException { RotationNR newRot = new RotationNR(rotation); RotationNRLegacy oldRot = new RotationNRLegacy(rotation); double[][] rotationMatrix = newRot.getRotationMatrix(); - System.out.println("Testing pure tilt \nrotation " + rotationAngleDegrees + "\n as radian " + com.neuronrobotics.sdk.common.Log.error("Testing pure tilt \nrotation " + rotationAngleDegrees + "\n as radian " + Math.toRadians(rotationAngleDegrees) + "\n Az " + oldRot.getRotationAzimuth() + "\n El " + oldRot.getRotationElevation() + "\n Tl " + oldRot.getRotationTilt() + "\n New Az " + newRot.getRotationAzimuth() + "\n New El " + newRot.getRotationElevation() @@ -354,7 +354,7 @@ public void compareTilt() throws FileNotFoundException { assertArrayEquals(rotation[1], rotationMatrix[1], 0.001); assertArrayEquals(rotation[2], rotationMatrix[2], 0.001); - System.out.println( + com.neuronrobotics.sdk.common.Log.error( "Testing Quaturnion \nrotation " + "\n qw " + oldRot.getRotationMatrix2QuaturnionW() + "\n qx " + oldRot.getRotationMatrix2QuaturnionX() + "\n qy " + oldRot.getRotationMatrix2QuaturnionY() + "\n qz " @@ -391,7 +391,7 @@ public void compareTilt() throws FileNotFoundException { } // frame(); // frame2(); - System.out.println("Frame test passed with " + ro); + com.neuronrobotics.sdk.common.Log.error("Frame test passed with " + ro); // return; } } diff --git a/test/java/src/junit/test/neuronrobotics/utilities/TestMobilBaseLoading.java b/test/java/src/junit/test/neuronrobotics/utilities/TestMobilBaseLoading.java index 9b42f51b..f553e5f4 100644 --- a/test/java/src/junit/test/neuronrobotics/utilities/TestMobilBaseLoading.java +++ b/test/java/src/junit/test/neuronrobotics/utilities/TestMobilBaseLoading.java @@ -37,7 +37,7 @@ public void test() throws IOException { if(!content.contentEquals(read)) { File out = new File("src/main/resources/com/neuronrobotics/sdk/addons/kinematics/xml/NASASuspensionTestOUTPUT.xml"); Files.write( Paths.get(out.getAbsolutePath()), read.getBytes()); - System.out.println("diff "+file.getAbsolutePath()+" "+out.getAbsolutePath()); + com.neuronrobotics.sdk.common.Log.error("diff "+file.getAbsolutePath()+" "+out.getAbsolutePath()); fail("What was loaded failed to match the source"); } } diff --git a/test/java/src/junit/test/neuronrobotics/utilities/TestTimer.java b/test/java/src/junit/test/neuronrobotics/utilities/TestTimer.java index d557a005..a654bcc1 100644 --- a/test/java/src/junit/test/neuronrobotics/utilities/TestTimer.java +++ b/test/java/src/junit/test/neuronrobotics/utilities/TestTimer.java @@ -37,7 +37,7 @@ public void test() { t.initialize(500+(i++), new IthreadedTimoutListener() { @Override public void onTimeout(String message) { - System.out.println(message); + com.neuronrobotics.sdk.common.Log.error(message); timerTimedOut++; } });