From 8dcbdaabe1a91f096b6dd9380bc091971665acef Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sat, 13 Jun 2020 23:51:50 +0100 Subject: [PATCH 1/5] SILT: SIM_JSON: update logging and report airspeed --- libraries/SITL/SIM_JSON.cpp | 93 ++++++++++++++++++++----------------- 1 file changed, 51 insertions(+), 42 deletions(-) diff --git a/libraries/SITL/SIM_JSON.cpp b/libraries/SITL/SIM_JSON.cpp index c37eb5b0532e9..1b454d2bfce01 100644 --- a/libraries/SITL/SIM_JSON.cpp +++ b/libraries/SITL/SIM_JSON.cpp @@ -232,6 +232,16 @@ void JSON::recv_fdm(const struct sitl_input &input) state.velocity[1], state.velocity[2]); + + // velocity relative to airmass in body frame + velocity_air_bf = dcm.transposed() * velocity_ef; + + // airspeed + airspeed = velocity_air_bf.length(); + + // airspeed as seen by a fwd pitot tube (limited to 120m/s) + airspeed_pitot = constrain_float(velocity_air_bf * Vector3f(1.0f, 0.0f, 0.0f), 0.0f, 120.0f); + position = Vector3f(state.position[0], state.position[1], state.position[2]); @@ -251,7 +261,7 @@ void JSON::recv_fdm(const struct sitl_input &input) } time_now_us += deltat * 1.0e6; - if (deltat > 0 && deltat < 0.1) { + if (is_positive(deltat) && deltat < 0.1) { // time in us to hz adjust_frame_time(1.0 / deltat); @@ -264,56 +274,55 @@ void JSON::recv_fdm(const struct sitl_input &input) #if 0 // @LoggerMessage: JSN1 // @Description: Log data received from JSON simulator -// @Field: TimeUS: Time since system startup -// @Field: TUS: Simulation's timestamp -// @Field: R: Simulation's roll -// @Field: P: Simulation's pitch -// @Field: Y: Simulation's yaw -// @Field: GX: Simulated gyroscope, X-axis -// @Field: GY: Simulated gyroscope, Y-axis -// @Field: GZ: Simulated gyroscope, Z-axis - AP::logger().Write("JSN1", "TimeUS,TUS,R,P,Y,GX,GY,GZ", - "QQffffff", +// @Field: TimeUS: Time since system startup (us) +// @Field: TStamp: Simulation's timestamp (s) +// @Field: R: Simulation's roll (rad) +// @Field: P: Simulation's pitch (rad) +// @Field: Y: Simulation's yaw (rad) +// @Field: GX: Simulated gyroscope, X-axis (rad/sec) +// @Field: GY: Simulated gyroscope, Y-axis (rad/sec) +// @Field: GZ: Simulated gyroscope, Z-axis (rad/sec) + AP::logger().Write("JSN1", "TimeUS,TStamp,R,P,Y,GX,GY,GZ", + "ssrrrEEE", + "F???????", + "Qfffffff", AP_HAL::micros64(), - state.timestamp, - degrees(state.pose.roll), - degrees(state.pose.pitch), - degrees(state.pose.yaw), - degrees(gyro.x), - degrees(gyro.y), - degrees(gyro.z)); + state.timestamp_s, + state.attitude[0], + state.attitude[1], + state.attitude[2], + gyro.x, + gyro.y, + gyro.z); - Vector3f velocity_bf = dcm.transposed() * velocity_ef; - position = home.get_distance_NED(location); + Vector3f accel_ef = dcm.transposed() * accel_body; // @LoggerMessage: JSN2 // @Description: Log data received from JSON simulator -// @Field: TimeUS: Time since system startup -// @Field: AX: simulation's acceleration, X-axis -// @Field: AY: simulation's acceleration, Y-axis -// @Field: AZ: simulation's acceleration, Z-axis -// @Field: VX: simulation's velocity, X-axis -// @Field: VY: simulation's velocity, Y-axis -// @Field: VZ: simulation's velocity, Z-axis -// @Field: PX: simulation's position, X-axis -// @Field: PY: simulation's position, Y-axis -// @Field: PZ: simulation's position, Z-axis -// @Field: Alt: simulation's gps altitude -// @Field: SD: simulation's earth-frame speed-down - AP::logger().Write("JSN2", "TimeUS,AX,AY,AZ,VX,VY,VZ,PX,PY,PZ,Alt,SD", - "Qfffffffffff", +// @Field: TimeUS: Time since system startup (us) +// @Field: VN: simulation's velocity, North-axis (m/s) +// @Field: VE: simulation's velocity, East-axis (m/s) +// @Field: VD: simulation's velocity, Down-axis (m/s) +// @Field: AX: simulation's acceleration, X-axis (m/s^2) +// @Field: AY: simulation's acceleration, Y-axis (m/s^2) +// @Field: AZ: simulation's acceleration, Z-axis (m/s^2) +// @Field: AN: simulation's acceleration, North (m/s^2) +// @Field: AE: simulation's acceleration, East (m/s^2) +// @Field: AD: simulation's acceleration, Down (m/s^2) + AP::logger().Write("JSN2", "TimeUS,VN,VE,VD,AX,AY,AZ,AN,AE,AD", + "snnnoooooo", + "F?????????", + "Qfffffffff", AP_HAL::micros64(), + velocity_ef.x, + velocity_ef.y, + velocity_ef.z, accel_body.x, accel_body.y, accel_body.z, - velocity_bf.x, - velocity_bf.y, - velocity_bf.z, - position.x, - position.y, - position.z, - state.gps.alt, - velocity_ef.z); + accel_ef.x, + accel_ef.y, + accel_ef.z); #endif } From e646711f37c78498da5e07cca7a9f3f0d6ca95b6 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sat, 13 Jun 2020 23:52:44 +0100 Subject: [PATCH 2/5] SITL: examples: add Simulink libary and functions --- .../SITL/examples/JSON/MATLAB/AP_Conector.slx | Bin 0 -> 32088 bytes .../SITL/examples/JSON/MATLAB/AP_receve.m | 92 ++++++++++++++++++ libraries/SITL/examples/JSON/MATLAB/AP_send.m | 27 +++++ 3 files changed, 119 insertions(+) create mode 100644 libraries/SITL/examples/JSON/MATLAB/AP_Conector.slx create mode 100644 libraries/SITL/examples/JSON/MATLAB/AP_receve.m create mode 100644 libraries/SITL/examples/JSON/MATLAB/AP_send.m diff --git a/libraries/SITL/examples/JSON/MATLAB/AP_Conector.slx b/libraries/SITL/examples/JSON/MATLAB/AP_Conector.slx new file mode 100644 index 0000000000000000000000000000000000000000..ff05f50cbf72938aaf645b7d880a019892d88ef8 GIT binary patch literal 32088 zcmaI6Q;?=nx2^f5ZM%|{c2?T9ZQHhO+jeH9ZQHhO>(t&I-F^OjBF@cw@!pN~j1_au zIi{Q>2q-E50DuHwx^Bs}FS>Ya0s#Pjp#T7se}6RvZEc*4ZJczK-0h4VwQ1d~t%g#x zZ5QZKLw+QZG#A;dfC(3!GBn5tr3(uLwPbP}6V#qky|RptRvhP3`szUx#Hru(?44<6TO251J^C;65w^?cQF9b`+C4{D$!4t zQgY`S;teuRH8ETpf7E>njGq}pF^bWb2L|1-pZNQEUJ^d+Mp)YD;rvgy?3STZvuWR` zo@d^04N^hM+TT()ZD>LvP9>%@51Gh!Aqk}QLrvMqJ$kjM@V1f_@0~vq`uK zu3}Mm$a0J$+QmNP*N^ki6&k@eZDm5(l~d;t!`b|E`h4zX!Y|in7Zx>WTkwcU)WmeK zBl#ngud*P7E=0rZEhQ;x;8ZhhcSSX$IB@`?g|#*(4|BV^d-kNK@qM8xa4?FRxsinj$7|G1^pzWzSol~*n5zd~0=D8nj(adeux3}EJ z8@e@Xu5$ljhTr?P0E2&KFaQGpVE&mw*TLAzk&gDizQv33vVru75Vy4g?>x}0m@I~# z>13Yt3>>_@)th<#%|%z6&sQ|qcy$J=UO@-nFEFZUH1Gw`JaRZSMiTqmdptM36NvO-q2uau~c>t6O?BYtRWOTi) z;%RfZsvul*WZ@R27A7%PCN*OUbqvn>_+BdHD*h8QMWR^&aP+dT^5CXP?Ju>1AHXA5 zh8%*0B83Vq`yuw=m~rc>vR2AtWtMlUAgh<(G2f8R*?f=`)cZ!Zko}^e^YI&>)ELdo z&TP%0in~zuyK<3v>|*vQ6I8N((_vK`)cdLYQ%>vZ)8->9dr% z*WC4{*~DCwNVbe}R#sP~%YGagR=zuzTGEuO2i%2M@b)R;&J<+sg&@7#9EBy+%@1mG ze`u6qto!=Aq8%6j!1;&5+Sp0oNZ(1H&d}Du zSkA%L&e*}p+}QEI?q{^ZoJ=4+>KEF)D|v8u4NywiTB0QSkeOHIQ4EU!p*7yY4Gq2B zIlhFL!&;UsWA;9Kc3lP)qEOj z(h78Qg$*AT(0aXyg5oxbnXQx{!?G6w+Cq-9nB=vEGJ|1lMK9a|K@|Y^)hCFGp4v2I zZ+q6-MAYf;JpWt@oNKGJ7(bb2UVgG(H+?uERPa>+Z zCsafKNQnNUg7?1@v3C7GnHa}1*bLCa3fB^u)gHM~LaVR+Ehe9T1XKwP29PQsE){iq zb34^-#Dng9ivJ16GzaMybcq~g`%lQok73#<}a&Tl4z-&F&z#Azfi$^gY!?&D4^Zq zw1%7`NWRdtG_hf30X~N}g(S&}x!jzVFE4d*RL6{^tBOOUq?p?Gj$BWV2VcF+q{RY{ zbwy#^U;P4OK6QJ?3d1c~DwEE`0)J$wxw9>_T?J5C_5J!m7SB@d+w4*U)cUgbg7(EL zRJgu%Z_o~8LAN&LFfe(43cv?gQngsdM`bkc*w!bEp9khF52Beb%Qy$tpVyd9d+U*a zL{?r?MWR(c3o>_g-)`alQ@`(W#!CA?-L(JolmFlJD;QfD>pL2Y+nCt?*9kbsNFoH# zBL>}kMkIUYql(c}91Tyw+}V?$sStKbMGoiEC5v{tZKT_pxVqn8Yq;glKh2IbpUC0V z(S`iIzNz=-C?WZaqJM`+XqTfX_tL`e?7;lM+{YiYWGojQ5+yG}YP4Fg2pJ?b6@5IB zy!jXm){7x{nLU~xbHc=16xC5_O=O`%dOWqM-K0-?F0h2~5W0I^`>w!VAa(~$4XT)f zJj_s5R%iCufa0?&-~M7wKR4Cb`f+oD@SpmDjx+$o7yv*a765?$zw380bGA0H(KolE zwX-qZatq~LvVG;HU>d`Rf}^5Z>*qH~C;T9%BJr$+RyST4Lr?B9HBlc)=@S17pTHe+ z*X8Z=GjQXnt-IokyK?7~`|_~)a^VyGTS-tlJ}J!~69OVsNnQM!p|d5o2l8&u)n7-S zvJ;7&{EYKp7f~j=$8I4-n#9iT)H&(MsF6EirF09gEJbEE^J9@BEej{Z;ZwE;2D@7~ zU;nK}8h=T8^b6nnWok&=L-Xes!p4q#{-Ak9?F zUY)+IJkziN0h^&^)1zWh@?ZG6@SU7;Wo3P+mDKMTSvviPCFXM4tvHw+`Rw5~hGaYW zn7E|MmW6LOuc%F0GizbW&>nmrsB%Ra<3`z_{4S>m+?O}^D4^sT3bhX1G|UG;%`p~`SWlKroU2H zS}JyNTr!rsq;&vvZGmu%l5WEsG;_mZ!p+C2EZk0yNPQ$3`a4;o)?Es`NE;3t`9V#j1;+UnSd6ZgiA-s@XAs`$RbFObJ=nn|^#HMIlpoT%N3ky_D zj*X3ZKM&`2RLR2DQtv@@rgLvq_FMJ%L@OTrWu#wDEVbJs3p}?9tWBHo4@?mwyMN$Z z=JP6utAuS)H>xhsLGejwvwQdiq2kY0P8aIT>1*%71{NW!8F0Gk)<8uHYpXt6n&G0u zIoaLQH`b4LLHAraC%~2ZMM{dsUWRN-k*#K^zNMEmAX^wAk|3|uvyCF)Lq$SOEl4FP z9mYz*@h+NgZ!PB5I%JlA=h-{3m^8QjPQnrL6hGypX*>Rv>`zAmVE-WB!+6bg)B&w_ z8DdI%O5Hd_O2S07BfdCI@K~QW24-Vp&wVPEnAaZO(ZuoH-6Q1S;h82szs1Ht*x5TA zO%Bn#@m#9fA?D`h_*c(Ff^_e5d56W_SUMz#gw85MK& z<^~4`!&!u|RD(i59$U><7Zp1~9U6zJbagxto!-`RpHCl-fD!*)7HUh=kqgg8$G~Ws zFv%9g-#mVEYh&hBivdAvt`O(4F^)WXhK3&B-`|EiS*bS4XIfZpmSsgHChiW6m8!Qw z!O;p_M-h)>W;f;WWN0#KYO5F1$i!K)xjcJ=-mi#>ad}+oZw|&K_@0&LNR3oOQj8>l zfy7cOiiw>~O)Tp3nPlan{2JJz3<+nF&QBv!L!)U)Nw=^u4w-v(x0Xbx%*@s!p&Ow9 zwX}?4rJJxXteer^-bl2l4_^+0m6C2ajhz*Jm*{V#lzjFo>6AWxuGkna9+l6@felW& zZC++(ROk*%g^s2pCoBS4HgVwPS9qxWq(9HJpQ5y>~73 zG8?jRtk*zJofC?STr_Xn!ys83+ zyOm`DjA4!DX5tiX+e}q;^K)(P1=Gv~wweza8=L-|oE%?t^qk~VQsNE|4-IL_3fFZ` z4%{J3-}-#@SM1muAfnW6n&N5K-;k?Cca9DrB@!NjW1hnkITxzy^MVsIeWF5RDwo~< zuqBKtV%@}fICB_FHq$R0?ibVMNZn;~Mc_@GL6{7S$m2_l+`F?qMdHro@ zSm5=A=i=cpfi%Ispo;AD`2neOx6<0Y!imv9GLJ+@N59RhbG?yxY-Q-ZD0&(#$h*nx z7#ZPletN2WsyJ0e%fqrXE9mFU%F4wD)s5G=m8WdDeEUj4FW3Leuo1TFkuXCa$NRxQbsm+*Y@z57f{yoq_R zf)MpKF!1-cc6(zZbDOmF-b}786&00Wb+IY;Br^V4*AYZZWqCn=f0!rr^=4aOevJS5 z-m3Je30llV%`k21O+|yM)S+@C9^_ZDO!qh#}lXcSF-4iJhsWBSr zVvTN=WeeIgQ-gk09Uj3h^)SLKvpm${EZA53lv(P>(gmf9N}-vPkD;NVXdb!>1f1`} zSX04(D3{{J_RG-pOpD44nt0p+sWbBmE^es6kceo{*lu1yakOxLO7ral^aLP>lap3G zq9UkyAuzA@qu99llA~h4IOO7C3FpBQq)F< zrUuXQvQ3{2bIzDFru8jPd}@!AhX=GOXHNEee|1(?RtM}S)sn?*CouAA{r5vf|G4)4 z*KhjCYaAwA{qKQ4FjGch=o5dZ4z744G&GneEg)J$OZbSww+O4f0wd^se_)vKABvEq z60-Arm%p%5BhFtieekCKj4z&_F%RSBW|3D`UZ7JP2tikzOh*a^tGL3#!jjok*UAgg ze6OO$zHn3F!2w)op4gq*?e+p7%#6&`R&5g-h}S!RgOxBj=O{5VGuYeHf zG}&NzX*7CadAPTy9r|Pb`R3Pr!hEYAeXJJlmt&&lOjHraWqZS z{FKR{nZQ*AS8Hi*5!~rvy_t#A&8!jr`YhMCuz0`g=DbPlbhE=@%d0edMdtvTc+pOD z`B71S-Y@o0b%u|P0cSiEH!?Qf@brXvvB1VbVzt@Cd``SyuRp)M1cgqbz{U%rQptgY z^21T<=y{Icp(Y^_GE^QE{`5!)`&!xGubiBmtYe=^rYl>?{%UMN-ER1WIN2*Nmn~>k zRgJaHE+(4hd^JLB^0*F!4B@U}b?6 zv@Vv|hnCvf$~LzLt3gSbc9^B}f>2%_EVd!RZS#aT=a7!wH83!sO=i>lvEg-I@c|m6 z*jR^RVPVm37fhYtLqeEp~Bfo(7RbCd9AQVPDQ0l@(UBq`t*}i zL61!fliVwQ)NSLlN`;zb^K6w~J{Ycjc5cg?q3sz%)5=UrDr#SdGF4tW3Xe#|^soDa zK51GEoo=_%ukZ>)%)nwPD9X3fK|Dz`=?X`R!##>sN!%9ei*usA11f`^3?{LDQSvrA zX14N^?gqW>!w7^+s2tnb*#$+9_arbeiRy7%ql+D_236S$4QK9-y6uv}xVFZ{yB-MU zPLVYQbL5;CKY+Y^KoXLgFKR@}akkgjlC#0-aU5kezc$#g}M&*E*m zuc>i?=*W-nVuSsn&K%v{aq;`mLJRRM5$7MuRYs$HoI|pWlkVrJ;)Zh!SQXZR2Ss>X zyG%ba)z8qB4~CFZah_LatFWY6(vaxY_Sm zC$L|Qq$p3o%S1H=iMw1s%L2Kt%!B)muWP)PcaQfJ*1r<{N9uh|^=w+<#-Vg|dv2a< z!-H;2%ZG^dJIbGD#_I)5z8Xd%i7+qC{PPQnNpWCVFjIF6LJI3z*(mK>n&RLeGJkpQ zT95nZ5<@qA<9D(++j0{L$+ZR5;ALE+ho zn^k6`hw)Ps>BuDQAR-sQzY@YBNVk4m284Y{MM?)RO#d}eR76>b(4UyV=2lpd#nz3j zinn}W0QN>ku(G}Yoy_DBhfLTtYh@%T)JBAleKQ4?$a5>KK~ zfJ3BsG&nT%*H7Npo!HZ8J~KBdTc=R6wsJM5#{{194AzW^i8+z4FBYz8sDyEKFWSwp zL7F#UQ#GxaW@;XU#Y@as*R+^pS>DyuOoVQf;O9pI=JIs$n4e!JJ2GPX!ht3YbKs1| za`AM2@{}n?NIRX7LMG^AUs+o6Mr|zV9b2GrkX&@{p2b3#=B-Q{DdT|thN%g<&S581 z`yS=+>~n!|eZgssc}C=}^0Kc9Zedvcm;!Nf1(lLAv2IUs?dp|j7U0*#WOdLd7}7x} zvSkj4Bz2I{(F<`Py7=pxUi5Xt8Bwy8dE6pETuiYRtM#A?7Mfsot3-BWtx z?l}PYTxWGwiK@uCsW%*cV+49dtRn7uPZ(+B7p1|Rr|CIIX`GzSD6%^XO53ceu!-TU zv(sVByw9*kLPU-TZOvF=0|h4`VSdCq)J`VZvy*UP;qP(>2q3(!ST=V{{|@M|#jpsu zZXki`2}(PHtd@2)$oRwFcPj85X3eGEaw8*{h8b83g^1S>w@AiZraaJ;2TeSloe$kLnM^#+?O?|`j-AG>a zXRTquyU-$(RXDmdT$`K+=tMaAv6|D;x76~fhrK?)DpSw{M20%a;<1Hs>mfqmfyCwc znMXgiuc7=x(LJu3N}69B%CQ}Q53FSs(+3BlXO5Ff*5M*xI->d;Xr#mKf0-U7LV8epKgFNy9T);VT&k zv(9GMZ|dsmOQSz(h_p^IUl10z-hB<-bxS*(J9<^WUI`HvXjJ~k>%!AE zxm`#v=9QhJsOSj70y4xT;_nz^TL)27E>#(qKapkR+G}pCMhCf6w44)P=|5-?ll@UA z^UjoS?5)s`fqdH9c)3aWM;|zy4;sKT=`Fg|_S)7kL|x#7vsJ9>lbihpC>(x_f}*z{ zc%A^|=e|q)PoEJ8-OaCfUca@QU1@r(1{9Z@;+?UI@av|Oa3`%<&0p~3oZBz^rc)=O zqSKOHHB`T!qks3;#(*!Rj7Zq{pJ?bbCwSlfVrERhyM-aM&g)zG0I9tb%k4X{>h>*_?J#HrXMYB*ehwz)8treEY_&c$)FhF5Jg&ulP z@O$k%422SsvFoPYIQIB@}Y;C=MKjMS2?uYKM}1+Eh+R{w}V z&NwC%<_#w-5l;fQ`yCG&Sz|lp_}H(WftznNL9)99QF2c>xa!;*FGN}>CAtXN#g?1@ zm2}`?`;fi$jhhL$O$LrfPMuw;lWO2)T&m`wFPq-CDBM&K-e}ju=rFc)&6rC_NT|0$ zp%mf)ye!LmrIIzxDWt1lenH)ZYC1lvcsgrHvn1sx>y+2XN4C_3L!L&m5{p$QL8!(2 z8op~v8oc$BQbh?<(J~Qy|3N`3I!f%LyYU&4dB^*%(t}8CD%&fUAFE6svw3{QbK}{Rz#>P zhDDL2i`Q>Gk7uxltZKgObSmT$OyRJZXAXK`6@>HWxH(5nam9k;rQ->YjFPNH06uEW zJ%?lS?`oHxiS<;CP+J=KFo_eocjYFcso0b7%ftBlP6G9_G6pxK~DD{{0>J0*a18y&sGpD=_U?+zPpJ9VkCL+9$` z7&h_g!4fkmRRG6G%B&QTPq~*f#=Z0YL=jUTLN-y%Fx3bsN2o}O8>1gQ?+Bo<9 z=YNdVSu4=&QvXE?Ef4?z$-l9>qq()SmAQ>2-TxE58d%vHS{j+_n>y%Q|5uvu-(hUm zlC|UjJtAPYN8x^}xO*$J=mj)JaXpx zq`J+I{UpZ(c1(Ue>fVq^&}<|guJ$Ml0U2R%FS;0nw#sL{Ozy%;X8lx^bmK#r)bzj9 z9*DFcxpf9_QeKsLC?&xK?m)WK`P8}jnF^u>dqq;^$=Ta_&>VU$2!9wpy?e9m`uz|# z^gBaVREZkIbjI}6QQ^a8y;+u(n_#Eeaq0?@1yuv7?(w4p&%MZY?JYJ&O zpOlqqTitAlftdH;ZrLBZSINpYh2*rg{+f$E#1AfEc=YMgnN(N$d0bhWDJgUt5}L*y%TuH)hZ!*}diFl{{ z;d^4zJsfS=W!$FOe_49a-c40@J~JnLo9+8>#s2k0%>HzBa%vzs>Odyf82N`pv)oibt6T#e zb}9g;VyFO)9dIH>mvX|-XTvpxmqnhhZuR`BzqjE_;_4HxmjM2l*U`KgZ0<4p8IrvUX*W%9i&>~ z_Ou_J>Ypo#Vo9?8v>Yu3p`l->Dmn>rUYobT9%-Va=ZPcw(;x_(s^CS=VMr?(RvkAp zDGwan6q(6HJYDh`z9Lg;r%>HVq{yHSAk_N{p|0wgBDLYkfYYZ{Q*6LfKW5ATu>e z$kyc1<7DtpF4(_zV$RpCLFBex@xI?*BkiS*F4P*PgOjw<39y5}<(YJBnJ`)q&eEC1 zIHII2Z3%)`E`3Q(1NKATnhUF6vWcM@+Xm4CtEDXna%Rt7>5OB8;LZ+;S~3Ty|W zz&kt?oz(cp5~MQ1CG<6Z*(~#Mizp%nd9n!?EGSKx(nQjhYhtm1p1psF3@=2|2iuTI z%|j4+BkEBzP28?b(0wW@?KhlDB*H0bH+QW}k;xYS#x^fYyqdl?V#QKH!#K8%_q`)P zR}<~AOY4OHZoo8t8wVl7woKnj_%@D!O(gS-o-l4-mzF|N-J?_Vhd03n8;&Y~?Yk$( zOtpyu?o?X6U|vTSMrh*;eEstJJ&XC|bF!a4KP1Ie>$#6PBWd!rNaii9XrPDj!2)Zyb1YYfxjwesiq#*Av&!8Z; zLGV~{oFtVuEQDm@0n}Ym#N(jTGVfWyRq;$4xBH4?VxutGx@}}*bacK5} z>eoT;F32&_&p9`;D`eVuXZFxM+fLumCa3LuXw)V|0a4tp&xM)#mdm5T4WNc7rGBB` zy48G+AKngjMXQ;9Z9j`n*GTsC6`i--fs)Jan@xkoPUm)-ApoO7ppv8_MU3_v!PzQI zB&7_-?#(fR0OP7E&{tSEx*#gOwAZ}ovm2E@LEYWmCR@^wB=;sPKs$Dy8A9Myu`aI# zJS)^dMF|HBD0$h*t)rAvf-PuLZym3dnylzc8Ee;tHk{)c{BD! zy@6d`|3gF4C(OuW6!~5xR%>4 zK`sqbsys3KE5&tffAapfwiX9!Op&H~1U=N|9mS()hMXVh-(0Vh{lCLWWr$LW+#oo1 z3UF9v0&~FHH|?b3&(b4-kmp;QdQ)$wK<*cmn9gjg*RjNzn-@n?Ss|uS?zP59|KM`P z`ePg3SojEWDg^_7ve4GcN_40Pf2|oj)IbqiA-Oxdc{@Y@kX9vouc~}Cr#IVvx=*#j z6zFN$`lrz}<$W~NsuxfCewtDre5~HdNn*h$EV{SPyYZYE#-)s`#MqiC&wP2SXi}^k z9z45R!7H7Gtd1|Fm9ddif(4kTg~v!Tb@?*cNB#3xhd_4ismq|T`c?D>3K6q;1U6Cd za}}lgbvk2$ir6=IeWzjt_KABn%joB8g@f*t7uaDGzJQkz3A!LLq;rZ#CM!V+6T%gz z!lkenlD^vX87FugU1PcL73doVnx;B;0rvO3e@noyEu^fZNVma_|wdB>T zDAy7D$W?R1zWh59Hk`wHc$!|s_6}N!k-vO0?)Lj2nQjlCj^^urTM@iNZ2e^MoNZcH z7tE`4qO0ku>rJ%!=ja|*DEqHWN7yQRK|gagU=0@? zzkU$^+Ku*VJNBm5_lIGHm3@US8C=w<=clpbM#?|s9jTFHlZi*aKzS&ob?E}MN773| zu)ry-CNFPTzXQ^PxKT=OX!x;g4||}ots;UTcoOzl_1lLGx-GeCY$S%Vvv@hyFX+*q{ILf*I3^ z>6!!u0Gts4fPYIL|63{lACJ;#HBH-nHdLRRTE2Lf?Giq^hDy8)q?QUXIYjY^?&{4$ z5;Zm#BTm%gm7Ds+zxjvrEr{KYKVH-J;63nA7nl5$l&^scJ=g4byZ(?Au>@ICqB}nh zK5eRj!I1t_ZX`wm%mSRX#z-#}3s{q9nI!jSId>}+4^qf(c3gi$?K(*lK(P-S<*r(9 zl0x^jy>E6lcVOEqWfg*Hf6@XDV$vX8hB75jlM-3M2YvyHy%>m~{|H3 z{xG47QzFFz9g^ipYgGZ`grP1Y61rV1fW~)SY+rfTu5=92GDIeX*ik4R4FyqNuo|M* zBBBYW){P|hOt-qbXnCDJ(h{e!&wHnXss5S@&7w#y6;I%}_Wt>PzJ9KG zF^$I41N-2;e5{pCG5NO$3s~{p`DAP0IQ?^INe@RsR`e$v|9z;pl?`2LRMx5-6rLSp zJ!i?o$-XR(mGjVW91@*;G8{`~k98DM@Gtm>=A8{9%A;SU$N_jevVvh>7<=%P7#BGe zg#xmnyI|~aRvo)LhzgzZvbNBRd@W(2Q2LAHbc{2)w73*eslqYViS;O4{ASV()vA7L zsl@0VdVscPj1JqJk;Ry`l5@(Njt!oBqZwfGa1j_-3yV7vzxLGJnAr)^w<>se`P7D~&Celvp$v{=5AGj=i#MOe zN-hC>1UHp{8TET`2P}7Ng~3Ovhbi%jW`Wqh&W{Lom9 zI^o=$@-S$bcI-;vRKh`#vR|O;eC&Od-`;YYdv)V zz8NpX1%cK&IoPhydfk6{82KBwf-5Ps{k+8wyu_s;XDTdp0-EOvL0JNeOTI}Llh&Mv z?V)OMlSxlW5=m@RzwSdeVZV9dKvzo9^MCjC8>24WmQ>+gGA=-WVA{n{l?%{m+&XHh zsW)hJXx!{kagjd{kwRQ*w!=k>Ik`4~@g#{?p3^_xUd{*7>4<;jQO)9nrvh!(S*4<9 zzF)gUFfjO_PBjGgZpW0M+)dX{@3kovMz@8{6{2sE1-?ZSk?Kn*xat9ta(CB{Sqy|9Oul-f&w;@K<$j^^ra@^(7Zf=+6$*fe16aN&IML;x) zE;RBG!-6Xt-Y&bcn)Z}?dtS3%V!e%#5S-@^#m67g}7ew z{m*WOyHT3jQD6%>UQE(f?OhKE-WmdoUWm^FRfvZzmSu?r!30gU))vmvV)5 zM52j!ls*9NKS!piP%GZtEN)Tt`CeIJqfjvDGdgyJ4*3_qqk>@RspkB+w1>;s+;%{j z(CFLo=kjU8C-$UXN~rs@O*c7GmEgmd{b!&we-gt0>+b#&p=-NzBUIO2>$!W`>}I>$ z=i|L<2dAWp+(vEK_ga*wQX!tV+lKxl40?1SC!`e>%u~#rQQ1Kob2IlNylOY~>!IiC zYa#QD5S-3{beVK=&DZezk6eVcCtFAe*0>doV@@jlp;t%9j+eeWF!3|3@IR+d@%|X8 zG;BnD&zvH=EFf&ClPLb$v|ELJ%9?unv-&t)em`CLY&>L95M?7+PjDb{jO= z<8=z$R$2p5W&QM|c#t1M%irByHg+>7y$3j4TbJ*~Tc)m(MFqs^39M zfUO$T*X8hQQGi`W*9C(pNb3B2QYixe?p21b%AB8leK5!LHLmwUq|Uu{AVpErF5g5( ztX|EK_1|b+zXjhe3*gVtU`wK6SNcni9n}#KODcv;K7}l1qTdN_8%JA=d_;MXyEB?a zY84%7iZt&uMu3WPr#9{^J^Zh3I}E4xlhtF}CD9#f(WZ)VtEkj~V55m`_IYGO=S1C` zF+b%T!;Y$0D7?(ns>{28$Ql#cc`B0HEoc%8E%({u5$~EQPpgfcL>yt96(7xqM21WG&2?A1P3voRv1G;hJ-kSVrT~Ml=IBuyr~@(D zmyA-WqZM`@N>)?gYJ%3IV@djki>_t(kHHAEcXhU}1y&(IKeyAp=Wd%ZS+LgJfJ9%A zQmvgnyV_{&LHZ?RIH2P}Vdqw66&HGG0}+2!d#zPc7ivf1!r|AIFDuJF!o<3Rn)xyR zT!!F9N+pTSl%uwCLYUT-db4%l;Yg<7UQTk5_cy0rAa=v;$oGM`b&wUN(V4e(%NGX( z0vp3_fN&cEp-QHC!cxMEz>V}bDHW3iNc#gvxypVtY=pK)k?CO03R}jtmSDIPR(w$4MBnr`yjTxG8D%D`pyi>vLqo>cfJ_RElWMQBz}Oq+TEnTY?uzv$m# zJOeJVt228&gqM#_!PJ!V)|Rz&A{U1kM8=u-Eas@}yR@J-Y9@EtoEpYg{LX?z1WW!< z3k!52zwH|%eB0&{`EWi9=HU$pjt}yViZxcR=^uLNEjitC9GY9eX`5pPm0c-!8tlSo zi={iHU zvo?fw)u^RgRAn*K9q!q1HGUH4FoUv$kl>~4`&6w!_JD;rGE}zA>=5ljfRA7sXW+~V zP_-OL1eD)54`vXtX1xl%z}71|%Y>kFn$|MmU`#q?NT~?v?I7HCk@?}7yDL$r^pQpdVG z^zDyW&JyQr0!69}5)FjIN&Xf1Km2)lWzqhMQZ>)ecypdDAv}?%K1WsfB zAOMpKMO{1dm@-PgpzDdtB}77t0&-$6wB)D12g2IX--8ZtE?6bvcESGog*;nnw`F>!*RKz1&{ z87AAQH!vf?PE}Jp6)O2+UKxOe*LYb?3R>hCFMyI$nok`{^W>Ikjgo&$u@}MN$~LO) z!dH5)EQ~QR$o8dr$AO79BnMe|=$==Di!2M{A9~QihqsmS?Zecu?p_BxX_X=dY*wS- zv2H|lsl};~$JYsK=5k(MOZnv1=@zd`=DhzA2*Q1UlO;?V_)%jX=W)v}0jk>R7O^rgW_#{km`N6M+ux{^=?=s;07R+lmZt2n4{M)I8@^YmDby!r#RyaOc#<5? zVsU3p5U71&X8bxtKm&99$tXLY#83vB**rcChyYHMLHa~itQ}$K?^)W(nJU#o18a5E zqA;I3NgE4M4m{d~SLIqZPQx|%OAe~VW1c|-s`U|C=w&}}|Lavj{|}$Cd(~Q3pS=~o zETiFDLg*v|h)vHf%q;s3-}`HkT8N4=q)#1y^Vv%(>kD*HMLOiRn<*Kj^U6)ae|~r# z1&P7(2~J6y2H6m?kO;RLs+5l@cz<49I9~k6A~mSaDxw;16O*eDgU;RXf*+ zOHZDK>#Ro-%wM~kq(NB^^(+NLt0{&hp0_XYSeA4YtBvU+vrdFq8)UKqH&LDNHDtq` zaKR)9g)*>lYW>~|tz`3(mqzhMSnwQTSZM#(8=4gwwq-!e#KFHlbQe#QUVn&K)+d|} zO!F9-+2&Gx8nSm$9JBqBO&KdY#S~;%_h76O^C&(7BupKni>@%-wS|S+gfq^zpgLE8 zMMit&(LktfIfU^^LD!F z3LG$bLmINSp*m>U9eC^}XFRa?03wA(p@7FJvMVMHWza8N+wmCTiE#KtGo7NWkxueo z0Kq7S$Tj`}XqT#5y`Z9b*ofWrwx=t~=}_vS^>awCmLMFQeGGd_4t*zjB;nz4x1%jZ zYI{vmjg57B_8BJx!1;qUkfUx8(p47*srsC*UX9UVO3();#`WbBr$S$j$23j zEfyH-9wq_3Dxz%Fg?EVhWTfsmd6K4|EfRVF>yW#)FtF!>tWy?P1;l2vOzu%7KeQ>W za2h;LRv;y%YWw6G@;j^+TMZcT1MtAc5=^leFi!N=90nes$PNWC>D5GcS#NVdF+F~C*csTfR8N8 z3q}uBaKV-RG2#!D%GQ3ND{ho|kT=tdgq%~ZVrB30ARRQ|+hF|Z6>x%v9RUtLdbR+S zi{E$E=0ym*?xh|gB}WJD62O*^m{6F2;QQ3~lMeZEy%I4j@D`iFc8Qgjh6CM+C4Orkadow*N@d zuOWeC2Re{KRZ1W|y~ySJ**b?v+M0E*EV;&G4sjXmoes2$hsHlb2`}8050Z;B)$5Ia zr`QnD(^b5EQl;J*(&wKDb8BbgVn>h=yyAC{yMpS=ky}f>2wa{d@G}kQ32P;xW)YZ1 zlI^{qBA&m_>q)CF#L4G_-_K@&$^v92*XJ^K7k(#lsMsxGhR)dyJHE2t&G`4WAgpG~ zIBWVok|{@hAs|S5rZ)=}av|4vK-J*K?gPQvn-+Zhdau|Li&YfE`U%n1vtLQ~D5QDzQpdX^>7+_>oY(S_(6Xnp+09R^a>6cZOJ~?N}CNM{+a`BH-JG+d|6-a@V z#S}BI{Sm!%UV5D1n@nyN&9|XWmEDLI5zpG#3_4LfYmeOG?l+<*K%l)vhs+?{Q*ySR z%%rSDX$lTce?Lj;X@cI#pxMjoMXBXH&?Dc%c;P#G&lz>bsWAMO>^{!>zE|_}a;{hN zOkSj*G%m*(qidcbz}2p@1`hX%qpiQ%|Fi6xvNbh4_2&he8H|A<`oipFA^j=Pt7eor z@Jyy&KeYa~GB`HB7FWwqa_>eHXBRpgHNJ}6NV@%C8vGi@Wq^WLD=`6p(FetLLW#mI zlKiJNy&FA8?j4n>vGfw&DtzAa!o(JYar~gMzpB9@;7qDXS_yWRlpRGSF5}6m^2~WW z1z+wG(*c+$S9^#`G?OMqxx(o*Xf`#e{AeCXIdxD2*$4uHMg5j<6$tY6nP8JP)7nnq zetm}u{e>tNZ6pLcWt(?bx5_Qooo8Gs7pzs#PHQ@|tBkLvGK(=PxclQ)8MS2ftldWt zA_}V)3qo4-$a#zCr|>Eo##+L;MKSPjw#vwgwuK#J#-pE!8Rss1_oD^I=ku-Q<$xLgMWNT9mM=fV~s`a~xdG`~%(9;wLrV7_F5!CJR^>KvzwJJT1W zx~ufo7h35R+upWs#-{vh_oAHT{TwDL&+b~D=U{Z6A7fXF8!R)@AjVcPE9Pl)jaes& z2gmVFYqFBsYM!EZpKxhTbCrAAqu=&ZpZN79(Jn6jH*RJ45YuSHs$U4)50ZSg;rc0zufi-f1eLSY>WZR84!u z=%$nP%UkwkyGTK{lJ|vY`S^-4HUwyQjUKVa*v)Vt6M5j%y0I=$H+;?j{qaFQq3Ox6 zpJZIXYSy8b=mF9N8Po&Wvsd{3;82j$iJjJFlex;29%|E08 z_~J~TgvUn`EeKkD^?+F;m0zB_t;}H^LOSkrl5*d?V#5=HB}qR{e3#TK%xQs=9i2?O*RrnO3^` z&7)7d>1HSpG5GqcWJ$9R;kPYjxAReOq$pEd5ceIq7h5>)-Jos=>r2+@vKQ^*o!taUaa8>qfE-P2nW@Yx0x@h4p^9P>cz--rXlh|_Z@4mDH z_O6rCc|5T(%M;;RbesFG$Ag1IzMS#CiJHZ2n$e*$n!MfyySl9+pWztD#Mn)LlL046 z{1mW8s>>Q;9W)_+#)QHtN=LROW6~CVE<(-Zd>2q)X%!sM&ttBdwc8eRnOI{n=r$g; zTnXj^TAZU|&Til=v5ghxRB?dic1?v^0D%C8Y9%K3hC}|s92+T6nymtg==Ix@`L$B` zoO6%~V%??s7wqA?h<4Q%I;o~aA90uB=#{fPeRz3u5tPL&h~Xazy>V7~Gd?dp>I@Gx%e4yWq&ALVrO)q~GZ=qrs6^X&1Kx|{jA@*FG+=8x)9lBW(X>}-B#;!|CH;2Lt& zn5Qdm-{)X0p}^;__)LqclJL>$J! zuF;+wlMf-Q;I7dg2YQbotD%5jkdWLPVoBg(XR{v_GCtztLb;Ld^pB|THOCxI!f#}N zawa2a7pnF-qjN)x+_E=tj7#dCY5s&O|r__*Y* zpG|Y{sn3Tf(RPN6jR#l0^%H3(Z(!eO^j4Mbr!@srh^O%-T!V*w&6g;qrvBzB6ZP(a z-{~YfaIPdL)#rV}B@*VHA$%eVV#b2*=1Ew>j%?i^wspt$ieCpv=q3l^VaI5oykaEp1$a+^y?LgU>lOvMQ)_Ya&ViG zyl}ESrOFhBm=Th++{KNRYM+8ayn=nz=$FN7@??^*uOFDkbOeug1I^cnHL(+dJ=~wj zg`C(W?1-X^+sk|tder#9T8{j6eD`~|NOLh0(fG%$Jl_}$m$MNO54r2cN5)4Vz-x9d zSaU_^z}DY1&{VbV`By;L6-GF+;p05;Skd3?LE_ZVvo&9?9TdA_=(wjq5TIm&^2Wnn z44jwbc=+OoH2XTZrJf{+>3H3^sUI*#Iz&>}wa=cxO_sqtw<|k0lh$ys3}3a`oH!ZH z=Y4K(=3~$2n0Z~+Y4Y@@{Pex=?e+^U)ykBr3g)>+AGtM+C!oNJz^0jzIi@V|6Xp#(W>__o-`WFpua&pNR54b6CU z#_=u~-%|@c;*h7b1(?HLI$TGO#_&?jzXcI}(9n}O7d+l*4Ns^lO4k;>hMRxyUfK9; zc$7bYE^S@O5Mv?Wf#wuPbh>?dm^5Fmg)WptZV?txHVH$T@*NcxcEuKgX0m)vA&^hr z_H|25HK|=ibf>ke;GGlS9cOx=A8jr#e{VaKSNn?Ehg?+Z=-w-lO;WFFcvYmbn6+vx&t}5 z!J+Dzbt!8!)Ql^y_uAK7c|hFX@l{d?H}v^av%`cJ9^MP7W-Np;wK;|A@9Wy5)>ban zr$%Run&F-@TX~-EO|`e?+BVE|SMIR00$rO9ZSqrj%bX#*a<(|vn)=c~3}_d!xt5sT z2+_ZpTt~!LZ#u~7uBEHFPcWut6O**VL!pQ$pK&ntDDV_HCewY~A9m$BygCtF5!c&G ztUX46_uD`$cqlKg*6_G28dY4CIf5)|intNmvB7{_c$$^biJYS2vB_LdAo4ilzwI)X z+*Ku`+9cDyhC3qDKiOjxc!PU&+MF^@WZTox+49z((~6AMUZK|yM%^pE&*PNjX=@B_ z%L~HO;6vqDGs7xZ)Z^k<&tfg;1;W7$*eZ1yr=s-ZxyMBFeG&)Xc*uL(X*Pn_dH&vn z=4V~CLE0u=zRoOIZ2g>zusD?ualr#uUhzcRg?8hghMx+sCX)Z>kMw+)3<@v+NA&Al6-I44SFH;_3nC>O-8Sj}Kll2?F zyz)aQr(h>dF-`_mNkV&9Ot~a*m5ff33}W3l6^aenAdWXi3i7+bcMtc1;toB(M_3>@5l#O!3^q@?=!(SmQEUiGia?Zqz?5+7D=2qHCFrkSFq zO9;NrzgfrDdc}sp+p@oHchp~kH`%Tu$QS*xCJ3yqAX}O*8=JlJO|73$dj($X)prbV zlY1IdH%G6?sDRjS=Wpg00q{J159`}_eD&?8MOOelFC=> z_5cUk+*JbQZf&84Hy@5W(#}B4bUbJL>@y|br7XUZ-H<*<8_ATQhSe=9MOB>aeeqX#IBSZx4U?L~%xs$Atty1KuUF8Gu?wESe(xc( zN((h5K+o6$+HZ1WJ1b{Xa~nrG0UL9`tI>dNlK<<6A3gQI9^BE9Q5kB`a+o0snTgSQ z!06V%$e&A%$~3A7CMwm9Ow>;yf>=y{oP-1#wyZZ5-!uRQ`2ZRPp#4h&{ZFHW0Rm_n zTSq5zBPC}$I|ma-M_Y&glV!uw(i0A%Fk^1G|?31=NH8&ElF|cy?Fmd?5cihFW+=R5tsMKiLdr2DD zfA76M!fNA`9Mb|kklFXKDr`X3K}1=?%LA-30yO+TSto1jWa9Y$Vbuto1P#K!TO){~ z_K&fooEKAg31m&IU46bBzzTgp!~2spO433?|94|xZtPwDWD7La((eA!!3&UgM?@9C z^NLb~YDO1eLmZ&d{mB+J6GJ5l{DgBQrW|qXuTMyK2)2?w+qW}}D04vvTmw=;_fs@HwD_hrpybxe*U}R=) zWAbD6|D_mjjH{IeX8uaZchVp8ZTO3&G&OGFj$znOA;MM#6{ZL8D(nL_Q#v8I=7Tqh^wCh+k#^otfe$MJgD-X!CSR=yM6*DY0 z$7@Vab*w4v_Gv}+IE{CAZ@kiDxfRWp=iZjhowP`%^fVJ`?xXrYGY!#ygJ*>Qjx9{L z*6|4O`%)Oj^N-;X=x7;Ye zkTyaI<`F=_2J6eib|>~ah2gq!nnCBivP^GxAr~4rhN+{xvV=BgVzvkSj4F7C_V56& z@Wt?Jz_HOP>osWGdN6HZuBNwY&3fWw|3!f1){=|(WYvp0<%$s|o+%6P@+^oXFW2)frCeH+tCn4!ijg*(tYB|AO?~_y1 z(e9~2V~7x&EMuS?y`SyPcL#n!;xb-y3cOMgUIdKE#@WhDm(N%S^8B^w~!D8R1b!xWMkj3r} z&H-9>V;=XU<;CQFN77Y6)zy!w|#qT3|?v^Ef?~N%n-8xUJ>@B^P zQ#``Gv`yD=xEy+KjQ@OAJlY+swf@{Eo02V`0jn(3#-@%;f^T zs9m|-v6CsM1ga}_wFj`o&K9%lovbpwN7UaJs;N&iWrl!-YVFnkuuw5E{aC0@)R%0w zS<$?2)sQ^MQF`Lvk4cG5@w?y*RI;f%tO&?s)(wPn#FGRTCbo!t?<_>Oq=A|#Mijxt zCp2G+zRi@?|OT#3caL6UrB;be^r#WD_u#@!WZ(!1l>ePGr3St;Xtf$o8Uu4YBLFXIK?`QoH zI|Q5#FeZ0(HH-o+hsQJy@Pi81G0Kn`+ADm zZ(b}RH}zibVQnEnsV$V9BnW0FinSuPrI&)I$&K5+E94U+Xq>X8R@N|ICi@6Jz>26q ze{x-u+8yyZxnQE+6{?#!PT#IOJC?P{h+~^Ht-Ggz)OXxP0vkERE=GcdAF%-3B&_fq zBqp<(92ridzZ6Bj7+zi4esAvBCyp@8(Gu370CVt&oAb60u-JykUH072U#q$t(*|Bx zwr+mNpsvz7{JK)fRJ6B|7i$(&a!SFe2pR>Jf|Oi&FvL!g%9J8<=~C3Vdpuw88JWvE z_fo7nar9okPxsRj<%cg)7+q4UNnz)Q)A=?I_+dls z7+mD;+ssHw*JL0W%JTK?j+l?m2v$XSiT0k}GWudxlaAlnYFU3C zY*t4s*=`FUc*nDc0cm6kvX1Fe`)tObCHt{^r)xwth9Ey$fmjV3))k3J^Fmvhu~3on zlF@*j!=6J11$!Ml!x|(71p6cw6gFo<^<}u!0_f>m5Yww~-TvBb>{eH3g54gjXx%PE zU*rt#gk7aeA8l)Py$H5baiuqXOvVPkOE_GQ?`*NH1#4iu?Zl{mz^bpKn}Tbl1*lIP zUNSoD@(IxGw8b5J50SVsx?HS3V7%2yy^c*4sl_HuQT{}?OH~=TUeOtd=*!$0@R2k4 zCSe-GMC3&s<&CG+0eOCvIsg2CfZAhm2w1P~440=k0qLYvr?Z<<#1mC{>21TC+Zh$N zlJc)$TJ&%4f><&4B#@;Wv92T3PA`fNRFx8H_nJ4Tsxf!yh~CDNQO&8Tdo^Sfk+dR}sSltNHV(^+?Q5mq=4c~hSJg7I-L!hLRWw-wRayFjFKcSE zh7UeER7G02i*3F15X=1B=Ex5z3FE}p{*5@5V})+J5wnK5I? zi4_~)DY@7Sz0Q`n_s=)pMKOY zPGwetjNFem5YHZ8C7)?E6(_ogbGSnh7g}PJDF=3-|NR14;dF+ly(iu@I@)TyK$XVZIXp(OQ^km$>IqU9@PA1ll|8UhE|N5rK_?JZZ zFK4}Sk_WDj9?5UB8^xws?NvlrZN>(rbMj=iwb`WrtYbbSfMeaTvmNqEQ%T0;3b<6FKB8 zCThROz0}a!rmrkLF`2LCT&>xsl8u4cg-vfAVMOFF7Gq3niS!PZ=EDTB)G9MB&)BT7 zGa`n^xP@t4W9!T18wu?_CFFI6o^=O?#7Mpo_WPkHxZiJha1xoJwSe=-{9m0v(_ilS zKVEMgfdyod7V#w+?ZP_FPcn2;J7`*ThT)vcb&r$4d-eujCD$46{Op)oe!r;EL0)$u z+pCL?KjhrSW+QKBInho8ExUZ}aT9|^J%FFy);9fKY3CQ>W*uthR& z+{jqJScMYrwx57&;v49Ze0F_pCjAk#6kSld%%Qar6yb_(e)Ctu(&HB>2NN0A+bbW# zP4;Q(YA2RjD7bDv%!l*6*4NqG%Xlk8%HP#4A;;ZI|hh zp1bsrTlLxlE=4&7C^h+o@@c?|B{GVKA!amXtoGPxzAT(2=%+w27fQ(SsjQFeJ1NSi;c!cnL>CS?nfRb z_$(LId8yR@HN7MxT!)^4^+fMv@J^&Bsr)$|O5*h_DzX6*W%5X!*05=lhQiM60U?ap z(sd}(lplno_>NIY>x-d$V&iWH>7y*!&xJa4Lde{hOI(mgxfQd*E09frhcz$C1kCvj zu4}`VRJ&pNblj}mI*QSCi9M(=(8SYe#E94!CoNF;+2vYD8FxTL1aDGa2L`>svXUKH zEg?~X&!kjG!z{6?HR-3S*R-KIynGr?D-?F#u0lbE>jLE|C0TdPnB;?ru5Z(WsXEYn zdC&7s8u`tn;XNEf8j+fj1Rj?6ks~AG;nwa~cb6y_9T)k`rEZ;BcHZiR)umETjq$Q; zO<9JkTWojdX`0-bhzZM?qf@z?A~Xl2!mRSJ{1JKXtTEzEd*}kDqDoiv z&-H#msIMdGhuyCiD&ioeSHId_t~ZVr1C z+l?Mmc23~@J))Y^U8mb84K*7-0}!@1k!l1>g$uK|WO=;?dvTA3dhumas`h*x$~)#F zEgE#gyqb!dFT=c2=8?A>&~&E0m^6()&xVbfr@q<3Z#;^~{seM=6D~fR60vo?r3}Ms z;KjCLV`ig5?CS0bIb1GM7yF`47qqXDfBu4Bw=y5L6Dw{TCq}uod4!qrSptEQ0jW$X zY+LohitP&VobUIA;T6craSq@D@%o=G5XK*la8|N{Z3bX9Tz{mZzGcy=B?uCRdDr${ zv&be~xDarOgrktv!@5AYtbBXKdW|v74s{don*FYeE5|!)t>Z0)8>zbhM~1-Fu)kkT zP&LKMcrIE-1;|*MCTx3gxOZg_*6cvesn|h* zaF~H~d_`oQXE780uDxTK(0>kV{>@qB)DQ(uAXqywXO-_HmIpfSPByPr@&VHK zP}79C28zQbi5RCbFs-pTSJ~+kx_jwaRLUC}Il!9}T%m@BRy2F(nI#MBjwP>NXZN$p z$$37g%6-q=ujwwyT~aW5u#V|97`s?(+beL4@xl1WF}zcu3Nc4F+2ABgn9#(ZqEVahD87EtK#;hc`9ZONURmpi3#7V+N z;R|{l+LQLAym!{T7aKtNJzi6w`KYxgx!dtU+A^tIU)|~%4SRT0G^f?rR#UX%R&aEf zcK0!g{vx`>y5=b6excfoX;}kEW;xw+TVJ~u^-NPK0?~IqbLoJd?|=SIGBLGbdjSQLSaFtjr+WJ-bPDMq{- zW11euqHrc+pw#yxR1*)QjTk5C&XwkOx+kDK9p#yl>-m7GJpuD~`uBhB0sp<`JJS7Q z?f>f$uLw{wV;N8~qnQ&j*zQr+dxXditKpc(?nxYWK!-0m5UZTv)pg{9lz220uV}a3wm95)=^&7_F z7R5^Idx0*deHze)e5RRJ@gLjt&yYHVhOmhxIpPZWCbI8Z|ihn^;H znTDf`w=@F%zQW9^XR=C-!@&?D#}T;WI+G*oP}8X^jEG@VTljjSc#$bHUcDhOxRsr3 z8LgZPdXSMpe$DcVCO?{+fi~7HtB$913uK}2j2v%emq;%wuEKJIQ}tfq+Le_G z_S4HlzE{F(Dd#9g4Ow_(XLJc8Nll1{p{1GOCoZ&<&K7(7 ziA~Sz(!+~Y`wdFW)!RQ4Y$hY2LgU9(`P=B&?5dQt!8a6(x z8ey*{F@yA%>C@~zhUBYOye^NErp}9mj@%;0%);-m>@!7EJ7{OfIPyA(+t-Ady;#0Z zSQW>+%QYq0*Jp0t_mrAbpOp~J+>BZcOkFvqZ#V=`ewueRXxUl`b}$$7_T{Z(G2FvM z;HFp|QE?^*8)uMP5Kp+$68CDy$GUn){B$(tUd$Pi!w)ZnCc)bsjMy_xxl!8rH3RzO zG>D7%RNp5qE|7J|=aBGxjujytKkGD3YgnG2Qx%RFq9}1vmBU<16}7Me+&zPZ#OR*r zMUW(hPVX)ZJDKHO^0bIlsF2l8{>BoOcOV%?!BO(J^S!w5SHJHY$MA6{Tby}m_U*%;(0gRWZ%_yxD;)*QtLKgl zNq@b;yHNM6#L|HFbo@9HtxPMS%@RY0A;RC-4KhTy5e61#(pw=l?&;+(>(w}E9AZ5= zn4DAS9t_40Q=&4_xRD!Fv7}#O2O_@jSJ5O}k!(4&lrU~n74YL+{Uq3H%^EEP zOW8xg5w-nu)FnTer5fC5=hoGROi~(W1QDmU>JjTnhuKFd>UL4f#YA6>??AO&R+htL zwg8VxC{X|X*1`J2DQZlz{oxc1uHP!D$0%DXHtRzNR|Qexjwn-T5lyK9yrOg|lUHAc zeDkkXCMMg4!9-TdJ2xP@xcIs~>4`B`+61xVB4Btw>~w}A+fhmmo)s@1%(Y|c6^cnb z=Q7V8A`1?qc+*&_cknsV^W(ee1|a{^W8dx%akYpbC5 z4^S<-^jtJA!f_Sr!(1xvRaieT*tjevYQcWUhQA1$)SS{~{nD{$+MQgqN|oiLgr)Ss z8WJzqo9;tamhQQY!pQ9BE#&~P6Vlhs{a1*$8nFFRZ0|fRO45YEx8sz~AVh8mYhRkK z^|1TkJW;{elM9VEkq5D(qrmqM_<~)UxYVcWj8nLBt7!*nOHIn>f84n+Fx&Y4&1If>r@JT}(0J$ga3 zI(l6FWyk#*P5CX~H+P@-UQ2kwY{xK&e)M2pqj)gguIXIJ?Q<~r!_zb=i|(&(#8Jmb6b2IvL-s%qbRzNR55zKdU$UNQ;(LETEF)QwquMapo@lm88j*QN<>CO=+Z$P z)YAz15+r?^WPcbOh8Sa!iMbLhTj*0TwbvID=3%2xO<72U2_NgI6x|s%oW6-KWT+7e z5DQz?nqJc}mvBaUshr63s7$w~zR*%$HgtQJSRJE%Q8rW=3jx9J>KAWuWGK`xVo@1e zO*(<*Ad^=GofFLD!6~^ezfUhy5dF}kn9+0}=)-|ZfR<#n&Bz`)fm8RD{Weo#afD*U zFE^nEo^A*iu}>d@YlIdtfQ#-VR1k0(iiZutIL3#0yK_&f8b z!B1@npXTA@mvf`7q}Ss=*_LydV(Jlcaeh2ATER0-?*RV2RF=IP=zng zv(sJw^$C8s$1^kgvvLJ)w%lpys|6?n`tLU52MVh-OoZ3VU)`(6@Q)jlO+}{^t#-!W za4&T4N4coJVThEMq7OD4Epmd26F{(#%F~5V{lYu_Zckwq4rhU}^MQfG3c+Py0&FBo zLwtVA<(&S)?CFk95CXj@Fg^FvU6CcXPg%mig|BJ6i`U@`*6XOaR-yh5A;VfBF3O1m zEUD_xLn0%(S5!pn2=5;SkXp6YG@9S4^YIqUw5T73T7GP{G+&4n$@8JU{Loi2>uj^_ zT_mSXS8SlGNr!&g-o@qUtH@<~-Wg{dFN;tH zX0&z1OEx$`RD*i7ds?D}6Unj5r%?|T5|0|g%k^Jfwi7blHQhyblxfF?iBX>xRI0So z>6IoEwa2qp+u-+1ui`ySpaII$*io@%%YBeL#^`Y+=_mH(toC%mP2+d&2A*{`=Iao> zUj`b~3td4{HPhzronBA5xr(QW<0uI0ra&qf@x-ei>VFVKL(9KRi0FKu^qQ%zRE~~5 zo>%m1<=qPw3AE{QlEjWw@iNK0Y4&$YrOLa`u+eWwrwGfX@i*5^kv4bA;Vnv0 zN`@)pgBmd0W%x>2oPxLKn77T>UJ-U@2|dR2d{cepq=!Z#JIvb2Su~3%K~c-x*&V0& zE>baY4o-H%T~`@0+av}0wG{ixBvKv4YwqgqKt<0OJ9#QsUp#bkyaW-4Lx+bEbz)W1 z_$tTcHtw2ilGK{Q5nSg+ydt1nY@g{YB$ADB?5Lm`3`SDVn09 z=d&789=v{G6;dg4XkEe)287`HoO;EwsNrJ?)sV+WauW!9oY7~;%-4?!v@_Ln-OlB<7oyt;4c+jWoOuZCO%wzW}rn*i9Qx+4!my(s;ZBgVDwp^ z;&sX4k)!u*cKhyuMcDRcpV03e?#OXFFE5)Sg(+_HJY(&X3_Nm)cjqS|utYRGdfq5C zo{k%O+J#gM^lF&Fw59%UvAHw-k8oF^OI$`Sjm?+I)>(}_`>ApRAR)b8Z(F~IYj?Pu zd%znt7z_tP%TBA8G`+-as0`IMZqm>vOi3Ud?{h>@eTF={st#TFMtNp`!R=r0#oyg$ zfvM+vd4B3LeU8`!b~gHTM`h*9?`c*MmQ@Z>c%Qu(>Zl{jg;lYW#pgnZ&n<*fNLuqE z6W*51GOC!jv0AjtR`y1_fSwObix{Hh5ujv%YTYz2#JklRRCH7+tffmfb%L$+ykTvA zws{03KLiDA3jF7KntN|05Hq zDjP5rxVqU7>fawq=wGP6)j9)a0H<>Oas1yy=MPZA{cFSMza(}ACIaUW{Ylg$_&4Ie ziE{r6xd0=9^K<@0DiHpH{5@MIFa$U=*iQ%!<*yK+JYm2X;Osg-F?ayE-oHBRUnllg zAPpD-EK>dn!Ik_I|AWdEm?td=?zr^1Ec) z@RsmT6x7@Qg8D1g56lAI0Q<=@HviA8zqZ4GQNY_JKT-ac{~7hq%@bf6@RR#bny~dR bG@$2rc_~PM_W}Y!0QkECgo9)qe|-CY9fF|f literal 0 HcmV?d00001 diff --git a/libraries/SITL/examples/JSON/MATLAB/AP_receve.m b/libraries/SITL/examples/JSON/MATLAB/AP_receve.m new file mode 100644 index 0000000000000..f766d94511dd4 --- /dev/null +++ b/libraries/SITL/examples/JSON/MATLAB/AP_receve.m @@ -0,0 +1,92 @@ +function [pwm, reset] = AP_receve(time) +global u +persistent connected frame_time last_sim_time frame_count last_SITL_frame past_time + +if isempty(u) || time == 0 + pnet('closeall') % close any connections left open from past runs + u = pnet('udpsocket',9002); + pnet(u,'setwritetimeout',1); + pnet(u,'setreadtimeout',0); + + connected = false; + frame_time = tic; + last_sim_time = 0; + frame_count = 0; + last_SITL_frame = -1; + past_time = -1; +end +if past_time == time + error('Receve repeat time'); +end +past_time = time; + +print_frame_count = 1000; % print the fps every x frames +bytes_read = 4 + 4 + 16*2; % the number of bytes received in each packet +reset = false; + +% Wait for data +while true + in_bytes = pnet(u,'readpacket',bytes_read); + if in_bytes > 0 + % if there is another frame waiting, read it straight away + if in_bytes > bytes_read + if in_bytes == u.InputBufferSize + % buffer got full, reset + % should only happen if we have been paused in Matlab for some time + fprintf('Buffer reset\n') + continue; + end + continue; + end + + % read in data from AP + magic = pnet(u,'read',1,'UINT16','intel'); + double(pnet(u,'read',1,'UINT16','intel')); % Cant set frame rate in Simulink + SITL_frame = pnet(u,'read',1,'UINT32','intel'); + pwm = double(pnet(u,'read',16,'UINT16','intel'))'; + + % check the magic value is what expect + if magic ~= 18458 + warning('incorrect magic value') + continue; + end + + % Check if the fame is in expected order + if SITL_frame < last_SITL_frame + % Controller has reset + connected = false; + reset = true; + fprintf('Controller reset\n') + elseif SITL_frame == last_SITL_frame + % duplicate frame, skip + fprintf('Duplicate input frame\n') + continue; + elseif SITL_frame ~= last_SITL_frame + 1 && connected + fprintf('Missed %i input frames\n',SITL_frame - last_SITL_frame - 1) + end + last_SITL_frame = SITL_frame; + break; + end +end + +if ~connected + % use port -1 to indicate connection to address of last recv pkt + connected = true; + [ip, port] = pnet(u,'gethost'); + fprintf('Connected to %i.%i.%i.%i:%i\n',ip,port) +end +frame_count = frame_count + 1; + +%print a fps and runtime update +if rem(frame_count,print_frame_count) == 0 + total_time = toc(frame_time); + frame_time = tic; + sim_time = time - last_sim_time; + last_sim_time = time; + time_ratio = sim_time/total_time; + fprintf("%0.2f fps, %0.2f%% of realtime\n",print_frame_count/total_time,time_ratio*100) +end + +end + + diff --git a/libraries/SITL/examples/JSON/MATLAB/AP_send.m b/libraries/SITL/examples/JSON/MATLAB/AP_send.m new file mode 100644 index 0000000000000..6fda364472181 --- /dev/null +++ b/libraries/SITL/examples/JSON/MATLAB/AP_send.m @@ -0,0 +1,27 @@ +function AP_send(gyro, attitude, accel, velocity, position, time) +global u +if isempty(u) + return +end +persistent past_time +if isempty(past_time) + past_time = -1; +end +if past_time == time + error('Send repeat time'); +end +past_time = time; + +% build structure representing the JSON string to be sent +JSON.timestamp = time; +JSON.imu.gyro = gyro; +JSON.imu.accel_body = accel; +JSON.position = position; +JSON.attitude = attitude; +JSON.velocity = velocity; + +% Report to AP +pnet(u,'printf',sprintf('\n%s\n',jsonencode(JSON))); +pnet(u,'writepacket'); + +end \ No newline at end of file From d9d289e27908f7b2eb4988140fb7b305506417c1 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sat, 13 Jun 2020 23:53:04 +0100 Subject: [PATCH 3/5] SITL: add Simulnk Rover example --- .../SITL/examples/JSON/MATLAB/Rover/Rover.slx | Bin 0 -> 27534 bytes .../SITL/examples/JSON/MATLAB/Rover/readme.md | 1 + 2 files changed, 1 insertion(+) create mode 100644 libraries/SITL/examples/JSON/MATLAB/Rover/Rover.slx create mode 100644 libraries/SITL/examples/JSON/MATLAB/Rover/readme.md diff --git a/libraries/SITL/examples/JSON/MATLAB/Rover/Rover.slx b/libraries/SITL/examples/JSON/MATLAB/Rover/Rover.slx new file mode 100644 index 0000000000000000000000000000000000000000..c6b0833c5b4dc554a1f5edad06407350b9338b3e GIT binary patch literal 27534 zcmaI6V~}Ry(k)oFZC7{Mwr$(C-m-1mwr$&HSC?(OYWm!XnYrh?5fiav|JV`xN9J0Y zPv*0hf;1=?8W0c=6i}JRwn9EJsoE^)iB%hiju#AM z$u@(@DU6*j*^r8bq48Q_p{`CBtRhmo_L({U3^kJuX=%Ti1`&TYgoiVP~8}G zxVrE1mxNz<#%aG5o{s&TvYL3d1(Fu)lH$sdK>lX@$-O?JIMZRD`4M&doi+kv4Ev)y zh&$2FziE$ahw5e7aJwtDSk689zzKEvtE~m|0Kj*BY?)P{C83B3)YpS`tfDF*Ot!B8 zdWE|h|1#NM2QNF?dFX_R)juF4WM~tvR84il6Ke1U#CB~)PeKX&4ZDSK0-qDB~ z8KIQP@3JBBCg|x{B|jMn@QFIpc5`N5G;u|Z73bRNc{keuQur^T{NA?*GWtgpBXA%f z*ndRPcQUncrlu z)T{eD36yU)!RSOXlhIaJ5tDJ$@_|q*aZ0LeQZNj*OJ*(MtAp_@QAFER+L$HSnKeu) zH8Hsx68fo8ss&Fhlu71=ATY|mDneSOb-y$Yet;f%G8GW5lquEdI1h1#CrsPdRdrGy ztFnF4gxS6Qj|E2b&K84Zpx?K0L>!lm0mp9wG843OJM*=NY91mv@2bU?amzWU%+M)@ zEr-<|(C?>;Pr2>uPk$cS+nZRQ#Xj6UQ$})`$)9B`y%(AQ zQ1Pn}j&6CjiZ~&Pr(xE4BG{S>N9ejCH;ms; zz07#CQe|oFS#a<7II*T} zCKb5q>uWg)u>|T2KIb%=bMo`^9fVV*}3 zhyhNtj>Mww$ejvCbEC0@V(}5ET4XqoTnTBVxYvi*rG6^`Z095I`86l0(>P_EX3q%-FIz|+%nRSHMJe>k{EPobHMD~m9fx>uD>Lt8|#D$HbA+4^V%>kic{o=!N6 zK*#)y$6UF8&Ow;@F>K({A_6 z|1W+~_kTx=v!%V=f2gS&JEb&Cga+;xVuTpXgGQ66$!U#w{taRGs{%S6NtT5*U@j%DK_&GGbj@HLJ`-XY*nKkCo>H7GM-$nb4uJlKZDE@L_% z<0?PSno12UrSJa_{!QQNVQms5!Z7FV2vw|Ab=~&$wlbVB5CbuT`S=hC!|8@)i-wE(r z&0OpJ7dYL&1W^3{B|yp4#?;W+RMO7O{y!-I#7ZLuG9U%td`6~t6`)BlP#%rWz}`8M zp{o&h%S4Ul(Wi)ayKiOKo4I-1Uu(G+EI!STwVo*8*3*YJUf(qMaFvoZq8i@e6FcN8 zE4;J`0-RVLSOx@RS4n&;Ep6x=?95lxU-(u1KKsO;X^6Wn zk?oE$F*m$YbsC$@pG(O$63eSi%zj;L2EV!_c|=&7EdeH6>3i*WcKZDKU-)J_P8_d& zvL6WQ)|^Lhu`L#r8WaVIkhE-RSy3JE+j%I*``uDJ00iv{?-sEtad*Zfek1GAwX8hl!0I~42w_tMp@<6F7^&7HZlcXmZSM8 z1@bbMj^!Tus?ykBmx2R1Uhf2SXmCs3FNeXk7vzeyc?jPAoV0QA)^Q~@vCT105GY)~ zxKmIZP-0j^3BCe~{O;;R-+#sBmgd>L!MD^MsVIzA{xNZ<4P-Tpa7_Rx_=-+WIz)wE zhN!VD%v81h5ZXZ^Wevl{?sRq%;kjgTVdXqx=BAH+lo%`IzH>J}K8Cck%p1u=XCY)R z`zCf)p;zqJUFkgoa{(OCyGvT`v zNC*$;M~F0@Ut9<)rlzKrI$OiS^5AnfptSPw@hJe%sQKrZO~aelWSX&HP;^Z<9xK{k zVKm_s_4NrC-9o4&gVaS-(5UF;bxp-$##z`HiRtj8cK$x&$n7MAf$`-0`uF%6ND&XtzYT3A?O`mJ$| zi=ddGwV!s7JjXbje2sV7VuSrv2psY$Z0ss54XT7r>h3&eS;BCtDLqg*gx>EGS&pzn z;EB#iN?IBjDsuD4xIv1FnBxDq;9+1X#zrDy<>lr5{CJ_RS{0y(bI3e^hqbZWA1f&- zA)NJQ4^5^+yZ?vs$(&P{?#Qc0TMZKRjC2Y}5wJ~uIf{pj8&2MHTtS^tVY|l0AAK<) znO~^OKn$!&=(ZW&gU^@YGAngPjw`EIHfP?0Q{wIpWfKJ%vnS&{ZZ0!gfdN8LqW3Z$ z_%@DeFnB^VCsq)+l80os>A^h?Z7R)bJaVo6wOG9S&e1mXGP3ow(R| zDBcZj!|QzF;TpPnt@x8c%=?sNHj~5WK@A!-;F@q~D+Z2UUFd6fb|D14_Qj;8P*py* z0v#K<^%N@{ zvJT<(y4?bG^)LYCHH()QzeSi7axDpc!#O`!pPZT^9DcQv{Zngib&h#pX8cjm;B~^O zI1m*UM}Y48EyJm4Ty%DIRb%e5ft4Q)P(wyWt{;9eV*$;)d2OERSkncAcLE9o9NN!5 zLOYq@*~lt|-Su+h9inBH#&KOc9v+iuAAfE6vXp73=0s~LIs(2fyWHv(Gvy&PDK%d| z)Tga`N!|R~1`4fM#;Z2;H1D!vYp<1cJ`y+qxC(44%r)Ot?4%ToT?ge%hn$P#A^U2A`+by8qznSWOO(C^c z)0ox@{wb4hGvQE*)WRk6h%_mj-MTK13l&FBZ7*=U=24F+q6Pwlm@av`0Vq2*<4;meLJ<(8iVBfB`PWPZb;E_I2>p?!-0*Y zS5%ajGa=C!78E49-Sln@zz1RP7t-C1;f5+gYpxa~`~PAkAw>r!Pf1SQ+&13gEsqGK z&lU8D?2k=94rNtUU&_hO_8u@85JawW>RuA=!&>izr9(Kq4?B8gk7eK7+FE00@0*!+ zm=?v;1V%CM^!@UkF)_5H^pKaI>p~<{;o-Iam~!;Jxe249DxGf};!90amXwrCNlClF zgZ#34H0iV19vbSuU25=Vral2FKm6Oxyzb4w6db^K_VIEvZU+ODLFn}P`N=fE-TLe6 zoxBRI6BtK)AdTVgMgmwgmlJvDU2A^6!JV?*1(aszfp$FzW)J>x2|k>`KN5(W(z z*jtv^`PFzipw+=h{oSlf`iPJQgSKiCn)EE#_}Ea;!KOMit&ZunCE{^O=Vx54-%a4> zJp?o-V8tnrG7uSsNXvIGA~HN{YX>Q_@99xB$)tE51Ti6Ro*QW1*_ahZeDNGLffikm zU_yp0jXQ~1lOkqj8ZB%JzinB<%f_GA3oQ&gjHr7j0Rjzq;ZmFB z8Lv-O>$9RiJ4q6BhDm$i1NS^>HXZ@pbW1zs5heSqhoRdCSFMCi)rl8iqCq`I2L&WIVzTH=)5 znaDb~<-1vUzpCc(;tQKO`Vl!i*Tru~mjDX|^=C5M9vX@E+MMd0)XG_C#WAwhans!P zqe2?`bc7?Y*~@RI?`7xx@Z)Y_;l$Z_)i!MD8cOrxem59YtW4_xlQpEn3790;q0Sn2 zv!)u?j!}Md+=@{nqrb1(Il;Y}pbY`Xf~pBkgkjCPmE4uW`>D28RY@#GmAa{{tSml0 zzA;NMGwj*tB&-VHqp~a~sXjYyMvps?%Xpvx^ z>0f(j@U`xP!NE18UY&7q>>klL=7%gmpyk&li~_XRQh&(hAjj|npNS<|5*5^1< z?A|L%M*QS9!2JP0m!Ha6c}5>+q}Sf;>gGC?rzeN!?XgfJ zd0p<5k31QNTmbeWB_kvIbW4t1QpIo~)@iPpDS|%@6RHJ4(-<4zb&YK`a3FA^CM+}0A4@2Z>rq--D%#%|LYAL31W1SJfE}z) zu$;*>AdE-^NEhS=iTlSoA@NwA8z17W`F4juVG`Vc!rY7sI;g*v|I+WuH*UtbcZiCJ zpNMET^fEF%Jv}pLduG1AJ`9Th005xLxq>Rlq2;R*4&E)fd4lwZZia+50*_fLf@_!X zhbxmH1*Cx4v)5hW0rVWWxVTbRmLG$<@0k8I>d6u>;3aLtA1yU8V9$ZSqsO26t4jy? zU3q=JUl9fBmm~%1;c^oBoi2lqkz=h^lLZ9@XD3$-bC#v~>U4?KJv}|eW~{5tMA$$J z+?=uNDK(4@HJl_a)Q>>UR0mAIk*w3=uMm@DyPBPS`P7q?|fF zPTGVkZ*dkC?hYmGEs|cmBd5VFZVwNZm-r$iNOq^BrN9OQT%U~@W!V+oxNe);?_~f# zMwfcuqVDuSPiH2#d&y0VAa@>~KGr_E8ylLpXmNg?j;@Eh2SY%Mhzf_r#bmv=XKO+9 z^o?B4Q5Ow`*=nS2pow@zFnumA4uB&ow~7VVk;ah_{BKq@m0qVK7$7X+mPDl^lNMF^ zV_WGDXep)ry_%q@gm5BE^L7ejV`DM?i&ZG^UDJraZ3`C2o&?$&-dG4R^6AU_X69?# zp6`-APCoQTvcA1tq#%C3lXv-dOS5Zl?En4QSi-52rRdSf2H(wN44+UF1q)t37on_Y zFqtm}R98WalD(FXVrGj|K)#ld?zy)W#p^hVfdL&?E&PiA4o_?O^U8MfnK-r)n{ujb z)P>=LfpO3dFW2=Q#WDx0>7$?go~d-!p7qz2`%jIOk zprKt%$!k4f>ASZWoqk2Tm1Gx^AtpB>d}L+7#=pXakJ|t=bQ?!wW8FnArOag2*9^_7 z6h&C6J*7SWUG52}s(4r=MXiQG8X#T7w*3_21p|{(=KAN)9~!-qByB*zoE=~BY*SfD zQ4=IJXyn}FNC`4BFrs?1BBg4g#TM~#B+2C}^Y)O2crM4^paGWQ!>={$LG*{8kU+?8 zZaFX|4io-}w+V-Q5%*Hp=P@|xiy8p|mhl9S9xkcV>adt+9+?|`rdrpLFzVQ%1#ob1 z5u#zIl0;A}lL+mz05UWxIVs@NR~2LK9EZtv%(&zU1{=%>M|$n!pgD=2IPC1EdXihrEO3OzhS4w`_} zx(Ml=0ahFcv5ffmoAj4nh++6{5eC^EAxsHO{PW&W7`R^tJ7%SPX=+-YOfeV@BE#P< zw;O1-S7)J(FMFlKc=R?wq7MbhiPIQ(bpuy{m_Cnw7+6>jesNI3VSXhYoy+~}T&z_* zIDz@KHAruZeY5?@KD_V`?lI|#LbZ3N`}?kg(omnLyQ0x$gWF>P8eD_8#6%QH%QKF6 zcd)UP;GL+vu|61-V0lDDT-j!opU<}@_Rr#B7o4Fc3#~H{CvQyvAo6W^S%s&5_Y)bG z+p(x$CI~5E*(#>mBJ-)y!$28Y@2ytLAOE;ug$XsU-uA2RC9^;)%MJCHH7EJ4^8Bf$ zNf{zu0w+Y$19uA zo>#rPp|cn{Ve|I!H;S^7D1=X)+r(s1slKUF`!3;Up9p=J8q}*@H+u${W8Z+!{hUmb z{>I5%_$c|B{TAWz=6WJ{NUpru)?tryUU?*q%kXzZ?D`QJyX{e~V@wPz3s+JWZpw(yiGg2SuO{RdcEj9c zTJ?rY`_STSMS8tOV-q}3m^0hlKsDnj^jm!zgU-=2YEx`HNzC)sgF=c%x`M$4C zz~cp0iNeC6r_txP(j-v`HVf4yG48U!4Nj(m3vjHRrDYt=OvULTA)VLL@g`?ye-XRB z)C4g1MA9*kk6itYJA55Xwjz!hc9Q7*hI+NA!Yx;=TIc)uA6MO)g3WDL|6~_-Xdoc$ ze>a`ZmbL&JOFL_NWn&9d6M&7W@IMLWe~G4Q6Lwn+NIfUiaNCxSX)5bf^QBV-SHx4C zyG+p`8i~YY zolHEfh$sKHpK8j`4_%qDEmMm+Fi4b9oBUIu-F{8QFONZ7{kOP+9kzU>S%D#E%N@!>1^$SWqeV|llC5Zf^;DTe%6-)Nmxr%{ zE#dK+r*{4Ce!p{kP?s4}F;UoLN=jsQ5*RY)(Be`~fLh?xc5Y%ihX~h~G>`c*_ISG3 zq8Z$s4n^{XMC2lhGR8)|_@e!y)ltD*J*qE1Pwbnz=V!vNEs_@U2vtk*(HI_H{{|)F z77kyk#a0(%^t{7|{Zk6)gLH%bcn3{1NsCyP1%H#-m;s#Z=_cen#s;fQHiCq2F#7>~ z?9qf$-Bw-6ko1zRxdyL-&n{Ez>rc6?A$PpBn?on?W4Ej`pE!YMI6;$$wq z@%Qm-;gz|wpIL&ik3J$SYoU68L_7%!4Qv=prDnC3_HeC1j@dPKAitWv{vms=x|#v@ zmhUsayIsx$()<0kPfsDz;Zv|fD#%C!swvjedMp%?ZH#bYy2g8;6T~Yv@$AGDmjj0A zcskin)1NX&FOWFjL;CbGdS-rUc3Lk#=Hj6h2A#5@qYjUt;<8OEZ;+BOc7-?C|5gLy zVy=&O|J8`dKTE-X+^}%7L|U!cYiT#&+>ZY^>qGuZlQ-S_Vv)^STUj0hzUNi0&^lSM zIp6W?0{+t{vm?7%sLg|w;|5^<8{=b7yj+x?@$t*P?7RB{gOJE(!{ zeUl;>DF#@T5qR3b$}s~3Z9zm*hQi1!$T|U2R*&7|C7X#QAZujxZ}@C;*Y;nnrIgcQ zsM<0uOh8hv_%(At)sg#}s;#6t-KK0{~OSys+mv2?~d4uz5x)pr{Nm9vI_%&IqPy6O@JFFjDa= zrP)~g4H*%3c6wzjnG8tpLIQ6%Fz}fyFe8tXx22KF&s@p7)~TS zMx=^x5k-k~fmhLZhj1rS3I~PcnH+$m?61@j>&_oJbWQAIs@8Yo`c|i8qOIcK=EJ8%abnT|;ZqT5=Zol*;;^dm!73~g`r zOIdW;8#Qdd((=+qJT6E+sJ^amUo<2+;#(#f@3U2XVK!(fj7BFqD337N6%KZEf3q|>c)ZD;7iO>WJ2#D-| zFO2`&OJQVVZ)|O1X=v_bX#1by_+Q?No>g1xf9D9$ZlBSkk78#`k78T0ONapX@zHnr3+_Qx{M}-T;XEv^hR7+ z7ki$Dm>>r^9M|{;M!4ykdfLuFIMPjl)LQb$uUIFw5Cy-zY!h&`c`$1SM&RaT}) z0%=}7d)w6k@kB_@1t>+@8%)EN7arevldxR`^vmRGhygK|h#ag(@rw2;pD!T%t80cju zb*U@k-?VoJ0?Bx(N+W@ti%RJoQTIaQv(~QZ+&hyf&dS}dvM>r*e`sprQ(W=4r6X^Y zPlkG$eb*6X7hBQ#>3EG!^IZql3uJR2dCG(rYV{Wz7UcFqk8Ar^7oc-{Q|CZM+?0}U z|IQ7p=>Kot`F|AR|HT2*xB;twmVr?Hk<(rZ z{Gw>&vbKR*>kpt&Mf@ZUw$!y6d;J`#q1gA3Uilw~SLvz_rIhrI!P<)fqz@iZ1dQ3T zximM1MLc=C85s;aG6RHzTiGgWPf}+ZBeX#yL%SMpqR2c-&NC6}KCTX&a$fVCM%F&`cXPF!&#ViQoH=On(mdAt!qx4q z)ks9VU5?$-6?e%04*NV5m*fu^5YPe=5D@179=6dx8P3cQVB_+?+$u8~+V&*uXudo8 zjG19p+N{JXHOsaE=)vVqLM47AeazlV4B}QeYvkcA5e)okEYTw}C(-n=;1$6`#M=_7LFVwgR z&STj(4+PO};z6*-8!+PuMOx)!!GMN>1=AvstRma8TL}}oQ?NFT_eL|?2%4FIJ2Xl{ z$6LmZ=2rswpiH0EkBBr2=#I)@jjaQJ43)m3{II&TK);x6=9ZD5-nr6yko0|z6-0?iej+i00`f_nUK*gaIa-`{0 z*0*Re96%4~EB)dPj}BS(NrNk4qC zY^tk9!GDCrn+guFcmYy3G*O>$>Gs#CrDAFATVtY%&Xh7XQ4)J9W_YHw(IwF@G(>(C zG=3f_4I0aOeni;tHXKZirvknnYaaPyrh-0Ps#+UC&rhcrZChCsd>K(`NC#4+OToLz zC6Y&J>eEFyr*w;BOB|U+W#mbT{vnhKZ12p535^Wq2s$gHc}YukvE`GWP%)>t!y)_4 z4=r%{lwQI~`YRP-5{YV!ZizB%25hagW{xw8U@qW+vZH9Qzl`EoeF^3#bh}hswRQBh zv3~4^If_DK61E*>__#voomYm*Pl~lRqhIQ;yRtXmXWO3Ta;&QLqu|XX85U_CGN1`N zh_cLUe6_y46H3JaU2;KL4ko2o8$szcd!yxpA5JWzy^uh>!(Lt-i&}$K7^$D#B*|-J zg{6n2I3HhncPocujXbPFO|lL}*?u<;@7|kiu>{3Rw`L0MGN^T++s!} zxT(SP{*Xi#%2d)|ccRx)4ZU{ugHP49gVq+(npx^u0xRZ?*380~oo*5g7zRYBy&_O)|CD?SX^q~P4w=?m|{(=dE zDvGT_<-AS?gEf)?0I4Q9!rfzS;l*~)Y~xNok>rHt zgLkAf;0vN^S-tOZGb}{4B-&0rfE=Sd{f(A_AP~EQ`4vH_!f!_l zZ#{X`d(Q2*>4-7o(v|XRgAa#cs&)FUkPbegBsjLZQ7DXMsP?{E!^E9?y4z+Ylq=)J z>d|e2^y0MK0RM*xhE7r%(vyq=pUUs0VRf{NZIf?^9?t{{Yta?Ky#<->x$6tWoxa1B zq<8C*FW_lXx}B#|hrG%_MNhkv9@tpdNe)fMn42G-FX9KP6Q%DAmYKOK)Ri3myh>>Z zU}_E)1?(|~~1$+70 zEqr^SYkWmDwe~2O3Tcv%FO5~mKv>T4Md(nKs-r;{fVAPn7zkKtwTS zGUNe+cSK}CQ-f!uE^)$Zu}JMw8Hj9y6mKOS&(8Jdrh`{`6#f5U87m~)1)YZg0`mXY z4gYJ8{GUTWj>eYV0UMIfP90Kk>nX&s3;b~{KR}H z>4>^QT22j4%n(Wn+(-uP5A0hx6H4F(v@gZ(+)rjWOH#OaR-kQYyR|Wub$=*Hkajq7 zH-bgv_|m}=;>kZ5By1hmCAt_HZ<0lmv1D>{CVhljWW*6P+QLZY5B{~M8_Y2Y*)(L$ z0&k_hS+Z#~2-nz?!Zsi`u($x2Wt@&eKi-@ao4Fw)imZY7R9y=bZ^A(~uU};2X*v&A zk`+%%mo{iCJIj1+2-1Asfx$yh=0rVtAloS&RQ_@E3Bnv6IUTjc7De+3M<_?S{_WxH zfcQPiQMNW@VqyNXMcMdj&)b$8|kQtc)< z17A6ObcwD#pdUdE4Y^)vZ&PL~8r$GvIZ)}b$nIpfqi(X7^ukK^a|?jTIQuk{pI zZS_KKZr8oea#R?a(&6i4x49JHzPMMnXDYHlTqF0mKnF289AO~TOBE`%8}3|S>t-oF zcP53>G1BcZ>@R5H~Mt@Y>c8w$r5 zBsRo3v8;9KNHCV3rEv|#b0sv(v3i7RXxpBnCVeP{z5F+v*8L|jm<@U}wAjZdYGc7E zOv_EXe3&Cw_&`x*vE7Q>EWfp z%&{1T|6iYU&8wZ}u z*fxV)U9_W@8&=WQ6bE*ixQY)39>#ojf#e(~qT$&nd{xfF`#J_;`|=9ugGJfxx7Wm| z$w77zKMlH8Z# z%>}$lZEiS6^s?)-IM_BV%l~O}F8#t+HWrth@I+bnE8bAC;TYwtlm?vlhelvLW!v&- zc$ZRGoD3svu8CadyM%F5fuguWU8&5@zu`0!O^;xP%*qxC+PE%J8LH!jSIY!{_ z*LRTXv|-zE8`Rmy^?8Fc{41e=8>USJt?q6HsLWxNZ{g3-KvqMw!jfJxGSCj!{XLq` z4)kZ|o}u2mn~#;QW0IUBVZ%vjvSN|N#igSEjgx$?oPXp+W9}yFw_(;~!udjkx}$@h zP~ce~K;#Q_2p27X?djzY^pEF34uc!{gotFRV4di4(Z@UbQ5Af<7O-h_s0!)I(z6`o z@{%w3#cZXa;1izA6s-Ej3FHv)AJm85Y0VqmH-)#z>zHX}` zPl-||{P5%b*jrLKhHZ#;_jnerdpSG)Rwqd7sbk$d+gh{N&wKP5N=6@HoqC=7k}y%F zx({1}HzQO8_SjrPB2}#aNdB!%z7{g@)sZ(2GT(|2P>=P+JwQkgxp`e9y=jvK9G9iPL(k#%gUzlFf z4Uyu(zFXpcD5-MKI{kWFWIO0cCpDl1Z=MGjB(PT*RQ$?RQ>I&j&qBi2b?l-8|&?<+P*{A7pU=LW`gIp+6DAYB7F13zn46S*1qLNFc zee2T0>xy;OOtPygDa^eoZAhws$KHfykDMZwjZIb8MZI;1Y#}cIRPIc(MR&_y>CE|B z6_nfjT_&O%@H{CY{oArB{k;6x*o_FW7g(UeRZgQ)eCjm(@`O53h8tW*<%o(10ve(S ztrr;4g>RVhHt&(YGVmzI6IB^! zrF)kn2OC7=tr8j@)7-Obu(5iGinA6*o)AoY6zbP>Cw?BqaFx0|d@wEa#H&pXviRFQ zLP&w6tR^*8$SAyPol;{T0N~M&FZZT(jnS@@PR(xprCO@Ii}XCJ$oasFpG~;WQYM8W zo^mDq+ngLhyw`&pGwUfP6Mtu`gGg+=IuQ1@ZfVhZ{MoG=Bi<5IFK|_Urmx zF$5ZdJL&|62Fmv|+EXi+Me5Jw{qL?V-CREuiY)d+fOVT8JgmiBa^BPxRcO$E4v9Sf z+9pRf+0gY#J}LNLJJ^L8SUXp7cINL)ObSX~MQma)9GI5en|b!=h2fKA9@L8!Rx2Mg zYqu}Ll$rk#;@e64E?Bs@9HKOxavv*CN$X};p}%5`XI1+Qm`6+_AcY? zEQROOhPIAZ_AR+Q8{I7}5`%+E0Ec1DPMxL>SPD;h+TFZe|b^G*5>C ziwql`LKWFiD${Ve?^yHPz~4hG_wnK`a#9gZXvR}vbRe&V*0iUH=3(N(O~la_(chqv z$*0R>WH32#;9&8Etj`e65kZ2NzMoyU4lxK0<-$_axv)#L3kN=lZINd^FGAUVC=p!w z*fEwz%#{B&`Ucai>Y*2b#$(;Yj*Btvo*|_s8(-c>b`~buMAtWO}-@ltXl*I3>7^~)ryyM z)MPD}+qC}B?jcqU)eIhb`?#Ak^`skcr*;4UjZxZu^@}-N+9M9V2M)cE_KHf z_s9Fwj$5JwAq{k$+y|&MCAvb7Qg_+8GyLdI#?x>j`&RC7c-<5_xHQz)!m%JwNccj} z?1@b2*(?ano1~NC9#sE>V-EFX2cZ>`v0ZTJ@>JJ&)%19gS+I2|5--eAN8|5Qn$`7Q z?J#IpaH_&?nJJ_A-$ftI>C$*34g6gd03z1ZM3*Z{8mDm>_5O7t8LU^cwQ$2#(~Z#- z4S!$Lj^9l%hv9@I3dvv0#=ksa$(sliEG?tx+F)QzuXNNr29t$1`|m`ez_05!0lYap zs1In~8(x|YEZUOgr7tCatqe?b4+U#q_T$qZV90ubyg;w%H0A&>#N$_73yw`Q>rvpA zAt=z=%}*Ue*RzK&&>yOmIe#kbNkzt~d-o`Von8r}#5Ta|mXdcEM|pyj>2Ryy1igyH-d&n}jkc*fePw>@R@(50zT6PFq!j@;sgFS(08oZmpJ z2!&CDKYI%euJut>b6yLnb~Cc@bQKg07AXVujn1DK#9rIpx0>G2stbYKVyVe#-|?6? z>aFUt<%iJY0O-HMGH76c)8sQtp@7%E_c-)*ns}gkRnp-VR0*tI?H%y6=aZ&2dJl=6 zr~S9)-auSt+2i^6C{qhW(E|x-`eS(sQO)^58dMXByKiKUfb6+*mGYY#9wkJkwR}KT z)uV>d!xfQZSA&)FGlU$^std=9{aU1jG}uN~5$xb{7otf2u6xddTqFzF@cq_MftP=` zFD9y=N;7GNi6+^;53E{k_;vr=eetsajFZ&O%nfzbqS)GBGsT#R8f?dbo8DwI+CjuH zzEx8@w{B1+>#NLkvd2Q=t3O==kE}1SM#xz9*42ZjJOQ=)0P0t@`|bq&okYDUo#4S} z?ol+b41P$#RIGB!f~5zW!6$3(bd)1O1&4n+V8#ngw!5pwkZ~)(8 zW-a?h9O<*B5-Pqi=1^}&@v}N`D;?4-^f=$)f5Is0n1G3NZaY;Nz-2brU&*tNP?gMD z<&yJzgr6PvYUR}&IM}VsS&|qmdvP>w;dCnD6QQ)0!sld(s96m?aNgZKSC<_sf7(dO zMR$TkAco!j@NWd#DQ>950uK73a9aC_g(5N7o`bS0jh0+J33genBoo`iZL5=w@ zC>ucV5*H34vYAq18*rz~s9zNr#Jm|+UX+Fb{p7#ZiU`~=D!0)q1E#((gSw%__~e&= zWF>3uB6>*XVC3vhjJ@}_5Nx&#{GLM@{u zekaAcFvq#=cYF}Kz=XyVQ8-^8k*yx_VpmshB zaV@bssB_#pG8>ICJX0e##3o=sr?AasW>TsF?T=c%5D~IJ>jC<)XlA?5B!fCiaJIkW zFBqx`l*gyI{2$jR&`G<~ZdK(M1RP;*BZCvcRtfO9hlpXtTM8kHab|{HiLYc{Q3HMD z+b4CJol!%-@g-ngZMc0fhY;)_;R#R!T!2OK-_{5|^683Rc*H!>IEs=iOXDKl{siwj4m)@9~#v z^cUibtXD>>$N>*ZttWIXLEJt8oTGW67yWzXwnUt=1ols;zJX&}(pFvIz@#0H?pJWT9qm7SwSaLrK1ojMI4m>NwlLkdvO8)0_^Hb#7Ql+)x&JPcu~&?^Rw zR>FOC8AP%IqaQ#jE)0$hQg!c65v&^Q(5 zB7fSdakTmorI60A-{GZ4E( ze;v73GUZgO-MVT)ie@rHqn3e-2)Xq_XtQ(=+6Q{55)SEcsttK3eEm_B2zyEWr-A0@ z;@<_8I^o}!??>6gh)+Fl_aAd@C$y?(;KWAQ(}WaVg|g;Lkj^7h!bMufu6crt4e%$) z89EzMc4AQ6325N$$ynTXjkB|UrsNJ+vRUL4tYg-u;D$Pgze(~em9QUQWHC*orEMO{ z=FWyTN6WHmP$6pu!NeLvY$Xz}9c?j=xc&Q5HazXhT<1v%1ggMiDbmTEHkM3##FB>lj-$Zu-q@wX=x;x9ZWJ|Tnn zjKSVRi?4&1oj(hv28N$VNA;hpiD8}ZJNjUsB$37JqszxLN$21@HB%@9R~l2ww$31X z>9Tw=Avu>^DVF0-9WA*QDWaVGV&8jH>AW^_i(|l^u7fynhXtF7cc|=SI|ihzL~ITY z%X~3U?r4SB&!jpi>_)8RI5H$(M|G7s`N$u3!mlv?gx7JF_wis5>Fd(0>X8E?r8LjQ z?jOpI5o76A*#boPB+}Mh9Z@f+r>@No%(A$_GXv9;M*+Y{3@_Q#s;J$v?E-T!K#oo4&WT5#MgYc<^|RrWT!yg5=z7!#o( zKg=8>?nN_~#EM*43{L+PuO4IUAAO@n!TPb3gd8u=-WZzI+wo1lDUXAiZR3~1;zD%* zgLpWTv5X&NWutIDIKm9(jO-557etacI{ZQRzG;|?*f?((V&Nql?be`{;){4CY1}S> zW%nyec!hmC&6Z5aF2t1(-@NRT2Fu9D(Ti^%S#ula3;1nJ-ZQdh=cjlZbAQK83cV6L zUYv*KeYhGz*R%-F$%BGh#q3Z|5#6TilWl~B^i_4a8$SRG-O>t&%B&YFN6WEa8_OGK zu+T0Z+{JI^PWFT>Zq7dTgjc-6vo>xUwk)_`*(+eV*+mG+usXEnS?d|&$6k@-hE5LF z3zJbG2tQw#W!8$}!MFXPF%V2`K1R{H`f_qqeTI9;r5$kR@%rjA+bSZGjNnUPCsR+* zjF&&sBd(HlIFatFAOTUa7C;IDTbdfOFKU3|L`awN_z%q3{q{1Q%=vfGQ3#RpL_Da~ zZ6kCqBi{28;cD6|Mb_`k9iDQ|+J_2p7Tio-%Ey-WGb2B9(`*x|idqhZHI{|htM2~_ z;YP?6pgU0N@1K&24@t`puV))|N*D@Tlx#p9uxM}`&Z(qkDb2i(AdBG6yM$NRiGnIM z^$b`o$Cc?|g~eI=5m)g}bgQK7F1`i}yxTtBM9@*$s7BXNE~(Fl z|L`TdwwKN;Sg~P!2r&M%No)$@utN8h2XD9qYJptxw>`3!b@ecNUSp|hhwcPxU(AjP z9~X8!V4$V=(G&=2Be@;S5m(`4ju`iM(wp?C(@~+o(ZbR0tt}AT;?Jmx_6us+ucnKu^$Z09u)0-bBo#yqqMEP?mDE}CAEF09ski;PVW-hyEfl-W6+p~*L5x| z7)8F43;-!;Zv#HP_r7kazHB7o{%mbYY*CkUv6>M^lb4py^C*ZhRdB#ru4JdYUPow* zZrftjP=7|`D&&mkb*BEA4at&Xo($U8PlkEO+E#Xf#j;j)qJxE%8u8X181Dyhh7;u) zm0D?A&nhXA$cku9xgaAgF}Wd2Jq-0yTKRQ+4pw?!!&35CKArP}#^?u?`$|VLht?ZR^FH?a?geNT6r|%4SWR`Ym{|#E=<%y0t~<}o?m~4>SZCV) z8-Dvst^m@>0Bc<2dB#(%v9Jj;jH^oEu|0Bf1i8NgoD#ZLEv| zEy)WleA~=O-B(S=1ztwyCt4aX`jdHL*+fjZDj5%nl-eQTYHx6fzcsdShD8`ShLOM} zCT9;L9w16FBZ@F==6ZHjipmc=T0Q$dF|qlvOz`*uF<5hSdi15~`;<1A`lDS3l7OP) z66;F>wdFF-l@htj`wz=yjX&Rkcolw8?#J&vXZzOd6es5%Y}n7u3Ag`lih(c*+>ME^ zd(1m{;$7X44{YW(Q2=YVGh7{UwJdap2gmISs;TZN+w#%zqTmNuwuw*_Ryvw}Hg%MN zN@z{h84H6Gi<|Add~QnRS-){**@Swzg-MB7&h3zlW%kC`l8+i+_*d6S=nqbuSpmn7 z!h!M4T5x#%b94;iV+~=g;nox7iKxpBIWThfaN#-&!LtjBg7m%pHpluMksoT6waNT4 zNfoP~rOw^1Cpqe!0h0GNzVDGbf~N}=;zJxai<>Upx7K3P*NOdrnH{Cds>#(y2B=Y_ z@g&~Di=wriMU1IAcdw0ER<&_A3kcKbbjzrECa$y3=xl~?bOdm>%UEiH} z)7pMfl$Y$FYy+3c^MI&fLg22nRDZ%ZA#Z&9Ocvkaa)V?cbh%eFLd42$4Mz%+QZ7;X zvuki3?-(V)?b17(S)C|}$l$Qcw8o53(dW+^_ky4@_pga9Qy}v@@Nug(Lg`PKiRp5N zSyXxYM|fcSa!YiQ+M6`oX)1k(gQ{`8B0Z**(VIp%oGi0)Bnn8gKYO$#v6NO%ElX;~ z%=i=(vvkSPh=uzg+kA6h;7%P=v+vjYgf5IEM~}(TW^l%vnNfBxG6GSoM#ypnd7kHu zaBBupJ2x}$K;|cN>08PdbjOCRxJ7p62o>JZ6ovlkh8^Aqd8xV_*GpeFEr-|H8MxxL z|B_C-#p3{H)8T8d^k?jFzI+w0j9g3?BytnFVN7F`296UOkK=2c#{~Q|{h^Sm?Q+PP z!x+T29E0mGh|5d11Rh!@7MbU98wZtG@G39|r zyUSzppt97-*e^hT+(G_6ecsDkPaZ*^fn&+{L#B@Llnw_nlNd~b&9Zmdx-3llSn*P_ ztOXuYUOtce(n*GFNYz_gv>5*dgyZ{K8yUBBVpxetOT9{d+@L6s~k%;?MYy|w9{#vvrI&S^h6`e zC@)lMw$q!->B_F745;72zO%wcrwA$>w=s6fb`{!SRI}n%`)834xnkK{n zYa{MDS5nfhJlm8=%xy@XKzL_?c@W;SNR3r;TaesoIU7svJiKy>IeptY&F&d8g?oQ&04uFVTh#VxYk<&fllbr50I4a!xw zvv{zUVNpG#ab~b}rX2hS^7c5yB6R_Wykz6C%kbOl7tDQoJ3Z{0o#4w=?w zJuidz=n?2{i<4M@BAMn%5Ks9wx7LorT1AX*j^7yfW?}rArhhD?ELGIFMP$e3-OYQ? zx=hG0|HMMXm$@Fk=mSzm>t|<+{lF?6Vyz2lnd9#0+9Tex2WvL4X1j$kw|Qs#E@ibcG1b>K7YByQ*%;~S|4|ze(*~@KK=eOyhv%QEwyo51 zvC^m$pTj%A>kvob#0>gI0!2-cz5Zf;T*hJdrNja449vcP*PYP)ojCi~rJX1XZvr)@ zb>DF86z|CQnW{+68}VDpcO2}&M`GqvKf)9#2?P}?Xp>K|y zY|uoVvFVH5h$9i;mu0zfm2%szIQE_FG&U=hWU<{>f< zca7H6Y5#0l?$>dxRbx&jYmB^m7jjB6s4X%DyM9Iu-k*i#=GpVe~U+opf!Sf6m%UMMz0}qsI`wJf&)%&lkU8ARTjX zfTV?zGo~>;VWb(a$`zlyzMLuuN`{49;?}TqzB=P}?q;`Jll2y3LnRn6Y5cCywsS7_ zhG19o+G+i<1qwA-n$F#AY%^x~*)h|HwQDD>Tu1GU;|E6#@tPZ4ATIZ5 zSmn_(SLu4$8;jWr3>nf$hcb)JX&E3~m1(s`}}~ zX^{V^MgU#;-(yKRB`Svmq9)v`GD`-iLI>FXcD4O;EEOaL1^@42;4Z8key8Ob)$GRB z>^3Y|?C$F?pyw5(D%H3aP)7u?(E-~(#!cB!PeC7;NNB4q0v8-=Xo0h(_er&M77o5)x+A}_7lc+3cS~HHZ#Aa#R40naDOYQv+LyJi_yuH z5|d4EyUFprY{pQ~;;nqj_}GJ``68N(1xC}Z<+|t?jQ8`G^bf2?>q#z)iTT8{ux5&7 zM3iejEO%aJ&WJ?;FEvEAcLDggdW`P?pRS4JbGR7t6QJ)wZXz1+w#o{Dg(mV;Am^;D zv#p(>g)QA5f3mE90hsp?vynh@#Ju-y0_>dt zV`uMO>idyIB9oSj<&@Ago1oPPe6S(^mDeGooCp4X5fw^mk0{;9Vf@paFf}`l;oci6 z59!8T$GF#;K{yoRHQl10w0N@0R@9Ni5E=5525Wk2OuA$!#%>^)X#}dIZW1G|;QeC^ z)Rrrn4|ZH*qC!rLi__QYK3Sazr)S|(zjBGnJ%euDYlG#|=Hd&gz%kOU@>prfD7e7I zj8^k^`Aq6g9C?g@+Csq9%^-+7&N5agH5Bkd@MZh*%rpHPX$0y}y2TYHgC5&FtLTD; zspHBW0%g)sn&A2Dd3KnF;U2=b5!6?1@lt3C(Thl0(n~AiFqQc-xwiD0X)_NJz&OPU zRJi)8hwI}~gs2xKuKG06<5^>$B#m<&i+f9=Qv~u7!E?$8<}?~#NR$NNvjJVTE+rAY z2M@xMls)$588@gkW&!k2M5sW`XaJ4{lO9B0cA8Z&C9` zH(OyAFl;VyE^?HC7{63@CAUVA)!>@S_<{{SV^R1S3v&BtJKy>3L4CIuXC*zu8YnGA_5&xD=y_OTQf*9gC+VR|@J}!vTe#heP6=vSO|p`ysZ0{ok^u5 zCaL`xYWOQEr^3SCFNlxj=GLy+)JbtUEsbuHvlGJ~htNM=2Y)|Q+D`8%q6#fU!wifk zBlRBt5koN(m$Tw)_0UB(wJZ3^iI$U8Tyxp%u&ANFaqGC}3Hy$kZ~T zCyajiP=94uns(!`*t2NKoQ>W>`^LsWf~2X>DC;)OM5M9LNOASb9w|!2*6WnnN5;{# z*BqkqLZHNDQl#>LBFEykIwJ22BH%MU%TlD8QW3NW1K5$TG=VN8!p?RnWA(d$kauGy3Y`dj%vo zK=x{ODXOyuY{Th5Zq|DpgG`5AGZzLT6Qc1=r3m5YNlnI6HHJNA)ta$dgNBJLPcMr% z?)<&|%8ij_3FATW)UNSO5GZN=O(D7RI3(=Ekny;zk>H`vL7Nkz5KV*DItBtDTs|d`MrIrRBm42CmW$XY8(`c5qNA zw@tR$qU5^D$2D}i3Y~oLVtm7G3gC+Z(-JkW^`BVqA{g_uOA;WLZJc{q(Dng+dC4>~ z6uD@eoL9o_fWLRB13yENb?1hKe8;)wn?ZHAfqn9-r>Gdw7&>b;PO3X)ImyQ~GPumu z$FfOB^r4I1kB?^e*`LxLnClvG9*v#gctQYx*5k{|x6{}w+aLJ13oLO^hCb>dcKO;& zaWf#To#?ZxqtTE{x%!uD(8|OO!S!x-T`kqMG>u?0hiQ!WnEDI4Fy@X&J(x(#EL(NC zrL}xAhRQ#;4Izhu6IG?X>YJh?cgew=FKY@aHYzro_#D4=Mj_yJVynU48IPx%1}KvW z=l5&#Y_svE7(2!A{|q~ZxO3Oz3I9NLjH{RLqOSjZ)lV`VEaaH0z)8sDeaG`Jg}U_m zD(AQ%)@Ku(J`}w&ycyg0S!{kAAB3aUTI7Zq$Gdmk1CQPKT}w=-pxmal1S)Vu^3{VR zFMZHE%)_3iMpcnrDIPr+pa@Jy`azh6WB?I@Guk5W-i{K>A)Pk>&kYkn<#gWnY3kUI zTRvf5z7IOk`k4rQZ`*+hap#pJ!w1%_af++y?Za%jr4{;@(~S={z1#fsjYd=OY%iwEa#4KJwhB%FGzt-~xV{;E*) zkkr#zj4Oe`g_=}~WG9|fr^i7h=)U1-^XlOmM#3d(wbhu|Z>rj3$I~Y1)PN|HCW=Wv zHSh*76mo+w`w01Wvm~nVhNu@VRg7XMNPsK+eaR}VUn}JUf&nQ@za^z#3aqR3o@6Q>SXi8dI zXq)=*0wVFR1}W8z3o-ZAy$^1rD;t8gSaNTg&o^$C&JSJ$!aQ)9xECmv00xZBJ7cYJ zs6Fuz7K&bRzLqaGUq<18s!%g^6~VCRBt6vIsDF?kw68e9sC-rp6;0K(@Xip5Tic|=k4+um6xz(_r>isbTt5^xl>kg3 zFSEI8COrGJv;Un&gQb!xw`K|1Za9D0HXat-IWC0y);GrLAN8Yn`Hc4dk}0hc zL7y25-INN-(Y3cQBb61?3{}#;f0O5Vj&OSwM>?KAde;P9A@>7O5b_0;TPi0@Lg_%( zyC~Y?oH2}8W%+`>+gN7R#8J|Qy0G=JmLhsgy_uiOWtjI60&BJ`TT%dI(o@|e{ZMLv3;(RHf96M!8n ziAFGM)W^-q35LG|r{eK`+&`C)I?h`rJAt<(c6IGWs9?X9mfUB_s?fScZjCMEEhMj+ z9^Un;(RvZgg-fg>2HnBz+)Gxy1y-(M=Aw9o>`;hniXCiD5%VUx*>i}ot(zfNs_oYY zYcv+OwA;jQzGuNinM*zz$T;PQ@Zym&z*$KX_n45_9e%chfpy51IvTCD9+L*(qop44 zkGDyVFrB?hcw+*`O-S^7onJdZE=w+PS`j5|4Zl+q#R|a$sTmCi?uO8X?)X_xz!HWz zm=V>i>4^2jeve%m$7d8Z2qr@NOeQbz7ce)FP7{He?T0Tj>kw5azVfA)lBesQus7R< zP(1&L?kQb5j$`VomsAtppV9@KJ+53q9zm?42qB2bK+s`_szt$Y6tpf6^N{6y?}NVk zwtSdR=A}&;Z5-L`h*qoJ$o%0ole_e4OK&H_#~qf9+ZnOzHt(Z2W8m$ecxkkt7h0+Z z2Xi`ng4e5UQ)VInGcO8qb9y_*$T%$znw`Qei5A>8va|H6_}xXuCEp3#T--Z-;?jW; z6gMa}NT}CYI4B%}!s!!!VHz$n=G!rlKW4KpE1BO?)H?JH@<&%WpkqX+*h$;Q5@!2) zzHQk~PumnGd$8EcoiVCR)C|0)OJlgdd>K@Z)NfezxM`|C%z53T`?aE*kh<0-pXzPP z6|TZ}169TkP2?0T-g2`^dO`A17^=SCudg-ACLs&P2fu@baX`1ie+azLSTUPng@PDJ zWD#abOe*Yo^%?=4pVgsNbY`!smzdlWSV#yC4A=P2J9q%EfndN#+<(7*v!4ej0CZ=E zpGW=ypaA}(U-o$bJrHysf~NzkAb$w~|7Qk1C+v-r#p}`k*M#Ec#zi zz;es~i27SHJtz}2-u;Ow4EtZ0AYt#IRM61$pVU8I!obJ&zm)zhLLHO=8b|c=_& Date: Mon, 29 Jun 2020 15:28:16 +0100 Subject: [PATCH 4/5] SITL: add Simulink heli example --- .../SITL/examples/JSON/MATLAB/Heli/heli.slx | Bin 0 -> 55317 bytes .../examples/JSON/MATLAB/Heli/heli_init.m | 128 ++++++++++++++++++ .../SITL/examples/JSON/MATLAB/Heli/readme.md | 3 + 3 files changed, 131 insertions(+) create mode 100644 libraries/SITL/examples/JSON/MATLAB/Heli/heli.slx create mode 100644 libraries/SITL/examples/JSON/MATLAB/Heli/heli_init.m create mode 100644 libraries/SITL/examples/JSON/MATLAB/Heli/readme.md diff --git a/libraries/SITL/examples/JSON/MATLAB/Heli/heli.slx b/libraries/SITL/examples/JSON/MATLAB/Heli/heli.slx new file mode 100644 index 0000000000000000000000000000000000000000..74294a0f8fd9e6defd06b704f3095773b6bfba3f GIT binary patch literal 55317 zcmaI7Q*fwJvn?8D#kQTS*tTukwr$%^R&3k0ZQHhP_C9s1_J4NOdHEi`x6xyC&z`e; z$Vmc&AOipZ`~fI;-;(=BK&0{t2mrtg2>^if`&U!Y*2c-$#z|Mn-Okuio5s!BYAD6l zc7YClxJTl!rPO{8RG{>VsVS4m91{g+pQN2Vb+G(r%w;)QcBY6r4<4upW?V8iw`0dq z#_Rs@T)5&8!#i$SYVE>l5|OFjWFA@Z`RvZ+F@}U7V2n>aP_cQaH=$zf(EfssILWF% zDVe_gB@0|WKO{~gG{nW>f>}u8J%AJ5l02>lBX-9@Us?!Bw640(BoXvjt}Jcx<*xlP zNnHCPn?lXuL13?|&tr;{p_iQmR0#3jH1W&8(5W`gLy1$Gya=jB>=wz-Wnc`XT+^mf zHs2Qp7VcjegsUKliveY3+L#Q9^eyp)p z-gR3n8zfKjy4zie`BKjD2lhXgq%BQo2hKd#$L5)N8e;Nj06ksk$4bg#g2elBz*kty zaWCV&H89e{?S~F%=)HXc0{T{A3YC9PxI*;409dZA35J>go4z7^Y6skE5eD=gm%hAs z&_5Y@sz9b%Z;zH$9{Eo1O0?!A2`iAN&0}1!*j1iFI>(F}zi(!{uC1(s!rJPwBEl6i zc%9b7-uON2D`dwboV_E@G+iB8=Z##DVnjK1y53E80ObBdC}jJ#00zH8F#rVsfch1R zu7k0aBQ4E;eTx?5WdrHp!Eb8>-gzKf(U}cB(@8z)=s9?Mt2Y1nHy2)QK3`E|;?x?f zdIcSPzd)&`QN!j#^2lLT8%gZb5dumSGtfLFb=KsPx)Rf&8i6Gzq$LnxB2pbUs8;s2 z<0{^+gU|?NBq1*^!zE#=`~yHL$1JL_N=DV&Dw;NjsSLt4M-*;RYGD*(WmGe!P)Fme zi|?gGtmHp2QzV=f07EVPDhqC!)c#UC_yKt2%8-MzP^3_yVL!wi95ZfRRn|&*tjO|C z6=e1DJLVhGIhzlXf_UG^7P4P7bUuFLlNzI**_o|ARB;!|epfCuk6p|@WrRr9Z#t}O zgLprcf68fHecF6vZEawF7Wr`VNFK^zBzcxH_nN!jG@F=<63LcP&dTblaM_O|#mIB# zQcIe0^?HcJ zazGks8s{d#IWC!xkR;QN+7HWSYI#I#NtG1}PEzPlFUwAPT_C9-aV}C$luozZhUlF3 z07KfSh#YC2hA1z4ODwGi`_Zg^jshua{wK^Y*rIyt(n3xG%LW22H_bQzO}(=LKvy`$ z7(+YiBwuxbys}wSk&WOLo4I>^=?S?qGG*O24L&S~0=^Nt&91QnCB+IO$`E`9KCPj{ ztA<5VFxKI;MfXe@5K#OTiFAI^Lo?G4m&YzG{3z5Bgd`J5vp5v1gr<>0mf^nHvAuU| zs}>96$Gdn%QEK;t}6xgeq|HW8gnj(H|f7N9DBt$&PC53FXi)E26&);rvf_ ztX=;%KgO~2HUo6f!Zn0uHAilLA=TIFi^%660V;(C14tC$mkPVRxt(e^;z4#ka-Uzb z6Wa}wN14tAS1f}M*@fDp-w!-IJeDOe<@^SN3UuTeIXE)$awxl%Y1A}@_%f!EF6LD;A0Gi`umLs6-I>KeC1+|)9j8`C<->a zKJyN+J3tq|5Q1j|xbc!A+61J6sE#8#6K+K;s>NyUxE%Z+9?8L@^N+ji?l*~@ z$pzEJ!x_br_=Vng|f0-v}1qx_T~ z>%%qNe+IyJIb)^$7dXvt0LcGe0Z=fuGS+uA7Pm36{jU%>$4J5j(7^}Yd`2XD<{^vG zQ5+3VLEYICqo@#cN<|Lm(k6>`x^1M}nz*{(Uu(GK%|FeKG@r;})zXI4U*FVua}*QT zBkAAa5ZL7?%DuGkJ3BBvF!k}rEE&s1heXMXkQlAzFa8OVnuaoZh2veQ2+o0Qvv{>{!jc)X3o|IHu~mPGd`Z0+S{Zp9#10><PATqtRXSQY~;H#I;l@igR9aFc#yl3H%IE_^e#uN zYsd#J=q37jz);HI68y1|zwxHF2$#_Zsu!xC)aR2X=J}^35|#+2T6K)>_yVVyux;Ip zogHF=ndphq6QNqPMfHPNHs_Oo@fIS809{?3XnuiWeqo`-)m8fB;!UDCAg5-BbH&DRgA`S>yg_8o$cQ3f;~9K$+M^OmL@1QJ$b50u~#kCn7+g ztn80{mu6XkF-OC7HMK!$(2l1EWO{mfa8MAs123Axj<<}c=*juDPZ0T}#?}sAv^&8% zE8XnlNy|N?f(a^4rFzEBY@CPFp_P@@CpE)-A?Nqr?7PPlv|)Xoi!6%ku(E8N~CGGU*N7 z;VW3z;OFs_F9O2rE**b1We96(33O_piVLi!<(({Pm2Aa1vcW*~<(2$SLJ^kRkN(Yf zy`!O4&zY_!prVe$iAcG~7CL%=QvwMAcnJJ`2dV%*yaEFQ(o?#f=bD2w5>Ev9>#Hw( zbz3=A3}JfN!0`$zt4wse9OJD#z+qo>fi|#AY$f--DBHg43eAGCZUCn$td+hQ8Mz^Zz0bN>Qgu^1TN^Y-0tBiK04ZObia+#5BtM) z$l-VMQ3PPdb1<7SKTnuA6RWGsYV7+Qrw%$!PAGt|jKO9zHahTt^KTlVnApvJ;}d%# zXy5)!X;33>VEwqbEv)o(WWH?Xa)yqy>J5}3e=ZU}-!GpqWo}NdCUYVE`}-T#Co#vk zd5v3CspMd;9hJyHaOG*NdwB+E4(Db{Kbq$EZpJhXwZlI66c!eD z6ci%5^15^m7-wg3PEObx6>_7VWU4$}2^CZ{IiOqt2G39uT`zly^%AXipi_7G%h$CCq#NT?YdS33u8 zq&l|I1DZG2M47r*Fqo}DlQ0`|q?@s>+{ zjvX>+g+?i7(0K76PCIEO)kTPG6j#12t5QXAlbs|G|e& z85|zsreSUkN5@nce3eaaYidIIH>^i<(B_o$ZPzf7a(`?mqIM$DK~b}k6~PKZNGh4Y zKyGa&cCr1LFRzMmJ00ckTQRO|EHCdOBcrF9n$#8KYLHWF$5o${ARsmwJT^8)fxG6x zV%oq1iNoSQ5GmqC?QP+Rwa`yUgbqGo66X*RaS&Wcx9SWCG-Vzek`3=bB3^;p7g?2DWI8jId8eU}~G!`2Z=dv*i6BUM(*$mqa^bMnWK z$tYIqKk3^x+85OQGOJi&lHPKaLMN|Pq7uf-5ULWNu~wS|P@JB~|7uZYxAtYo6K?_6WYhzn8cgGMz*zx$d=0!a($gW%p`W(hL7&!%e-_p- zj*+irU)SG4G4__6~YXC3flGkpx1U zKZ?GxchP5FTeysLUu;Bi96H~B@l_gbWMP)~GqAK&d>rniW7oKGeY*9Vnz}-sP(?<;(8 z+kTZ7_dTu9sH~GrMqzC)W?Q1cnueF+lbF72p?1+nf6d{M)>Gi9M`UIoiA@2#G%+#) zxpKd`xq*w|l)`VlMFm1gPE0&Nf_DRY24G6Kao5(ydDTU*rL1h_{;ruh~MgAniZBw$?d{x)!MFb#8ZHza%%ix=)`Xznp($zx$Y z21M@cMIGyPwpE@O4qtg}e95DU(I7&xR37<;6|cNitaEoVa0Uq|#cOZCZwNb+oX{+8-K7}QK+vr-gyeu-i+(aOCcn8zjsHw-a>VkL_ zePe>}hL>pg{*j@4wLlLbCJ6st0{!*3Sg-Su2I-#&PT)Agf0_D%tr zf-I^?L09K2UN({fd+BEU1Af}u+v~9@D&~$Wu?q3h#yP9?ESQlU4-F+P{aLJkpj0PbCO-e#R0nx5{_TBT0<#qh?cp{6c zgT1+(KW9K11-DLUXeeDQ!D5qe^0FB^2~O{HE46K3Eadw-mCVw*C-p5h+zmnBv&(fV zUo|Dqbc81Bem*>F=Rl2Qb#1D|jvDThjZX2A4Cb7|5N5~C_w&7_ zZ7S*r#-Ba)1FJ}rMD<-*vbKpEasAWF&+gC}w6*>h_=)}fHL45n>A|YXE&X0*AU<0tL&lkoQA<)DL5qXFfM6gp zr6m?OIJgP{Rjsc=U;XJtFMzEV5HuXzjc9{Rr41-GlH&a_DH6rE_jV&Wa>T;gTNs(( z+2P<)&_;4l+UvJw6|#V@FI+}`B9gH2DHaA4l>BmGSO}O^oajCn>u=wLt^lU2j);+N za5=ZEpN#`5p(a#B+G(D1u>+IR(rf_E`Uhz-q9dvTkJo)aI>Cr`a$;k42_i;KM+Fq@ z;#O|j^A99!u;U$9ifuEoDif8N=har&y)@jHd1EwBBvRrS_+rAZM87fc{5>K97Lx_@=olM zv7@aD01F6^=@3o3pYuw5>;?a2(D-u_ID9e-%gUj}DP8^-Xr`@a6_c%&k*83#i0b06<#}Zq44ViHb=J10}2*=$mYfXe`17k za^9CJGJOK|z8GnwYAXsbpLfRqZXW6ZoI$Q2Z^~! zO_s@q_yI7j*-iwZR-&P~QkGV_(&WI2K<~3M(Aiy1jUCZtbI<6{ilEc6zm+TX^v!Bje!vSx*q+O*)9&I@v@c1?;t z1xK;Ev{0|iTc;t;FPuDMfrC}Lx)``+tMK|O@I*c;3<5=M@-hvM_UbVlA9u61*xwzg z)>bz*%M7>N+C?DMFb(Cbr^llNYBs3S>Wu1O!>j{}lbKmuXpPaV?G4{-7uPFHBgQUM zZJ|%ZXJzGdqou~dm$ShDp`*?=8pfOb<*Z&#B(r0~4vfv+5yKa}Z2A-5W&mB4zLs2+ zy%n2(^)@}!pz>%vd|fTQ10dYc_pZeMH3`n$x^SwY=@LkDvepgq!eIXmr-TO_bY=|V7s$XTBfj7U2bI;;=skk(~y0O7n|2QO}Rr4>;q@G@h-QB%Uu}I_G z!lEMD2IlQ8?}JA(UyVGH{OEj(bwtpTqR<`+>XO$IQOBNUywjUg9mPnCmshi=2KH1? z2J}j@!&yzG{NKKln6^2XUCYhQ4^U}6e5MN0Jt-}#tEZ=@`?QJWn)0E+OrKwTpdr|@ zBc_z1Nge$yx8m;j>-X13l$6vR2F7S3ocHt7NWr%cx6tAg`eQ8w!7&d_91BHrHv-(M3m`p(xpVs1g?LYiukkMYj zj@ybmD|GMkS_YnPM(sDjHQ8Lnp6m7N7dt?st0^RmJAM+TUYZSrYF=uQFD+rQI7Z3( zkPv%Kv;aw{h~;I%kE&AvgKDlfFT*&lzKrP$Z#X)Uo9E|7%8aX$9MqmIkvtD8PyohP zInPz<-Adn7VGQX{^5x*9$bEMz4|>kV98$}&YCH^F99smY&C4Z6buDb1l@ALGQeRog zgO{i~Y`Kwuy1PRXZN8OY7rK#R%AlaD>q*W|<@JbU+aR!5$*z%~THRt1aoR zT{D%&V=lM~b)iBaBC@}42UH#hjt!jPZebNsdYN)VTUzdJ;cJ@eT{Egg1Z1I{y$ua8 zWO_BcsI=HO%|Jvz&az@MsQ(BDiHL>VnW7mP>4$<6qheTml~iwZZbH3{bv+|vvVnj% z|FjU(>T|Q>qC~~U`j%8l|9KRud6R-23Gy^NC^AT4n>;4=+59pNS51p1M6C(*nV!su zcm=JFN4S%&=MU_fuYEn0#otRVi(aABu2+{+(F5%hU zC+s1f{ff|OH%!Y;X6kJ!4|a7tPD~ zrPJyN6E4a+WJTf>HO5wR3u8i0;z(lyC1Sr9u@tV1VKL=%^eWV#cocaO0+bXdsO8^3 zd_DxHi?##HqN2L#iL0RFfpzVF-NHrrkssdIq8D8MC=BXGL_r}a0@4u>vXums=X!kP zF|ZDdaBgZ|GJ}G~JQN+z{;*BM9jbcc{>|7|Qe^bu6C&2+NUm5Ww^$jBa!rh=oaOHg z^TyB(YlrLG_F2TezRv7w|4e@^M{s{_|$(NCe1l)8KC{y@M}?G+RFN z(@Opt4G5J9b5Wt{Kz&m2jTDK31y0$AZ=!$@g2E%nVk6JEFjo{T&lSzE?LJKbg0%va(`B z2@u#v{Pd_3W;C3XTo+q!XD8WZZ4pvyXFrD8->U@j`+^Jn;~SA>&yGvOt=ry_clad$ zwV4nxDE&O29x@C@vDPh528)^3NNnAxRJnip${ItpzsLC8|DMj%f>AWp{?@#$Wln3B zv8+5hSZL`$DHIo^#YP8$MZKz{(?f3L;d6Gb<2v->aXye*?!qnM=nu`F?Cl#r79I|W z{Arxtm#yaUE~e$>B^$XidFO(=zR%3*s`f+!n9keG!jQg zRSM}!$c>$VbK}$d41Jr736R)!LS|Wvel`tm4VhIu4IWW1FmUB0a#a@vd-cgDz!D`y zT}*c5qxW4OKAtBQlkzK4Zf@_}Jy8%jGCGDQM@y>s8w{HS-|f!MVt5AFSGfS^`{{XG zK1SixXCt}zG~D2A=(l>+CZOFnk$GxaSlL|5dsa6xjfTke4LQ1PCimTF&Q-R{ITKB`{CT|sZKOBo+Xrgu;?-|2A&-GBW*6 zPBMjsc+mB9Yfl+qF|1;`oqo#Q-}3HbZK$DMyoJ(L+wWlDL_~)B zZ*Oi77*MG~o~o^za^;Gd#|WcAxf9Hk1JVPhV+YgIAbedV*qBeLh0;=^I+}L#60aXy z2vISbk&taRrndAbLM)aq&yR6(gePd<{g9%*jg4Gr39WFwEI;0Kt-flu^$I`5a{Xvz z^&2DKh;`_vF>y4!nw-2w60#%wZNRae`7}|PacSgdo{TIg>^#-mJFWmra;tOJ*4ELa z32Jfj%HG6rcf>Uum_diFK`Sf~j>x@Lzc=%3U(|FLmtqL5Dzi7fXRq!9(O#8vkPt3s-V zyzg9VF1eg%P0RFk8A)!TZy?yk0!HA@ur{#H(#6HWAMU^NgU{p+iyiFlpiWH>Ay{D> zrlpypO@z&feVsa@UKi8-d|%`|K8I&oo!tDya^dDbZ^p_*WT~VV zVvxSxj4l84PD;LZz~S%$z8JxDa~eKd3k*nuxgGB78if{V!>V&Ptcr0+EW`Dud%V^qcASC=wYY}a1nbeO;;t? z1afX$m@!S?rmT?6YGFlCZ*76?Xkq4V?~Fdqn)(D zKOy}&FE_K`S(u%DMJxCHs)x*JUb4NL!o*BqWLDMr(v)^U8murGIniW4@V_D!0;Tq` ze^ah-SyqWmMisWPHQ)+xp`@VI6=mkMqH%qM*EH5;@NX5F&`0BaXed2pTzr|Vyk80n z8wFac&)hg8lP=vmmLn%RfRlAB-|#^(<6rWh%%7p3i}opTkA7%7uxiF|4MDVX>Vez) z*tczJsxus-Rp(0a0(Eq7P)qnG(10z(W@OYFF6wJqEz;o=Pgr-9_*Z}*+6Yp1rqe?R z9VsULRQRmrQu0rZN6W4ZWbXN*Nv*inqcZ=^!*kc3GI!?*Gg|Tn3eM(7Gq>%{oxbk3 zl&;{5&fVQA(FW^qkDQ&S5F=`ubCD+4^IcKI4RokrD?8WF)=v@kAGyroP|J$l75O@n z0CX^DZ$pR1b7S`z!y|~lD=;z`dY9X`9`ewlR;oukE#=UdYT9SfjD7h=E>J}Z)-tFnQ+Neph>Do*3|2VJ#DR-+5$gOQeWHb@t|R4 z#da&KtPK?S{B%cll#|m;Tcbz@3B=B2<41-7e@*%mOwX(se1L;@q#-Z;kRRuiWypFjRWz8M-Ba%OwQnK6!icIn|tTP}0Tm=hd%CMYsC zw#=G3WnwZ4#)dhm2yi=CHR-|b{(Tc;Wi%P``AEs#=_;G<@=M~*nkN){OZr?lD6y@5 ztEi3aqDTv!xvbLWma6IUxgOv;zxcN$DajOE`(0J}rD&DtKd9*jMyF-K_?LoH553UH zXqsX151iMb%%g(LD3a49(*BZ8U4vqlmQx7Kca?@e?7J}!vT?VmMV>)Dt7w@9B%o$K zHtz7fFOLx{6nZ6cZM}qBqBsd>4`Z;$X<{*X0aw4QM0v&j=R$Ii*Qys0t;?MfTB=|P zOrhK8KYf!su@?S##_Of9ryj|GW4kvir78 zq-DQ+x957)p*^qfHB3=i>{nvawSn{6_Z(IA8m)`~kz9vyZ$=btGUl?kV7Cu<=UR`X zwr|4YOs3!pzitQcO!5$?u>nXpJ9b zIR~PC)g>Fu%DOH#4-fAw=9$qV=>u09@IwgL8s_v-KBAqIQcRT+T-*vq;zwUOIlA=M zJF#Ay>))P5uYyh8c%vxBL>;(|XuZ?M$F{GIapeZbeXX;GBg)H$CcB~0Sm`rj%cQ+> zpnW+r+yO2aND(Inu${>|QOe0;yXt?ldLo;yxG#6X9y(}otZEuw;f@ufLQ z5RD;s3upM-g$MU}Hrs4qPdlwZBmFf#SNAGp(JLtMX!CVvEc}9-DjM{Mlk=;rdvEV_ zQQvVll@N^eG(CO51p1RPakbG62X$?z#tO8}N4Mbs@%@&HNHJ9NXWgQCYn6J7)KFNn z;_Or?KwtX}>D+PFAIfZTb@de>`rB1ir%G+qI`r|@?gH{9fhlIExQM;IO>XaIHdn4M zHrK})d7JT+@z`GdhB2S;QSZAzr}UC*bdMh({*MY7IZCg#-l>FmF&Iz}7a~D}%QvS? z|HomSNtyRYN)^D{*9W5-G(0&Bg?Xwrx7UKD{``}Al~`v=pY&N2E6v`uq{(sRnYlX; zBv7QhSqs5SpS~@scE30LL>6o4sAelF{s*fTCZ@>>r-qhl?q49u&ROzTJyo{w~=Tr|N6AONDergX*m`IKLYc(*?G9WN-i;@ ziislUb-xEGK{@%@1=~&YJ;6A-f}4Hv!&9>JVrJi(L%4U!qFC>kApdxZY}7(B$aS+e zu+Zlh5GlrgV7?75W#ir<^Rw5|a?`Z5G!quqt3*!ktiQK69G{bA%sihF{1^XDwyi%o zV|-61S)#I4{Y;G@mXw<)ZJ3{UYEwzn@5R>DaXArP*%O$pUE^G}p1RgifAkWhpB+5v z8eDt3cgE@3Ir|c}Uxd2s_&aubi0) z*{+EKTk~l(x5fWd>`!XgT5>rNwJ`TCN(W({k9#1VwZM39V)FSqA2mNuLscoQvH`+V zo?%M6(^c{CFr_$M&niq!oUN^IJVb>L4?9WvQx6r4h{w)8;1yvI^S5OnKfg0Tz>?$m zIBr3{vS)_x3YzR)6?iT-Aptb)295@GI!OUoIj#Z>D(QIy6_u;U%FfQ7J~C1<)EUeo zMdGCNJ2j6E0W_dBOe~TA#2r{iw}pl*eW=vW)EcF`Frf2uLbYZy1bVjO7(Ke3NYI>a zX22#e+&<^wS@fHAv?FlYyN)Lr0RCPC0Z% zt=C8R5^ws~(zH|yjbi_v%$YWC{0@InIDoxWOWhlJ5;>QFsDU4W9$l{d{&g6|VS9Lf z7}v*2jT4YWPYdkF#A$NB07^mf3oa%#gL^2MutBx(U25uaCXt8#jiV3KMU={^G5fU? z4<9qZSv{Bxhus$j8=Ha7->4{o{e}7W%*{9fo|DbdbO{sG6dttX?pX{?m}qLP_hGHc z@4d-s{_445x3j?VH*WlBX-@9Usyn5i*2(ci(Uf*G>snQ4z4E8rWw(!d2=&3tl2Rr#WM>?u9uds`WvN8%jJA4^K0|SA0`*@Zf zkKNCo4aCQJoTw@G0N*;(hoRC2Ns`{$hgVh#MW{e;=W%{Iq<$NcF<{{3`+JhIO{aKW z3%hj_-T8Uk&#V?;FN`(Y_Vt%+eFu|}QgL1T)BM16gbTCffcqj)-OuuZxW5%f<*hgT zyht>1{)1zr%zSh^YXNNf_N z1s6Tv9dLpMhZ0YY^PZn4xN3tKn+0XpS)L5;er&mipVBIaEdH)0@tjb?Uw+IJGpTz= zRy|ZL)UdI!j5q{%$8nHXuuqE$ra=BJ&`u%iwvbh2;AjDo2?4dQ&_b~2-A6@3J3&Ty zis$lC*7W>KGI8nU?Gr{ZUN|-V7$vETQOa&AafphHxFmUS!%9IU6J>4Z6K%$m=EXNL z#jTQt;J!~ydVal7x9#ieU6E=>wnj!>O4CO(n?hKd07& zhN^PYy)vi7zeW?1y=8Zj_4d7w>(pK3nm;OQWQ2G~u zk-hCU_7lqAiYy&hL1!CiE*eTwP+7gxWLuqm2FhMbwsH}N`FZC5D-^qLg?k7IT^R1gbzuD)6SgS)S~`26}QTM zeqYQXKCxs@acf`{-V7(5%4ULL1~IhfhfRmJ!*jjj#l^9eefFX?QqyW|$-sz#fJbN8 zYvBB$S!t!BW`@>cTi9>bFLhg%X_kc+DCE^rAn#uL*tq0 z9y%)0H0>+shGuuzN_Dg!6&Fpb~1nxTeAWS9B4f~FpC&2F>cvR+1u z+A(qe+-0n;#iNwDhIXp8wm1V@pa-_Yv<7as)PSacTw`S;?E=k)=0DOckqWI6qUyLFrC8wxf(F_v(yfGFFu1)q7{&3$YfRcA?7D*kCyQOn*H6XtFW2Ik z10I+wst#KLZ}RkAHy}nc@E|G?l_jRH8Klu8m1Hg_6F#y(uJ)MMKDm14K#5x6bm&U> z=zRHF!PRpD6cUQ?QiZ$(uMwSMv5*8_(KOm zm?f`l4X(1fUe_$4sjNI)U2CrYsdWfrCZVxktp`B-9~;E~(z>vbxs$EKf2qAnMba^o z54!tAmF_Vk*!%8$)u`BcT@%hdi_t)JRm#l`pheu*8_kN&9%;n<3Row)ah|N|@oKs{ zCt~wG+&NMCXww9?iJD5esKJ5#cUIONKieHaYa+c}jVEVntt?xWZe7LC-H&*4QJKC` z(X8$3vL#Yg3sBEfdhb5{UtXa6IZB$#C*Lsc9#+p_C2X~UyC<<)Zv%?l9Y~!Rp zxWtCC4_%<3Btmpn`u(e;>({Guc;uh z!W&P{o8g~!i>ROSs56r6wgRTo%u806@(G_SE4X_b>tx?3Z1NW7#sD;kg}1RAA> zkDLqyg6726BiP-G%Z-)Z>vlm#G&j?oAUb-;F1O+7F zHSV0apKpvDgS4)?ycyiJx;^S7Uq!vzl4^!YXu+kbp`2wCexh0vT)(C!52x%1|1w&h z`d@H(2dqW1s`F>~b5D8)N(mUHS@&VGht+=bb{fLggklAajn(tZkK$0>^>tMy<3G_K z>{A?xwigpfC>H^so9X)nh=U5^metJ)myT;)iScLJnWy~*%I+~!4%I7 z?Bly#29M~rZ}4;R89#rnt$3g2%2$q>^pPY^cj+PD|I3q=Rb6j2_vt&eP&tXxH z;#AnWhmOOmCAoQj5_a)n>bQ=t9bOWx+1uJav`2u zwIZNjm+W5SH$32$FEOMO)3&gbt%z#c$CLEuGHWqf(~>t#_p1W@bB`mJNwC$u)Vl>b z3jGHI694|Kn!E=^n#E;ow=sDA@Ke&*keDv7Z{!PlUPUiI$9RuQ zPk0eIeZs5Nw!|PmPk)2KkwdFVxlCvF%#mtW3f0;n-{CA{lA7)JSC0K=G&96#p^Bz2 z!Hx}gcv{$r(p{{_LYe;z8j^aq3_X@rd*i%V+?vzgcu=8X8b3NtxmAXXi;&>tutO8C zkIZfg%hkx=t&JN;OKM9Hkd00)5m=5{v%hwbL`}omf3r;pR64NG`IAnmxNxQDmD-MN zv-57u$|Ru_UfxbPuK=VM#d)k&Q?zU zZHK$kys*V$Mf}lnvAVej8ck|re` zP!kLL!L#4ZkVQ_b3~3*U(gq0+i^o7r9_7acj)UJG&&6sVIbj58l4vptT9|U1a0Zbo z_Fip&ThH(76V?3n%)_<@0tSIJs^OSuM5p{BWSQ#yPgEwJ9jHg~@5=Q9C= zXW#b_iW6q*o*`?0mD;_81cNV|EXQH9CF_1Y*H?BxXTsm4Qr(%s%S#>PSCsNavZ<62y;sFWf6}%oimg($*`gV*dR#V{&1IZ_&IV(;) zSZuT!n@qyS$9q80tbl0Bj#oTw(qgw=r6^QW(tfOobdBc1QP5q~nqndyh{L;p>Bo=L zFrWHWXd0eiUnPLoyZaNBN!&HvX?Q`&&FN#v`skt#Xt1_}(6N<`NNSasKljQm5#pIH zNO+s2B!JAdL@Ep+f~dAnRJpzE4#LOqNfNHY3-Bz{f!8M;K^Q_=C%~~jPzv~4tBI*c z8%Ns?g8$Yn#pnCWe96(Nb$We{gt4hc2pHaQ(3a=eir5Z!(^5-D`|n>4*`!O04#@W+ z?@Qy$*npg?9(yP4QO77JvyaCoOogfISVPiuw_ffwg5^57g^@_220)}x zLM?QxVOU9|7}AuGV5+u}P|98-gWlsK6T%9K!$Pl4u$1RQH*&n0 z%h5%cruga%)6yjL`$-<`WkP)cX&L!t4Tu-mos^lbsLB4y>3W8rCV?`s*4P5kM~p)= zLS{ayGC4eQI=`E5g?RFCWa_nVcY$7;pMDBpQuaO zk#})@8D=`HAIi67xl`!*vGhwVp8X?-R@!^m35==G{%Fk;2gr<*n*3xV8}{|TZz&g@ zdO)hWz#wQE0-O8O($nPFl{0UsSB@m$n&G5LJ8JQ1CZ;6lG$TqZ6LL*RsbTA6VIq@! zn5&N@qIsR3c<~kSE<6KVaITs&+1Y|~s z^O6SgC9zbcOkxWweGe}_Y67WBYPh71(F$rCF7O@5K>WLSo<8LW#24+ot_v{zSz zo8B%-ACjt`PL$#f9O>LuzkPR<6t?edx-%=?9y`=1SBF?3wybw2|EZGXAEYLJnA^QL zItN74iqYP1_n2xG1-Y(TsiHwpWows8X32&4r)2$;gSGlG)Atgrs<#Z&(i-!D>w^2? z-SIKW9_fY=OsE|OZ{f`Yz8xM|qW!EZ-}MsX=q`#h}2g?ce| z@ncnMl%bp1moov~kRe_D{#>0hg@+u96J(++XR-wLEch0Dq8YwWGjRTQ?K=qxGhk)kjy+l{I}}SCsp}DM%>0plgy9%zNI{^5P2qw3cb5{p@P@#q(%Vq4es{Nwtd47;%bNpl8g#M)Ql3;N>)H7<@7x z;5(b?#yag7*$il{cZOHUR2T7G!DQmUeg-S2uB(U*Ddgw6yw=I$eGiPLsJ`qJ9fvmZ9CbqZFX$iw(WFm+qOG4I?0#+Idjg;`JH*5nfWg2 zV()$PR;}7qYt^cEmCE1Wl<+?<*fFAh8Cmudp>W2#b=UI<}2_OBYI|#WopuGKIfzPnIz$th z+FT8;nxVC|yF!+3?{4LHIuDb9zmkfmwBxsnkFUfIs}0H9KewSq**aLo3HFa5a>G+h zu`IT1=J}?S^%j?eLAi(`*RXbHAMz9M+YI>1Mc+`HyHq4I66E?WlY4>71dh3-7C0;= z5&Zb0Frxil@OvjbZJDO%^N2_#U;pyfM_rAIVB_$JT$ook56($S6x3zXTNb6t<)R*9 z_^8D}mcOTt-=FPsMyjwBEs-KOI0=%T+Vxs09yk|0Eq)UZ3)=!gLd6w@`|QlU;eNbj z#DfmQXbatccRSqx)YPOb8sBs zX8kfdxtSyz&wF_xH)Y#2IefdvJEAWxlg|(mkaJ@x4inV!eqg>3U%LZ8x$*Uq?8+bV z+Dy0%WKGvCY1$OYj|qcnmSb;QxkonS$`Xuxt+L)XL20K)8U%1N|ULBl(Fao%-fn%Q{iD ze_q@l!`s;{ir@MLviKVnmfNg)(CgAs=Y)<1(Qy-_YVIVm1p6SKr`d1KVM z<-!rL2tat&;Be8OZXIojuE+!>f5Veg{{fP4a(STu?7hRsxs8ih;Tu>1hnRyuLA^?2HxSva8tmo^WNvW98wO1Y}V~QWVQvC1#kJ`8gnp!kw!#VbhIVdE-6>!kvF*`(m&x#}x4wzR1CCyX1&Z=coW zDW=Uo(rLVw%@j5fJn6Q-b--f^Dq!AtAk{k(`GmLN{MT<27PWv1fKG%ACj+b&ScB&wU%U#?-lu!(^v|v=O z2_DkW??4%&3DOCmXL>#24MY%L`JOvbAK97CS5055B9k7V6AwtqU$xOzd6mAX4! zP`fzZk3Z*L7jwdpR>SCnqQb<=?vs9=c{ygG8Rp!09B(E<+3Li03c9xvCxBre5*l5& zE+>T=R!?hTu3%mcU-((}j%5k5LkUpoJ%k0A5$UPQfY@^f5TLpr^jwLcNe>pveR@W< zc@|Pp_d*bdKxz=WA1y$|Pu(9Mxiqfv49nf>lfv(%l}JSLsjArx)94ae)>HT)%SJ^2 zj%`mA`!v9UJn~raV=GF}h8YX}LJwROHoZ~&i~NDnX5}byjK&S%yvo&WOI;N0L5&KU zT!^W4h4WCMmwjz(V&-E!*0*4z&8rtF6IV;i%= z#iI6?!wIHXzKW2NX&aU8+vIPagAOGM{zb$wdB0W5FO`BSyd5)@UX#Z2c&v*(E%W*Mt_Wz0ZJp9!Hj(=wXOtMkj94>K&w%gD$sXqK2pR8)t5< z!FWnXbW%^MSK=1YdfjGkF6kg|eKNdgFDCvEsH+=p46~|JL4?{tq1x~u=JA;am}x9> zp_9gf3u%K#!te%kwA#0JC_lV?+(YL*i!kH`DwV86jq0E)vPf{QpTpcBnX046BfVZE zRdB7zmYLtzAjO!53pu`GAb-G2ROfws1gHA)18H$aA(<_rgUo z_KfBqN4B=FT#)mB05s0?`QoK#g{ec*R!%a&i&^-->6In2qtrBf=DI=}NKp%zc<5A? z7Vz+L0?2#$8{s!2k&A!&H_2r64CLl;AUgSZ8hp9FaFnBr)>C8WNN})SQ6m!z#Jq98 zv_~-Jv=5EwxW8_Eg?(*7e;yc?NVrkcmu5uorbca5<5bB&e2nlU37uwzNX#WCbe^af z8?LG9!U-<>11w-P(`%qf;IN#sbz(!gzABTIdndueDB`X7jzrk2E^?QL?!`X7r1Qnf z5iZ4k{WxL|GXYEtI=^g~svOzf6udz6$cvqbCZV^?Oh);~%rL4jDc8gO^siyV2&4)= z+Sz|60>`j5YZy`d>SgU_?Sar6YmID-e0^MLq)yw(`shIK*W~CSo_Zy2>m*FQ3^7sa z)XR(`(}9Rg-;4sv~VO1aV}k{3$^`8^iJJq zS5_>23|_%XMNtwSgKE=$gPbxl1!+Q&@Oz9h_2lR1ki?MXAk`|1yg_1nl*cDD?5ycz z4!?yf!2zv~3|{3rm*^7o+A5tM`YbzrjhsQe>3h>J!#4Aa3St?z9(Pv~R+j8qO`qVN z(SlfSwC0Vvj6|NOgQQut-q<1+AyR;8hdE!8V;WcNgX~EZm-j|=fR|!A>PB=!PBZVS zK4c)DWy6Dmbi>@SckHQtva1PMmk@*uAdLu>^wKzTBoOXGx?Kh{S)(a&f0+St>hM6L zW4$s&R0Fkz>_ZWORp0e2PzQp3lj<<-UJjxW2qhjCXIYpxoY9e@*N z?{=?9V_<%0)SPqu(TG~@PDcRd#wI2fYdu{h>{-il70EghiQpRm7YSRTf{K3(wJ>DG zCAX8#$yB%<@XscW%M zsa>(SQBxB#e31TEoj)OERtK!7s~$>CoLTo$2aWCHr?H{jD!!ti@3#C25^TL^0{$s0 z(DSy(?gs0CPbl*)Rs3#{sb^p?5{@u72N&wDSIj8Hk@yQ9$=ifapx)1hN=xGcN(410 z4MU(#ZbM&(UjaZoE+5ovdzGj*LOaQ%7;7;=4^ly_4cCa|YXjY1BmstEpcVB#R#pph zA~w%&OS(&PKQ$n??v_=bUWedBENG{_TJ9-5M?V->Umy7Y>vq8cbbjgy8wiLq_#aif z|1487{Hty~#cSoX!I7|YqF$!*YTue1ddWjxK5j0Zawy`KP>phQXxY-DjRY-;l^6s; zif-le;Q~r1Dm5sa)7ACLbg;VR&hoYee{;W+o6y!+NNmLOQSABpR0?Bj^!o|OnP&+l!hEOwdrU1!f>qCK3@!V}_VpxLdtCS9vF8@ab>VSCv)71lQ(po8 zF>C5K+v!)_pfU3&GP3gdQvV?7C~6QUuJ`m(U-{1YCoxq!?*K%)p*NaM6c)sxq4>qKR&Zy^BGMju?(SmZZD+^>fu*oGs($7MEUA}ok131j0(#Rwq=+WjnAi6A^;aCU!kEmwR<(_ zn}hYPEY*v^4NWD(6*Jc!p;#WR6Jd(~5ml#8=W)PMX3<8+5oP!&M(h+}{%r;wxWQh~ zy^UmVFhzrx+)A$&+pnkvbiJELu97_2JCN96ApYsNmXAv|Qx@#fKKEmuVNL~F^`sCI zV$E#?o`W9)TT@^Iyw}YSSdb$wQU1xId_OsLpb~UPVq1pdjB%6~11W$BOK89&T@XtY zz9PlQWyyYOYRh|o$vk-rE5mG@TkrW{;r3W@H6bzde!`I;-+{!D88tNRin7T$wX0F} zH;BfWrNq6g*k@Tor*Y92b?lwCKxpElT{P3(=k8G4Td-Bw@kXD=9U6N*W3pG+g9%8A zat1nrsmhB=?K`y7`o(|7_gtWb%-L#0q#&%SoR$B4g$>mKGxuBkvJTCz3p$dR`C-<^ z4Qm!x%9XX|C(98Y<7$eFW{^4247C%3U$zU>xglkhR&(U2Q|Jf`xpXPXJ_j_s%y19( zfD@%TBADQ3+fY?BdPyokc#?9ykjeUoA&tvG0NqA#vjW*h{4?4FJbaA+jkI<>bPVP& zAi=n=$LTiB|Gdstyx)f;Ais<%Wcu*h-GHdrQ6Rc-+Cn$1DMOET^_-Y+$w8l1X?V57J0t5f|x_Q$s|7_HjjvW z{dWbX+2z>tYVZC84DD)jvq3U%4`v-A;ifLEu@tQ@d&3CItKCid2c6qTq2f8Do8&ma zw8MsV3cqJtMq4*F7Eg{J5bS_+Vj9a%ojB=KsbSswucrBnorM$;Mb}8axP#6gj^f1G zgCgk}c9WK|mF4+a1DZe{wP4zr&$xD8>|OcS$4o$F$HTg1+Z0qRN;IlBGsCq?rKZR= zu_1nr_^DDHQ}jyvXkaP&FwE+MT#&#@dbM6Y5waBHCAgrd43w0qo4J~!*ghXWR`#qg z*%QF6)u_?JNsoambRjj7j5|FJ*G~QNFo~EOPsEzH>5jiuYISpYy*hCt*zs|HZX8Pn z5|Z@cZ_5w)nDM|}SvD9|l+r_&1JNejxGiYw$bTa;l{}2I^eAkSXwsnaX(NN0ix=cY zKSoRJOJulS-sf92#7Nm0^jMZJ++&)?z!hf<%+!H{m8FWLWW7SKau8qwY^o8-K);x` zh8gHB2UQD9plE=-B&NX8QZxZInY5PLh?Aa@86S zlP8OjTU}&18egZWTn>o3&iYDA*l8;}QqaMP56YUwizX@<`1-LZh1V&g9uO#HXo0uM z5lB4YLA*9NYG*8YKo1^iez;ya-W`ZS3=}n{R~eH}8KQUFXY)oZp%SO@3%@e$%N}a7 zUj7$PDtGs<>r9HG387)`j5{+czbyU*?GGd} z<)oopgEu6v`uG5tF~z-jB?y&*G^_T#&=DoLzZ?*?x=2BqiWYOroVykYf`!SU;Ad++ z7~}6OeQEU0MK57s2c7m52Ux>3cvG>IE{c%%?!%k4rEC07IATA5pbe0);QorPS@=;@9`m& z5!+K|)9wVGpr7boD-_1>N)iizWe66O(e7~@5Mn1ohz!Q$uD1NPPCzJwPrIFfPmD4Q zlT4AW@G1(g))x1W8K~sj28hX*sBB6p19LmF9W6H-f%-Qp!Bc_3aObC^6)h%-zJOEc zCUj1eiCEN*0u?yTVszA@^5%uoFEVZ>2cT5k=R1rTXIBsvhb~HQiFJ>_<(q;tFSFN)Xj4Fl+8=GSyP}tXq8Np{z|{amn#peK zRw`bC_WF`cpvMNHoz#g&qL0j-r9qFtb(zg|Z+6)@B&{7AE;HcAz`L0>IES*oDPQF? z9QfoANI%O`eqSj+c{)H@;4updR1#+nhjUEZPycpi69}I^y9OWV)kHk#4cbkQ_&e!J zY)|nLtDj5bG1=?B4zkB&UPD}(x4O?{vsX%YTz0YbGHtSqy*oeZ4|a&fxidbB2CSl` zK=oOru)J|4%>uDBXF`TgF_+fxq=Rg3 zyh2K4QRi_Ei?eHk0?AgXPg4T^6pm2N*A3*5xd=2&zch#fdrWRc!$dB(nAk zF5AS60mq)WnqkN*fZJ64*c?#u6NGV^r9p8HVoCT-D@;oObQ{XY_QTcFeei=NV}aHH zV!nS2D5i#x7EDy?vC--RzscPnlC{WEm21-B0-W}9t0E+8j3vJ4*h$sU${S{qDjSOR75Xj-+ljAtE3ViuZ$gdbjSaTgJYuNLBUq30wHpK>tFpyNDdWR5_+_ z*Psl!YI-4nTz@eBlW`65`+cFC2X<0k5d+-`DDzIP`wJ?|=ljB-*ufUY4;3}j}{EZ9#uzWodRHf2<%#r+rS~7HT7L3wQcV-EoFKH2^MH zAgAo!$tW)*$PR5iuTF~1mOl@6VAPIb!u5h-c?8;TG=k1?piq<8Q85DD=C2nBPj2< zRsygwD}=;rXBMNsNrs^g!-|xUt{14H?Lxk$MT?~NTDBl?TE}8d*Ne9W+&+Aq8+k93iD>r(=ljDXDPCrR#j*AN9tf+c*<2cPDYFS?WIcs z0+HNdTQCDyE~H@6GCeb~p7F6{iQv6bYMJR=c^ThyfC1z2Kk&$;u|=uAC~PU-q89h# z3<`_co^!B@mF=hYAmQogrPxhBu_vb;C4HWpB{N=gdfJQ%HfN3#mXJZbN2t%B5$aE5 zlXwG3A)w_~AUsq*A{iD>Ej&?67AO$<;iKc2tdh}~2r?@;nrVv18#Vi@6_*G=4b(Pq zMP2pQc-CB5(mQ@jyU6ez+`Js0XVuYQjALq$WOW3-L;=KNniW z_BIk&anW9OOn&0R6~FDKG)U|il%Ml9Px2Q5VAkp3e~hZ*M6#+=ZU}SEs6M|ucE1G{ zyEID@raT?6x@v6(pC>eQ4YaMBR^um1k|!Uma{;M{eNZG%pbQyQuv*U=(ro_PE4*%m zU|$t}Sy6**6OxSZ!(>v5ULTl(xuS0Afo9iE4gtdKgK5hnHlTz^ByaoOj(|VbL}_X| zvxbL-n*X#sy@PF>72@E(W@-Sg{KGP_$~-UMnLLV+>`(djd}dk|UfwF1F}MgHPB4x% zfHo#M(p^7Tp*7JYwivvkDmb023>qaAEHeA*^yMUs`^}C1N3?JGOdNaC z{@*L66jYzm3A{r7>3%_<9HlC9(-}f)Lr`qjx1S9Wo=;H9DJE1ZZ%zkMyY5mB4??)3 z1*Qx+lf$T*4fg{9!T1$20ks-5iPJe{=pnyg1gW0yJ1 zk_K;)-o!%2(;v{c3%a}SSrpbzLMd{tH4sK=GQ`{<8p1h3xGvk4nw={ z&#q#u2uy_9w)6gaz`Vz@A@AIPg_$ij^gVpbREULZn?i~CxunWz z7HlAdWUkM9@Q3()TwpBRzL6l6OH--i?J;SU<}&>23ii)ovYOt9%*&F;&2FkEp?S|b z=-puE(;(-qH}4HiPUF^cmdAiba6#zEI|K5OZ{Mva^Sw%Lnnv?m&%*eefFBN z3hyyfWVYEGYxvtAU`%y!(P^`8PS2&N2zivIRLmUzc4wg04Y9iIc7`3lkMn~$iA%wb zPJ?3j_FswupIx-WEbv4G(n;eWB+z!9yAT}_ekvyh76H7F>c4RW#PmZvkXw0#jI+>~ zKW7AzTCH>ZOSi54ndMY4OV|teB-fg;4}Z=;a=z#bHhNJL!13HanDJ~wz6@iDAwJ-G zB|~*WFEq+EcqJI(_8F&T-|w6u2RoxA^LPTG^`7i+?=H~Ih#>%!uzkv?V*h%130y{| z{0$*^a{0^A?aB5#@iLdAiV|8>+Hwx@mCua!m5YB<@$SJ43w(BlpNC(&Y zg7X7!qZ^=S!JH>?S!=S>G?NIH^tYG%wSR@DUZX z>5_K^B4P5+kPO7aOB(xMb_b(m@175qBahdFcJCbJmA+ty1H=u6?<2)Q^JT&l#=Mod z+KxFDGN0DVr2bZW7v?=?D}Bj!S_L<(!ZCe`IDPcmY>{Z9`=>JS)c8?X+wCxwO_~s| z854ufR?eti)QnbflU7)(7e{Q|ynePMibd%(A2W-BV}U<=M2qwmzHCm>FCRbQo6?d7 zX_O7f>rvu#bnhQ{Qd1GkX@s#lZz+dy$lGjJ@dsDfEfBUij~p@f@PN?PXiu~N&ZgKt zljp@87v*aPi4k4@C)6A4l+S7tE*8)iHNS}B4{{Z*HkklV8|g<*mLJoSJqNqOY7CR1 zPH+goWUg@w2W&eeO{P$*m$Fzs%%szk9FQ|p_28-+Wp2#B*}Pp(7Lb!8jiruOC~&}2>TV3H7_}g*0j3<^15UEt7Sel z(}ZT-Ywe)3&{s}91f{JU2F)n{vg^>|Ja68iG~reEB*}}-H9m2bLhmTP0%KTv-SBIl z;J8m04viLCx^aPp=04Rtez=aD_pFeL%YnD`iXscnfY z32nDGezoqZwVDK-1<`i!c9y@#)$WJ#ygJ<3`@rH8f)By$V6)IxwjcTb0ktm*bs^}5 zKS#E%yL%hMsiSRmi=2LGaUzJyk`7pfDvOmb5F%uJc{!WfT@XFte{1b~;kUVUDcn^| z$-(YPpg-*=%n1&P<_MG1ie_otoUHD;>kR?%aS8_sJ|I3zk8mnWoeF}uCv|tr9=iW0<)&T@GL^AA8z58 zvB}&R0)DmMss8!MhhN55&-z6w_XSV_?TRBB>WuFUGsj$K+Zi%45La83yM@*hE{f#` z#jzCEJ49?@iMuFe_69A32Kcf;yB)aRAr~d!F0qoA0%ub^Y%FA}F5y}v#TcE8#ac6r z!AomSP|w)Rt_$AA`q}ulkx!}g#DkUG4tX{JhRbxI<$4!lJm;9W~&FSrC zhPE2hwJR+(ALa_mh?t1Iex@OOjbNg+=s{}?&maXcnW$X40iVHlgh(WhLIC%d zG-B>#SwAmzPzon1rF9pZVl{OsH~Qlu9wH^(PF~|o{#XBaWtUqHqY(e;OpW$==bk`5 z7Nwc#VRA4}#Pt@t6TOZeE~IcP4%|cOqGIjWj`no5jBBa2(KQQpIJfF{zITE8B(oJ&N?b%(2G{9XgJU%>dNEbqD3vkPPPYE2Ii)F%TSePugW zv76pKsakc>GQIX*e_e6G>uX!b(s+athT$SkEce6^vg{?O`6YEp!{WKXVr8YW^T!L=JKqc=^F|*+ZDNaL|+}4YEAk34b)US6FvO~&`-<5OD`^Cn+ z6BWCY)U^Doi+ZN8Ua1EO-R%rs5LFPorS(A&%KGjx=zeoMX3(_!7UvptK7B$%y&=+@ zC}DOw3=0e}$sNIZ=5@TOD-40+Fg*rp703wpWs55ex-&%$yq!TAU4pI`UIVFe8r^n+ z$s{u(0i)VoqR_{s_qSW`so4|Hxx4%XwYxn8{9fmO@6mMlJU11BLS?;u3Lzj}Hr~&C z|1tAL&v#(gE~_??11~{-dM6vA%Y6N|8dEmTG!(rcsq?ky$}WVoG{i zer!^@Rh5cXa-mtFq4l7_VR}Y-LIzQe_I6TwqV+&YK_H9*j1(jJh3vRwo$3tJ>^SAv z_}Jvn&jDlj2R{r7N)GZ=;}l@kB(&rbsx`rf6b!NyAe-j7P#o|k34$r|e{fUA;QUR3 zzu8$!-`o^}{}u2z8^zw-!pOi{@_W#fqp5+>zwr^L)U4z;7|=eZYwM~kK*DKhV*{Gl zD2i!C&`_F9%yZ);>H0E^%vu)EeLk{8&I;J_%Y>|RQFL_dBa1B`G)pHRvqIN0kLnI)aU2w)%dD`Dxj2a}XE6xP+~yh% z;GQf<{!5&;g}Fs7UYJzRhuSBfd-~Jb_ZL*Lfr-m(FHZh7vt86|4ReBBLLkkinKuHg z36lO+YXMi>y(&#wK@r#-hjbWoMb%D@?9>x8ocU7|HlX$FeR2Z5~38tLicnrE4ep& zhx`_BOYC{4mbK-@)6eO{5pUm%Y&}}MjZp{bClO?PO*+J=30W@!*{NtlmbIN%nf*f? z$1)XYfwpWkI>>ZRY}(W+%glV)DaYpZ5mx$;Sd~BQM|=J*l%(Fs+BjNn1vN#%ZHF-AJ>$5QNdt3SGN;1 z{^NE!h6BKU_U*Zx-&C6KezyPlm$R`mHnA45FmnE$U1Q+r@vkdt**IzWAO^JH=X>gm zD`^5}D%Rc$at8y$Ma|3&NYEcJK^QKdT^wZ&PKortPbS7F5p(m!uYF>+I8@Ti;7Isa z=UfJU_m{4aP~PNkC&!9EeMK4_dVxyk=Je|BUQpw{PaCk0 z)?*#I2Pb3vLqg`Rp}aAotlR;1eL)oVUBYEvzlRS&rB*Ch?fm8%oNM~)QXvRWjP;;I zi;&@g^Ldfik0UVq>$p7=t1?1~UVj7s@s;uYOMSl{7_Wp}SWJ`vE7#;0!Elf?>OBo> z#Mq@;0El*hZI4m>XH+t;wp3UCHjUl4{1*b6y|s&(g{>34psj_C!N2UJ@NZxI%T)i@ z@o92mQkDj|0(z8Ec4o5iJ3!SzE8Iv=$~LPCB`P;e%rwp+0$I+F%!2@=b}ewR3W|Fj980w|6vga{70c=>IjcF&UYe33|FQ83a073JNJ& zx@r1`{}o?aQ)w5fudeJI$1k~1WG<9sr;v3QE5^y=zimf`xg3d`ETo{Zeplx^gVseNl(nq z#rAt5+y5`WhnAOxk(;KMpp9{xpr4YKqyeTv{O@M#ua@~AE@qy@$Jh7|v&rziWi@_7 z#QhFk`2Qd@ug0$q7`ls(B}cd`m2mzVt<8IYm_GIiyp$m!HC+!&>vuW~ zpm|Dfb{YM1_kcjOA?B>4LfrRbuD!Zd6JZ;6rL2YdPh0CPWO*C3&U4#C@p%Y;R3e5? zHq*n5Ut8&=1Z$9%Ds}i&2LY^q{VYA;szQmh#ZJ%daDEsvN!f+H5-1h%FqWo)e}Meg zJ|foDTmAn~m+HT$>*3^VV&g>r?|fLNfBU4z$j0%XY*>@n37GHEg`&P>lie{cM9o-R z=|*p}so;?8$W3+Q+!ITisK{IcOT()CRdngriTkv#v?@mvSATP%+~O zmJTVTRfB}+V>Am&4Idv)dgPCc-I22`~U+I#BPt_mfW-jHD-SMR-A@n zdVDf&c=C%dUu&FiEV6W=iVQ{J%-#D7-j)5EV_}<;Ax>vVdjjDodwz5G!j0?qbKhWn zYcI=DeTgCASc7No?!|M5cOjlQnn_4A*l$?}sKo5NoCB(1hZ9rc64Qr{GI(MOa3v(0 z66FkAroBAMolV&8`!ZKu+bQx{vgZ^#(-jFi$I3;)+MS=wMgEoK9L9g>3Lk|PtvJTfAeg>luGn=;Wreu#>;aK~zV4;t1BaNt^cFEOyL zdCRO{gZ@!Wv;4kYSQ@CG5-jMw&# zlEroL=SIxr9X17wQ#hr*F#WqNBN%pp2C71cH+Cdx;38k>sRn5SAw;vcE{YrrVcMXr z1}5b7Weq&+B6DMRfZ9tUcxHQ!0U~3!Uu{0<&&?j&3qs=|MF|)jiEsLj$D`w|ft?Fr zw>j<+%Pxx?w`vSt7o@Hr#%{oX+bf$Wtd;AIH?6_5t>R7Ui1CC2lr(`oHqaP9A@u$g zWsEi4q*mSnx9BHhCOUWhsb(9s7YI&?=19)MC_WRX1=g(#)~fJltijCd*hL=>xShR@ zdrh=AU=N$`g${yS2;#F>n`%Jk8N;2z*^dX44sQk?3WQ@Sl7XuG~=P&o<)m7-d z9m)>pL_bSfsGy=iRy+#=M(x*MTF=6+X?IQ#==Ui$nlzI`Ma}R$K`;|R(1v6dXSZTK zS>bdWRT_a`{b6Q+1qgMA17Dg4g2y7uvs7{L*AuUTJSn&M(qUfb6q9(?95s8)im8xrR z5^Yp&@`^*Wst!0Rx3D92=2N7y;#N9W8>fybv=6H0+IjN_WY{#Y7Mt14P-Jv=^mvMY^-Uo=Hvp1sJ?mv~Q!*G9@|WK&p4QU&eF1AlsRG z2unZsm|E77pXIo6Mq4nMP z&O~*q;CPYj2U%j%e@3i$ZY1o|&_YCM`{m}P-9S&%EqiP%0;@!q-qNn_4o3e(%K9}= zg1ssDFb&1Y(>OqgV6fCFwGS6+?A&qT6srM+x*{oKvAAYY16BILRWw01%PX-C(ZE4Y z`CDHQEMscaFfERoiWA$1>OM{vqE5YI?%X3q%`Ek=)erY%msUy`l@(M}>NXWjF^vTB z8j&6+K|>~KKGM^dpdszgRLW>Rah@8nzl?Y*>64{|1+4wXKX~zP-%~ykOwPE+?gIc< zvfNs%S-8Wb*s`g5qy<@yd1_O>lH+*MkoBp84>biZwl1wD)w04Zk1!O7Uc84YdA8$_ zJ3y}zRKC8ggbG7NG|)8ZA}%s8Yn|w|5w<@kYmiNeDh1QlbkeLRf&29%Dw7}vQm*!m zL4&oms~wjLuk;fnEZM)4?l|sAv@SdW9Dsb-p$hx_W{IWzxFe` zWpIsp9aO^HgSCacq3U38%3AIUF6z*_nwUY?XW>4VdSp#867ZIN2|_z(F{82LKoIz+ zTu|B8MEi3%3?D4Z8k3+Q7}zt;=H3Xd;zH^lE+T!a1;`m^=%YnF7uCRjBs6uP0_Uu_ zwJ)8j0mCO5QO49v3Hs;I=mn9<^ZBissomYVQ9L~jonj;lpHzBHB@0>=+gl1nKSGy; zz$(z|MGaG9fSno@ONq^AT1UO+C2y7T^l;wpDgIa!$-m)v(ABmiQP_-KYXr8-#>@d) z3&peAAG@S+Ugx{3wxf>rTU}&~SED^M=esuWO?9S&zADXmWMFIO11NFOtJ7UZng~C< zX~oq5M5&`x&=Wfc1ZuB3Y%`j|?V4KG*BD=;&;OX<>iuz*!SJ0jISKy{DU*f$U;BwE zEgQQHHl)vOJ)$y!`f5oMCHj<&K~WTT0Y6jLa~fbZG;msG1mtiQ3QF0KkC*r)GHJF) zZ0ps~)drEf98dR7Pr1?Ckx~j4e8yPl!k^^sX6X8q# z*wvM5=w;MzA6+9SrlARz-VWi~Rg_S(tdA(h9_<`acgz@x@X`u5 z2k(#})ZPBzP66WzJvU?+42XiZZxWi9As`qO!|)V-)K#%yaN@dAI0n5RX3Q3jARW7z z`xM^edp17CKsr_ggz|>rSG{$tVdF2n;Tw;|m`u9@g^*95jm&5~RUFc1cUi$q6d3t! zjr_JgGd|;$j!7x_zLJS9RE!$~Z4`#X-~(fEaPBv~SdwyiJA*;@{04@@=^PWHt8!x` zn)?B;8Y98>C@fCEssgdr$f!9mQHrQ|SD(xdIY~I;JubHg)ZGKxMN*x-e*QNin;ZtB%2x~yeuz5xgdDsl)I%ur6syHKjXULFA3wjFkZ_27F9GsR6q7E*WOottF!`w&RB4Qw5B$yn5Zcz~}@fjM%7 zlLCBsq0T%G;?5FVx^A*^xw2bH*7AeF2C;V;f4PyL5o>n2;&mYt*)5mIjNWqkZ}5Gc z1ev9og5D0>>|EE%T*HP@yd12P^36S#*R$s*X8D4Qe(tCM59}kfvI%(5?HeKBBCr4^ z;=Hz-E^?6J4`?W?>>ZNyEDi(_iQ4(P8x`Tjo$u6?FKGHhC|;#L6TGI?fZuZ7)5xkY zHLn=Pxbdc`opTejQd!?dX|#7{sC@Re`W)?4O4hC_s|w46IREwp}{ zV)Fupy}#H^>)=#y*}~d^6GnV*8VNRzy3%((D*tRyKdV$ugbg!1uyKtGw=hDk4xSXUj;?* zGI#AIPF@d+^RCh}^a`HQXPAi47EIU-+q|I(%aJdFc00@~D`OqiR^YQ9+HgPG&u4Yp z^skJdd%JhNMHzXL=ZX!)s=v5?$1Ru->dxQ4Sl2SpZWUN`sgjPTToz1^qG`wlPq-WK-MVU!bS2lNaJUZq} z(UvdMUK@&AHBdW;e?a=C44I2T=1XTDun9KQI4_X>L!S>xCOZTnzYU)vK)NF34bCCXdo{EE|UK zCFf8^kP4}H)q>D@rCLD36(PEK9j3&gZ$xiDe)|ZNh7%(%zqHzEhQ)MR+K^>-!T8EA^qEo~)NdE^Uj-~Gx$~`rZv+{<1;_7oj zqheO;yAZ$ANJ&JoFHvHC@;Z#&Z`E*>3*SuF(E=}X5aA!XmkVQ};J!QqU?P2J2Fq;& zb?VQW4m0$%GWMC-19DG!TwZQF)3}aDh5||0UEOM>{@9f?N@L08J#z|fW4+#@B`Dy< z%wePOtEGU2O11rLx4o?~?w__w*IJ8@LD1qAVtD4*P^z&B8*1l_fhjIqB%G?tu~+Aa>aKTnGcrdJ{Vju zH%42tu(Mva3|#}M8OO=O?TNy$5Ry2clZJdX`t=F!;oIN)h5o{`C(#1~gGgR7}4uMa3=Rn5Sktq5$*geS%H zIaRh~)R{@QI|24YBPH#eDt!`hI!Yn`|M+^xCQ$+|TeEE2w(V24ZQHi%lx^F#?K)-K zw(YvrJ<~CB-wz#;KOr-A?!BJ1mVvD?655$&AJs<3#JswTV_7LpVChBAq9=j4@x7pk z1zxREcW;MQ+5(mszs829ITIY9G}m0yD*HyfCdDq244Nl~%rf1?7l`L0Oie-`=~nd= zWF0XtMAecV`+ZKr9 zY0dPCtA_F@AMt1|x4Y|ZT$l1w2dXj8j3V!{5pL1|G8`R82dH@0+E+?Y++7*YZ}M2r zmRza-9Z{GATK8Pb#IIm+2s#QsLBZGe0rEkOqqU|VW~ro`QivKMy&6y=J2WO0=Ife%R)sBTqeBFnHC zonx$whR>@bC;QJ<(gDfn(v}0&4wy>+dq&2tCkuA?DT8m@*5&E94G3ya>pg4-NCexL zOVnDk#MyE@FB*!lE4x)a86XTr1DhSvZ!k>(H03D4u8h?qBT(T?n*3QKt8i?$h5b3lqoYY{*5hVjrHv=Nu z@nDTWu8D?@pTL)#^&O~QUX&&Anq(W770DqwHw1IXE=u9-;PBHuS#@TRDBl#VHRf@Z zE|()BLN^-)G2u=H0*f21zYXVxjn??FI|)N%cPYjP0$(Fn`Y3TxD5BknqSe?Dvd9r5 zydfVS;nQw!31tz{-LX?rt6CBOhL9%JAM0}ESTWksw)F&2L&|YamGuPHw-cPwajx^g z-uwe7Y^&NC3rTcs#h&aIzh>n_;BW2-k;HvnQ}g!5(`E0_j0Gaho7{YKI#6&7s`q|l z@X9Uur#?X0swsTuRy0`_E(zvyYop#&Rx_WiX()V#^2+AVdT?PMuZq&GEpVcY?1Fh5 zq))tjf$W&Yq8x~3{%WI?l?&#it4~SHMcBD%FO}7JG=u8PQK9=n-3dts-FD@b^I zEgi$Xjj`AUSO2#4A%hjXBb=`uQW@iCe&;aRn8sf3xBpoBy3WIdy+D5zv)`rf|CS8? z-y8b>+)4kRolnEYZe9Gp#&Er3v637V`ptVXTG^<8W)Yb^f6ckb(imgrP{f_05xa!n z*VQ{{mV4I-$(#t$kf~d`Sy zW%t?S^$McS^ESa^dY+P*MCUmAF&Cm<@#D1CG9Z#)+UhePlg)?MiT%C)eU#`R_xXrn zzdtQ*EWJ@`YHaDB4CY=vg<|%+$kpQ5(wsWbr&vMP&XPSfJ47AoKLr)BW?zG=_p1)X zXnzNp?Jz%d?U^I#9hKk2-WG{-+u12R(Cs_MDb(v36dUX?K-C2r=lq?_s0{`7Hps27 zOkfZX05r0&1ApuivvP=L9oq76jG<3L;E^*s4G1_xTw%ei%_$+QHJMO~c-Ropyo~YP zHNj%bSZ~A99fYkZB{WfaZ1CMZ;ow*L79OMiOvN>ns`W3p1+eE$ywZuKZXRky#WD3U zXgWEk837@n-fmbX)$kKbWpus%oPybTaV7 z6spi5+@O>(A-{=|uP>w_Si~U&6bG>A(IRFh&F6}O%rTR(sEh|aS*EWV*WR&^v1E~k zlC9uh<^sO>b^~XxhD&@+YcPWSQCLPLPb*$XmTI$H_A|g zzcxG6#oOnpN^lZ1mT{zOqR(dGC3Mj&kB>Uv=l=|2h3ACsIE?&n-km?>I>W`rgD}Y#<;-_06yC8aq@P)<7ywa zD|6%%BO@9Uz(6@vcro9krgbLPDA%W-q=G3sMxT<1PMbyZ8|E#0dGLnoBb{X_P`qXS zc2S~88v1q`AW?9(T2SDn3NH-}Drt{JQohgjW3RKUU)-_}*p$a09cN1J$tW-u+5h z#|ei)A`t`?kDIrai5D&L$B~nXH+$5z1A!DzBqC{l5hYgYW24Rh^7@zX!aAK9jQ|J~ zN7PWUAD=eAc-#q7wh-BQsgbpUMF@0$gc48dhR5!PSEh=rlr`Gn6U#n*VOjigbsX1+ z#nK;yt#6sWL}q$aI@!E%zxgjL4@b*qG8BBgH#qH zPKY^ExaR6K6@s@aB7Gmnf^4H*9&cLxLqz1*n>of>gQ8Gq=~dJ+`KQGvna8l5$MKJy zZKWi>gO+XNrNWi+8D9Lx{BykurCD-E?tAf#L8W2|)e}#%iSp_>IACM~zGB1QPUnX7 zmh#erx4Ph%e+!A2?^7Bzym@E#Jh(8W%q;kYcWd5`Y;qwVPLHNspBL6FxNx&`>?{{2 z(7f5vvz^~_z2pb|r?1$v`Y4iKGFkPvqFD$^Szf?rtWZQ)U@?CCL25athSR|?#q|2` zW@w(h>Ij^^J1;eVNntstdApfp-=~JBT@r%zdNDKAUR{ zV97%*QdZ;svZ8XmyIU;#3!Vn6Q)dg6vRxyO7&=G#=H;3P3pPPpv5lz{U;P->0v4|` z*DZ5S`n~?Z|KIW!HOx1e>F@fK_e&D|Ujq4m$XiT|jQ@43>(;ce+Ym+g%Fz>G;Gbnl z8UEwG)B;2<2?gw6BU}T_LII>{XiT(N!yh01b<-(ym(bkFV~oOZnA~>Q)xJGh<^29^ zfQrpGXpHROYFc14!6L|Z5*bE2GfDHsdq3Hlh+f+GPX?=oj2`CTas8EAJ=pA+oEKiv zA(iv(y!~{PAjQR4|2&*@VDbIM*}J>Z53K|rZ@>fWMf!~@Y$*Hl|@r)%k){FX*l_=x04>EY&=II}_Pj!^^Qy1x@VoA5ACqa0-61*3Pi^_u#0Wz;?Pv z|1yun)IKCSO!~;Bp{MD35D~Ji1sz+ow}9&A?EW zd}tEHNV`2}nnnv%d=@<#DU#)$4~awvB14cn3E~Do1T7$(21?&R1P4}Hi^+{%SDF)B zCww2L1cw}O%j7;m{H4(a41c%BLrHH4xsbIbUE+;djNp zrixozg$JA<9nxK{e0IU;dAT{fiFh$gLkP8y03=mYevEpXr_JckQ43#yKm_;B14m7o zKuT;g9UVtV1Uk1{yp=_hKux0`V=8xjCx2E*fl- zl0iQ<%7uI2`t|p4CC!#5Hm8nqyKI~OcSLyU+>ANma=9R!e()yo5G544qc<(BIFI7U z)XhPE1`EVAH^D{zB7(RV1z!xW!fbwocb3{+F8xGbgG(@?09dD3Na_l1K{S@#&wglV zbK9d9S&orL?Z4Y~d`q37@S==MLy;6cf6@*|0UL>SceJ`TFzRw}RP|e)dq9T6!ZPP| zS0TYSR(0&Yc|vvUOQP_7@(@tCN!W|idddAq4H&75qy-V0e1Ak;im9{y<@rE5(`uuW zr&X>I-O~F3CEbFpnu+^@NDXjz%(uT(+8_@8JUSkCBn|)#wttH`HN+U@dZ!jhws%O_ zHbpZ}=^_dr=dx&we9?!5nktm$7C7@EEYVs1?hPy>g$l7+Ru2)qq1CfU11vk8FPlT~ zf?8ZLNEB~ffr}Phf+GO1N#xpa*q2T*@NZw^TLq&ljj@9@fKWtaAEURH8eQ<}VS$(p{u*=pDZ@D7FkX zHD5L8n0Eqnr*aF0`jYIGputNQPI1BE)h=r}xNU*emk`$sid=<08-m9W*jix+XiLmA zx`6OrA4bdwU~Q8CQXitn`pZQh|2qngG!C-PYE$>zlhekr={xnvzLw6(zOmmPH#~p=Zr6}lh&nOKo&{mL!LN`CfXme zW`msvux5}NcDm+>9rVAl`o#EUF zq{5wvCJ|b%PW$w5#3kvsbm|dUh~+`#@7WB!v|~Go3ZEd7$^egt#pM;DQ8ocgVJT}g zrdt(vzNGg^`6gUr*ea^)Z_pF1>hR^FJ30j!hX5IZgi?~|JTBOwY^zG2yAe*9x@oo3 z#DZH}&`+{*9z=S|D)DTWz((2_?i@FZ)K}o^$i$7O9?KqZKwIX5lcp_7)b$mrsd`1b zU)KRA-R5HKJ7!X}-9JZ{8&wfOLAj!H?fY{i(a@M=<`ysJHTGbfZ62Si)hP9;n7&0> z9n+0m_}nkfriQ8@*Yz!XOH%zsCmxlO$k*vD<;<`J$UutfhhCC#F$z%g zVAA~(!!s5#PSe&9!DO@xVGcm!LZ(zX1p}pf)OtC5cZUM5`$TF9j1zV&DoEW{uu3!!;_Qt5pz!qoKa$ z2}FMfjzG#flFsd{Ds^IDRn;Y7S;thZR%OM}U_;;!5*eli^@${&Pfga{qNq0V|X~fo* z*7ZYaihwIztrd%0qla1~GoN=c&FZ0CjW0>RUOI(cgpfxXz@z+){7$s>ko9aTk-pGM zQZz}^v_UW+hg}GlYC*U=d17x>Jkd_%no(6eL*%>obJau;vMg zjFI5xf)eoW%g!kGwlD5wTlh{S=EDi9C z4b(V_1?-2Clc|e6C%5EcpK7}vOBO#7uSP;rciT0sjP4$woJ1JLPc;6XS)=WlN?Lsd z*Bm)vo*IV@KAw5;T7DC1-=DX zAvt{zi0x%P@U^Pe#h2=7nD4IvDGh2f8n0*C5uZ@w9Tlwr>c+IL-4Rf#en}UXD}iW; z%AXLQMPa{$X65~(T>Io@wqXMhTg{vH>`p3kH^`W_b=B82W4)@N+h5HFZK|%Kw?gt! z23v=(D(DlCSdQY2He5NlAn8Dz{0be3Q|LIjH_Ois+tiqf`?sov8xT|6rTs=z?rhNI zG38&p-(Ja2?8T}}Y^1ED7`*-6=+EQ#e-L@b&Tdw%umAvuzho-z|MC+2H=(tq?Pa&Y zf%NlnPYHoe(cvah-FnD&MnS`2IK->H5 zIwz<~5+MY4a+kR${;yY74A7H6;d0@&sHAtvGAsz#^CEOGah;@{``)sb4L*ij&OuOg z>eq2qJ4en#MBW_h?2r7cT>Uo1h!r|o$KuK$?OJh>^Zd`@>s{mnPJ*t)m?6My`V8XZ zQo_@XeaE_HYHA^EG2`UWm5Ja%X5%ph1fS>~Bk{D-FLQGxBcx=i^&P&r5DkxnrGm9P zxD(fp1@iM&%xoS#5Ghr70Ui+dlm8Q z1lYdC<>YeG0R!5N%k>#?7HVp(eI|TG`N~FQYmGyY*a=5J!>8=PdoRq5#3A{Od?+hF zho~<{4oRe(u1rF6&c&`V(q52uaH@e|2uX)wgD?857~88oDw-de8;K#707!1O)4HG? z9T{NwtOW;*_@`9QcSg(T3q?5Q0_=zlWG3{4;h8lfj9MtFfmw`AH4$F07yj+;KZb(D z+vg}Sf=iZxy*L`S&(jxToIfr~#b#1Z%am33Vq|Z9=Z|u(dz=3NaqoY9lU`&;vg=Ej zaA1l4cj(!<&2v^fSiOERI zYrUAn`t`^E5~Dl69e0@_^AgSZU(>8)q=~Rzeb!?w`tWL`(3FUTxoj?O-j1y@qqvM`GlGD3$6>=o z+h+?q!(wJ3qV(b!=R=jOB&qnI2MsR(j6mLW4lHI{DTewr;b&Ccmj12jBO{TmAbQ-6 z9f*W|0Ji&B`HN0nAxK(`$FddF@%LngxWc^I04Y>_?F_RLwaHdrnGve+Ze*?tg)r?sqP9ENu> z7Q@VB07M@}`_J=DWPY7~W$l7QZCSJYdlI4L0gLRuWzqg*!F=j}&S<#K4~%u@Fs>`# z)$k8Gl{+&Ds#r3epZsBCnlZErX`d{Dg!G!`Qk_;V2iWfj^!7sO8YfH8W<2_Yc|?>zKu>~OC> zw9)Dez7WLpa+npXq_?+=PyX4``05{DVfB+mMEvu<7|xDewH~$A4wh}Tl$P@vHc}TR z_$i5ocGdFZS-WJdzo??dXp;{axyEP^hCfgF@MqV_;<;71GPa8>Hx8$cPkZ~fV_*lm z8GCxf+4VcuGQbuS&2pUqvkJ3~Sg{FGV?93VdPyBL==pPN4d3RIosO3;IkpQW>O(2+ zI7i~YBf)J$b-GkLS6v7l72oN(KJ>K9-Ly?=b1DxPs?ZuUz-S38061WHJCCe@S5}E6 zDP+&U^u`|@$HcAE_xha|;1EiyDFglw4)x(&x?2(CD2p;jXfEL>vbJyHR9p;n6>o=^ z0rZllPUA_MW8HC#4K}8c)fgIx8O(z(Tnu7@!eV-}C_p6O)n6?ZX<-%Gh(mFm)JnP^ zOT}{%7~3cVZg8ILCH$Nx>Y1H^sbx2E{MoSwBPIK8*gh#tyEcdYlW&n!j6pPcO$JnS z0(3+kI;tIg#Ga->YPsz%Ys>EgF1lh^iMaSy+Q0Xe2g^$!mnAJUmG!louH#j@$tkhlo(gr;mM8C>n3u0w_63k} zO@}%@E>m|=jtT_?1ZPf=)STpRDz{z!n;v82SXvzcqX=wW2e8Aas8qFiu>qgP$(Lvi zYa2~3o5Q3-MOTs<8M*$Am2lP4TlDp0>d*o;U*ym-a$ucVnVi7=5x~-kioMrrg9;|Q zG*%CibGLZjgwL~ZWfxC7YgNrJ5VY1JsckJja{CxK_0`Pvr7wOTHX#Y+`gaTMm@0v` z1!>{_F|o!h(IqOxv0*7*i+61yo6fqYfr{ez?>l#lLzs3dF}%t5P+82-{TSR`*~yJ# z&zounlwR?}k_@AskPfyIuHMnZaKC%&1FHMHYJZ7yk95t>Dm27J^`skoXMhCGV+ocXPA7fdTLAbZWJ9YF@dCKudZEmg*42f+^PV?x85Z zi>rBE$R`)&x@opcYd`;uW6}>`QNC>jToj{rTlACs_ z2G0e0jH@?36f4`Btp$?D+>wu>T9;~zW6sph8qGz+n#Cn10s-r4SCMk;*<2l2ynl%E zxl4wWOFE3`s#o?Ip<`v=a^f|ezMC9r(cbf}RCtb;!Xe;WYT`0gQzTFubgIMZDj1jm zHAOI-7>!FkYQ&gHD7afUrHW<_wy~pHPVQ_tU6LJKq&*?2hejM9Ykz9?>vxMG_=au` zQ|*0;Bo}c>=YtsL?)pFl=I57SiixT@;w?w^D)G0^-^|(TAUAXGY4NV*QV)x0A+5J# zRrC=bmTd;mA~}LZRz=!PR07qPh&U=Wf;b^@L|*|J4Dqtc`L~z|4^2X05eAwVlxTwz z+>dL?gF2JaBuO7ohl6XKn~`+L`qI-d#(f5xc=~src&937yAvO)^R-sV}7I$Nr`lD-fndb)>R}*>Y__OVMWg$*va8V-Pa@U zgucgj*R7}7>!dYECnc?U=RMHC9IY*M=TynoszjeiHe}UxG72{_8y_rbCe+nRZ0Huy zTEnzER5B5ln3uT?nye>0i1G9oZ&Y7Zfj*o}6;vSSLnf{$`t)e4!IZ%|TdYk%dfxgH z)$S~+a$C)ZM*X_U_fqZo2jjMU-$Lvii15GSk`NNFutb1MXxFKaCw3$xgQtz$?-n0* z-}bnP$;rga%*WVlIB0!PH9bi+nGg?~#>FASUrp;wsGwd#!vb19aPnzaZv+jZsg;I)nWB)W}Lw0y>l%N=`+uc?|U!V4Z{ zzzIss7D+tgYf_bb3_GfJYs9OpEuXQplT-uI!X>Uthn8oVEWZ5W(}a%}M4XoQjLH=^ zEFm418C2(~Tx6^2q3R=;69te7OfxGHm@5&f7c8wH>s^ZKrOP!S8i498rO2vZkC2&F z^Gs9axzMATvRhc1Gj+w#ib3l{42!{rGy~PkCC!G$VZsWl1*(*Py~GLq zMMIOUVaer91Z0@flGeC@lqzRYX~qnc^&?nAlDICS(oAVMaBInZ$?Qf6Rm`a_&v=YM z#hLf?J-3{Ki;a*&_eJ%p-BQ+EA}gmP{7Oz_zcdTVx5QW4$AZE?3r6R;p+F+!^anPQ0qIFXJQtx~uBp zx~zjFTN~r2<%j@D*);;SiwNh`A~Q=t+V4Q3bC;4ZV;QC^s+n7lCdA48OYBT-uI>FU zRWiwa6wyRDM;U;r)KXze=c!9W%MdY9^ZuYkHo@sCFtJ5XBUxF6WM;L1oX!?Dm}W&s z6=R%B_1)Jgdp56*Yl?nAULg&a=3HL4=T<|Z#pAVXMSru59pnb%$UY+tiGthXutSWh z*D?x_A8jIXW*_j+=(hR=TH#m7P67WMui)*?V|)oK_?E+_@)oeYC+T$lIIuhpPG*?= zkWT%`5dWlyK*Gra`(eb0kEUV8aZ6MiqC>%e(_=~UEtb4vT+zVt<|U5KxEaS>G%h93 zAe-h*upx#$OCX zvf0n>MN>IBiPC$2T^}XIUhHR1{bv;`g>q3N*)K&a`0E}0-`0L+HirL}RJ(sA)&Ie0 z`|4mV3f(4b_KCt12lzKJnpXg*L;j{%WJU^Op(Jzs_=>GH9HkW$Id6oLG@q<_ zs++j<@mt|!JdC{x+6zYv+S4;DEd<_UL|d`KF>w^iB@OFiW6SMD@gijQ&^2gW`PWD@ zKra$%9daNwoufE;GbT+l^?L#q^OQ&!4&se!w8(FHtw89G(s@Dtba^hEuf_Cx} z{IN90IuQ8TbOxqoIZBy-BTh-6h0y)S#fWpe)4JR51O+2G@3(!2d2D)ZB1;mg%$Bd$A0PA7|!ibDKENXWgXgL0)%#Q zd*2%sdmHK10Gvzg)h!1vd`Bm9KpGN7Cul#wtT3i zeHYuLp@1qQWyur*r0jC<_jhK2hjlZF7$EU$PvS7i1&# z9CTlmp3desTW}9>Ku%6Z!K11bLXa{QA@*1kcS|768!`;r@@WPiYZQuzwm`qDKb5UrDm{i8d^$U z-Q`?ln3DUTZwu8j_??6g^Vs9pn114F6zin@L71I4otNU!ImSp}kP8%(xwQ+K? zY8OdF%~n!5$Sl!!qQd=jA?CE$KVgVeu(Gr7Vi9eA$*r znuGkLs5d~~0VL!t#i4Tj6EW(ie~qfrVypFg-f|tjBTmu=kDNpAzfK%ZF+ooz=z~V^ ztU>2&)?2MLJQAAQIAL3wglAP5`iZ-KdFX&xP`j}t;_puzCqQ3jyS zUmQA-GP8tc1Sq#czKqMzDPQ%<{zJv91?3K@_!UZcYJ2!e*E#ONA7UcUu7~RChpQcb z-#Dr;GfEU#GRQidd){P{Qz}Z>awl7@+2cVMpmm#iimFZWy<#ij%%Lr)$I{7{&>!P& zq@!Owpd7>DQ~Y*;HF=4RyJ{rC*;g8I=7KdMNRkTpu;1URBTS-0Swj99I6SBryr{jY zXP;xhLh`gga{p!xepEI(U%4l*JrX3-uqGjG?BhEI7>DMM(a=LGw{GwiBEiTQkJczd z`EPv3{rmfXc{!AvUP*1s&nUP1*&irxnmL`VW+uCxoKBmao*XbrTYei|*fBD*SsK7J zSYb0!&qt`@%^60Jpc9P@-6GeY5Qp1y-|#bh6u9C#?=&A1Z(GP=RNb;uWOmMkHa^{O5h`Ux9sP0@AH1zEn8w=V{I`og7+HAD409tufiBu_<|Fov>C) z%w^Ci8+?|fY8PylQdyl@-RyI$c7>Bwm-DRWb4j1~(LcSS_!x`2dM-kMP2XEs6guS< ziv1oYA*pn1Do;oFiz|B`7046B3I?_>b=JCAo8rN>stRlye;Bk3LaSQ~eK@KA9kLy8 zyI|g=2CmBMx%||1ufrs@LP{|{!NXW;AZ5TcrVBrau@S#O^)KubdMHQ26Iv&2=){nt0j-wIQX|ry4C` zZ3#xoQrpOaACv*qq@Q%8;?*EaQ~|l$+~5JoJi^?H7U<6AV)Dhf{hC){lH5$f+?p0* z<)s@!|BgN1v<2|#fU^HeKAPiy!A*QpL<-uko&WpHywTh8bMJlgtfv13^QI!QE+RZA zBpfZ)!d?S~+l2H_;To-6!PTx9Y`2aHQu87XQx`aTB?dwpGn=W@49Gs-T#|-| z9Y$22Bx%0Lc9-G>t*t9}oj&?Q0ZgIL={)crH_=7yu&T#DusH7Wr)}Zx;-KiRg_%CI z?Az(Y#t1(JR*trhLAdM+W6WSyH8iTOE|URsGQ!zSJEq}Ge-pynI6;9 z9quG#evXuK#MbVU(BX+Dnhewo7$Y$FW~1PUsTJmd$lLGw{}lEVLVNy*=xgv2Q^`ob za%l!wj|PKOKnU(K;0VJq#L$*+&-hP9=ozOvXbNMdy}~-YW4asC%4$QW#gXvY@()0a z3-b$e+&NxYzRBoE#mySs@7=$C@A;)3U2Ppr`H{NpHAzRjl7(As`(mMKc>fIc`qJoW z@g;RZ1LS;qLV#5>w6T$w>anXcu!G1>&)IE9Qq^mWcyQ$~EiB{tvvcOeNyaFP+ z;6UWlMi4F~JO5)V^~?+!o}Vxo8F#*eRa){GalhC+cPXgaJzJnka~Va0S51Fl+vynH zPtF@%C|rQ0aS#2S>d{3Yz|H`g%Ouaa zRl7jcuAkF?@ih!=eZm{N>I~Jz8hi{CObrmTi^;oEXbLYc*~WWFE^FvZc?~UegU(Em zc^wlY91&S5kuO%$%o!+}t}v*;$^U86Oj-OZWuP<|b#(T$xG|JlP`7xXE<(mY^04a3 zlc7GIQ^sseBs6Yh3|L0sM)(lugX@R+v$f38Qk3omXk{++?h-zYtONjq4crXR-I1Li z^U%7w&q7CbHs7Lc%`7pGPUl3YxrR7H@3%3G(#kk|#SpAKw|^cOe62rzMOWe;P04i) zUedNy^ZKrXd8xCR)TtwVhpkG031{OrN<`i%>n7_82LAnIi`hQx;2bW!x*OpSsCaED z6v7oqElsb*+hD@8g8_s;AZ(x5m`Py;%hxW$jevq535Mq&=j?w%^pz(%AL}FjTMQ}0 zgL05Td+ac*juhOjKKL6^$Ymq92UNUNF)8f$lvAQs)^pDN%u7?w4$^e?jf zB>p2vzMJ#*z>TYe(*uIVpI566j_BPuJG5Hc1Pb~b(AMQJWu^xvpy|6VD2|ooXTF#s z$DggfsqrZadF`4LvIJfeSjelOp@1}@B)-!=4FFheT3`nHbaJPZ=^7yp`so5r`p^lc z_}u6!qlX!GyX~l{e16!q_}Q}_IKe-o`~~b_Q~~9-aBO6Q@Npw{-eUJl!_p@kCR)ia0<>^^W&!NY=1=sCl+@hw4;&Jy^4@o42JoOxJkEFE%T$kiyk^{{)n69ehEC zZ}=cJEmfg5?^10kleXu zLT`ol$|<-aY;NA#|D)H=;+B~L4Hux`Y6!vb*UjnxCjDRfV-t7~Ao=+wD~8#Gr6Dwg zkc)CZgx#xobSQBh;Jq>(w9*)z$1{Kj6P@;$lh+vYgpK&}liGck?tNG~&l-Pu!U{QL zTCtMF_{Mw=T$J5rwr)$~#It7us=|dsa)+$fShpCLYh<4zqGhv+XPe}o$wo}oUmBffay&tUpwYZUd8OopOq+q_VK**qGoFVo}jnp;@uPWlabvs}P0)D`%(2kWcutHrkZ1 z0$O?j6IV(#X2=;w?qk#ygQ@rrMs)-RMiKn9c-+XoXE7jNh+kWukg_BHOEv_73juyZBm8 zILe9wbQjnmkCwXF(Rw=fK4&3ZwxpzPf znNA!!_a9;S8TN?z*;Y5luIKBRrxJ9ICLYdywcmU#|Cy&0BT#}-2M+-7X#Bt541RO5 zoc{|IxWct?+F*P3@Ro+43_B644lU39qQxU16fvSzo)7;~q9O5n(c2o8-k{@6i> zClQ$gB2;KeY@ud%5#M)z85|spNAKN~267fDSS{U~K)a@(6&8$z`?P;-NG2O>*?KR2 zIUIho`EBREffS^dovXbL>axaFn2}MhRJ|!Q;L;LTYKe=WeLhqlFGb&4ki1HyG+?!G zfBE2)(A`0x56*c$8+yuLws&t`&*nmJRhmD)N)$Mc?^OB8b9UVIgpAhwQ-$RgIWw9h z3dz&zST=jgw!lZBIC%C~iS&9mX-<9dI7$~U7GW^mU~+?-d) zSymdAkamY}N2qPzrHJ#v42dbtb&STOLPn;AzW9AWf`u^B*wUf?JpRNROOz23_y-HX zs9TF&yULZfWW|3WeuErPh^B~8qsm3Jr-|F1JAZ(d8nIs+iiI--w!6 zV%>s#)$jmuFMj*nRp;b&T8^u-QlD&wDBhlNvu9^%YLphpV~3Wa(h3E0TzW|I65L?g zgU61{=4GO=FF0a$-$%Zfl*P=-Np@~$q6I&lcU>79+7frCyWiwF;tc_8_u#A?T^en( zXZz}0Tz~*F7eW90NIE`2^afCSln+05n0xecsI*eyEbOwS_qpgL@rAz0s-3tv(Xo>( zF;jGz*nXO5lt17KKY9?e9k~;%TcE%0j{wp8bhNi9ZJN3;DXc6pmx~yT@)|*);!aSe zO&Y^yjkn_$m-7c8=A_3em za*SGhiL=e~D_UcI5|ePCU=0!znv`k`30#JzMhutKa5D9(S&}d=*Mk}6=bMi^7JEA{ zIRcm-n7-}YKQ5&#+xZquGKrTS&~_&97T-Bv!@K_5sy%ZIA0KbiiRAPhjn~Y3$$29A zI1q*&46SlxXEKB{pQH~56-JUElo8`pj5zL&*i?VTRkq^86jx9J22Es{krjit8Y$sV z$c03yO8}MqUT(`I;Es@<1H3t=~5Cc3`EIVRxbwz7_1g-FwLFMgq>{k!|DuZd`ijic3X6!9RWvaxYGwdTSn0QPJejysI%ehk>;(*olD4hhV=j{K{A)STo7 zDhWXakeZCV9cv`f`^n@O|1OCAg3d18j9gbj7Z=jWP`@h0=%EZHY5mhdxO6 zK}i3av33GC_QMB9rd#Zp^|2td&H#qe3D~f2IvhJid+i%9m_&(F{)oX7Ol70utTXxqQl(0l-cCMyBoO!Pnsk;U@8;#pmI zNH<)86B~6}UviiwrYDR-;=d$EVbBT47m+3yV;BtrqqB4=17zeh?#d8pZdefpqn_AR zGs0lgiMYwOa6qBI!A%ab&#Bn0)J#=coC~cA!Z8ROc}a8l9vipdPb3aQ3muz#k%f}mfFp^z*h($zIK~sJ zyev==-MLNIiQ0 z`M&Or=4K(XmpyJRSH~FWgR1r5b+QkvhpgA5s&?Ps0qZepm1$iu0Q+6WP~|4a0Pzv6 zx>Z66;Kw6Ef}5b|Q1W2HQQ!3ThJW@G0rQ3N<$|#oaAd`7warEoB1pc`v85y%;GS)9XSdEwwz`C7L!B@c@;5CHxvuMp;B`z=NA09gVTh#LozQWw zN@v}vKd+OtEKV3?(1(q@$3Ya84@nFAI}U!eFv*gTXW8-Ni$%hH@=f6kT$3s%CZU2F z`x)2QfFF*OJ2v|?A_BhC^Yvz?d)AsJ{9!y=0rxy&i;)1(rPrl?x8e+hi$*$*6K5G2 zn`>&LPcWv2DB^kIX{?C0cOufb+2gcn_tFTf1sW9H{8L!{ML5;5>{MmiV)Y*Mq5k1? zmgXUFmW_x!G`62i?Z<+zGdYH>x@|NAJ9@X(tW7bd=9JmbLuQ*Ly6Jo%;{T?aDhaL9 zugVwtq^&8ZvPtFRA*^N|T21)xRCy>IMoFNf!rQY4W00|QxNwQb97XsO9MEJ@P`P#g z?}=d@SF5X6t$Fg4z=OHUg0w{wRm2+m-1(ovCBs_>2`11(f|eSGC1 zYK&Poc<1!Y0j?HRthc0?LX3`gU@%@pkI; zH!ziqkw*E}3T}K=jKUvHff@^gp`btb$EFH3misYmFAsx)+wFgR|Dv8R3F)fP3+gT< zgmiV7PYjYBegP8JcKqf1^53kP@+N4>N){EYsbj#D7ePMaWk=wfWzH_VV>J3hX*-^0s(#p7}t z#K6ssq#ihvZWA}EclOl2cymM06`l4L^}(5^Vwkw_+1jgKKHDQXLh@9xg_=dqYhm&%>qKKfxnInx zQM;mj(iPg_zJ;q+Ik~5|Lt-!}H7eEynUO$sH)I@`EFBcnxd2=BHCjDkRJozLTQa*p zc~;RiVprAf4dBj+uEXT@4B0zd*8EY${aLI5th_povWpArRpGok%mEW$uJKq6b}F%~tH1n#)kU;2J;OY0TvVB3 zO=ZNmj$Xw;>5Z87G9PShhC-6G9W8YOsW9zLypjBoY_&#WGw_g^8hzn{-f z?cx7?CCnR_Ze8`PJa=q;MSfK&-%xB_U+6W?cg=H1lx%EWKRvmeXkN^kFLrZW&5TzNY1fctg?1L6A!tr+nU+TSO*?Sr>&XvDnHLe_}ydwJk-)gt}=o3g2v zu)lq<-iaL;XIgkD0D5l0S+F<+W^+en)dY7bmtD35awsZ4bC?M$VBR^L2x zo5W1_I{l2zd)LBx)5A=+t%F7iCXG{tA0iwb>7TDuD<2is3ItTT0@;LBpP$rAvMm^~ zqPeae>l(p>t;KLok{_}Q!yQ0PGly`y9DB&K*TllE6U^^Bvz^jm^ zXveS9-0S8OAKAYb+kFFE=#dW9pINUX49{^uB~UZB9E? zTwVK6KGl}2fBG@?FXr#nbxu0unJjr~|B z8jhFg2JJe3bl2evI@Ue*z*eWDa%yf4E6|H^P>A3h5 z%SS-XJfeWq)pl?nJ&FWQ8~5ZB0u;sAyBGKe?K*L6S0`421pdxiKWXge47^QE*;!}Z z$Voa*&nGV$g8J@3r1h0u`ag{U7jk%qtiPs!d~5&!jQ>9q?q*?YZ0F|mKZ)*J8aw}$ zdE$Gc*Z*1%tB!;eCYumbhx-rrx3?2dDnVug~i&a#9{Xyp@i)UQ@ z>X)n9$JzfW?9St%%;PwK&k7Nxt&njPDy5c`t>oMs+X`VsAu$XFos2Ud(ZcI=6O9cuV;S0?}xS{G(jRI zc;aE-lZdkG+|3%AJxQW|LHm@Px>9VT_o#`ND$fptT3y~;>@Fr=in;t){<_83t?G^8 z_NVq?f|@gn$p<;ybeIZwUs8+Tat!HvU>8c!RMP=|V z;WwLW^}j4HX;5+EeD=gAF42QufcodkcR~N|zeBm0&}&6fU*X#~Ess5l-e*YK7~uGD zwymu9^|(}n&Q^yg+A?LKXK(YxB0$5hv(;;gy9c8arW>;^WNJL3l20moj&mFJW^la@ z^69PcNQh{1y6IMOHR$WM(a<~LXxfd6vTai`ubK!q56^Dw_c+#(Dx@~4dFsvAZmX(E z8_L_{;n1fuU9Aq+C-?CsQ)sz4QTVc8XO1*c0VE|h0YnvkAOHf^A&~dcOq4?|qe@V%+mYHX@+k{7AKk2X2KP+aZ_ko+EdG#I4=Uozf z5~d=8Ma!gwbk4+@?B!82G~s!Yn53zjgxk33WlJHkXCm@cbOC?AT}k`t_KejPXjMa= zBs7Rm9>57kgdO)Yp(grEw4|!kU;q2F(ZuDES}AhUhfi7u%n3KVRE(3tZ|EPPRG22k z4EA@;a191yV-?j$GLNkC6fLB^Xy8wk7v(5CIwuu(j&h}4^7Np- z_1GioDE~PHzO^E%zeeeJ%lsU8Y14tsj}K<$>(gK4iII1#9J;$jKq$)h+*Sq2x`6EZ zu^hpYjYfeZospIPmo|~xXI14iQe9(WkEvMN#g>boF-K9kuT8lNpa~Av<9w?*-7X$n zKf7fw-s4VrY=~Z#b8U|9lb@C;Y6WXY#!s!6zCBJ9@2D%AGauz}W)m@w1!B=TV zK_3&_<)^M5NP4={w39pcqhyn}5NFJ3SEs@f@735p(*zy~XYv=@TnSV(8ZFL`$Ma}b zDeAp%E7Bf%*r1n1FuZh-L&La)cig+3klf#Cblg&ObBetcF*PH+O3G$?Y+bTpU5}1- z-Yv_5TSv^K?{*)^Qy)o;Xxtyslww7x&A&GNW=%J@;1&Ps-G3Dc=~^iG7{Bx+TmPHy zGps`uoOpbOMv(D}zpBD3CG+8NRjE%MRpo zKGJfw&vvuOc37M1_{+?zxt*2fGq3EWKD(t6>vUoQYYKUbsz*eI<8!FBtJ;T@lxy}I z4=A+R-u?JnZ)e-c_M8nzr^1wCzQ_!}%o4Q^O;fg$u(g(Z?pmGO=t9ljU@(Gdt!i&6 z2rTPRZMEHFoucYZlp9$wp1%7$ABEays}v;vWynFksisrI|G>?@ycwd}?{U%2HGU#B zep#Vuec6ZXPh{0a#_3ZY8LTJDa7tDBOqfOc^0Y%CVga|W2tOa} z%6j%>E^B>hbRTvuL3a{Io5^`U)lqpVZ^CEHLBcd4Jw9N@HcGX>V_GBVwyyD5*7F_5 zOlcM>JgwC|-Kv(qJXq6rb}A?)r|@yqQ0$fJZDq2zR+$a?o-v8QV3xOw1dOGsf@=qXrVjZ}w@}N@v zUKl1yN}EoDRan2SK%v%x|I#<`aAC91bOUJ=uA~ztexQH%ar(Vg7?A08Lt()PEVyFx zEevA-+rSGkI!uE*yDmg{Aa!D<1qYs40-gr0^z$2I;C;}vnSdkNfL7r)^0scCI73g+ zKHQUp#}QdoU>5OudpQ{XI~Yx0Lqy*gkTIy~8$|H=e`-zL2FqeFoD+=SG7o*Dz?3z% zl(sK8NJP-qoK<O&jCzXq zGC_=U3hUx#>ud)i3p{NI^r~2%WAO#!f8Pg+IAAuw;kKb>g|Igbm;rUIO@0YtPpl*B%Ex6ILDlr9M(BE@SedTBM2r+V8U2L zj=&O}#eqm_u1wNmZ~}{D4p@YPG!U_gmB=nu17_j;3xp+t9FZSV71*R@!$ z#dXVUQx#wr4krO6#F*+c_ z7~Inm!Gg(4V2lozFa|f~LNMOHmcZucl*1O>Ee5e3MzFUQddI*RysjO=Y_BeXEv#~f zHF$wEqB+K}*XGX-n1W~CBb0f{64b&xd{~3$SRz` +B=zeros(6,7); + +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +% initialize higher order model variables +DCM_0 = zeros(3,3); +ic_vel = zeros(3,1); +ic_angrate = zeros(3,1); +ic_controls = zeros(4,1); +ic_euler_ang = zeros(3,1); + +% direction IC's +h_0=0; h=0; +North_0=0;% +East_0=0; +Psi = 353*pi/180.0; + +%Derivatives accountfor mass +M=1; + +Xu=-0.02; % barn door +Zw=-2.0; +Mq=-2.0; +Mu=0.001; +Yv=-0.4; +Lp=-6.0; +Nr=-8.0; +Lv=-0.02; + + + +% [u v w p q r]' + +A = [ Xu 0 0 0 0 0;... + 0 Yv 0 0 0 0;... + 0 0 Zw 0 0 0;... + 0 Lv 0 Lp 0 0;... + Mu 0 0 0 Mq 0;... + 0 0 0 0 0 Nr]; + + +% lat long coll ped ' + +Zcoll=-60; +Mlong = 1; +Llat=1; +Nped=2; +B = [ 0 0 0 0;... + 0 0 0 0;... + 0 0 Zcoll 0 ;... + Llat 0 0 0 ;... + 0 Mlong 0 0 ;... + 0 0 0 Nped ]; + +max_saved=300000; % limits no. of data points to the last max_saved + +%% Re-order rows of A for aerospace blk based sim - columns to be ordered in u. +% Pare A down for Forces only +A_Fxyz_uvw_pqr=A([1 2 3],[1 2 3 4 5 6]); +% Pare A down for Moments only +A_Mxyz_uvw_pqr=A([4 5 6],[1 2 3 4 5 6]); + +%% B rows = X,Y,Z,L,M,N, B cols = u=[lat long coll ped] +% Pare B down for Forces only +B_Fxyz_u_cont=B([1 2 3],[1 2 3 4]); +% Pare B down for Moments only +B_Mxyz_u_cont=B([4 5 6],[1 2 3 4]); + +ic_u=0.0000; ic_v=0.0000; ic_w=0.0000; zPsi=306*pi/180; % Points down RWY32 + +%ic_u=0.00001; ic_v=0.00001; ic_w=0.00001; zPsi=306*pi/180; % Points down RWY32 +ic_U=sqrt(ic_u^2+ic_v^2+ic_w^2); + + +%% WIND MODEL - NOTE ; SET Vw = 0 @ h_ic, Vw units in braces are KTS +h_deck=21; h_island=h_deck+130; +h_contact=h_deck; % h_contact is used in landing gear model (same for fixed and rotary model) + +%% TURBULENCE +W_GUST=.8; % BW in rad/sec +K_gust=0 ; % 80; % Gust Gain Factor +Th_wind_limit=40; % Limits on wind swing in deg +hw_gust=[0 1 h_island h_island+1 5000]; % 5 break points +K_gust_factor=[1.1 1 .5 0.25 0]; +%% WIND +% hw=[0, h_deck+1, h_deck+1, 150 151 20000]; % FOR SHIP.. 6 BREAK POINTS +hw=[0 200 5000 10000 15000 20000]; % 6 BREAK POINTS, MONO INCREASING +Vw=15*[1 1 1 1 1 1]; % wind magnitude in fps +Dir_w=0*[1 1 1 1 1 1]; % wind direction in deg + +Ftrim_grav=-32.0757; +Roll_ic=0; Pit_ic=0; + +%Make the trim direction cosine matrix +phi_0 = 3; +tht_0 = Pit_ic; +psi_0 = Psi*180/pi; + +cphi = cosd(phi_0); +sphi = sind(phi_0); +ctht = cosd(tht_0); +stht = sind(tht_0); +cpsi = cosd(psi_0); +spsi = sind(psi_0); + +DCM_0 = [1 0 0; + 0 cphi sphi; + 0 -sphi cphi] * ... + [ctht 0 -stht; + 0 1 0; + stht 0 ctht]*... + [cpsi spsi 0; + -spsi cpsi 0 + 0 0 1]; + +%% A short run of the sim to sample cockpit the current control positions +U_CONT_O=[0 0 0 0]; + + +Ts=2000; % set Ts for real time sim run +disp('Init Loaded') \ No newline at end of file diff --git a/libraries/SITL/examples/JSON/MATLAB/Heli/readme.md b/libraries/SITL/examples/JSON/MATLAB/Heli/readme.md new file mode 100644 index 0000000000000..b0fa19194f671 --- /dev/null +++ b/libraries/SITL/examples/JSON/MATLAB/Heli/readme.md @@ -0,0 +1,3 @@ +This is a example Helicopter Simulink model. This has accurate physics and can be run using the EKF. Blocks from this example could be used to make other vehicles without having to work out the conversions to the ArduPilot reference frames. Note that ground interaction is neglected, once you take off you can't land! heli_init.m must be run before the module will run. + +Many thanks to [Bill Geyer](https://github.com/bnsgeyer) for providing this model. From 4ee1c90376976995248cc0ab54b32d5446502c7c Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Tue, 30 Jun 2020 16:57:21 +0100 Subject: [PATCH 5/5] SILT: MATLAB add Simulink instuctions to readme --- libraries/SITL/examples/JSON/MATLAB/readme.md | 14 ++++++++++++-- 1 file changed, 12 insertions(+), 2 deletions(-) diff --git a/libraries/SITL/examples/JSON/MATLAB/readme.md b/libraries/SITL/examples/JSON/MATLAB/readme.md index 08713d3e3dfe1..eb558a6b0eaea 100644 --- a/libraries/SITL/examples/JSON/MATLAB/readme.md +++ b/libraries/SITL/examples/JSON/MATLAB/readme.md @@ -1,4 +1,4 @@ -This is a tool to allow MATLAB to interface with the SITL JSON backend. +# MATLAB The SITL_connector function can be used to simplify the connection process. SITL_connector.m uses the TCP/UDP/IP Toolbox 2.0.6 by Peter Rydesäter and is much (10x) faster than the MATLAB functions available with the instrument control toolbox (and free!). However this may require compilation of a mex file, prebuilt mex files are included in most cases they will work without the need to re-compile. @@ -32,4 +32,14 @@ the structure can have also any other felids required for the physics model The JSON SITL interface is lock-step scheduled. This allows matlab breakpoints to work as normal. -Using the connection it should be possible to achieve > 1500 fps, at this speed MATLAB code efficiency plays a important factor in the max frame rate. For a 400hz physics time step this gives a maximum speedup of 4 to 5 times. For planes and rovers it should be possible to use a much larger physics time step resulting in a larger maximum speed up. Note that large speedups risk the GCS getting left behind. +Using the connection it should be possible to achieve > 1500 fps, at this speed MATLAB code efficiency plays a important factor in the max frame rate. For a 400hz physics time step this gives a maximum speedup of 4 to 5 times, physics time step can be adjusted using the ArduPilot SIM_RATE parameter. For planes and rovers it should be possible to use a much larger physics time step resulting in a larger maximum speed up. Note that large speedups risk the GCS getting left behind. + +[![Matlab Connector demo](https://img.youtube.com/vi/sYCU2ch7oFE/0.jpg)](https://www.youtube.com/watch?v=sYCU2ch7oFE) + +# Simulink + +Simulink input and output blocks are provided in AP_Conector.slx. There is a receive block that receives the PWM inputs from SITL. These are output in a 16 element array. The output block takes the vehicle state as outlighned above. The input block also has a reset signal, this will go high if SITL is restarted. This could be used to reset the Simulink model to its initial conditions. Unlike the Matlab connector the time step used by Simulink cannot be adjusted by ArduPilot, it must eb set in Simulink. Variable size time steps are supported. + +[![Simulink Connector demo](https://img.youtube.com/vi/hTFyMrjwQlI/0.jpg)](https://www.youtube.com/watch?v=hTFyMrjwQlI) + +Note that the Simulink connector and examples were made using Matlab2020a.