From 2c8cd0b07bff097a49e036fc94e81216fb04cc67 Mon Sep 17 00:00:00 2001 From: Adam M Rivera Date: Mon, 16 Apr 2012 10:26:14 -0500 Subject: [PATCH 01/19] AP_AHRS_HIL.h: Fixed HIL build by adding missing public property. --- libraries/AP_AHRS/AP_AHRS_HIL.h | 3 +++ 1 file changed, 3 insertions(+) diff --git a/libraries/AP_AHRS/AP_AHRS_HIL.h b/libraries/AP_AHRS/AP_AHRS_HIL.h index ea46cbe92a..20d903ffa6 100644 --- a/libraries/AP_AHRS/AP_AHRS_HIL.h +++ b/libraries/AP_AHRS/AP_AHRS_HIL.h @@ -32,6 +32,9 @@ public: float get_error_rp(void) { return 0; } float get_error_yaw(void) { return 0; } + // settable parameters + AP_Float _kp_yaw; + private: Vector3f _omega; }; From 5652acc12f6138ded021eaa47ce6d72b5a95c198 Mon Sep 17 00:00:00 2001 From: Michael Oborne Date: Tue, 17 Apr 2012 07:43:53 +0800 Subject: [PATCH 02/19] APM Planner 1.1.68 add turn radius - status add new pink line to Arduplane - turn radius --- Tools/ArdupilotMegaPlanner/Common.cs | 35 +++++ Tools/ArdupilotMegaPlanner/CurrentState.cs | 2 + .../GCSViews/FlightData.Designer.cs | 22 +++ .../GCSViews/FlightData.resx | 132 +++++++++++++----- Tools/ArdupilotMegaPlanner/Msi/wix.pdb | Bin 19968 -> 19968 bytes .../Properties/AssemblyInfo.cs | 2 +- .../bin/Release/ArdupilotMegaPlanner.pdb | Bin 1172992 -> 1175040 bytes .../bin/Release/version.txt | 2 +- 8 files changed, 160 insertions(+), 35 deletions(-) diff --git a/Tools/ArdupilotMegaPlanner/Common.cs b/Tools/ArdupilotMegaPlanner/Common.cs index 4a596aeca5..3768265e06 100644 --- a/Tools/ArdupilotMegaPlanner/Common.cs +++ b/Tools/ArdupilotMegaPlanner/Common.cs @@ -131,6 +131,41 @@ namespace ArdupilotMega g.DrawLine(new Pen(Color.Black, 2), 0.0f, 0.0f, (float)Math.Cos((cog - 90) * deg2rad) * length, (float)Math.Sin((cog - 90) * deg2rad) * length); g.DrawLine(new Pen(Color.Orange, 2), 0.0f, 0.0f, (float)Math.Cos((target - 90) * deg2rad) * length, (float)Math.Sin((target - 90) * deg2rad) * length); // anti NaN + try + { + + float desired_lead_dist = 75; + + float alpha = (desired_lead_dist / MainV2.cs.radius) * rad2deg; + + if (MainV2.cs.radius < 0) + { + // fixme + + float p1 = (float)Math.Cos((heading) * deg2rad) * MainV2.cs.radius + MainV2.cs.radius; + + float p2 = (float)Math.Sin((heading) * deg2rad) * MainV2.cs.radius + MainV2.cs.radius; + + g.DrawArc(new Pen(Color.HotPink, 2), p1, p2, Math.Abs(MainV2.cs.radius) * 2, Math.Abs(MainV2.cs.radius) * 2, heading, alpha); + + } + + else + { + // correct + + float p1 = (float)Math.Cos((heading - 180) * deg2rad) * MainV2.cs.radius + MainV2.cs.radius; + + float p2 = (float)Math.Sin((heading - 180) * deg2rad) * MainV2.cs.radius + MainV2.cs.radius; + + g.DrawArc(new Pen(Color.HotPink, 2), -p1, -p2, MainV2.cs.radius * 2, MainV2.cs.radius * 2, heading - 180, alpha); + } + + } + + catch { } + + try { g.RotateTransform(heading); } catch{} diff --git a/Tools/ArdupilotMegaPlanner/CurrentState.cs b/Tools/ArdupilotMegaPlanner/CurrentState.cs index 5549044d61..d37611961e 100644 --- a/Tools/ArdupilotMegaPlanner/CurrentState.cs +++ b/Tools/ArdupilotMegaPlanner/CurrentState.cs @@ -80,6 +80,8 @@ namespace ArdupilotMega // calced turn rate public float turnrate { get { if (groundspeed <= 1) return 0; return (roll * 9.8f) / groundspeed; } } + // turn radius + public float radius { get { if (groundspeed <= 1) return 0; return ((groundspeed * groundspeed)/(float)(9.8f*Math.Tan(roll * deg2rad))); } } //radio public float ch1in { get; set; } diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs index 295cbb8ff0..9b17adaae6 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs @@ -53,6 +53,8 @@ this.tableMap = new System.Windows.Forms.TableLayoutPanel(); this.splitContainer1 = new System.Windows.Forms.SplitContainer(); this.zg1 = new ZedGraph.ZedGraphControl(); + this.lbl_hdop = new ArdupilotMega.MyLabel(); + this.lbl_sats = new ArdupilotMega.MyLabel(); this.lbl_winddir = new ArdupilotMega.MyLabel(); this.lbl_windvel = new ArdupilotMega.MyLabel(); this.gMapControl1 = new ArdupilotMega.myGMAP(); @@ -1075,6 +1077,8 @@ // // splitContainer1.Panel2 // + this.splitContainer1.Panel2.Controls.Add(this.lbl_hdop); + this.splitContainer1.Panel2.Controls.Add(this.lbl_sats); this.splitContainer1.Panel2.Controls.Add(this.lbl_winddir); this.splitContainer1.Panel2.Controls.Add(this.lbl_windvel); this.splitContainer1.Panel2.Controls.Add(this.gMapControl1); @@ -1092,6 +1096,22 @@ this.zg1.ScrollMinY2 = 0D; this.zg1.DoubleClick += new System.EventHandler(this.zg1_DoubleClick); // + // lbl_hdop + // + resources.ApplyResources(this.lbl_hdop, "lbl_hdop"); + this.lbl_hdop.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.bindingSource1, "gpshdop", true, System.Windows.Forms.DataSourceUpdateMode.OnValidation, null, "hdop: 0")); + this.lbl_hdop.Name = "lbl_hdop"; + this.lbl_hdop.resize = true; + this.toolTip1.SetToolTip(this.lbl_hdop, resources.GetString("lbl_hdop.ToolTip")); + // + // lbl_sats + // + resources.ApplyResources(this.lbl_sats, "lbl_sats"); + this.lbl_sats.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.bindingSource1, "satcount", true, System.Windows.Forms.DataSourceUpdateMode.OnValidation, null, "Sats: 0")); + this.lbl_sats.Name = "lbl_sats"; + this.lbl_sats.resize = true; + this.toolTip1.SetToolTip(this.lbl_sats, resources.GetString("lbl_sats.ToolTip")); + // // lbl_winddir // this.lbl_winddir.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.bindingSource1, "wind_dir", true, System.Windows.Forms.DataSourceUpdateMode.OnValidation, null, "Dir: 0")); @@ -1348,5 +1368,7 @@ private System.Windows.Forms.ToolStripMenuItem pointCameraHereToolStripMenuItem; private System.Windows.Forms.SplitContainer splitContainer1; private MyButton BUT_script; + private MyLabel lbl_hdop; + private MyLabel lbl_sats; } } \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx index fcbfad4a2a..2cbf5522e0 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx @@ -208,7 +208,7 @@ hud1 - hud.HUD, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + hud.HUD, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null SubMainLeft.Panel1 @@ -247,7 +247,7 @@ BUT_script - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null tabActions @@ -280,7 +280,7 @@ BUT_joystick - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null tabActions @@ -310,7 +310,7 @@ BUT_quickmanual - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null tabActions @@ -340,7 +340,7 @@ BUT_quickrtl - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null tabActions @@ -370,7 +370,7 @@ BUT_quickauto - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null tabActions @@ -424,7 +424,7 @@ BUT_setwp - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null tabActions @@ -475,7 +475,7 @@ BUT_setmode - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null tabActions @@ -505,7 +505,7 @@ BUT_clear_track - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null tabActions @@ -556,7 +556,7 @@ BUT_Homealt - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null tabActions @@ -586,7 +586,7 @@ BUT_RAWSensor - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null tabActions @@ -616,7 +616,7 @@ BUTrestartmission - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null tabActions @@ -646,7 +646,7 @@ BUTactiondo - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null tabActions @@ -700,7 +700,7 @@ Gvspeed - AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null tabGauges @@ -730,7 +730,7 @@ Gheading - AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null tabGauges @@ -760,7 +760,7 @@ Galt - AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null tabGauges @@ -793,7 +793,7 @@ Gspeed - AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null tabGauges @@ -874,7 +874,7 @@ lbl_logpercent - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null tabTLogs @@ -925,7 +925,7 @@ BUT_log2kml - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null tabTLogs @@ -976,7 +976,7 @@ BUT_playlog - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null tabTLogs @@ -1003,7 +1003,7 @@ BUT_loadtelem - ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null tabTLogs @@ -1167,6 +1167,72 @@ 0 + + Bottom, Left + + + NoControl + + + -1, 390 + + + 43, 12 + + + 70 + + + hdop: 0 + + + gps hdop + + + lbl_hdop + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null + + + splitContainer1.Panel2 + + + 0 + + + Bottom, Left + + + NoControl + + + -1, 408 + + + 40, 12 + + + 71 + + + Sats: 0 + + + Satalite Count + + + lbl_sats + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null + + + splitContainer1.Panel2 + + + 1 + NoControl @@ -1189,13 +1255,13 @@ lbl_winddir - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null splitContainer1.Panel2 - 0 + 2 NoControl @@ -1219,13 +1285,13 @@ lbl_windvel - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null splitContainer1.Panel2 - 1 + 3 Fill @@ -1391,13 +1457,13 @@ gMapControl1 - ArdupilotMega.myGMAP, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.myGMAP, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null splitContainer1.Panel2 - 2 + 4 splitContainer1.Panel2 @@ -1454,7 +1520,7 @@ TXT_lat - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null panel1 @@ -1511,7 +1577,7 @@ label1 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null panel1 @@ -1541,7 +1607,7 @@ TXT_long - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null panel1 @@ -1571,7 +1637,7 @@ TXT_alt - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null panel1 @@ -1772,7 +1838,7 @@ label6 - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null $this @@ -1850,6 +1916,6 @@ FlightData - System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/Msi/wix.pdb b/Tools/ArdupilotMegaPlanner/Msi/wix.pdb index fe0ea8f0cae44d85ba02d5628ea76877bec61b83..14d8511dfb0a29b9cd21125615e744aeb8817ac3 100644 GIT binary patch delta 541 zcmZpe!`Lu~aRUpN#KP4*{)`L^43FR5?)kF7z`NOyiL+y6l)`2it~Y{gGioG1Xvl2l zlWAdMG@3kF?l@C4&*T{SEFkB&d^V%eW@ClvK$*>_mD)iHf>pOOnM7^oQCr8vBqp(W zkA@x-Qw-1KH(F^RN$q5y%I(^Td=mp$CK+*TR_Arm0oz1J;d({}1wl3-M-(gsB3R%okn5#^7^F#Jx~4CM07S z84`0ufeNm|<)9281=9BlNL0b)6a-;^d#+OTfmeDn zpG*rAquJ!ia>tnr1SZGGX8}3K<+B;hHXAEU2g++cVlhEWlK!!j*P{hGr zt=AxSSD^ zToFSkkO#Amv7W&ZNm4I48puN!3YP*Jn!}I;fRa^kNdt43EKrysg^7W|9*9AJiJ=I>0FofN#ViaA7Elo;230|r fBqM{S;BBBBD0D!8iNU~p^9ctVW;`jt#oM_jh=I8+p-hXZ+FaQwkNh_XV*}N`|}SRUH#_L(Qof>2p+RY0Lz?Pe%o@> z0GD&8eLp!@8nz)K^Fj-kX~C56yRcim4xr3@^OscbqPe9u>!R74(Z);W4&?reIgh3Xv2Lt96$G(zAP>51UQebgW^ej2 zn3ZL{C^wibXLIP@74tSN^Qzgzw6dX0W_0wrS*G$;*e*6g%df&lGkSFsl6N=Fzfj&S zb6KiYjm0uQN~;FDL0U#NHbi!8f^2JsUvo0oV(n?<5ok;~VxH$IBcsv)%)qZHuAAXE z6W6mysm+>9TPhh0vvE5IzXQ1bAASe%3xVET$mZc!8P}osRl%<|es%Cm#;+TG^MNnG zZy|n*@EZY{hF>mzi*dgMzw@|WittPPF5o&3zkK{I$_8@z#jH$A2e1r32gP9U$8R~V zSKzl2zg75!K$d`C7yNqTHy6J>`2B$2kN9QdN8o*h-(FmQ!0#h|pYZz|ztxbh!S8GQ z*5daWvVZVvtQrg>RYR!ZJT5W-tiw+>8Vn`zE013=eoY~3fnRt0dN}NkS;9)heFZ-L z;=a<-RX&2Hx0|-N0dpARFe%mZWw3WHqkH+xFTI^vi_T&jx%|w#dyw{M7i;7oPyRG5 zSPS0IzHpF-A8yaJ6*+8?tVj+9^#vuo0t!BHQ zW&uXzfx3B`N_Rf8ntrwjjRut)RKp)IIsv~IQ$<9~5JfdUF}L~$42J0?A^so2(g+Ws zQu!b}iu;NPa}b6iJch6)!s7@d5uTt*Ke5nhR=1g9vhW>$uK1m^Tp0{Mfr@N4oUxhs z8DS0FUqCny;ft4_r!PR5kNbtT`^5+^;r>^IzaVS~yVnr5Kq&aF5Z=IjYwLaK>9M%D z3BhQD1qdf0yiE^(Vr?9e5tfwtk@Su5-jHkEfSiPdctDTF&`v<_S@zf)i`ErD*xol(+;f){| zPz+5ch|;aVn@-RgpJ%_avbKWK6^F=QI1`!2Dsx0s^=JVc1q;4(oC5Mz!s@W4RB(mWWm)8Lm33mtH0&z;m<2PZXysKFWAh^!0(%|(1S3Cd z&#y9xu~S;%HCBzON8l$7pz{ypJ~ZzJb61W+kWCwI0L-TR8!W-r431F9O+=6b_&Fuq zWPa?qmU5F-Dk|9Rx1fCta5SB~#R6Eg_V^YvGPaot3s{`d$6Yk097-E*Dns3FGm~;0 z+^00`Hn>kI{dQ4IIrJDZ7_px$O zj=e)4)f8RLQ{-AF^1sVExe1@`c_1>B2FT>nRc@v1LL17~uHR*vkv*sMM{F9rHa}*Q z89ZA2gzaRFwTP#zCS%>TlxJ+Gq?ANz(8 z^@~|{olZ{}XDDE|KrzCy%8tudd zw8(38{&i6cD@jgoVBQr#GphZDH3T(9NX(EV&}v+=1UmGF%`b{D?k(U_fHP_ATNcDJ zi^E}m!5=rkudm5eZlml;BmaUwuW9OEY$-2sot)pXs@!~?BHyvDh;8*dm~#jJAIiZc z`-dLBV~dMooA@5E2jFG2;XUftGRk?+mZJV7d_W!8NogNgGOQGQ0If7=>q+^Da#(*; zrjncG5Nh`kk*}xjA5oJ=yIFHI`y zd$cW|kdLgr#y%rkk-aJZu%|ro+R7fhGHbSSK5xPjR_5~2$c`9>;I)>`II7G)R72w5 zvSr$3N!+fd1cj4y4epJYP{LD_RX)mStr#BKA}8KRHMWCeZ+3CZn8Ly}$({R@P)eb; z4xmcD+>Z}9LQ85o99ZSY6QS7NkB2C3K-W;39}i_~Xonx~#7>h^o~Ib!`iT^mqN(M1 zfYBW+mmG=Oo^|w~gXOu2yX4T>@_a8ZpF=bJc{p#FLwo&s9p30Tz3}HfSSgCDzyq9n z!lTR+lBG2n8c~e^?nbFkoK>O<+{`mi&}kEP1y*UzfJCxUvf`te3RJdA&yGp|GZOPn| zx>e!ZCE?vp52=-6!u)TG)+LO)N$iL=tUBM#d9AKm`I>x=y@%8e*5aikAu)c zLL@)Tc~=v)tIypjHU>!#r|)BU2x~?8F}yx1Majn8!&N=48q|Y9w4^;RM=^t) z2sZLZj5)K=JC#Lp5^!H4n6f(X=Db!gz3sp|qO!#$LH{iDy9Ha_S@+V}NM9v!SKcjH z+nU5nFuo#~_I5-i+Y(GqI`SUe6hf^#@mOOwOFws-GCIM=&#+NDgw}ONk_r|{MtanV zo21$yDlI(5$J@&FG>z>H?m2M#TDWz1-w^FeXWpFgDIw(B6|tB?DX}YZ?lkS_ib{hC ztr{CzY@#M|&t40}V2sQ|YMH^0QZAvi8zu8#M@xSFE1M1(M;2{O=BGr$Ms?$Tn8mxO z(N$Vbb37154mNx#n7q7z9I7~#6qbaZtmSD-zmU4=qyNgW@l-bd-jv^Uk z9!@WV#bl@tcUR*x>CIEhfc$ZExc~Ct__@iiQ-Ve>t+F0UfWj|O+1Z_(U9qz~Nldw4YTLA3= zfz;5i_Uh6B(V;944^zD;ZwQZ;CW-=$GB~_jnH)y&vW~m3#1gf0JmtRuz0n9hk|V`gBVZRv89b7Ab-aNoj^Kol|8vDnyE~Gn z%IGY5j^*VzPc~8JIPR`}Ii3$@yqk$!C*jU@BL6ILUw3ky%17~Vg9zQ}tEp(8_8U{G z?q)h}(6QV}#bPa-+D@|sN321$>6W|o(=pJ669Nyap2i2*uea;2gJ)ReOK0#O(BoMn z?L3p8x7-N78qMMrn7HdTo2QBhXY=vaz=MX)L8}X=3v>RBr`KG&z0y=Lm-n~F*?FEt zeq^4-vug9L4q5}31(v&M3;5`wv^p%*rFDw_<`r&`mu(mEAWI)UVF|wV<(N^ehD)Uq8wBQ(@U|TzhptgSl1H*sMx@-)A% zRzUN)+K>W&LK8>W{3jlZ+#3;&O0xMU^mhTkZ#Sf4Kk=$ww;Nhpx)^uvBHk((gvuj) z+K@_|;q8pcmJy=@^*)27R)nIt5iK~w8`<)p0_6&z5`Z#|=&c^8e->#E1mN2UYtf3B z2TeH3U70WCT;#26IaGnJgJlW=s{#5JF#uA+KhEyt{WEuG4T@9Keg+kr8*0a5)Dwc* zu{bs49H=3njw(hSdJfc4#i{v%S{c+OI%*jzlgrK6Lo4R%#9SUg(dW6$w>F}0axod* zTAbi>9(hp(woWyo=I6ODJ5?M<=U9f$o#!Ss45a&w==OOY$nF;>C0&4#s=z-tqSOnB zlDXp=L4?+ zJTZcLEPIDT2+;lPJS(C2*U4=;|VTm)Vd_<{&pa}oLrisR->z-s~D6hRFx0pC;{ z-!1Ukz>h`H4S^pkjwk$rymq~eyuKYllYW5%w~G^=gP_)hfe#T>`ZDkj#qs%xyK~$WW5rzuD-x{3ku>hQuI=p? zKoo#Wk#zq$(ulB_X3`B1qCt2WNvStLKv;}WC zL>dtmBhVKKsEL1+cS z(Z&Ajsext6<%$KS#1+cO{U++Y6v~{y8D>vpaXt!9}|}{=vFOgtq0s2-D>aO zFx?s|t{YgdH;U_y*6Um1dX)9r{a0Ksv0lfD>#f%7S>pPX^*ZmhqfAGC-3Sq#4x z;AiV~m4~?YBL7E-u%EcDW4&H0t`n`-zliJM)@##mxL#nrZYr)fS+A#v>tojI%uR@J z-*1TUwpH*a6@N$i(S8pgb;PuB77x; zsISgXAVjUS2zxz&5EU?02vN^0!aN~Foq8dJs5%y5^iv2?OL{zo5S2j)wOvm!-&7T> zqE1iKFG{ez{sQ$!1;C~k2TlsW2*CG0K*&n~4giw=11uJRBY?I40SX0B0>GQ;?#|XU< zK1CRS@EO9&2%jSqTk@#mM!d%|C)GfGw}|g*kpWZs&Mjc-xw@_fI&~N--eF;3_xq>hlp^C5;LLCJR3R0k@ap3VTA3{{JgX)Rx7=w(S}WjDa$k%tGu5(rBp6id;v%rL7PLSNkX zKvGja|z31T!J2~3357=yBqsfg+r^VXq7MI3h z)zDs&PKy;-uX}DOZh?`ZF zq<1VzdtXVyHm0w;26A(;OGSB=gjT4uM%=WkAh~M?L#0v{gLzfpd^G$#9%*-;*5{S< z&{~E`*Gx(noZLi}8c0FtYvUS7LlEq5Aa%E87FB5|xhqvcI!nzOf^?RKHI(|7v9>>< zY;S*!kit#$xS`a9oz=n`NsC2(TUHWzQ5L_nq0!PNkrK;xN^oN-UR*at5*Ia={;({5 zr#D4f!!-zh5IIw=h2%lg(;Xe?XbY*MT~MW^Bo@0CFw=VdPfN+NT76K7=*H%QJwQVQWmBhN!VrgxAX_?5->K&v} z_89kd_&4?{N&jAFTCe{}l177yNIYm>N68)g92p%Yu{n6PqtwdBgy+!e!6w#+Mzq1h z#f_rINJ0Of2S6e_4{B4#NZ&H!6v?1gILpP}Y6R_yl2jTzPO7R*g*cir#!1y!H06$y z>>I38sM&ZaKurZ)>USDGUaG(m#yjvxEpI&X0RCBupyfmq?KH4jQSXV8{n2bHWlWR; zOw%F97-L;%Z72;#?@W~J>)BLtnuHkAz^VC|>P(WVdewYv<%-o|2N`VSa433Og!SLws*2rnqkX0cZ$>= zME|KE&IED7OK#mH?=@92u?aM6sx+QgeMP@bmFnP;gHI~V|Bt$-N=iINQjRN~@;*b2l9~=HeHG-l8+Vg zxsdOm488oJkk5nsI60*un&VpSG*krkm$qdFl8fgJY?joJZKntk%%q94q!GN_XL>SA z3dh3TXSP(6Eu@6mNO2l{Hyf?+2Qtq=FqWpyk%rlx$fZ)@928AQ)S>4kt(y(Bp^U31 z)t@Vc6!|!4E_|5}Up`a%T+|IL3g=3>MM+*c5AXuOYv|BCNj#c(JWu+F+1$hVQd>L; zsl7m|%LdRe5p<>RM36-V3*g{mGB1Sp(~saa86xkA1i@U8--}^i7p$ zU7@iw#imOpWd+b!3tFU=k&fJ133+#KY*3BF^SQfVvhMUeT~}RWmVvbjtRp@WMNQ(K zPAxHxJK&_kX>=DyD1DiDl#FQNS9x;pQ%0`k?66Gg1h z@n;M98ptzg#|qS^Oe$ER^Qp#4^aNi6F6BpESBk#IPfJ}XRbfSr>|O-}Yr&XB*H`IE zC4?Z)fP6M35Dd?zG?GTJHdIKkZ+$G7O3l6kYaLj}Y1mg_9jA=1z#2nNt97j2tKr3Z zuqp)5g4I%0j_|;0bOEEuX^oz@2G%mcdr0%w=zO^@!xWYo$QPQWdQ&r2!Q_Q{AY1 zhLl*8V-quA{X3AcRg$5z{swYmXIQUUNwQ2tY!6Ar0AU}8#Zz-JSXiE#fATOGqP6|& zB&oC*0}lTvEnuy*R@u@v=4kERnPDvD-;%J^tw|$!&BxjdO`5?)Kdc^*8gMp2i#aIu z5>4h8A_>`-NXOalY(W9$UG$ZSE(`!<+ zqqRXYgE!T<24k6!u{^qWO&Z7>c~k4_Qdh@VZ)<#JE9K~QP`YdEhE$H>ai7mk2}dgC zkpC@sx`fhiA(k<>BphrL*L6|5&)kw0I+pUY8W}|i*^-+!vOxNhv023KpvRo8h24?n zG9)|uE^4Acp~|n)6fA|e{3_kyH7jWg9!l?uW>jB2784Kcug8*6Jf{BVl_a*| z#}`T$FkR7F{vnlRtR?mS(=ze+`cG+gEkzu1=}(n{Wk0EZu1swX%Q36`C509T%e}1= zf)M3BIHM^oM7GZb-cgqjIY9XU`PAa_Lqh%$^11XdMD}BIHKnrLli|T$|4_Ln_r5@< zLgfy&M^Nv`zlt1S`~>>f7i8M`prj9dQAIXM;x74_G>GnsyM4H;rb=DdJ8BgM^M8Xs zk5a9oEN{1Uc^j#I6FDGo2M7a8+oJ6-Xy_P}j+jtJV>0iFE81 zCM5G&sAc54u3Rvr!!R0KN~U8`(vjzyV%{)&hjf7wG#I!H z-tVC_Nz?g~1HgC%0IQ-}&nC6pC%YT3LgEL>`aW{2QUbQu6LE$B2|m0}?#huaul;gk zj%4)MFIVR9dV#oyljp_#`B3^G?h$9?0lBdxq7Vm+oTj6!VcjxB{6Ohdo!zu&2jtSC z;4R&H*(35YWbw8mawVC?Q~q&Fj+Z0^rM?P9< zU2u9(M7~^?^}u0&d62CU*P@34t_OH3IbFnvH&u(fCzsPa6GeWg! z@h^z5KG?lp+9I4<)5V*PE|vo6^DnZ>YLRjo1{;7fj>0Y%4bin|wvac3T%#R&xpD>a zMvz~muq%2#m7VVDOSg%Iikj>ot54wF#u1r&Iz+$IA z{$ug+4Onap&DS{gjv2{oins~G)-5;W_Dwl}s^5}j2jibM%Qfn_RHR;G+I^(RrN# zjO@nfj3b4#vz3AKw}4};GV7$*1iw-17Mx^Kk+?{P-F527Z4wLYBt)6iexM3Oe~SBzU` z!LoN(VwZ3^-FqlEkuuR+ygcsUNzuQ_D6)*l>zQE9Y zyFZreO5r1^~VoLq`g&fS*S+DE8#PxM? z-GsZpCf}FPISLtXYrBzOfv|wWUdeSGQMQ)86ep+#sby%^E4eH?Lm98+ODLI?LU>&u zf^u}CQ1*7T=DC=hTP9AQ3gHQIHS!P4!;`edf5^){)UlZCL{6tb2PL|!b?N>SMs$0w zidkLcbS>3E`G%=t7r$N@1(r~JrFvoLk!$ipIOSWGqGKditx8E{fMu{2)Ah|J9GM;j z(-$enqy&|_h<$T0#}QN5YdEP{9w#-iAUD*kCeu8+d6 z7~6^U-F2y4><$}iVPiFAyTh;5RN$@4k=irAs`^j40rk96G|)@PBE57M!WB7Bs#yn0hw;-f^e)|Bg`L?NwC zzDiF-J4?m;JU_Typ zZ!7uxqizw6^+$F377FeyXq~@Ol_NawuauVDTgY@|m&tQg1;t$|i<_6Yq3RWsMj}-e zP{&5W%kNv*>R4K&OF7aiDE9d~(L->Qjj)_WP60}&lm#0uK~f}53{c$Iep(!Wthf7p zF9784K)z3o6?Mr@stETsK_1$YQY$KzIl`?Kl{IW5HLHX|&}d>MOA+T+0`Yqg8?>Si zl|V!o7^s{@85agBD~lpp9E6BAgO^L$K`6dldKjd9&0;An80KbDwg|H6aj?Z|ObF7s z1#CkbTRQJWp)Jh~QSe?`8*NR9@|LkAN)LrnA)O3G$&VwYilyZHS3yi$q5B&xuA+=K zZo{SA*4C8=hvEFWxYI3~w$kD-Bw{qOwR)mur{e$f1o2lC9{L|kN4N&B7a85iyQ-4M zE^5!KDlQD2#^2SHZylX2ZJ!yck@+>2jR&hMogJutPfYcDyy zh7yh4m7E$%T~zb;A~>Pd2vWS7DILK8j)mp|Y*O>7xaz8u`wfF_EXQWDa&o$`}VMY5o@gx)8ims_IwcT})aJ3;B4P@}Mq(+PZsj`X>c zg`ds6r$kq3qQJFOg>7pdV@a!%i?gFuV7s~3Qj56-VH5SWa zrPIW=EETYQsB4PxshO7670H6P+WBM!51W^05#1HMauM1|<2{wFj0XUZOluDdhc8;Ra!BGpep@FS(Cpcd=}-kkQQpcXWzdnp*}I?=>Yh-V#b8HF?7!21EeKq+&fet|OPq8iMj+VjvCY@k8&5aljfJr4yMji7hgx8O4w_c<=rWm_Er9MoaPsk(w`gjTOxcjDUqIfd z3f*3Sl0nE9D&tV)CoV+Adr!MXFo7N~gk$r`XA$o9Q_>=IUCrpExEoD>FT(U9nGzNw zjzO@MP7@a^_C5Jz$`|s%kng4Ui&5wIlK&E<3vcc%vFM##q6AQ{rRZeZ(DNlllgng^ zSPDhF<*&{ca$lOcRH=b@vW0jE?4729rO3R~0l@Vy0SpC@N-P}_rD`GRN?*qP zYtoWsN&`HRKC=vcY@OP~m!qWZZQraqA z(()lUjev>yb`$BXap1y@U}8R1BIPf(P4oFmOk7t|$ZF*MH`IMK`r3FpiGY`FKvmaZ z3ObF3twB*-(+buo(->Usz80hAEqb_CY3SsSEfC?JID;2Rg&9gYYMG(*V!dfg2HNN^ z^e_YE@E6ry2m3>5&^qN3+f5PcEv1sa9-ia19`z#aU$3ie9+{{yDUho%6q%_6N@|RP znT^8;+d3ne3cyfCfkC8fP=Yw&B_(~+Oxu98&qAKO!d{6b`_kHoiPqYp&8lR20}eVt zgZh?yzCjtkrB>f4%Q;>-zWt37kFy_P-y#LCY0$T*f$6m2TQptk`)kns7P@1gdx?BD zqBJj2vyDiAy=U045%5^R|Iir$|3ifvm78dEx!0iD^3lno`e4R@2M_BM3?+iCGO6xanS*ajCdbJ`Bd0cs|K zXqvhmbK8H&bBCp~n79MQG!gd8#?m)CFnvIHc87AV$jOW>44#uf*c7Xf%lFt5xSOSz za1`u$mQn`iKa`z__y*M%!CM-(6YHM3addbmy2>F`D5Ti<--Tvw&-SUikfO;jc#po@ zg%sVR++B)>7oTVEM!t@ud%NN0PV(FX)q@nb2T8b0Q}>{OCeyt=@OBDxYqq7~3zX7S z{s+aK)i|Ool=TdK*uC@UD>BbxfiPcOC!>#zxPSpFRl9saF-j~^E4U~o5@23Z21==Q z6{_Zm*Mbx!XBC0HW#8Pi^44bZCq(~?(| zUx2#tR&%_Keq6fL1hcs&u$Ea>a-dIll=AE!&F8N251z`B&wXW}qqSWzgOAl@=6xj? z4d~2$Y%4pK#Rj0rz$MnzQ29qnXSPY3_(-Y7**$H`6BM~)O>EQ&&Id9N#6b+#XUYl3 zFl@33Sw*YOSI=NGLGyer7Fxq7-Qnf2nx$dWjVO5`9reE#sx~yU`IP zY%ws*@*bg<`Ij=CD`BV^=cv*LB|tj&0NarLl(BU5gYpW81b2T#L+DEnKPr}!mtvmO z`4cKrRj7=kluzha#%U`*VfMhwKcr)yG4z}vkAIZWER5#=g9={_#7x?aOO~l!{zq}L zpT7xP`B)85ssqLs8kib{FErF=YKpBEhtX~ZxCY=ube-W16KnelBOeZVIOON48Hd_= z8phTC;ha~9q*lXJpo^rgN96A%(56|&G=CXSN^R=Uvrk7~VbD28!({a@B%!~eE|gG9 z3msH^v4J)?!sH?9UP4Vq1p7;uvm#9L}kfzE0mmzrzw&MM9} z*cJ;@TvT_pI|xd1TIGV*XRMKTqw6jzCWHVmv*xZkpqVRxo&X%0({MeoTL8TPI5wvn zdcemFpf`Y$&8fLrXKKCx`T#IBr#*V$jR5)raBfb%rF0s-O9AKyz@<4Y&;z*ujQs(W zZmyC`<&q7H5>nqy4e%HMB(%ABoP@uDc>dLV#PDLzzq-)|@YI3eg*T_OZg`o=o)eCE zhfn_D0T1_6j~PFwZBdjNrh0ra&;S+(z&5u>cTm^BooV{d{yrDiGgsW{R)mvA8as)5|z>7BYL=S}d z0GJ3MB9=P(=rmRXaGnI9X>3tkJ$!U=DZbF03_@%yRrS?rrU+mPfUdE$Mh_GSU@8EL zCDl)-(aH}%Du8vdG|Ep6EVs@Ur`Y|ThvWOd;D=2}1LWkFjvhU_oLa~BU299?emGajqckzev3;+Rf z)(oIDp&aV3Q$7QZIuo4GIQqk1R}X4b05A(ccpP=DpaWJ5U^alHI678Amj{?F1gLWW zbc>^^;(b1QB2ok}7r@LoTB8RF1TYW4f;dtu>g&p3Kg>6JRa8x;`G9xZ{V(hS{})!& z`MY&R zBVIu|BWFM`rGwDgZe+JGQZiU)q<%1rECVOuUnBT##=lK@3kb?`5Jpf+b+t5A@8)8n zAt5>w{vlwj0An2Ghl4Tl|1eey#!4_&TW##>=3=I2HC6jl*ly%e8H`n6WER;_=x<@D z7%g4U2(-giL($z~=x$}5A*WClrZTJPvNabRP)#-*E!UxI;?yP#s<5U-o22bk~MTG$^l2& z2+n4Ul~px#`t@r-|2tr(?E3e5;feOu3OfC4aFk8pShpK+tKYBI3)IeDgHHKYYQkfi`lwcQ|E97IO<7X00|*`owj$}>4@N%fjfB*LksrbFwsBzOiQdR+5Y%iCDkjje zdOF{g`T+I+66N045E<0(-PE{Sj@GH$|VB=tlR1@;-3V6R1Q3-9VVo0LuFT zthOuf?vGuFk_~kUKM9U{0G#g==tTp(h;1*k`VEno{{eVuPs~8V*C75K-gbbX9t7cS z0$pjS)AVnIXb%DSY>#%s0QlT~Z_$B{Zj=s=dKes2A{}U?^O;3J`3QgxiMD(;4@A{( z8lkIaDd4C_!AVY}H4!@HdjiM-&^M7vMCx2hiUe>BKuRL!V>;jr0Ml^*TkO%XFOWqp zQMxROhyv#XIJ@kei2uXc4UT#eoPCLOBT5%RrDy=B0Gz^NFv5B6uT!vjE)NlW$`kFsLy~_GbX$Hmin# z9yp8J!I@%J~3x+m%y>KzVvIUCcYcQ7?kC z&!X%}FPjy8`=}d*G>3&tKyTSCu%YPLpElQJ`UY^+U%+`_Nqt!w+#FxZur~|O7CCpH`n z^C^_8*~|kJOZWzc%HrKy!zXdp2!G^-b2w*hXmIyQAU9Q(Po z&apvl;Mg57e&|5U+UOj+4#0F5K#tw9d&048ZFI`5VqyLsIM1zd&x+N>ywmRiA;HZzmS)W9I z=#}fYgYpvqo9xQw6eyQ$r&Hbnj`|dwtR%YFP8YLh0+gQtIA~W+6UtBZ%JacdpM&!{ ziS{Jul-~nzegWX4O&O!yfdt)9IVcgDFF}wx(y~Och0{?xkcbsC>qhzQvFq^)Scgvd z>Q9J6R8hT-=>V-lAW5BQa0jfjlR9ZjI;f*${xzORcTt_0)4NXA5~?6R6ihK)G2f}% zRgK_Xy3n|;Y8~#@gR;7+4fw9U^hAV1`cYuA8qP=eqprznM}DQBwkKJ|(XDRe*&TlT zf!NxN#|r?J9qcavbfYvN>YqURkEgBOb;)`R!2BA(P|GK3(Hz9FWHP(z`^Fwnegn>! z@ieK2uB{&uz*_*5$J1|mAfzW8`3t~II3k|c+qQ?hL1f=d6Gzjq9hTKot<16Ol{yaz zf8A5Xqgsp5i^})H4R*IINUXTQj#iIepko8eBHSp1*tCKT9DWx!*r>7~pTrF|r<{AM zl_jwkB@RVUhu&%}3Hwhgdt$S5V{g?}3b#Xf0%~D{%J%^jZ--+0sI@q@h-UOr2Xj8C zHNEHuAFu(mWB{VA)gS15ix40C?T=`&(PKe&31o{ESv3Fv_H!&il>q?G*i@zn1p78X z;_+T;!XQkW-w7FZWJ(NFZ{t8j$`HupFH~1Y>qZMRcv?4etAC*ebL_3$o(V_BfWWbz za()7CGQUt`v6quJ6q*i$05pxI^JxI4zmjFDH%KkZu}^YaBw(n3u{V-B2$hH|Dys$~ zF6*WTGnBP{v$)D&HI`#X!xGmD5O^+3inxvfVcwK85^)6&0T2*pjjO{D)tiM{fkgtq z?gL)>=!(-u7P9+L$gsbVH568&hpN#yyJP{@3IN*(0J`GIokdo07-ah_2E3@j(6D4F|cB6*wq>D)DrFILNK7vZf;-OR$kgjsSUt z6*wn=aq)C}1jwtcvJN95%e0ZFj|BO!6}TmUlkxOoB*+h}vVJL$J+YC$Oaa+}{Kvz; zX993(OP^Cf4ztR}jDoCITkC5vnWI3)hlBVyjsf|URki{$$6U**jp6gE)|YU`sL>J@VwR@hJr+t>Y*ihrc9pQAvbGN) z#L~(75yG)*H1FI_ye&|U!p5mC9IK(oaiC-IW1;^z4sMc37w`S!E037pMOI9A8imb$()>=@h zKrnx;nu?sqOx0RYLWn7;<$bEWRM0UEwIEfd0a@IhBBz0l>7})xgb?#c2$46_K*zMv zf;5^A1oOlA=_n|MclhDh3CJ8BEE5=XJ1f)i@y5dGY7ob?&yuiOY0$w`&sTIoz0yz- zabQ9y9uz>I4x%Th!!c*Gu*=VYaDt5;I|J;ER`zBAY_qVv=$9GDIn1UkDyEr0ax5xc z@mj9M_6i|;ZDSvu2{z_Gs3euSTN0I+g~WDDvLOiwQO`5p0cYIi!7YsXTj!}uO7b@2slf_0Ug|&I>fgo{h->J0tABYbpo=l~#R{lk zNVRm>wN|R$ju=KQ&)~u>5C62GE7h*zZCUHrT-RdY2&d2twJ(CD8LBwA_Luc8d7XMe zd>Ew4dUcNo@2*$zRT8{4pkBhQR&j&+Nj7fB%Vmi{#omnDq*hgSKs=H%HsKN3NG*4h znqvRL<92Gc1ryUO;3+h0iy9=Q#N$nW2Ogo}bF+BK*?pV(3@4@7cBsy!8r#*jcwU>f zU9E}7@7Y4QmmY3chryBdJJb+mr-+}@b^uS*vUjLB8!~}%vcQ{7g;`MELNPl5{zzkY zs&&~l+9B>9(7m0YJSFokwFMr-ciDw6;98&AXVH#baBvswrqg9yqKkOHOSPZe$)bea zn78Z(+$f1A?Z&JO;kw=G9{88A2S)Eu+8&i~=lKKd>;bV4#r%LLhkad2xr$c;Zj?wl-H&hc3vt7Oqbp^yz=KRIQqp*VO{ zKU-~&<1LG`;idIFF<9B~axYkJy~uelyhIqjS8dJf^`g|hsyNHNdoOYV$KLmy(X&!~D;9EfKjhwh=*B)Z z(8;@x)s~o^;uXjJsyBt~hnLo4CrIRe7{dP}QL|~wetgl+p7=LH{y)f%kKlgW-q%)Ji9r8hc>}w4Tdi;_4FJ- zFAkyQ%%X_Hx|)-I81Wy5spYi)Fydd1PoyH^<>Yw;6$5A6kKp-k7JYXFv?HJ;Qmz0J z>F*<;&7c}baW|iOAGOd99R=+uXaRIDM=eW#A64DF0tQ)~6doDM84R=VTLO;)22tf4 zbqTER&w*MF)HIJO+7EIi4P7+e!FlL+5w6Np`|$9|^dS!!QD-t$&PUi_GIh;Ydx+A>M|3|y z*14b=a#+Lkv=qrI1r!JFyLWwjIcnT2n6B1Knd_7$D2 z>sMe4pUhQbiCslD#Nt&zbv$>TM{BNPy;yA?oxiGfL;@;ZLz?l4Usak<@z;=Mgp;nR z_D@x3k@-5>(>V~L@bMkX@uJ;R(4N{~SIsMNE-MXk z^%CT!MYQ#H(FubrdM|)q07NdL3U_os${kp`3}7U!zJm{G+ATd6@+**kL*~1>PO|4ps#p>F(5WACX;xp6V6_c01I zTuh1g(Sc2)4foY3vm-tVB$6*aSA=5?hDQ|B6raSgcagOpAPLuDEMO`1c!2thaLI$B z|Ehq|1_b2>2puT@S9DdCenrl8pa>E4BhQBzpR(`?50Gwxv{aC)v8BWw0$*>(hdl&- z3;0=qyVIKKF3zMqRL%Zpi`z#0 z++%e#^m87Ab{Dia^!Tx^*y=xl{2t^{)cXmN7e(n$P(SQd{UKng{!Eo|HrVN@uHy85 z3SgH2X3_koXt%TI&{Np8D>^-cUHn%n6|bf}#f-7tGaMJN*OkQpO%D+1E_^h}Qh^W6 zz#Ep=o>`U>#q8974m-bs`ZM)@t~O*pQ^xb6^H2DfJTCx01dKOaU+Bj4G$H>D@~gDv z1wMRhkGW9De~0`UdA>w$U880%)yeo~NzO}4X?wf^{s{OV6!8il*SG7f7V^iCCsNKU zT{d_WLjDBuM-)-0HuQRgPcvDoq-6f04XPx5Ls90At7%yws-V+qI#y^Imwf(!=2K{5 z28ByZ9tZuQj==oy`X82YwDzAU@Mpkluc01)>I(cj0LpU!Eh+a;U6ReOG4*-@dCxWY zR~cO$Je|toedg}e~*9J>BS*U~G!h5Qf5Ur^jzonz^ctA9f7@--cJi@q0Ov33~o7o2$w zLiE=*XL9D?LBy=TiXI1`nhVYwaANEnHWw4U*MFhP#E|k1HLxSq7r{&#_6`+!CuN90 zquh6v{0w;y18-r#bFD3sh`H#8M!ZJ{@41#{yvLIYd+v1kfRy|N?s)t!91P>*wJjf1 z{D-A;IO&JNx6f9UPoTXMepA>d(4w`ZPneamotookbv zCR*YdZVXV~L+b_=a$_ha7(S9Qy(o9HCBPp5cc22v7=->vk&TawTzexM1JsXzgT5zU z#aNXij8}|xFh88F7{}WF!%-G76=ptx*Ox+6V?&%y?62aKnmvX20{$EDxAa~$Mq#p9 z--v%_VK3rzBjC?~C(wSQ@!w|P;Q;wRkRPB32c3MikQ?w8%Qec;%Y7V;0VW3dNPH2* zQq9Z@@H+VjN23|*mo!J6N6$f3IjD8FQRx!KIvinq3FE(0p8OIZNFbQE(}xnq1{`6X zl14F|on6vc4X3BGOB%&|+Q|f>EG+GyIwlYi-d-VR?h`K3^0p40nMpgpG=ZU|y&kejhD z@+H>|9+w2|36^)3!dScrUkvDJGAb18ZZxqcT5WgZamK!)_Z~>8eZCl18s<&Vn@VF# z8=GJ`v%j?Q0WY_Y)|Ej8^xH@0%NWH}JESa#P9R>Rgt8!Bqm^ZiU5ax24Pez7aJ>WM z>uL1m2qQg>D~br$J)!Rc!g*p|sFdd^#>+SYdsn-?j4gQm|Ir68V>oL^Vdac9#Ye8o z0nDQOa?o;x)=hd}4%u>(YI_@Z^1ws%o42tlUJCW_0sSB30)oEp1#>86p zY-_ZIk>uINc$$0n(eAe~;{WJm_r<3MB`2KDjx*vL+}hMQV?%UIw7;$KsiSqB$P6>B zUL0*_+{cz{6BE#iu)51ngdr@@*0eW1anvjeIA)ke{%wr-a$5)EcCprqPcoho3#$J| z*P8&wbiM!ovt?%P+zE-qk_fU`B8b@cHd;zsODwh35^bnz5KCJW8T-%QybsbbeCRs^iVZv zL!s+n6rMGz$7WMC3Fo*d*)-TuU-MO&&88&T{H!Hn`zz|4Ih4y18V9t8SjG<)FeiL7;q|5C=MDV4tjts4{QJFED3VdeiZ(!!D;F#IB z!bk|0-f*m^>XJK-1lz!e7=$x`1X6CGdhJsvR05n<;GJ7xyK-BoVPAkXl@oHo<(2W7zcS(v^pw`UP5 zqh-aLj%+?6aXAFeSs9+=c!}I}E{9adm#9~+qd*HMtE*gFRVI!h<+^7(Qq1b(^4J{5 zEcN+-qveM=jx6myJ%vh>pin62U#N_~@tPM?!l-g0c8;jEFRUO{S2~*e3#={wvt!c23f{3R9c=FWgv70K>}8{=?^iimm>omW zD+puTsMoEfrTJ=y+iKjYMWpHP*_kr7%fXDi;^P>Pt#&M;f79ro^}Oqdv=77nhOpob z?1#$fcPVeP5Znxtf8KQjrgRRK7Hbf&(Y*cFFmZkC2+SZJDjSqw5&}J3#s&*2tVJ*x zL1?%{{m-u2 zWXpSeTHvLh20gg-dK6}%@I-_RT^|${8DibN6zR#P%8}~c;8PNUc}ULC&MI8vg&aCD;^ZS5x1 z^HKLi25;UsR6;l74~|l{A7vB1pyPg3!V7#+({YMqXXKKyzG2zI&5m{!64v$2q;t|y z-z|8QWHU=Ksl+!lzJ(&16k%A5_HCW;V2h(Z(eJJMfg{>%A-X$kC0F}m*KDe13^WvM zqnszEdTn#8v=A}>Y{OB4K54sSphboBQ9@(=c1L~dG6L_{ZtPU}fIE$#G#(Y}^J6=& zqn-6zG%7vG_8VKdQ-O5!D=f$Ca9pqu6o2h-Y_zI3H`dGS`_R$b;^0N?W9)$}x69!U z;m%~1I&XxQm%Ll%NEx?_&prFc?RHeR^L9i-a0UyLF}n$D(kmwi24}D^xvT^U2)?uj zXRt8o^f7|U2!6H)XRt8N%R*2E!8N;F|F}4Tg-P{K$QX$TG>3X=ejT$0424w2NMV~C zx-?BMagSVHc{ik^+&rkU8EQeIwLroa&thm4_)Ao>9eLW&! za&8ZbNhn@*24~MOd3vuSp(-28*=?HN7eU#R6=0@VyUDZ|U)VI6yO%0m6-^H9rAk*z zlfU+oGI{k+al0l?EYoD{r;d0&p0_{eBYo?=;?y1{p`W2t3#A{l;A|QuuPQ+@f?qV1 zO*u(M3(lco(qJD7wNa?*3eKTnvP20|5VUm3{(a<7I4FmPNt4gX8Ff(T=lV|$#VQhe zT_j^%Du-4qv5GvGLY`AcUtspXxiyTly0K9Y8(Um5Yd^UaCbtf@oO1bcXqXKD0+srx z#OT2}G)zt-kd)01oAm|Vmqq>G5S37av*;MRJafP?P|H)vm48ir+2HU25n4nVs zAX)NDze0>0|Bx?ZI%d|NN%3r*SwZp+QqGaumL7CGq4^S*nK_Nd>3k0kIM zx%qL&4;H(baxH1BkvUU*&FY8#nLu^@bMktysg(M4A-4p67Ho|hTYRRvEvhm~N@3hs zUm{m$tE;}wE7IwxxqJwb&!us``h)%Elx&p)3o(nu+BmXi*f^iHs%oZ{(lwim`G8!S zG6sx%dBlK>ewlpL`enR4Qtj8O)|V^q1nc$B%o@}mGv&5AHtrZ$&V38N+p7DOuc5M& zUF>*P9bdmJ`S3rEWz{vARKf{37K5+WDV-q4$hZHs<9ACGS;ug|K~FkP*bPM=Yb?6h|MNWIe4FRQ*_!fI@`m$`hwnE98VR| zRU3k;A18x&l()vfwcs~kRVB!VXTj>c_Z)a4_v&1Dbw3B5#Qjh3WVi)xO@ZgZGvP(> zoA3t0(}X3@UJUZ#BKR%1EMYbu?hh*m2g00~;t_Zmd;nenhY^!XUJ72#eT4tMG)$O# z;{5mQfNgq@`^x_Ns_=U5pS9{H(?%{jWAMI&eC?=FFPu;gH>H6jc0+r`kGZ^x+8u4U zAJdHcP*W+zQu}L16^+0*N(PRCRR{lOeeKB0Ps=RWZ+3g#XB`D<=Vi6Qhnb5l-TqtS_mx3I|ZmpbZ2ZaYRQ6>7(J#rAqARTG^Rt-T(Gs9m_LNP3!clw3-5+Liy+HgXRVosst6Q9b-n z%2am-rrFi9ZmWe5h6z^BXA@t2+Zr2k*+~DA@l*;rc_lS=||^0^gMeNeJ#C z`0b(eO>zb*&39#q65L1d*F)K#r0CvN%emab zOZH86CRuqWnKO_b3s)sO>szmL_tix1?j}29tiJ{BYSwnf;6?88)H~*QIQP-Iq(hB3_vZSuFw)wamsq1{*{G_z5=S&D`jbOG6spqU@ zp6$)8hk#~nNCRg*I`o@BmeRk-&<4&7f7+6(4Tu}IRHar}((^DUXw#F=b?n>y$+^nFxXi`EqT>~m)CE_IqZ>shpN>^)+212zRs%!JGtG?U})%K`BypfnmPZav5`X2h4Xd zGGK&E-17ep9N^{V*zJhUZkgEJ8JHi@T8?1uc!}(_kLRlTzJI;BiuOQ4Q$1)ONXr(^ zj_hra-@wL>>A=09sac;Ck-0&WH#`%-kyizu|bG}J{wP^3`sKRA-duIna zNx$Wm2?@12Kp)BY4$c~uUAKHaH~Ts`!?fLo*Uct}uan_c2WJfXrG<8MMwsnqso0!g z!^kve#gG%!`pmL-Tu51!&Bv08zDaXdcbr4z&sxT;XS%pLIhnUwOB!}^4z*NEmerk{ z-Dsmf?8K{{M{!c}f2Jj$l>wcJ&u@_ACClv2&QyP9Q_l^Af!fB{cs2oC#i(HvbaAF? zJk!X3Z~C@F=-tKH!>XLG-Ov^#$GSKZEjXzrPm2S>T);8>sHm9ER z!|mOjPP4haXgvs;SEOeTr`ie4*x2b<4`*b^PgwatuJv#xm_Lxvo=#y;vv+!upH9m; zMc=XsH@WObnc9me{u%8LISbrbjsD2fy_~-??ELxj&X+9FQzW^!vo5{Y{d;3;y3B_x zNmJ!eZ)Zc5!23A+;Yj~JIC2$7{*{@1aO7X_=0475W{Z2e-0X|>F! zzqTLx*U-N#$NQmw*?YgAv%J}oG)v0#cP2C1-MYV_xTHUd*HL^;KJV{r#Lfi|`#WDT zGc@$_i+H4Yjx2o<_dCjQZp}R|s6%^!GMyoCSF zA9@E2a_SadeE48zS+%Lf%uIZOe@_o_{%f|XM;aUD#b!Be<}KbTSJLj#2LALu5+$&s8-5kBx~k5uNa4EE#PMPeCOceo7jS&o8<-0pDd&3F;uP< z3U;{hEO7p%*l;Lsp_92KoXVvfaxU_z-&*8csh(>Xu379wgm;J%*lYSd+wzv*iUjoGdsxX0w({bjdRYTTyf|R!D5IUw4m-PmvXd*d zlC(~NS6{!{KeVYn6^#?pO1B+^}Lpt*zXyp|$WoCCW`zS^a_?3qdPQ`qV7eqL+DdO)VnCj-am` zd?bka;s0UXfmT0hP^;K_RGQoOkYKMk(HbHvd|E0EMD6iwMf;SEzclI?QVdPjS_V8^ zGt?(mM{5RtG!&TTGCtXOqH>F&k>kmDn3jY69k~`{-RXbPngP3T8MO9F&)SA{(oC6h zekG%}>sKs`(hd3Cr_`?w{=Mqg3SOI54y~I~Cq-+Gf0b5z?~*1V0)7nV+ z&RepybWG8z`R%aFwYd&aAB~#zBZ;n~wem}%TZQ>tQ*E`tuRLn5k7Tw_O{M=QTKU_v zG|P&AX{fdMC@6uqqUqdqSo@aUd`;xGI30#PWv9hQl2lh)qe_K6m9@yISffE?GSx12 z&1C9?d;7&)Pb(kV7HdU7iT6wOdfL=tn~fuURu%=>q*=yvo^O@S$~bI8MTvhGc8J|; z*leanmM`?%RL#%8?{#d>p;@eU+6)9qSfo!H9KfT|i`gwl8)y|}bOWtwKsUvowkG?N zt+F`=-6TUdzCl3_KLIk4|w)?MZ|)@m4PT`_tBBkeOe+Svbu8JP9JtOpfvt(swT7e@Ry?Un`s zqr2P>!srKixrzS`)co2y81CF+3C%- zgT)C=4S1^`5m@}|LTx{k^UPFjpO4|&Ewt0tP_-7-_lYo@9+%-4wX#)IVbqnL29;J7 zS7GI9GgB*5YdSuD!z>--%J`OA`Rc7m^^fwm|lf*;L)&3<6~i!p2o@EmRf?j zvTS%ls}x$*)YfoFMM_<%^Q2b3lIn9&VWGH_slVw3(~E{mWz3rH#Lucd8~dbY3r#dV zTWq@0Megv^f!bjnF_$#;`d;;zUpM>e9 zBO6X^ttDvtjgnmLxUG(fj=F$U1^Pu;CFe_UE%=I@<00Dbe(gm@pLEM#kg8`D!RlEz zVD+q9a2xnGtgJcE111@NEJ=_yT3DV_L~RCa@~$n!)X0x-LnZoVNh07i|d-h1rLq2Hp<0g+GB+ujF311NTIjsU7?coCXtUhMYh$b>aT5>P=M^{=lFs1{{EG z>JEp(6hodc_<5LcGWCHuh}zT_=74EaKlpJt9p)jX{;(>#UVsO}FTx|?4A=v6=&ffK z{0f{44}lBJ^yUuZ;%yAF;7#yw_+xkkd>FO_+If_!_Kw z;(vjo;Tv!@_*b|#d>bx+vFmvk{uADk&BZ+~yzm3~Q}`kL1^h330;UJtL*3hCfv><; z_-8l-{tc#4>iH9P!qkOL8cYq-gr|%SVmD0P%v1u7hfBiMU_9%|uFFL!E*im+@Dp%p zxD8wuRvpCU;O;PQ<#_=v55ELgfJeX;Vd@=fXu>lIj)SMe3GiH)kq*x`n9%UBe#Ddr zvjoDFWHDuXj&V@~gVS&=n3>F`WSFVHrn)daI;MK??{EXSx{XdbxIWwjZU{GnTf)s@ zx|~dp!}MgCQsFfC3HW*VNw^Q(8Xg2cWyv;q26OQ&2Cu>$;mL3soDX+~Ie)^`6+RAk zgXw)R^?~ogec?ahbl601VShLjegTe#2f)?ffiSyFng+p~0A(5sKMB7={Cm`hW+u$m zl%^ptyD*!E!E8=z%7UlBBj9{^B)k+J1-}Qs2Je7hhd+l$!zbWz@CA4R{2lCpufmgH zI)qJ=;SzT8-xMz5xL6J|xDcih=;35S(=ONxQ&f3&+R6W)aPb)id*I{nUidrsQ@9BJ489NVgB=v$ zpTni${ct>d5UvRyf@{Nv;l}V+a69-IoDTm84~Bn&hrn0i*Bs=34#@UQ#^5@f2mb;u zfp5a^!oR|7ykxo!v%8S#4$Pi9rr%-qZZVPdJon-Ia49F*)yfA3rorl|1k>>JB*L^A zJq=-+h#n5DH#y+W?9geVo##o1HJF3zO)i+zF-fm2fHe9XJx+2-7(8 zs75q-+;a$~h2>G_ZqbJF`~=fT^4x`K1$itCE5^WKa0NKKA{UGjc@p8ua5Bs&k*5)y z2)Bl-!(HGcxIbJI9tPKf$HU3+n{W!e5UvBi3)h9W!IUkYPvFMzr*KpFOSrj}{C|#% z78v{tKL-B}r@~em=PluIm_o@@32qBlho6RP!_UHv;r4KAxC7i7rXlC)2QwGbBXBqP zbC^QRa|iALtJ4a4TFL)97rihj13wSP!~NmfFr}TRE}Q{3g9pG*!vo>&@KCrHOeyH; z508Qe!Rn(n7^aowdBx8jzxgDX78PIQcBXJ|m5$m+Ru1gF+?fj3c*D4cQA65FO4=%+ zU9|H3r(uk*O*7!iFta16Ml+NMQ%5%Cz@Njj;nOg46g@w}`LLNU6=kre4m=O$du=L! zJHi61vm2Jm%r4sFme4~obhL{zqK-Ra3c6}e4h_+|YI8y!P{E3nC0(_8*_o%PRD)Gu z7q|fKf=C`)6SM{CUd7TIE1}&<1F`T6|!KUT?cswEDIZ zGtemnTfwn!@>`DBo~0QF8XCg}<%Vms)O)QOuCd9o92su(*hGxbK2z^^c7&E}wv;aC zb&k@;S*l*ei3cE(YIaS~3Jd}sPzbhy3l}!G>}D=-S{Tk%2k1sJYvR{Nz5{mQ|8u}D zrM&%qBjbQwfA?ynL%Ka~i?^3S;%ID~u=_}|UrEX$32$s1vHM8UFcnETB$XQb&e(;G zGj@kH4nAWyQnWX;gsM>}&TZ_QTw$ECo8{~M38MnSWOS3Nq|R+Do!`)|`iI{lrR6v+ z!5)pp`Avck-i?&CN>Cob7fpf>-i?&-@d#oNTyG*x$7>ZW*PD2IjVIF;yZQ12EuldL zG;THZdnV}Q-7LO{X?%3%66*nZMgMG#GjjPib0xVnL0eSp*u-oeR}sf1HIsGO#U}$t z$~7gZgkV9l;0Z#J(%z#bIARg3YsNU&qw{woWg8NE9FmWk8IxfAr}wDn3=EH`QtH=6 zkIvs^4$(x-rQN4S5!6885Z)LI@yPkRNfu&_qjwuxh#OAbT_pvRv@#aLdE+E)r8d8b z&!Yd(-OR~as)Z2UI9cmOz_Ck$R-pNU!EBnV=KhqGJyW!{7T&gRf*viEr)r57-jJhr zds)^sQ>X4m%f6{vs`gPcpUW}6iG;D!wA7(@Nvx6Il8`|=kO8KELa+;*0#|`*OGbj4 zpcUv1MuR-C3hV;Mz*S)Tj=T<1KwFRwMuVL1Hn*&6-abPctTN{-Gc{wNXHOo5(7l-& zr-@7VS(+MU_&1kA>cT9ei@x5Q+GiO3=_5mOEXR--*UfVuU9Ty=R-+1r*faZ)xG3oQ za8-74PoHCyeDBXO#sv)hlswItWr3&GsRF_9oF`u^D88vVH|XZV)Z@j0&ynuByO8We)9;4HWWB7fo;APo%qiRsHZT&x1ez*XS>8Am`W=mDmHLa-Ga z2Dg6R+;Wy#&D#-oMN6ckGqXf4hlfbDik1pib)m+YIbu!$Vlo#JL zip2-Da7*b@vhko+hDqn2AJlp}{;1^U1v*QWLs~*eSFBu-_FQr_#_&Vh9rm&r@TK-H zt5QM_Q{X&@{I4=0vMj;U#y=0DvrI)2(hbSqvf(ge0DsHr!^l+dq-HY@@V5l8Qim&=q8YDWDMS0~f$O5O$5^0a8H* z7zgIb?bBLqJ8dz0*HEc?MyqJ;8cK=lwA7K&XS8Qj)=A{Jg0p9|$g1gR4Gi^vMly%> z&*0V6ESF<&23-fL7C10eN_|aLr!Z7r_*$E0sZc_$tNXeor0H448~e%pvlRUOaq8m| z^6^w~-@52s6B2s-#>wug$g8EGe&j!*}G1lCtp| zEiKA-+^`C!K)g2RrBzV9f6~knl?!|s28McjUC^ePExefVy?F4gmZ+Vgfvmn(<$N4zXxB`p0MD}jTiZ9l`82ye^GnP+;BZnvIm?6MZk8Qx)?|S?LY?bfCXR^H~=nP z-`sMGx!{Tx8$vGy>!7P#(JEQKWVTB^=gxxfwGn|hobkOD8PW-rYqH{dtr9z{?fqW+ z(|pbQ;Sbu&X8#hyG^zfR#u>jqktpF=0&j_mxINcBxmN)zoWmb)Q{4p^>rR4oC0 zbSiL~%tR-$J34WG9aGmHUHiQ}3gzg%jKIC9oeG&ss+}ZGL-x);=YJk z^7^Y5IPD`%4l470nCHmtUn$zsxmMz=EX>Rj6@4{Q!aC2GT^n0ZmNatNi=U+

O z^HzUp9eIbAe{0#!?0aMi_b+^OGf=OKN~w;YH7y5nya*2 za=O$9(70}^xjL&#MoPRZQZ{KW)yzborg|9iaV|smE0;@Ez96QT=q@#-!w~P%4RJ}g zVZ#vTxDBy!J#LW2SrBSC+A;Kz3&%nYmG{GNt$7KTnoD9_ulHRWF2|HKTpm{Pk;_FT zAGzEkEZ~HySyl>nDVh`h=ow+90t%&NT&YLTC+wO9P?SADR8C~!h)s8a!zRX7@qm8?4AN?Br z=wVsqAHC3p@{c^;F6PnouAu9h6%2DD9ttZw@~E?-aow-tBd0I>A4dm}_0JJ8K>{Zj=r0pj20w+3^fjs#oh3j|zX#()F;R z>=^BeX|U#3K9JxPC;~Qy(qce;&<+d&9#9Cjg2Uhk(Z;wEvJW$G^aHRl+7<(vgRUSG zOaX;pD>w$O0viKNF`zl<3Pyn(umab6?~QTQ z$qi9?_j$N=L&A=nB|fg<3(N4W-4K@Ttr~>u?wZ(&%3LWw?UjOx*2wU6xE}arki7Dw$~f24 z{>imyqDDIZ~C`RqJ*>KobZ+3FQh$f3_7(b9Y*{;BDeFNl1 zRlTefX1m<>m#}LKk&W4|q-Y!aQ3Na>;3AAlcMU9ahI+*ruE3hO0n*yzN(fueSjKGD_4TqI9Vbg4SV_=!BxSF;@;$0xcH>@Qg`3mOO9>YVBprR96#!kK6#8OekR~Bgdw? z+#y4eX2|8Ku0WkdINen>+M+#*lDitEg^SucQ4+1GDCx{`zQbqW)JUv! z;*i&1@0X~hm62OB@ct;Iy~I4zRgHs4zn$qSFRf;}l8b|M%uHNhV9`ELR&W_LFX)+D zbuv5{%roaHyMgUz21uP*t_1PC>9VoY@8%p=gk;Wgxw$@`pW+sPk+Ii=*;x#C+2Xy^1u2sbI>1+{tcyHi52NMJ;xHMi|fsx1hXv{wK1smlW%iT z>n9I$T{DZ{E_b$z(#cUelTZ)pN=UQ$a?ltGT-ZQK8ym78;0_nEaTdt3Y_-l|x z(j&E+O*MV13HQu%Wib!F&U{x#w)&bl-}O9`!@pIuLYfq~*iBB37r0)skPMoNYooQ3 zX7imFXj_0UdP&>@S2jD=tytjtf)Ec~M3hch=$b)ja{V?TwHea->Ar`K@XgrITI}j! zRiV%?L64Fj7P}H@7K9eMI%c<{@JR=wK^|BG4uDI*WT9~h>VtM53(NrP!9H*S+y!pB zoGXJ=&;yJDIbc252QGlSAks!CfL5S47;Q5*H05!z2J8W+KoKy7@L*6Av;sXq7MKDG z!B%hh5?8LO{w`Z))I%K0U7s1V%-`Wle`&d^my$Jm+w}(IeVYKQD~(neRQnyOrH5A; zl^m|=ZWF_3*E@z$rPYR!tY-2LE5EwF>q;^PM?7m>sim_I^XyCD9*DH#Kad6nfjqDV zoB~CloWpEN0qI~gSOfNetH4D0oCs3EAm9OOz#ec3+yh}6I-ni!|K$2{bD7O)@0kns zxMJNU_|{~wJ%JKSi(lALs!OE3n!leYc!gnQ6i`$PU87~m9#?sL25!#Kj4#gSv;@_q zW)s_|u9y-7ar2WizNR*tS6|jjl$F+>x@!5C%LISTGI8}2nfa+J+rAv<=A%m_B+Azy4EAVqgeXh)C~H)>8UuA;&=W2V zQ+(|s)BeD-Y;t+O>+gaSEJ`1J)8e+z;bEONNY(wWR{qcK^q_9Cwpi}8!PoOu!Pkpk zxZjl;65}EQytwqZ*?t~<{ghNa;HqfVPx*Ti54xt2I*g@tg$G@c_HR%ca!R%zbOn~y zotOIuT?q}C$Y7s9KaUYnT`~s@$nt%KO?*U|zhHbw19CM8qVyK{20^k8xgPVESLbEh zAwB`$;@H|#a`BKW$pX8+NC>eNYJa~E5T(1`_IVEBd)+PKIbLmD1s{p zuAY(PqpoDj)id6{M_pUYmKk45sbj7VmJMIa3&-%^(XZLg6aM3CIdsg`Fto{8U!bV9 zy>?k~%oRDmmenDN$6anq=2>ZY-1V5na!y`5?s~?u>YRLf9JdailTs&e9=Ub)1a3_|FF&2YEjD7RdeSwRaLGT3pTEb?7rv35C-L)zZ@kw} zx<;5S?Jh{)(>&+q1=)BS_e*{&R}|O(R?3`lJz?4Tt@Jv>edmiZTk)$Gwm)%M!?HiZP zGWCl5bUrBhYkfmq=^E}A25k5L72CtUan<4tmLPRpNBY4P{|UsEFOa~0!Q}WAdF%q= zb^MBV=ml4r*}t|(DF;4{>BIt=1W%bwY}NcUE0%A4>uP5qZ#;I9;FxfVK1kOaNP#rn&rks$xN?3!R9{f)iinqb`@kVbxwl(hB2_pVu16=64jQWu2o z*z2xYT6GewdSpx1&S??e*k4?kW)*C+i(Dr(Um%%HWo7Rdto0dx!&P2|$)X#shMF%3 zl+2iRSaib`V^uG%y1ngFN}5c(YpVn8bB0Y-y7 zupaCKMZo6fn*dsYLBIo+gB{=)xC%^69xMkMgEWu@W`H%J<`SkoT$}~BK;*XDdPy@Y zmFMZP_FRg%hwJB8)!X_D_}~(*D-rT=eTY<=Y>%41TyGarvxM2y73(jnF}vq2`Y&oQ zsjXFCZHy}2vg<50VxX+DQ%|I_(%z}7W`^orC2<j{p9gxrvn|7;YIa~XP4HWP+ppF*TVK&rS&WekMCPX|HB%M zUE?6>tg?Edg-0wZs}Hm)7uA*v5>rl3tTm6oSP%Arv)~qRGdZ*}XbaN86i^7ZdWV0p;4M@hO8;oyq&$N4Il(8$K9qw>z@#nv2RZUvG{O5p4m%DlV=~MVyQ7xB z(0C{V%A-~RweVb-U0x4-rXI3W9fFDo%H>LOyU<617BL8z1;!dfSrjZ-i@*_!U~w+% zJO_jX&K7>irgm6~L$WSc9;;9sK@VlT62v3eoGa(shXxjlKa?MpAOXP_xl*E{9v}Wi zuCGQAm=REwIO{YFSCI7QT13 z&rS7xAWm7JkpCnlQ*2tOvqF)XT?72T5&eh0G@!2fK>PNkDB=uWy(~{SSV?c`-+Az% zgva7#X2scE`O-92Z|rX&1lLwnt|J1~K@joGyHL}oOyO`DIMQaC7z3B(J|2#;$^KZq zqIG?au^C8I1a4k3uPKLX~wc$Q+3LI{VC2*2Jb=FVR#FP%DIK7rNJlE&f z1}H_CDiu%qDrZC2(=`LzkG{MrmI>*s2IZU8GkH-aBW{uulO{FI;Dz^%CN z2tNf6fZM=tz)#D>c>Qq}q#C{{#Ts%?qN%>&88KJ&8m^LY=&_R`wY$))lP;)(5phwR5pdO#!k7@ic;K{ zgw3WWtr+lA(bE`n^?Lz3>Q!Ha)hlJdyX9K|U@%ZtRMi6`gZou)72CgK{=Ss1rq^IQ(w5cqhkQ>SPt>c297M2Ph9v5N zPM8C-A(3+H5azqb*^EVI{^7s_5?&q2mq;?l+oV~n9yqV-fQ&&Bau~@dSy5dNbo3mM zAC>tL%-@jEq#*N7NthqSe36Vv(gQmb9FT*`{42~?$n9YBmNoPQ_c6?mkN0<6UH*ez zh9A_>14sTIkZtIM97pG@vRhW}*3bh7_8pMwHF4ksLdyid1O5M0I|$d*19iazvP9{e zL`MtgEcrh=;k78$PN7qFf;6qA2Zl-y$V>zgrx8^2TQ&|Rdv2&4uc=2!uUdLyaWI;b z@#q;;IUc1pQVds~iPO3$yvB#1wnu)e zs|Olb2c$_o9KMLn_R_x|-fAy1>*@209j;Oz@pp*-l=k)cSp6wO>g$ax)`_yZzMfXr z*X5}acAz4nnyGCiw1M8yJkZ;xfnJZ@oF%^@Ugq?UhI)B9+fWaq7wTF={iHclb~hpn zM#=ETNWvN;c|+nFV|S4W;fB3EZPLw*@Q|D zN#P&v%@rlC8E&;|s@J#HonVua9XZ2oUQ;YK@k#b5N&A2#tQnH7O45-S8Qx6)$b4OD zHP=P!m+k9%+UDDV@=|lXz82~6nU(jMrL@4Tw%@EICns20xZeT?+e>~6U95k4*nMEQ zBT8C5re{{aN|9lTpwzE90D0& z99RH0fqmutT_n#JG`59GXsR9&QiT+-LaLSdWoUQXPO-JrQ|LQv&{F@~Quc(@ zeL`=@VIMC)L41#q6;J2`RHp>{6-msKdSpqe0QQiR{vMl-LuJ`B*4qB;SVdlak|M7f z8lfjS6X(%UiB;rBB=$rkB~D6-R>d{ND$=QyPP?;}ZnIXvj@px_*tOk=>{K!AHBZV< z!FH;*MnIjz-t44wZe3g>tRndc95oRh%^t2^I*{xa5cn&+Ay4Vc%vRpR zHvqq$E$3oq-)b}^Fg3nP@ zRfTOFvuNymlJksS-=2vR9-kAN)5@C*u3BRqH+aGPxi+bG)mp)-E{1iteOPeKI*F(o zR@YKm7PRMccN48mvbnw9+CT7c!zTY+v&K7qMbQ2&tY5cQAxpIHp#N&llNKHI+T`mY z9Vr^l$cm17KRSEOX_Wf6&>t|*|7EzX@nvXJWDU1sB+nOFUsWCLY20atG_p7trl~%li1E*R$V7bQe);M73{Q+xQdL z4H^F&FY-H*4h#G*(()e;Jpb}JJ>1+uzI{&bXlb!flDp|0*jIaeH*RY$lB4Q&tyJi) z55wEJ-ARUj;6%(~U!|g44?WWHCk9Oy+l(10CBxi|A%a*M0Lt*Iy3SYG<@;O@Uifti zd4@`Q>J9w8ohlXs$y8PL^QC=H{do?&S=&?pMI(ZYDtkHEd_5$>yQvqsmicp+pQq7o zejvAd>tas#&g`T2vzVJpTsmc|EnSacJ0`9hnLBuUrt6a}7W{hg1-*l%>0)p4i~9B| z)?P;lnJ6u)V5XkZcL9lOJ=h1X0<{7&2Gj>VKo%$jTfr$%1j1OInF!LrATSTC2m8PU zpjK^`11S~!>Ap+BEIrm8#_JCZbSKCCOJ~vJv-I%rfKjx+S;gKtv-I-pPBY#|3w?Au z+Z_?YOgGbya%2|GsUKxU-Oz{-r(x1Emm#9CH+6S-uKxjLa7|U5f0W@$mine17Jev5 zW)H|(_&@Lu<()T)T{a-J_ns_A-_)yy_n!Qy5sA9#Ct0!AQC5zxC9mq)Qw%Kpk!Ny_C>ulRLUdsV&C z&x}^-)j|woIX;K#+NxYVOzzFm-IDW8h+7Wl>P|*jPUrIcpCxW0@3?$@h#EUmmcwTg zfUC5sTs3xd6wfrbO)ll> zY2wb)ozgg;w;8AYq^4Q}J9#~nK6$uS8rP0bmuY!aB;fON^$G0fqdTLnnQ2J+e=iPt z#T0l1XRYQF7T09BkMi@W1o}q++m&yrnaZPX6Po(0M$m98c=~rZk+VCx!QZ^S=r17wJ@*lb?R^B{Rr(x7kOxRodgg zy!rGh_;=xyp7Z%0F2%`Fbl<3r3H~453aW8AaFQIIPh<3bJ}nV=a5G#1-U3&Hx5Cw7 z)t*zM^xL^lfxU1;zr3lRQ{kPMw}C%`JHQ{qJ>gH_40td660F>N8UBp>u{6<5`?#3v zS6JZZW$+i6uZ9o68{tE+YRS^*^qhka!@t8{$=U*anC8o>W>cv2Pp5_!YVmaylz_{l zr55_C*C-7?4y$#&^I)}}cQLHi^Dc+gdfskZZ|F_7r%?K zDw)>6%Gz2u23`kK4>6W1H-R^Bp9;SZcY-&=J>U=E!SGgiBD@V&nQlA04fevjV6~L_ zGgvKUR^3S-!N=%4G}bbo!Qf*IF2HI@^A&gx{4=~)UM|%8X~)@$UJbCEmhg)q5!w5Z zDsO)QD{miwOTh=>axfi7M&y49r*eM;R)x$_SQRpAVe?S zJHglCSK(jam2eTf7QO**f^WislE2=30jTO}@m;H{y3HVQWxI|y9`My?W zQ?l%xWRJ{7SPNf0ghNd)6>ny73Jbn(6wOYq)vpSm=rn#7#C0MP(t_rKw*XlVstn!>%ecc?+F2RKg|B`SQnDv03UNE0{&kJw_JQ7yRvZuhM z;rXyyp8YOd4pzxZEz4HPNiECX2dib-M_{!an|Lu*gf%>032q3-!Yw$A#1zMc$~^J# zvv3038CJ`-d%{)V{%|$;C0H%n9t_ujN5E>i_UmwMI2%^Wv!}xKC3LyI%))1Q<8nQ^ zQxl9;9ithX0INbm1?c14w}RDT>_KoVI0t?T-UO?~*{9)WU{%PsgK5^AI!M$Cy^&RY zlGTU~`{xZ=p;vpZEmh<}zyk`wR&W;F0$~-YVuMuB1B?PWU_ICet^&0gN;!}M(!e0# zkxuXGWw)=?D;kqZV&B%28KLubT&3Tzlv#knCU5{00b48%#QN*#a|+I@Wlw8p(5OQ+ z(#r;R>R+R~t?JHLS2J#nzMm$hF+H%yT0PSK0lH($1`jfAkqv99*K9?wwXB?3TijaT zBBj?M*oI(NS$S+7Lv(Q8b@~a*xw2CCJ-wTGi_ClvmF=j^D#ytZbeGL4=RNQsR9oj&RfW_1`Qd zVkCJJR%gb@z)e_L9wR$98IKF!jFlZ&`7K78ZVvM57zCw1L=aNJS0_{bl`TiVJkk_g z_1z+ul>=&Tdi{7_Q>C zf^_(xxT9o?M~IH|ggez@&%GI*QbnSk28jq30xIPhJZ@8u-l85SY`Zqvgp-^EF(?RtUb zR-CNcZiJE9i$C_Doe?id-r^3*EizmQ_9DoNmqlLU3jWlqXB59$tsN+Qio()(>9zv} zc)|`nu)psXIjs~vLt#t2{Ii1?gOffCQkeK53j0tv5-;mML;>bB0ges%P_JA3oa#H# z`W!7*|8(Ao7Cd2RP$V2t3j0yWO^`o!;*s10Z^e&v)~{z&mf5@XOn)PAiFAS+sBdTi$NHhlPxAeYZYP+v=A&eS1`8eyoR))V&iv z)=QXGf}Z_}e$ztg^iKFxUuU-d7Q@u3L99t>wNH<+lHh!ImZ#1 zL`biLzHm2A|5$#Ie$yj<3(b9VnQkdFmKhnZJ4Nzib(VV{(jQlWIO&i+%@+?M@OuTK9>%O8#T5^wyd zhw9xH;K(L$02BdRRZ4A;0@{HLFa;EX1K<+42g0bSB!X0s4n~6oU=uh{%_#LZr&-Mf zztJU`Ku6Tu$7InRhFem9)7_jL)&4iSmv+gIzcHo|eOxNu;r-)e_#OJODx=+97TzJ; zy35`>1O-R4-PJpl9T}nO7jcLKIpqiL-R>{)i)s9_b9r3NE+5m(A$de?sTo6ghvtxYYe#D*Q#^x`-C^F8`Dcf7|+dj?2W# z&sg~)CAjle`8M#ns);-ad#Za)!u}?s<)%pT-+X!&85}JhWymv^{!PcTdW506=lM{Z zT>V=wXZ}L=b}3O_Vjk!*$!!Uu3@{Glfi++kI0bG2Ck={N&=|C<9tg^?yVlKV)6Lue z(XXr2t3K89+^ox*-_iXxNp}8S_XLbbn%&G<#jLc~X?G7)D|5VAPWNLWB+K_h-QA7d zew|_NjcOVXf=KUSb%RZ$r6n)IJxxhAg}Ni9W~A@NP&*Lm-l!%4iKhm7x#ir?sr6w> zB=^d>jr}x~CGUbLcU?oz5M7FK8!POyD!7fkm<^|HRdAPbD5ugZW4l}xpNjFwT~*wl zs*K~Q>i);Zsb1MN+^<_KBk9&sUUetCIRuI9nONK1P+drRiaU{=^=GEIKMW+L9(CM# z<|n<^>bOVN$<81MM}s`D3hV;Mz*P{FM2-d-U>ukS)`J7!5_kY2YoG(#fpjn$;as(;RKu$HfJ37lhR!=YmwwLms~9E*}z^%)}_Ekm0V;zg2BY zFOUUhfHhzbxCHKjuoP^AR-iW+2j+oI-~jjmJOJhDkO4tgkO`)MLa@oZB7?NyevUj) zp!vpqWJTGq^3rCYJKS90?K#lRYD-^_(*$2(*FhicsbO(C4{+0YpcS496^MUeVraLe!|F7Iv<`&Euy&d9i;Lo-HN}nN^TQMId zQ@M;9#^|&vH`LOLrX2{+l?!Y3Jf2H(Ltl6-(LRt)U2S)7wm5IunerP+V zXAcc}{5556$NYkX4+}EyGz@bG=GSBlm-J6A8OCFLwZnhqHfDAw;_%ZFoki$`pJwWS z!_m>-Z>It-5Wb`EcAb;nm09kwW+wJm7~!sA9e9dy%ziAt51Z_^%is}imu1i?-3d0d?cFJWcNsSwk770*NvfZPLLt}n63TIGAIVm4! zqW~)f|HOM0!GW~fmK>(yxY-JOd#j4YVVRaF*|VIbCzm|#6sw9pjOs|MiS8JUC?k(j z0QxGR<0iW6YX|&hwS9H!!xP<{O>s;vPIM2{`WQj0j=A$4yfw)krse(DEC(~oXUApf zBzKa9U_JzEkpz@_PMmZa;f{)UqIeEh1Ha%!pM%XOW0?T$Fxj1CJ#d0~uqrRj!_;~@ zaJPp$?TX)C2cO4_CgbrG0$n}CZ`OQ@JGJFKGKIT7gT|mSNCO#Q9LNJ}z&>yR+y(9i zl<6Q9q=V7&`4so#Au)}x?ln(!N0=klv>=H6ziEX07kz!(e}vjFWM?9iQuxCA+%)%n zwM@2SuDiN@I(owjWkN1#eORF{2YShYhXNG`*)zu-X`g}G=0Z6?hfPu7zvj4Kvy53H zBl0M)cPx?BdF~FDAD74<>i*6WNy>LW64c%+8%kq5pat_UC zIhR~96L)PZe0s9C0wXfh=eol!wiU8yu6vL_nN1h%Ep%t0D*@ey6~ZcscY-C5gQm+= zbnI`U^T7()_!d#Dc(1#n>_2;4KVF?7BEt>Y^3CN&lomj%d67FX!JnrsLg7uGc5=Pg7YF(8xy1pA*gPwW?`OY|5(Z@y^vU`zCkJ$x&z%7(`8H{j^v{|bc3ucbXT>& zhYH<2io?135_dw0JXMMCJI3^g@TJrVhb?hOSuvEqH`xQjZqwy5>h8I?7rW6PHsNuk zh-yoN!sfZ9Jo7Dd>Ti?@OWjH3>-%+$k2!srF;Voalj<;+8hh=z#8Rha*qMi&qZ?)H zGExS-dYQYI<>p4QEH@(Zx#g(LN9D}>GGV#9s`bqKd}i{k&lbPSeKZ^eXx!cuB9D)y z=xV;g?T+ToNaX7Ajp@!k3sk@O?M?E+3im39uRSzfLRV4=5UlT&O+ zx=ci9Ux4t|W?8o~C^mjqf`tekY?g{|<8%0#x7}IAHut`b!XgybY?1442c@$*s}L+k zz=1ctRt3fUS|un%(EI~Au`0+$)H{U!5(F(i@P~eG0yVz(=M?WwGF|e~v6HRs+dhz; z?*zH3t;X^)1V02UhgK%)I<9tyYXPHZ>9m-Wz8`e42D)vg%Qo!Umt*hG59H$NAm3DZ z7Xg{we(wY6@NQ6$EJRRpC4w?recm*^G)$K7amV;hdM|pHoLpwB{PnJTo#oAKvU-g> zu&{W#++TyEZ)11eHi=&wf(J7~YXUCyiv3WX}~Ay|!IFV6gbY@H8WjpzUW&pCAtC+EI7NQ&r0I0!`u(J>)J zXN1tmWI~&Kv@Mf!LL;=vmTPS?p-sqyB!tkmHkmeU+GN_atxd?ZY18(5-RJ$z$LIU_ zc|6{p=lXl!_jO;_>$>jizPj#%Pr783n-cIL0SeW-zmbpp*w#C)?6^SpO4sbt=djv(% z?JVLO?AaUlX#Qb?(FtCTG3S$tRffnqv|3$Vk$7+zH4p6e5z3N=ts6!BN5~CrPxsF$ z&Mmz+gyNfsr>aX0;^;m?oQ|i3%aNzf(Ru`l(Q_<^xXj#jP9;N`9;6~~)ip35DXuz`t=!PE_3;BdY)S^!y8{8e; z)Uz$w^v4E3$4)@Yr=ArbpD=u_S%hy;6dKlPlFth7lj!5VI4kCyL?{09S@Fh6!*fb%z0#f0eR@Ih&RsTYQZb# z4K06thhDq{5iTOagDYZP3CGj&;{G1&H}L62gTV>@PcLBED10xWvr0$DtHq#NSp(9K zp4F96Vas^@dQS`npHni#V3S9V%J!a@3kxn8ep81Y(%`igUX$a^uL`gH9G~697~YOo zr>ao!HaH2q2Tlh61*d>`HK+;$@oEoWeNfr^in@;t(`;FAM#8xt#2Z8VNf58??Vp14 zKrAm+MS(ZL=fFB}K6np&9#d-W7{o4y+YG({jsTZ|lR!+yJGM5D1F^e-}#XaP5YR&Xo0 z983c-G~+go~n8WZ<-xjk7vT;5j@@n@r_^Q1I~7L za3?qh%mQP;T_9EhIlgzA5AKHh8!#Je2KRtHFrwcJhJyRRm%tn_1N;Cy4SopLfctIu z(W*7p1%STb0dP8a5KIIQf$xKPU@3@~wD#XXtcb81_1HWGRJOy;2cy8F;Ck>Fmat*SAyrjb>Mk$ zJ6Hnl0WW|@!HeKo@Dg|hECp|ZAA`SwpMZb3p!`3@4_zB9EdZ5mu0I2NfuDmz!OP%y zupE3AyaGN4egVD+UIkOYYp5Q_z;EEb2wn%Tfj2c7p*c2f(fdl>d+T z;R}!3;5hIXFcQ22z692TDd1i3J@6iw58ekafOwy5{}Oxv-UNRK8^MR5LBd`&pf}hA z4hR1Nr-FZji){Gu7(Z5n&EPihAMgY4U+@eFA+Uc5s=;4C4fqe}1a_3MY5?pDYQbPo z2hIdrfiHlq!B;>%xE{pcm)hS3@mHO8+dlkgiyue8cHk#qNANo63M!w;!kcotb6c#< z0^5ODS8eYNVnL~WIEc66_K6_geA^d+c!6zS0eXQOLA-ylzXReGiG4qaS0MIFAl^0L z8w>b>8FTy3AZA$Yk3h_>+FQ57nk=v;}%i@;~WtKdwq2Al;pfU`lVJroyo2j|%EV-S8k2aW>ggQ4I8FanGQ z7lRAIm%+v0M(_ntfJ?w*U@UkJTnc^-z6kydz6AaWt^hl9fCPix!Ij`p(DpKZOu!E; zzOc^%Uj_dICW1C_HMj#@3w{VHCtL{H!LPt%@Oy9__y_npXy^!O2ED;e;BYV%oCTZ^e(-;E@Jy2h+hl;CApR_!f8(d>i}<%m8nJJHUESfX(1LpxzbV4FY?B z?}7ut_rNhAmfWQr2KT^y0o)6BNGG)aT>RLGdFGE0AiyKwK`wsSBpKzz$#!uqW6P90K})7OG^zyMHL1UeT~7J)7U$APbbA(3Vaug^FsSq7E-Q;$4+n~s4S=y;4W}4_&#_H+zp-w zv%zw35BM#(7yJp_2mS%(fEp8qT3}o7L$E8jAM69>f{H-i6w0{j=;3#zcn?ii>B&wkz*Jm9NEo4=U>se*^K=82jH~5ZI;y>W5|EU`Oyp zC)I|*;D5kv;H%(AU=sK_xDLDpZUi6qQ~G}-Y~3IIzmfs?2IvL82@V3cfuq25a0;k= zFlILR78nEK!!aq>z<0qqa5t#+Mf(R$;2|&wJPIxX@qlYz1r~uDe9`_-;YT_=PJ_F^ zGvEQR7(4}@1wR4Lf!DzE;BBx3yboRgRRhqBK?%GBdVr;1Z}4MqF!%}h42UOd`!ui& zoM*$2&+uaj_&K-=ybRjGa&RYj1v~_P0iFS`f|tPx@CNuLcn8Fzy4`6Y+CSJ4ybksR ztH42EH8>u`qr80{_&sP_i66J{V-r{d?gD=RkApvgrQmI_608Mlz&h{&_$#Oxghkb$ z4Bi7h!27tjW5Gtar-OgM{U7je@I6rFj1d;7c1HjI34Umt(W`+j2>26h1Ge(Rzyj<5 z;!T;oFNnX`v5x@TgOkAy;B2rXxCC?sZ6GEk?At&Oa5vZmJOp+HFM?j+HPGaY_J12c zyy0;l>;Yn~RfWHswc|a%V{?r`AZ9o06G8k1tbI19Y^D(l4g?dy!Qk8A5O6oBY>aUl z3ge9sCVU1~tQ=RG>TfIyeyA2!?>0z`0;57!Pg+H-cNhEO0A$3`_$r zfp37Ihr44S1}2~nh#56|09XiGz|-Kf;2Cf&SPa_Uz>l-|@h*4)JP2L{zX30SKZB*< z?_e3|JOY9RwgW#0yMmX&{$M#c5xfG<0KWj2fnR}Zz-!=EuoB!4eyz0s5#lGqFdqwkmco2tX4rEu#qVR-6F>3&PX@QbAAU0Y zq1Iq+!?(X+aby0@!m)LRwN83kZJ<`YC2D@bd)OOy3{x~BTlB3r4AmdQ3rA%-{Jf~R zf!!k3)EibPs{-!U8{}3RyyE}op4sX(@{%Pyt>)2R)aUge}PV;jv-beHo|!O zAFN-Yx4+8z64NBStv&yb;cb0^W02Gp?_vw4O1sn=ymGy(mewjSRbSLdn>BcM`jTLVW0Xrdr<@uf~+9twjE0O^3oYTFIc+;BDt- zowQg_FE`aH?0&11qM?-(jCYrXQ(H+IwVvKpD)&V>Ke4dlneam72<#6DSmiW=r}X1tyU`6s5a6R4c-rK zZX-?A;4R>{ZE&Gw94CtkxW7SqTTk!#90lyFL8UZEL-ZMrcYkVCktmsl^XM;0SMk=a z@E=L~TBENzPY0SxS9!mk6s+%!H(E-u6pHL9T-+3+G~4NB2}*E@GuBxd5kr50VhjVJ=(kNrN1=#WsY}YYSl=}@`x)6?t{|82d>hK&U)PyN_j^#3`H$l;~|~Y zKVUy!sukf~q&~_ktkqqlU-k5+O0DWa1#Rz&g4SLYyShrNZQ;YP?jE)kwhwj&b`|yu z%rG1)qF~{$C9qAf-LR9etFT9~c7a&63Y!R91=|Wc3A+k=2s4bpQbgDk*b3Mt*nZe~ z*o_gGiG7G4UL&z?3N{b63idYa5bQGSHcT}N%VS|fU{heLU|V5FV4uS7z?_3{vanIG zMX)unov`Du8?cA4uA`9$Y&L8K?CsH**gS+E*I;*GoyXv6V6$N>VDG?=z^=pY!wkVV z2y7f|9?TAV2X+Q_4fYUbuwZF0Y#eL}%nsWPI|;iEyANwO7VF1g6K(i!0c-A3*dtiiafkz(0b35+2|EtE4!aNQ8G;glEr)G@?Sq|x z-GDuW4emM~8NlYjR>2OzF2QcY9>Y3gQhX3>9&8nC>jbs9*In|{jlc`dIw5*_N#4df zL2LiJVR0F{N7X%%K18zc&bFmerFU|<950YcN zq}w8VeIyI-5~JkT^8R)r(gZES9!hhZL&a4e$yq;lk&=~K*mBq=*lyVQiM)7M zsCV?0ytKXW8o6Hh^p$$6>kGsBN|V*<=S5~e@T#coCq-j%p<_qmdHqpDy%9NBB=kq* zU~C{JeSy8E;(VpanqD`>DPPGS`;6E7O4HSa!ZJXbukIzX2jJ5CAk{okhM($rqJ97h zmfm3Z5+MT-Y)0_=B5oiueP3h@lwLwC?I39aHmnaDBn?)7E|LdHBQ+j1;_M)4yvCW3oUPnwHkl>158W(b+||3OS`Pl`z6gHu$@|VJRx6od~cQ7LN zL*()w#Nh|(PGb3B^f=`raj;ax_q&$}9D>tYiy9g&qKDvqM~mbkl9kuUD+Sha--c)~ zJ}j&og40t67y1m7zR}?1n*$}Ge!nndgw)+hIgbO6)gFacgQQXTPFkTf1{a7NlY*sb zL$Bk8JcJoSal>H2u-UK`u&uCtuuHHTut%_Vc$d^?5?ABz>C2;IabHZRON)iiSQO#n z!mzQD{z=_j{tSZgq^f&aq&$Ng@UqB#MhfL6y-Ko{OHr!e;;T-g`zox3?Kw^wf~b+> zBq0amm`$v3&)k_zEzm<8Vjp#LA>gM!H8~laoEazhJs958VO5@nJ$o{?5 zy7M@tMex6&NKw#+n!Cswg!MY>CrCz3K^w7Sf;5r$4py>lIjsdqh^!rLVKnU>+-@Rz zVx)L(qBKX|kFz=hy9RqiXXn^e>Eo8YzWd=e4orXgFIsuq)cy#VlKy|TO`U|=fmiCf z>FMIZB+1)pIyN-CcLa;b22GYaI=u?lImNYLvgH3{>(9)|NHhS6+HC*dO;oj05HJt{ z?YIB$CaUpDz#s&KZ~xy-RI3rt$`1jvw&PEUp58}n5wdvu|8An1uLKN6K-~8K z-9*)WDguTeVEuMw6V*;)_EgDWT)+LlTI-Cmy-Pc(0#9~Qy-Pc(-W86WRPWMGs&|EB zC)K;cv6Jdu;n+zPsgw;>?~3?NI&8x_4coBZ75Sa;mx_ayJGT~BpLn>5JJY0g#zcHT zUC~Dm7J3}1Wy@70G>1!FJnyRiyC2NTm_^|+FH&?T$GJv_Ll&AvZa6M25SLad9Gk8F zf4T~#IuCU0Bd=D`ChkMy(IvEj_e!u6__CAAvFBCsr@a-tKLp!>xu6>pv(gSXrdk}Q zhnWsl9>Vc#r}{|vPM7*=P=)1aT^A#KpWbG5)^^7>t47SAI&xPiBh^unKV5QjT1@BG zUYS3AdRJ9cVr5rVqcU%*L@xnd!HdE)LvqugDvy|fqF1IvF)QMj4poX$nGIEXePuQ@ z4pe4Ab3kPlv=~%oK|cePSgX(M06I5nFv7SKnEr_9%>N^lJ zjSo}ci5LqI9Mht6;h{{2?gEwB&>FA?bVsM4%!WpQ$~~P4{sea>_%n!CD5_t;j;Pbh ztY|o>#Iu5T;KsDO>Mr;`sLYNcFJ*Sr?t%8&0M2yARJf907Ce;cQq27*)1`LIe5n2e z@!YO@1S+eW9%G|4X|KN0F~q{4(DCWV_D-0JQ0}=i*a5_%`l&N95^FaZV?Nj@*bLZm zkvdcAVVW@oKVchSJ7LFRmtnVIk6|4PD`sQVlpb!_F&jgQWoVh737^@Lg}Y4gR6m1x z2-RmIX|^;?+dmAWQzfaZ@`s3yO$Z*(k(6)FO`a=dNsAEtDr_5Ue_`WXDMjhk@JF_t z3e%&c9E0MBm0ZP?rIPYp-GfUd+*Gc}GJdOBi9r7;Fh)(OJ(VC7< zV&;0OW!?5;k-HulIU%DSPU6e;lD7u@W4&}!Gsp>FUXotcggN1>*2rj{lUSF6jAER` zQH7hF#1APL|DAObeP4en!=%@dp))e9bP|&`N*?0;>lpsQaYczmOPn7I(?-P7BGyli zSiLmh|3oNNBIpp|PbYDAqtr_ScG@I`Kgl6(6C$)igbmoSa1%~^gLC1jO&HWYiP4;j z`?DRDe~#{d_8L&?M$33+8>&C5hhsc5fxhXrbu%8_-&ZMrSd0&QZ;`s{apxTomQ#dz zTckCPTm9V@DML@URjoQr9~9cURoboGtpRDc35zv_Ytt|cN1+xTeM6e0R?6X@H!(GX z%LP5eylqk+e7chIPveh@ZNmxRYPzLM+tqrUyyM{A>5rZ+ZhqZ?I^??P$ zmcSG-+zC4ly8(L$>xlJC{bAv-B_ixCsfRxNS^R|A3*+CC;+0nMe}q?R%0<)6GLH-U*$`69qe^Sx5!3 z>Y-haR5wLH7KHGoh{=+sVV1BU3(qg{qE2!BDFS!lL1dn?j!fO==&B$(I(r#(Ax=f_*ekzmd-8gUxGN}{VY^jG+ zT{rw;=wVE!-d{KGhb3)mdz zsU(3PAqid?>ALq73qL~E;P#KC1L{{r&=Ex6EaDZsCvuM9j@d*^KCbRf#J?%h@^Nc! zih_J8{z+BwJ&NFM2p%IMjw0O{k$O~$eG=S+V6p8O2K(j0bWCd5o7*Phj-ltl8!O%Q z{!|je6oe#Ec37#!@BK$UCJb?&HAj&;_#m&FfEqnATO4Fjr z%Cmx^IyC!oLUPu47z)2WA)RgQ^s^iOAiKYeNtSa`AE$?KIcC=%p2GxrqZ>`p1dE!_ zBz#}yytF_KsVH1mB0Z;3-z==TDE+HOvo8FhRJyBy8dQ9W+UnB1(7Q}Jp+-9@{Pr^m zfBSu?FygW@C-7xqX*tHY>d3TfZL-P)J(oe=7}f>fwu>cvoU_sq1&rDBGtH>RYf!u&&cF9)eATEr7iW+XmYQ zI|I88yASI)1Kj{@3TzQ<4eV{$aoAA(*khR2Y#azS1GXHtVYXucr|ed8 zOnu@eW|Yt`wai*51Iq8e$6dh~^A=PK2oFe)`!v! z>BS{Dh8^|}>=&2{4?ulj!LTJTJM0kb66_Alc^+yCYzk}*>}}X3*bSH=3J)5v z*{~I`ov`DuTTwha*+%)u95yg>mOEo?@U@ZrRt|U&Lr-%!MFykRud-fp<-u)ykcmUb^Nea1Rk? zbMfQ8*axOYqx_oF zi;qy{49}q|!op!oVB28(VOL?lz*^6TcEEyRvtcV>n_&B4=V7;Ck6@h_K!aejVJl$o zz>dH^h24TVNAm;YtP`E&g^uRB$W2z7tN5m~tbB2Dmb?6s(rE47<&L7O2O{|w+C1bf zj+X53^y;d3iuGL`5etWS$^+EcH%Bb$CV!x$G;~LX{=(K>R+>9y6zt{5Xs?(2vtx6r ztvzMOXR!-E^^uo%uyu__D}_ygt$=NU?SvhN-G)7e^;w9^hb@O~fSrV0g*}FKd>&!2 z*|1Hp-LT8B+c3i-6fJBbYyoU5Y#;10>^7`x3_f8tBnE-7S7F;kNuWGmHyuw|O_*06 zA$vPD(Y$h<7*ycwf@>QyQa0;mAcD#uUK}a6?1(X4%E^coyUNy@j&Ct08^p~~@(lh!@pKUw zgoLw^@R-3d|Hz|}=^`5ets)WNCgCCezu!;5NsLC4IS82`i4mja;rtRvxzd(K(i2C< z)n?2`t=>0U#sYYQxRR{%5LZW|F(_9xT3+lFVxSl+#>nmTbi!)9<%+(8Z&&RcBX80l zb6iBr3o;QLEC=gxI=C>@PkN@?87vRcPhdaE@ghy!36`gf-j92533dba2-a>fZXj$F zYzAyOYy)g3>^ST)><-NN1>DRRxPC9&F;@1{-NTh#!LDCpKiL$o_oHSA1uDOY` znJ7`P=1tA`8K~zY)A;u=qF>`GCKM%5P|n4i>8? z$vZUuLqz+@@+nQ&5OHO)>~DN|NJ}I0GDkKA(YTj^?0)9-?CegrM9}hcFPPZ%eO;kXPt&Uma)hI!!1&j*xfbCKm3R zDgUKW?!mi}$PGn3X^y-{Dbc%gqZqo)lXvJh4Wmq6ped!R^W;sYAy9>h zum!MHu&uCtursi0usb3-O77sgdVF^t}`dErK~Og}%T>!Dhf# z!M4IK!EV4hE)#d7WDo7OC0O$*r03)=wzOQVutOQ=4_1T^3mh>WrLY|Rj>6pEDLh~b zF@6O3mwZI-TD&T8#8Z=h9Qry(`UdhZz&cmOU5Dowg$cum%`ZFryQu2%GDQifx=yS( zNc8I^K6?)RcCKi8PVR1Qz_XGPEfW*t3Imde7EGln?gI3`4u4^pFZZ^&eoMh&c%!6v zyH*m_diJj-mi6M(!D|jBUgT(USFa&=i3c%a9We$ECyv83k~?oWF?%*KV3Z?#p(+Wl zqLhen>xto`A6Z|73rQ; zl~M7kd`DA+NE1bS|B#?i|E~12^DJPNU zMO05B|FZ4GG+|jJcejl9)$zSgV}+|`g>%K5QYE_rs%)wZRyfZ@@=s=^F|)#H z(LE{g8(85ASmAP5;rw24gln)Yvu=^xJGvRK9hLaioL@Nxgo-ikv1)*D1*YSn;gruNAi|D_=GG1I6w08~K;< zEly!Y^!=0kt40um<`O+wcEz&cjiMDA2> zU#1=8t_`50<}-8Jk$*fhgypzuEX6DJAU1LOM6<(fQ~9voSy}HgSnq-&D8n4qJM}z zGpn2N8%k5ks@C)ixqZ0)m$9hjvWR7|h?y2qJhiA>BKI~M2hm}I#*lXzYgAPXxof!o z#tFYzxw~Hp-?=PSpqwQX&6PXI(3RxQ`(h%91N4$+q@ahQl)3jNcI#d)83A+Gq-oX&|>LfSAO>gg+;C94GNGG3FHqpH(Ha zWXyNS)1M+l@K6kYd*Vo#W+M6>A{LwIfK3(Tj_2x`Ct{Z=-6kth6f03mB}EHqP4rxZkd1 z>C<0NRcu<}<;;CNis3igq^!j+iJx7V+ak{;b=0gF;ad&jobiBm}$&N5g&(Y+RUk=Jt)_JHN++sw}k%WuDeZ4XH9B8P40#n zL`x51W-zgqt9zA}+|`)(R+>XJ9(@!B5N#?W3q~rRND~W1UR`B zz0mTK{EAxRepj4YArCN1EcZ1m_szu=FLf4Ci^WPxiIoUrygXa~75O&jh^6szH+>+7 zHj4Ck+0CVx?~|XGI2teavRYXG>-e@<$8vIRZKZs&5qvu%xzno)qIktzy6Mb1VO}Zs z_AafV;26HEF&v!Vna zBJX&v)!H%S&g5=J9Z&8Qu56w?$sOxLlz61;yM){p?r%z28ym97-!qk1e9}Q-`;Y8y zOLV4d30g{lp{t11xx^$Mi)HR4cK~-swS&p+$u-||Ik{aqUJTcl=so0b>`lkfa>cEr z`!C#9$$_>AKA0z0f9tap+2})w6MiSgaJ$XqZYqSksYdQint1%|KAz%dakI_j?#asC zQy6zo7V4H3sxqlxQZ)^y1FQK2>bP5qWTtTUl;unZaMw`$+}Ft+H;vr2tgZzo$UjK< zCE$*ybN3X=-BL+w3T|W_N~tDy5_dc0EXtuH$-i{{ByXA$>lDllDio58H%67U5uW) zm|O$-rBI(4%1`?yxsxKvZRHclXZb8vPE1IN zavS#|3q>jNq$K5U5JRv{J_b#>tf^YoRM%A$oQ~60&OE}Kl3V(aJLx*HZW*zjZ@s(7 zOoVDA?&n~~pa4(vJT`P)M%kor$*RLBUJa|GksE0$-vRAM6kg8iXZ(`fadu+r^ORo} zSD_SAOAnPRC(v@E&CR0(_{8{XJkS;#AZIL#Vxvf0Ef2J%a0_bS78Nm$vafb0=JWk) z3?X-P2g*jx-C}hsa+k0;791hBg*B$~PjaWQIOec8#*ld0RDOdfLOzR=men+kRWg@V zGK$CQ5qyBOL`s+CO3d{jhTJ4Z{!C2ZF;zMb-hyy*mD?Nno)Rv0y(W7Y(31#55j}c}7#be9k|X z<)@4rRhgq>osM<=6DVRDkBBq*CS~#ySzcEPuWL^%k%&z^eoSH6G1k!uWC?4M{IkuE zlY6qtT7RNo_g0iVat662Z=xrkf75@+t!LQ`V|7j{CjX|H#7dU=j2@I>(ByxbSq9nZOQag}kW7RCb-PdAER98K}c<`OLuv4ncj_9{Q_p6l9BK(mOq zqd0T#k<*oxwj!3?@p(jdzMb)09j!yizkrLoXc@U{S(z)s$Za`K%;nmav6tNSUUa?{ zG|&|P+A(x4VO=g_U3TSJ-qNKMIX#A0K7}&z8BVOk+Brohinz>!UL}7Ex48<|-(u2V zRTU4hts06K^|FI~RRxR4BZMncOcl8+{E6CwL_blMEO)mCHjy*!5z$gXRC5pP$pW3w ziTu-9@3O~{yPWHMGp8>VmUYOsf|I9Cq-gk{xa0EDShs6fR@FSXkLD+VQr7KwuDV$~ z==Bu&>(G68vT_9eLD`kCYR9o^XRvCUIr~yp?RqZVP!^Ob4@w`zH7FvI+&Qe?F|6Ko zEJQwZS2U^^5xrjS9vIEaU3rVrMX+=?h0mslYyP2_H3!HC+(;UnmP$$WoOrjdU!D`nnHa%VW);_L?5+ogf! zqv@3Rb%Wf^oX6@G!0J|@<2-&Nda}Cdguni4HuB8i zNLd18Ev^ofesQOG&h$h-bSVj3Uc%3>GIBIo*$ z!ed$FGPxPXenkEWEOPOj-jkbk$d?q}%%jDi2jtG3?4V86$SRn_DwxUb%=Iuu%y^lo z?B}bfYCsiH8cdAh0!-^h*IU2`wlWh;Gv<@KHkoKQ3=3lj!*6{m5-*p{vo7f321L z^{hk9e&mklhE(cG@uImQH9bS&lHEZMRTF3A^D_km;$A8hBvn{9qhhCXJIOIqK2^08 zoXdJxF`e8A-o)Y_#1w82`P{zBxPGN`u{ZGHil$Ng=$XWTo|M;qu?oK}csXfg$*kvBTy-p&(r=VY;A~=6TVfqo*J^%Tw~i+Na=smn+}p{*2qAv4T)h?s!?qye(_?WE2~kW zuxypxysOTVcia|Y^mSqqKjW#pi`84@ZVN3eZaLpjc%Bnw@547C=|AKjIF(q}huD0d z7_y8Q#)T_!{`GH=zwws%YpdML7RQAiu%G-RS*?;;?L1lS!dUJ6c-&~^puSoUh}A8Q)y;P(`6sfdm653Vt7>=vTlO+V2w6f@b|qITueOR9dw^IZD$-;(bJ}`x z1_)vWUvDOlxy&8N-zto6K+8f|v#`I1BUdX|p2})+*K%8G;05bn&++P7@Ccidg8fS=efyr#hF* z&*qWmD88EWDHuxOVN72h8Pt49@#1obMUHb&;ge4oKGfE5CfqEgNLPZBJ?J!QJCk<;H}iZ^vQ3!)<7VQ^^(lz!lZDSVkBiK+6(tY)jo3VkSjy>R zg()4?)yNOEuB>6H^%M<%;YoM953z>3+G6)H4T`Vj({Pt4epE0qiN&pG48@CP zQA;LK^H*tE)hfAEbHga14_|gX5B6%}DT8{^kS=$(sJl?KsuJ>!<@3+)P40m46yA7} z+(xcZ0b9sjAgtTvVbKzcUp0$f18YJUi(b}P%BD7(v*m~0au&a&A>^N;rFiZvf}Vz! z!!&HinyBhn3QkHR?^r)#DObs$x5ypWkEowQjAkv1u{k-<~4)OeQvPv823B;Z5_&zkjwyDx;C?J8Ging5Gu{w%q zZcVH`ME+TPJ&|0DWwR-~dLo5KJRs&*5F3k#ah%S~=^7n9)=2C>+kqm)@-t}GK5|>T zQpS;|$ep!>+%@UsP7yUbuvoU}19BEwh_T@mEdhTdkMgx}bqHf2Oyg=%z^Cb3Ny*~< ziFGXF(&yyXaxJ&cp={OM=1jR9pYuuO)|1K|v4zr!4~6V*^$F(0$0(5}4`K@Vrdqhl zSr$^fbXLFIzbJkXA2f{pYlZ$DEIusb8H~C?6fJ^pWg;h&TAIRT3NJ1oChsJgJJI2^ z!-($F$iI0rF;t|#1KG;m#nE|4XK6#xL)#H+)Wo2c>80xwKZ~y}Es*0gjogwGg*sE2 zWY|s7D-0B^f%}>y9ytbbUlFmC!W*|!eB)kX9`}@?FHm?kt7`Q%3P-zh2t@$jndn6n zuWGWxAN$#`yav5M5wm@WHLQ~oUti=U@^9ec)n<@8jdeDFb=Jay;>qcYKj!>)5KCBC z;~c`;27Ah;P(Z3My{o*s;3{WfVb!zJRk8v#van{2pk&F<(gj&qk?OhS<|k8l*nXm! zJ9*_>O==WM_NPP>D{~$x@lQ5p#QFNKAI2Nv0F23Apba*3=XcPGA^)qMYwc*vb0qIb&Q*qXkf^C@QLb3W1|@-H1lG)56KS^3LZ`9oOw^Da=h znFY6G0=c7D@v~X+Gr2nCQn_?ctm@%eji;+EbC$>>!Ox*v3M)xoy6_9hHr4jbL4LtORQ@oR-YtV`C4<%kvp3O zF^nr-2n%8nrVMKWX?xeKVWs+t#&+X_KY zG@*cp4@Ioi@!8}rv1n?4CwKE=v1d0P=aYHNS@Aacmo6mMuomWeQMuQyBmc-kVicE2 zRBLiKjH7sUe0FJ3YiUDA3NPM78P~ZHtzQt0B61H}SG-8vBTqBe|3JPb z*1Q5P)&g#eNnA@xM8h80&99y%Cyym3nI$JQin0j_ri1%%Yf_8Az38!h|Dxb@R+@BH znwoLsACt`C`-vHSDVvI)$Zhl`7EdSt2CneYd&%FEr(kOJ6yCUo{A);Yyj8v|Ii)N) zWh^;?e3|j0K{?L=)*4TL%17HWf)#g|w~WBIU_ zi{xK1hNx#Pi=(lji^?>gGD;Mg`{eE&+*weATsWOxB|hIL`)JHv#e;ovFLU#I6p+Kh z6BSMF{Herr9+*`NOAc0~`*P(iWdW+<4kv{Ls755`pbcpGDK%gYp+W&Z79$p>(?D zK}2kY<+%HitQ1YycL}8w#y3Bkl}!IUMayL+tMsDed8}j+zfpK#1o>BTp@;lP{-LZ` zo~&5a{1~0hLRG+rZ@BJ=FE)M%H4oq-&SJT8ZJ^9@ME-|3$9h(sELJJgNIG^6k2sq0 zDS7~3OF7FxDvz|%xxpp9Lh%C2h^c%-e7_{Op43Yf#Nvewag`!ls50}ICxX>0V-+Px zX}M@V-;8;5VkLYpqL5r^apgQBOky=F;1-s|Ek0Z1@5dm)!si>wx|GS+Q!48Aqh0&3 zcOIW^no15|>3*{_}S^RzZam&Kt?p}`g z_}dCT0SoJ8GV7%jOc_Q!!x^pR6Def!$UK@)Ov}X6Njprm?I>^6)zLTZ-O@i%~Ae(t+GLJYZ|sOKvq+vUFC@I9AV~bP8|a znwrZuCy-8SuqtT)MaW{k3u0X@#le&Vx(=WNmvSwLy&+r<%H6P2iQhq-e=)a&IPRQE zCsDEjuKW?KJ8Bp5ui!4y=N`EmS+9&d^a~PSg$eT^j9DxByz=K#^ne&Tj|!B9QXJL45Z(1e zPcG+B*3U@R&ve#L={&_#lYXj-Sw1V%$UpBm5koX3fARexS+9@hmXs_S4&j--;!TPZ z!{e6HByy+qWb(Pzv?X`tVPZKeLqHt4^H^c>vdJAS;`8M0(KUaQQ@?{)GM|{jH8#|X ziXef-()BmXp(r2xK> z)kX?WVSO|GOYw>_iH#a!)Od=Q#Dg+-mbF|O*w|FbJOpoI9W!y2D&^5!twb3Gv7R+^ zhK;G@uMMID)UYu7dXj$tU$5yya+l7fcs`4W^^Rv+Cwv7;=s%LXd(_{ec#$WG79O#< zj}l`)l1JMDxMN7>0!!jYx>zrYZ|X-hb03+WMec|a4rk@5`-0px3@;4F__Y)QhZgdo&1a5CI<4exPBkGEqootSIBMZ zPw8`dkUNq6V|awvz$2eh7Sv=KHQQ8K+=T1LQo^94#7M61QT60@4Yf)-l%CH(${^}AF`e&RDUa(DCsBq4i-{%eC|)*; zTq28FJl}z=gA^VhlJjM^z&h6cl-A^3%oQbIFlWaFncz-t3!g@ys6cXyFDrE&--j4Z zmK;ynm2>%)zDn*`mZ*kEazg=+%Dw#(xjOl|(oq7260K7ynkTo*%Ejc463ItVJKVJt zt=^ef!i?uy9_K>-iRUPpD-W^4rjXmBCDyQ@YPq!<`D*f4QFsiGkF)s$V*cO6vI=5(2Co>m5_Q$&cIRir#--%;<)#)EO$V=8K+NR9R8u6mo4Bl!Y1Hwo zN;{DPtlaySv1XO=0jl|_%AE(D4P1z3u7d@4=>#lw#ByOSkiTeO{Tey*4-s84*f=2% zu+{O+PG-$FK~2>v{KY*>bOCFAbqe|WUM7|zmJ%=dJ#ts@>6m45t6AzRJ|K7IOo|`D zU7-&t%m`IOSBl`r!x_sNa_1p)l;zTsOC!La z(xrJ*cs$%zf}JXga9$lsSnn+?ba`i0;_z9X5eX7$k&xtY~0K7`!bbwu}1iRmm{X4Vm(5Gn*M3s>MsatFOk@jdSogE(IP zC5L;QDmI(~D!wPi=!pqDx^(9{k<7vrmq_73k;ME_YVr4J*)!0SpL^Utqky!3iPlVF z1WQgWOOBBxCtFz0;Dx(|6-LcN0W&`wmu{rwk$ks{3dx-lN*5UF%!gq?OlO5igo!g82Bc ze0*OkrPJ0^J}DQ8@x2}FqDtrDcIAGdJb@x)?iTIO$-PFHxq53`swc+}; z<<7cdT|og+pYe&XOu4g6rLs)rji-!4S*BuAD1K5)m%o6*Epv(10t(lP_zT$UCs!h8 zm`J~X&2*zg$p!33>&}THh591IzoaLnjeMTiSVD=SSakAPbP`x}qF8j?x$@<)=!9@> zjpTU7K+3O#JJ8Gu%D0Joyn0e2o65IEj<|U=?4gJOJWNtAC%3woSP?-iWBn=PTItTi zz)EgbIZPjFE~+v&N|(-hQoT=ccfiIKJj~5ufl3m7moTHEXB|pr9ZEk<>7!!l!m7Db zaGyl}A*@3&b>wc~QDy@7f^}Tm0{B@VSLEU_nnZly^%ADy5=0%G-T^E+78aeTHz>DQ zt{PEh;a@5bwUz87|2h_*SQZ}>t7908kGqZ2vsza1)u$Gczr>@UD>1DGx zSE`ImS~E#~?A9tR?Tx;BHhDNpnm)PqSKsdt zu4-*Di_boh2TR6T*K;;3XdiAF9)5nhaQRf8)GZ~Y^9Pg0uiGcr>}yvsOG`;!H&Sr!0y0?Xz;a2*b3Mh*d^Fi zQS+(%6~1YhUk3F(2^G2o!AlMAp0@!lctFWE0{jmR6*O`DvRV97@bf>!sTlzLa5(0z- zB0HFUVKc}gONap@0wQE*ktHm$i6kl_ARr)6jKe58z6>hEAR<8q5gf)rKn#k=FsO)# zh=_m;gAC&LJNMr1PUm~yex83$ovJ!jb=G_Cxi{V0LAZf4&J8{4Q_yTjj06K z52`_;3_iq$d4-HW#6kJ)NWucgz(sHav}0XK1=%16lz{!BFz(ruR zKp&KYd0;2l4-#UD6kGa|)08&9VSOivs4btN2YbO` z5XU~Q56HWdu`>!{2B-wbz-e$1+yJR;wsH<`O}7FdHlYE5LfN z9qa{%!3l5{bZSR~ff-<3y9#Otu@&qF$G}B!17x?yF_;Gyfz{wVNbGpd2g$t1I}k0c-~6L4(dX0Np`Cl*iC{L^4)%h>AUp|u5C=MeOfU*mjN{J?uoSEVuY#@M25=?Q1t13u z2PL2!ECSUaIt9m|KPUj}!6vXB>;;EG<5U6!qrePM3D$v&AT^C&E?ksGGl2c_^^u4> zk`mHs0MH-gg90!cEC7eW3D7u$ii14xs>FXBaYu!b$>aw)U>;ZmR)Y;-Gq?s+7VQh7 zL3fZ33cy4#8>|2)z*%q^+ya?h=|r#;tOKuti{J)ubz^3M>~0L>c@T@hYOn!p2K#~P zj#H2T5;U4M&`hxG$7~$^1wJS15|)`xKmzCv^1(!~ z0IUa_z+P||oB(kT5CoV3mV$L)D>w#DgNxt>a1EmYhdqRIh*VGl%E3Ia8f*ZY!A?*O zPJx662?F#7`Je!72YbO`5I&q91aTl!9LM+)@k+?u-~c!VTqAHP?T?Tz7J$9r zEVvAAflej(EvaCnK&%4?z-e$1q?S@ckORuWJg^9?2KzxZxCZ){;Rvh%+reIN7@PoS z!7b2uEPVkoK_4&<%mC}a)(ZZ(#xV*&2`C4v!A`IrRD)9>VLa0pbO#H-3a}m=2A9Dt z5IzBCAP#f_eZV*{15|>gU>(>Enm@t_02QhHDF^ewBCr$e2i4#_xCYcj`V>Ti1z-hO z4>p0b;4%oGgk#VLj05Yyt6(cICgTva1F4`K%ma%i)Bl?x_JeA03aBYK1JR&6$On7D zVQ>~SF2@n*1Tw)WFb>QBm0&4Y2VMoc!2xg#oCX&`^Qi;^QbG1q`acI^IM@vKgKBUJ zOq|Bx0SmwiupVpzd%01qZ+}a6?K@MEp?qz&x_xw2b&? z#8(XuFQ7Cy3oc9FlMyL{Z#+#@3uzLN4HkjbU^Cbcs=;}14X9@b4D<)H!2+-XtOt9+ zVR`o?hyR(2Xb_MGMuFYn05}GW#kd3QK)E#hS42w1;UxqG&Vuk~>0HnWauuN(FUKj!1bt-R zzqrYL6>=-s4Gw_j&k-_61@pjWupd-|YoNgjrYGnQ`h$E>05*Z`U@tfeZh`QX)DQFl zd0-T%1WUoIVCzaXTJ4574K9Kkz_p6Xf^x6{YzF(mDR3UB=Wz`3K>?Tuwu2MkEVvAA zfljM&An%-tXdQoT4aL?n%)mr28>|3l!DY}`9A8A-(RrK@9(WaO1-pT;Zm zR)Y=F>kDr48vKr6Kt3n{o4|H(0$c{SK->!i12RD#7zM_G8K4p@1zW*xa15LV7eUVN zX$UY6ECTyMH8=&%g9htWGZnp_?f~6Ef3O0q2bU|Z_k>8(8|0<$$SY~3PlzkO(wZGvh+*kZy*vdTD z+R+i=RS9SKO%g|uv^k3`Mas@bWMK8hv)Cz9&7v{jLwx*tv#=Q5-TlHKKLGXvRwThCn?h50@73& zd4T}REZOk`zb})XSat4)h|itm_gsRVAvZ7a zBVw7-^Cwej?oZ?jWslAk$xWRrmY$a*?vgcEyDU++0sTuLb zUcnu|Or(=!nSaHs*|sa_q{^2trN>p8G5RWiE@&s=Bye zehcj%Z=rqQ7TU#f2?l;+egOOdO;Mx@Ay+muPXO-H54$lEYJ z)QokvBa-lS@HUE>;`uG2o4(0wrS9}GnbZmK{l?GcmhuPJ^M9jti)6=dcq*22zY$l- zniy|}qjb$sZ;GRA%|dS%XG-Fl9k7ztT=MFw#yXIs$WWc6%0d$P-r=n;`yJjprKuC@ z8Wa)4IML6Pfld^&WWG)cWt&clnL zrlImZ-gpem^mseUM`$<>%M%{&9kSQsZ79F!A}6#)rrbn>8nmfHQYb^~;G#&Ltb_Yv z*`bq?sta|zy~7BqOMP!|M`_ix`rf}e9A#DM4ZWB6^*4S-%WGD2v={Bts#RX^Z*JC(Pm@Z6OA}iW=4DUG}#f2g)F(MWrfnADY+skYwEoh*IP&=E5=)Y zZHzZd9*2-VQ23u8AWP%->Bqgb-s)6DcgO(&`HN;CX09d&~9=BQ*yzvia% zxy^BxCEGN!P%bs6K#|0@AfjR!-2x`_OXo`Eq|TK|WURNRvoKMH#d`0Sf5sBYhFBs= zmXonWkRq`y&AJV1iTPAn(h_Ex9BGN&%&OZhy?=31<1MXdyG%K$lPvMH_I7N**1VBD z1@?=tHQk)o+S`y=Mz_XZv8>fei5$^Msdy5wS1joX-a~}syc1@sbS073?j)jlcbd)o zy5?udnLABy5p7IwUE5H!P$slt1b)~Cd>nLWORh|YwPl!6Oz0i6JOV4%%n&5$Xv-RPez8QKk%Vp*`IdSI|jhW4Nf7|2U{m`*>?+$6cJ6DDv^m?<)?CqqA3w)KRWDi<^}P1@W| zE?q|JBtzET4Kq_d(Mgs>WaFYxdS;U=lDRsUBCltAJ2*=d<#;v~Di&uigeB6mmpRg= z>7-0H_OeFWaV<=$YIKixj05Y_dLzx0jlC(EC7<-hUa~m*ppzm!`

3LLcH_4Co|X zPWGWG_|34s$ckiOU%hbmr3n`G^(NtTS6_;j%Jsg~i+xEy`Z_&PX7HzP3xW8v0Dk<{hKvcMx4D=4v-R2pDPLgyT1UFfx4I+wE*`jkPa!$)q zB_@YlnhedseY!lEgGz?%$w8JWS9QWwU@%Fcj2w(+k*pewO0gUnOo0-)t!1T>oQwN1 znU?GAs+aC9xd@Zw%Uo2GCFVYI>{jkWwM6FYq*S(PCgb!ze*CR}o|m6~&-1pY%)mUv z>@M<5@fMvcmNO(WU1lU`-_qMKeWm^;JDp zp43U2>==sKbUCM!42is-sA+SZWXan5>0n0w{n%=s&xIi$Qx8K(Dio2A&c{ZntRj(L zG`~9E+fF(?K=7^y%;38`fJU+uJ%ITXS*4Ryc^{^2l&B8ep?#B+1E#2q#$@jWS2$P!jp)DD>BlVtGuHlcQKK z$3G0C)59<_WWvMd^0w_^vj?u~q)?JalN8A`ofOM9oiNTxWX>4vdkjU(WbPPmKM60u z_hHRQl6nQ$N|vDo=+pQ*NtI6un7nBcS;)%$yFyBr6nfKe{6ZmOu9t;6pduYm5k|O( z6=9@Ewvk9yF??4s`X$n}82wV2TTHW-$(CY9ZFC8~FBY5ijw#V?SAzbi5*X~*G~*Y| zIIJ0Ia#J(Lm%`{?3WKVb(p2n>OTFEsX&Lv*cDUx9%@}cIhFGIgX4wj)` zD$cR+=ZuBlf2=oA-@(jBZCOc;konrtMI7USVx)O?n- z@i2a;871SXWtO}!o>~^lN%({iIf0~DhE9OV&W%KxK7#V831$bxJVFO-dW1%p_=wp7 zuRmgTz|}|4Pm$z_B&jlOA}xk*ov@Zpq!k8C!btN;)QYY0BpB~##!}5FlwF$9elm<( zno%qrCd2rhW=xz6qf}ndjJi``oSMue;3`mW3YKX>UfMPPhr3N?Vl3IT9H$P1~70FUq*STUzol2vnYm@MzlrF@E9 z*G%^NkC}eU9z({Dnd)4I9MQQL-K%5j}Ag)1n?zDOq-vb+MLnesseGWNTbFbm}# zofOIZN|; zOVHywyTokjzHM1MHpGjXa=U~GSlz5W!`@JSftBxxJfcvC#AA{IhNApgXLICmYWu{ z!*dL5?hu}%jo7>_d=8x?*`t$Wx&9ogY@t@5lP<$nz+@DVlkZm$!u}QPN3-O@3e2;H zu0**=a#wQW``Svxi&k<+QX;Rfq;#nqUrFgQiCBdrZuEMtf}120R#BE)OU)(VgBJI? z=JI>P&r>8tM(ZS1);^E@G&%S@1vBOP^E73abX|?CP^PVhStKv6rX1a&6ShgKDZn;q z4FN4%LqHSPc;h%`kmYMk-@DdOmURO;URte%nJT$!&D?x)^3Syt+P;=M`vIJgxkovb znk-YBc<+cXNgkLdCMITP6;;&}?{6;r*IQ4iN$V+iYvIDxEf_blS8j(*gllGTTFXu!{3! z#13yu$2@scJ2)>Z$;F&E4cW@n*WVub4dmbs+9SU~Fo2|_U;z8YQRQvcVt-9BmGvLE zB{rm(T<%i0u?(*A)^BR&t!7P0s!{6=G8Hpv8??G#OvwILZxG?H=A_c;(+kJ)WG_(7 z2J&ka^_VUHtn#*QIos5<>XAe}{DEAwEXY??-WDyajIC7Tcu>D_)>h(@>PE@Lo!;=K zX5JqTXDEJS$7I<~Z|j(2THP<^$)-Qr{)Qaf>5Yl$Zv^FOi8bUtxsAM{KjXw-KCMQZ zCN$D~JxY6x%%3v2*RUG3wPaT4X*9I|Sf~3Px{URs^ZpTN@hsg8#<)NH4W{k`BJX%x z#8??ysYZh}ZY)RM@wTdH+&CCy25secm>Q$`y(dnYTpH*Ki)Y)Sz5ETb&eScLGHd+g zlH$UNJlqX-pCz-)(1?-tMBLuYtdLA^;`K#X8B-}UEv0JtF7IE%^o47W_YLX%9=B8P znd@4Y_gFJHOec{KVaulX%p=T$@3Dwv$@TZlm8H#ImW?7Axff=!EYt}H_?lTN=X8z( z{C(aoGI1aK*_?e?NUEB=&-+|BtMcs+@sJ|v2eHHf(LvTVHnayR%Z64nGo;=j7NAV& zcZh2TcV#mVvG{&;h+sA!Vx8v>^#~k-zj=sK$vF;Hec0dg>$Q6a`#-#=8FdgyQ;m-8d2o<84RRK`34(V5_y*JSo3wlihb5}vqvW-a_Ow;rq#D3T+hE{Z^`w1`L_tUo_~uOuIDl9} zB~|H{y>0cu)95P*Ibgd&EF2qM(We4ev2^1KJH0aLaFyO*XIgd@HBKY0niY6o=ZfU2 zPKu?~&lFnxGldF%<|e*WmcXFwo}am2NKTZiKcmLOgKH$*3G0M2A)RE(Hl3u)nQO$x zjl#dpxQG24CN~QIHl1zLxgt69Z;Td8wx{EO-K#a{@i zSdMFEiPXDk7VUSF9QWNf36LYbn`mDEc66zQadCsMfMfaMlO%H;Mf`hsnG*I%i0lFa`V zN6E6|S9J7)DC(9f$+wa5EakQt%f{Qt7_vH-A&q`x$g_tW_#5UZ{~JQO{5R9g)!)!b zS<}j3;IA2Ga1*y?xj{3nIcQLJ%}qF&lI$Q;Dn$)itJ8|E^V|2v*Fpn-MOLUF{ zEuBl33m!_bN2)`PJyIPC)2lkiXwJe&g&XD_ z;MH&}B}s?6s3ptjy5zVM(@ClvsY{$`Qm-B|p77Pv@ycYKE3JB^o>3({fQ$GqP1W$&~k-8Xcu+3{}0+RQr*b z7%Z?@>m*C2#ZZQ43o$73Y(eLWrCu{CT*5;i5=LJ$n4J1FGm`b#KSNdqG{<0EbECaH zuBm(|!kOP3%~YQKkfg~uouo@l3*Egktc4lX!WO3YZJNm$d<#Rb*2%FrDv}AYs1(Z! zv4(j#rJ3xYTcVOB!*o(8FSMjwsT^;K3P&_? zGj+o8Z@d}X8J+MXxfOPJh}a5E4kLAvB}ZDJS;$i)(?`G72(ZSGn6Z1R3ERtOvj6t~dbc9(V zxgAj{m4!NCrR`|+)CVQEJDRoa*~z#MpUXQTOpy;dQL|LJ*@>Rwj;S-9$#~UCp}c4% zM>?A>>UCidum*LZ0C&t?Oc$@{T)G_B30sQ0D3>W+?;@8alkY->QL1xAa#G897a|d6 zlH8L>j^q7AY%;qN@xaDJ=ZeIWgbYU{^1CFOp*)F!%H4SqhIk7ii6PBxs56-?56zNI zOJzD?*6W0aW;$Ubm5j5ZsxB$UbSD;HNrTH>UK(6h>vWofWBGK`>il%0M;JGxvM1dP z@OnBSB};OKX|^bX>GNR*v24g-`uwV?V^9Qr8xd7c&P0)8^h{$6F5b_iG`G;1REW!D zmSJwOMrM&sl7(56NS0k$=x{`pg+Gp{x>7z(Mt3F05mi^y=s}&!6lXUE#GG#U?B9*? zTPSm3&`>*cQY=@ypJt#n1 z=_E~@Jt>#YBQN5}tSaki9CA2{s*dpAzfV2;7#-gYbo)q;VyfnF>6CMus zrN0*U#r~+i4BHG@($|dseGIWRmq=n#}nGNeo=nX)zqyUciChkX{o-sad+#@LTyeJ6IM?v+DUP+a^2dB* zi0j7QM{R4~2aLWhqbb%*<5M0mM!2fep6no}#~LlA{9{)`$)0Vv<<|#{`(3ATBYEZY z%d^7>V%;|wHM8CaF`AuDF|wJm{y}57YpYf^twaq+IWL-Q!Q)1>%o}d>ab1qo*-1tx zxjfv+c2zH0ewURk7(w9WI-sp1i~?8qxA@3@$cT|HBWZ?B-}$qvbasW-Go{yccB`E& zaV2VRW@ukML=@ij1tr(ao(9us+iIf5GT;h_lOR@@qv#f7c2fM|Lq0-Oz&xs=a(xOt-Gk5#gz& z3@Xu$r9BaOoNO1+PnY%chPW>4 zDp28ASv8)f>~B{vN`4-XZ<+4^Wv=y^N-VCzC^;j{pTW8P><=Uk`>z4M98oe7Nj8KXbT~)4|#T;ep z9%XRGY1d}fHPaa7GPExPQ!C5Prv&8<4H#&Z!A=tYSF1+H~kg~l4^ zD$o@+hr`gv7=b&rTQj@uF=M1_wzE(sdc5%<47y*o*L!4 zp=ZP1$7#F0dXP4sPbGKi{x=8x3-k4$*ICo@&H0R?4dyVcAhZp-e!DAlyW3Q>BvxV| zPj|zLN+ZAVUfuG1#*sQm%k>~b5+~75&_a9l)GT;HPhoArbn@jBMy~6Iu7Bc_%#%1B z7IS-)s}gGMQ?T0UfXbgDf~`zDSRJL#0;8Afysk6+_VVZgqtSp-+VN}pkNKIT&p6GG zL&e>%`JB+&p9wW&6Q^v4yTA^d_j3nJ^#Y?!#q3f2!}MvL^>L^f<86|PO(`FVj8j1K z<51JP1Z5?UP6{bkUZdP}RS{CIWJ<8y^ha0KEElFmmCNj>38Zvd6#`BX&5u(}85=A# zYSWxUCPe;*W`PzMXffv7BJ~Ws^z=H_?aU)`xO69d>yn zL^kRHTTQogamC^g;r%m$!n|pJ3Xx5zAsavO@5nj^9FCn9EH}OMa)@k3jS4D@WyYg2u$@cgpsgzsK7%?4s`Sod~c4{am#0ddolWNG?E6HADH0!EXqY@0y zPw7sbq&^Oj9jj4%p{gfuQeL($GSZ3q4UUzAt#iB5uc~MJaV_&l?O?MIR3z%e#kw^H z!VV4t*yBw0!VvcDO4+d37~`v4m8#S|whNbnZ7eZ*cdG1^&g=OBwyLyAs=_<@$T-(G zKQ7f=DwY_{vRc~=UE7xG7-#wI11gkVe^G${yiMtFJIJ7=MzgRDd=chg2wAYyh;cNPmzEltzRH7rlo}H#M*Ez{97CoH z1Is@gOgC}MbWlA8DE{@r`gnA64qs-fAB6vyJ>gCD6{dQx+?qiV>;cp(ZdW?*Q|cc9 zGc}vPx%v>kvvzhXq)2(`eCf!)Wpe!=kF$FA!buGTxsC!Me z{zo>xSHt|6>>DQg`$zaE8jGt;cH#~Smfyx7O0)Y4|-qEb$n+WH@= zKDTX~Y-6Q1GJZDyCR>x;-(qO$)y{$-|ywyj}Ku7bze7zT zp#FpGOrV^9*6N-gss72op|uT^V=mbrhsrT~AT}Ut5xA66FkQt~^1n%SENNZlLhn_C z*jbHuCOEt5sWiK^_LZY%A-hOh=}*0YS1r3w6)#tcN2KPbp1RAXv}~#>N5Kb>RO{s?5JLE!1p&)!_dq5;Huecjct4jnsnUC_UPbWj0neSd15Pf zB=ff#x&e2&oXR0Dzs6wRxs`i>*IzRt+`D1MSj@`-ro-)2tu1D|H~pG#z^t&C1p($N zk5i4anCmoCyLG=2?&M!@leQYsE~xRA_~M&JIzja590($No6*dpro(u~RB_*gY-EuQ zx;WJ&DXencA=R%LF4?-xh@rHbi(n_q-uZ3*z#fJfE&KjLz2e?7)t00<)$0t-4!g^07dm&3Q$24MYBs00 zQ+@Nlt4Xu%M#nn>-WUjc>EGYQs|Sw$X-GeJbCnVl9=IA!pQ7 z+5R>+%ZGMw`gHwma}-rPXtwqa)<-M^GBR+7!87|EMg!OLoMWWp||im=FJ$Z(778szp5a3$|=hRb0oJ4Vab?;FkBV}gp40*dZO zA!AHSj^|{^-_ZLXIL$5F`ye}6!XHf|j!Uvn>--ymW!)L}R~fz6h;i5Zt5c;|#d<(4 zw#W}4@3P2$L%v{<&+T@qWfs}|-GHSI@5-M24AMUzFfDqvA8@J>4w=8#h;%nR=u}P2 z63$i!rOV&h9%RdazY|KM@0=<_lKyT)IR?lRnzQG;Q$1>OJSpEhRXwNV{+-6}@q<%! zbD1>nfn3p=Yp-xuU~0P0LoSl|4{7ppF5f*Yi+`5F59pJ>$>Ta%E59Rg|5!gv`7HTu zIjRLO$d6jkxmg&q%?#xs>Gcl;qs+wpFoG7ApSeL&0;FTRyotKI8qP#ZuY2<_Wmsem zr0wrvi9dkedo9A$KP=(G*f2(d>2tZPMCcGRac@8{&C+SqQj=!g7Q}_ILYnGNi{nGo z|0XR++^x9g|IHG7D^s=LqLut?B{$8)?MU#);%)>v+j6i3@->T0xid^Pv&dY?Sebf| zo|z~^4r1~nnMC3aZyTmOrobHm+1etLAmc6dq4I@RFPC4m`qbPo^|f622s?DvAvi1Z z!_*t{HJ07o`S#5=vhNUN(TFhB)Y5xQUPjLu@sR8}#MpdiOqd!eUms<;E(lYjy*^kT!Q?FPRXgJ63&>aKWSEdrN9Q}x< z*eXAgxIK@BsdJX$i;%O-a-5C#I)X6gnJ~`1&2|ctH#O&OzVmOesqR>6aSp(_*D~N; z5~jLaZGdRj@jnYdqBs>hMp1Al}ZDMJoXL#Q@# z^fTJ7^>bmYkET2yvYSOd7bFit9=05;m8sRZY|7EV3`=hr%!DpOYc17 z^OlFlB)6R@)B88ZqvDke#g(mmuRU();^Bvt&cs zE!Ye4gr(4QeV7_;_2Dde;#1l^TmC@eKKVakYObY|zcEm`wtv!nXpYw6O<^kAQurg} zXX5*a9(gTH-D5HxyQJ_Kc22|t@lK%OGk5tL z-f=|Yk0boo?!Y*5ycZaxJs{hg9(eAv59dgR22gaoCR0Dh<9i?Kh1V?F@t`j1IDwVBA^GkVNXIPs8a-#r zLvkBqo_2>=o!zqKb0%K*c z|0!Iun(V*9GRv%xKb$n0)+wLT^|)SZbYZSPPmtl%!TfOd;J-JeL_*?DxpIJz@B6~N&;-o2;Uu0Hdxf~^y2a8LaT?|tN$HWnWpAU^jpyW zU->Ca@jYDTCr!;Lv`LIlocNXWIz@LiyUf@Qs7$O;JkIwZvShjPFQZAf(pigjCZHJF z9)Crq{pnAdDxGCfR`2bWH&4+M<4fK}sgAZ5<=*cnBP)D|p#ANauEv)H%g&kjJ+dZt z-8gItsrT)xn6s7BL+b5vxqq%H+g=c~$(c}y%+N;w)<;+1j-O@A7e+Mulb8^-QceMa zTJe@v#U#}(M5|`&O)kAFL^dgKC(B^-rH9DI`i;|wle+Xk_Gg=uPTnun@m)Z+#vUZ; zC2Dew*5V6zZiFemw$%Kj)5F1n3BCotutT#M>8do~krVatOOXY8Ak^XO^7WTS(~3FM zceq@E=FU)aYP3i3Bkv-+*EXJ^a{C4y4=!}^1FxK{n4b*AJKy%lfsLuiUa$ks2sz*$ zTv)%3D=;oI#)TB*Fc+c!93VqYpAs~h;CmBUxy{H3d6qC|dVIJ``Hve2rbg?{nLZd< zlsLXJnzSyRQ9{Ol>XV@c`71#GB>0{}7ONE_NBUldW?-71j9Qcbb7cNw*^H1`ALet` zbp=j9GL(JLg%#ZxLy*%QI_QsO-*qF6FNr=4;Fwr50d4j?ZdQ?mUm-?u_6-j1r zI#HM71HOxL1x|r7Yc1>7klCHDG6PGCZUc|{w_N$!Xx1aGsY|_P>tw3ZLc6-COdJ1Y zj7#xF%;qPvRvn|7yVNJrYmf7eI~}a4-^aQF=bV|fnyOw)7l$amGu)f`lH*)#Z#3Q0 zw>jRW+62rO`dibC_>)#H^-MrE!+$J{EY3F~!KHrIHlo})ZCvV#MfPatQUgrVu~2$_ z!+IF!YuUlYj@{J!vZG5C%F%Ch5O;TSDHeWcr|%zkp79ui}ZnygQ5CK7nfRLbC89Ml_L4`S*|Gu z?{WqD+CO}C3Ee&si7xKN-#lwHsqm;CWQqc|0xPlE$S)zw4#+|){S`7EW0;?;T0`!? z$QlG>eQe5_T6L0K>Rp@Djf2v_hi7;V_9OhvWwEkUhmeZ>F5RVi*zr;6K%@>;IPrLQ z)&u(@RlBjS@zTH``zjUMSP6;oclTrH*&$>p)=>N7P<5SSkvViTMY+d8Mwn#$Oh}&7 zn4heWWn;>u*O5)IN;JOL#jS&GI_N)0)|5y zyJLTs^4g<4w0_Fhb%5B)Q)i(RXv-m`h^?9Mz0w`lGJxWf@!E8oVrTc)2H_(^PO#ky-STMO@Fl0{R}BPjPAjXVn|*1V0pev{lO_;erH6+ zcYM&L{{6q|DHS(Dukic6)edi%*_`MO+)z_mW*g$tH^WU`0n(9^YA!ISO#k(0K zb`wyyKAbfbes44l>)=}=kAKgG|JgF8fjsfO5n168Xn&(;o4>DOmDDTr+sHEQgWK%D ztku&cS^YT0rS7+#WY?Mz+2tjVz7Na8 z7gz>8s{doURgYd^Lth5Tm$sXqUaGvtnmcLwU*t_)Y==&owoXiZcb-fA#ZpzhLdHPJ z^oftVIF8aL9o&ljU^Hv-7##ogycZ+EE=WMz3trGFF&@v$=p;`9*B`V$o@A+R93X^v}OuwT4QTRtuO4y-p7{y}9!P zmg2`jJ{iysonaS{J!(3v7*pX=ZwJ%@OBHo>xf)lp+y`W#8{@l>c>}WG)X^Q%vxe** zTSq5aHW=CKHjkc=F+Um&-T#5v&59@a38t-9zZjYCEo40Q zFh6}l7CWWhdCH~w+4HYY$ll7Mep|?T7ARM@gH39Oebm>BU22VvnoscBpk*C=GbQPg z5mVt=y(~Cg`lyl`!%(Sh$iA{y>d^8o*UDAFLDtv&hEmIqcDEJTAFM2oU_%>s@blbl z+A;N2a`2MTfIV61YFFR^U|%(*M$_=EcgRX4=_ezyrLTbdfm3!J`>M%#wi9X;=j*;s zy8OhtJ9$Rmb!;jF{zE4~F0vy53;yzE=X#p|Ue8WEMLE0vUS9l(1A~ztu_S6%la{5E zO3C;qL%&+ru<3H;C#EdFuSt^i44RE?Fa1KgGcob^AG=hQ?YLjaWS%~Ks1#ntN{N-s z)JfC36Vet{(*yx?HG_7ki=VgxxB2~QO}W;e>Z_^mvJsV)1nIwG^$%L0<&>}F7>}`S zUjJGq%B0s7A{r+TlgQR9Jmg50!Yf>=U#3(;lXPs6H?OdS%o%$sz;k~O+0GQV@Uhb< zxBEQQw?{o8@mI0Gjc=yI!i>`UKX-AE+v_S0zJq*FlTBKCRL>K^m1RJ!MXfKg23j%F z;~4^dpH+SXWWHHG?9oZr#PKr@!qjj7)K_usAb!(bHSPt&d^69oe7h}!gK7n};d>WH-d|tSw{iDe zaH+@aS`V`Q>jakX-5*?m9mb&G#MLr&1ld+we^9MaGXJ99v0y){;(18_v+$e{6UPT^ zK=y)dBB#cZq<5rUe{`vYfGl)JIvSb(ik1`7R8uBBj?DkSG{^idZ`+8Dx!@=6=K@AU zuOc&%^$N&BuSZqLn#quV)Bc}8jq9TrP#Qm3T@S8ep)#d1kj0uYI3AE*H<*Fbrhn~o2W}1q*IJ63G;*tt zr0@ni+B1;RE}4JBh>X7(={Co)4q$M|{FpfBzsPdTBCYO?atHR0sMUy4sZwO)oTfRR zti}Jr$#Qs%^!&w$=}{-%9oVAfhE#6Kv>nJEw=14o%VbI`w^}1_{=#x}0P>-LT4;B) zZjA|3&AFkqY{6sve_{Er%2>4v>OoUF=S&P{*?-4@z>Yo`K5N z+_)VdusB5KucI{`{(;PY^~|lcO`o6aRvfLHpIo+@0jv55WoWuv{o-$uK^bn|qOmnY zdMhDuKC=3jqDw6%Gr-E#X_Q03M-8xv$B0?tBD#4jWBhncHf zww6`Z>oWKjdx_n>-73l!+!s*LDv61oBI^_|U2{q$B>pBZ-(s$~)bIPc^)}4>)ULy6 zWG&1(RQP^{=H(e%ujV_yyt$R*R?96BzfPckC&T(URIkY!k#*CnEuUOfI?qRVw8^x4LO7=cm-h>RcmGC#FtlZLp}`vIe~ zL(1JX)E(Ft=BiLxW_N`C`^H=~Ii%n)Wa0LqRBhSlhuyqYq$hBTLy-Tqednpr`g|aT zw>d5P$7r|OWIv@Cq6&*_ZF6Covfj-N6F~&2FBJ;w8#4a?MI#GxuZ|ktV~vz)v>e z$nFI)S(@LZVoLF+S`x7CAF(=j|~$L_73Sz82XMTf24yaa)K^SA*lmROlB>y25t^TK}?_{tU4a^Divl z@xL$={twxet!`Cq>km=IrT(INwC{V<9eDe1NXU}R7kDFU5GXgOct*{Fw-9a)2t%jI zrfu%P+qFYNMwLf--g5J7j><*5pd4mz-OW)W8D7pbKSMb8ut~Gk-$r&OfP4E?}>}t*;q+1aXGZWJhoXp}lKd zR}&Kdh|IR=Qv1mGH;}bE^9ZtD+9LZ{ZxsVM5Mt=F$V6oRrDaISEpwc&!%ny2HC*#E zq}Gy~^o~E`hY}OllNlUv5E}9K$owy0hK?TIC*M_bu7r-%#(%Xd5aoUVveIfDULGKm z@xS`wA>MAgll82;hfIdVJABbDsJ3QXczhe6@33rn)LUeNb2YU0KScHiQ<2lCvUeE@ zIuq4n4dgok|26yj5tX~gt)8`SVusW@iTmeXx5~Bbb?~*_$F*5!IEMQYx?{j#&8Hb* zzPj%RH*dA4Ne^UQ>`;`k^sn zGGY1;yz|v`|3G3^70xIKk=3k7Lia_;vTdLFwKj_fknwJx#~0=P4`i81#y@;CxS6S4 zVuhAjYJY?DU*Kx1eH~D9H~vIlAMnwHEqfZ7;y^Gp1D&nbAxjL%LQh!^AmePnWpvBvNGJ)qp> z$YRYPJVzlH$HdtY(gkGU z+DMf9s-JAa749aPRC`T&u+|l>3+4Q0un%&w5VWUMZ!I%}V*MLV=3aTZzAvifOOXDH z&TuuY#=%PII6tg)8#Eyxm!jB4oNk&G@Qd4|vB zXlSwXVKes3d>eic`jI|#`u znVS3+vadzna|hjFkpm!k8C5GRfNW-wFG0pya*0Kb zjbwLZksm?!wa7+Mx+_d$36MUEOoQxbkp+-3a=%WlCCkI3+iYmP2;2$QL1bc&9_&2FdFYn*0dT_FA_! zL&)TMmO;kYhX2%7_k>n1HvQqa=L`C9=!p^969)9)RB-7e!pPKX(Lw?Vw zj3U6Cj@pi?Q3%Nkyl6O=ca$%q=+QsHVjOAK7Mt~tAnSXODVT_C=%lWEVY4OmYPz7a6$DbzS&|Diq&>HA0e_qS)Xrb2{yG z-XR4|eJ*!QqKALcFh%_!+gju#$R-x~BxHT@#b9n(qC~{dG%r}G`%k8p7P)r^wA}xI ztYZ~8lE{yn;Qv=xf0ie-;_FEsUNbhy3y_9I-h`}Uk&fg586G6PkaI1C#gMHm@{J(* z5oD&tb*FgLLX&hpn<7V=5x}!)9`#2{+9ln?JMCrwk3o*K$j>0}vB;$r3BsXeIAk z$(L4g(@G+xS1ZaTTS=~!Ot2E(rP8uj%*4H?ryg&*5{^$T!B3W;KD(plR_)pb$=*S7 zOptsmNJ@}=D@cAEB!38!b+Q94S_jFy1ElkzY`&n3mYxIaE;-tYmfi%}&LXQJ`6mm_ zJrB9hB46tjP&f*?#pF6G?y)TW;U05E)Md6p&a%q1?d{>eU`$KZko6=!fzfudkHjY6 zJ*=Nz@KiEv3~>23K~ryDkn@zqc{#}0WN|(SaNHk3cDHQR z&GY+o8<4h#lpwb&B)4X|>xKupV}jhrgWLr{?khp=YmjX$3m-#TL&EWe6y8M*n+yr~ zZw_e>odn1z8PbN$36wn=mIPH-nyNIjDYpmNpJ4X4{QMMDy>6%8nx0mqO?h0*db0khb2dLA^IDy|;pT`+|Bu2KBC4dbi+2$(42l_JD_% z9DFuquQU(Cw1+?`q}>VAA#KkuLE5?-gSuOSy1OCm4!dURetoCq%U(RfhDmNJ+o}8q z&E?$lz=Ixjy`{Cj4w|JmfqJMoOJ_;XBzgyq9nTC%+w)^V?o*J-aO|kze*CyZ zq*LtDsF3-H-Hu8Rr-)C$a>qhuSmXnc_gdt7 zNWQ&AEBqU>ktU;EPk8vBN|QMjGR`8Of&9WGoh47o+ziZ@JxN>1(F}IRqn@H_PPvr9 z&UpOOazu+CdD_Dh@Lri1uUhEgKMA#_`#j|LCh0u-jP%SzapPk1-a$)`K`ye&jCxjI z4b0**mg;MyS$r{MYl+XImYbJKY!=1ef;HM=`IcF%=w%)?&tk2%S-*$nwOFs)tT$mr znk>&hAbW?&kxUx0-by{vOc&8B<+gTl7pxXCwJTn8R?6hAuB!oir3FX-!++qzZc2v=Ih`bysm0)H{XQrtLnL; zUwUKdeR>2en3?p}2Tzadwe|efnLmE;%&w~DvwhckIeJ(5cKMn)`KtfUyM3QK`?$sP zt}oUZmnv=E^{sVWmUrLv-51fgQmJfCRXRPQk3pr)9^c%EFF4`;5_|Gy(_VtV8jv=qeg5I zR};mas6SEA*u@r2>`K(A(dhTi-h0WC@6YqxXLir~o-=3aPTM8*Mw`?#ZI)Gcdg)*? z#rd1`zd}m>ht&P#Co zp<;=^Fqc4Sd)BZZt!KZk(-ZcWxj%nb_-3{{s%@Oh`HT5;UcK5i|LYZrH4?(SoCNSi zskR&2ZW`#);_LhG9?lzdZ0)zsPZlm~@=RcROR*RM(UHcWPmKvuQFuMN32V4Z3B3DO8MvNFjtyDM=}RP& zX%=p0m{{el_uHfL}xW;_*wsZyxaZ_$|P1A$}tv+l${B z{1)MUF@CwYUV?BberIug4!=D7@@3O>(|KGh1CWlNSuvR^oGRopx|7c;rFV4I!nU(-xU891ZPOm?WKA99Qr@MwR((Gk>>zvI&3~t@ zIKmdmDt9ocucpwmXS{(q*kpm}50v;b^Hn7P^{0~eSyqPD|I93|^{1*PQP;gqm0dZ) zyA*qtRiL`ES!THIrj%V(*6ctZel^#nz+YGmbGp0LT(4i4uNmoAw@*{))_YdJk}V>$ zN#!Qh^e2o>!td1-5dkwbr=SnaErd{kN<#c4!ZHX~qcV9R%*1_FgliGjM7R!NeT3@~ zh9cZR)lRaS9#(gmX{zuUe=hi)p~S6@ZqtRtzs;gDy@?} z=*Ai5uKojV+ywgT4EwC8=o;pt=sp4%FoAmKGH;GBC6|pZBD@xaPaxz@5M^71=T6XC zoMrb|Ia_f7vKNZTWjGU>$7*myRQprO@-!=tRdgIM!Rq^93XhcC=s+He5_U@DvocJX zgpzh6rwh!BTAXLqZ85*0r1Q*|DxYUEt7b*_8qxbel_^kdB*0c>tyScW{I54n;f)&= zUO=6jb%9lf75)08xNfB3x(-)nC?<6gRlCIMdoJpw=+(81Npfuq)z45E_YrQOB*6S( zFWPj81+$J+aEUcyqsZej>(1h7#AWy~6K3Yp%F8U==0`jP_FVY@Ba5`Bmzl)aT&?g5 ztHabB_!&2l&i*F%qj}euyK)GE3AEuFzzLLpjm6qpLkQMntP}o=F6D&@CG_$HiQZbShV>cH_@gJQ`#6yS?YO{S(KyTZle)5!QDpb zH;ZCAOb;Pbjscd)^%fkFDEt;H%UV#6TS)3*+I0)~ap2x`6}YGOc)2LY-lCg|Kv(k^ zxmJ#RZnN%g!e@IPhzyMzD3f!%9I5O?Z#6-?dYfrxww=-+u<7vH^&y+e;L+koYzLFH zW{+8Y#=NzpCv1nLlt6a2plUBzC8@JPs?<-=_(t}m(Qn{SHYLAdOZoqT>Bu{_6!jVUr?qj4QnXhH(SM7gblxIQRyv|^#%fzWARn2# z#y%ojk-bTu*kk_b^2*-422)qg=Pg<3mAQN@vLl=!$kwtMN0m8DK@#7{I%^jtaod+- z6;4tH+#5Bmgr|ll))=$3Vt8naoOn~!90SK*@8tTUg#~MpJNGJ~xT3cDQ#Eg1iTfX- zB@G>ZTvds8f@0@NJU}T8G=b78@tQ1wvMTZJY#u38v~%YqnnLZa!5crUtAjk_!5 zAQ?)9)p#8?lzjY5=+%a)aAQ4Pj}ZU*XMKWJ*0M^0WU2HXuk}bH0i~6%_Qd{}alFqyWg?B7nIFO*qdpym)3>5m7git$RP31 znT77D9MThu`{jPLy$f&65BkwxU3fS4GeviW{we6+x9P8aUCK;fcI7VozMr?q|yE4jZRoBgdcC#vx4wizG8W=*}%tj=xF^ zkMfB{{*I3W_kZ9%(Ye9=iNAI!j<;r9sZQSUh-GB}b&5yU{Y+W$s5KbWsuu&S12$WO z7ujd82I6Tfa<6#{)V`((yt;&(vficQjw4&PCh(s{V#f63{h01i^IuTnFM9Df5qrDd zdhp?cvoquc2g2U;KR7_3MpnFrJJ>S74gkGreU zVzkoSIC_nupwE%g4gi9hQ~c*e!`diXDS#LNJ(^Pv00(O~7G*X@!(w|$*9RVjb zS7~XA#e+VBgeNtp*8S1;tStmq`ol^rX!XJ%yOr3a(bqiDon#L*oldbFUFA-p{89E{}SCTB2TRuoa!Az;OU^?6Id^5dVk)HV&_ zZ|&npQGoV3(gpFMFmpzzHfuhL+}la@`e$mB4Jmvao! zQ_oBjDgQO-O-J$394X#DivK85GITVLcl^Ai)nowqJXPGZ+oO4kj2@!TcwT|?x-PVS z0(aMzP2@uv4{{-wDY$c)%s)!}AH<)`$M9g22;J$+WVA{9jU~l!lZqSkCbv>BLkp&u z>3VR;8q`VE@7AT_=@v`~Jg9COA85bcX1K0CLzgd|!GB=safs|)M>_>7q~%I#w_CgdcQqs3BMbFXcG4E-ymk`1-g1AME!ho`U{Jfq5kW}+TBJjB*KJju0I$+EOFhg*~i06(K6Ioy|h zM)z~LefZ-^lMiuUw~ByopSC@J$BrBG`RK`1=NIN*WT^lw)eEeLr%64`tMG@XzpHVW zb6Yj{q@bf{quwCAJ15b)IJ5@6Z=H4&P2$}-T5yz4vQ3yoa_kjebc#q?`D45VGf}T& ze30X3x*N>2nOt{Zs&xAppT=*WrryUfYIt~BTXmdo;=*F+FZ{0RgT~XhG5MWD3rE=c zB#%PwjjD%&-+U6?T@~Pi8q?8}ymt9PjsJbr+(x{Cc*@~)A4)uh zr20Z}bz@p^iZ`|8fe+;hpelg%jp;8V5ONx6uLj_|#+ZQmVeB*MG#*ReHKwz~Kistcfs0iQ^;R+NalyUyA8x=IaI1s+z8H7-8F1hK zhnp|B0pONxV$BWVLs=@Di(yvTCdK`ooQw3<0JnY<`Z^c=4Z>mx@;VDbO%P(5Q0ucO z0))i~=poC}nX}wNVP`Q!7}kVto<$Fcuo$iDIoPQMJ9C>*$~i=YP!JrfowX01H*c`0 z;*!TLYHiRqHlZqcu!FFeos2x#sRP2HCUi6pl@wtyLc@Fz>Vj~+3H8p01%$;27X={* zgf~s-V?Hb(EJjE=4?;Z<+?vwr^W2ZQQPBT*q^%kFkn08D^?}!EN{uf7uTvb~CGZBo z+c%|a0&ia&kNp*RL*Rp&(v)A(TMa6XKNWZ|@R?1i%thcci{tYza$j<}h|FHsly(ck zy5fXtmtf#C82G6vb+`lvekzWi5O@gi%T4K-z%Lia2V4f;82HPkwB$1Im&I}A3h*Yt zotshZE10=Blh1iW25k{|Q{XjqybL|K!rfWT;-u)SATDoMp>*jcEFdgKh`xmykarU`ATE?9+=2;&#TX9-WArUB#)VSp+pvMK z7-RlzL=uTemW9&p+c1H!7@^u75ZZyTEtERkLCZ&2jBrp8+JkU1lztZkgo5B{Z_@uh z1L~p=?u(9dR7;FZQtx60gdThCU5s#!A^qVMggKkW}nI&$}W$8D0ZyjYie2vd0Y{gd^2g}A}WDX!zJ*LmW4ob}q_F|LGSH95^8W6+qSh00GYdm;ogG2Usis2LNCH2PhPPBY^kGRQ^TL z#OMQceF2~Z0H+izQ*dv^DFshcD*Tz1rF}1WJ=^2p0~HElNf1Y*Q2D~5j_d>VDgY#q^iQTlDv(7Z%d4l$ZL3%W3ukI)f=Bu7&X z{6ttn-+br`tg6jMBYjCb;J+SSu$j1sP^>v#LKuwjGTnd4eL2dY#4BFD-hb7u+SINi z6bZP2@H2!32wNk(X`*hgkXb@uD#;5rT590!VXeAJs$&bGSx0hre3m`PxaN4S>pv@tlkPZwFJVK2*o7zHFoEE zB7Beg-U$CO(UjNdI8p9vU-R;%ITL2<>t<&GN3oxVJlq1gEAE{TRzX+_q1c;oMi_z6 z1z{vYSA-o9mPUyE9FrSD6uQY>tM(U9mN4kW!mo$6?;Wqlu&|>&`5Q|wXyI;L`bEsj zZg6P=CKR0|=@&6~tKcBb)F(pg9i{4K?3}5M=bDPv14~F=?#c)V(F$D^A8PF_Rkv+H ztuhSWMZG*(S1f@u(?PvnYU{nFpSf)Wu1)iirZCLIcKAykWbu{6BGb8Ql7}|UR~jki zF5+fYHR&x2)!tQ;u$uXgo3_(mYAqJ4D6g92PL`U|YH`!CisY^xs411!oz4q{)6L=E zu~56ywC>lE9$MR4(iMvm2pK+n2PF_)^wJ> z5E)vxi!{a_rY*!v7jOn51Q9aa>vR?W;aQ!5nk>lMS5AVBdsR4 zwC)|zh6>JZ)O?)e|9|WQiR?_)lE+CKnR%*YQhz(e#S&{X+Sy!EY3Ky0wlWQ3Mwt_& zI*d{71j)Y6I+a>Ylzi1>z!!d}krSmV9AO6s9;)R{L>|CDy$IS)M$x8#Re};HOAT#P zw`9tkEcsfdLq7chM{UIp^oELX^wwm_KE+KYrzwab6`WTOD0qrgyZkE~SFBBTk+G$Y zRiPnJ{`i1WrbwOGR?43uHAnyHI#ueqEK?F^nC5_@Y z{-H;+qWqo%~pMv7a|x3kd-$C2wC1i_R%M;c+d`FYGC%wnnjQjJY7;J(xTp%@K z{xm`a73fsm+|Y~7cp z@C8x@s#t~BMeb)TLfI`qywA%2yUyXppOx2_IEvg$S`7CVf>x0-7Nc~mE2qiy6mrWV z$h|69W1xeToPFtBGXJ+Cj#vWS#o&0;$|Z&zxeqxlTO!G<2{|n_7)@LXg{4r4qxnX8 z0pyltkdL=VmS5Sq5{*hTMAl;&bko5}r?h2Kt0G5pAy>bE{GSTcJ6-zBw)UGW(b|{h zG8C0AS(N2~ov2s3WM6SYLrX{Ytbp9RA{MGfV{h&@n9Q4=rW@*L_!nTU1S{1`qUKY$ zr&HUCCX)jWEBu1CnM&zjNE?c>GGsYCTm^C)N?dNJxLbsrAdjK^<%Wvxu>$fhA&;YG zD-8VELY@J6B4w>Wg-WD?6$YPzRwBWx0blT@_?4oA@zzpSN`b7%kzK1`;43g%(bZLk zatR>F*FfHyVhM&@QyNL5n1u=n_N`lj$<*pgurk4#MI*ihYZhgG306aL$}q4JGvLKq zuzssT3o@kI9N~`{X!i}sX|<8J8rIf)(Lfo;G9}tiOib+#S|mRh9Hnhi$)PDya5{uh=mcPY8X-{DX(d#I*fu zC8><)_;dD13s?y)GF$qdIa<4PW*SfVHzce$Ytm@`>VY;xlV)(y`KmukjX4X^!VgG& zIC{$sIZ^`KLjUAQw^$Gr9KzFmB>5ah2Qf?Qfxsg6&t5S==M9xp*_mMaZ%bVP&K zhdQ-sLodX0_>vUID^{Qmlg;I+!DY#Xd)aRK;s!N7=`!MJB7zF^;Ib5kIgoxGaYYJq zw6;iQsz^asU~D~P7%APkA`RkbaP6*2@s3Uvt?{{9DTl9u;;pf3QU!*sKCkN%j#IQD zpBwNrhSF~!mT@;EG1J0zBh>CwH>8D*7rd=T#!zgw2x1_lY z$?Ey9AKD^*8{ajP- zV%v#&Lq37BulYUbJ&S(+&GR?J>VozUXjv3c7ql$uT33#>wYfKx1z4Sm=5p^m-F(j) z{2yn1s-m^{kxvkm8&I?eLPb!4Rs_i|NY%GNvc_0Xtyg{7pTUjU4dmv`F$;(K#OU2R zhojpK8mlN{!_Ja|iemy}9TB!OX^TrlfAf zX6JA>@(Y#yIKmF0@(RJnw1nP<%I@knz$ds->E^P1Nqr-AZH|Rb)&suvVE_2BRPi4zOI`=bauC{belR4 z7&o30BTEL@GIk@407u;dj;lKjO?9+yO>U%%0@wz@fuirKhUf84UGGzETl#UohhG7JG55Ix9f8kCuTFQ%x6g?tfISY#2 zJSa3mt|E2wz+UnS$&;o<$o3V5jg&2D+d=!vgKkF1_A`hZ$+H!z<_-W^(Cd>fH7ZJF z8W43SkQ@(vsl?XVit@5|wxaqBcf(#|5T4jBtz{Q!0`8pKVXJ!dY)1>Vg@~h!mdtjn zOjBCRC8Q;Ge0^)Vq9}x%*7A=M@|r45uvDY>2&=VYPBZqNh=-Odw zd8*hJH^{u+ZRHe>ytvs`j@Of1=`NN5yF{WUB8461JC>&dk)URI(8owna*(=py>PB& zTs!#-(UIT;f`?YIgZ!46o1j{LCfTQinEA;0iuqeSQ=F^mhdJysjc#&nWfR1;Fp-h# zNVR~TtH)z(Me!|F>yGC59SBP(x;r|BB{ZVD{2FoTbH7P(vb$w7&{KY*zr4OV5GVUuwt#ca&KXh1xiY=@#zCgKJ!A_%=SQJEWc!hp?`UNYl+jiw{OLzI zJ><`9OT$SP zq`CH$J+OE{htA1f6wzN6)7P*1%a|N$&I9D7j-t36hwv+T}d>ELErOibV4Tvkc-EGqb;0P@=-drObRsfq6L zL#mrCmq1)ivgH8v90+A=(9rCnj^`}x%0@xt0jOJpu4Nas{Ile_7eGFMMm4C#UIUOO zfb#%4)}XCM;2{8y3jn&;u=PM=2aM~}WxymXfWBt-Ug#{vYB2CCc%y636wTnv5dh|k z02b6xt%s4??vvfkmmt{;$+~`WWN880Ylt{LfCT64ljAwkRerzRf+HEd_scanyj~#g z;pACy-@OL?E$$I#=#O#>Nkkz|6gj1$tYKY$F8o00^-8&EPkxlkh=SMq@^XjdFObFG zACjxdESmC<={a8Vxa?6vsgDD0U8vewJe<2c!TGc9@_6mQS(%F(fm#!wU$`SEGxhr9k&pHn3{E9#mM=GA zm1umvJjB*~>(hM!Hv$|=PUrEM3)P~}i>Kc@Qht@|Gam~1RgSiu393(ve?^3!f$j6$ z7GZLTb45D5Sn{Kfzsf4BPs&9Y3<0GP)w)>pT&_>Eg}gE3lPJq5S1v)`1oGun>ynWV zx!M%+56@})CAl$2c=L)}!|93xj=4CROk#zv0r^~(d)P)C^(pN#+-nA%nJ;Ya-D!+D z+_}rLD|QI(Tt@PLDy}j43Stk1MhV(*MHa^`3$DnGq!xu3m1H<{FS0!TDtOJoOQ+1M zvVG!RpPoW)!IMfYD73|x)dW-2=GPEofv{DRrd`7@r`(_aG5GKr42DB7n_RDB1d>h7 zuEVZ%T@4w19d=s)KKZB3ZctO_s?>L!>}Pva)hDMLvM=qtF3S#o*-6Pwo&D)~K~d*g zALCmXih!Z2FKvcgcY!m^$nhwEFRj4oL(K~0u0;`K2zhJBSJM%r-0LQ6wt@Vj-DXxZ zB)V9g7$ z=^KXt$^(r}rGh(#>euit{9k_u{;#E8cjYG1TCj^nUI>Pz1MD1mZA(b(9<&Ahu@&|k z+BnxeAuOrxHtnUFgnz zxuukdj^g87IQ019cR36VJLnHN0S$QZAM!bdmfPzgYI39JGW9tH zjhzp{nM8#UvgH);NFL<)L2ty&G}n51WZNTo8k$M^BaDP29^<+M9eFGhrdmCo;9*lx zNFSfb=TTGhpUN@(pBQ_W(H8$HFZWQ#VU+V}I{7&$VdbpT^GGgYkCzY8S45{kF%8sMO~c~tim83UrNR$^Q8?=N@tuS zeeI;!JK0qfSxWI$zXa=C9U4FCMul_LnMFk*6!b zQ2-AJ(BA8gb2YGc;Dk=80WfX5E$VVen11PDIVqZi=K?(VK@Eg(n zN=i-Eh+Hcxoq3Daw8U45vMm9xqWzUY+W^`yx>H&4_Z-&RofSK& z@j=~MMdN)?oxX;`#n!aeN2$#bp7l}6NEchnbZC#ob5#|^UAl^!=eVJ|Rg|V8RaH>O zlHldwHnuvJ7U5ihv?_{y;J%9PgQIMOB6Z(uPv1Dm6I5tyPuPYyh>YhC-M`ldI`PoL>#ZO(4E+ zOMh1b5uu--avEh^=%=hKifFMvBKi)zC6w)t;#)%Z{gtnn6Qxy$xd_S@!326(UAGz@ zfOKvK`$#)mI`6bXTbdi7xbh?IwABI1Ukt~o(rZF#H=U@7l5a#xpkDF=0uj>|=zd3w z1C_Dnt++hV!PcEuuZ8pG;?6Kz+CqzKArWJct%b4r>V&ORGVT=KL*bzx;N3GD0)mIKz zT=14>P&mkqAawS}S?j|s6$e@ru0*h5I0>)(B5Ky^7Rq@xm`1b&(OMs@#3;6roFbI5 zC|+$wgwl`K_BDdq)DyO;h9WqUfu4#08Mdl|uXcO8iySY>tYkf(B zT*U0GZ3pEFGv7jvzf48Vea7qCX6nZNUCaUnyrZ6jr?#l0vVtk!Lqnx%os>$F+6jsy z~l3{3;AR|LNu%~u26yZ#};mUT72>u?f40HrtA5fI0*lBoSD|v*n(Yy;eR3ZWO zTD-6_Yb2iJyCJDgnIno~g zK%RYURpW@+#f{F5R$Q4U-5HJEr7?vhA;82i2{j@cTr=%YLX9xfog_T#%F*O8h_erE z8H4iuft0bJ?FG$`YK=uB^`ik}q2GuOj#Z+|TAyLU8GDLF^)5j^b-)fBi&dH1pJ4Cn;F}Hj~F><(8vgKPzRRzBI47Oi^68DqcZ6xu{ONd1pRGu0DsH1FBvomGLrmjS zm26Sm;>EYHG!%CN44BKKort@h^J^n{!QfFAh#xs<7Jo{J9Ko0bT z%0xOi16ebXp3cBC#5yaAr|_954!n7(zVe}=Gw~=x*kKMHj&{OR5R~2^%qNdo@Na&V z;&|pP80Z81UKRRz7NSO2%s}*P80ZTE-lm%k2NEfIj=_O<0!{>cfPCiQ8GWEQykQRD zet=DM3NSZSEp9z>F7VHRFQcTnP+vxwb5Rc>so^|y4E<=xJVcp98S_x0412VA%EVLT zd?@vY(jZEjuh?g2@sta>WdP)OHlf6^w01BWPiX(?MH`m!)M^2A2ZHkjHg}80CKz!+ zt`36ypPF=Y0g478U#Lt#{hz!LHSb5-C4vxoxDbxDBd?-rxdPb8luNEcq!TcYcoSOOd`@v9bkx}<1u z8BfiYLXH>v)pkPeO*5A&L5L<>h=;=5JStdCRS-{eEg)U_ zobkK$Xvr5!W7eEbeS!Y=O#|Y~QR3GdQt)zguJJT~ITVLO(T#R3hoT!@U5*^DKp`ve zDC|X(SD*&H3#RQWbUIs!{2l?i1uU>V;dfJ2Dix@0rqY*Hp)Hwc zqbuotCW>JnHCzk(wP?s%+e`7(bq}IW22h%k_aN%h^z9zZKI6$N z8zqqfpmwaSB*MF(XB?D`W>%XfXJb4ROeeApMeDg2aZHECi&)B;0Z-!gDz%F|SPayh z3iMs9VjVWPYZx}9K~k1#X-HC8>ZK{^wp>o7*BTV?p%JxGFGb(7w+&Z}FZ#>a+B)T_ z4c&+L)g4b(7LGF04(m$HvV+Pr^p{RK%5?FFTattIiTM_bqxZfiF?#<(OFD^MLRYV?KBYY4Xh8GN zpo}JJ_s=Nn82Yd~XVF)zKa0siJ8_+WKDOC8JfE6t7tbkXiMeS7=fyw*%nQmOsd*!X z>Qun4SN~s?imaWM_N&sw0c%SKZzwGt(Ld-ZN~fd?=vgZkDAlF7aQO2I^MSqv7?$j! z`~uVsO>?}7ejM%f>Mf-uJFI!#Rz6|(mAvjMgB-1GiJ82tX4cGsyTnC|_cX^^5cYKD$H6g2NwfW)+ zY?jtMpNffAZ3=j%JeFRdp!*z$r*)qz75TeZ>hK)>PgyPVx$=kE5v8gd7@@y5sI7ma zq;gCNaXy)<{jK;)i+{uVV}E5l9sXN+!AjAt_o)0;>Hd2~KUOKmMsXidfoege5hZ;< zU(!fh`2hn4e&-$?{fNiS0`mBzj76K9{|S}6Hi(I|3zsZWyZA|QvY)dFT=`J-Rq6o7 zR~VS;kFPL?pltys%CmiSskkmSO z`uC93b%^|(1X_yz9P^P?`}^7=rS>5xj`*4u(+F98gCq=4)P)jiW}$~Z zUM187M6kbv`dDf%Haf(M_J>QVeYu)|gWHQD$gh;@#}`Ft9ZIPXajiaK=6Kwpwn)6AIY8*j_v>k0mzG>dhV+I z4SsxjKmdaQT#lfvM&KO)zaapg*rTld`M6PItQ+nooYj7S%@tL~dxjBO3lBAq6~*OQ z7AA*6^Ut=_qO8G*Gyx0)fcgAZBk)iF!vU0zq|)UK8nNX7i~vv}lBO7e{Q?*Xpk5^1 zH3B}K07e055=rem4W{M`U^IYEk+j{3TheY=SXbRuS7Q&RzYpb5-7O>h~q#EYe$FSDwm zYAH1yXq$GnLLE!nE8s0Qd!co$2=xgd^le8e6%94$hyW%6nAnaU8G%|}044$WxgB-$ zGH7G~C^Z>C?!R&M_AunweDC2mUXtYVd!5RTT1kaKddI z(^#5P)!=SGHDtm95c=DVB=&`oVbu&qGQcUd5S(HE8i}uFFyiP3Ba1+oZ#R-JjI{SN z7?})Csm0(d``1WgKZB8n!pIU3w%d(_CyL_mHyG*R4ZR}T6d z%C~D6l$~lqnZW6wE0?E^HSw;jJ^J}TEnfm1Zntpcb0naBpdkS)5Ee4P8Edm}rluhQ zlYv@R15LME2=5OIO==k|6bcJpf%9cFeXNZvI1p&CFr*eNtO2^$ZsCZqP_wqd!X0qb zOmGg`ENrV~u+XD6EUX23+ioFzz<)FGA~@S`IfJ;2$O z*4Hs)VJ;Zz1~4ogtnRziHDqCAUFd%ew1!oG^gw3|l?*aCe*_G5BN#z8{Y7;R&W8j+ z{~Mq|(=XM>@B3r4pNbTi0M{z3Jix(UD+MXCxV4{|os)OrT}Eug92 zftI1`m;XN~KJ{T~GbjfPmTuQKBr_8Xbqg5BY(|Qqo(-VC73dv<{^G&NiJmnLIk^%v z^?T4BbfBCDhLpHAg#I=FDkTP~707D{5|Pl*kcjz$kp+em75v`}77XLt!KfKSHG&P@ z<_H1o08lT6RvCe-04zHJ#KqYA#UbbeDl{_08`%hbz%FnG+BoPJOEfZcB>O?I>;_@2 z-ALk47=x(9@;7&`iy!FMGDKsJEmF;qLm03-ph>;>S~ z(dK*jFhtw(bkxDc+JkVkrLwO&7Dt6^v!?1=>vWX$#C%{qngHyL7 zJ!^~?r0so1NE0OHM*x#-%BDedvx&jAED+S6K$zZ=aeZ#6_TGt{soaMVNK-0MiIn;DXP zM*xQbJV9QB8l37H3g8HUzdK@NWdKeAup9+YFV>dBY$P(txw#>enl%UK7&swzPP6}y zvkM&cI5^?4bgj7|f@)y^P5_9(#4pSMWB{=I3}CL^YN4=tE6fnHQ#d%kfV0HTsWs}q zoHTIMli;k1rLEzH2wn@|6oAZF@@`=OhO|K0o(Axf%__>aR7*qI7J#7s4}_z-W?AxT zsn#m08nG?m)ES`n?M@|*b}mPj2tx^-07uOQ=SeI*YiWo(Bm&B30XTQE<@cS@=*8z5 zm9xQ7&w*2>6HeM1I*_1NP|gF;*sh$E1m)CLhM2R!QS-qG*Ofi#d8?w&79~(XYgjlB zbb#Fg8-vHt`W+Gp_pbtYYtQgNk z8rtS!g2wC26oFy!t(#x8QdDu9&X(Pr)g*UqP;=+DgetZ0PXC`cZBly z?G4J2QBb}O&V*^81#{(_ zU9}}$)G;!zie2R%YANQF*3If|74bb^3XjL&vQfO+jNk1}6XMlizNRN_k5?P>kbd+? zgs=LMUxJEn9`>X71hpIQ^SQP=LB)})1oG?!KME1suj6r8KhVK`SRd;gK-52hJR472 zdl{bn4*|Ho1n_#i)eVz4O-!yX#y+t(lwX1K&v=^B+t9`j3g9&Wc>?`z1OocNk-q>~ z@aYt$)rDiV3c~VKxi4<8LZu^7;s&cy zz59ZWMJQePjSyntNvG$D8!R^I$OmzQ1*TGopsxd?o2=p!O8FlqnF*{(;0xnC9!HRCNSwghyFl?&vr|4U;f;*O6@k8HOE~5ujr(t_vHC zgm9TIEKhw$f{qEcjvNq3b`+f*2|6asx-eoCgx75J(W5}eELca*2n5sJo1@ft><1)SHpp!09 ziE0!Msp@v(CV~EKjI|EUnxt0bm_+DR?tnlraX^(Dh|Li;9oGFdX1Yl8SE+@ ztugEo2nPE(QxM(l$%tT*Ri*6|02s^bD&wX=Wv)$Sn?P3TDg$v2U5_AaDr6Xa>+IoE z!N!PNPr^4qq`y1bl8`qQO`sk|k<-)~I02A28P4^erdDL(lrC!YnrX0ukug3oK2X9y znEKRpDDNVRPjl4NKiMI^QMAOW*E1O{XH~4V_N_>UA_lg4AskLdy~JQvua^~5fMDQS zI|bDkLsVV(jSylis=oo1mjXJ*pE?pa9S8=Rq0>d1vI+MHAqJ2TBA2Fvj`5;SZ<-1O z1H%rfpf9iqk3;B~t`Eu3{j5yq?o^nHosg}RHVuhvkOm!$@w`P()He;*?%5O%0AY_Q zb}Cp8(vU4Lts0eQKm%t*b&aSQs5RKeO#x{$0GyTxPsa7HGmz~VP3hTgnF)<{x<)(> zBgX*iFLf4pzgv0RW`T#{if;5C0RF+|hRbZY zQJprVA?o3?0o3V2DYMmJ94RWC0a+eo62=wQy8B@^s#da<-G2`3&!SwRxoi&XV_dL( zj(V2yg0A9OR6{)Sx6V_Sl;ppTr^YMP4$`ynwsKp6h+dDk*0a17(8UAx*$SxOd8${w z1}oKyj(CRZEx4Y(d#4Rwsm6=fTCHDSU89QECu?S^pCeeBsfv?lZ>)C-Yt?h&vmJr! z)ZHSyy-vk9LnvmwdI7gu)eY(g+5A0T1#|N+_8!|NwYIVi;vmZ0ggvexEq9ZeWd9`N z_ta_&MoC$~@qN%Os=rjP1768@;LS9A9yW}T`}gV-9B*RVpxTy#wy81LWKG+q*2kWC zwh&IF``gqJaHMmV8lY?!@l#qBa5pVGOT~eX5IV9Qyw+5>9m+!~d;PpOx$ackVDG%gPJDvay3w9RSv%q24%qEP7jcQ*+jl$hrC94MAd6ymVbHP@ z@IPH>$}SAa5U$;&?uLJ{yJ2)arR`P;FUxxV06V)t^ri40P~m-P$PaKKi8lP8j<>DX zXOY()uy%vhlv?eq&q(N@}0rGS4l70}+dbB-@?hA!I0H%;rwptU1g+j8`&N!2@ zI2&GC4*`Rf4KK67`n3<0+6ylc*4wML$ij(~j)0%kgPciKTD`~Z~l2iOuGJ{`mUV+U2&@^+EfdO40gm+IwArorfRuMMDQ2hnm` zQL`LF%}LKe{0CvG3+>NA{9W)(Q$*Z_JP)B_#8KoSY|v)Ww}(K>0nLqa1>i>i90IK+ z1s%p+J4!sP(+(a+4LAhay}@W-Ut7HVj+e)OOsRl>YyuY`M60&#Cqgz0za_eyY8+9Q zAe#M05Y1uePog_VV0aR_9z|~8kn2%(6u&owRv$HF!_%WEyEyDXzZpVhj$wX+F!Y!@ zL4z{%~j^x4k&(Qs43JuLe2aIr4p4yMUoI-!+AtT;Qp&I!J-%p|Ve6_bI zoqR<13skc3uU=GN&n$dp!d{-QYNC7tO{UMWKa3vYJhE;s%|DNHE}{MB)#mtD2=C4t z@+kTOs_;qJs+wx6!uko>r599JR#n?@L0!sNR|>ia$NSNMi)sx2kV<x*i4 zesd#4aOCobXDYI+357ORFzq2KizxoxQAfLt?63LHhB9 zT=n=o>Tm_=M>yq*YX97H7P(%9hyMe?gpcFsN49p&KqKpXRmK0HnNM49;5+*Ef;b4S zat7RJx_=dEj;6_1RQr)1bkElS=K`Kj7q6*x`27E<_qq;W&H~SyPjjxL^5qrRkG%o? zbHFV$`3B5eXv+;lm&6L-X&&JE_?(XJ>7AKkKd1nCS)Y0ppapHC@dfCGTqvtR?{<`% zu$T{(UR3KQvd`X&r9rNqhdg&7ZM|7^Y9Nc=3E%>NPYbEaEd!8r3zmKb5JVZb@Tp6? zrH4X(5%SN;^|qm(>~$N?UV^+oKHj4{n>ZUwpc`+it`bCaZl~q*qI~ta10$C~&Y{RV z=$&$C{2g^EKe>q1yLd2sSVW!fqE8E>4R_V%uBY*@ovih-vMY`%m>y7g1U_eD?=>6# zh9q2pv3pCX_iw1#2$%d;^xqKh00Kd|3W5ja-@`g#wR^}p4{9cYYUFtzkE|?wegmXy zAaxX^I`}Ux>^|_mc6`Kr;MajK6u3LBp5t7KwEL>7&q91y$m*Wty01C>3p1JeAb4Y! zlk0Jd8-2Ks4V)sMe}}aju-2V={f-RiPV;|PHMkM}2NF{N;95Ej{iA3}2oE#>%1r4&%i7}w@IQe6K+Rs@ zBlvc`3?Y92xf>mMVaNrKLdYLNzJ;0cnd<0Dlsc?zW~*T=aDCbSj5;qSxamK8jeG5?`tI_q?+xA7sljkUQhEO?nAzSZI55 zyC}_(uMyF6aK_`G&fvSo_Pp37fX^;jojI}y+Yz(g6m1Hik_*l&aJZer7Gvc1>J6$4C*>__U|9+g zK?IF>i)uWYGDR?na^LFt8SoAUUcx2aM*QGV^t`!&BVstGtEQS5(N&H8IfelFaEvxtlEkeh1it3M8{XdLus;kp`2at9c=6^h#HAd%Pxe$JN{jr~Exjqg+=|*V1PFDODOuj!@c8`K3{B zw$r=PplzohHv~>J#LfIUGAGv!9+v>^drar_5?TBOJ^;|iVpgcSyV=6N*BZK;k1_n; z#&;e_srCPeWKnb(m@f&vP#Ryx+!B+V{bkI*@f#YgEsI)sTcfjO&0^dgP!2>3h#3@H z4#W&vSt`lUcvN~}C;=28kTZytry=ex?A z+wi}Cq`%9X>*2o*)v92wkFic-1%T+!DnQE_T5ITC1!T(_YFN>{ga2`Wey?b*jpY;% zFVN>vq!%)yG^L5Vs+8?z7E>KpZ}@~IEA?m&HTE`F;Rt(sqY5Hi<&D&x%%PvX&0;`Y zt&-W-+zXGjk2%(_ui4i8#R`Lc&0oBS<>pVN;^lUVJHE{qq&=);u27NH)0C!Wd`rVk zJJ`%@mK-~E5hcJ(-&?;Kc00_x57TsQb+~x~$2{CM!o1P3X}p!QoP44j@U`Ix^9p`0 zUK@y6sDw#%W?M61(yRqXn!jLT27J058blCzwm1L63lg=v?alp|7eC4fg zv>9K>){>*mP0&Zt{uuLPN9!DtnPysjIo#2_k9E-|$D%=D=9k|I=I#xq)t$|c948I2 zTANNj?alc7S{L&+G5zY$)%>%VW0mP~UasI}S4TS3mb~2nHeOxO-qxF|FOqxeMQ~+MTr>bYHg<{+-;z1n4OL<%u29G@VzOx|GEG?t`KA53A@FIe4En^qk&1@!Z-Ww~0=p06EBIPHcK zW~TZ*-1ep<4|A=zb?_Y-M#Z($zx#8zYnZK-Z_o%;6SqqBk*?voX7!b97&);5+dY!N z=#!0d)zO;;MDc!6k5Pzv$XX@x_pof5Uz9f*$xLZEn%i}kzel@TGvLs23~kIJ-?iP%7_10soPK`~=^SkwU4L5&B$EHy*RVgTV&9#Ou%&c*g*}E8u zR6$_e^+iN2#=9!$y4B6FX(gn3*RWX09q)>_CCS?Hu6_=BAkw-HMI?QKs{%t{ohG=t z=#v8aRs2Qv@C1tNdiiw%PjomS3M6XdY#zxbv$A;zyKj58m4a`{d9P~+n|PN_bbZBp zxz8k54802(GmYdfCcjRj+VJ9>I^A`bW?=jbTzkvS8Kg=*S^g%a>orN9N#ZP$p)+0m z$orEsUD@i5)OnUGPd`d+R}Yvf6UR_&S>u>)Q!kk(=D23?7HK$#{Jk*8m8I{n-U?Pq zsB)K;L%H+6DQwzb0n>yzl+S(Z{Q(a4CvZZptG6w~H!+twLIa*Wk9e*29hpaBVb7zU z(BcuZ4;NBYX+8g3=*qLr@#QX3&P#l@w`gNj%e7+(Mfl+-zN$-Ix5AtpG3zXoAgS-T z8U&iGjsIi)s7!)y>^m+@GB=Ur6|OzDuD<`Sa5c2K2BB9v5))9P9L1!;`!3UAU8xE2!c_O^6&#!aM?8m zaaSVnA{ZSho=;rCg~5YltrAQ`Fh5eph6*105Wyq_d6Dw;hpsXXb_XasD+$tiwJUhq z)galU)TW@eAyTe<$a@F&ta9}aymto4m{llDMd5Iiyt69g&X*CCe*?ku(Sgb1wtaf` zrj1wQZ8sSF=*ZR`)x}0GkGtqW{OiWkR}=0uyibjmO{;miz;AyRa^q%eP?(OwH_6YM7*1U0 z3hs^_BtzHnE}MnI(?y+fwO-hx#5#_|IU7k|yso3C0u$#_!fK~hg(%Me#D{>5TOe3)Hj!jx^Pf;oLm8(75);`>TdJgJ(OsMs}K@zc%cyJW5vjcYV zLXPZJ1uytc?Lkl!JFD82@Xy*V+30Fvr(j*#NI9n*b=%}hbBtC6^=Ve;uh`^@vQt+4 zv*ujrlncvyDZgce2b)~ACi9TRBq3>>|l2wa(|mL#tV&oKu1_2-<~*Rqwf4KB9PL!O zR`s-py2|1T)0dA)&VE`rO4!@`T~F%%0%c=qqjkRCgZ-{73Wjg+*RH8HeW;bs$_TKv zp)l$I-AnSe{sDTZ72N*n*Gw>wg)!cPu4#@zZvS-Tg@ZH&BLWJK`=b|ii0G-TIpk`k za$ud}OXT4pS6_#nC${RX_gl0`GwSVK{XN}(i>Lhy4hjyt8aq_lsOl>@?ezp-$0M$N zcBe*~eKb0>R$3>XmneGJswyNIe>RlD#}uA^?k=W;;bZ&-`TySu=$r!YJU;ecdG#P< zSyB#nC0bv9@0y!^f#3d{*|cD+)Y`!lK>cx4g;y;f90N1tue}CWhqK{naPTnmiCn)K zxK@XmPvTmI{W`1;GoK94h2MbRhLyj3n^s065byGU!@KZwuJ^$N=KU6)DSb}3D#_jx zuCn&yW97;T*Q%{Q(je3FDZ>)JZKqw`+{(6P$)8>7yofh`cFhS>lfNae&<9ipV;sB6 zw+R})CD&blV$#GXw_U@PikSCY=at~bJ(n{~g^_u|#nBmmyJoA4C4XB18V_ApmG>?8 z+-{p3Rwtb!Omey_xSk`Oi*Nd{wz}O(Wt_L!9{JzDBsI;Q==kqn z;mYcAIqA{XJ%aroZl`(%WkT#hnmg8c2h|rINbySU;9jEJ(y5X=rO59Hx;{|5O!*rw ziIv>J4P>{mLF7(x-bG>f1G!$w9qcjPmfDpO{DI)L2hy#wJJ`p%ElZW)9)i~&$d{Gf zW$f^k%I;S7_aFG`S8;O|Y~n+Cx~hAa?Y3;M>P~UpN7wg|4dTrUw=3S3a@COhiR1v1 z*45mP2TnOr&l`MeZzj4tGx4@*!{p{b`oKG@x%2HjWVdv8nuBMOIeoEMw<6tL%Q2j* zZzpnfC*7UkcrAEUxw<=nDEgkO?&f4y6%Xw9v~+M=-#<0n$u`%Me7TP}^{?6eTJEah zPvJaQmez7tV=2(VTJBK{g*U71P6=;{ptTID?JkY=n_0CH@DUVV$6b?Q;Chh#`ztcI zj+-vH-*CyLI^<0=Je|HO_PXvej?-5iGUr!ik*KcQv|qX^6Y9F#GVXY!t~a7^d`v?meT3u8|OT&8ZMoiU>ug9Igy)K*Txog<}xh@y$ zxw{c&v--sN8Nz%?2Gw^52VtAaTIJpx_k1~C-(86becR*i-~e7z>GZgplg#S7!|bPj zlSz-etJ+TgTS0Gte{5Va=~2CbyQZV$4TpTXJ%XbryXr2P*1(+>csn^Pr$U1%JyJEQ$sFnlWpW~&A#^BM(*1lvUbXI?s+ylnO3TWd!7B* zHQ(1Q+!t-w(Ae0@{U!<4u(i9jN}k!R-K`i^JHsXO+Ep^4aWX#BUCBQFhW|T%Z>Bp+ zpI}AZrn&r|q&G6%3E0hwXycBtIe*}t*#%>PZQY6CUFag%WY4(p5~`Yyr4*fN>#pcJ zfr_`XwQ`oxkmub|c5h|Lc-}qOzM-3cgwf=Bf|B z;I3dNNVN{f7u%lF9DadhbxXO9?$QqTMC=vTc5mO>iFS{T>w0IBrm}SE>{b@BETcY$ zJG*1Uf5yuQx!l>Eg1xMWE^fiL)q7p2PkC}u(c2Qym0ET|rgSBXFQPqG)^>H5X8`MX zSNCsBRetfJyPy5k>r%Cwy9Pn`?1r!AvH-GQoh)B>b7!am-re1uKzep3kY5O7w@mL& zAiI4VySpE^*$+;Y>pk$^Q<8g9=Q)qOr@I6CANEB568i7Rk)G(k+ zqGCizvzIKzr7xj)8O1vC#Y^rwwmQDQUvj@B~)L$(FwEe%$o2e&pm8!g^s=z_iqgex%e@Tv#yK&t1(vd=|?z!?OZs zmMPU>M(!pfNqQ^S2KtX8>)7V;kXX_%iXgjrH{z;5O_$_|Spw63V#2^uff0_#PkP z{>SD}x3mnVB@J_j*@pYd4Rar1EtT(&G49APb?9)xN_VU;VS>A;T47afihGng;;7(V z9CuD}7crGe`W$zx6y&fq{7>7wd~9Ky(Z*$`m&(=>xF^U&G$#dy7#txw>l2F^m6y7 zB+*aHc_|Quym#Ga)qPOeTIg@h3itb{ema@^^?#4329t91`xFaxB)k>z-5lw zH}<)GKdp3kQ9Tv7m}IV|ng>GIx!TR4UcM4*-2bS)g_K*p$@I%FVue+TG8@Fh*p&0*RuL*{-0VnTG->Q_9(1z0j9o3n7{ILwH@GlBa8PcXYBMlL|*vvO4 zT`wPeti1t!brxdqFB<(!zy7^+J?;N-r&7=C_0i={$^f5p(6 zgayh+31S9PA~e~GqqR<|)UdREs-YLNd1Yb^J;p47VEvB3X=Kr#FpXQOru9HdDeg`n zsL-@6iI1%kQB!Y5w3Jqv{*nIJs85^VUmRL{1L5-7`LL!{)|7gw(*bog&=>qGh59!; zV@uPj z75db)O#HqfFW1)NBMR^~85JddLvm~DQ-VI594_kjvN*(N8+>m4I8YIkC6Okb+YM>i zq`gv6ozR^GwFH04&sG_fq3=<_rPtA8<7>tE!%<&x!M~9Nm$}n!E%FQ`VX2h?z0ian zh2EK+l2KPrl!7{XYEXAyoIj-314UY0jYjvXrCX-R8p4{7j*?&9>FZlp_t+w?;h2MC zbsVGVA?uYQ!Z4&f4J^QaC)rX@f2xRb+6l67`fHas>+7kO+6~-BsM|=r`g(awtvQAK zBo>(;d?JJE>(5zkUffbpJHJQ1tgok8Ubo@)9&RP&@A`TrOYIs?PvZ3TXOi)F;0{Tw zw(N*ooV@(FUf%NA4k!L;6J%-7X(reGae7aVJRW$0-8iXl=u)CL2zb1MQ#wwZycKk6 zUefQ8O|}j6XRP48IPoEloyRX41j5=GaLSRt8|c;iPmU9x*~F_}!$9z5NyZm(S}TKs zP91T&jZ-OE9(0&mIaYsZC#JoAIE|OS-I28vmT0jkRF84|74Q(P#xp8t|0(pKOL8+k z{xRjO)D^d5z_UMQm({RXSr9F`P4&`|6||=dol5WE0LN*3>_#;*!XjF0nT3)hr5rC& z&GfK{iX3a80#OB{s=7~k342+#WZteCz~ z=*((VoF%D;Gptw@4$@H}tNo#q0-;s5#?mSY-c*~dm(i%5uCmxr~as z;T2fj@G7iscpZKQ{tZ_3@CK}Id=s7);5_(u`MbHU))-cKR%isV zC*k6-N|loE^Kcxjj?OIw_krW#fp7vm9DWQQ3n#)8;nJ|G97(e0S^YnD8f=v@dL^7y z+E$k8&*?GQS9khrSg_6J8MIn7#pPHp;SKN*_!Bq_J^&Aee}sp@zrY0Qy#sR~kk@ACIAz#?k$G8P ztX+mn!B^q(@UPkYsK$@q;5_&i`~mzsya~Pw``|y}&)~n{ui(Goqwquc2UxRf-t#aw z_5K1o;9GDQOs`z^9=-H~H5W|pQqy6&aay*AA9S@e6D|Wsz~$jcxCR^r*MW<|Pr@#t2191^0)W!UN!E;aB07@au3ZI2X=@IRijz3m<{o!F=LtU0@Ei z(7M8$#;0|IwQvd{90B)$OTjO}N|y4MHOrSTR)fEW>%s@&7VsfE^}h!{{)@u^_yRl#z6g(msY>40;Y%Ix^o|G=eTTegFa z20!=`^=80)YkHf)d`)`k6=CF&2*NIyBRe!VJPy|38L$Ul2uH&2z)=>; zCtM8v8s>A$t4>p*%6l)u*?cs4)u%Y0MP54}&wTHAqu_Wr5l)6Hz_bnCs&HAj4x9=% zgUiFu!xiA3a2h-Wt^|*VE5mQXRpCW&HTVNK9p0i-|7-K(Qyenj&)~Z7H*kIUB>Xu1 z3)}$y9ex6K@Ri;Oj)ohFc* zve3^m%l3LB`=R|Zc$}w{n)ocs!m};y^*Q0%ck1)$*$#Tma#_dtW&0;f zZj-#cwhR=GPBctO>a6eJE5%xubfdGbHk3B%VvTM=#bjp}YrreAtFHE#LLAuMRo|h; z_@cV%vC{EH%Znx0$!|3(xVyI=>r3i}fG-$UFY1G>9|b-1`s#-??t(nM7Xd5zIzqP&pR>mK zOTMblP>;0YRlNe8(}S;C11T{h_0QF#ofxTCRl}w}_h@~bJ#{ld>;nbh9*CkJT?@1T z{ec&(JiW0=dt2TLW?MThiZY!s%ubKa@SlJR|9?(EjYU2w!#V*qFdiD?lJ6P0Zf)Q(A;Lzsq`BJdZK-JU0>&kx;tp_H%4Bbq^G1NpfRRi zAeJF#re^W}%j6X^mspLdCz~ee`wAm7@pXcJ439>AS@nA1`K>W>SqTymB-amJ1QH`H zC+jJ$(g<^uDVU;1*~ukNNnIg%Q}yEZ_&Ty~s{W3iSl2(d6*wey;2U~l zJ4v|i4ZSldC7x+|p6*WJT{5SEbL)AZ(c9=Th2qm-1Lu2-=0m>iYb*hx@D?7ik3{c|LL_{owS&aouc?*_S#ey=S2t)>Pnv3Kqx@wJfO2T~nw=`qi0 z{?^a42K+7k^!d8ANP-{<-IHxAXD<*d+mm+h2AHcSRfz+P|~gcZ=%f(D=+$O6+qKG+5hgG<1Dj&Ezw z7<2@qK@Qje_Q~@7dP?@T^QeP+AnL#LZ9pa%4RXL{Z~)u^<^>v1&;pDAGr?wX0Nem> z-r1EwQ_vr%clZjh6BK}ZAmJimfQ}&RB3*_h{MZamfE&R4g&rKp1pR>*ECf4$+1O-; zE$>VApqh#HSQke0o$o}4OZi0mV-EF0O%Zc4o|UG8(f-vc{uK~!9n_=k z-$%>3gL-i+fq!vO?-V${yA3Cv>M7yRUhPOM|IPouD%`V7!qg{+e`F!+$@_B$Js2UR3naomP|c!uqErEX_|U$>&&bC z@AMWtneX~{dJUWHU0?EXBH~a{wFdWkf6rju&f@+RFfF9bz;Mpo{a&B%aC2w>p;kZW zVYXD?t3T+cY;2rvb5eh);W1ME63{MDia=eE3HpN^uoCPAr@nE7PwLg2 z-B=iK#*ow>^+d-RgJ#!luP&p1)SpvTrvet|PyDFIrt(4N{LKiwHwF&r*_(T+xdBGU z)R(8Gx_G}CQuGx4opPr1I;Bswzi-MFb^Wm^^-t@aZQW$SXelX}nwwNItZ6+O7HrnM}^-Q*xM=a;tvi*lBJr;c8|q6cklx0bl8dW!76 zqKCN;29?fz$4>KqDdnPMwj-cpL7n7d|Er^4L+1r_P6c&(9#cC3AD#2sTBf5D+a8_s z0UfPf$9COc9@I}Z{>sed>cx&n5wrbD$>@OY3xDmWj#p7yg z{I4NTbyIongw7wgq}25g&o5ucb7uq(gPzwOCzh>q-QlwPx^CJZ-jYMt>4C)E7SC-x zRm|V?G*_1xld{uV8vaH?GhF0cEq(aOo{j0h=^bqL6Sw934LaQACGMtP2m1wWZt68T z`Dlu|DkZzrRe8C2Q-9q4*B?^#mZjR~mi|08uD0JI%&vslSkB#|ZD}m}Z9TXFv9-K- z8!;nOPBuZ_)`KTHw3hwKox{JJE#>BI+CB~?bG~xl5or7F=%(!z-=aJEP+JNA8f>K+ ztO)IRn3Tvx7_gRYJ5<9g$kbi0r1A3@g*%2g%qeSHS$*6B~3y)KPq&)@nVj%LK$ zS{E4A#}Otc9_l68{B`r8-kN7<@{gYF&fZI{IRS0}_f;BA&=hn9(?CAh2MU1u8gh^c z`hy&>5*!AXK-91F*g!il5G(G*hksh^r!xHa|w8W87mJdrjGs+TMzsL2ryYr&0KwC#Y3gK|HrLsPj&>9r= zumVM_-)sE8t&kI9tdNJqJPP?*%%hMy#s-5>Yez~K^C+5A?9n}n$++T=?r|;T zch?e++zD$%-g2K4|H!wQVEOKz z@W|=3->KSTR@|5QDKgQz%J$Q5iH~lURr=8boi6<-;w_RM{oWb!yK=JSZso(06``+9JggTY0c81_(j&AVC=cNW7r}g1~qoKzd^T;cLM&m|SG}MFmRyOjasc2fI?9!8-RfXZKe9F2| zK79R~dZJia-NYW|c(rEXT<=HCJb!06cT%@bT*tngC$U&Q(`VbjVQ>kkX*BjjkMqPt zEac|~un!c7ZM-MtvBS(8T>@?<5tBe&kO}$&FUHdFsl)S_1 z8DxU~U>e8=d%5H|KFNio#3fhW%5IsM6ekg0M|g+ zKO`ck3p#=ZaJVRsK`4^1YsE&J$d-+SVV=NB)nLNuJp7-uN9Qt6SymHHyYv)a7C+!)_jnsz))5@&jXJD7S)v&o*6@P2s2u-s%% zC0h+yG}$u>D=*PgJayP${_GTw>I{sZ!X00<`W3z9$P^Ff_u%J%Q~sRdNwvderg}yy zUObh+{e}aG+EfC68AZ1gdxOB;(&P=#lt6d8w;X%}G1FGgVe-2Y50m6+A>y^uxXmkw z&%5ONX`V8U^9*49?@r3z(q=lL3`DJnjG6AK7Z_RV9VQcs*o({I=^itD5YlpTZn`Jf zA?YpUX5ecu?oFlT3{P+!dvBSg+=t-ai&H3xQ!hC;!&AaOjD1j{$=32s)Ur@pD6hU5 z;(ZJ5&Y`$}?v}G}dQwY$?tYYscXSH5he|;{oU#IJ%QoMkGYM)KUW&@1nIS=)RPMuZ zj~Cl4PkBc0&dl<}OVe4Ns)Z>yW)?al(0M_Y^E2)R3@!wV%w~gbJs7~&+Ael zhu<%WJ|`sL={e|+LVumoFU@9QROev-_Fr0Ca?u)%R+5~_MJq}E&h<<$e5hG-Jsbjv zc&@<-;HUNAK2UZgum6M5!JY86aeMV6)skhi8Y}q)n*wfEWzSn=tv(8ae5Az?<7Pf>~#7puLPd4Vn zmM`&qrBb`d+e}YPUh0`fYDT>6d6$&h2d=-KQpdATmFy@iDQSc7A9% zm0o2z$tussgy(Cw+LLBYX?WLo8W+o6$i3Hqy`TWx0|}fWUJG;uBS1db1}=aHpt6ex z1tY*ruo)ZxcYsNATnn@SBfw0s2J8i=!5vUiR~6CvlPgDT#W!ZIw&fjVlkADvQKlKe z%Vj{ef2aT>39J}>KGs=2P@qG1#+4<60om5JVOs+GGd=OnbV6>YTkn{SnJJ8fd6J6s zAw2K*{?BHt4xfuCQbL-2>8TRfn-co!8c2vQ=)v@JR4iFN*n(%qx7^`IxX zr|qQNKj=wGJ%zyaoqv>2dwyV_K3V=Zuf~gWa^U6Z`c9ra!G}G;?Qw*q z1ZNRM9+$JBf^tU?u=K%M?YOi$5)$oP1ZDw(*2e>bn@4VArfS+@Pw)(=lM;Ru&*#t? zdR(d=^;ESFJ?`sv)U(NEkN#eY9`i77_`UQxMpQd|FL{cyzn8C%c`_nC``#aDDQ1zJ zviz7Qc0m<~ODY`qnD*blmyF|{C+u(jAR~`^p0iguA)g&5tQSs5(eDXk%n5l~@jEAE z?DvFq>cpe4iaZMI#P@_%sg{NRbU z_xaIx9~;c59y zarrZH_eW1(Zu8`V;HP)oE zDCOWwu?N>w2&?k+@^3M|an94iPCa9&p~%m(uGydfxMi-SO)&MuTf(Jz&kx zs8JyQ{Mj?XPWc;q(KEq8aq~-Ke?dxt>h+6fhC^k|^(*QJ={WYfXNJCs(yZ!h6X{u? z$M}+d^9;191e$%rb5#F>f~$ljWY2!4#K+(C#H*B8eAAPmm!rV?WkV0!FjI5Wli*Mf zt_G-`lOr{aXYG8;^LAu*S&vPt3o^k#Fc~Za8^B?3377^iBG43c1*1U@*ai-RdmzfB zK?g0sKrk6B0h_@AZ~=s|nlAw~0PVnt2wS8!lOHRToIjIxBDU!;BW;_XsG-cQed*SxvNcaT-_E3{Z2I@xC<` zbi-rRu;%j1nnneT^R+Y$wLRwz)0pn6TDJ&K0D6OQU_Mv__JRU%50s3wY3ZOjMi=XIa&|`aP=m zsFFr-H1(9chmP|nbiS=Bhe{g3L!?egT%5r^($0LB->v$u-Q+6H!Sb$NL&Se}objZJ z-h?}LY$nASS$3k*t(0+B_upCd?W`g5tazh>ojWa#H~L!P26xRDk+cM(RFxj2*JzLf zR)C%01h@fWS=(6|WP<*{>l>P2thYJi$oDzZ|7W9pB2QHc!KUego&$fwdJgW_r-piK``0~O zm5nJz3GTN)#b^>R9QQz?%M#o2#5QWS)Guq){lE0NRIMcMlx6=i7_e09owVz4aTt4& z6BFP&T$h3GI^@f;MxtZWbjzMY+@H9|Xvx+x?A^%8NvkdEW^J6z#)hHQDZ*xXM?rO8AEs0GG{E> zd84%?5+@B*WCufKv@}^=&Zy!jF~c9%qA0~^rLDMbMw)2l8*PX6k<_yoV%32w4y(A9 zgi8dte1L1iD$aG_1msV^rQxRo{0yATb!#{U?gN*FUxP7Mm1;C{ET#miGa4u=>|>~9 z#YWZO*l5B(jsfyM>9vyfp6%NH!O_pV| zz}E6#7gqhz`j%cflBTQ{!6rHe;nZqy&0l(L+EWf3_*2FjkLV;K#E#sNu2yz;s#e{w zvuNIia2vQ8%(R$y8vH!`4b1G8m-W#aGg#iIV3h|=VP>GbZ@^4Ad09cKF{$KbU8dGK z%;jGb{i2MoU<`3Y(Mwl5uA_USpfZ_pCu^yFUx}+|q{JFnPSJ5j>9RD;a|%{2L^-WqB1NI281i{H)v$;NCzYs)o3?sfznS z+`Gt_sz%Uwz*n+gxgWy4m)s0>Z&D5SZ*iY1FIOvk(ywHTazBjwBBftK?o=~^2f2PF z71NEBB1aH@KHi@U?DIR6Uf8yOB}-8-kD~B(KtYcD&FgYVdg1GmXRc10_8mGW#!LO` zMsV`+E18a<$T0*z1w$V$kq;x|q)YV>@3tCvKaSSz@sd`f@NN5*ys8A>BlvT?yd5gI zj3E361VtpeX2_$ySQGaXxEGV9HCWKJtfo<^FlUY^;YoxQ<$g`0Jg533*D~tZ8cC;G z#*2Y5!>?plEh8oRN3>Q?2qZ|8-o3GOU0n~J7xmO@fP6c$PKhDI0L=YFS^IN84*FFP63MI^V0A&zZcECLL5#YxjAje*&lX*dpm z3jpI4S`ugsI)W@P4J-kh!2xgqXt8u|o! z&?T>_krZB*GSN%QH8oP~y^hG>4q-bateKI{U}NoO#$WamN2JEnMh3??y!v>B%cFq-p4Nk9*>jF+ftpoTUVVl(FBOeLM>+Q7(NTD1SB94g2+ra~nae2*Y!?zIFInfWN9AIumx|9)YYLhhVfF_{rR}qY zUBj}Hi^Nq4FUEJ=|GK@VJUkZWj8+dFtOyH9&R)Lo=Zs}G2hZW3K;QizBf);?sGR+e zk>>bT#XXf_&ay4&j-Nd$ty&mQI(`khuEEvuAb53yE1My4EscJ0D@pF%-~_k<-0VK9 z02)hfOC#QMho5FCidCsVj-)Ux6D!S^@^$tHD?*Hw<4WBovQQZeUPm3Y4{CT6h?V8xy z@hbQY{nYt^SLV$~UIouwb3{9Ek}lUAud31cc19OF!B_p&QO3N1`mUh*cvnJ*`c$%xZ7=Y|l!w4#a|&UnE3-5mm!}d2EjUGLy^CqI(h@1<n;v|Ee^95m_$Y~BC--B@pYgazpdqd)%Lrb?8*a=3hsuX98dr6)%IeRTl#N%yV|*LBQHgD-zH{A;NE_$L-RxnA zE!j7{r_tT+Pzlj}uRTt}dK(GYT~F>!f<^i|^)_C&+llSjzD6tiUyFTJ`x#ryIpPnJ zHt~8~-Yg@%TW<>5XpjRog9G3aP&+Bhf(D>J@Pd4>4V(sdKmxlgYk?kMG{^xf!2xgq zJV*#sgy-{S8%fSc5@2Aqq|P?d?C{$+_*xz~o5uQrjGt}9LyP=$^K~;OoMmj<1vxmI z5338ZJR>3|+-&kGD|7w0ofb)hfFP$g?T$B2qP93pcDWeo%G{s;2j z9I`Ts`1JD1p*cosbT99tFG11oQ;-AL7>o`s$ffR{Y}M3E-V!hS~VtKDuE=ikGuF^Ir z81CtLM!KXgFx+vMYyCk^_=vM}& z805?XaCp?Ly6PS(vDJ;PNU|AT+IGcXLa(S2$|j7mjxd}yszQ53j`)e8j}lU0k&#xI zlbsgvLS0JWV;Kli>wf<)qZH~}mHK*U5#P2mX$fMu=WO^fcn+*S(R1O7u=+f#1kd9- z9i9(o1myJt+!z+z)hGKxxE1^s+zDO+_lDnw`@t%_m*IS_$0|D%%lR=kps+B&%itBb zzYo6$uY*5;)rav)_$2%x%(@kAjeNM+7^3^@yG_F~d~YKr`wCJu^1vvMwTb;YtRCYQ z+z7q{&xikj--7SK`S73c2k>9;8d&W>{s?{uZ-Z@YY5Wwn!(YM<_!~GJJ_^(RtJq~* zTaeGU7-Q`~{s(52g_pTcYX>sJ%GM5KdbL_C?sOEb9moyf z5?nt8v%lKg0aiPY$wO<$F?pmValL>I-`0*}5?@QffyB3V9Fvw>d9K&M72tJn8oUKo zJCAq5YUlAMa8>vVn0?#UCh&Cl5Z5)}+pyY+OzK$~dLORCHK}KDII*^V@buQ!WS$xe zs$VQIe&E=?iA+VtJ&pQMZM-#h;>DZ4v80b=4f$s`vuhK}kSx!lri$Tnuo}&30jvB| z+moM$GvO|98(0masBOxx!tLO3aC`W5xDz}FR@;`}fnS7I!m2o~f_rkk9_|G*>@vXG zx2%d8i^sh`!F}MXaCcbcTYp&P+skk`@gD%Id>aU>VHvf3xePo6E)T11%M}Bx>YuuP z79J)C-!@*?{q3`|udj}MO;($j>2)yg?jJZ)o0-dUtu`}PgR^DUGNZJe)_UDCDlxN+ zyzVq@3aq?Mg%e=LbG&q1wCQj?cm~`Uo(Z>sXTu%g9C!en3r~dS!m7^AgSWu*;hpdT z_;WZ9CY7{>@L`IYwwNE^?z;DaT`9^o$-|*YC;}U%~JSO{Hq$=7g zU={86;G*#Ra7p+BSY`f7xG}s6R&C5`ShX=~$Ms-%9jr2aJ?w=yz;D1C;XGLF$o>xA z0;@b_N4Cn-Y->lhs+`+!P??Jz7B359wVklaT(u*cc_3>?w#wAqT&v7fJF)A+d*Md# zmv9^SEBIA-AN&ryAEuqMc4TjWzv0>kAAmox#cOQM*1UUhI1C?vkHSacWAgWM<1O9) z&a!D$MNMaApG2yLc7KE;w0@edd93<#3?DyQuQ$Fj`K|uSfqjABKcTPExd2w_d=6IW zd>&Tm{9m{<{4<;i{{pM~T!K}ly9_r_>2;MKDg&;;&% z1d+A;JL^58Z2Q>9=y8JZKRYt6@))r1y=7Y8o)<1EVU_g1*)(jbH7>d!scD%m>@RVQ|6n#Tv#rd25U$*G6W= zE*A@$Y+qxT4s~U1z8Sa1_>wPFYvp0bwMMLS6S|J#p)*z+W$juzIUgZtSX{neTlmGl zQHrfYuo*$K;_}2grUBt@>x`rJUd5%xdZWEnIB&Dp zC?TJ0G&1a8myo*~jr#WPC8fqDqpf{bNtwFI=!V~)H{o|Hen*#*A|LT#0@we@xMi18 zQgt(4i^fae&3LI8FFQ6{w~O9_7Ys5uUyGOeTSB5b20^iH2xiCoJ80VQJ|mipetEbS z+I!w8=TrdO(OVubo~`r@;i_91O!ap{H_G^}C}8Trc_v=oR|@dgTa9*w3gvt#e2juS zL0b6=2U|8ut`h7-5T77BLIr;#aP30yR07#@NM{lJHp8?(l_1Y;GuqoHCCEG5c*;Yi zhHVI_?1V^lsx z<<}%h`?zqdbE6DZg53!2C&}WE$sqW%kB#1i&r@Y53VTo}pDgWnq5x0WX=DbvsT<|E zQuqvo$CKsZPVNq;?FvztxC@2PQD~nmt9GFPV^5x=BX$`z3hz_#6MFZ1(VCka=-o$0 zMa9a%PZ+qI%Pl_%$%KRGI=?`-cp16-32`c3#+Uf1!A|#I%gF5A#=yYGyhv{MhR>@oW44U79_Zp*Hf4E&53 zH7o9$@R?D>rpoi|&yDML3a4+vm&PiakRd-Y!fZl?7jk!uI= zNS=8PGK@ghbUx_M0qYcq{DTa^wztxg(E|U9sT<18pTno-$uw`EG3W@gz%;M|>;%WaHQ=T@ zl>{1qc3>cw3|4@h;54`cVpD8YwaO_Bs)8QC3l@TH;4ruY%(9I1fySVt-2aXN`-YNy z%otC@w(OX(HarW#OkbPh#)p=50X3Q$^#c_rLtgs9c!`$us~-$DM5(6rq|wy=*b4Nw zfy3YuP=>BzL1oawH}RCwGkAQO$W517V(S@3qEv%?)+pgnmficGGuA09wk0kb6iw_WVJ5a9-CvqfLpf)^hJ8#KG!vf$Gv*Cf+lyqB`il@n(@V#9<#O z01y0e@kQC)r)+r-7+N|{RWqtd>I3R2-0FcbKlsYI_keMa|EhY-aT6poQ=21t4wE*q z&fs{)d1?7KQ$ZKdNqM9*BrCMlJ}(>5asG@>dNuj+@4`0sygc@h>c5EU->jOy`UhIA z^D+^M^CDg{tA&pIs>lW(RDB~G_*3I?67>)Dtavr4`VTLj6pKrVS2=RexBp@2THV4@ z-Q7JROfLOnlyqcPv*y?rB$x?RV=IukpgHIYMu2G`AM6Cjz%_u`Lak)QK!(0%ZE^OQ zPV=lPyXrli=Qh=*tk!PxU5c#Sahnsk9Il($rhm8LQ`V=eFV|`3fI6~ao_(vw9IUqL z__9p%iEv8l`e?I*W#88wYpzqFAc*xHP#1)Sw3y_SFsCZXhG;WZDwp(MSZe!9n(Ndu zB=J^5Z&rf&g4!^qL~<{|vgWV5JC1=XVh zzDrj0t5~<(S<(DV)g^D5`7n%QpR%i&qwMysjFqXVnl%{A$D^-8O_Nj1RS31r3fR)0 zUd!AbNGR!8+sv^&>APIp99}&;on&nax`He)4J-kh!6l%jkv*U}=mAE9`Ctv$2MT~z ziL3#YK~vBbi~u=cB{&AI0kbmAAZQMHfYFt0Pii^*SP6E6)8Gy;tDp#)g05gR$N_7> zUQht;0kbN4QmnsOsY-)tG?`!omQGAwJ(fkL0<(QgQbzhn!^1kn#Wd;|nK9t-nGbLPO5o3ATo@E9n{vXPHsAehMK|6GY_TMFuXbN)=L@= zGlOda9?C@J9)|l6`EXds?Jp~L2Em<6C3<*>dz<07J8@qnWBAF|=cU8Bjlb*oP;TPp zbRj-^OiGO)rH&qBae~X$Ixw!M5;2(IBS?{3M}6;%Fvr?#<>axEW+g{?)Yo@c);ZrW zoibpg>9JR2{jl2QkTcRuu%*k|k!C+fFVsqpp~*@gWkxYZ(`1zSlw&E5)&5~#Eq@f6 zt7O+GGuwXjnD2?v<|2pw*z9fd-%>$O4nW60jK@0GEJPlZpV+K?~3uj05w* znwo*Oitk+!$wuIWGUNXaOSEK0HN#`#+xUBXRCW(&k$!Gr8g*@v;a0tPG!*bRe64VwY_!hy^{}CilL~t0vC%mI4h4`4I1V<1gACVc8%;4g? zFXVS6U~R9n&5?im=s5`i>)D;%{>R6DCBPhk^OYlVYm!;U4i|sj99@_K3tmToCFRcT zN92>&QGk^~V8Or2)nHjw%Ntb2KEB-9(xI|$$UvsMcCTRbOTlC_-O4hYs!P);W`a&O zQQhgT`MaazrkJ(#HUYP4{vP&$DJBO|d@Eb#x0}?dD24h%glw8hzI$;#S6{rHhcSb zWyWH<9T!)~-Nj~xz2Qo!`WD>sL+SgLS>HZ?mAvzo*_Md^{uTkf!F%zuRg$>G46dP? zDub3Fn8_XfyGrtw6jtx4az+U_TEO|oDse6~TLhY{snThwnUc5E46{e9R)S=Ccc~d% z1~pZVBX!Oqyp+}Qa49JSSAE+I?inE5w^6`gqO&XBmxaXSg=Gk4<8#<*nXt?Zu8N*2 z`;}l0f=#RC)-uuyPRuuhBNJ0)Og;)ZDEzTn-pMyp?eN$6X2-&0thk(9nZrFxuLOwWWowF z)zN(&?R~D}KZVi1kA`aj8e`XoOQW&0K@HwB%~D)hWmVn2E(5hEfEw{0yIy*|XRdJh zzi_5X#QWSJ5AV-ykc{_39%!Nx2!b&iWL2o(cO_VeV9Ewb{D4@)&wXHK6{gXi4@l5O zC{*7VNYLntQ8Dtv3xzgArb_jd1hN>NIUA+(%8-oyPzl~b@Wn9jEa}_b3#JRRXR)2d16yAE7Q<9^`ZHwg6XT!!TzdqP*A5y8uO{GSDDdz(5aNP zS;`U551w}fM{1_Z7W_Gv;m^BC&aMiHSh>{*sL;-do21q1kQ7{mAaXf^Wq~_s{f0>X zUNgae#P_w;)YfI2XSDtqi^d4CP{$bY)xRJp%~SiXbbnwtYp(y&rgNol;cu%Afn zT+5B$Md$6!>c$*)S1Br7Hm{{+$K}hl<}mx`o2C9bb6{Wv_*7ZDj$l{drSg_Qu)8Xe zKq2N_rb@Z>1p6L3&ux)b>kD7RQzaLH`96XULC@7I|8Kt9HsJXKbQW%rv<)GN@v0K6 zM6i8}yuE>{4 z?2&Vp!;-FQqNPn0GPV0A>M%}Lf3vWB?nl{4?Q{;?Cbu?GfZ@cCNPK^nb*c>g2!*vM zys=#te-v_?b4sud!P4#G*&HHhvl#(3&UtpbjNNRel{&lK9}iXi=BF_`%G@oVs9LEV z^2uhNzTOVGzS(R~BhYLMUN_*i+YTALB_zeRD*2!Z|MKq@3xBME=nN-E$a>(kiRgh`a(CTd<;K7yizIV*lF1AKG^Dx%itR9LW2 z_sE%hiee661GHkY-}_xNNlZ4XC66$XB?SC6E53XA`|v?nOo^T}TG)}Ek`J)L{a z6R!r{nN*Q?lK6CNwL49|K z?=$5D1T_%w&_3O3Nwjk|UgsDd+Gl=xo&H(2&s?|9SH^~YWb+!a-`Z!s*++H0wXbeq zV-Q~e^lLOD-r)FdYBZOs&)%=Q zc31H8$YXB?4H(wv<+RLWJX4*_OAu=Vc)x$Y>A#W+#e*-?xN`;!H$QIg=Wh=DBPhrZf8Q%FfA!|5 z1B`zUGJJ0$#Cc!jEV+<(=8JuE^~qzICSK)a$km#gOAkPo^)dg!r!%HAf=UfXQ%Qm|b;aJG?-2Agm$J;@R@}9z( zg7Zbl)5ZJ-$g{uv18_O~5T?Qwn8y0ueoSXq;vNLkAuo^e#R^#;{RTJ(_l=OXr+nYk zSPj?U<|Sr6*T8!qkjKaQ+u-dy=FG2Q<8OF0!n+_Zg!AxI);Z6IHs^aC90m*FS@1r1 zKHLB=gAc%4ATJ%{Gg)S-5FQCb<}mq)kMq@+e9pd$=hMFB$_@Mq_g40l{}UT!c=++u z_EE@pf}KzP<}ZSe!)#a%AA?W8M))NB7u*Id=Jplv9QYJWfltFcxE)r)O85?Z26n-} zLtaX9?Qo7Xj*TkFN+zynVG(=|z5sW^Bd{9&4tb!PAMWMpJDdx5!Aw{KABHc&ddO=u zz9p|;hM(cCg~#D5@C2-bLH()e-E0hJqaIF#d!V!U#j9`u+zXdO-UiBF4PS$I!`I

{_y_dB!8VWM;hE4M&V&Il2?oM6cnZvf zr^2-`2yTKFd=%O+uZE3*Y`g&n!4KeI_&p4P|AjnN&ksJ02>~1pd3iN|3LFj>LLQsv zUjcb6o}UGIE|h-{}`oC*5}JHI2N{|{kf4j!Z7#qbu6y!_n}5I32Es39tyJzzr}RJ^=3?O#k1^#zs6Igpb1#SPdV7 z4e(+3Hhctr0!!h);1>8FXrL7$??Q&cGTf2yQMapbE8K>AC#=AI_7LBzjfGjT8vlYJ z^#AACD8=Ii_$u55-+?voGx#F>4!#6`g)c+Dp-3tm1Ydz8VI7$BW!`IVF%1}UY+b_<0j}C>3fB;FbigLg!jR_;8U;wz6S4ypTc739wl!r z21Dnq#c)^(Cqd_}#q*(obKzEaIV^)Kq4N@B)+qYF^A=+P9?n~g#n5?+u^c`DpM_7t zI=Bt)hZXQJd)^L=H}s5__Zw}v2loj0Dm7LN z8*x{_H*k;58{>O{vG6*`Og{g1_&(eK55rxs8GZ~ufG6OGFla3AEyCgO2%HE%hST9E za5g*&mqM-#@>jr5VJ7^HwsJo_2J^mVqn!;`1i}G_!yjNY{23-fE+z6);D2E{{2gXN z=Z(Pv=)5sl44oGS%i*7}3OX+gz5?BTuEL0MzAw%co(C=5m%%}Ntf}x8HuzFZ;U>td zeucHrd9|+zj)O;_^NQbB(D@?F572ql?|0~Y8RpdS%pc(Ca3YL=Q7{HNUx8t6(&|5l-==|KGvJIe4stQ{f}fSrlnIbQVRbf#<>o=zK}$AdH1apz}qUcIbRj zrW-n6lnI!CF2E4zd|4&}&Vn(JAFJojfwSRda84c@*RgRiycN!c_riJbVd#8v=1Djo z)x1pEPRho?r- zui<#O3oeAOknSp22XBJA;a#vEu8*Ss?_uK+JYI#{;a*q+xf0HQ4Za57gRjF+;Xe3p z*a&}xZ$SS^T=BqQxF3eWCKv_Zg0b))@M6f7b^a1~5MGtX#@lS%0N;W4!FS;ncnCfN z--EBf_u*UcF#H%c!%oQhmid3ckD+}w{T~j4pTWuSb9gaqh0Ea=@D}(b%v;aKF*crn zZSV#76?`536TSog1wV)1!sD<5{sudt|75O=IJXnwe{jb^7Ts8v3VUE7`~&||_$RD^ zE`J6!$SN6m`E6`?{b^LtStg?wI?H4Xj%ES@$HDE zYvB~Q0XmCTRKj!NJ~$nI24}$IFbehOzK=xCs6Y zro%hnT`&i3gm=Qn;aXTdjsEYPf)+gTVFxUL-LMb_p34;t90>2H)t(18!Yg12%z;}7 zFM5SOg9Zhp)nO;OlTU+z0cPveC%K8u$jh8@>r2 zhW~(%!2|H`@F3g`--ZX^JMbg;F8ms@ct-wl*bIMzA3*PUOjuwjz!sRlrMm(8|2NX{L`UlIvbH}_`&m_KfD+Qz$GvcrovO;D%cO+4Evjy zwxGtkKiYx@^M2TOK~w8)|Bknfyu3x=a_$_@VztVkLFVz!par}#Q1|c7ptXL^GyWU8 zcws{x>GR%$N&B27AC7kg4R;>h_y37^19>FB<)~6yK-_0H^Hf=3^MzAf+l!) zwEpj&plRM;HEf8iBQfK@yl7$ZNXv<@ej6RXG3pm9rP+58uLT_YZ_qpskIc{fou?=~ zA;0r?GJH`ZPLQ2#o5YViKl(jrl=s*F4H$5OQjFYb&N~rwg}2K0)S5ScP1`?N$F1f> z&>5bFoptY>2;!~p%d6|Y=nY~KHXcR~{4?m^o;zQt`{U0bkJ~$+2Ut!)&o?i##gzmY2HE&+i9Aen%U*H)_CQ~u-kQ&=~_ia%k7ZEwLFzyOF18LeCuoLUhHRG=JvewN?rf{);PC!56{7z z`ngd~+JaN91)hlA=FwBFE4;V(9$C6wA*RdU=7;1#*0&xWJpMO`x-0iRMs(H@^wrY> zi{i?oMYpqT`dp6sUCX-L!?VNrwzby7qr$fx@?>!SY0&ekdHXc$Ixmm)eEZj$S}?$x z>Ybr}L!`w%K7f+*3~$c>YM4iMHw0S?ohNg9f~|k^%&qR3f!4cDvqk=mSJnK_1NRs z%h*xuM{M|Xen5mR#a3hMu*b3e*yq>@Y;Y|3V9T&|*yGqf>?r0sk2n0V8Q4-HUnF6K^{9|V;i;``x-lejlGZv*h=hfY&*6WJBs~?4VXz` zu?5&lY(2IO+lL*+e!~XDQ)}1)Y&EtH+m7wUKF5B>2ItM}5^XN|E@*mP_a=KKPVheCoWgJJuQ;7|UbAA09E|##*DT zA0CmH??*VlSvOfrtTW8v(VjE)moj}nrT>ZXWho}HsYCgB>r6lSU0pn6hUmK%T@IaV z(QDys(>c~UD{u|vSl?HUHz~)cKqe4@e_X5UgN?HW2QZTe9BwMcS!c7zaq~DUNgtZl zo5=Cjm;fdifzwRVcxxnYuxE|8BAnOQd~4(EoL~*M_7Z#v^FZo`*;4B*{?Yni^i>lO zN%9857nrC>D_)o2bn@$aEIN-ge_YF|M_2eKn8T5lzjydbCoAU%LE)WzAM3|R>t}Y? zex~&g_a&zKEbA=41=sPO^Ge<$*mZG#fAiZ}*2Hn!ILh7FVeDrth&%kFu<6)RY&EuV zp1vPz^v4>LIP?e}(LQe?CRyX%&(|eRvMzDE$C|RUVTox!+e&ke)cI`7^2tOVM`X9j zo=jvnD}!0@vy4<`v~`K+U#(_Ov^9kl#yg{}OWk*v_$k)a?g&#ch2tMjsxWhqO?Q~- zoI>r&)8Pm+=Ny735X}4H=aA_NQ+kedGqD1uT65jwOyX4Q9QQ_3Fx5KW^Vu=;+EnXe z&o{?RV2pKxyVhjISXZ)-LopT$29Zf;n_1Y!Yu^K=SwS8gBc@qEo3gSa!Ip~xBiOFJEH(x!9LN1KA_R+7G)?o?Rc z$(!n7He1&*o#MIObrI)VpLi&IZ=7Y^E9y!wutxeh<#_gldsyA!cxwhms>8jMg@$bEsZx37gKxV z>k==vynnUL)pI#x;RK&+3g=Sy=bEayR)W4o>m=(t3a1HX1TRDQU^ylvckYlNSxKR@8Q+`qy6*5H{! z)A21pl>bkw-|4gaqQe+cT+m;-zG<7rOG5WvVg-9H=x?@MV$IVPgq>{rO1Q#F>`UNw zT_7t64_LtPO^T})SXWrLQNZ=sHf+BZbjFs2)~LWUIg2ryPX1Nt36nO0AK;utz>-b> zzjaU-(l{m(kh01Aw9p#um%=iIKfKIaU6U7CgZSlh>bMmUF2}vZ0CS>*I|6LWe z#tE20z^$AAcU9ETB?O#9K+$GrRn#G7*%B)#xM=hL39dhN+9^w;cFNMIow77)r>Suk zL+vz;&eEuzhV?-l_?AZPG~v$DsHAfiO6@dRLs-3N*QJ&}+a=ES;lH*AnZ>L9{mt=9 ztpUM#e9PRC$6>lS36cBOP$gmHQtOPcPWS(<(Q-@r%Ejq7NpwG7G1HbJ2q#R{QjTgm zNA=kwzSUFzA0vg+nqzz`$oDPPe(pj>gj4Ze1cyLwD*6^ty$rXPmq@(4P~vrk{Pk0K zZXLUpZ1VkpY9Kcpd2A>Ps`ld$Xc|u>Tf_2FeQCLW0Q(dFY8VVxK%Q&(Zb&+}ik zJ~uZde8uD5f$uhF9NcK4E@vdVO!hL+xv6>b;;E^deT%1>T_gJWJMWSB?t0n|P0i)j zP`}lhj+>p-nk)g!)t`%2>@1cV{5bwj^e12l+-Aa;SwlUv<@1(N`IUHc$HDasbSm@j z&>8x7z)Z-!()>#J9BhC);oGnp9)mByUtkRk;H2`BP`(9Uf?=>0MnUJ^sxz;0?yVxv zzI&^SdARSpw|XTW&OOy9pmR^P4Za3>nCH8vnhc$@dKr8Zf1VKe?xB7ToqMQ*Y1z&_ z)Wy(=mjs=Ar^}&p%k)X;+%n~^rSF#MFgmPr%k(mTZZkUxF2~~oJRXG~Lhd%WK7t_u za_=+=wy?yR^|bdh-$cu~q;yuC9(asc&RKD8j1Gcd`I&`RSffKfM?ZhW`dz~80h^93 z##WhvE37fY7W2BmD(95}Y%8`4JAfTqpc4z0q+8CIbORmq0TZ#@iq|odTS!*FaWwg6j$t;cp^`>}5^=Y5D#*mP_;b{n>Fk&eUnZdq%MI^}n!1#N%u zW23cJxE~vJm#k&NMmc=5rwRGi;8RWzWx}5U=AwKn!q3^bG2gmWCmp|=rhLS|mnboW z{E%-&`#Bq93QmfWTR@aQh*Ckw-wVja*?7OeD)D=tjcf0*lHI?X`g^P~L4Oi!Fyk_1 zcbUc+15V#^FPGwjU1s3D)*erc%e;55HOVvEW&XI=x`{-Y>qtcW!1wzSx#M_|@P&1Z z%kR6)8|$p~f0Z<;5D|70_Xn4`v(P%z1D`1*+W@z@=02`ihq%p)_gPas)7<8p``FC| zZZqV5>jF=?+gx_P)%Sw+@22X0GV+koPPh5servP`{&K(dg{R)l7niKtJs-RI7Bv~Q zyUjgCWb{25I}G-iuZoxp&h?lxH=LAV?gldCeYe1?JZAm_)-bbg15-g9?>VvL)#Bex z_yg7$vu%Ur@449*ZJfjZiP1!izyR{e_n7Y=u*P}dkd4;jzp}{ONQ6KlSbk>9MoMn^ z)$Q5H4DYWPy~UiX5<0>^{r~6Z|4uvUo7Oz&bV1IiGuxjlU-8=^bNHav+q*aD2Nei`PY3+l3rmF0Aie{QvM16D3^ zet3k}=90xh&axw?+=Xg1@bRI%jhz4hHP1Xj zWBX>P`Sb~EEvw?DJjq!uAmT5lo9CDJ8)hDVlIDct*(a^@_?de9lUAPR%TROOHbmDULis^7%yG`sF-E$u&MaF^*Xhlwu5Bvk1|_!(4{{bW!~ChT|@mvR#8kI zN(5$_q$)0JGEGjEb*uXU(^*BGJ!Qh5wQltEhMP^#vh!0-Bh@(5=3u4?*$E0w!cJ?E=Z7)o(VZuixN|25T}0YpWA&g5;(0}V zaAdhoQ#4hXn;19;ju7_~0oe?_fH}o?$9VI_ zE~*XMHP)l<@usTgq*L8nLp&bn1kQ~#8?L71&U}%}+_@(4MeADkLR0f11-O@GZca)P z`w~ftNpdXGT=NoH!-rn7o^{8XxR;53iOF)X+*H2I*;{MUYdN}2#DCHh*K(SkG_|!> z)?Y0s>J@@F6YMg{uaM4Vie9lY{tE7Kf*&M!lL@c0`j%y1YclKb=Lu9`nJGQlzYYJO zhw$G%QO`}uMRcn1yXjQhP3&$f;jgTVc9X@!M6EM5yHCox7yrOV@PA_>zlE@7>Rkx- zSx-PI0S71YTL@Yze69Yk0b{KR-a~}z(eke+nlFBLPu1Hvjz0BCxpURwXqDW?*~8fK z*{O9O@3CI%=eJ`hKc1d!bGPPAYl2@bF5lhspWn0wcwZUn91Sne}?$-1_GSbw@bN6)DH>Y(+#2i<6XmxlY!h`P~-tXKG&&B(e>-?R9gc4l4j zVduWW!*xx~%#*p_(E1_0#BJ3jd<sX}h_jUA%&%wVNa7Nwq z&#XJ#oW+{YktE(eY(-W!nSxg9To(BTXPA##t>IL5S1S?fO#BztxgM(W&M&xGe9(7R z+%8>!``s^i3h?zr*5SQ{yHvx!v}WWzg1qm<_G8~-u1lGXViU31*m7(QwjSG#?Zu8^ zzhS5I`srkB9<~C@$F^cGWA9?eF@Ii7oq)~6R$_N!+pyi(=gF+H{WBW_E+Z1Q09%RW zV_UI(*iq~RHu!SpdDvp?Hf$rd3p;=v$NZNu7sRGxi!ERyRk>G-PmF5XDld%qsHc8 zcVmxWJF)%Pw<$XLyxIA{vI#oQNOuJdbd-rWPG4kQ`r}+>&B*aHn>~K4Cv}*03Em6# z1PqcVG`ce4&#(@HMYJ#BcIPz6u{^67TIFtpj?riR^EW30T3| zsWD0Y?Y<8=M4Jly1E-SBryrTO``dkj6m5b}B_NFi-+yGzJJs%6J|NoU5)cqWiczNW zRJ(6R!$ibMFb)6Tj~F}1KGOrw3$h^XX^=%ngXRp+k%OQw2&eWl+gEbV^b z9)E672HO*;@VbS;_7pcukQEHH7kQ|`FV1p4voz2i?xEKD53;ZDj^YI(M_egRLjNJ= z-a&S>-|t8K%sY?s1Kq=e?3oPQ!GrB9-8m+6uzjw#g%^#S_^BoMBC)yZmn2Pun_*{fG^}iuQ^v$8N(O$6m%h!j5A>SJN)B8Q48t{@J!61y9F1lx%nUZGw6@>ho0*ZBJ7$}?=IUz$&b+s-E{FAuX{aC&F{ z7<;f8K7vTo>hea|5BR#Q&vVo$$J5+9$``S2YPdbg%@Q|eeTrKL7buzjDjt~(HEuO5{5Ek$#s(H*fF*ivj2=B%8!3p;@Qj0IhT zRAP&cmVKSydm3ZSMfL!%6xi*$ z-lQGpQ&x{(WUu$mI90Cn)7} zoOP`(dCfoCY}@M@U`CzVKgc||)(SG)F1Fv`l=^NM-7(i5e8CSSy6lD>F2~&(aE9i{CpK#tg*^EdyDNSkuY5qgNhRNo>lLMLvF!>3# zzo%rf`TpdPsQD!6Cdt;x=Cb)GH~ltUX4g8m@FRXn<)-MIKd1((BPF13Tt=<{-_Z!85{jRg|r?wCMl@^y($ z1HR`g8tmmyGT9bm-oDhH<$?B6dx+=R7&C6Ez4(+XeGA@wZ*rFs(Z#1hf~PqV$C-DR z+EesNM_-$Bo{6u(=pq!zdFdxUfu1}$*% zx`WOz>n^tkxHtGVcR8CSzRl0s^w8wKzubP_X<1J!v#;<>^>LUPoPro!=4(fEX89uZ zniPADmvige{e5!#=|qaXjT2e-#1%HLpKu-?O(i#~d;V4SQ%e&u0d;tVy*|nLA=qGSA~q9ShONQYW81LZ*kSBj%zqW5Fg6`qjIF}* zu}83-*gov2sYtWOj6R$}60F}12op9FTZTP|?ZA%RV7^bYhXptb^R6`3HTD^KO;yeh z715A$oOIvr$1D(LpC|r3FNixVNB!O6AIre!OW!5_&P%6`yOWC; zhgs(e2cC9YDbMOPHh-<^yi!X-i*zY}oWQSHLE0P!!~EAHlGp?8e1 zOxtj}X-l_9hPuy^=t=*Q;Ff<2TTSS7w3#A3H-~16cRc%Y_SSWpuzZRz_`ecf;U^5$ zwvaYS+zDq2b0$js7_R7?e7bpr=Wxy^!jj{{=nfzATwP2hoCuNH0}{i;o%oDIjGrX# zYNq2(yvpyzKjUU$q823ClJIceTy^4gj1pF#E&e$din~<1YW#JM`$qb{R!H+2i4eoQ z-pL?wny@`ah_d+nGiC|f`wMgYBs@f$XASccCw*3(@Q~I}x~aI{9-nf^U!u3(Ai*KG z2?MSc=1vf1{3uLNMVQ0A5+~cvZ1JD-gs=qxbo^6H_$qs-JH^DVvPb5{d?=y4DsZ_f za2?t>QdHooRN#_$;_BqmD6P@er~;R)0+*fF$^J?ck^oN9Zy(X;MBTRiz*uj|S#BV+<%zjH4cS6W#r7}3| zT2;VsZrM4}+ddMes{)3q0#-2`IN@D-?n{+Ps*F9Vj9zU_*;i^ls*oLF;_l{Fj+0M} zG{Pya)IgL) z<{Xu{Ln>`eUrK!UO~OQ#xVRDGu4h1Xid(LSm7XsC6{>BCvR{w$I_wSh$nf|!39nX- zvs4S4G=8OtzR?~TAFGmAbg4wo4p*w=mGp=^S-WER7ID{T&&o9=H`+sEgH@<2XGtkb zh6#H#`kY8{cYQ6%!&E_=Ok=t|)ckg%Jz&;BZsIvd7^SLbsp@6-6aU`Jb=S7$aZDI~ zzp(pvGk>)`DX&w-H$u->mC9N-H?f@jgFlh@%_?Wz-)cVEu6s@scebimhN@TEO7Sli z`E$jnie>E=|AOg0njco%!Qri1UvVm3hg7nRj=o6?|IT6Jw zC|Mf6Lr-Xp3RScURgwx-fe6(NuFB^%V->1G%`jZgXxJ19FMLkOuOobCzIK)wtK7Aj#TpJ10mrReUGGv1bUQpA>fTl7!QqlO7d!f$DtATyghmJFVR= z?&c6-qAF73>5{%t6{$-UX_l+mD*>%4S%oT1xlxkAp-f?pN>t4+;*N@tbS0*lxiF)L@DpYR6?vEE*)?WdnpIrwLk@9Y|K|3zcbYeDvnNHid?WtVIsnA$1mlnn1kJnw<(z_I z6Pj%=b3bG5%(h2(1GE`6nu=_DX#XNTFTEqp8`<`_BuhtwT0I>}IwkZT*HV8gOw!Sy zc!0Qbw+f52T2qy^CiZrF{OA&G+|hbAqcu2JJ6XpU=APT_NzoBHm>kq&j{RP;4PPm& z*G}7brno~)8`+;9s?m?E7wfsRJ4)-mC0*R{S;CfOE_43h?66^#tHdKq2bLz4 zxTq)0Eq`Os%+`@4Q%92A+a!Jo73|b;t7?AkdEzd6TMqfJVwslkp`bX?>O7BdBwVuP;Jt2I-tb=M-r!NA8gYBB~b^Ixbq~lNY(eyizR-B z_Q7-=ND6fzNsxiW6|Y?@N5+%+u0uMY#Or`^NT=K#I-sN|n{{A0cBk72Qy1l{(9Y2b6{HWHBmZ0NBnF?s(`4T_iN=>KN{JE+mO*(!Q z$4YpoPNdv2am{m;-z5PBx`WgxsjtMr;-7tnFiJaQxQ-}E+QVCRNO+mnci0edC#v9g zX(Ml|5&v2lNn9zuxosYkRvj@abTS*NQ>QME6eL!)E>ZoR#a^6N*L+MEr_-cj9Wnw& ziGR^tNncSZZfC&&C!Jeovq!?&X8*1lonpjYC@X!CE{)flY#|o7I#95xWhgYcUQT_(*kurDDJ{| ziB}(n+a%`Nr-lXxiC4@xiPC(ku)q3OVW;#FkO=P9bxK%MNP?3X3galTY<%3P~y>t=~!kGE7#1{ja><5fZOMXG>wqYiJPvI91tzvEokCSx080&u!kn$M!}xsb+W0 zlt`(%(<Il@K;&-r3(gmn|rHmJM z_7B2folpkcAnru1#ke%dICrY}S8EgNxKZ4p*}~>TVfH>Bhq)@XO_e?^0rjIKqjD2k z$Vlncxnr%$XqZmj+HR0&sp-N)3nY1l%4sXFpE*6ZSF1Do4hiRdOrL+b>S%Y2__wK= z7kR{8Rqdn4RcdMqdGZmh175T0X!3IsFT=D^%#?s0ai;txjBgem(q#48)529>vvsPK zs&Z8^TjG~#OFpRil$fOZ?2$?3Dz`=RB-)&Q!bX+b;2PbX)>4$po3mDgQwx>aD64b| znra&FL-jjU4+4IXXx*{GY!%xw72D)p;@_Jitk=p7QN8f0ipFUpN=}h@kyl((>!aeoWw5e1kpMR3Dv%vs)F45lB9Q5 zs&lF#OVcH-lJx1ek9n>bofkH*kbrDeB>f!KvgQnNhpLwK{wVGw z)v^xNvU=6BhJ6yAEz;$bw`YS>Zy$+&jB010?mtmAD@wJh?LQK)TD7V|yHn{4>aSWA zr|CPo#ea^rvV%HV^Zq3MRhRgf=Zcyp9+fI)2escE)X89qP6pjA63?RL`I@s%1|zis zQ*`_;P+bU9W`#>d2CS2Gq34M^$rsM7K5344WG<2jodbobs$Wg2U)|b*5_U>B-$(Hk zq)l61dx5yS^|nH^&Y>hE?F+CgYk+Gqt$#F)_7bd9w1`n5Lg%1d;Hw&}1g{7PL zVteS6tYhNclpx9LUlezM>Qsjg=FZZdPALy9H5-cUi}Tvs#GP@I(0W4c8;3w=9GHW{1f z0IAxcvUJ{8sq&Yt@@J{+Rr+L)w+hBc@+9pzHCj!j+746oY&85!;?--js=iFzg|;wE zCL=uJ%odL(6TF%7q-j27>RqJ!2~+)#*d)>C6boDRa=Tuily|6ndcTwK4lPHCcI1Pn ziGQs&@2W{se@Pek{71WDR5{%@OT16XZ6|XQWxuJXN_e)WPq;j&|#{zO>ir`hZ2saBngT`1ul6NCpQ zxuj*{u4omuUnFc&vCB}gi`K@{sv_5@LM1Hjn6O*t3>_+g%_?~{*GgHco|Jeg+IA1=gs5Pewhd*Ep4-eyiC^#A zHxsK!pF7W0quSY`la-j8Bx3B#!nl#bfQiD|e+tuA$d0_KnGt#xl2scm(MDI;V-i0} zN1Srizzm-T`tcH!so2EL;}Vnh2+w3oRN4yuCCOSp7Ut>%FUFJ+Ex7%3@y^zsookvO z;YF)#6`-EaB{)u-kfnvo(b^8vrZ?w1i5II)uSwIFo9I%fg{p3ah;F&cJ0dR%W&eTZA5d zj?M@}RM_fGPbt4EIW)`++hUIhcV8^$s(ZKOAFquj^8s-en3OH{xfw0ri!)30txel= zgz8(a>RZMv$*#RZ;=A=4w@h`ecB*C@An_7a@4|w_pQSvu*hAB*G9);+SiGH;MjaK8 z!5qdtEX+Jh7_QyPyFlEnDqm$| z75|uCq1!YXu3)Qm>`7KpE1oCGs^$n=M=SFrS*A8vOXrG}VG>?`o`e_f5?Us9D-TP; z{}5-|2f|Rjf(q~#cZ+IgyVl(t)tr<;k}V66`zkBzPhpobKwC=AV2M{2BkW3)cpWnG znlHE7-jvLN5*U7outBS&@DYjJbhY@GYj{eqxNBBOc$7A~SlxMs#)~lVW%khMMr}vE zXG-*f1(H02Gwqz{?2Cmd;X=z4kSs6sL-n2^OxNCJ{U+}0IAL(Autl$e4{0xJ(latg z(cSemNtn*6~mmP60Jas+4GUOv!)1ZRk^Kq#NB*E7`#n* z=xbqkm9SRxN$%@GdaYqe4>9I3J2at7Pn!EBNff4Ym)hmx<|oO%Hj=7}m#w|otDQVY zFVVSM`8eIFR5hYwvX(_p;T%oYqIX>C-<9x&T4Cek!k8hlyMS|r$&1uql`>?4_{XXy zRn$p%+Y>%6ai!~=an7j{F=>FX+AZ|zSf$K|=MM)NT_0SQ$B7;WtQj-4BU>!qdW9Z6Wd3OL&E9ZaUr2jYa9yvgHzShn(wU zo-0$QfJY)EpiR}Xg=9{`l>Or0pcNgXYTKl08>ea;uhNpN=^NgXbYUv5^?iD#@|s@g zg!{3gvI&2J6CADb8n5ztL?x#}$!>k+X*o}r@v<;p`&Pa7-I@aNPt-Yfw+{8r7mA$Y zsW>3))X|`AtIvIn>yUQt$hmUhk(NaCsxWtW#otn~i`L%K^r*yZP(e=b>wQJy->u_B zgo%8Tc~HY>@y@wGvP)7)^(vc87SULJuH;F&a;*AxYildLRZ@qf345}H;W}zKUx;yz zvPP9BRgTUTtBMt~ME07k3e}n*?sz@uSXI0u(j8{Ga>r`~ol3`y6nDESRfZNUT5k|k zv3sWg2^~_9G?TT>{v@yI6LA(Pb2XcmU&Y_6lAoZGU#aTRbCHA><_W9c5JsxfHmKB> zTrK{UD)om7#9bxzG02sz`VjAHcD$U`Za%GG1{Kp!${QLf3BpDQbI%cGo6x81k&yu^ z)a5GFC3^TNdn8(;3U!-FBRXfV;3;&v{uv4F&{~aAolY_}Pub_@c{3!qY@4uLn`DNv zeu(%Ne6HC{ld@*Cio04X$E_07t6iW?rFG6J5BHI&*<+zqoOUajuG?K|=BS}y(p{}6YWHj}n3KKB$?w@PfL&Riq4tp{uS=~YE* z9wZsWnTkp@rdyAwK8aX+m1LZ)%9_Ucan5wHDs1myaR;cfIv;~_!js+?GQE6;&c|Ur zV=v09|4MwrRSFBVS_`zRCTP1U*3%NJlfaH-Nms8DmGhgpn`Q_LQiX{#r8KG9tLCUg zWxwqUH#h&?4$kZ8k;sj6m8w%AbHrU%AS~G-OgmFDE&oQ`MVE@ZOFKteUn4#$;Waua zb>A)SYSpQ9(WzmsLn>4~Dpaw0^pz%j2h)!%Rj7z5vLCNbFBr^yRht$ijL(qpQf=ea zdfnZkZ8AoiSc_IljP5r6O-bK;q40=~JDF8JcYjx>p7S~8Amtgcb`6aVgHaYyVEcc}_{@g3rB|5RAwC-FjuiMyy?n6yo3Y5F+J z7jKxWNE_pvzUiL!odA>etbKNH%Ttmr;ta`mj;VOo9-7glJvUCT$D2DOTA3=8_dnw9 zy-t`JAxzK?7JRw5t8^C7eYRv@;4l6u>x4}v{5fhVR8M~MBjVkqjk;O|?uhoJ_Io5e z{5xTQ*4h!R^x%Jre}W2G#|d$F=+v-M^{Z2N-yn_M)IDbhhq^zL$gQf{Z9j@TixrqC zW4(%3hKg5;PHb9rp3+kz(cOA1WvULz1Le?DwZrB9P2$BK6ejBliTXg?bG8cORn!7R z)bd=Bs)i*hYNfYH#3ViFkS=kjY0qiYa}h~@bHwbBP9N(NC0@gNVL_^dC$xw=bDp@v zPZxKHPXxzscSVmR;x`HC(wmg&dc-BhTTRdJ`c;Cf^?*{ejWp}1a_|-jkJ9p2ohj}D zmDMDzIQJD=?hs+?`4X>3!!7No?JB47Qmpx|f*BIALG?6PrK9vB@ps;LbSfmOPBYX- zo~8wA)`EnZo@)Et@FrE-dc6q{GE2%6uS%P4lAh->qxWL*E>)pT`9^YY-zkjH%a0iC z$=%v><8{o;Qh|*Ufps;_lynDGUo%u+vr5FjLECb+oVN2_v0A>|NfMz-=Y;X9yv%BR zhux+MTcYixIMJN>0wAgk ze6Yo-<<_5tA=<4%`!37RlK7cAI(FAeyxzxrT;l4`^P8$d9J)v%l&BDwP8D~9?yy34 z)S{;~N9T@McU6{^VP%O$xxUCI&c5qH(M!cecU<9Z2CP{mEr^LFS-36I|= z3=qY2HK^cPD!A1zOE_2QPJNgkcG+HUoc6gyrFJ# zq61#gUELvUnl43)(W=ckU)sk(N5EaBE# zVTr0~p?2U(Z4q8=fwiWK(&Zge9SZ(JlC^7tPxeUmt#^rkiY<)M^Vk|J;e{%QohpbO zWfCvkPne?}tUzXWu4L80s=2=KJXd0nWYnX=7p^U;QKyBGy5n3GzJr=!caiL%d4{Bq zcv0LLVM4baZ}{KEU848syL2$@^j%6*${6E)$sReZ{+Pr|*)6nmiqn3+ne~!=L7rPj zlEkkiJXdGa<)g$MtW%>%9aKxo#Xq@G*s1#4;S*+_RZ9i9IUD?Kc@hw1f?wtYrv6u)Ju@YJt;Bal6o`NQBf*f1T_&K2E~t z=#j_i87O~F{N1LYmiM4*bx3GdX(`f%;yy>RDb|XN*C%=LT8seGO!D|1748l_57C;e zI!pFa{hF{zggm*yE#Xv^mA;xEiC^b^n3du-WRXqvEkg)m*m`lb|dH)&lZ$|Pio zt66s#rgybVRkKQU2UU8O+I3FYpq1FIm0a+>6u{~bmYK+U`~87ocZ)M+tn9b#Gt++$ zKd!3PlU=WxpRAf6sS;hUnjfl~AN8)}Q$p1{mEZ7~xDV;1IZh?M`5Ey~zf9sK>q$vf zWr+&&g`ejt*W>8b%f$G-lCYZ0ogH+Jk_@P4pF8qtVX^7j!-L6;QQ~aTdsc;q#2qnF zl9e=yyXH4xxX#tuE>^crMk-V|A}$jDT$S(?llH28Ze)}ybcObr^s6LV+iYQbzOdLd zzRI+sa*R03W(rI16gI1DrJJ5tnXq^0%+sy6g^DUAT7}AJz$!TiOJ%fUl7x5ac$g5c z*{WKGX=S*lNIK^eyG|W;=x!Sas5{QbVXj7n3rF*en1s15zB`tHC z&-U6;c{$}0KS!0!tx8s-N*1O{mVK2Jq-naukKZjUQGqNPD&dtXT_Gx6?Pp26m~Vsy zS|P=6_}pf5gB>1Pqq^1FBaxbQbab2M23`z4R3YB=s#2*FWMAc~QnA4j-ldgPrP&-h zMdIbES`|O6@wDM}?h|+EW?|6?VY&9Cm}hP4jSzD~=r^n@KMl}M4-2;F+d%IAnX?jB+20b#Qd zhR>5i#Ok$1yvka@`QjgUyTt4GLFmWo7utG=HoDq^is5Y6*90{*Z z5!UNeuV$yqeD}H?7Tck1H}q|Zkn*RnpiEfgCu~ znu^D|%~_2cRjM|og7+mtrOHjJ%1!!(TF)voy=@XN!W1;}c2=g!OsC3BX1qi%&zEQ! z<21QxY_!jwqOO|={=|P(6M&n1i*TrVa8{F_=w7e+|D3e}|o&A(f#%d6$c&~o&s>;!j8x(2zTJIht>u_tnk!H!89B`cKSgq<< zx$0QB7PM6_P!6?9y5QNuB-O7*)vspVZ|egR-mRlgM1WM#oEybIdzr9Px>261QoB)u zwuf$Qej%DsS%M@;e@IxW2bQTlpT5q_5JCE{91)vf10vPVm$`cxk$?jx#C5q<43SNwyuA*X1(R&5K# zdQQulC0>*YSLD?`H@`~J9$KV5r|T(+=+^m`d$qXZ8iZjgVL9)KyYw6>c&O@mh4#2C zW#=r3cW|gMRV63XCuQ8>3)A^>g=$!}i9Nv7CRwGbK3>u_EOMJ057=Rm$*M^e(N$5YtPe0snh;f^;wIM0kz!6{O~Dbwbex=B)HXshT-G3On$r{%fJ z#lKqxC_@D(X`%R+ssM%Ni904qs-sd5v#3t|TeP`X>I5rP1*%)CsjTlB@pXxxam2?w zSD7}iCY>lG>4^?j#fsL>oU8*?nf4p^DUwmC`j<&{#<^Hlq?@Bpjj zjedJ(_7AM}T=LU{weuKspT1+CV-2|cXyv*U0~g0nU%c;DGwfY^{)mFY)1R4t@jcsZ?;A%)?QdT;_@bGk zw^mHuw=Z~GMc^sso_FmjaX&JrraQVQvWt%3VmNcH!ggVMu>;s|*i4VhwFbKzTaO*a zK4ocY(4e}_Br+~HY13%*d5q9?7<*cp6hWoc3@v)6VZ~{*kWuswhG&b9l(xZ18g$J zW@2lwyRr4yBiJ_VTg-JDg~pa*E3nnr9oRZ-2lg_y4;wsy{S2TvFK1&F=6pl!0QM1f z3_FeuXKp?Ln~5#JR$^_+T8uVJvMLG5Kbp{06T^q$A+Ub6R@e+Ol%pp8~YqP zaRz%CPE}%Cv0d0+>=@=BMjC7xwi4Th?ZkpcP-5&THh3hZ#TH}BN4h4tR<)cVGm-DV>_^yv3?QME;b#T9YMQV&c-TiFLnU?2s?%iA4j>d zsn`N+8MYF;8+!!XhW(7WnEC}_^RT7Z3T!pD4to%L9NU4tjQxn6z@|^2!mw2n@;F*H z_^_O7EB62O^(JsSm;3+!=UxqF=KhS`3}eQ=j@cK+*o7=(Ns?vuER(&G>`6#t32&s1 z%IQdQJkQ_-RTXH1IaU=;zL(>0wUDrKxp20lC=4HkjbU>!II zq7oTz&-WrU^Z9;R)Z7Z9Jm5*gP@Mg1u(cH<3AiS z5i9^Jz*?{g>;U`0QP8*(V+h8AxnL<+1Ga&^;1DX_$O4665||AZfrH=#I0tTnpdM5L zGzY056RZWBzz%Q;lmNRY9SPcj9$+9?3fA+I$3-?wAu9i zy@>_fnZyH$U@q7I_5!O9^#}DqEa(cdKp~g}PJnaZ3b+kY`!X0H6AT8!!9=hCYyvyL zesBr6`_WN$KNOAu0hD zfVE%~*bgp&65t*{g9l7!_#la(9q0k3fVp5P*Z{VHz2FqM0Ae4e7eIfI1q#6~a1fjT zRR%JBKy%OuWP-t9IG6|)fTQ3Hxa8)aTGHl3=$Pr39;ITS@nGr$+JS*!E?5dSfNfwe z*fEqCpz$y|3rqnUz+P|)TmaXBmBr|R`d|`R1XhD}U<)`0u7IFyMj|SkN`q9;2@D4l z!3wYzYy$hi8IYJm1wjum1;hN7Z4i_=xU=dgi)`4B%1ULt7gP_M~C`bi^ z!9=isI{%yjjfYbh=mExpDPS&G3QmCw;5tYjL5o0tFdM7`Tfi=G5S#$#z-4g*y`hzU68mt4mzzJ|0L_JPH zU@#aC_JgC~47daukET4(4&;qy{HH+Xf~8;^*b5GU>mYaxT?=M|)!+m;2d;qIAZjcv z1f4)87z~DkiC_U(0oH;|UuAA7p_-un4RM z>%bPU3sjjv1;AjSegb&~SPOQ5qu>m<1WJHCkpe+G&;#UwvHkgH3YZH{feYX|u%4hI zARQEf)nFai1rCBvPtsyA7_0zm!49w=T#~7$LVqlObPDBzOET`8&~HO_%_b)}0nW*g z)1e8S-E$ZZkO+E!rC<%%1`dH!;5x9LXDC1okOdZj)nFaiBHx_mX zBG?a(f-|7jJcty zZD233UZj?w2ABk9gI(YtI03GJ+n`DjWr5~J%)V4eCKwEcgNa}USO8XlO<)H&3eJGU zg$y9*0hWTj;1sw3f)}ysfUclF$O4665;zD>fO8;dF%y=7Kfg5I6;_muNYt57NOTFdHlatHC*N8w4$-2S6&=A>W({t&@LY z8N&>Mms4j@2xfy5;2a1N>IzapCy)sSgNa}TSPM1*_X?^A8iTQ53YZI)f^9P7ta?gZ zN%w&MU^Q3=c7YS%90*!P?LZVr1)V@97z~DkiC`_*1onfY;0$Q@GD8B!f+=7d*b5GU zQ@~nH^Hy8ct@@BykPc>pMPT)6x%PeN!}9fNUq$JEF0_GkI~Q6}X2Tpgvi=;0oVjvR zi9D(BpU`HGd`bRKXbV?LL4g$fC$z02Ro+x0t@!+Z`1vtsOi*$7h0uylN47M)h(2Bl zE{3M?tC_D}Bu2h`elfI_Gp9f*{79@=N&Yc3fgflcsYJZI`eSHoTu=T;#zYCfgiE$` zxkUaPnRW@6T-kg{SLHh;@}<&G{DxX=fn@wdGFC?aq@%sAM7$hVB0(x##+E3pE)y+D z3REh$c==`Z%UX#AvhQcqadPcv3W=AdSFk3?pes}$UshcSZ7q*np*zl82~8q%wW~x- zmhM;aN|DJ|scouky~;1uBo!2&zZ&|Lll0E(sFUT^b$*U4MKXTXPLqEnl_on?DqC); zRE}ia&~ZlJ2yG_ag6aRYH$tOj>moSg7hUD`PMNjkiQYd<>hmvySyoWHk67EHrCw;x7@@0gRCQCVelT^*k?z6tY@$4g2u@PR zX{M(R%FJM2W!V+%3nAL)$|*%|A@~_UGRKDaqUpiDA(WCWvqC5(N46@FTYNFZ*U?42 zV#0hK9eKs$!+ak(9Qnn`m3^1_WuXFTSXH-mXjQ!PikDRN{pq3UOCr$n`$iE&%#m9W z40Ns}*CLfC1+^$XUzXJJB|B3JuVURPMFv!_5v#M{%F3=poD?V#FUyrk zkbTKiJW=kbRFcG`=%PlZ_`aZWtx^e-AO)!?6XkU!lH_zMJ)JCd(|iw7o6%{c7}GRe zn_CFEnMSwtXyt38TF^>QrNgc8%9CoXN#)DX)(k6`!K*46E9YAiH%{uN6EI#zE5RkL zM51`xAoxWwC6eXUHe^VV^D31p@fie7lP5DsWy>BVawN1Z%3SH&mQ$fN@C4cB2nhIqjkx$wH+OhDwo^Q0VxvMo?%IqzU^_zks_5!lRfQq7;gt(2WN7D zbnk#MTjq4Ym?PUesFkGyZNA=t^(0TiJ2E$Fc0@6_qp!J|zw73CiX2uVRYJQ^(KN~ELMmG(t5m$K@8WCf z%qx)NU1(E|I3K{6D;W>yIW}I2e0lQ$GsliAV{CDyuD)UFmoUe7!j^NjJ1rW~ofd8Au4ntn?sQ19L_UZ)Te?4}J7U^{y3p-PrE zp4qabA1*oac|S7b${l6PllcA=pD*M4`&y|bdt-l$v2waUu5l9n5Gl4T58;|C)0D`Q z%}U8^eaIKD?zq(kppBL8O0dHipp6?Id~OKRpcdwqcl4ClCid?y+6gQP3JsU;7jLh~W%kXTve}huQ%E@d(#Yv?cJr(;Z zkswQQnA3@J5+Psbkh^&plSAr>)PlkM% zobT%*lkzF`U_OCjr9uJvIO$t}7hSJJf*da3noX2yk0Fv|&||)~^2lQpzVClCibT1k6gQP3eH04XK8l=djYn~Lq{?Z8d@~Aj{X%xKH49-` zFlw=+5XW3OphTWHAICpmG9LG}lJv*vf!UAa|McVd?}E_@*OW)R#EeEH$Vh~Y7>#+; zXv|6Sozk z6kj+_55W3ydH}AC(*qDcUJtSYHqF^RGiQ5bie7n3DXu(4 zujEPHNsLCm44TA#BfmhFOyXjXl|4!@0!qY7-KX^m(D!NG3v-lUYxA_~{^A=?`~K}9 z@Zo1j=1S-kj4a?&=(l{CHHD>x$+dNgj(T1hS<$BIsNJXPJJgd?sQ|Z-sXFR+Q_Y}G zBb6e3l}MF2(@?UUsT9kZO65rWbUm9!PA8QoZ%)?*o}W%Lcp#3Pfi_kK&A=yBmdv2Q zIN39U{PA)_DcRxA)a4e;#Fiw>Rf=Z?l}eF2DwQh9vq+^$!7PGh%j>gH=E%uel*FUf zv%1^?&+2lQKg+Fx?b>0LjFn2Wxl(!5nN5oAni2_eTnVn?=g7#uNQq=AdXAtevhO); zsp6f3GEF)tkuB5apv;k-b8unTsYIT{Jdenig6Fw8Gi%;_9@kj;?s*E#k%n{0!8UO& zb2wKv&PB-sr%JK!ok!~vW%N8UB+2@DgkjS=kNbCu#LQ>GXfdBzF=M`7L3Ylk<=Jw1 zK3;@<0g)?1UmyavjTZ=;FUMbCPr{7xF3>gTumB$>trGFFc>xtkkZa18C^0YUGDp5h zezt-y;*uiAl`>T-6_HAl?nR{7m=#f1ZpTGz19*&HsJDV65i(*SwcEAO*VdK5VTp4Q ze%xRe>3%L!DUK+VNRY_IdQUQPF;joUVsdR*%+ybolS=WmQq)?4B2~ICp*}oGFTp=s z4lMEYmQR*ouK$v+Go_Dwi9X;;eF<~EoPWvJMIDaBEJYhDLzT#rqNUV6N%k!zQk>i} z%BIVh*gP04ql37w&RK>}tn5@GPHrs2mHpFle3E3qa+J&hl}eHA%hi5#IaRp6oc(B; zgbU8u(n~0eLmS~)XsTe|B0Rz7$#EffzJ#uzARg{ARuCmtMy|k{he@TS!Uv4@hSKum z#Vg4YFGH0`kmW0hpC|`b>f&##q&Io=S%oc4#;-!jqt7Z`_UB5lL0Uxy?p`mG%9os% z*}AgbDSBBKy!~Y|vS=tHi^gh{3DRq|PEAv(SXoa>-r{u3ljpFk(K0T=S2sBrDQg| z!Hi}m}rpbW6k;;~$zv&{k|BZX>`+p;P$=}$V@Z7bI zI)NySB5eSO^(BK_wX=gLXs2foNU=gO(? zmgtU(FG#VhaKC*)kkUUU3qSBx4L1qxl%T$UQR-9@B=bM;g*!@Q+y}nuH0Z+*d=dTf z%9n*qh>Z_;AJX~>`4fj_7fu|OKYsj}@m4jfi9U!jHh&2TfjsFIOf`n>@KtrBOUMpi zb?3SYGH8b{yyiM>^XK8HrnG5Q^K9vc*)dzh)6d*xPb|30ZtMCpZk>DdAJen_01ggI z$4z}Ttu$uRUEQ{WQDyp&r~RP&^B9|HViNu6KYfX@j#g5c%&*Ru7GQM7IpwbYNR^NO zNrO}6oqy884La3%L*+niQaI);J=Zx{Q|UVvjv1X_R&%5C2j&c@v^Qd9#4cY%?bz_U zLeW{({MSW~2=r!+(bT`jB*ho++2#Ad#dIFIfjT4gZn=JP@t_QpY>~B?~Q&;?Bb= zp2Qp`3(sdtu)R2}!|hWdQEnW@l>?KyM@Ys>-y_6}lcFQ6VexYK2t~3c9@QoHJ<1A1 zTS>{vqcr~9QD2gLtyukI?4eU-&@r;5$*ae3S7HN@S_S-lXq}oLSa2LMFBHZmFg)X|tBFu5n zMP1A_C32d-W;}=F#FRae0iqrkDHy*R<=b zYlP>-U8Q)8zlICjz+Z6T=I{%td@1^c{Vuz*J-^WUSaDuQaLjrgpLm&e9iIf*dR9_UsWgks`n;4f5ps6>#tpbD!>@JW>eCA#i6REn2KH+9AVH_4GJ^AR%dCWY?5$qkAZBsZx( z)3)I)++t;b5^*v|iFnzn1Sfb(Q19OUH;G=HRlhau|ZcNUhXJmf@Iu5B+9fqD0$pK$oqGE6_@|X zEJ>00KT$J`e-b@SUjI`UdH7GNle4UXO^M4gZ1OFe49{D((dM#TcG6Z8qk;pGB&{5_ z>iO{w95_Q$B2`X0?1rIx-TV~=vsNU=r%9+6|7^+d+Rdbm*RCiNy>_(x`n1m{YrS@D z+P23_QF(I5ON@MpFK4$>8{^UCY<1SYxg6!h$;EQ`#7n~V@`NLQd5ny5c^#%<1$^RpiGq!z^9m>vWlsfMlH`uEB}+_2lqphB zkyM^6uV}ws>~RMD?pmDbS-#KVmh@mdnhFgKrcZdj57v=(s#Ky}R4LxWgb;%FFd?KE z-4G%%x+=w#R4ESsLrLXGUnO#7PN*(yYbg2h<#H%3;3=%3k0g6#A3kxiM5W^8fD#Gf zw5c=uG8-HFGTUw`A1|d#H`z8PvBk%2yPOOA>B`vSrBW3{f^<dP2M21zh?NPXSBh@sJ_((g=mB>@X=t#1~%IiuU zC!a^s24}jJ(@vbu3PLVdzG+;)wt&RgWDm~|i(RRGLEUMKd$>R+|y4A&PZe5#K zZ;I`JQN8oZgSWc%5J}Rjo}K{n>*-ocDD2Nap3{0KGTr> za|4vQ(xm||>`0YJ<3$Ylct70`7fy&9lHy%rLxz-RjGYa2&8{`HJE&xGBdnaoHqt}8 zUWo+xu92==wZ^(`-5V1pS>`vkTg$x0wBS%pLfqKPhMvPyACrcxY|DZyh# zQ(gAxrd&{*#jkIQHdZb+rJ8XP(~J}^9T4((GvaP*W+%}lmz(Kg>ozA~vJ7fYv5z#z zyr#J>_OQ}(e`yISb+xU3XEDMf6I-CP}E42{7vR#qWoWekQh zF~nnLwj@x3bZ?0{QRb*rlI&C>S#BsLOI0kXR2dm-s}29=Sd=_k$J*+pN2@rLxiTvb zmps|71nY2|ouRIu_;}sm@$q(V8oVbSW4zpor+pk>B+v_qGCqOvWC|<6!-NseL|sHi zBJ&_eMkbOWS6)rjMI2WtUhgF#*lr||k5@q|mCCy(T$rmW#UHay#+D};$tYvxNtKF| zH%*INq8HIt^$eMoPCRxW z>2@1e5?Ay!WsQ}lZKxjSAZ^IP2B{5B3331-pR}QXpbW02KNL%c(G3L|x^c@h>|qpf zL)|%YCB7|<_LE7TOV|+WxOOTv)}1}Vj>I@zB(=(K_^Hv3!N%ynm$@P4^Fy_FzuD#43|?o=$1 zS3n33sU9R}lFU&l-jyi93a3P>#Ps0eYSDu#OzOeKl`R{4;G83;dr)?6ad=PrpKijR z>_Z(AB($%d8?E}P+0d6v6Z?9YHD%B=pn(wqAefztpbQl!E|c$I$$udWZ_#eo0{D*dJs z9Naxb>)Ejl;L@%+0I$IVxYpTI4zPR5^8@Sr9} zsWP~Z*n{k9QZ&%+;*M&4t&)t*v#ZO`1MP0^ZTml|ZLEDCv3mudSaFRfBlD54o6ah- z>k+$$JLnVRHQaq-pJ9#UjX`!F_ljks>zHW1NA1q;)EbnfgO7RCe#9Nsin7i;Zln9c z9U|?f*&g}hQM;e}f+{uhNt*J)U@Bq%dBbUvz99tNugbuhDyxUs1KlU2G)ncMICoWL zWIb!w;4O>Y$$g@#N=~qw%ax&aJNMY)LH=acFe<)HReaMhJIg&I_ z-=RpIT%wY@wvtUJZ>VIAY6K;j=N?!crfd3bHVy3RIpVMQupH`gNHtJfANVcAC)aZ9 z4EH2eB)ZlzCRgRqO&w>~lrMAb2i%#e`)lRdneKtRKd-I&D$BiJjZo%ubki?+p|Cpj$ZHPOGwsCr|YmSk3$&!$W_l&MKtKuMfAo zx`!+8b|a|K1yxm86FD}5VV&!*U>$jIq-uzp&Z6c~vSlP=aX}5MPSzi#YN@JKT90n- zbt-vj6dlu8RiD!G+%r^F*UY8wb{E8H7`ikmX(j&9o>gi&obF2 zxwBMtVJT8)j9p3oI@)gQw*6C4>-xAS?V=1C94Sl2(3Ka|uu^1o`DF}|+bQStvCO^w zsxJEC**KQI3pzk0Gu2>*j3a1?o~YyOLiY((`(27PRxYvQseOr>IwtRUySqEKA`?(2 zD@`CdNm-e<6Wtg7rGl!9!8eiN>Z)3K&qWg|%O^6i)~UMOXQ=dq-PgUz-}1m^7AkWm z+M%-P3C6auDyZZMyT5yq|GJtH9OOMx+YB*(mQ7#gSDv&pgB#O|d(~M_(U3zGsJR}g zZ=X`bs_LsJOWR4*cZTY$(z)Z6wtL7cGtS+BUrv<+n4Yg$Jww`|8?&Th?x;S<& z7t00J?Ofo4-503z@_DE-)pQy=j~ZNI+M#MD<>u3>6RK6{o5&OM?MmHr!Efn*)jz|_ zn1lcOp!6KF`akLr(R>_Ml(hvqTg@B&iMQm?e7oWF@m5!tI>a*{ht=NCRKp6bLD)F& z)1UiokKdE;p}X>px2E5d@A12AmbK*Wd~i!9ygFY8eC*T4T(8l$SaY1qeA zc^_uiZ0)^*w%PwPT3+V}ZZrX#>z-zIsip$dsN}ZB;nlhesF|I zyCOTHRoGHgf#N6dKVQs8_u)OZi~9n$Em;-h-6A{O;gwBAc5+*{`)%&7fyUlD7RT?g zS>8Y##;O+iI2&dIu-a*PlotR@18y4FAyw;LL{vV-4FT%CfB0I%vHBaX2 z=vv|F4~;jr1&i#^(s@lusv$>HEUSsO`u>3Ow*d5qDJVx4*&TU>bE=hPwbvew+R|q+ zJ>Pq=UCV3zg}$k4;?7-cM|iDcC?btw*J4!(^?xUWW%m*mo61WVELIFObG626Wwo^| zepnl;*BVjA?Ku=HY^Q8jUx9YJ3?I+ zXr6J&XjSfNR9>rnuhL@W2ns6V>}^^9@)!OI{HEsRtUZ~Q^@~&I^}N^5vc~&;8uhoV zhy8pSe5%B~WLGO^{r-?;mGk>Mxj}{beJbC@>%%Mf^)c{obzZ5r%&t|=df-vZs^_ol z;AN_^7x|B7Z)$gWNxOt+alMu|?K!Aj)PHj7Wumy2t4>fqn7qs6X{{BjS$wJ*#f0T{ z|1fL!1k0*p#?~s2loQMCMqaDN6PERrLd#_MP_YYJJUr`)Krk_*pXoYmcg5=||1S$Qk_q3IoaZsyC*@q3efa{f~OxFlEajIDNfrQz0gw^IjI9^uyUZn6P=<;5(` z=Hp;3*nv;Dy!Lml>ML9A(8!0Fc%|0D5e|>js^?GZ2(^ldz{T$Ws0eT4Gu=eUD!wm5 z?x-bRXW5NZM_BOxh!EstA&J{+*NA|XPK0o)XNN#JxufJ#v7KBlDy&lrT4l;>x6O{| z7B&F|W1~Oef#r>+yWO|2mEM8F@4H6@$2cu@r&S-8TCc3#W;d+lu{`lktGQ95&wfHq zZKKim-j0UgQ$u#YN4G`2Z-+aZhDrMSc0{T-G0|!L-9Nb^EcNrM=HswNS>LyD^7kLi zC&IcXpe!V}in0OO-y7TBX>Ii{llMj`9C5ybQ~iG={fS^y{Zx)syE&ec%-!|syQmg8NIlZ0MKXed=GA+}|%Ag{~xZQRir`6H#8gbuH^~1Kw zzaQXk=9R1u?1nKO>)HO!vfV_4HLNtd9{Sg?O)Sf^B}=w^z)_1=E|Il`$C~~yBj_)# zmQ{Gyo!1p6_t-qrb_e(BF=GSmaJx_9!pmR%sdZm%D-I0QiuN^O zQ`_R}1OAVisGG6zchU5x_I>d_e8g$(@wbF$DX&C*s3+=-T&ET7Uq5PF`4eQ|hjt@J zSn-Sx?Hv^yBH8=w>Yo3+@3cY<{RJ9i=69l%+rQk$ zUcC=$IkVq(JF1y51=wmCIt$udQ^!V~-}(3LGISrCl&w0BbFWEyKE*M?+?^X+>dmlzlTQ3 z%!4f3jss5Xa4qTeDa-be^G+*8s~r{O6_scD1*i3d)_AT%D@d5ibLXPdYVFo}I5P`5 zh~vXoomOAt_!e}oy!NSGowLGhjE>PV72%!zi_RAje zH1rRsZDNE-^yd^7S<7YR=t_HL)ON8i(ODjdbTK0ob@Z0S_&Ek@;mO7@-uN8RR5!P? zIKCiOmnfH&VPehZ&xsE+^!vIl>mw8EO&N!u;~gWm81aD?o;~$k>|k{1N1&4oeXzdE zddtx3&NWHWXgy7x*BZ*{Lw2~Qaw8X`zxzu@ zG7jo!BzF$k)i^Yb`;ustr6}BPQ0c7PN)&`@4jF zjo%?O{yuTMT-J9^=n0eiBy^~$Sn4Y->l3Z@I$m{ItIFvM!SnK8UDjk1w5nWHK`*?i z23R+y{yLY{&P2+C9y5Mvl6?}tXWlBkvOFuHbcLFlaqHEBqG<{Aq@jo3R#%mdS+c=p zoi*C8-zlYz?b80=#Qbcd%lciuJZjf)|J}tGAa$JNO=@XSnYo+1tK8n+%o1rPdj`iD zkLrQ-tbD($>u*B+UB6J;oFdEW9jXRu0(kc9EStf1piOisEDZ19=Xg{;L3j`Ca#@RA z^7$#&ifnOwLxf{{U7VY|t0MdWbr^aPnxm!|LAUsCA}#N` znXn7Ro0mD?s7(6~s|CH!w^aCZs6$id7l)LcfBB8+sMG%g}d^s?O97C!tjgy$p>vH0qd|uF4_04|Ki1_6hg3 z;&*Hhm>eCBySPcK9FC_Y+qk3M?IWi9mI(C_!p z{n=%;(Qb}4GUPkD@{|^y8dp?DsPa7B19S@1VYE}rsAHN$f6o|M&uKZ`T7aqaq%5$L zH;;+yu~qd~=6>5huer(|A@8^C`yaN??y>P0UHVa5mZSF=OD(1{|NbAg@BWAFhyP)_ zGW~xTfBPS{JJ{aw*YEz;zx|8LTIM#!`)%z?To!*NQ-74Lv!SMioo{kg`4#tP?1}CF z8m3Y5$2mQZo^rc+(2D!7U6n~Sjl=_`iH}JmCgF7;SJqFHI;BNDw! z-7Cp!=UEvd%Db&rr4A2~SX`PoPa?0>ySs$_muq07wD_-Glm3pXC^7%FYtZy172Q^~ zQnz(76Fb@u(Q-cg154t+p`TTh&>vV5*Hw3O8&qn~drk}b`cI?%OEb5XZEDHJ=?8T&7fJL*x?-gk zp0&;0YyfmKij8IunsO%4C(sB(&q1qd>b(hF<>1d+&>=6yxUEHU_L81O^;){w-KYc; z=LHg-{L_V_)UuD7IA36ES(@t(iJa0zR;-&_y+7U>617SbJ4giU1jDyKR*HVKYj6QP z7w5K)xpif{gOc4=8?WX(YM%Yku8G5Y8E)&ra;COc7uDhZ=#5D@bb`s(MEYFfv?Ha9 zoW7)|#VD*JOI?qVc&Rio`~lTJDhT<;$Tyetgn0vPH?5`2OC)^$9{Rm&X#{?u9p&UIo{okR@-w%(1vzeOynhAY9J}nJRCjV!yxk3{opKx10`cEzJDf=jw^3Uj%;0jG_1nnj>|5lDaXmE`a zhq3Y*xgAew;h8qYZT(%o#F3}N=&Q`8q^a`x6&{Mxr>bR6S)7j=6?>z_%43P&Vok`W6+h%v79T{Hj|4Rp>NRTGeT#UY;h|5fry&!w%*ek z&oL+$w`$lGs87@AKNau9FufHz!)>iMIkrJtYue@)XjQ*w$NO>w&2;l#(R@l5 z1C>%8I}w{#`dqiG)wL!+>$bWuUDW4(zg=_O9HlEiCy$nK*Y&*Od)U|Q@C@sr7X!2D z{)`i_eam9;{|ef7i5imEex>o_ps#4^4SmUN)!-udm20EnQnw{q?f6i_ezn8PS<&37 zPdSbG4{@_+)&aaLN~yyqGx2m;->i~XA#~df9pBuv_g+iRL*6HG#d?pe!@f zeq(iLAVYp5M57|nV#jkU&m7&_J;vxBrL z!GFSWxAmH|FCkc!uiP9EDC*!(K9=aZ{fUmFTxIs2P}jevm7u+iCr>mt^=Q5)wISSg zcYUoEOYPV1q`K8c-_+|#mW;befh+&5Rzqcu-U#jIzvR1{G1mVomE#+A-G|fWoAUr&`g_;ZrbE;H&=^B+1Ze$V)bgSoh6U)V06i9<_VqH~ z2chicbOWLMuGt?<{i{av%&%@v<--2pp?P1hO*u*)a!1d{*TX!V&b0rN zmLG?Hrm5o%dG`(t`ku^s;18C(Xvrl=hgLaj-ajQpvLORUgijk@a(APVUw(FR(%iKE=9eIpkH}p z=$~Bck1ZP)rY@t!%~Z{_=Mv~Bs?e5xfUP_o+@rk(sDSD=6R`|>P7APFX&=J z2l9Jyj~Mzc)N5!lbf2zJJzh6=^zb*_%!jwtWgm5cEydPc=W*=f&wA@DYKO;qc+}~gY5D6tJshR`6W4ortXszEa&HgUhW4+N>0wdv zyTtVISbL2A3beeTH=&$}t5K=m*JA}$G|jIw#KZHH4zd9HyUcWlRd+luQ{7<^-nm0P z*4T9ZP*_+sPsu8e)j_g7Vb#5@UiMi1+(!N4Upy>|O6`eSqbi|kI&_zDz75@1UOPMY zte2sluyD`!>pkohwC8V7UXG~zA#az_dQgtgly-1HJ05DXMbCkjzH{tb*7as}+l-C- z0-2pB-|Y zGIrnOQ7>Oq^`3?X8~Pk{gQ0QndN@xuCE`(?xQ3e<%4oQBRYg$>>AVcF6ZTL$$v{?mZg z`GJQoO=*WFP=AZlq5hfB7y62E_!;W&>c|})>wT^Deg%EOY3h^nPY++b(9t$Qiw%8j zmxpI_tz805H2L;HV_YWR^^epwraZhY_j;_XAfsM*(8FIT)fu1p%)^PIrt6>|89M57 z4@lK(I(?gXs)5rUwW)qL;FBO3>_MvqoBQv_Wb}YcUVPO9I98>ktAy9 z1bfn1hovYqOg+FZMV(_wk&kQP20YBq%N?P24R^*LkvpMb;ohH)diejz#@BbuV@3IS z%e#1QxZlS)?wHK?kuU$G$GYP(`EpNttllP{XEVILIDGWzFW-7Bx2E3T&Zt$_c!!=1 z@CJABbU0uB(6t@}pBJwA^zVQ7SfwwKOP{*b+M!nLhi-EX_!pAWA?de_xjQj~#EaTO zkA%3q)^Q$J!nk*Q@AmRQ2_hD#NO`V06CA22BeG(Oqnl)*_Y`?0gOyyY(W$t73_^PO8 zX&MIQ1&q>mgt8M?v;aEa&@0daLkCn+4l==Y6)a!g9Lx^5Qt?0BE|r8xdB+4V$f%-fDGewm)ucLp4I$w==YkjH^wyya0U`nxnPO|1^}* zwdt6he3>yutGt(>KR6_^HnZ$l6BSD3cV28Fr}g_>7N>#W&AV(Q=+jVeN3Q;zA- zM+{x29mj3sP(72T^g{+uUb{6@~neS&{j_bUubs8;(9bIl5Zx* z8*L`Ep2Q$Z)KEk z?Ch=|7U5`V#DhjWX2i2b{Kbe5jQGlkUySg{YYoWWObgEgZS+M)A2p zG@o$fg9$?dau5 zCb}tQEa)UfN>$WJ-3b>f)k42&aX_`iuUZ;VE%U3SOyyYt<^E3$&tITb4c!vZeh|Ko8L8qki1 zhMHJ2pt}rh*S)OP4?t@gZ5GsD?o&{{0H>O@FW~zblpT)J9)tSheh+P86z|e&mux zv0-k$v!}Y=vBNlh6v%egXf6aaUKtlhVIjR$VKY?)bvmAOLpdAIT!ZhHVofqW(*r)w8=qwXpKpxMxq#0l z<8up5s<|loluhY0sDE0umzjwa*Bgzgy65?TUs0K#XL&&T3e-#;&j$hR9;oS8&wm2i zO98E~Z&~@(p!Id*JgoxS_F6lR3FrMA(`sfpCTc;P6%TWKq`zzGn#6JRB_mgGXU}(I~7M%eteG5D4zTI*UY{BwcYwiaF zpXBeCvnuDK8m?8|&!Fdd-fd0w{xQkRiEWE?7DCU{UQP|ezN*L{cS&b6cxjM|R#8Eu6ASE)8mk!i~PvnlH7;i`&QZmO3R&r^3tZCwbhC(&(j+zc(Jsq_7L64@5V>hnugo=E5v_Vq|nJBt7JQuR!w3;21djBFp))Y)%Y@$&XzBhwdW)>=}* zUE|21`TWYUWo5i~>4`^%&g=Pp`^ihU&waFfajj`#*V{W96^HE#i*Pz7NsB#UUpY6q z#QRZLq_dD;2l*&$xudIm_)%Ez@aud#tsTQ#GE)CowzY%vnGeCvAPL_aHko4^c{RZ? zy4d}3*cnIhm3?7zYnLC#A<$Sbrg(R(qpeeRoex_fdH)Sty*M+t!Z&0-4ZaPMJO2&q NqV>hLGpLH|{{uk`Whwvw diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/version.txt b/Tools/ArdupilotMegaPlanner/bin/Release/version.txt index f9ab193fe9..4b80de476b 100644 --- a/Tools/ArdupilotMegaPlanner/bin/Release/version.txt +++ b/Tools/ArdupilotMegaPlanner/bin/Release/version.txt @@ -1 +1 @@ -1.1.4488.39145 \ No newline at end of file +1.1.4490.13519 \ No newline at end of file From 49bf5b4195c93a7e6226d14712f117344c38233b Mon Sep 17 00:00:00 2001 From: James Goppert Date: Mon, 16 Apr 2012 20:37:06 -0400 Subject: [PATCH 03/19] Updated cmake. Now works with ArduPlane/ ArduCopter. --- CMakeLists.txt | 182 +-- cmake/ArduinoToolchain.cmake | 11 + cmake/Platform/Arduino.cmake | 1555 +++++++++++++++++++++ cmake/modules/ArduinoProcessing.cmake | 103 -- cmake/modules/FindArduino.cmake | 611 -------- cmake/modules/Platform/Arduino.cmake | 0 cmake/modules/Platform/ArduinoPaths.cmake | 21 - cmake/toolchains/Arduino.cmake | 72 - cmake/updated-arduino-cmake.sh | 3 +- 9 files changed, 1619 insertions(+), 939 deletions(-) create mode 100644 cmake/ArduinoToolchain.cmake create mode 100644 cmake/Platform/Arduino.cmake delete mode 100644 cmake/modules/ArduinoProcessing.cmake delete mode 100644 cmake/modules/FindArduino.cmake delete mode 100644 cmake/modules/Platform/Arduino.cmake delete mode 100644 cmake/modules/Platform/ArduinoPaths.cmake delete mode 100644 cmake/toolchains/Arduino.cmake diff --git a/CMakeLists.txt b/CMakeLists.txt index e7a3783400..250a871ba3 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,55 +1,68 @@ -cmake_minimum_required(VERSION 2.8.5) +set(CMAKE_TOOLCHAIN_FILE cmake/ArduinoToolchain.cmake) # Arduino Toolchain -set(CMAKE_MODULE_PATH ${CMAKE_SOURCE_DIR}/cmake/modules) -set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Arduino.cmake) - -# modify flags from default toolchain flags -set(APM_OPT_FLAGS "-Wformat -Wall -Wshadow -Wpointer-arith -Wcast-align -Wwrite-strings -Wformat=2") - -set(ARDUINO_C_FLAGS "${APM_OPT_FLAGS} -mcall-prologues -ffunction-sections -fdata-sections") -set(ARDUINO_CXX_FLAGS "${APM_OPT_FLAGS} -mcall-prologues -ffunction-sections -fdata-sections -fno-exceptions -Wno-reorder") -set(ARDUINO_LINKER_FLAGS "-lc -lm ${APM_OPT_FLAGS} -Wl,--gc-sections") +cmake_minimum_required(VERSION 2.8) project(ArduPilotMega C CXX) -# set default cmake build type to RelWithDebInfo (None Debug Release RelWithDebInfo MinSizeRel) -if( NOT DEFINED CMAKE_BUILD_TYPE ) - set( CMAKE_BUILD_TYPE "RelWithDebInfo" ) -endif() - # set these for release -set(APPLICATION_VERSION_MAJOR "1") -set(APPLICATION_VERSION_MINOR "2") -set(APPLICATION_VERSION_PATCH "0") - -# dependencies -find_package(Arduino 22 REQUIRED) - -# cmake settigns -set(APPLICATION_NAME ${PROJECT_NAME}) -set(APPLICATION_VERSION "${APPLICATION_VERSION_MAJOR}.${APPLICATION_VERSION_MINOR}.${APPLICATION_VERSION_PATCH}") - -# macros -include(MacroEnsureOutOfSourceBuild) -#include(UseDoxygen) - -# disallow in-source build -macro_ensure_out_of_source_build("${PROJECT_NAME} requires an out of source build. -Please create a separate build directory and run 'cmake /path/to/${PROJECT_NAME} [options]' there.") +set(PROJECT_VERSION_MAJOR "2") +set(PROJECT_VERSION_MINOR "3") +set(PROJECT_VERSION_PATCH "3") +set(PROJECT_VERSION "${PROJECT_VERSION_MAJOR}.${PROJECT_VERSION_MINOR}.${PROJECT_VERSION_PATCH}") # options -if (NOT DEFINED BOARD) - message(STATUS "please define the board type (for example: cmake -DBOARD=mega, assuming mega2560") - set(BOARD "mega2560") -endif() +option(BUILD_2560 "Build 2560 firmware?" ON) +option(BUILD_1280 "Build 1280 firmware?" OFF) if (NOT DEFINED PORT) - message(STATUS "please define the upload port (for example: cmake + message(WARNING "please define the upload port (for example: cmake -DPORT=/dev/ttyUSB0, assuming /dev/ttyUSB0") set(PORT "/dev/ttyUSB0") endif() -# cpack settings +# macro path +list(APPEND CMAKE_MODULE_PATH "${CMAKE_SOURCE_DIR}/cmake/modules") + +# disallow in-source build +include(MacroEnsureOutOfSourceBuild) +macro_ensure_out_of_source_build("${PROJECT_NAME} requires an out of source build. +Please create a separate build directory and run 'cmake /path/to/${PROJECT_NAME} [options]' there.") + +# modify flags from default toolchain flags +set(APM_OPT_FLAGS "-Wformat -Wall -Wshadow -Wpointer-arith -Wcast-align -Wwrite-strings -Wformat=2") +set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${APM_OPT_FLAGS}") +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${APM_OPT_FLAGS} -Wno-reorder") +set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} ${APM_OPT_FLAGS} -Wl,--relax") + +# projects +set(PROJECT_LIST + ArduPlane + ArduCopter + #apo + #ArduBoat + #ArduRover + ) + +# macro for building firmware for all projects +macro(build_apm_firmware BOARD) + foreach(PROJECT ${PROJECT_LIST}) + set(${PROJECT}_SKETCH ${CMAKE_SOURCE_DIR}/${PROJECT}) + set(${PROJECT}_BOARD ${BOARD}) + set(${PROJECT}_PORT ${PORT}) + generate_arduino_firmware(${PROJECT}) + endforeach() +endmacro() + +# build firmware based on options +if (BUILD_2560) + build_apm_firmware(mega2560) +endif() + +if (BUILD_1280) + build_apm_firmware(mega) +endif() + +# packaging settings set(CPACK_PACKAGE_DESCRIPTION_SUMMARY "A universal autopilot system for the ArduPilotMega board.") set(CPACK_PACKAGE_VENDOR "DIYDRONES") set(CPACK_DEBIAN_PACKAGE_MAINTAINER "james.goppert@gmail.com") @@ -69,94 +82,3 @@ set(CPACK_SOURCE_GENERATOR "ZIP") set(CPACK_GENERATOR "ZIP") set(CPACK_PACKAGE_NAME "${APPLICATION_NAME}_${BOARD}") include(CPack) - -find_package(Arduino 22 REQUIRED) - -# determine board being used -if (NOT DEFINED BOARD) - message(STATUS "board not defined, assuming mega, use cmake -DBOARD=mega2560 , etc. to specify") - set(BOARD "mega") -endif() -message(STATUS "Board configured as: ${BOARD}") - -# add a sketch -macro(add_sketch SKETCH_NAME BOARD PORT) - - message(STATUS "Generating sketch ${SKETCH_NAME}") - - # files - set(SKETCH_CPP ${CMAKE_CURRENT_BINARY_DIR}/${SKETCH_NAME}/${SKETCH_NAME}.cpp) - set(SKETCH_PDE ${CMAKE_CURRENT_SOURCE_DIR}/${SKETCH_NAME}/${SKETCH_NAME}.pde) - #message(STATUS "SKETCH_PDE:\n${SKETCH_PDE}") - #message(STATUS "SKETCH_CPP:\n${SKETCH_CPP}") - - # settings - set(${SKETCH_NAME}_BOARD ${BOARD}) - set(${SKETCH_NAME}_PORT ${PORT}) - set(${SKETCH_NAME}_SRCS ${SKETCH_CPP}) - set(${SKETCH_NAME}_LIBS m c) - - # find pde files - file(GLOB PDE_SOURCES ${SKETCH_NAME}/*.pde) - - # find the head of the main pde - file(WRITE ${SKETCH_CPP} "// automatically generated by arduino-cmake\n") - file(READ ${SKETCH_PDE} FILE) - - string(FIND "${FILE}" "#include" POS1 REVERSE) - string(LENGTH "${FILE}" FILE_LENGTH) - math(EXPR LENGTH_STR1 "${FILE_LENGTH}-${POS1}") - string(SUBSTRING "${FILE}" ${POS1} ${LENGTH_STR1} STR1) - string(FIND "${STR1}" "\n" POS2) - math(EXPR POS3 "${POS1}+${POS2}") - string(SUBSTRING "${FILE}" 0 ${POS3} FILE_HEAD) - #message(STATUS "FILE_HEAD:\n${FILE_HEAD}") - - # find the body of the main pde - math(EXPR BODY_LENGTH "${FILE_LENGTH}-${POS3}-1") - string(SUBSTRING "${FILE}" "${POS3}+1" "${BODY_LENGTH}" FILE_BODY) - #message(STATUS "BODY:\n${FILE_BODY}") - - # write the file head - file(APPEND ${SKETCH_CPP} "${FILE_HEAD}") - file(APPEND ${SKETCH_CPP} "\n#include \"WProgram.h\"\n") - - # write prototypes - foreach(PDE ${PDE_SOURCES}) - #message(STATUS "pde: ${PDE}") - file(READ ${PDE} FILE) - string(REGEX MATCHALL "[\n]([a-zA-Z]+[ ])*[_a-zA-Z0-9]+([ ]*[\n][\t]*|[ ])[_a-zA-Z0-9]+[ ]?[\n]?[\t]*[ ]*[(]([\t]*[ ]*[*]?[ ]?[a-zA-Z0-9_][,]?[ ]*[\n]?)*[)]" PROTOTYPES ${FILE}) - foreach(PROTOTYPE ${PROTOTYPES}) - #message(STATUS "\tprototype: ${PROTOTYPE};") - file(APPEND ${SKETCH_CPP} "${PROTOTYPE};") - endforeach() - endforeach() - - - # write source - file(APPEND ${SKETCH_CPP} "\n${FILE_BODY}") - list(REMOVE_ITEM PDE_SOURCES ${SKETCH_PDE}) - list(SORT PDE_SOURCES) - foreach (PDE ${PDE_SOURCES}) - file(READ ${PDE} FILE) - file(APPEND ${SKETCH_CPP} "${FILE}") - endforeach() - - # generate firmware - include_directories(${CMAKE_CURRENT_SOURCE_DIR}/${SKETCH_NAME}) - generate_arduino_firmware(${SKETCH_NAME}) - set_target_properties(${SKETCH_NAME} PROPERTIES LINKER_LANGUAGE CXX) - - # install settings - install(FILES - ${CMAKE_CURRENT_BINARY_DIR}/${SKETCH_NAME}.hex - DESTINATION bin - ) -endmacro() - -# projects -add_sketch(apo ${BOARD} ${PORT}) -add_sketch(ArduRover ${BOARD} ${PORT}) -add_sketch(ArduBoat ${BOARD} ${PORT}) -#add_sketch(ArduPlane ${BOARD} ${PORT}) -#add_sketch(ArduCopter ${BOARD} ${PORT}) diff --git a/cmake/ArduinoToolchain.cmake b/cmake/ArduinoToolchain.cmake new file mode 100644 index 0000000000..dfc40aa4bc --- /dev/null +++ b/cmake/ArduinoToolchain.cmake @@ -0,0 +1,11 @@ +set(CMAKE_SYSTEM_NAME Arduino) + +set(CMAKE_C_COMPILER avr-gcc) +set(CMAKE_CXX_COMPILER avr-g++) + +# Add current directory to CMake Module path automatically +if(EXISTS ${CMAKE_CURRENT_LIST_DIR}/Platform/Arduino.cmake) + set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} ${CMAKE_CURRENT_LIST_DIR}) +endif() + + diff --git a/cmake/Platform/Arduino.cmake b/cmake/Platform/Arduino.cmake new file mode 100644 index 0000000000..a242083e14 --- /dev/null +++ b/cmake/Platform/Arduino.cmake @@ -0,0 +1,1555 @@ +# - Generate firmware and libraries for Arduino Devices +# generate_arduino_firmware(TARGET_NAME) +# TARGET_NAME - Name of target +# Creates a Arduino firmware target. +# +# The target options can be configured by setting options of +# the following format: +# ${TARGET_NAME}${SUFFIX} +# The following suffixes are availabe: +# _SRCS # Sources +# _HDRS # Headers +# _SKETCHES # Arduino sketch files +# _LIBS # Libraries to linked in +# _BOARD # Board name (such as uno, mega2560, ...) +# _PORT # Serial port, for upload and serial targets [OPTIONAL] +# _AFLAGS # Override global Avrdude flags for target +# _SERIAL # Serial command for serial target [OPTIONAL] +# _NO_AUTOLIBS # Disables Arduino library detection +# Here is a short example for a target named test: +# set(test_SRCS test.cpp) +# set(test_HDRS test.h) +# set(test_BOARD uno) +# +# generate_arduino_firmware(test) +# +# +# generate_arduino_library(TARGET_NAME) +# TARGET_NAME - Name of target +# Creates a Arduino firmware target. +# +# The target options can be configured by setting options of +# the following format: +# ${TARGET_NAME}${SUFFIX} +# The following suffixes are availabe: +# +# _SRCS # Sources +# _HDRS # Headers +# _LIBS # Libraries to linked in +# _BOARD # Board name (such as uno, mega2560, ...) +# _NO_AUTOLIBS # Disables Arduino library detection +# +# Here is a short example for a target named test: +# set(test_SRCS test.cpp) +# set(test_HDRS test.h) +# set(test_BOARD uno) +# +# generate_arduino_library(test) +# +# +# +# generate_arduino_example(LIBRARY_NAME EXAMPLE_NAME BOARD_ID [PORT] [SERIAL]) +# +# BOARD_ID - Board ID +# LIBRARY_NAME - Library name +# EXAMPLE_NAME - Example name +# PORT - Serial port [optional] +# SERIAL - Serial command [optional] +# Creates a example from the specified library. +# +# +# print_board_list() +# +# Print list of detected Arduino Boards. +# +# +# +# print_programmer_list() +# +# Print list of detected Programmers. +# +# +# +# print_programmer_settings(PROGRAMMER) +# +# PROGRAMMER - programmer id +# +# Print the detected Programmer settings. +# +# +# +# print_board_settings(ARDUINO_BOARD) +# +# ARDUINO_BOARD - Board id +# +# Print the detected Arduino board settings. + + + + + + + +#=============================================================================# +# User Functions # +#=============================================================================# + +# [PUBLIC/USER] +# +# print_board_list() +# +# see documentation at top +function(PRINT_BOARD_LIST) + message(STATUS "Arduino Boards:") + print_list(ARDUINO_BOARDS) + message(STATUS "") +endfunction() + +# [PUBLIC/USER] +# +# print_programmer_list() +# +# see documentation at top +function(PRINT_PROGRAMMER_LIST) + message(STATUS "Arduino Programmers:") + print_list(ARDUINO_PROGRAMMERS) + message(STATUS "") +endfunction() + +# [PUBLIC/USER] +# +# print_programmer_settings(PROGRAMMER) +# +# see documentation at top +function(PRINT_PROGRAMMER_SETTINGS PROGRAMMER) + if(${PROGRAMMER}.SETTINGS) + message(STATUS "Programmer ${PROGRAMMER} Settings:") + print_settings(${PROGRAMMER}) + endif() +endfunction() + +# [PUBLIC/USER] +# +# print_board_settings(ARDUINO_BOARD) +# +# see documentation at top +function(PRINT_BOARD_SETTINGS ARDUINO_BOARD) + if(${ARDUINO_BOARD}.SETTINGS) + message(STATUS "Arduino ${ARDUINO_BOARD} Board:") + print_settings(${ARDUINO_BOARD}) + endif() +endfunction() + + + +# [PUBLIC/USER] +# +# generate_arduino_library(TARGET_NAME) +# +# see documentation at top +function(GENERATE_ARDUINO_LIBRARY TARGET_NAME) + load_generator_settings(${TARGET_NAME} INPUT _SRCS # Sources + _HDRS # Headers + _LIBS # Libraries to linked in + _BOARD) # Board name (such as uno, mega2560, ...) + set(INPUT_AUTOLIBS True) + if(DEFINED ${TARGET_NAME}_NO_AUTOLIBS AND ${TARGET_NAME}_NO_AUTOLIBS) + set(INPUT_AUTOLIBS False) + endif() + + message(STATUS "Generating ${TARGET_NAME}") + + set(ALL_LIBS) + set(ALL_SRCS ${INPUT_SRCS} ${INPUT_HDRS}) + + setup_arduino_core(CORE_LIB ${INPUT_BOARD}) + + find_arduino_libraries(TARGET_LIBS "${ALL_SRCS}") + set(LIB_DEP_INCLUDES) + foreach(LIB_DEP ${TARGET_LIBS}) + set(LIB_DEP_INCLUDES "${LIB_DEP_INCLUDES} -I${LIB_DEP}") + endforeach() + message(STATUS "includes: ${LIB_DEP_INCLUDES}") + + if(INPUT_AUTOLIBS) + setup_arduino_libraries(ALL_LIBS ${INPUT_BOARD} "${ALL_SRCS}" "${LIB_DEP_INCLUDES}" "") + endif() + + list(APPEND ALL_LIBS ${CORE_LIB} ${INPUT_LIBS}) + + add_library(${TARGET_NAME} ${ALL_SRCS}) + target_link_libraries(${TARGET_NAME} ${ALL_LIBS} "-lc -lm") +endfunction() + +# [PUBLIC/USER] +# +# generate_arduino_firmware(TARGET_NAME) +# +# see documentation at top +function(GENERATE_ARDUINO_FIRMWARE TARGET_NAME) + load_generator_settings(${TARGET_NAME} INPUT _SRCS # Sources + _HDRS # Headers + _LIBS # Libraries to linked in + _BOARD # Board name (such as uno, mega2560, ...) + _PORT # Serial port, for upload and serial targets + _AFLAGS # Override global Avrdude flags for target + _SKETCH # Arduino sketch + _SERIAL) # Serial command for serial target + + set(INPUT_AUTOLIBS True) + if(DEFINED ${TARGET_NAME}_NO_AUTOLIBS AND ${TARGET_NAME}_NO_AUTOLIBS) + set(INPUT_AUTOLIBS False) + endif() + + if(NOT INPUT_BOARD) + message(FATAL_ERROR "Missing board ID (set ${TARGET_NAME}_BOARD)!") + endif() + + message(STATUS "Generating ${TARGET_NAME}") + + set(ALL_LIBS) + set(ALL_SRCS ${INPUT_SRCS} ${INPUT_HDRS}) + + setup_arduino_core(CORE_LIB ${INPUT_BOARD}) + + if(INPUT_SKETCH) + setup_arduino_sketch(${INPUT_SKETCH} ALL_SRCS) + endif() + + if(NOT ALL_SRCS) + message(FATAL_ERROR "Missing sources (${TARGET_NAME}_SRCS or ${TARGET_NAME}_SKETCH), aborting!") + endif() + + find_arduino_libraries(TARGET_LIBS "${ALL_SRCS}") + set(LIB_DEP_INCLUDES) + foreach(LIB_DEP ${TARGET_LIBS}) + set(LIB_DEP_INCLUDES "${LIB_DEP_INCLUDES} -I${LIB_DEP}") + endforeach() + + if(INPUT_AUTOLIBS) + setup_arduino_libraries(ALL_LIBS ${INPUT_BOARD} "${ALL_SRCS}" "${LIB_DEP_INCLUDES}" "") + endif() + + list(APPEND ALL_LIBS ${CORE_LIB} ${INPUT_LIBS}) + + setup_arduino_target(${TARGET_NAME} ${INPUT_BOARD} "${ALL_SRCS}" "${ALL_LIBS}" "-I${INPUT_SKETCH} ${LIB_DEP_INCLUDES}" "") + + if(INPUT_PORT) + setup_arduino_upload(${INPUT_BOARD} ${TARGET_NAME} ${INPUT_PORT}) + endif() + + if(INPUT_SERIAL) + setup_serial_target(${TARGET_NAME} "${INPUT_SERIAL}") + endif() +endfunction() + +# [PUBLIC/USER] +# +# generate_arduino_example(LIBRARY_NAME EXAMPLE_NAME BOARD_ID [PORT] [SERIAL]) +# +# see documentation at top +function(GENERATE_ARDUINO_EXAMPLE LIBRARY_NAME EXAMPLE_NAME BOARD_ID) + + set(TARGET_NAME "example-${LIBRARY_NAME}-${EXAMPLE_NAME}") + + message(STATUS "Generating example ${LIBRARY_NAME}-${EXAMPLE_NAME}") + + set(ALL_LIBS) + set(ALL_SRCS) + + set(INPUT_PORT ${ARGV3}) + set(INPUT_SERIAL ${ARGV4}) + + setup_arduino_core(CORE_LIB ${BOARD_ID}) + + setup_arduino_example("${LIBRARY_NAME}" "${EXAMPLE_NAME}" ALL_SRCS) + + if(NOT ALL_SRCS) + message(FATAL_ERROR "Missing sources for example, aborting!") + endif() + + find_arduino_libraries(TARGET_LIBS "${ALL_SRCS}") + set(LIB_DEP_INCLUDES) + foreach(LIB_DEP ${TARGET_LIBS}) + set(LIB_DEP_INCLUDES "${LIB_DEP_INCLUDES} -I${LIB_DEP}") + endforeach() + + message(STATUS "includes: ${LIB_DEP_INCLUDES}") + setup_arduino_libraries(ALL_LIBS ${BOARD_ID} "${ALL_SRCS}" "${LIB_DEP_INCLUDES}" "") + + list(APPEND ALL_LIBS ${CORE_LIB} ${INPUT_LIBS}) + + setup_arduino_target(${TARGET_NAME} "${ALL_SRCS}" "${ALL_LIBS}" "${LIB_DEP_INCLUDES}" "") + + if(INPUT_PORT) + setup_arduino_upload(${BOARD_ID} ${TARGET_NAME} ${INPUT_PORT}) + endif() + + if(INPUT_SERIAL) + setup_serial_target(${TARGET_NAME} "${INPUT_SERIAL}") + endif() +endfunction() + + + + + + + + + + +#=============================================================================# +# Internal Functions # +#=============================================================================# + +# [PRIVATE/INTERNAL] +# +# load_board_settings() +# +# Load the Arduino SDK board settings from the boards.txt file. +# +function(LOAD_BOARD_SETTINGS) + load_arduino_style_settings(ARDUINO_BOARDS "${ARDUINO_BOARDS_PATH}") +endfunction() + +# [PRIVATE/INTERNAL] +# +function(LOAD_PROGRAMMERS_SETTINGS) + load_arduino_style_settings(ARDUINO_PROGRAMMERS "${ARDUINO_PROGRAMMERS_PATH}") +endfunction() + +# [PRIVATE/INTERNAL] +# +# load_generator_settings(TARGET_NAME PREFIX [SUFFIX_1 SUFFIX_2 .. SUFFIX_N]) +# +# TARGET_NAME - The base name of the user settings +# PREFIX - The prefix name used for generator settings +# SUFFIX_XX - List of suffixes to load +# +# Loads a list of user settings into the generators scope. User settings have +# the following syntax: +# +# ${BASE_NAME}${SUFFIX} +# +# The BASE_NAME is the target name and the suffix is a specific generator settings. +# +# For every user setting found a generator setting is created of the follwoing fromat: +# +# ${PREFIX}${SUFFIX} +# +# The purpose of loading the settings into the generator is to not modify user settings +# and to have a generic naming of the settings within the generator. +# +function(LOAD_GENERATOR_SETTINGS TARGET_NAME PREFIX) + foreach(GEN_SUFFIX ${ARGN}) + if(${TARGET_NAME}${GEN_SUFFIX}) + set(${PREFIX}${GEN_SUFFIX} ${${TARGET_NAME}${GEN_SUFFIX}} PARENT_SCOPE) + endif() + endforeach() +endfunction() + +# [PRIVATE/INTERNAL] +# +# get_arduino_flags(COMPILE_FLAGS LINK_FLAGS BOARD_ID) +# +# COMPILE_FLAGS_VAR -Variable holding compiler flags +# LINK_FLAGS_VAR - Variable holding linker flags +# BOARD_ID - The board id name +# +# Configures the the build settings for the specified Arduino Board. +# +function(get_arduino_flags COMPILE_FLAGS_VAR LINK_FLAGS_VAR BOARD_ID) + set(BOARD_CORE ${${BOARD_ID}.build.core}) + if(BOARD_CORE) + if(ARDUINO_SDK_VERSION MATCHES "([0-9]+)[.]([0-9]+)") + string(REPLACE "." "" ARDUINO_VERSION_DEFINE "${ARDUINO_SDK_VERSION}") # Normalize version (remove all periods) + set(ARDUINO_VERSION_DEFINE "") + if(CMAKE_MATCH_1 GREATER 0) + set(ARDUINO_VERSION_DEFINE "${CMAKE_MATCH_1}") + endif() + if(CMAKE_MATCH_2 GREATER 10) + set(ARDUINO_VERSION_DEFINE "${ARDUINO_VERSION_DEFINE}${CMAKE_MATCH_2}") + else() + set(ARDUINO_VERSION_DEFINE "${ARDUINO_VERSION_DEFINE}0${CMAKE_MATCH_2}") + endif() + else() + message("Invalid Arduino SDK Version (${ARDUINO_SDK_VERSION})") + endif() + + # output + set(COMPILE_FLAGS "-DF_CPU=${${BOARD_ID}.build.f_cpu} -DARDUINO=${ARDUINO_VERSION_DEFINE} -mmcu=${${BOARD_ID}.build.mcu} -I${ARDUINO_CORES_PATH}/${BOARD_CORE} -I${ARDUINO_LIBRARIES_PATH}") + set(LINK_FLAGS "-mmcu=${${BOARD_ID}.build.mcu}") + if(ARDUINO_SDK_VERSION VERSION_GREATER 1.0 OR ARDUINO_SDK_VERSION VERSION_EQUAL 1.0) + set(PIN_HEADER ${${BOARD_ID}.build.variant}) + set(COMPILE_FLAGS "${COMPILE_FLAGS} -I${ARDUINO_VARIANTS_PATH}/${PIN_HEADER}") + endif() + + # output + set(${COMPILE_FLAGS_VAR} "${COMPILE_FLAGS}" PARENT_SCOPE) + set(${LINK_FLAGS_VAR} "${LINK_FLAGS}" PARENT_SCOPE) + + else() + message(FATAL_ERROR "Invalid Arduino board ID (${BOARD_ID}), aborting.") + endif() +endfunction() + +# [PRIVATE/INTERNAL] +# +# setup_arduino_core(VAR_NAME BOARD_ID) +# +# VAR_NAME - Variable name that will hold the generated library name +# BOARD_ID - Arduino board id +# +# Creates the Arduino Core library for the specified board, +# each board gets it's own version of the library. +# +function(setup_arduino_core VAR_NAME BOARD_ID) + set(CORE_LIB_NAME ${BOARD_ID}_CORE) + set(BOARD_CORE ${${BOARD_ID}.build.core}) + if(BOARD_CORE AND NOT TARGET ${CORE_LIB_NAME}) + set(BOARD_CORE_PATH ${ARDUINO_CORES_PATH}/${BOARD_CORE}) + find_sources(CORE_SRCS ${BOARD_CORE_PATH} True) + # Debian/Ubuntu fix + list(REMOVE_ITEM CORE_SRCS "${BOARD_CORE_PATH}/main.cxx") + add_library(${CORE_LIB_NAME} ${CORE_SRCS}) + get_arduino_flags(ARDUINO_COMPILE_FLAGS ARDUINO_LINK_FLAGS ${BOARD_ID}) + set_target_properties(${CORE_LIB_NAME} PROPERTIES + COMPILE_FLAGS "${ARDUINO_COMPILE_FLAGS}" + LINK_FLAGS "${ARDUINO_LINK_FLAGS}") + set(${VAR_NAME} ${CORE_LIB_NAME} PARENT_SCOPE) + endif() +endfunction() + +# [PRIVATE/INTERNAL] +# +# find_arduino_libraries(VAR_NAME SRCS) +# +# VAR_NAME - Variable name which will hold the results +# SRCS - Sources that will be analized +# +# returns a list of paths to libraries found. +# +# Finds all Arduino type libraries included in sources. Available libraries +# are ${ARDUINO_SDK_PATH}/libraries and ${CMAKE_CURRENT_SOURCE_DIR}. +# +# A Arduino library is a folder that has the same name as the include header. +# For example, if we have a include "#include " then the following +# directory structure is considered a Arduino library: +# +# LibraryName/ +# |- LibraryName.h +# `- LibraryName.c +# +# If such a directory is found then all sources within that directory are considred +# to be part of that Arduino library. +# +function(find_arduino_libraries VAR_NAME SRCS) + set(ARDUINO_LIBS ) + foreach(SRC ${SRCS}) + file(STRINGS ${SRC} SRC_CONTENTS) + foreach(SRC_LINE ${SRC_CONTENTS}) + if("${SRC_LINE}" MATCHES "^ *#include *[<\"](.*)[>\"]") + get_filename_component(INCLUDE_NAME ${CMAKE_MATCH_1} NAME_WE) + get_property(LIBRARY_SEARCH_PATH + DIRECTORY # Property Scope + PROPERTY LINK_DIRECTORIES) + foreach(LIB_SEARCH_PATH ${LIBRARY_SEARCH_PATH} ${ARDUINO_LIBRARIES_PATH} ${CMAKE_CURRENT_SOURCE_DIR} ${CMAKE_CURRENT_SOURCE_DIR}/libraries) + if(EXISTS ${LIB_SEARCH_PATH}/${INCLUDE_NAME}/${CMAKE_MATCH_1}) + list(APPEND ARDUINO_LIBS ${LIB_SEARCH_PATH}/${INCLUDE_NAME}) + break() + endif() + endforeach() + endif() + endforeach() + endforeach() + if(ARDUINO_LIBS) + list(REMOVE_DUPLICATES ARDUINO_LIBS) + endif() + set(${VAR_NAME} ${ARDUINO_LIBS} PARENT_SCOPE) +endfunction() + +# [PRIVATE/INTERNAL] +# +# setup_arduino_library(VAR_NAME BOARD_ID LIB_PATH COMPILE_FLAGS LINK_FLAGS) +# +# VAR_NAME - Vairable wich will hold the generated library names +# BOARD_ID - Board name +# LIB_PATH - path of the library +# COMPILE_FLAGS - compile flags +# LINK_FLAGS - link flags +# +# Creates an Arduino library, with all it's library dependencies. +# +# ${LIB_NAME}_RECURSE controls if the library will recurse +# when looking for source files. +# + +# For known libraries can list recurse here +set(Wire_RECURSE True) +set(Ethernet_RECURSE True) +set(SD_RECURSE True) +function(setup_arduino_library VAR_NAME BOARD_ID LIB_PATH COMPILE_FLAGS LINK_FLAGS) + set(LIB_TARGETS) + + get_filename_component(LIB_NAME ${LIB_PATH} NAME) + set(TARGET_LIB_NAME ${BOARD_ID}_${LIB_NAME}) + if(NOT TARGET ${TARGET_LIB_NAME}) + string(REGEX REPLACE ".*/" "" LIB_SHORT_NAME ${LIB_NAME}) + + # Detect if recursion is needed + if (NOT DEFINED ${LIB_SHORT_NAME}_RECURSE) + set(${LIB_SHORT_NAME}_RECURSE False) + endif() + + find_sources(LIB_SRCS ${LIB_PATH} ${${LIB_SHORT_NAME}_RECURSE}) + if(LIB_SRCS) + + message(STATUS "Generating Arduino ${LIB_NAME} library") + add_library(${TARGET_LIB_NAME} STATIC ${LIB_SRCS}) + + get_arduino_flags(ARDUINO_COMPILE_FLAGS ARDUINO_LINK_FLAGS ${BOARD_ID}) + + find_arduino_libraries(LIB_DEPS "${LIB_SRCS}") + + foreach(LIB_DEP ${LIB_DEPS}) + setup_arduino_library(DEP_LIB_SRCS ${BOARD_ID} ${LIB_DEP} "${COMPILE_FLAGS}" "${LINK_FLAGS}") + list(APPEND LIB_TARGETS ${DEP_LIB_SRCS}) + endforeach() + + set_target_properties(${TARGET_LIB_NAME} PROPERTIES + COMPILE_FLAGS "${ARDUINO_COMPILE_FLAGS} -I${LIB_PATH} -I${LIB_PATH}/utility ${COMPILE_FLAGS}" + LINK_FLAGS "${ARDUINO_LINK_FLAGS} ${LINK_FLAGS}") + + target_link_libraries(${TARGET_LIB_NAME} ${BOARD_ID}_CORE ${LIB_TARGETS}) + list(APPEND LIB_TARGETS ${TARGET_LIB_NAME}) + + endif() + else() + # Target already exists, skiping creating + list(APPEND LIB_TARGETS ${TARGET_LIB_NAME}) + endif() + if(LIB_TARGETS) + list(REMOVE_DUPLICATES LIB_TARGETS) + endif() + set(${VAR_NAME} ${LIB_TARGETS} PARENT_SCOPE) +endfunction() + +# [PRIVATE/INTERNAL] +# +# setup_arduino_libraries(VAR_NAME BOARD_ID SRCS COMPILE_FLAGS LINK_FLAGS) +# +# VAR_NAME - Vairable wich will hold the generated library names +# BOARD_ID - Board ID +# SRCS - source files +# COMPILE_FLAGS - Compile flags +# LINK_FLAGS - Linker flags +# +# Finds and creates all dependency libraries based on sources. +# +function(setup_arduino_libraries VAR_NAME BOARD_ID SRCS COMPILE_FLAGS LINK_FLAGS) + set(LIB_TARGETS) + find_arduino_libraries(TARGET_LIBS "${SRCS}") + foreach(TARGET_LIB ${TARGET_LIBS}) + # Create static library instead of returning sources + setup_arduino_library(LIB_DEPS ${BOARD_ID} ${TARGET_LIB} "${COMPILE_FLAGS}" "${LINK_FLAGS}") + list(APPEND LIB_TARGETS ${LIB_DEPS}) + endforeach() + set(${VAR_NAME} ${LIB_TARGETS} PARENT_SCOPE) +endfunction() + + +# [PRIVATE/INTERNAL] +# +# setup_arduino_target(TARGET_NAME ALL_SRCS ALL_LIBS COMPILE_FLAGS LINK_FLAGS) +# +# TARGET_NAME - Target name +# BOARD_ID - The arduino board +# ALL_SRCS - All sources +# ALL_LIBS - All libraries +# COMPILE_FLAGS - Compile flags +# LINK_FLAGS - Linker flags +# +# Creates an Arduino firmware target. +# +function(setup_arduino_target TARGET_NAME BOARD_ID ALL_SRCS ALL_LIBS COMPILE_FLAGS LINK_FLAGS) + + foreach(LIB_DEP ${ALL_LIBS}) + set(LIB_DEP_INCLUDES "${LIB_DEP_INCLUDES} -I${LIB_DEP}") + endforeach() + + add_executable(${TARGET_NAME} ${ALL_SRCS}) + set_target_properties(${TARGET_NAME} PROPERTIES SUFFIX ".elf") + + get_arduino_flags(ARDUINO_COMPILE_FLAGS ARDUINO_LINK_FLAGS ${BOARD_ID}) + + set_target_properties(${TARGET_NAME} PROPERTIES + COMPILE_FLAGS "${ARDUINO_COMPILE_FLAGS} ${COMPILE_FLAGS} ${LIB_DEP_INCLUDES}" + LINK_FLAGS "${ARDUINO_LINK_FLAGS} ${LINK_FLAGS}") + target_link_libraries(${TARGET_NAME} ${ALL_LIBS} "-lc -lm") + + set(TARGET_PATH ${CMAKE_CURRENT_BINARY_DIR}/${TARGET_NAME}) + add_custom_command(TARGET ${TARGET_NAME} POST_BUILD + COMMAND ${CMAKE_OBJCOPY} + ARGS ${ARDUINO_OBJCOPY_EEP_FLAGS} + ${TARGET_PATH}.elf + ${TARGET_PATH}.eep + COMMENT "Generating EEP image" + VERBATIM) + + # Convert firmware image to ASCII HEX format + add_custom_command(TARGET ${TARGET_NAME} POST_BUILD + COMMAND ${CMAKE_OBJCOPY} + ARGS ${ARDUINO_OBJCOPY_HEX_FLAGS} + ${TARGET_PATH}.elf + ${TARGET_PATH}.hex + COMMENT "Generating HEX image" + VERBATIM) + + # Display target size + add_custom_command(TARGET ${TARGET_NAME} POST_BUILD + COMMAND ${CMAKE_COMMAND} + ARGS -DFIRMWARE_IMAGE=${TARGET_PATH}.hex + -P ${ARDUINO_SIZE_SCRIPT} + COMMENT "Calculating image size" + VERBATIM) + + # Create ${TARGET_NAME}-size target + add_custom_target(${TARGET_NAME}-size + COMMAND ${CMAKE_COMMAND} + -DFIRMWARE_IMAGE=${TARGET_PATH}.hex + -P ${ARDUINO_SIZE_SCRIPT} + DEPENDS ${TARGET_NAME} + COMMENT "Calculating ${TARGET_NAME} image size") +endfunction() + +# [PRIVATE/INTERNAL] +# +# setup_arduino_upload(BOARD_ID TARGET_NAME PORT) +# +# BOARD_ID - Arduino board id +# TARGET_NAME - Target name +# PORT - Serial port for upload +# +# Create an upload target (${TARGET_NAME}-upload) for the specified Arduino target. +# +function(setup_arduino_upload BOARD_ID TARGET_NAME PORT) +# setup_arduino_bootloader_upload() + setup_arduino_bootloader_upload(${TARGET_NAME} ${BOARD_ID} ${PORT}) + + # Add programmer support if defined + if(${TARGET_NAME}_PROGRAMMER AND ${${TARGET_NAME}_PROGRAMMER}.protocol) + setup_arduino_programmer_burn(${TARGET_NAME} ${BOARD_ID} ${${TARGET_NAME}_PROGRAMMER} ${PORT}) + setup_arduino_bootloader_burn(${TARGET_NAME} ${BOARD_ID} ${${TARGET_NAME}_PROGRAMMER} ${PORT}) + endif() +endfunction() + + +# [PRIVATE/INTERNAL] +# +# setup_arduino_bootloader_upload(TARGET_NAME BOARD_ID PORT) +# +# TARGET_NAME - target name +# BOARD_ID - board id +# PORT - serial port +# +# Set up target for upload firmware via the bootloader. +# +# The target for uploading the firmware is ${TARGET_NAME}-upload . +# +function(setup_arduino_bootloader_upload TARGET_NAME BOARD_ID PORT) + set(UPLOAD_TARGET ${TARGET_NAME}-upload) + set(AVRDUDE_ARGS) + + setup_arduino_bootloader_args(${BOARD_ID} ${TARGET_NAME} ${PORT} AVRDUDE_ARGS) + + if(NOT AVRDUDE_ARGS) + message("Could not generate default avrdude bootloader args, aborting!") + return() + endif() + + list(APPEND AVRDUDE_ARGS "-Uflash:w:${TARGET_NAME}.hex") + add_custom_target(${UPLOAD_TARGET} + ${ARDUINO_AVRDUDE_PROGRAM} + ${AVRDUDE_ARGS} + DEPENDS ${TARGET_NAME}) +endfunction() + +# [PRIVATE/INTERNAL] +# +# setup_arduino_programmer_burn(TARGET_NAME BOARD_ID PROGRAMMER) +# +# TARGET_NAME - name of target to burn +# BOARD_ID - board id +# PROGRAMMER - programmer id +# +# Sets up target for burning firmware via a programmer. +# +# The target for burning the firmware is ${TARGET_NAME}-burn . +# +function(setup_arduino_programmer_burn TARGET_NAME BOARD_ID PROGRAMMER) + set(PROGRAMMER_TARGET ${TARGET_NAME}-burn) + + set(AVRDUDE_ARGS) + + setup_arduino_programmer_args(${BOARD_ID} ${PROGRAMMER} ${TARGET_NAME} ${PORT} AVRDUDE_ARGS) + + if(NOT AVRDUDE_ARGS) + message("Could not generate default avrdude programmer args, aborting!") + return() + endif() + + list(APPEND AVRDUDE_ARGS "-Uflash:w:${TARGET_NAME}.hex") + + add_custom_target(${PROGRAMMER_TARGET} + ${ARDUINO_AVRDUDE_PROGRAM} + ${AVRDUDE_ARGS} + DEPENDS ${TARGET_NAME}) +endfunction() + +# [PRIVATE/INTERNAL] +# +# setup_arduino_bootloader_burn(TARGET_NAME BOARD_ID PROGRAMMER) +# +# TARGET_NAME - name of target to burn +# BOARD_ID - board id +# PROGRAMMER - programmer id +# +# Create a target for burning a bootloader via a programmer. +# +# The target for burning the bootloader is ${TARGET_NAME}-burn-bootloader +# +function(setup_arduino_bootloader_burn TARGET_NAME BOARD_ID PROGRAMMER PORT) + set(BOOTLOADER_TARGET ${TARGET_NAME}-burn-bootloader) + + set(AVRDUDE_ARGS) + + setup_arduino_programmer_args(${BOARD_ID} ${PROGRAMMER} ${TARGET_NAME} ${PORT} AVRDUDE_ARGS) + + if(NOT AVRDUDE_ARGS) + message("Could not generate default avrdude programmer args, aborting!") + return() + endif() + + if(NOT ${BOARD_ID}.bootloader.unlock_bits) + message("Missing ${BOARD_ID}.bootloader.unlock_bits, not creating bootloader burn target ${BOOTLOADER_TARGET}.") + return() + endif() + if(NOT ${BOARD_ID}.bootloader.high_fuses) + message("Missing ${BOARD_ID}.bootloader.high_fuses, not creating bootloader burn target ${BOOTLOADER_TARGET}.") + return() + endif() + if(NOT ${BOARD_ID}.bootloader.low_fuses) + message("Missing ${BOARD_ID}.bootloader.low_fuses, not creating bootloader burn target ${BOOTLOADER_TARGET}.") + return() + endif() + if(NOT ${BOARD_ID}.bootloader.path) + message("Missing ${BOARD_ID}.bootloader.path, not creating bootloader burn target ${BOOTLOADER_TARGET}.") + return() + endif() + if(NOT ${BOARD_ID}.bootloader.file) + message("Missing ${BOARD_ID}.bootloader.file, not creating bootloader burn target ${BOOTLOADER_TARGET}.") + return() + endif() + + if(NOT EXISTS "${ARDUINO_BOOTLOADERS_PATH}/${${BOARD_ID}.bootloader.path}/${${BOARD_ID}.bootloader.file}") + message("${ARDUINO_BOOTLOADERS_PATH}/${${BOARD_ID}.bootloader.path}/${${BOARD_ID}.bootloader.file}") + message("Missing bootloader image, not creating bootloader burn target ${BOOTLOADER_TARGET}.") + return() + endif() + + # Erase the chip + list(APPEND AVRDUDE_ARGS "-e") + + # Set unlock bits and fuses (because chip is going to be erased) + list(APPEND AVRDUDE_ARGS "-Ulock:w:${${BOARD_ID}.bootloader.unlock_bits}:m") + if(${BOARD_ID}.bootloader.extended_fuses) + list(APPEND AVRDUDE_ARGS "-Uefuse:w:${${BOARD_ID}.bootloader.extended_fuses}:m") + endif() + list(APPEND AVRDUDE_ARGS "-Uhfuse:w:${${BOARD_ID}.bootloader.high_fuses}:m") + list(APPEND AVRDUDE_ARGS "-Ulfuse:w:${${BOARD_ID}.bootloader.low_fuses}:m") + + # Set bootloader image + list(APPEND AVRDUDE_ARGS "-Uflash:w:${${BOARD_ID}.bootloader.file}:i") + + # Set lockbits + list(APPEND AVRDUDE_ARGS "-Ulock:w:${${BOARD_ID}.bootloader.lock_bits}:m") + + # Create burn bootloader target + add_custom_target(${BOOTLOADER_TARGET} + ${ARDUINO_AVRDUDE_PROGRAM} + ${AVRDUDE_ARGS} + WORKING_DIRECTORY ${ARDUINO_BOOTLOADERS_PATH}/${${BOARD_ID}.bootloader.path} + DEPENDS ${TARGET_NAME}) +endfunction() + +# [PRIVATE/INTERNAL] +# +# setup_arduino_programmer_args(PROGRAMMER OUTPUT_VAR) +# +# PROGRAMMER - programmer id +# TARGET_NAME - target name +# OUTPUT_VAR - name of output variable for result +# +# Sets up default avrdude settings for burning firmware via a programmer. +function(setup_arduino_programmer_args BOARD_ID PROGRAMMER TARGET_NAME PORT OUTPUT_VAR) + set(AVRDUDE_ARGS ${${OUTPUT_VAR}}) + + set(AVRDUDE_FLAGS ${ARDUINO_AVRDUDE_FLAGS}) + if(DEFINED ${TARGET_NAME}_AFLAGS) + set(AVRDUDE_FLAGS ${${TARGET_NAME}_AFLAGS}) + endif() + + list(APPEND AVRDUDE_ARGS "-C${ARDUINO_AVRDUDE_CONFIG_PATH}") + + #TODO: Check mandatory settings before continuing + if(NOT ${PROGRAMMER}.protocol) + message(FATAL_ERROR "Missing ${PROGRAMMER}.protocol, aborting!") + endif() + + list(APPEND AVRDUDE_ARGS "-c${${PROGRAMMER}.protocol}") # Set programmer + + if(${PROGRAMMER}.communication STREQUAL "usb") + list(APPEND AVRDUDE_ARGS "-Pusb") # Set USB as port + elseif(${PROGRAMMER}.communication STREQUAL "serial") + list(APPEND AVRDUDE_ARGS "-P${PORT}") # Set port + if(${PROGRAMMER}.speed) + list(APPEND AVRDUDE_ARGS "-b${${PROGRAMMER}.speed}") # Set baud rate + endif() + endif() + + if(${PROGRAMMER}.force) + list(APPEND AVRDUDE_ARGS "-F") # Set force + endif() + + if(${PROGRAMMER}.delay) + list(APPEND AVRDUDE_ARGS "-i${${PROGRAMMER}.delay}") # Set delay + endif() + + list(APPEND AVRDUDE_ARGS "-p${${BOARD_ID}.build.mcu}") # MCU Type + + list(APPEND AVRDUDE_ARGS ${AVRDUDE_FLAGS}) + + set(${OUTPUT_VAR} ${AVRDUDE_ARGS} PARENT_SCOPE) +endfunction() + +# [PRIVATE/INTERNAL] +# +# setup_arduino_bootloader_args(BOARD_ID TARGET_NAME PORT OUTPUT_VAR) +# +# BOARD_ID - board id +# TARGET_NAME - target name +# PORT - serial port +# OUTPUT_VAR - name of output variable for result +# +# Sets up default avrdude settings for uploading firmware via the bootloader. +function(setup_arduino_bootloader_args BOARD_ID TARGET_NAME PORT OUTPUT_VAR) + set(AVRDUDE_ARGS ${${OUTPUT_VAR}}) + + set(AVRDUDE_FLAGS ${ARDUINO_AVRDUDE_FLAGS}) + if(DEFINED ${TARGET_NAME}_AFLAGS) + set(AVRDUDE_FLAGS ${${TARGET_NAME}_AFLAGS}) + endif() + + list(APPEND AVRDUDE_ARGS "-C${ARDUINO_AVRDUDE_CONFIG_PATH}") # avrdude config + + list(APPEND AVRDUDE_ARGS "-p${${BOARD_ID}.build.mcu}") # MCU Type + + # Programmer + if(${BOARD_ID}.upload.protocol STREQUAL "stk500") + list(APPEND AVRDUDE_ARGS "-cstk500v1") + else() + list(APPEND AVRDUDE_ARGS "-c${${BOARD_ID}.upload.protocol}") + endif() + + list(APPEND AVRDUDE_ARGS "-b${${BOARD_ID}.upload.speed}") # Baud rate + + list(APPEND AVRDUDE_ARGS "-P${PORT}") # Serial port + + list(APPEND AVRDUDE_ARGS "-D") # Dont erase + + list(APPEND AVRDUDE_ARGS ${AVRDUDE_FLAGS}) + + set(${OUTPUT_VAR} ${AVRDUDE_ARGS} PARENT_SCOPE) +endfunction() + +# [PRIVATE/INTERNAL] +# +# find_sources(VAR_NAME LIB_PATH RECURSE) +# +# VAR_NAME - Variable name that will hold the detected sources +# LIB_PATH - The base path +# RECURSE - Whether or not to recurse +# +# Finds all C/C++ sources located at the specified path. +# +function(find_sources VAR_NAME LIB_PATH RECURSE) + set(FILE_SEARCH_LIST + ${LIB_PATH}/*.cpp + ${LIB_PATH}/*.c + ${LIB_PATH}/*.cc + ${LIB_PATH}/*.cxx + ${LIB_PATH}/*.h + ${LIB_PATH}/*.hh + ${LIB_PATH}/*.hxx) + + if(RECURSE) + file(GLOB_RECURSE LIB_FILES ${FILE_SEARCH_LIST}) + else() + file(GLOB LIB_FILES ${FILE_SEARCH_LIST}) + endif() + + if(LIB_FILES) + set(${VAR_NAME} ${LIB_FILES} PARENT_SCOPE) + endif() +endfunction() + +# [PRIVATE/INTERNAL] +# +# setup_serial_target(TARGET_NAME CMD) +# +# TARGET_NAME - Target name +# CMD - Serial terminal command +# +# Creates a target (${TARGET_NAME}-serial) for launching the serial termnial. +# +function(setup_serial_target TARGET_NAME CMD) + string(CONFIGURE "${CMD}" FULL_CMD @ONLY) + add_custom_target(${TARGET_NAME}-serial + ${FULL_CMD}) +endfunction() + + +# [PRIVATE/INTERNAL] +# +# detect_arduino_version(VAR_NAME) +# +# VAR_NAME - Variable name where the detected version will be saved +# +# Detects the Arduino SDK Version based on the revisions.txt file. +# +function(detect_arduino_version VAR_NAME) + if(ARDUINO_VERSION_PATH) + file(READ ${ARDUINO_VERSION_PATH} ARD_VERSION) + if("${ARD_VERSION}" MATCHES " *[0]+([0-9]+)") + set(${VAR_NAME} 0.${CMAKE_MATCH_1} PARENT_SCOPE) + elseif("${ARD_VERSION}" MATCHES "[ ]*([0-9]+[.][0-9]+)") + set(${VAR_NAME} ${CMAKE_MATCH_1} PARENT_SCOPE) + endif() + endif() +endfunction() + + +# [PRIVATE/INTERNAL] +# +# load_arduino_style_settings(SETTINGS_LIST SETTINGS_PATH) +# +# SETTINGS_LIST - Variable name of settings list +# SETTINGS_PATH - File path of settings file to load. +# +# Load a Arduino style settings file into the cache. +# +# Examples of this type of settings file is the boards.txt and +# programmers.txt files located in ${ARDUINO_SDK}/hardware/arduino. +# +# Settings have to following format: +# +# entry.setting[.subsetting] = value +# +# where [.subsetting] is optional +# +# For example, the following settings: +# +# uno.name=Arduino Uno +# uno.upload.protocol=stk500 +# uno.upload.maximum_size=32256 +# uno.build.mcu=atmega328p +# uno.build.core=arduino +# +# will generate the follwoing equivalent CMake variables: +# +# set(uno.name "Arduino Uno") +# set(uno.upload.protocol "stk500") +# set(uno.upload.maximum_size "32256") +# set(uno.build.mcu "atmega328p") +# set(uno.build.core "arduino") +# +# set(uno.SETTINGS name upload build) # List of settings for uno +# set(uno.upload.SUBSETTINGS protocol maximum_size) # List of sub-settings for uno.upload +# set(uno.build.SUBSETTINGS mcu core) # List of sub-settings for uno.build +# +# The ${ENTRY_NAME}.SETTINGS variable lists all settings for the entry, while +# ${ENTRY_NAME}.SUBSETTINGS variables lists all settings for a sub-setting of +# a entry setting pair. +# +# These variables are generated in order to be able to programatically traverse +# all settings (for a example see print_board_settings() function). +# +function(LOAD_ARDUINO_STYLE_SETTINGS SETTINGS_LIST SETTINGS_PATH) + + if(NOT ${SETTINGS_LIST} AND EXISTS ${SETTINGS_PATH}) + file(STRINGS ${SETTINGS_PATH} FILE_ENTRIES) # Settings file split into lines + + foreach(FILE_ENTRY ${FILE_ENTRIES}) + if("${FILE_ENTRY}" MATCHES "^[^#]+=.*") + string(REGEX MATCH "^[^=]+" SETTING_NAME ${FILE_ENTRY}) + string(REGEX MATCH "[^=]+$" SETTING_VALUE ${FILE_ENTRY}) + string(REPLACE "." ";" ENTRY_NAME_TOKENS ${SETTING_NAME}) + string(STRIP "${SETTING_VALUE}" SETTING_VALUE) + + list(LENGTH ENTRY_NAME_TOKENS ENTRY_NAME_TOKENS_LEN) + + + # Add entry to settings list if it does not exist + list(GET ENTRY_NAME_TOKENS 0 ENTRY_NAME) + list(FIND ${SETTINGS_LIST} ${ENTRY_NAME} ENTRY_NAME_INDEX) + if(ENTRY_NAME_INDEX LESS 0) + # Add entry to main list + list(APPEND ${SETTINGS_LIST} ${ENTRY_NAME}) + endif() + + # Add entry setting to entry settings list if it does not exist + set(ENTRY_SETTING_LIST ${ENTRY_NAME}.SETTINGS) + list(GET ENTRY_NAME_TOKENS 1 ENTRY_SETTING) + list(FIND ${ENTRY_SETTING_LIST} ${ENTRY_SETTING} ENTRY_SETTING_INDEX) + if(ENTRY_SETTING_INDEX LESS 0) + # Add setting to entry + list(APPEND ${ENTRY_SETTING_LIST} ${ENTRY_SETTING}) + set(${ENTRY_SETTING_LIST} ${${ENTRY_SETTING_LIST}} + CACHE INTERNAL "Arduino ${ENTRY_NAME} Board settings list") + endif() + + set(FULL_SETTING_NAME ${ENTRY_NAME}.${ENTRY_SETTING}) + + # Add entry sub-setting to entry sub-settings list if it does not exists + if(ENTRY_NAME_TOKENS_LEN GREATER 2) + set(ENTRY_SUBSETTING_LIST ${ENTRY_NAME}.${ENTRY_SETTING}.SUBSETTINGS) + list(GET ENTRY_NAME_TOKENS 2 ENTRY_SUBSETTING) + list(FIND ${ENTRY_SUBSETTING_LIST} ${ENTRY_SUBSETTING} ENTRY_SUBSETTING_INDEX) + if(ENTRY_SUBSETTING_INDEX LESS 0) + list(APPEND ${ENTRY_SUBSETTING_LIST} ${ENTRY_SUBSETTING}) + set(${ENTRY_SUBSETTING_LIST} ${${ENTRY_SUBSETTING_LIST}} + CACHE INTERNAL "Arduino ${ENTRY_NAME} Board sub-settings list") + endif() + set(FULL_SETTING_NAME ${FULL_SETTING_NAME}.${ENTRY_SUBSETTING}) + endif() + + # Save setting value + set(${FULL_SETTING_NAME} ${SETTING_VALUE} + CACHE INTERNAL "Arduino ${ENTRY_NAME} Board setting") + + + endif() + endforeach() + set(${SETTINGS_LIST} ${${SETTINGS_LIST}} + CACHE STRING "List of detected Arduino Board configurations") + mark_as_advanced(${SETTINGS_LIST}) + endif() +endfunction() + +# print_settings(ENTRY_NAME) +# +# ENTRY_NAME - name of entry +# +# Print the entry settings (see load_arduino_syle_settings()). +# +function(PRINT_SETTINGS ENTRY_NAME) + if(${ENTRY_NAME}.SETTINGS) + + foreach(ENTRY_SETTING ${${ENTRY_NAME}.SETTINGS}) + if(${ENTRY_NAME}.${ENTRY_SETTING}) + message(STATUS " ${ENTRY_NAME}.${ENTRY_SETTING}=${${ENTRY_NAME}.${ENTRY_SETTING}}") + endif() + if(${ENTRY_NAME}.${ENTRY_SETTING}.SUBSETTINGS) + foreach(ENTRY_SUBSETTING ${${ENTRY_NAME}.${ENTRY_SETTING}.SUBSETTINGS}) + if(${ENTRY_NAME}.${ENTRY_SETTING}.${ENTRY_SUBSETTING}) + message(STATUS " ${ENTRY_NAME}.${ENTRY_SETTING}.${ENTRY_SUBSETTING}=${${ENTRY_NAME}.${ENTRY_SETTING}.${ENTRY_SUBSETTING}}") + endif() + endforeach() + endif() + message(STATUS "") + endforeach() + endif() +endfunction() + +# [PRIVATE/INTERNAL] +# +# print_list(SETTINGS_LIST) +# +# SETTINGS_LIST - Variables name of settings list +# +# Print list settings and names (see load_arduino_syle_settings()). +function(PRINT_LIST SETTINGS_LIST) + if(${SETTINGS_LIST}) + set(MAX_LENGTH 0) + foreach(ENTRY_NAME ${${SETTINGS_LIST}}) + string(LENGTH "${ENTRY_NAME}" CURRENT_LENGTH) + if(CURRENT_LENGTH GREATER MAX_LENGTH) + set(MAX_LENGTH ${CURRENT_LENGTH}) + endif() + endforeach() + foreach(ENTRY_NAME ${${SETTINGS_LIST}}) + string(LENGTH "${ENTRY_NAME}" CURRENT_LENGTH) + math(EXPR PADDING_LENGTH "${MAX_LENGTH}-${CURRENT_LENGTH}") + set(PADDING "") + foreach(X RANGE ${PADDING_LENGTH}) + set(PADDING "${PADDING} ") + endforeach() + message(STATUS " ${PADDING}${ENTRY_NAME}: ${${ENTRY_NAME}.name}") + endforeach() + endif() +endfunction() + +function(SETUP_ARDUINO_EXAMPLE LIBRARY_NAME EXAMPLE_NAME OUTPUT_VAR) + set(EXAMPLE_SKETCH_PATH ) + + get_property(LIBRARY_SEARCH_PATH + DIRECTORY # Property Scope + PROPERTY LINK_DIRECTORIES) + foreach(LIB_SEARCH_PATH ${LIBRARY_SEARCH_PATH} ${ARDUINO_LIBRARIES_PATH} ${CMAKE_CURRENT_SOURCE_DIR} ${CMAKE_CURRENT_SOURCE_DIR}/libraries) + if(EXISTS "${LIB_SEARCH_PATH}/${LIBRARY_NAME}/examples/${EXAMPLE_NAME}") + set(EXAMPLE_SKETCH_PATH "${LIB_SEARCH_PATH}/${LIBRARY_NAME}/examples/${EXAMPLE_NAME}") + break() + endif() + endforeach() + + if(EXAMPLE_SKETCH_PATH) + setup_arduino_sketch(${EXAMPLE_SKETCH_PATH} SKETCH_CPP) + set("${OUTPUT_VAR}" ${${OUTPUT_VAR}} ${SKETCH_CPP} PARENT_SCOPE) + else() + message(FATAL_ERROR "Could not find example ${EXAMPLE_NAME} from library ${LIBRARY_NAME}") + endif() +endfunction() + +# [PRIVATE/INTERNAL] +# +# setup_arduino_sketch(SKETCH_PATH OUTPUT_VAR) +# +# SKETCH_PATH - Path to sketch directory +# OUTPUT_VAR - Variable name where to save generated sketch source +# +# Generates C++ sources from Arduino Sketch. +function(SETUP_ARDUINO_SKETCH SKETCH_PATH OUTPUT_VAR) + get_filename_component(SKETCH_NAME "${SKETCH_PATH}" NAME) + get_filename_component(SKETCH_PATH "${SKETCH_PATH}" ABSOLUTE) + + if(EXISTS "${SKETCH_PATH}") + set(SKETCH_CPP ${CMAKE_CURRENT_BINARY_DIR}/${SKETCH_NAME}.cpp) + set(MAIN_SKETCH ${SKETCH_PATH}/${SKETCH_NAME}) + + if(EXISTS "${MAIN_SKETCH}.pde") + set(MAIN_SKETCH "${MAIN_SKETCH}.pde") + elseif(EXISTS "${MAIN_SKETCH}.ino") + set(MAIN_SKETCH "${MAIN_SKETCH}.ino") + else() + message(FATAL_ERROR "Could not find main sketch (${SKETCH_NAME}.pde or ${SKETCH_NAME}.ino) at ${SKETCH_PATH}!") + endif() + arduino_debug("sketch: ${MAIN_SKETCH}") + + # Find all sketch files + file(GLOB SKETCH_SOURCES ${SKETCH_PATH}/*.pde ${SKETCH_PATH}/*.ino) + list(REMOVE_ITEM SKETCH_SOURCES ${MAIN_SKETCH}) + list(SORT SKETCH_SOURCES) + + generate_cpp_from_sketch("${MAIN_SKETCH}" "${SKETCH_SOURCES}" "${SKETCH_CPP}") + + # Regenerate build system if sketch changes + add_custom_command(OUTPUT ${SKETCH_CPP} + COMMAND ${CMAKE_COMMAND} ${CMAKE_SOURCE_DIR} + WORKING_DIRECTORY ${CMAKE_BINARY_DIR} + DEPENDS ${MAIN_SKETCH} ${SKETCH_SOURCES} + COMMENT "Regnerating ${SKETCH_NAME} Sketch") + set_source_files_properties(${SKETCH_CPP} PROPERTIES GENERATED TRUE) + + set("${OUTPUT_VAR}" ${${OUTPUT_VAR}} ${SKETCH_CPP} PARENT_SCOPE) + else() + message(FATAL_ERROR "Sketch does not exist: ${SKETCH_PDE}") + endif() +endfunction() + + +# [PRIVATE/INTERNAL] +# +# generate_cpp_from_sketch(MAIN_SKETCH_PATH SKETCH_SOURCES SKETCH_CPP) +# +# MAIN_SKETCH_PATH - Main sketch file path +# SKETCH_SOURCES - Setch source paths +# SKETCH_CPP - Name of file to generate +# +# Generate C++ source file from Arduino sketch files. +function(GENERATE_CPP_FROM_SKETCH MAIN_SKETCH_PATH SKETCH_SOURCES SKETCH_CPP) + file(WRITE ${SKETCH_CPP} "// automatically generated by arduino-cmake\n") + file(READ ${MAIN_SKETCH_PATH} MAIN_SKETCH) + + # remove comments + remove_comments(MAIN_SKETCH "${MAIN_SKETCH_PATH}") + + # find first statement + string(REGEX MATCH "[\n][_a-zA-Z0-9]+[^\n]*" FIRST_STATEMENT "${MAIN_SKETCH}") + string(FIND "${MAIN_SKETCH}" "${FIRST_STATEMENT}" FIRST_STATEMENT_POSITION) + if ("${FIRST_STATEMENT_POSITION}" STREQUAL "-1") + set(FIRST_STATEMENT_POSITION 0) + endif() + #message(STATUS "FIRST STATEMENT: ${FIRST_STATEMENT}") + #message(STATUS "FIRST STATEMENT POSITION: ${FIRST_STATEMENT_POSITION}") + string(LENGTH "${MAIN_SKETCH}" MAIN_SKETCH_LENGTH) + math(EXPR LENGTH_STR1 "${MAIN_SKETCH_LENGTH}-(${FIRST_STATEMENT_POSITION})") + string(SUBSTRING "${MAIN_SKETCH}" ${FIRST_STATEMENT_POSITION} ${LENGTH_STR1} STR1) + #arduino_debug("STR1:\n${STR1}") + + string(SUBSTRING "${MAIN_SKETCH}" 0 ${FIRST_STATEMENT_POSITION} SKETCH_HEAD) + #arduino_debug("SKETCH_HEAD:\n${SKETCH_HEAD}") + + # find the body of the main pde + math(EXPR BODY_LENGTH "${MAIN_SKETCH_LENGTH}-${FIRST_STATEMENT_POSITION}-1") + string(SUBSTRING "${MAIN_SKETCH}" "${FIRST_STATEMENT_POSITION}+1" "${BODY_LENGTH}" SKETCH_BODY) + #arduino_debug("BODY:\n${SKETCH_BODY}") + + # write the file head + file(APPEND ${SKETCH_CPP} "\n${SKETCH_HEAD}\n") + if(ARDUINO_SDK_VERSION VERSION_LESS 1.0) + file(APPEND ${SKETCH_CPP} "#include \"WProgram.h\"\n") + else() + file(APPEND ${SKETCH_CPP} "#include \"Arduino.h\"\n") + endif() + file(APPEND ${SKETCH_CPP} "\n") + + # Find function prototypes + foreach(SKETCH_SOURCE_PATH ${SKETCH_SOURCES} ${MAIN_SKETCH_PATH}) + arduino_debug("Sketch: ${SKETCH_SOURCE_PATH}") + file(READ ${SKETCH_SOURCE_PATH} SKETCH_SOURCE) + remove_comments(SKETCH_SOURCE "${SKETCH_SOURCE_PATH}") + string(REGEX MATCHALL "(^|[\n])([a-zA-Z]+[ ])*[_a-zA-Z0-9]+([ ]*[\n][\t]*|[ ])[_a-zA-Z0-9]+[ ]?[\n]?[\t]*[ ]*[(]([\t]*[ ]*[*&]?[ ]?[a-zA-Z0-9_](\\[([0-9]+)?\\])*[,]?[ ]*[\n]?)*([,]?[ ]*[\n]?[.][.][.])?[)]([ ]*[\n][\t]*|[ ]|[\n])*{" SKETCH_PROTOTYPES "${SKETCH_SOURCE}") + + # Write function prototypes + file(APPEND ${SKETCH_CPP} "\n//=== START Forward: ${SKETCH_SOURCE_PATH}\n") + foreach(SKETCH_PROTOTYPE ${SKETCH_PROTOTYPES}) + string(REPLACE "\n" " " SKETCH_PROTOTYPE "${SKETCH_PROTOTYPE}") + string(REPLACE "{" " " SKETCH_PROTOTYPE "${SKETCH_PROTOTYPE}") + arduino_debug("\tprototype: ${SKETCH_PROTOTYPE};") + file(APPEND ${SKETCH_CPP} "${SKETCH_PROTOTYPE};\n") + endforeach() + file(APPEND ${SKETCH_CPP} "//=== END Forward: ${SKETCH_SOURCE_PATH}\n") + endforeach() + + # Write Sketch CPP source + file(APPEND ${SKETCH_CPP} "\n${SKETCH_BODY}") + foreach (SKETCH_SOURCE_PATH ${SKETCH_SOURCES}) + file(READ ${SKETCH_SOURCE_PATH} SKETCH_SOURCE) + remove_comments(SKETCH_SOURCE "${SKETCH_SOURCE_PATH}") + file(APPEND ${SKETCH_CPP} "${SKETCH_SOURCE}") + endforeach() +endfunction() + +# [PRIVATE/INTERNAL] +# +# setup_arduino_size_script(OUTPUT_VAR) +# +# OUTPUT_VAR - Output variable that will contain the script path +# +# Generates script used to display the firmware size. +function(SETUP_ARDUINO_SIZE_SCRIPT OUTPUT_VAR) + set(ARDUINO_SIZE_SCRIPT_PATH ${CMAKE_BINARY_DIR}/CMakeFiles/FirmwareSize.cmake) + + file(WRITE ${ARDUINO_SIZE_SCRIPT_PATH} " + set(AVRSIZE_PROGRAM ${AVRSIZE_PROGRAM}) + set(AVRSIZE_FLAGS --target=ihex -d) + + execute_process(COMMAND \${AVRSIZE_PROGRAM} \${AVRSIZE_FLAGS} \${FIRMWARE_IMAGE} + OUTPUT_VARIABLE SIZE_OUTPUT) + + string(STRIP \"\${SIZE_OUTPUT}\" SIZE_OUTPUT) + + # Convert lines into a list + string(REPLACE \"\\n\" \";\" SIZE_OUTPUT \"\${SIZE_OUTPUT}\") + + list(GET SIZE_OUTPUT 1 SIZE_ROW) + + if(SIZE_ROW MATCHES \"[ \\t]*[0-9]+[ \\t]*[0-9]+[ \\t]*[0-9]+[ \\t]*([0-9]+)[ \\t]*([0-9a-fA-F]+).*\") + message(\"Total size \${CMAKE_MATCH_1} bytes\") + endif()") + + set(${OUTPUT_VAR} ${ARDUINO_SIZE_SCRIPT_PATH} PARENT_SCOPE) +endfunction() + +# [PRIVATE/INTERNAL] +# +# arduino_debug_on() +# +# Enables Arduino module debugging. +function(ARDUINO_DEBUG_ON) + set(ARDUINO_DEBUG_ON True PARENT_SCOPE) +endfunction() + + +# [PRIVATE/INTERNAL] +# +# arduino_debug_off() +# +# Disables Arduino module debugging. +function(ARDUINO_DEBUG_OFF) + set(ARDUINO_DEBUG_ON False PARENT_SCOPE) +endfunction() + + +# [PRIVATE/INTERNAL] +# +# arduino_debug(MSG) +# +# MSG - Message to print +# +# Print Arduino debugging information. In order to enable printing +# use arduino_debug_on() and to disable use arduino_debug_off(). +function(ARDUINO_DEBUG MSG) + if(ARDUINO_DEBUG_ON) + message("## ${MSG}") + endif() +endfunction() + + +# [PRIVATE/INTERNAL] +# +# remove_comments(SRC_VAR NAME) +# +# SRC_VAR - variable holding sources +# NAME - variable for labelling output debug files +# +function(REMOVE_COMMENTS SRC_VAR NAME) + string(REGEX REPLACE "[\\./\\\\]" "_" FILE "${NAME}") + + set(SRC "${${SRC_VAR}}") + + #message(STATUS "removing comments from: ${FILE}") + #file(WRITE "${CMAKE_BINARY_DIR}/${FILE}_pre_remove_comments.txt" ${SRC}) + #message(STATUS "\n${SRC}") + + # remove all comments + string(REGEX REPLACE "([/][/][^\n]*)|([/][\\*]([^\\*]|([\\*]+[^/\\*]))*[\\*]+[/])" "" SRC "${SRC}") + + #file(WRITE "${CMAKE_BINARY_DIR}/${FILE}_post_remove_comments.txt" ${SRC}) + #message(STATUS "\n${SRC}") + + set(${SRC_VAR} "${SRC}" PARENT_SCOPE) +endfunction() + + +#=============================================================================# +# C Flags # +#=============================================================================# +set(ARDUINO_C_FLAGS "-mcall-prologues -ffunction-sections -fdata-sections") +set(CMAKE_C_FLAGS "-g -Os ${ARDUINO_C_FLAGS}" CACHE STRING "") +set(CMAKE_C_FLAGS_DEBUG "-g ${ARDUINO_C_FLAGS}" CACHE STRING "") +set(CMAKE_C_FLAGS_MINSIZEREL "-Os -DNDEBUG ${ARDUINO_C_FLAGS}" CACHE STRING "") +set(CMAKE_C_FLAGS_RELEASE "-Os -DNDEBUG -w ${ARDUINO_C_FLAGS}" CACHE STRING "") +set(CMAKE_C_FLAGS_RELWITHDEBINFO "-Os -g -w ${ARDUINO_C_FLAGS}" CACHE STRING "") + +#=============================================================================# +# C++ Flags # +#=============================================================================# +set(ARDUINO_CXX_FLAGS "${ARDUINO_C_FLAGS} -fno-exceptions") +set(CMAKE_CXX_FLAGS "-g -Os ${ARDUINO_CXX_FLAGS}" CACHE STRING "") +set(CMAKE_CXX_FLAGS_DEBUG "-g ${ARDUINO_CXX_FLAGS}" CACHE STRING "") +set(CMAKE_CXX_FLAGS_MINSIZEREL "-Os -DNDEBUG ${ARDUINO_CXX_FLAGS}" CACHE STRING "") +set(CMAKE_CXX_FLAGS_RELEASE "-Os -DNDEBUG ${ARDUINO_CXX_FLAGS}" CACHE STRING "") +set(CMAKE_CXX_FLAGS_RELWITHDEBINFO "-Os -g ${ARDUINO_CXX_FLAGS}" CACHE STRING "") + +#=============================================================================# +# Executable Linker Flags # +#=============================================================================# +set(ARDUINO_LINKER_FLAGS "-Wl,--gc-sections -lm") +set(CMAKE_EXE_LINKER_FLAGS "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") +set(CMAKE_EXE_LINKER_FLAGS_DEBUG "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") +set(CMAKE_EXE_LINKER_FLAGS_MINSIZEREL "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") +set(CMAKE_EXE_LINKER_FLAGS_RELEASE "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") +set(CMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") + +#=============================================================================# +# Shared Lbrary Linker Flags # +#=============================================================================# +set(CMAKE_SHARED_LINKER_FLAGS "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") +set(CMAKE_SHARED_LINKER_FLAGS_DEBUG "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") +set(CMAKE_SHARED_LINKER_FLAGS_MINSIZEREL "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") +set(CMAKE_SHARED_LINKER_FLAGS_RELEASE "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") +set(CMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") + +set(CMAKE_MODULE_LINKER_FLAGS "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") +set(CMAKE_MODULE_LINKER_FLAGS_DEBUG "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") +set(CMAKE_MODULE_LINKER_FLAGS_MINSIZEREL "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") +set(CMAKE_MODULE_LINKER_FLAGS_RELEASE "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") +set(CMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") + +#=============================================================================# +# System Paths # +#=============================================================================# +if(UNIX) + include(Platform/UnixPaths) + if(APPLE) + list(APPEND CMAKE_SYSTEM_PREFIX_PATH ~/Applications + /Applications + /Developer/Applications + /sw # Fink + /opt/local) # MacPorts + endif() +elseif(WIN32) + include(Platform/WindowsPaths) +endif() + +#=============================================================================# +# Arduino Settings # +#=============================================================================# +set(ARDUINO_OBJCOPY_EEP_FLAGS -O ihex -j .eeprom --set-section-flags=.eeprom=alloc,load + --no-change-warnings --change-section-lma .eeprom=0 CACHE STRING "") +set(ARDUINO_OBJCOPY_HEX_FLAGS -O ihex -R .eeprom CACHE STRING "") +set(ARDUINO_AVRDUDE_FLAGS -V CACHE STRING "") + +#=============================================================================# +# Initialization # +#=============================================================================# +if(NOT ARDUINO_FOUND) + set(ARDUINO_PATHS) + foreach(VERSION 22 1) + list(APPEND ARDUINO_PATHS arduino-00${VERSION}) + endforeach() + + file(GLOB SDK_PATH_HINTS /usr/share/arduino* + /opt/local/arduino* + /usr/local/share/arduino*) + list(SORT SDK_PATH_HINTS) + list(REVERSE SDK_PATH_HINTS) + + find_path(ARDUINO_SDK_PATH + NAMES lib/version.txt + PATH_SUFFIXES share/arduino + Arduino.app/Contents/Resources/Java/ + ${ARDUINO_PATHS} + HINTS ${SDK_PATH_HINTS} + DOC "Arduino SDK path.") + + if(ARDUINO_SDK_PATH) + if(WIN32) + list(APPEND CMAKE_SYSTEM_PREFIX_PATH ${ARDUINO_SDK_PATH}/hardware/tools/avr/bin) + list(APPEND CMAKE_SYSTEM_PREFIX_PATH ${ARDUINO_SDK_PATH}/hardware/tools/avr/utils/bin) + elseif(APPLE) + list(APPEND CMAKE_SYSTEM_PREFIX_PATH ${ARDUINO_SDK_PATH}/hardware/tools/avr/bin) + endif() + else() + message(FATAL_ERROR "Could not find Arduino SDK (set ARDUINO_SDK_PATH)!") + endif() + + find_file(ARDUINO_CORES_PATH + NAMES cores + PATHS ${ARDUINO_SDK_PATH} + PATH_SUFFIXES hardware/arduino + DOC "Path to directory containing the Arduino core sources.") + + find_file(ARDUINO_VARIANTS_PATH + NAMES variants + PATHS ${ARDUINO_SDK_PATH} + PATH_SUFFIXES hardware/arduino + DOC "Path to directory containing the Arduino variant sources.") + + find_file(ARDUINO_BOOTLOADERS_PATH + NAMES bootloaders + PATHS ${ARDUINO_SDK_PATH} + PATH_SUFFIXES hardware/arduino + DOC "Path to directory containing the Arduino bootloader images and sources.") + + find_file(ARDUINO_LIBRARIES_PATH + NAMES libraries + PATHS ${ARDUINO_SDK_PATH} + DOC "Path to directory containing the Arduino libraries.") + + find_file(ARDUINO_BOARDS_PATH + NAMES boards.txt + PATHS ${ARDUINO_SDK_PATH} + PATH_SUFFIXES hardware/arduino + DOC "Path to Arduino boards definition file.") + + find_file(ARDUINO_PROGRAMMERS_PATH + NAMES programmers.txt + PATHS ${ARDUINO_SDK_PATH} + PATH_SUFFIXES hardware/arduino + DOC "Path to Arduino programmers definition file.") + + find_file(ARDUINO_VERSION_PATH + NAMES lib/version.txt + PATHS ${ARDUINO_SDK_PATH} + DOC "Path to Arduino version file.") + + find_program(ARDUINO_AVRDUDE_PROGRAM + NAMES avrdude + PATHS ${ARDUINO_SDK_PATH} + PATH_SUFFIXES hardware/tools + NO_DEFAULT_PATH) + + find_program(ARDUINO_AVRDUDE_PROGRAM + NAMES avrdude + DOC "Path to avrdude programmer binary.") + + find_program(AVRSIZE_PROGRAM + NAMES avr-size) + + find_file(ARDUINO_AVRDUDE_CONFIG_PATH + NAMES avrdude.conf + PATHS ${ARDUINO_SDK_PATH} /etc/avrdude + PATH_SUFFIXES hardware/tools + hardware/tools/avr/etc + DOC "Path to avrdude programmer configuration file.") + + # Ensure that all required paths are found + foreach(VAR_NAME ARDUINO_CORES_PATH + ARDUINO_BOOTLOADERS_PATH + ARDUINO_LIBRARIES_PATH + ARDUINO_BOARDS_PATH + ARDUINO_PROGRAMMERS_PATH + ARDUINO_VERSION_PATH + ARDUINO_AVRDUDE_FLAGS + ARDUINO_AVRDUDE_PROGRAM + ARDUINO_AVRDUDE_CONFIG_PATH + AVRSIZE_PROGRAM) + if(NOT ${VAR_NAME}) + message(FATAL_ERROR "\nMissing ${VAR_NAME}!\nInvalid Arduino SDK path (${ARDUINO_SDK_PATH}).\n") + endif() + endforeach() + + + detect_arduino_version(ARDUINO_SDK_VERSION) + set(ARDUINO_SDK_VERSION ${ARDUINO_SDK_VERSION} CACHE STRING "Arduino SDK Version") + + + if(ARDUINO_SDK_VERSION VERSION_LESS 0.19) + message(FATAL_ERROR "Unsupported Arduino SDK (require verion 0.19 or higher)") + endif() + + message(STATUS "Arduino SDK version ${ARDUINO_SDK_VERSION}: ${ARDUINO_SDK_PATH}") + + + setup_arduino_size_script(ARDUINO_SIZE_SCRIPT) + set(ARDUINO_SIZE_SCRIPT ${ARDUINO_SIZE_SCRIPT} CACHE INTERNAL "Arduino Size Script") + + load_board_settings() + load_programmers_settings() + + print_board_list() + print_programmer_list() + + + + set(ARDUINO_FOUND True CACHE INTERNAL "Arduino Found") + mark_as_advanced(ARDUINO_CORES_PATH + ARDUINO_VARIANTS_PATH + ARDUINO_BOOTLOADERS_PATH + ARDUINO_LIBRARIES_PATH + ARDUINO_BOARDS_PATH + ARDUINO_PROGRAMMERS_PATH + ARDUINO_VERSION_PATH + ARDUINO_AVRDUDE_FLAGS + ARDUINO_AVRDUDE_PROGRAM + ARDUINO_AVRDUDE_CONFIG_PATH + ARDUINO_OBJCOPY_EEP_FLAGS + ARDUINO_OBJCOPY_HEX_FLAGS + AVRSIZE_PROGRAM) + +endif() + + diff --git a/cmake/modules/ArduinoProcessing.cmake b/cmake/modules/ArduinoProcessing.cmake deleted file mode 100644 index c7a2407a2a..0000000000 --- a/cmake/modules/ArduinoProcessing.cmake +++ /dev/null @@ -1,103 +0,0 @@ -# 1. Concatenate all PDE files -# 2. Write #include "WProgram.h" -# 3. Write prototypes -# 4. Write original sources -# -# -# Prefix Writer -# 1. Scrub comments -# 2. Optionally subsitute Unicode -# 3. Find imports -# 4. Find prototypes -# -# Find prototypes -# 1. Strip comments, quotes, preprocessor directives -# 2. Collapse braches -# 3. Regex - - -set(SINGLE_QUOTES_REGEX "('.')") -set(DOUBLE_QUOTES_REGEX "(\"([^\"\\\\]|\\\\.)*\")") -set(SINGLE_COMMENT_REGEX "([ ]*//[^\n]*)") -set(MULTI_COMMENT_REGEX "(/[*][^/]*[*]/)") -set(PREPROC_REGEX "([ ]*#(\\\\[\n]|[^\n])*)") - -#"[\w\[\]\*]+\s+[&\[\]\*\w\s]+\([&,\[\]\*\w\s]*\)(?=\s*\{)" -set(PROTOTPYE_REGEX "([a-zA-Z0-9]+[ ]*)*[a-zA-Z0-9]+[ ]*\([^{]*\)[ ]*{") - -function(READ_SKETCHES VAR_NAME ) - set(SKETCH_SOURCE) - foreach(SKETCH ${ARGN}) - if(EXISTS ${SKETCH}) - message(STATUS "${SKETCH}") - file(READ ${SKETCH} SKETCH_CONTENTS) - set(SKETCH_SOURCE "${SKETCH_SOURCE}\n${SKETCH_CONTENTS}") - else() - message(FATAL_ERROR "Sketch file does not exist: ${SKETCH}") - endif() - endforeach() - set(${VAR_NAME} "${SKETCH_SOURCE}" PARENT_SCOPE) -endfunction() - -function(STRIP_SOURCES VAR_NAME SOURCES) - string(REGEX REPLACE "${SINGLE_QUOTES_REGEX}|${DOUBLE_QUOTES_REGEX}|${SINGLE_COMMENT_REGEX}|${MULTI_COMMENT_REGEX}|${PREPROC_REGEX}" - "" - SOURCES - "${SOURCES}") - set(${VAR_NAME} "${SOURCES}" PARENT_SCOPE) -endfunction() - -function(COLLAPSE_BRACES VAR_NAME SOURCES) - set(PARSED_SOURCES) - string(LENGTH "${SOURCES}" SOURCES_LENGTH) - math(EXPR SOURCES_LENGTH "${SOURCES_LENGTH}-1") - - set(NESTING 0) - set(START 0) - foreach(INDEX RANGE ${SOURCES_LENGTH}) - string(SUBSTRING "${SOURCES}" ${INDEX} 1 CURRENT_CHAR) - #message("${CURRENT_CHAR}") - if(CURRENT_CHAR STREQUAL "{") - if(NESTING EQUAL 0) - math(EXPR SUBLENGTH "${INDEX}-${START} +1") - string(SUBSTRING "${SOURCES}" ${START} ${SUBLENGTH} CURRENT_CHUNK) - set(PARSED_SOURCES "${PARSED_SOURCES}${CURRENT_CHUNK}") - #message("INDEX: ${INDEX} START: ${START} LENGTH: ${SUBLENGTH}") - endif() - math(EXPR NESTING "${NESTING}+1") - elseif(CURRENT_CHAR STREQUAL "}") - math(EXPR NESTING "${NESTING}-1") - if(NESTING EQUAL 0) - set(START ${INDEX}) - endif() - endif() - endforeach() - - math(EXPR SUBLENGTH "${SOURCES_LENGTH}-${START} +1") - string(SUBSTRING "${SOURCES}" ${START} ${SUBLENGTH} CURRENT_CHUNK) - set(PARSED_SOURCES "${PARSED_SOURCES}${CURRENT_CHUNK}") - - set(${VAR_NAME} "${PARSED_SOURCES}" PARENT_SCOPE) -endfunction() - -function(extract_prototypes VAR_NAME SOURCES) - string(REGEX MATCHALL "${PROTOTPYE_REGEX}" - SOURCES - "${SOURCES}") - set(${VAR_NAME} "${SOURCES}" PARENT_SCOPE) -endfunction() - -read_sketches(SKETCH_SOURCE ${FILES}) -strip_sources(SKETCH_SOURCE "${SKETCH_SOURCE}") -collapse_braces(SKETCH_SOURCE "${SKETCH_SOURCE}") -extract_prototypes(SKETCH_SOURCE "${SKETCH_SOURCE}") - - - - -message("===============") -foreach(ENTRY ${SKETCH_SOURCE}) - message("START]]]${ENTRY}[[[END") -endforeach() -message("===============") -#message("${SKETCH_SOURCE}") diff --git a/cmake/modules/FindArduino.cmake b/cmake/modules/FindArduino.cmake deleted file mode 100644 index dc2b18659a..0000000000 --- a/cmake/modules/FindArduino.cmake +++ /dev/null @@ -1,611 +0,0 @@ -# - Generate firmware and libraries for Arduino Devices -# generate_arduino_firmware(TARGET_NAME) -# TARGET_NAME - Name of target -# Creates a Arduino firmware target. -# -# The target options can be configured by setting options of -# the following format: -# ${TARGET_NAME}${SUFFIX} -# The following suffixes are availabe: -# _SRCS # Sources -# _HDRS # Headers -# _SKETCHES # Arduino sketch files -# _LIBS # Libraries to linked in -# _BOARD # Board name (such as uno, mega2560, ...) -# _PORT # Serial port, for upload and serial targets [OPTIONAL] -# _AFLAGS # Override global Avrdude flags for target -# _SERIAL # Serial command for serial target [OPTIONAL] -# _NO_AUTOLIBS # Disables Arduino library detection -# Here is a short example for a target named test: -# set(test_SRCS test.cpp) -# set(test_HDRS test.h) -# set(test_BOARD uno) -# -# generate_arduino_firmware(test) -# -# -# generate_arduino_library(TARGET_NAME) -# TARGET_NAME - Name of target -# Creates a Arduino firmware target. -# -# The target options can be configured by setting options of -# the following format: -# ${TARGET_NAME}${SUFFIX} -# The following suffixes are availabe: -# -# _SRCS # Sources -# _HDRS # Headers -# _LIBS # Libraries to linked in -# _BOARD # Board name (such as uno, mega2560, ...) -# _NO_AUTOLIBS # Disables Arduino library detection -# -# Here is a short example for a target named test: -# set(test_SRCS test.cpp) -# set(test_HDRS test.h) -# set(test_BOARD uno) -# -# generate_arduino_library(test) - - -find_path(ARDUINO_SDK_PATH - NAMES lib/version.txt hardware libraries - PATH_SUFFIXES share/arduino - DOC "Arduino Development Kit path.") - - -# load_board_settings() -# -# Load the Arduino SDK board settings from the boards.txt file. -# -function(LOAD_BOARD_SETTINGS) - if(NOT ARDUINO_BOARDS AND ARDUINO_BOARDS_PATH) - file(STRINGS ${ARDUINO_BOARDS_PATH} BOARD_SETTINGS) - foreach(BOARD_SETTING ${BOARD_SETTINGS}) - if("${BOARD_SETTING}" MATCHES "^.*=.*") - string(REGEX MATCH "^[^=]+" SETTING_NAME ${BOARD_SETTING}) - string(REGEX MATCH "[^=]+$" SETTING_VALUE ${BOARD_SETTING}) - string(REPLACE "." ";" SETTING_NAME_TOKENS ${SETTING_NAME}) - - list(LENGTH SETTING_NAME_TOKENS SETTING_NAME_TOKENS_LEN) - - - # Add Arduino to main list of arduino boards - list(GET SETTING_NAME_TOKENS 0 BOARD_ID) - list(FIND ARDUINO_BOARDS ${BOARD_ID} ARDUINO_BOARD_INDEX) - if(ARDUINO_BOARD_INDEX LESS 0) - list(APPEND ARDUINO_BOARDS ${BOARD_ID}) - endif() - - # Add setting to board settings list - list(GET SETTING_NAME_TOKENS 1 BOARD_SETTING) - list(FIND ${BOARD_ID}.SETTINGS ${BOARD_SETTING} BOARD_SETTINGS_LEN) - if(BOARD_SETTINGS_LEN LESS 0) - list(APPEND ${BOARD_ID}.SETTINGS ${BOARD_SETTING}) - set(${BOARD_ID}.SETTINGS ${${BOARD_ID}.SETTINGS} - CACHE INTERNAL "Arduino ${BOARD_ID} Board settings list") - endif() - - set(ARDUINO_SETTING_NAME ${BOARD_ID}.${BOARD_SETTING}) - - # Add sub-setting to board sub-settings list - if(SETTING_NAME_TOKENS_LEN GREATER 2) - list(GET SETTING_NAME_TOKENS 2 BOARD_SUBSETTING) - list(FIND ${BOARD_ID}.${BOARD_SETTING}.SUBSETTINGS ${BOARD_SUBSETTING} BOARD_SUBSETTINGS_LEN) - if(BOARD_SUBSETTINGS_LEN LESS 0) - list(APPEND ${BOARD_ID}.${BOARD_SETTING}.SUBSETTINGS ${BOARD_SUBSETTING}) - set(${BOARD_ID}.${BOARD_SETTING}.SUBSETTINGS ${${BOARD_ID}.${BOARD_SETTING}.SUBSETTINGS} - CACHE INTERNAL "Arduino ${BOARD_ID} Board sub-settings list") - endif() - set(ARDUINO_SETTING_NAME ${ARDUINO_SETTING_NAME}.${BOARD_SUBSETTING}) - endif() - - # Save setting value - set(${ARDUINO_SETTING_NAME} ${SETTING_VALUE} CACHE INTERNAL "Arduino ${BOARD_ID} Board setting") - - - endif() - endforeach() - set(ARDUINO_BOARDS ${ARDUINO_BOARDS} CACHE STRING "List of detected Arduino Board configurations") - mark_as_advanced(ARDUINO_BOARDS) - endif() -endfunction() - -# print_board_settings(ARDUINO_BOARD) -# -# ARDUINO_BOARD - Board id -# -# Print the detected Arduino board settings. -# -function(PRINT_BOARD_SETTINGS ARDUINO_BOARD) - if(${ARDUINO_BOARD}.SETTINGS) - - message(STATUS "Arduino ${ARDUINO_BOARD} Board:") - foreach(BOARD_SETTING ${${ARDUINO_BOARD}.SETTINGS}) - if(${ARDUINO_BOARD}.${BOARD_SETTING}) - message(STATUS " ${ARDUINO_BOARD}.${BOARD_SETTING}=${${ARDUINO_BOARD}.${BOARD_SETTING}}") - endif() - if(${ARDUINO_BOARD}.${BOARD_SETTING}.SUBSETTINGS) - foreach(BOARD_SUBSETTING ${${ARDUINO_BOARD}.${BOARD_SETTING}.SUBSETTINGS}) - if(${ARDUINO_BOARD}.${BOARD_SETTING}.${BOARD_SUBSETTING}) - message(STATUS " ${ARDUINO_BOARD}.${BOARD_SETTING}.${BOARD_SUBSETTING}=${${ARDUINO_BOARD}.${BOARD_SETTING}.${BOARD_SUBSETTING}}") - endif() - endforeach() - endif() - message(STATUS "") - endforeach() - endif() -endfunction() - - - -# generate_arduino_library(TARGET_NAME) -# -# see documentation at top -function(GENERATE_ARDUINO_LIBRARY TARGET_NAME) - load_generator_settings(${TARGET_NAME} INPUT _SRCS # Sources - _HDRS # Headers - _LIBS # Libraries to linked in - _BOARD) # Board name (such as uno, mega2560, ...) - set(INPUT_AUTOLIBS True) - if(DEFINED ${TARGET_NAME}_NO_AUTOLIBS AND ${TARGET_NAME}_NO_AUTOLIBS) - set(INPUT_AUTOLIBS False) - endif() - - message(STATUS "Generating ${TARGET_NAME}") - - set(ALL_LIBS) - set(ALL_SRCS ${INPUT_SRCS} ${INPUT_HDRS}) - - setup_arduino_compiler(${INPUT_BOARD}) - setup_arduino_core(CORE_LIB ${INPUT_BOARD}) - - if(INPUT_AUTOLIBS) - setup_arduino_libraries(ALL_LIBS ${INPUT_BOARD} "${ALL_SRCS}") - endif() - - list(APPEND ALL_LIBS ${CORE_LIB} ${INPUT_LIBS}) - - add_library(${TARGET_NAME} ${ALL_SRCS}) - target_link_libraries(${TARGET_NAME} ${ALL_LIBS}) -endfunction() - -# generate_arduino_firmware(TARGET_NAME) -# -# see documentation at top -function(GENERATE_ARDUINO_FIRMWARE TARGET_NAME) - load_generator_settings(${TARGET_NAME} INPUT _SRCS # Sources - _HDRS # Headers - _LIBS # Libraries to linked in - _BOARD # Board name (such as uno, mega2560, ...) - _PORT # Serial port, for upload and serial targets - _AFLAGS # Override global Avrdude flags for target - _SKETCHES # Arduino sketch files - _SERIAL) # Serial command for serial target - - set(INPUT_AUTOLIBS True) - if(DEFINED ${TARGET_NAME}_NO_AUTOLIBS AND ${TARGET_NAME}_NO_AUTOLIBS) - set(INPUT_AUTOLIBS False) - endif() - - message(STATUS "Generating ${TARGET_NAME}") - - set(ALL_LIBS) - set(ALL_SRCS ${INPUT_SRCS} ${INPUT_HDRS}) - - setup_arduino_compiler(${INPUT_BOARD}) - setup_arduino_core(CORE_LIB ${INPUT_BOARD}) - - #setup_arduino_sketch(SKETCH_SRCS ${INPUT_SKETCHES}) - - if(INPUT_AUTOLIBS) - setup_arduino_libraries(ALL_LIBS ${INPUT_BOARD} "${ALL_SRCS}") - endif() - - - list(APPEND ALL_LIBS ${CORE_LIB} ${INPUT_LIBS}) - - setup_arduino_target(${TARGET_NAME} "${ALL_SRCS}" "${ALL_LIBS}") - - if(INPUT_PORT) - setup_arduino_upload(${INPUT_BOARD} ${TARGET_NAME} ${INPUT_PORT}) - endif() - - if(INPUT_SERIAL) - setup_serial_target(${TARGET_NAME} "${INPUT_SERIAL}") - endif() -endfunction() - - -# load_generator_settings(TARGET_NAME PREFIX [SUFFIX_1 SUFFIX_2 .. SUFFIX_N]) -# -# TARGET_NAME - The base name of the user settings -# PREFIX - The prefix name used for generator settings -# SUFFIX_XX - List of suffixes to load -# -# Loads a list of user settings into the generators scope. User settings have -# the following syntax: -# -# ${BASE_NAME}${SUFFIX} -# -# The BASE_NAME is the target name and the suffix is a specific generator settings. -# -# For every user setting found a generator setting is created of the follwoing fromat: -# -# ${PREFIX}${SUFFIX} -# -# The purpose of loading the settings into the generator is to not modify user settings -# and to have a generic naming of the settings within the generator. -# -function(LOAD_GENERATOR_SETTINGS TARGET_NAME PREFIX) - foreach(GEN_SUFFIX ${ARGN}) - if(${TARGET_NAME}${GEN_SUFFIX}) - set(${PREFIX}${GEN_SUFFIX} ${${TARGET_NAME}${GEN_SUFFIX}} PARENT_SCOPE) - endif() - endforeach() -endfunction() - -# setup_arduino_compiler(BOARD_ID) -# -# BOARD_ID - The board id name -# -# Configures the the build settings for the specified Arduino Board. -# -macro(setup_arduino_compiler BOARD_ID) - set(BOARD_CORE ${${BOARD_ID}.build.core}) - if(BOARD_CORE) - set(BOARD_CORE_PATH ${ARDUINO_CORES_PATH}/${BOARD_CORE}) - include_directories(${BOARD_CORE_PATH}) - include_directories(${ARDUINO_LIBRARIES_PATH}) - add_definitions(-DF_CPU=${${BOARD_ID}.build.f_cpu} - -DARDUINO=${ARDUINO_SDK_VERSION} - -mmcu=${${BOARD_ID}.build.mcu} - ) - set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} -mmcu=${${BOARD_ID}.build.mcu}" PARENT_SCOPE) - set(CMAKE_SHARED_LINKER_FLAGS "${CMAKE_SHARED_LINKER_FLAGS} -mmcu=${${BOARD_ID}.build.mcu}" PARENT_SCOPE) - set(CMAKE_MODULE_LINKER_FLAGS "${CMAKE_MODULE_LINKER_FLAGS} -mmcu=${${BOARD_ID}.build.mcu}" PARENT_SCOPE) - endif() -endmacro() - -# setup_arduino_core(VAR_NAME BOARD_ID) -# -# VAR_NAME - Variable name that will hold the generated library name -# BOARD_ID - Arduino board id -# -# Creates the Arduino Core library for the specified board, -# each board gets it's own version of the library. -# -function(setup_arduino_core VAR_NAME BOARD_ID) - set(CORE_LIB_NAME ${BOARD_ID}_CORE) - set(BOARD_CORE ${${BOARD_ID}.build.core}) - if(BOARD_CORE AND NOT TARGET ${CORE_LIB_NAME}) - set(BOARD_CORE_PATH ${ARDUINO_CORES_PATH}/${BOARD_CORE}) - find_sources(CORE_SRCS ${BOARD_CORE_PATH} True) - - # Debian/Ubuntu fix - list(REMOVE_ITEM CORE_SRCS "${BOARD_CORE_PATH}/main.cxx") - - add_library(${CORE_LIB_NAME} ${CORE_SRCS}) - set(${VAR_NAME} ${CORE_LIB_NAME} PARENT_SCOPE) - endif() -endfunction() - -# find_arduino_libraries(VAR_NAME SRCS) -# -# VAR_NAME - Variable name which will hold the results -# SRCS - Sources that will be analized -# -# returns a list of paths to libraries found. -# -# Finds all Arduino type libraries included in sources. Available libraries -# are ${ARDUINO_SDK_PATH}/libraries and ${CMAKE_CURRENT_SOURCE_DIR}. -# -# A Arduino library is a folder that has the same name as the include header. -# For example, if we have a include "#include " then the following -# directory structure is considered a Arduino library: -# -# LibraryName/ -# |- LibraryName.h -# `- LibraryName.c -# -# If such a directory is found then all sources within that directory are considred -# to be part of that Arduino library. -# -function(find_arduino_libraries VAR_NAME SRCS) - set(ARDUINO_LIBS ) - foreach(SRC ${SRCS}) - file(STRINGS ${SRC} SRC_CONTENTS) - foreach(SRC_LINE ${SRC_CONTENTS}) - if("${SRC_LINE}" MATCHES "^ *#include *[<\"](.*)[>\"]") - get_filename_component(INCLUDE_NAME ${CMAKE_MATCH_1} NAME_WE) - get_property(LIBRARY_SEARCH_PATH - DIRECTORY # Property Scope - PROPERTY LINK_DIRECTORIES) - foreach(LIB_SEARCH_PATH ${LIBRARY_SEARCH_PATH} ${ARDUINO_LIBRARIES_PATH} ${CMAKE_CURRENT_SOURCE_DIR} ${CMAKE_CURRENT_SOURCE_DIR}/libraries) - if(EXISTS ${LIB_SEARCH_PATH}/${INCLUDE_NAME}/${CMAKE_MATCH_1}) - list(APPEND ARDUINO_LIBS ${LIB_SEARCH_PATH}/${INCLUDE_NAME}) - break() - endif() - endforeach() - endif() - endforeach() - endforeach() - if(ARDUINO_LIBS) - list(REMOVE_DUPLICATES ARDUINO_LIBS) - endif() - set(${VAR_NAME} ${ARDUINO_LIBS} PARENT_SCOPE) -endfunction() - -# setup_arduino_library(VAR_NAME BOARD_ID LIB_PATH) -# -# VAR_NAME - Vairable wich will hold the generated library names -# BOARD_ID - Board name -# LIB_PATH - path of the library -# -# Creates an Arduino library, with all it's library dependencies. -# -# ${LIB_NAME}_RECURSE controls if the library will recurse -# when looking for source files. -# - -# For known libraries can list recurse here -set(Wire_RECURSE True) -set(Ethernet_RECURSE True) -function(setup_arduino_library VAR_NAME BOARD_ID LIB_PATH) - set(LIB_TARGETS) - - get_filename_component(LIB_NAME ${LIB_PATH} NAME) - set(TARGET_LIB_NAME ${BOARD_ID}_${LIB_NAME}) - if(NOT TARGET ${TARGET_LIB_NAME}) - string(REGEX REPLACE ".*/" "" LIB_SHORT_NAME ${LIB_NAME}) - - # Detect if recursion is needed - if (NOT DEFINED ${LIB_SHORT_NAME}_RECURSE) - set(${LIB_SHORT_NAME}_RECURSE False) - endif() - - find_sources(LIB_SRCS ${LIB_PATH} ${${LIB_SHORT_NAME}_RECURSE}) - if(LIB_SRCS) - - message(STATUS "Generating Arduino ${LIB_NAME} library") - include_directories(${LIB_PATH} ${LIB_PATH}/utility) - add_library(${TARGET_LIB_NAME} STATIC ${LIB_SRCS}) - - find_arduino_libraries(LIB_DEPS "${LIB_SRCS}") - foreach(LIB_DEP ${LIB_DEPS}) - setup_arduino_library(DEP_LIB_SRCS ${BOARD_ID} ${LIB_DEP}) - list(APPEND LIB_TARGETS ${DEP_LIB_SRCS}) - endforeach() - - target_link_libraries(${TARGET_LIB_NAME} ${BOARD_ID}_CORE ${LIB_TARGETS}) - list(APPEND LIB_TARGETS ${TARGET_LIB_NAME}) - endif() - else() - # Target already exists, skiping creating - include_directories(${LIB_PATH} ${LIB_PATH}/utility) - list(APPEND LIB_TARGETS ${TARGET_LIB_NAME}) - endif() - if(LIB_TARGETS) - list(REMOVE_DUPLICATES LIB_TARGETS) - endif() - set(${VAR_NAME} ${LIB_TARGETS} PARENT_SCOPE) -endfunction() - -# setup_arduino_libraries(VAR_NAME BOARD_ID SRCS) -# -# VAR_NAME - Vairable wich will hold the generated library names -# BOARD_ID - Board ID -# SRCS - source files -# -# Finds and creates all dependency libraries based on sources. -# -function(setup_arduino_libraries VAR_NAME BOARD_ID SRCS) - set(LIB_TARGETS) - find_arduino_libraries(TARGET_LIBS "${SRCS}") - foreach(TARGET_LIB ${TARGET_LIBS}) - setup_arduino_library(LIB_DEPS ${BOARD_ID} ${TARGET_LIB}) # Create static library instead of returning sources - list(APPEND LIB_TARGETS ${LIB_DEPS}) - endforeach() - set(${VAR_NAME} ${LIB_TARGETS} PARENT_SCOPE) -endfunction() - - -# setup_arduino_target(TARGET_NAME ALL_SRCS ALL_LIBS) -# -# TARGET_NAME - Target name -# ALL_SRCS - All sources -# ALL_LIBS - All libraries -# -# Creates an Arduino firmware target. -# -function(setup_arduino_target TARGET_NAME ALL_SRCS ALL_LIBS) - add_executable(${TARGET_NAME} ${ALL_SRCS}) - target_link_libraries(${TARGET_NAME} ${ALL_LIBS}) - set_target_properties(${TARGET_NAME} PROPERTIES SUFFIX ".elf") - - set(TARGET_PATH ${CMAKE_CURRENT_BINARY_DIR}/${TARGET_NAME}) - add_custom_command(TARGET ${TARGET_NAME} POST_BUILD - COMMAND ${CMAKE_OBJCOPY} - ARGS ${ARDUINO_OBJCOPY_EEP_FLAGS} - ${TARGET_PATH}.elf - ${TARGET_PATH}.eep - VERBATIM) - add_custom_command(TARGET ${TARGET_NAME} POST_BUILD - COMMAND ${CMAKE_OBJCOPY} - ARGS ${ARDUINO_OBJCOPY_HEX_FLAGS} - ${TARGET_PATH}.elf - ${TARGET_PATH}.hex - VERBATIM) -endfunction() - -# setup_arduino_upload(BOARD_ID TARGET_NAME PORT) -# -# BOARD_ID - Arduino board id -# TARGET_NAME - Target name -# PORT - Serial port for upload -# -# Create an upload target (${TARGET_NAME}-upload) for the specified Arduino target. -# -function(setup_arduino_upload BOARD_ID TARGET_NAME PORT) - set(AVRDUDE_FLAGS ${ARDUINO_AVRDUDE_FLAGS}) - if(DEFINED ${TARGET_NAME}_AFLAGS) - set(AVRDUDE_FLAGS ${${TARGET_NAME}_AFLAGS}) - endif() - if (${${BOARD_ID}.upload.protocol} STREQUAL "stk500") - set(${BOARD_ID}.upload.protocol "stk500v1") - endif() - add_custom_target(${TARGET_NAME}-upload - ${ARDUINO_AVRDUDE_PROGRAM} - ${AVRDUDE_FLAGS} - -C${ARDUINO_AVRDUDE_CONFIG_PATH} - -p${${BOARD_ID}.build.mcu} - -c${${BOARD_ID}.upload.protocol} - -P${PORT} -b${${BOARD_ID}.upload.speed} - #-D - -Uflash:w:${CMAKE_BINARY_DIR}/${TARGET_NAME}.hex:i - DEPENDS ${TARGET_NAME}) - if(NOT TARGET upload) - add_custom_target(upload) - endif() - add_dependencies(upload ${TARGET_NAME}-upload) -endfunction() - -# find_sources(VAR_NAME LIB_PATH RECURSE) -# -# VAR_NAME - Variable name that will hold the detected sources -# LIB_PATH - The base path -# RECURSE - Whether or not to recurse -# -# Finds all C/C++ sources located at the specified path. -# -function(find_sources VAR_NAME LIB_PATH RECURSE) - set(FILE_SEARCH_LIST - ${LIB_PATH}/*.cpp - ${LIB_PATH}/*.c - ${LIB_PATH}/*.cc - ${LIB_PATH}/*.cxx - ${LIB_PATH}/*.h - ${LIB_PATH}/*.hh - ${LIB_PATH}/*.hxx) - - if(RECURSE) - file(GLOB_RECURSE LIB_FILES ${FILE_SEARCH_LIST}) - else() - file(GLOB LIB_FILES ${FILE_SEARCH_LIST}) - endif() - - if(LIB_FILES) - set(${VAR_NAME} ${LIB_FILES} PARENT_SCOPE) - endif() -endfunction() - -# setup_serial_target(TARGET_NAME CMD) -# -# TARGET_NAME - Target name -# CMD - Serial terminal command -# -# Creates a target (${TARGET_NAME}-serial) for launching the serial termnial. -# -function(setup_serial_target TARGET_NAME CMD) - string(CONFIGURE "${CMD}" FULL_CMD @ONLY) - add_custom_target(${TARGET_NAME}-serial - ${FULL_CMD}) -endfunction() - - -# detect_arduino_version(VAR_NAME) -# -# VAR_NAME - Variable name where the detected version will be saved -# -# Detects the Arduino SDK Version based on the revisions.txt file. -# -function(detect_arduino_version VAR_NAME) - if(ARDUINO_VERSION_PATH) - file(READ ${ARDUINO_VERSION_PATH} ARD_VERSION) - if("${ARD_VERSION}" MATCHES " *[0]+([0-9]+)") - set(${VAR_NAME} ${CMAKE_MATCH_1} PARENT_SCOPE) - endif() - endif() -endfunction() - - -function(convert_arduino_sketch VAR_NAME SRCS) -endfunction() - - -# Setting up Arduino enviroment settings -find_file(ARDUINO_CORES_PATH - NAMES cores - PATHS ${ARDUINO_SDK_PATH} - PATH_SUFFIXES hardware/arduino - NO_DEFAULT_PATH) - -find_file(ARDUINO_LIBRARIES_PATH - NAMES libraries - PATHS ${ARDUINO_SDK_PATH} - NO_DEFAULT_PATH) - -find_file(ARDUINO_BOARDS_PATH - NAMES boards.txt - PATHS ${ARDUINO_SDK_PATH} - PATH_SUFFIXES hardware/arduino - NO_DEFAULT_PATH) - -find_file(ARDUINO_PROGRAMMERS_PATH - NAMES programmers.txt - PATHS ${ARDUINO_SDK_PATH} - PATH_SUFFIXES hardware/arduino - NO_DEFAULT_PATH) - -find_file(ARDUINO_REVISIONS_PATH - NAMES revisions.txt - PATHS ${ARDUINO_SDK_PATH} - NO_DEFAULT_PATH) - -find_file(ARDUINO_VERSION_PATH - NAMES lib/version.txt - PATHS ${ARDUINO_SDK_PATH} - NO_DEFAULT_PATH) - -find_program(ARDUINO_AVRDUDE_PROGRAM - NAMES avrdude - PATHS ${ARDUINO_SDK_PATH} - PATH_SUFFIXES hardware/tools - NO_DEFAULT_PATH) - -find_file(ARDUINO_AVRDUDE_CONFIG_PATH - NAMES avrdude.conf - PATHS ${ARDUINO_SDK_PATH} /etc/avrdude - PATH_SUFFIXES hardware/tools - hardware/tools/avr/etc - NO_DEFAULT_PATH) - -set(ARDUINO_OBJCOPY_EEP_FLAGS -O ihex -j .eeprom --set-section-flags=.eeprom=alloc,load --no-change-warnings --change-section-lma .eeprom=0 - CACHE STRING "") -set(ARDUINO_OBJCOPY_HEX_FLAGS -O ihex -R .eeprom - CACHE STRING "") -set(ARDUINO_AVRDUDE_FLAGS -V -F - CACHE STRING "Arvdude global flag list.") - -if(ARDUINO_SDK_PATH) - detect_arduino_version(ARDUINO_SDK_VERSION) - set(ARDUINO_SDK_VERSION ${ARDUINO_SDK_VERSION} CACHE STRING "Arduino SDK Version") -endif(ARDUINO_SDK_PATH) - -include(FindPackageHandleStandardArgs) -find_package_handle_standard_args(Arduino - REQUIRED_VARS ARDUINO_SDK_PATH - ARDUINO_SDK_VERSION - VERSION_VAR ARDUINO_SDK_VERSION) - - -mark_as_advanced(ARDUINO_CORES_PATH - ARDUINO_SDK_VERSION - ARDUINO_LIBRARIES_PATH - ARDUINO_BOARDS_PATH - ARDUINO_PROGRAMMERS_PATH - ARDUINO_REVISIONS_PATH - ARDUINO_AVRDUDE_PROGRAM - ARDUINO_AVRDUDE_CONFIG_PATH - ARDUINO_OBJCOPY_EEP_FLAGS - ARDUINO_OBJCOPY_HEX_FLAGS) -load_board_settings() diff --git a/cmake/modules/Platform/Arduino.cmake b/cmake/modules/Platform/Arduino.cmake deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/cmake/modules/Platform/ArduinoPaths.cmake b/cmake/modules/Platform/ArduinoPaths.cmake deleted file mode 100644 index 27372098cc..0000000000 --- a/cmake/modules/Platform/ArduinoPaths.cmake +++ /dev/null @@ -1,21 +0,0 @@ -if(UNIX) - include(Platform/UnixPaths) - if(APPLE) - list(APPEND CMAKE_SYSTEM_PREFIX_PATH ~/Applications - /Applications - /Developer/Applications - /sw # Fink - /opt/local) # MacPorts - endif() -elseif(WIN32) - include(Platform/WindowsPaths) -endif() - -if(ARDUINO_SDK_PATH) - if(WIN32) - list(APPEND CMAKE_SYSTEM_PREFIX_PATH ${ARDUINO_SDK_PATH}/hardware/tools/avr/bin) - list(APPEND CMAKE_SYSTEM_PREFIX_PATH ${ARDUINO_SDK_PATH}/hardware/tools/avr/utils/bin) - elseif(APPLE) - list(APPEND CMAKE_SYSTEM_PREFIX_PATH ${ARDUINO_SDK_PATH}/hardware/tools/avr/bin) - endif() -endif() diff --git a/cmake/toolchains/Arduino.cmake b/cmake/toolchains/Arduino.cmake deleted file mode 100644 index 897ea4fa0c..0000000000 --- a/cmake/toolchains/Arduino.cmake +++ /dev/null @@ -1,72 +0,0 @@ -set(CMAKE_SYSTEM_NAME Arduino) - -set(CMAKE_C_COMPILER avr-gcc) -set(CMAKE_CXX_COMPILER avr-g++) - -#=============================================================================# -# C Flags # -#=============================================================================# -if (NOT DEFINED ARDUINO_C_FLAGS) - set(ARDUINO_C_FLAGS "-ffunction-sections -fdata-sections") -endif() -set(CMAKE_C_FLAGS "-g -Os ${ARDUINO_C_FLAGS}" CACHE STRING "") -set(CMAKE_C_FLAGS_DEBUG "-g ${ARDUINO_C_FLAGS}" CACHE STRING "") -set(CMAKE_C_FLAGS_MINSIZEREL "-Os -DNDEBUG ${ARDUINO_C_FLAGS}" CACHE STRING "") -set(CMAKE_C_FLAGS_RELEASE "-0s -DNDEBUG -w ${ARDUINO_C_FLAGS}" CACHE STRING "") -set(CMAKE_C_FLAGS_RELWITHDEBINFO "-0s -g -w ${ARDUINO_C_FLAGS}" CACHE STRING "") - -#=============================================================================# -# C++ Flags # -#=============================================================================# -if (NOT DEFINED ARDUINO_CXX_FLAGS) - set(ARDUINO_CXX_FLAGS "${ARDUINO_C_FLAGS} -fno-exceptions") -endif() -set(CMAKE_CXX_FLAGS "-g -Os ${ARDUINO_CXX_FLAGS}" CACHE STRING "") -set(CMAKE_CXX_FLAGS_DEBUG "-g ${ARDUINO_CXX_FLAGS}" CACHE STRING "") -set(CMAKE_CXX_FLAGS_MINSIZEREL "-Os -DNDEBUG ${ARDUINO_CXX_FLAGS}" CACHE STRING "") -set(CMAKE_CXX_FLAGS_RELEASE "-0s -DNDEBUG ${ARDUINO_CXX_FLAGS}" CACHE STRING "") -set(CMAKE_CXX_FLAGS_RELWITHDEBINFO "-0s -g ${ARDUINO_CXX_FLAGS}" CACHE STRING "") - -#=============================================================================# -# Executable Linker Flags # -#=============================================================================# -if (NOT DEFINED ARDUINO_LINKER_FLAGS) - set(ARDUINO_LINKER_FLAGS "-Wl,--gc-sections") -endif() -set(CMAKE_EXE_LINKER_FLAGS "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") -set(CMAKE_EXE_LINKER_FLAGS_DEBUG "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") -set(CMAKE_EXE_LINKER_FLAGS_MINSIZEREL "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") -set(CMAKE_EXE_LINKER_FLAGS_RELEASE "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") -set(CMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") - -#=============================================================================# -# Shared Lbrary Linker Flags # -#=============================================================================# -set(CMAKE_SHARED_LINKER_FLAGS "" CACHE STRING "") -set(CMAKE_SHARED_LINKER_FLAGS_DEBUG "" CACHE STRING "") -set(CMAKE_SHARED_LINKER_FLAGS_MINSIZEREL "" CACHE STRING "") -set(CMAKE_SHARED_LINKER_FLAGS_RELEASE "" CACHE STRING "") -set(CMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO "" CACHE STRING "") - -set(CMAKE_MODULE_LINKER_FLAGS "" CACHE STRING "") -set(CMAKE_MODULE_LINKER_FLAGS_DEBUG "" CACHE STRING "") -set(CMAKE_MODULE_LINKER_FLAGS_MINSIZEREL "" CACHE STRING "") -set(CMAKE_MODULE_LINKER_FLAGS_RELEASE "" CACHE STRING "") -set(CMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO "" CACHE STRING "") - - - - -set(ARDUINO_PATHS) -foreach(VERSION RANGE 22 1) - list(APPEND ARDUINO_PATHS arduino-00${VERSION}) -endforeach() - -find_path(ARDUINO_SDK_PATH - NAMES lib/version.txt - PATH_SUFFIXES share/arduino - Arduino.app/Contents/Resources/Java/ - ${ARDUINO_PATHS} - DOC "Arduino Development Kit path.") - -include(Platform/ArduinoPaths) diff --git a/cmake/updated-arduino-cmake.sh b/cmake/updated-arduino-cmake.sh index c8c26b6781..3cda692b83 100755 --- a/cmake/updated-arduino-cmake.sh +++ b/cmake/updated-arduino-cmake.sh @@ -1,5 +1,4 @@ #!/bin/bash git clone git://github.com/jgoppert/arduino-cmake.git tmp -cp -rf tmp/cmake/modules/* modules -cp -rf tmp/cmake/toolchains/* toolchains +cp -rf tmp/cmake/* . rm -rf tmp From cffe9b4c93dd5ce0d59556fd7a0cfc098034e314 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Mon, 16 Apr 2012 20:53:06 -0400 Subject: [PATCH 04/19] Modified default cmake port. --- CMakeLists.txt | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 250a871ba3..bfc853a29a 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -15,9 +15,8 @@ option(BUILD_2560 "Build 2560 firmware?" ON) option(BUILD_1280 "Build 1280 firmware?" OFF) if (NOT DEFINED PORT) - message(WARNING "please define the upload port (for example: cmake - -DPORT=/dev/ttyUSB0, assuming /dev/ttyUSB0") - set(PORT "/dev/ttyUSB0") + message(WARNING "please define the upload port (for example: cmake -DPORT=/dev/ttyACM0, assuming /dev/ttyACM0") + set(PORT "/dev/ttyACM0") endif() # macro path From 5ff1467c7f9461ddf073fb6f17f834245207e3fe Mon Sep 17 00:00:00 2001 From: Phil Cole Date: Mon, 16 Apr 2012 08:19:11 -0700 Subject: [PATCH 05/19] GIT_Success.txt: test edit Following the instructions, using Tortoise. --- Tools/GIT_Test/GIT_Success.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/GIT_Test/GIT_Success.txt b/Tools/GIT_Test/GIT_Success.txt index a4d60e15ae..a5cfb5e19b 100644 --- a/Tools/GIT_Test/GIT_Success.txt +++ b/Tools/GIT_Test/GIT_Success.txt @@ -7,4 +7,4 @@ list below Test Developer ... Chris Anderson -Phil Cole put this here after rebasing an old branch to master. +Phil Cole after following the instructions explicitly. From 304c5e205177b684026e23303c5422a21762779b Mon Sep 17 00:00:00 2001 From: James Goppert Date: Tue, 17 Apr 2012 16:59:52 -0400 Subject: [PATCH 06/19] Working on cmake options. --- CMakeLists.txt | 65 ++++++------- cmake/modules/APMOption.cmake | 27 ++++++ cmake/options-ArduPlane.cmake | 171 ++++++++++++++++++++++++++++++++++ 3 files changed, 227 insertions(+), 36 deletions(-) create mode 100644 cmake/modules/APMOption.cmake create mode 100644 cmake/options-ArduPlane.cmake diff --git a/CMakeLists.txt b/CMakeLists.txt index bfc853a29a..829c2c1a3e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -10,14 +10,6 @@ set(PROJECT_VERSION_MINOR "3") set(PROJECT_VERSION_PATCH "3") set(PROJECT_VERSION "${PROJECT_VERSION_MAJOR}.${PROJECT_VERSION_MINOR}.${PROJECT_VERSION_PATCH}") -# options -option(BUILD_2560 "Build 2560 firmware?" ON) -option(BUILD_1280 "Build 1280 firmware?" OFF) - -if (NOT DEFINED PORT) - message(WARNING "please define the upload port (for example: cmake -DPORT=/dev/ttyACM0, assuming /dev/ttyACM0") - set(PORT "/dev/ttyACM0") -endif() # macro path list(APPEND CMAKE_MODULE_PATH "${CMAKE_SOURCE_DIR}/cmake/modules") @@ -27,39 +19,40 @@ include(MacroEnsureOutOfSourceBuild) macro_ensure_out_of_source_build("${PROJECT_NAME} requires an out of source build. Please create a separate build directory and run 'cmake /path/to/${PROJECT_NAME} [options]' there.") +# macros +include(CMakeParseArguments) +include(APMOption) + +# options +apm_option("APM_PROGRAMMING_PORT" TYPE "STRING" + DESCRIPTION "Programming upload port?" + DEFAULT "/dev/ttyUSB0") + +apm_option("APM_BOARD" TYPE "COMBO" + DESCRIPTION "ArduPilotMega board?" + DEFAULT "mega2560" + OPTIONS "mega" "mega2560") + +apm_option("APM_PROJECT" TYPE "COMBO" + DESCRIPTION "ArduPilotMega project to build?" + DEFAULT "ArduPlane" + OPTIONS "ArduPlane" "ArduCopter") + +if(APM_PROJECT STREQUAL "ArduPlane") + include(cmake/options-ArduPlane.cmake) +endif() + # modify flags from default toolchain flags set(APM_OPT_FLAGS "-Wformat -Wall -Wshadow -Wpointer-arith -Wcast-align -Wwrite-strings -Wformat=2") set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${APM_OPT_FLAGS}") set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${APM_OPT_FLAGS} -Wno-reorder") set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} ${APM_OPT_FLAGS} -Wl,--relax") -# projects -set(PROJECT_LIST - ArduPlane - ArduCopter - #apo - #ArduBoat - #ArduRover - ) - -# macro for building firmware for all projects -macro(build_apm_firmware BOARD) - foreach(PROJECT ${PROJECT_LIST}) - set(${PROJECT}_SKETCH ${CMAKE_SOURCE_DIR}/${PROJECT}) - set(${PROJECT}_BOARD ${BOARD}) - set(${PROJECT}_PORT ${PORT}) - generate_arduino_firmware(${PROJECT}) - endforeach() -endmacro() - -# build firmware based on options -if (BUILD_2560) - build_apm_firmware(mega2560) -endif() - -if (BUILD_1280) - build_apm_firmware(mega) -endif() +# build apm project +set(${APM_PROJECT}_SKETCH ${CMAKE_SOURCE_DIR}/${APM_PROJECT}) +set(${APM_PROJECT}_BOARD ${APM_BOARD}) +set(${APM_PROJECT}_PORT ${APM_PROGRAMMING_PORT}) +generate_arduino_firmware(${APM_PROJECT}) # packaging settings set(CPACK_PACKAGE_DESCRIPTION_SUMMARY "A universal autopilot system for the ArduPilotMega board.") @@ -79,5 +72,5 @@ set(CPACK_SOURCE_IGNORE_FILES ${CPACK_SOURCE_IGNORE_FILES} set(CPACK_INSTALL_PREFIX "${CMAKE_INSTALL_PREFIX}") set(CPACK_SOURCE_GENERATOR "ZIP") set(CPACK_GENERATOR "ZIP") -set(CPACK_PACKAGE_NAME "${APPLICATION_NAME}_${BOARD}") +set(CPACK_PACKAGE_NAME "${APM_PROJECT}_${BOARD}_${HIL_MODE}") include(CPack) diff --git a/cmake/modules/APMOption.cmake b/cmake/modules/APMOption.cmake new file mode 100644 index 0000000000..5f5597de27 --- /dev/null +++ b/cmake/modules/APMOption.cmake @@ -0,0 +1,27 @@ +macro(apm_option NAME) + cmake_parse_arguments(ARG + "ADVANCED" + "TYPE;DESCRIPTION;DEFAULT" "OPTIONS" ${ARGN}) + + if ("${ARG_TYPE}" STREQUAL "BOOL") + set("${NAME}" "${ARG_DEFAULT}" CACHE BOOL "${ARG_DESCRIPTION}") + elseif ( ("${ARG_TYPE}" STREQUAL "STRING") OR ("${ARG_TYPE}" STREQUAL "COMBO")) + set("${NAME}" "${ARG_DEFAULT}" CACHE STRING "${ARG_DESCRIPTION}") + else() + message(FATAL_ERROR "unknown type: \""${ARG_TYPE}"\" for add_option(${NAME}...") + endif() + + if ("${ARG_TYPE}" STREQUAL "COMBO") + if ("${ARG_OPTIONS}" STREQUAL "") + message(FATAL_ERROR "must set OPTIONS for add_option(${NAME}...") + else() + set_property(CACHE "${NAME}" PROPERTY STRINGS "${ARG_OPTIONS}") + endif() + endif() + + if (ARG_ADVANCED) + mark_as_advanced(FORCE "${NAME}") + endif() + +endmacro() + diff --git a/cmake/options-ArduPlane.cmake b/cmake/options-ArduPlane.cmake new file mode 100644 index 0000000000..b28bd8016e --- /dev/null +++ b/cmake/options-ArduPlane.cmake @@ -0,0 +1,171 @@ +# options +#bool_option(LOGGING DESCRIPTION "Logging support?" DEFAULT OFF) +#bool_option(GPS "Gps support?" ON) +#option(CLI_SLIDER "Command-line-interface slider support?" OFF) +#option(APM2 "Build for APM 2.0" OFF) + +apm_option("APM_FRAME" TYPE "COMBO" + DESCRIPTION "Vehicle type?" + DEFAULT "PLANE_FRAME" + OPTIONS "HELI_FRAME" "HEXA_FRAME" "OCTA_FRAME" "Y6_FRAME") + +apm_option("GPS_PROTOCOL" TYPE "COMBO" + DESCRIPTION "GPS protocol?" + DEFAULT "GPS_PROTOCOL_AUTO" + OPTIONS + "GPS_PROTOOCL_NONE" + "GPS_PROTOCOL_AUTO" + "GPS_PROTOCOL_NONE" + "GPS_PROTOCOL_IMU" + "GPS_PROTOCOL_MTK" + "GPS_PROTOCOL_MTK16" + "GPS_PROTOCOL_UBLOX" + "GPS_PROTOCOL_SIRF" + "GPS_PROTOCOL_NMEA") + +apm_option("AIRSPEED_SENSOR" TYPE "BOOL" + DESCRIPTION "Enable airspeed sensor?" + DEFAULT OFF) + +apm_option("AIRSPEED_RATIO" TYPE "STRING" ADVANCED + DESCRIPTION "Airspeed ratio?" + DEFAULT "1.9936") + +apm_option("MAGNETOMETER" TYPE "BOOL" + DESCRIPTION "Enable airspeed sensor?" + DEFAULT OFF) + +apm_option("MAG_ORIENTATION" TYPE "COMBO" ADVANCED + DESCRIPTION "Magnetometer orientation?" + DEFAULT "AP_COMPASS_COMPONENTS_DOWN_PINS_FORWARD" + OPTIONS + "AP_COMPASS_COMPONENTS_DOWN_PINS_FORWARD" + "AP_COMPASS_COMPONENTS_DOWN_PINS_BACK" + "AP_COMPASS_COMPONENTS_UP_PINS_FORWARD" + "AP_COMPASS_COMPONENTS_UP_PINS_BACK") + +apm_option("HIL_MODE" TYPE "COMBO" + DESCRIPTION "Hardware-in-the-loop- mode?" + DEFAULT "HIL_MODE_DISABLED" + OPTIONS + "HIL_MODE_DISABLED" + "HIL_MODE_ATTITUDE" + "HIL_MODE_SENSORS") + +apm_option("HIL_PORT" TYPE "COMBO" + DESCRIPTION "Port for Hardware-in-the-loop communication" + DEFAULT "0" + OPTIONS "0" "1" "2" "3") + +apm_option("HIL_PROTOCOL" TYPE "COMBO" + DESCRIPTION "Hardware-in-the-loop protocol?" + DEFAULT "HIL_PROTOCOL_MAVLINK" + OPTIONS "HIL_PROTOCOL_MAVLINK" "HIL_PROTOCOL_XPLANE") + +apm_option("GPS_PROTOCOL" TYPE "COMBO" + DESCRIPTION "Ground station protocol?" + DEFAULT "GCS_PROTOCOL_MAVLINK" + OPTIONS "GCS_PROTOCOL_NONE" "GCS_PROTOCOL_MAVLINK") + +apm_option("GCS_PORT" TYPE "COMBO" ADVANCED + DESCRIPTION "Ground station port?" + DESCRIPTION "3" + OPTIONS "0" "1" "2" "3") + +apm_option("MAV_SYSTEM_ID" TYPE "STRING" ADVANCED + DESCRIPTION "MAVLink System ID?" + DESCRIPTION "1") + +apm_option("SERIAL0_BAUD" TYPE "COMBO" ADVANCED + DESCRIPTION "Serial 0 baudrate?" + DEFAULT "115200" + OPTIONS "57600" "115200") + +apm_option("SERIAL3_BAUD" TYPE "COMBO" ADVANCED + DESCRIPTION "Serial 3 baudrate?" + DEFAULT "57600" + OPTIONS "57600" "115200") + +apm_option("BATTERY_EVENT" TYPE "BOOL" ADVANCED + DESCRIPTION "Enable low voltage/ high discharge warnings?" + DEFAULT OFF) + +apm_option("LOW_VOLTAGE" TYPE "STRING" ADVANCED + DESCRIPTION "Voltage to consider low (volts)?" + DEFAULT "9.6") + +apm_option("VOLT_DIV_RATIO" TYPE "STRING" ADVANCED + DESCRIPTION "Voltage division ratio?" + DEFAULT "3.56") + +apm_option("CUR_AMPS_PER_VOLT" TYPE "STRING" ADVANCED + DESCRIPTION "Current amps/volt?" + DEFAULT "27.32") + +apm_option("CUR_AMPS_PER_VOLT" TYPE "STRING" ADVANCED + DESCRIPTION "Current amps/volt?" + DEFAULT "27.32") + +#set(CUR_AMPS_PER_VOLT "27.32" CACHE STRING "Current amps/volt?") +#set(CUR_AMPS_OFFSET "0.0" CACHE STRING "Current amps offset?") +#set(HIGH_DISCHARGE "1760" CACHE STRING "What to consider high discharge rate (milliamp-hours)?") + +#set(INPUT_VOLTAGE "4.68" CACHE STRING "Voltage measured at the processor (volts)?") + +#set(FLIGHT_MODE_CHANNEL "8" CACHE STRING "The radio channel to control the flight mode.") +#set_property(CACHE FLIGHT_MODE_CHANNEL PROPERTY STRINGS 1 2 3 4 5 6 7 8) + +#set(FLIGHT_MODES MANUAL STABILIZE FLY_BY_WIRE_A FLY_BY_WIRE_B RTL AUTO LOITER CIRCLE) + +#set(FLIGHT_MODE_1 "RTL" CACHE STRING "Flight mode for radio position 1 (1165 ms)?") +#set_property(CACHE FLIGHT_MODE_1 PROPERTY STRINGS ${FLIGHT_MODES}) + +#set(FLIGHT_MODE_2 "RTL" CACHE STRING "Flight mode for radio position 2 (1295 ms)?") +#set_property(CACHE FLIGHT_MODE_2 PROPERTY STRINGS ${FLIGHT_MODES}) + +#set(FLIGHT_MODE_3 "STABILIZE" CACHE STRING "Flight mode for radio position 3 (1425 ms)?") +#set_property(CACHE FLIGHT_MODE_3 PROPERTY STRINGS ${FLIGHT_MODES}) + +#set(FLIGHT_MODE_4 "STABILIZE" CACHE STRING "Flight mode for radio position 4 (1555 ms)?") +#set_property(CACHE FLIGHT_MODE_4 PROPERTY STRINGS ${FLIGHT_MODES}) + +#set(FLIGHT_MODE_5 "MANUAL" CACHE STRING "Flight mode for radio position 5 (FAILSAFE if using channel 8) (1685 ms)?") +#set_property(CACHE FLIGHT_MODE_5 PROPERTY STRINGS ${FLIGHT_MODES}) + +#set(FLIGHT_MODE_6 "MANUAL" CACHE STRING "Flight mode for radio position 6 (FAILSAFE is using channel 8) (1815 ms)?") +#set_property(CACHE FLIGHT_MODE_6 PROPERTY STRINGS ${FLIGHT_MODES}) + +#set(FLAP_1_SPEED "0" CACHE STRING "Speed below which flaps are deployed (m/s)?") +#set(FLAP_1_PERCENT "0" CACHE STRING "Flap deployment percentage (%)?") + +#set(FLAP_2_SPEED "0" CACHE STRING "Speed below which flaps are deployed (m/s)?") +#set(FLAP_2_PERCENT "0" CACHE STRING "Flap deployment percentage (%)?") + +#set(THROTTLE_FAILSAFE "ENABLED" CACHE STRING "Enable throttle shuttoff when radio below failsafe value?") +#set_property(CACHE THROTTLE_FAILSAFE PROPERTY STRINGS ENABLED DISABLED) + +#set(THROTTLE_FS_VALUE "950" CACHE STRING "Radio value at which to disable throttle (ms).") + +#set(GCS_HEARTBEAT_FAILSAFE "DISABLED" CACHE STRING "Enable failsafe when ground station communication lost?") +#set_property(CACHE GCS_HEARTBEAT_FAILSAFE PROPERTY STRINGS ENABLED DISABLED) +#set(SHORT_FAILSAFE_ACTION "0" CACHE STRING "Failsafe mode RTL, then return to AUTO/LOITER") +#set(LONG_FAILSAFE_ACTION "0" CACHE STRING "Failsafe mode RTL") + +#set(AUTO_TRIM "DISABLED" CACHE STRING "Update trim with manual radio input when leaving MANUAL mode?") +#set_property(CACHE AUTO_TRIM PROPERTY STRINGS ENABLED DISABLED) + +#set(THROTTLE_REVERSE "DISABLED" CACHE STRING "Reverse throttle output signal?") +#set_property(CACHE THROTTLE_REVERSE PROPERTY STRINGS ENABLED DISABLED) + +#set(ENABLE_STICK_MIXING "DISABLED" CACHE STRING "Enable manual input in autopilot modes?") +#set_property(CACHE THROTTLE_REVERSE PROPERTY STRINGS ENABLED DISABLED) + +#set(THROTTLE_OUT "ENABLED" CACHE STRING "Disabled throttle output? (useful for debugging)?") +#set_property(CACHE THROTTLE_OUT PROPERTY STRINGS ENABLED DISABLED) + +#set(GROUND_START_DELAY "0" CACHE STRING "Delay between power-up and IMU calibration (s)?") + +#set(ENABLE_AIR_START "DISABLED" CACHE STRING "Enable in-air restart?") +#set_property(CACHE ENABLE_AIR_START PROPERTY STRINGS ENABLED DISABLED) + + From 86848d10636617621ffe327840a4020de119697d Mon Sep 17 00:00:00 2001 From: Michael Oborne Date: Wed, 18 Apr 2012 08:04:57 +0800 Subject: [PATCH 07/19] APM Planner 1.1.69 add ability to geotag images from log file. - will release guide soon --- Tools/ArdupilotMegaPlanner/Msi/installer.wxs | 399 +++++++++--------- Tools/ArdupilotMegaPlanner/Msi/wix.pdb | Bin 19968 -> 19968 bytes .../Properties/AssemblyInfo.cs | 2 +- .../bin/Release/ArdupilotMegaPlanner.pdb | Bin 1175040 -> 1179136 bytes .../bin/Release/version.txt | 2 +- Tools/ArdupilotMegaPlanner/georefimage.cs | 163 ++++++- 6 files changed, 365 insertions(+), 201 deletions(-) diff --git a/Tools/ArdupilotMegaPlanner/Msi/installer.wxs b/Tools/ArdupilotMegaPlanner/Msi/installer.wxs index a03d29139f..74d460a504 100644 --- a/Tools/ArdupilotMegaPlanner/Msi/installer.wxs +++ b/Tools/ArdupilotMegaPlanner/Msi/installer.wxs @@ -2,14 +2,14 @@ - + - - + + @@ -31,224 +31,227 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - + + + - - - - - - - - - - + + + + + + + + + + - - - - - + + + + + - - - - + + + + - - - - - - - - - - - + + + + + + + + + + + - - - - - - - - - - - + + + + + + + + + + + - - - - + + + + - - - - - - + + + + + + - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + - - - - - - - - - - - + + + + + + + + + + + - - - - + + + + - - - + + + - - - + + + - - - + + + - - - - + + + + - - - - - - + + + + + + + - - - + + + - - - - - - + + + + + + - - - + + + - - - + + + - - - + + + @@ -290,27 +293,27 @@ - - - - - - - - - - - + + + + + + + + + + - - - - - - + + + + + + + @@ -331,7 +334,7 @@ - + h!aV7(S$uaU-K+bXbY(}lk#tPGcGMi5;wSyD{t8QmnQNEc+Z5{IAylR!ncYq9z93aEN zUaj5==p+UPHZTbyGTeIpAxhH@U(tfknX|$hZS!F!%u( z4)$v7Kt}-q+eAm3a-NCpbQ`d()S8TRKevG1Yxp_3|=MvVszhDuNcE`czmZooZKxv!JC4_px+E7EgKAVu{AH4)5>cS&wG}o_N6e;u(x*B%WoY z#Y%p|HUjk?o)Z8`R*Oa8k?|;aHUXZ8XEUDn@u+}V@wCG;4bRtjwgA2rkC%tVQUOm5 zJazDN0IV~fp?HSr>YCg2t8xuDAPN38+~CNyit$oz*V!L7mOLkWHZD$@{5a%-M0bj$ z@Z7GNBXOV9(?==X@w|>>&2edg&05aWV!b|x?%x;nJYy|(Fi|`y?Tl2_>IF=twmm0c?-QWU>Z3X7@3>tJn3e!H%aFrMWS?*GVT@9D+Qtkk+ zBv-mWIh_a6)tSZBRaL7q%asl~WcfGORJinSO0DX}L9P+YH-Z8KSYpJqOFCslq)yq* zh)qC1f1?p-{UynlDt(T(BX|R^vzMeu1bKZ_ztx3OR3&FMyXvwUBtX41FO*^h${hE? zt1`_kltOGq@g&PgN@}P0(eXm5qo^~>QLab|kgQoKPqVMd=SwMsT3(i-J&Zd-M%Dy5+YJNiuat5=;&ZDF@ zUcpp&1zJ4Q4aZvS!YO3GDtX%0ngjuqu*&X7@mHm$QX0K+73EqCk@APo>Z?+sSuW&X zsE*UMzXig8E)|HGSF}mN3ez?*-i{mi(pmR8%a5Ywy6&a;*oL zcA`B=H>GACD=KjR|AMk7+5>68P04OO2eGb9rExdWVXsV8X!i|k5be1sH4re*M6s2wW*42_IiDdv4jI)PJ11RE@9%OIyuIOQOfB|%;L<$5duYorQ z+C#L{Q!_oc6NXi!PkM-Us^iP;RDp6HLgW3BU-KKZ?;$j&`3+ZotT_Xz=qb$7y~i*{ z_CH{jJpaU7^dFL48c4;jBBOyM^-}$4@E=mFsm&EA_YW!3qaxT|zJcPhK`ulJ4KZD5 zoP*0C$}8{)q{LVsPiYX9{N)uynLRwMH29h1Pl=BtyX{9aMP(}Z3$SJ<>`kN!wDl3B z4gmX@V!HT9YG|6R3grD5h(I9Xi>bk5sWE6LFsKqhO^a#WW2ve@_`?$^ihLK!p3>`d z=N~nY(%)AUs`pfCURr`qe21EzY|#-Fhl%)VGeeo&J7`>YUDRmAJe+_^shH$-epts_HSPK>a)0Z7`)i!}u7_ zxW7#tTRv{1!Ib+<>VUGYeFC9_k^3(<>GTt{<}WwPR(Ps0n)^PL6snbg{Hi=fmrkXG z?tXl>P%aru7<5P#~_9zP$Y)?6h#Tydp`2WYERnp!uxs@qa zxVFv&|5u5MpP@vd5M$A8vi=97^`hIZ5^?>Uq>`&jFm?S8>cxq34iqP;+YTkkqgHuC z*AM>(yyjxm`s6m<{Et*G$QZS_cRI}gdnDXL%kNZXSi6G%hHo9a{+4=60{z3Mm3L)F z$aATuWHS_5vh<;Z`_TO*FQh^dQ@m=Bh!ye0s}_lt(6Ut*#YEd;y{RNiPtqORgocoavQckqg;?f zv5F939RRUg?4>AA5hW0I_7r!ed`hs1a0Dgitig1kp-sX21Oudf1<(Tnly88Fj9>y| zx;D~@wQ_p;1S9BX1QW`MKq-IK1X#e^qXhHJ10*QlV$p|WRGVeoBtu(SBlD?9Pe4B# z$!%VuhS;@_+WU#h)X_`W!Jwa)2(IYPVB+{`7H+z7R8#@(-X<^MAM>yMqO==$F=Mw3 zhnpF4>*iCj*UR#ZpRV^FA06#&7lEPfsmBf*J{cID#8)Rt0tw4y*ULY{2-ey~Fo1{c zB2ue%zz~LotY{?JWA&p0!@ZT&-oox3o$ta27=?)U7Htf(UXhk~3xDfCwAsajw9Q*Y zX%`O~^lT1Umk(06a`s@A9hQSs*mlwW(cH@ffT3*<-H_g;s zHWuIm%8T_04DE=a@E)FS0Oh!4z(Wa0%8MG>N)yaon%n*Zx?Wy%fP~e3A>r$g@WBVv z*;j;V58N1lr{xeOM2TSC_c%loG9XG;Q=!liUty1N(lS?&S`N82{KR1s^k(BaJ4CPwx&>?jCC(HT6T2gqt`PldJ16<-G@7x}T^AS-1L$NRK|SX15OueS&2= zt85hTr%$kW65L|1qq4vFMlsb$vP`A?*ITuB=%HAVf#MmnX zo%5-zcV3bn`1sMg;X>1#Ag2dV&TV>Gjy-^2dJ-<|>OoFQZ=4c=w$!ncEmctk5_KyO zp>+R(E#9M5HSY95G^+|KAsAUb`%I=T7i|^kcoozfVtU4$3pc-);r@CV?yr~O{(2Fn zX2Eo*t+y`?jSwN4*BK)fcL8or&_$q$qTImTGrZ`t2&jFHFI;(WZ}6gjB19J{h&ojj zkv_xGFpJL`6qcrx5Q!SkeBfgxs)|~0Vpu*TwOpfuCZ0*A7ZXHMB-AhjrFwCeVk1Rz zDPjsELV@r*M;jwWN-5$uAUwi=@INQh{z7=T@zsP~_@ATBe|m+|{sIr1?qyNNpI+su zd~P|7*7IAP+;TSZRb+I!KfOYzYlQHGcXy#0$`^3XRX(l_JIyMxbwK&LRYzXo$ZIO{ zn!Q8}q-)iMzeg27Rsy0=bqb-cBhg_3Q2PwLG*upNx)$NIHVOa)!w6GcVCs`)bghDt)r)pv}L|xsiDH_OrEY$+c zG2&|pUzzJ;_iG}E2GkOJWR`e;MY)~Tjuu;a&e6ZNs34177ail`#Q}i{iKEIZVxDsm z!EwAEqX8{^Rcy2J%k<{rq!4v{F;)tH>X;<@L*KV2i5RIX6(xyAQmn(PrKsp@y=b*q zx7VU&Jz#;8x(h#fdo3&b{jF(zcl4gm-Tbg8y#zeK9{M=(dJhp}y@a%9^t27MGqqfc z4BQI;Q$kD6G~DD9^ae!XZI9-G2fevcp^0yYFr65z()OXDcn%SFX%*1 z*wZhlWCT?9r=DzwY8x`J9pVn~1*N8Xwv{eYr(VdZ2syQ_ZIpE5V;>J%(@XejZOt^S z;cyf!XL+s}tnv_kmZzCPn6uy=5k0%Jr1eIwXDOyP%;Z_hFTgm+J@+gX6~Hyk>J6Xc zEamhTb+p+gYwo6OGS5=>VsAf6?2n=2MsH!Su+lAWwwq@qx>({7K)!vT-DfGN519Pr zRwg*JV3Pm7+RP(CpB7!D4Si6u%P3iuINI13ZCJcS_Mo5o2)kS*&PpGxm4nE>RJKd! zDE~ABKSv2mt%xsJe5cZNz-Ww?Eo#gqbN< z6xRb-m=)!#{Z+>hh;clyo#QpU4rtT8{Y9jTMNR9gloaGu-}I4Lot<5iS9VyNTeRef z^lKtohLRewEW`xVZr5w#jA&ciF>!!Mlk^&E@j3e7gMsjVJI6WN4-(6S^eRaqUcrt> zgGDXL+S9{gZPS{f(y%7qrnTNxn$hiCyC-exZ)>2+SV@ni-=i^}-bjNN)eGc9Tk8v& zrVZ>#2}4lny@7bAHT54N>Xjl^F`^F;AGM~FK$vTKJv}IHlLECED(oJ8f&LQtzMW~W zNDTqe5YxvHrvvgO6=d3-P27`K4F%JFNVT#Jog6BhQ_!CD4q$QkgROiG+(x&x(rX*6uauUm({SW7 z0GI`BY3gt{0S+@_AQ11irJKXycD>uStN`DV_Xy+8txqZG;5nqhK*z~op>2N-OSrt zNB{O;Xft(r9UVI6CDCTgF!JWI7gHyoz1<5olOjfm+UB}4cSdJ#?+JQz%#&|eD^uYZ zkth%4-r3R~M773>M1j6GZmj4mxND8Y?Dxyo^vhUrOrTc)UYSn4A?n$T9w1rvnV#o3 zc%Gx%(#dfmR$c(T4j-uo(ekNwg*?ZLN;X4ZCCfA_dW3ESYDx}c9@!$(R8J#Zr z+l*F~EHM=Eo9gGdoh~vJ48E^V5%5^!eQDEF;qO>JO^lXA0>;Ogi22SC&t>sW1@fIG zCW=@KhyJu?mcXptjMy{XB3X!Fbib8}y_Q(&GFuNmHi9}?dhER{@g{HxDpGv5818)E z$bjj*0Gz2t)@{9D?>_uWyX<0oNyOlM=J@Nn%)Mb|?n6v9n z&oXg02HCuJMEo1@7DvS$VU2*Z7I2B8j*F^tz$G}}e|yz;WE~f~oZb^9o`j*U3bNQs z)c<6ufr=olwpSn>I4SJbNMO@0(dmoPe$~LST%qZAPntY&Ncs$_^SM;RG@B7r3@U4NQ27;-^%U~; zGpX5A;iUo}-8ECW8~M1FB!hh1%*Mo#F0DXGi^8et{m==Ls+i4Ma z{71`I{sgOBXxc%ah~YM)@g&O*W3lS?Cn7_XE2Kf6iUz{3(6Rbcu}yF;%|91+tuZh! zrxPja3(Oo5w)sMIgm#Uui%zuT3+PNN@Mjb0^cNy7=4_(Vddu2vWLyiTyb8iACY(nU zL@n1T;ei8lLRpv8W!HK`2k zr%apl5^cVx6=RrI0CE6mUO#tl-H`+i7ydX3&<0aY|7f{~1pk0+jn=imX zBP>&((2F2=1qAs?)aD{u1YsEh4AFsf{vvv7Jy2apqMH}7+=#FYRj*56Qy&CBCsF1l zVjEZAn!N!3SX(K5Gj_B>8?V6cN#qP8W)*9G0P|Uxb_* zfiUL9bS{ z>?#NlmLX8DfuI!#CbXisYiLx2We9dMK{5!I>I4Dw(>3TTB4wyLT?bWbQ0;6*Q?I*q z#-ogA1H{QzboV;Sh_Fn`Uf)0)3U5LizG+37-+%&P8Hy67NWTS&KU-1dZy_VXG8C)6 zMJDZ#NrhxO`7KI`una-{8z5*8g1BTFbOQtk%Mg6c1RX%oKAE21fDj1F5KJhB5V!9@ zh~de!t{5y3mZ8vYf<-5=n3GJ6Z-NEFG6Z{>pfd0p5M)|MV4Q z>-`&8*x8dmVN4p!5g1ZEvV|kClzQX_M_>x|i2rwpz}D%JjvRqq(<5^^0vo1B3ZK{% zI`y5X#P&*uJYqC#lOCz{JtD9`dSoa^U~KfrdXB)b=#j5D0wbbF>^~p^gP}*dwgvx` zAHW|LLWg898rDFMY}y6%5k{l?>yUelMpxG()qX?--CBA*q;LeuUu5DKLO6MqE|$}{L!0HGrc zbR75b;0P3L_YP)B`LMit) z);Gugfk~82mq@Z;T}D60^M~jtQ1)_i9bDJ%dXvYL+K|A)n#7(+wd{h1cIh zmOtkiRCx`mmr*J*iH@0c9Dq6lWwF#4>>Oy z-8@MyzCkEiPUyvVYzjlJrZ?!wh>&OMc^#-B`;$FV=GE3q)#Zwgj7WJLPc%5Py1M*C zYU6lXT|O*fdglOf8(y`g!s?u=ro4_LU8~Cej^j1u3Od8WS`fZ1#)*xyRqEBtVF8SME19$;MT*} zs7(_&N;_<(acYr2&1xbCW3NBA9#$;(fW-8#IYX!EWd9nO{?bHlDGpzA#5I*4N*>Q8 zSpIQ>X6Isks%dlCE^`cr-?q|&=JGkS#;CA`?CZa$P>6Qi*&$>^S)`OHHA{NpiflZmMhV45XHA zl$Rt2O4~^K8_T2*F4#QjMv`77`f6QtO9&((qr1rH_xs`%v!hr9Www;7S_M#Nr_r{S zsI9Zp4Awjo<0X>q#`Yl3dA1wdgXyQR(z%^NTgic;+ufFhrc4}Lw|;~8(nE{esaq>K z9F!AUp}M!zQUo-;n{1~;t>h2@idxB$6}(YqUK!&2c*SPBh2oZ|0jvM8DpVy|_SJrz z;VLW7#kNyYvfRwmSR_UX<|U&9IOc2hok{zWPixt()ie{b3bC*|s6_J!4uvmnfsL~?0%);G;#?Tp zK~ftzvi1eHlsqHd;Z|XjhK(II1l!-7gqPVNP8&H~b5Fvv)E$%!PNiU`<`s861566q zKt5*@#&IR;I6q3iVpUeRmFo#qQ-ij0Rmy5FE8;qiT(*^yUG=mJC@X9J_Zf7#3??i^ zuIk|dOi2c`{yXnhu0$( zjPU{{Vir|s@1AB*dtmIq)SgB2+RG^}39c~48<_xsq+TNf1RPTg&0VNC&9lP6{oLxz(u-vJ#3l)zVc-Y;R8)Hfgf1m)tlz=}re| z^G=dF>On+DDD_TiW(55JtnlV+m!@*p*=eCcE4(U)+Ob$zh*gakz|<@k4fm;?FKM&2 z6AI;nLiNm|xK7a7o@N5>A6%$idVi#>PSDw1#`%&>#yifJ1k)+wJ)aL6+t%wSmSPtbbe3yq(@ik<6;|I}lKLE9 z%28_d9I(Q!wh~Aw+r53I-Bi?7j-(@}6uUNg{N&WJV9&yHcil}|H}t(GoWulk4eX{Q z=a~~40E<>(ksARQdbfp^eQOJ#<=wEWyP!aU0`9^=uR{fjFCFhD`_h`zfc;(GZntsu z@q*EADk*RGTispu*M4&2#&xipx^2Tbl&0NfyX`L%7eEoGaU$tnW8q0-fzbYTOT;y_ zn-+GL>sY7HW6|m4X>7819=7{Z;d2qs1|gsa>IEACR%Jdl@8RCDmNBLRFyZs*!ya<1 zEquONeCoCVTVa3qkn5UG7#o(Jp!NgxEAwekPxr373mCgUFfGjVG^=v?K>EF>T*K9i z!+IfkMG$qEPi=a+Cttys0ATver(*51Gb0yAVj#r1YiGZPq(o^UC~&o6Tx<2goS z(CgMq335HNy(Ejj0ZRu=pmp@TPE9~wE#}kB3CIg|Zpc3oKvZ+*i2$Nf zb>Jojj-T&1IZ;lN?6?|Y-JW6`_NKhx@_y7}vRvbTIGe5SOr|(8C(D~9kGEut)%z00 zjwPZQ9cUq2Y4lV%&N>(1nwMxJ-UY&oQ{{AXaqlf^Jxz|Z=78XzUuoPlxvD@2N2s}@ za2n)*kEOdbDKp^G%mY=udxlG6E-vQKh8c3CeLgTde>1d}@aQ+rTgy;v*)I}b6A*mp(Pdpsulsg7*`%V8VkQ8W1 z+uKj+jZFC!t@@uX+1TEGO8J?(Y>zY1aEl>Z_Ma3s8^%1FDam`G97uy_%XLjH%AvKh zLAV5jU;as_XUopD=NwYAfLIE|YfmUHOHM4+n<{tw9y^$JtN)*V&4<;$;Obp z?}@7>A|TxvV@MvHjUoArQ5{*vyFMguGT!xbpQns>ocj!>+r~Q%e+I9fqbJ1y&_D{A zgX4i~upuCiNS{RIm&z3>We&GLKs46o<*9Fro}oA9KoQSS&K!(ScTI`7#<{-EQ1(jC zKq>^=&@*mh?)3DrspEz0XyM$KGM_$m z*brd!%>8tdg1OK#tL&Nz`s?7QbCG>4s>eB0^YKs=DhJ@HZeaFl&QNNOUgTLh;5F9M zm8g=A%@4Qx*;uF`Jz8WCr_S;W46Oz?Y$S@X2H9-%awQDbDI@0TY@5x~Tc_7Na3AdL zA_~)qa&2CLYPkNobDo@JUf9T?l6i1M;_qS7a?O`2&zGHN%U~|%LkX8d34ivb74zjd z?Pp(uX=BI;MmP^tG+%B)KdpkQ+?X#{r)CReFPtFCuZk`Fv;}gl(yp;;0a)dNRgOj{ z7s#<%4!Ry!8TV|iU>w82`AXWe2CS+rlznkrr~X2y$yw@U1XC8G)z8veBX)G5TvN?w z9+XFNp!XXlEAG!{$$ODpLoBL5KD@Pc{0plu4PFFm(k;MMC+sVqrPLCSU|Pet)`2b@ zdopL~Fqmj-gA6dcfb0pMrEW`PztxK|NBqh}Ien?K6tNh}H9FXpf;a5XQqqSwDxAI; zy$z|OVKkO-@-`s`9Vh24$FsDTllz6b9=p+!8t^V32u&pal_m!%+_W%4ur7Hj1)?aC>O<0Ondj~1oRH1cC<&LFx>o*|m zD}iWR#mJOSgqM$`OS6P)ynACA60ZVHN)=kY%uTJnX9RA4T8C93pSRt(roIgX0Wqfv zEpkT`17TkS#Cy){imH?kr}5ct+4WnF#A`wGQ5BlATy`Fv%%Ka6SO-Ln2pW_tJ1+$0 z$h7efoDJ)kE8DH_0{yCiE-mARTvXe7AW|Z*$(@c19k)R$QX=SnE`&DL^l~U^1;{pl zY*$s8TFewd6;nbi7SB+e*h3=#Xjld+xd$!SvjUp^FPiYwBN#!p9f#`gt-xiJf6=T7 zO0!a)joyLC8^LozB&EIMHeT#x#Ct%@h@{K!xQ#FsR|2sKh&hqee5G5897f~;u{e_U zt%U1?@a9T4`4d)wU^58*iKPCkJT# zR3nDa&|82=uWstq8EZjx9vli?JxskJ7yjWJ|)OBFL9qbFiew|y5U1!7&Ag)G} zc-IZl?Oh;t0&z2%X1XKJ0%6|;#P?>F^m8?Irrqn@eAU+Lk$4ci?|acSZoQj29cILC zB>pFwZmx%4@{h^HIV4=-At9bxZ;)%3s`HEu$Z-!6O^GpEb!~Ozxc_ap93O+m<8|a1 z7Hb?0HqRfvg=FrND0b}it9pOK^wqrNIJQw10qm}yJR~m?_3k;^AC`AXHp35>EK{iH z2K+u>hnz0L?mOl<fb6vO4Y^O)D=XpZI= z_>>$3$BvCvJn=py7W1IKbfLBq4lfgzgz2aOxo!mAaA6!M48gI~I`WuF;5YwA38@_jXx0L=r}NSsa@FY)%JuWKr;%_FKWD591U=^>*e^S)AO z|BtwCFtV0nmpS&@J$V$}=Ggm))v?O`q!-k#HcGC5e$v-8v9=PcO~U6Hoc!5W>c=Or z0x9D^m{(RBkKKoBwUtWvv_%O@i9m}}0ukiJDe?5iM!N?Mj>81d0N7J47Pdj`r0I|* zKot03N9@lyrGo98nNt8|kGK1Ir%jn$dPArmCDc)ZLEXs+xcKIoDlRj)6o_#BsuI4j zQAcTKUO{<5Qap--D?Qe$S1C3g#kq>FOE`;zl$QQRaSE%7SktR`L3=sTTd;FJ*W9ln zvYI)~Ts0(RRl7ADcNv-{D82%^)j2_l6;LIFm1!jdCth}JOHgp1aNbvrL9ZxLl9=?h zV_rR_xnwg0Dcv!=U0>-ae6XR^KzS%x`yrpvdnl@*QdJ8Yy+PV|!c^C@#?fn$ZaNDh=NUHPZ-%c@6Z^Uizg`sq*)u>W!fpy-~`Bd&?|| zao+gTm&E3RAM#(Vh}|& zSE2;M&drsTkes(N=}B|N-?|6*Ye7_@h2orl@1|ZYAm?5ne!w;37K(HJy_-H`#6BP% z;9Q|QqJAO}`+;~KM1vBQFztDeu`SI04Y%4^K4g56|G zQX;hj;5EUdv-B7?c?zYr^NKOmVmG}38f!jiCRL`sP$^Eo+Ie58vS#j<^$#d)WtI$k(@0e5GT|GMtorT*<%DN^!1; z?52vz5b`j%9to!A$x2oENHD$$vQiGBjAS>m!%X%e$o>hYo5`hmw3~ujLysIlln=4e z>$&o)r4^P9jP(dGRYLUh0j9ga+Tm0%?nf7caAr9HzPoQ5#aF(DSo!w2ypW!Qn~*60 z324N!99tEd*+wZRKXBqVwNXL@n*L-P<(Q0SqwuNr>a?k?qSz+s)ht=+Qqg*hH>cVv zi2`l2aSV=0hom5a_863+WQy)6ON!E8FLL-@7^0r-pw%d0=Y=-RO51_7dn2a+l% z-FpLZyLWPXWd)B`xD8a%5z<+CB6+mpUL-sBsvTXrDn+WtUU)@~;3&B*arRc?tos1& z6H6QMF82Z2ZRd9{Rqulu+YgE(HK}tSB}^b3*GGAT?DWBLdSAugegODCYMNeJLLKS@;7EguZ`zdzuv?ew0r*t)&X+N#%hfEJ5K}an+ z*-vR`uHCX2&Sv7J@kX)a(_iT<`oua0^@k~9+4fC3bb)$lDpmdwFjIuf0`V zd&c@9jjV@*xK9Qt{!%;geq9L+Z6{guUJN?R(Dc-asc%dw-I{4fNv~t9Xh#EIM^9=; zvk+*vM;K%PN_%{d>E|>hvPK9%R~8wD*!|le50KYAaO1@z;Q8AiKU4f+4D+${@g*hH zuO<-Af1zM?T$x_K!{U0z=sVD9)qWdE;TJ0GLRS#P1K;(eRj@G7eN~V5TJY9L8 zPiTCauKda2@d?Tg9B!GY@CQ!HPf{i!cx#d}8-YAoc?-e($$A<`ttrZ*XpdzOvzJ3q zjR#Vw=;bIqyzoDLU*kQDZEu5q9?0HPs(R0JxW+b_a<{SDRol~(lD8}Vp@UJcPw-$W zZ@Fs{a{B^gf#rM;j>u8!l&7?kmQn3ZFjC9GSv`Wo7LO#Sky=KpfU)KRV?RPCHz{E@ z`w=700Bi=sHb2><*kL^Ln!=D&%EL&~#fe8&JUN76eUEK;g0})XGr!zCa9she2anLP zJf*63&`iZ+6R*U6WZYH$2)DHD!O}-GAsIZHZidfiJ!<67V+8a6hz4%P;8e~8a|zj* z{D^WlD{WD<>%dyyK~{-JNxZK_X^AGKbDDqLShmY(0DHQpJa+ol@EeRfZkxZa_xWw=FPnWhE`xjw}gT4mnQ0Y{x)9aI1+%EW`_9KpU zyA&K7g9cvQ4FuF<-yY?%?V4WKyfK)1+vew3zgHP63Dj`8{mN=om1FaM1#>||I?0k` z+!?5quVjcV$7x&!zNhqQzA`|lS1^osq};Z+Jl^mSCJ`Ouab(oZyfrzD&U_U_GvaCV z;Zle03gsV0WnBYeMLd0TxYS*`LO~w_aUF=Y@znA|H$*lgz5(K3JneEv{0v0JZ-F=p zC1Z`SOd2-%^`2PgqNK-?({;N--5g+W19X?;X{N(XmI5F=ih;NX>2(XAazyd>xCuzP z1Pu6TO1lb-cGfswxat^BCyyxo1xZTeAoDiC}TgAVGTpBQvBo}K|D zkaP26N=unD;#2@qDOlx&e!SXnP9*&lOhgF2KS6U(;e0|ve%o{kv%URv^psLVi`!bZpX|rA86{k7 z*-GciZ09HJ`K=ITXY;&dOL3uwdEWlX3%ni&=0dgxqZf$lN z)ZAa#K|pQ{e$x%i8wNT!JZLhEEcdblZfM>!*iWgal^QYHE?3q(9o_G?@;7wERQ)&! zZ)oku4PuNV`|0dy*x>ivQt@r1{qzrm!*;uv@ixJJO85leA#PyaCfHBIK2h3Ih7V3= z)bhoD$3KCp^+Ff#vd8G+<|#~80Q~7)oOjLl>y0K^;z`r6x{&y(Qq5*GykzmC318w6 zYSyPpw0OA1vFlUC$3td*ZwGk=IllTA+*xZA%zraWDC#2CM>0$F50p)D9KWat9^m1H z#8{hxVsQ!GzocOCxrD+B5!xS8=R&2UdF#3f<8{Tk57>l$1Hz7D7*>zJOcC}r!ER5BZy